From a03fb5b6b20ccb497e3567d103c0d81f2451eedf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 14 May 2019 17:00:08 +0200 Subject: [PATCH 001/132] Add initial design draft --- design.md | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 design.md diff --git a/design.md b/design.md new file mode 100644 index 0000000..190cd3f --- /dev/null +++ b/design.md @@ -0,0 +1,36 @@ +# Design + +Plan for ROS 2 tracing & analysis effort. + +## Steps + +This general effort will be split into a few distinct steps. + +### Instrumentation + +The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). + +This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. + +The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. + +### Analysis + +After the initial instrumentation, some general statistics analyses can be built. The goal is to make those general enough to be useful for different use-cases, e.g.: + +* Callback duration (mean, stdev, etc.) +* +* + +Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. + + +### Tools/accessibility + +To make tracing ROS 2 more accessible and easier to adopt, we can put effort into integrating LTTng session setup & recording into the ROS 2 launch system. + +This might include converting existing `tracetools` scripts to more flexible Python scripts, and then plugging that into the launch system. + +### ROS 1/2 compatibility + +Finally, we could look into making the instrumentation work on both ROS 1 and ROS 2, through a common interface (or other abstraction). From 4dc39bf84a94aacfed1d0cd4627c9e7ecb8c53ef Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 14 May 2019 17:05:19 +0200 Subject: [PATCH 002/132] Mention pandas and Jupyter --- design.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/design.md b/design.md index 190cd3f..3021205 100644 --- a/design.md +++ b/design.md @@ -16,7 +16,7 @@ The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. ### Analysis -After the initial instrumentation, some general statistics analyses can be built. The goal is to make those general enough to be useful for different use-cases, e.g.: +After the initial instrumentation, some general statistics analyses can be built. The targeted analysis tools are pandas and Jupyter. The goal is to make those general enough to be useful for different use-cases, e.g.: * Callback duration (mean, stdev, etc.) * From ea991050eec34fe28b489092f9843ead9291ac01 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 14 May 2019 17:14:08 +0200 Subject: [PATCH 003/132] Fix ROS 1/2 compatibility wording --- design.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/design.md b/design.md index 3021205..05f00a6 100644 --- a/design.md +++ b/design.md @@ -33,4 +33,4 @@ This might include converting existing `tracetools` scripts to more flexible Pyt ### ROS 1/2 compatibility -Finally, we could look into making the instrumentation work on both ROS 1 and ROS 2, through a common interface (or other abstraction). +Finally, we could look into making analyses work on both ROS 1 and ROS 2, through a common instrumentation interface (or other abstraction). From cc2cee6c086acd2a788058ca98dca3571c53ca81 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 14 May 2019 17:17:57 +0200 Subject: [PATCH 004/132] Fix wording --- design.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/design.md b/design.md index 05f00a6..2a3f7c1 100644 --- a/design.md +++ b/design.md @@ -16,7 +16,7 @@ The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. ### Analysis -After the initial instrumentation, some general statistics analyses can be built. The targeted analysis tools are pandas and Jupyter. The goal is to make those general enough to be useful for different use-cases, e.g.: +After the initial instrumentation, some general statistics analyses can be built. The targeted analysis tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: * Callback duration (mean, stdev, etc.) * From 2e70477bb78e8cd112e27af66f9421cdd10c0751 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 14 May 2019 17:36:10 +0200 Subject: [PATCH 005/132] Add more statistics examples --- design.md | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/design.md b/design.md index 2a3f7c1..c296e19 100644 --- a/design.md +++ b/design.md @@ -18,9 +18,13 @@ The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. After the initial instrumentation, some general statistics analyses can be built. The targeted analysis tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: -* Callback duration (mean, stdev, etc.) -* -* +* Callback duration +* Time between callbacks (between two callback starts and/or a callback end and a start) +* Message age (as the difference between processing time and message timestamp) +* Message size +* Execution time/proportion accross a process' nodes/components + +with mean, stdev, etc. Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. From d2a50b19a85eb2b5211398a76391de131dffe0d5 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 15 May 2019 10:02:21 +0200 Subject: [PATCH 006/132] Mention interruption-related stats --- design.md | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/design.md b/design.md index c296e19..d442f57 100644 --- a/design.md +++ b/design.md @@ -14,17 +14,22 @@ This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. -### Analysis +### Analysis & visualization -After the initial instrumentation, some general statistics analyses can be built. The targeted analysis tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: +After the initial instrumentation, some general statistics analyses can be built. The targeted analysis & visualization tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: * Callback duration * Time between callbacks (between two callback starts and/or a callback end and a start) * Message age (as the difference between processing time and message timestamp) * Message size +* Memory usage * Execution time/proportion accross a process' nodes/components +* Interruptions (noting that these may be more useful as time-based metrics instead of overall statistics): + * scheduling events during a callback + * delay between the moment a thread becomes ready and when it's actually scheduled + * CPU cycles -with mean, stdev, etc. +with mean, stdev, etc. when applicable. Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. From 5583fa68d1ca57bc54d2375f5c234bedba807e52 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 12:54:01 +0200 Subject: [PATCH 007/132] Add basic tracing lib files --- tracetools/include/tracetools/tracetools.h | 30 ++++++++++++++++++++++ tracetools/src/.gitignore | 3 +++ tracetools/src/status.c | 14 ++++++++++ tracetools/src/tracetools.c | 20 +++++++++++++++ 4 files changed, 67 insertions(+) create mode 100644 tracetools/include/tracetools/tracetools.h create mode 100644 tracetools/src/.gitignore create mode 100644 tracetools/src/status.c create mode 100644 tracetools/src/tracetools.c diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h new file mode 100644 index 0000000..19c977f --- /dev/null +++ b/tracetools/include/tracetools/tracetools.h @@ -0,0 +1,30 @@ +#ifndef __TRACETOOLS_TRACETOOLS_H_ +#define __TRACETOOLS_TRACETOOLS_H_ + +#include +#include +#include + +#define TRACEPOINT(event_name, ...) \ + (ros_trace_##event_name)(__VA_ARGS__) + +#ifdef __cplusplus +extern "C" +{ +#endif + +/** + * Report whether tracing is compiled in + */ +bool ros_trace_compile_status(); + +/** + * tp: rcl_init + */ +void ros_trace_rcl_init(); + +#ifdef __cplusplus +} +#endif + +#endif /* __TRACETOOLS_TRACETOOLS_H_ */ diff --git a/tracetools/src/.gitignore b/tracetools/src/.gitignore new file mode 100644 index 0000000..2b36a18 --- /dev/null +++ b/tracetools/src/.gitignore @@ -0,0 +1,3 @@ +# generated files (LTTng) +tp_call.c +tp_call.h diff --git a/tracetools/src/status.c b/tracetools/src/status.c new file mode 100644 index 0000000..fc54ea0 --- /dev/null +++ b/tracetools/src/status.c @@ -0,0 +1,14 @@ +#include +#include "tracetools/tracetools.h" + +int main() +{ + printf("Tracing "); + if (ros_trace_compile_status()) { + printf("enabled\n"); + return 0; + } else { + printf("disabled\n"); + return 1; + } +} diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c new file mode 100644 index 0000000..d3003b1 --- /dev/null +++ b/tracetools/src/tracetools.c @@ -0,0 +1,20 @@ +#include "tracetools/tracetools.h" + +#ifdef WITH_LTTNG +#include "tp_call.h" +#endif + + +bool ros_trace_compile_status() { +#ifdef WITH_LTTNG + return true; +#else + return false; +#endif +} + +void ros_trace_rcl_init() { +#ifdef WITH_LTTNG + tracepoint(ros2, rcl_init); +#endif +} From cb6dc3367f8f1c52569e5bdb54576170900dc1bc Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 12:54:35 +0200 Subject: [PATCH 008/132] Add .tp file with first tracepoint --- tracetools/lttng/tp_call.tp | 10 ++++++++++ 1 file changed, 10 insertions(+) create mode 100644 tracetools/lttng/tp_call.tp diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp new file mode 100644 index 0000000..7260326 --- /dev/null +++ b/tracetools/lttng/tp_call.tp @@ -0,0 +1,10 @@ +#include + +TRACEPOINT_EVENT( + ros2, + rcl_init, + TP_ARGS( + ), + TP_FIELDS( + ) +) From ad8894d12b1b6e35b361185243a8c556346d7ead Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 12:55:31 +0200 Subject: [PATCH 009/132] Add build files --- tracetools/CMakeLists.txt | 94 +++++++++++++++++++++++++++++++++++++++ tracetools/package.xml | 19 ++++++++ 2 files changed, 113 insertions(+) create mode 100644 tracetools/CMakeLists.txt create mode 100644 tracetools/package.xml diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt new file mode 100644 index 0000000..328185e --- /dev/null +++ b/tracetools/CMakeLists.txt @@ -0,0 +1,94 @@ +cmake_minimum_required(VERSION 3.5) +project(tracetools) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -fPIC) +endif() + +find_package(ament_cmake REQUIRED) + +option(WITH_LTTNG "Include support for tracing with LTTng" OFF) +if(WITH_LTTNG) + # Try to find LTTng + find_package(PkgConfig REQUIRED) + pkg_check_modules(LTTNG REQUIRED lttng-ust) +endif() +if(LTTNG_FOUND) + # Generate necessary LTTng files + # If successful, enable tracing + add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c + COMMAND lttng-gen-tp tp_call.tp -o ../src/tp_call.c -o ../src/tp_call.h + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/lttng + DEPENDS ${PROJECT_SOURCE_DIR}/lttng/tp_call.tp + ) + set(LTTNG_GENERATED + src/tp_call.h + src/tp_call.c + ) + set(TRACING_ENABLED TRUE) + message("LTTng found: tracing enabled") +elseif(WITH_LTTNG) + message("LTTng NOT found: tracing disabled") +endif() + +include_directories(include) + +# Status checking tool +add_executable(${PROJECT_NAME}_status + src/status.c + src/tracetools.c +) +target_link_libraries(${PROJECT_NAME}_status + ${PROJECT_NAME} +) +ament_target_dependencies(${PROJECT_NAME}_status + ${PROJECT_NAME} +) +install(TARGETS + ${PROJECT_NAME}_status + DESTINATION lib/${PROJECT_NAME} +) + +# Tracetools lib +set(SOURCES + src/tracetools.c +) +if(TRACING_ENABLED) + list(APPEND SOURCES ${LTTNG_GENERATED}) +endif() + +add_library(${PROJECT_NAME} ${SOURCES}) +if(TRACING_ENABLED) + target_compile_definitions(${PROJECT_NAME} PUBLIC WITH_LTTNG) + target_link_libraries(${PROJECT_NAME} ${LTTNG_LIBRARIES} -ldl) +else() + target_link_libraries(${PROJECT_NAME}) +endif() + +ament_export_interfaces(${PROJECT_NAME}_export HAS_LIBRARY_TARGET) +install( + DIRECTORY include/ + DESTINATION include +) +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME}_export + LIBRARY DESTINATION lib + ARCHIVE DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +ament_export_include_directories(include) +if(TRACING_ENABLED) + ament_export_libraries(${PROJECT_NAME} ${LTTNG_LIBRARIES}) +else() + ament_export_libraries(${PROJECT_NAME}) +endif() + +ament_package() diff --git a/tracetools/package.xml b/tracetools/package.xml new file mode 100644 index 0000000..2d80723 --- /dev/null +++ b/tracetools/package.xml @@ -0,0 +1,19 @@ + + + + tracetools + 0.0.1 + ROS 2 wrapper for instrumentation + Christophe Bedard + Christophe Bedard + APLv2 + + ament_cmake + pkg-config + + + + + ament_cmake + + From 9f771a18122f0f446070f9dc53c968e9c7fb6a1f Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 12:55:49 +0200 Subject: [PATCH 010/132] Add basic tracing scripts --- tracetools/scripts/setup-lttng.sh | 37 +++++++++++++ tracetools/scripts/trace.sh | 90 +++++++++++++++++++++++++++++++ 2 files changed, 127 insertions(+) create mode 100755 tracetools/scripts/setup-lttng.sh create mode 100755 tracetools/scripts/trace.sh diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh new file mode 100755 index 0000000..e5b6c6a --- /dev/null +++ b/tracetools/scripts/setup-lttng.sh @@ -0,0 +1,37 @@ +#!/bin/bash + +# set up ust ros2 events +for event in \ + ros2:rcl_init +do + lttng enable-event -c ros2 -u $event +done + +# process context +lttng add-context -c ros2 -u \ + -t vpid -t procname \ + -t vtid -t perf:thread:instructions \ + -t perf:thread:cycles -t perf:thread:cpu-cycles + +#kernel +lttng enable-channel --kernel kchan --subbuf-size=8M + +# # network +# for event in net_dev_queue netif_receive_skb net_if_receive_skb +# do +# lttng enable-event --kernel --channel=kchan $event +# done + +# other kernel stuff +for event in sched_switch sched_waking sched_pi_setprio sched_process_fork sched_process_exit sched_process_free sched_wakeup\ + irq_softirq_entry irq_softirq_raise irq_softirq_exit irq_handler_entry irq_handler_exit\ + lttng_statedump_process_state lttng_statedump_start lttng_statedump_end lttng_statedump_network_interface lttng_statedump_block_device\ + block_rq_complete block_rq_insert block_rq_issue\ + block_bio_frontmerge sched_migrate sched_migrate_task power_cpu_frequency\ + net_dev_queue netif_receive_skb net_if_receive_skb\ + timer_hrtimer_start timer_hrtimer_cancel timer_hrtimer_expire_entry timer_hrtimer_expire_exit +do + lttng enable-event --kernel --channel=kchan $event +done + +# lttng enable-event -k --syscall --all diff --git a/tracetools/scripts/trace.sh b/tracetools/scripts/trace.sh new file mode 100755 index 0000000..68dc29d --- /dev/null +++ b/tracetools/scripts/trace.sh @@ -0,0 +1,90 @@ +#!/bin/bash +## Helper script for ROS tracing +## Christophe Bedard +## see: https://github.com/bosch-robotics-cr/tracetools/blob/devel/scripts/example-run-script.sh +## Call this by providing these arguments: +## 1. a session name [optional; 'ros2' will be used] +## 2. a wait time before killing and stopping (in seconds) +## 3. a roslaunch/rosrun command +## ex: ./trace.sh 3 roslaunch tracecompass_ros_testcases pub_sub.launch + +source ./${BASH_SOURCE%/*}/../../../../install/local_setup.bash + +## Parameters + +# if no parameters were given, exit with error +if [ -z "$1" ] ; then + echo "Error: no parameters were given!" + exit 1 +elif [ "$1" == "-h" ] ; then + echo -e "ROS tracing helper script.\n" \ + "Provide 3 arguments:\n" \ + "1. the lttng session name [optional; 'ros2' will be used]\n" \ + "2. the wait time before killing and stopping (in seconds)\n" \ + "3. the ros2 run command\n" \ + "Example: ./trace.sh ros-trace 3 ros2 run tracetools tracetools_status" + exit 0 +fi + +# session name +session_name="$1" +case "$session_name" in + ''|*[!0-9]*) # not a number: good + shift + ;; + *) # number: so use a default session name + session_name="ros2" + ;; +esac + +# wait time (seconds) before killing and stopping +sleep_time="$1" +case "$sleep_time" in + ''|*[!0-9]*) # not a number: error! + echo "Error: not a valid sleep time!" + exit 1 + ;; + *) # number: good + shift + ;; +esac + +# command from remaining arguments +if [ -z "$1" ] ; then + echo "Error: no command was given!" + exit 1 +fi +launch_cmd="$@" +launch_cmd+=" &" + +## Trace + +# create lttng session (and set output to traces/ directory) +lttng create $session_name --output=./${BASH_SOURCE%/*}/../traces/$session_name/ + +# enable events +./${BASH_SOURCE%/*}/setup-lttng.sh + +# start +lttng start + +# preload UST library +export LD_PRELOAD=/usr/lib/x86_64-linux-gnu/liblttng-ust-cyg-profile.so + +# launch +eval "$launch_cmd" + +# wait a bit and kill +echo "waiting $sleep_time..." +sleep $sleep_time +echo "killing" +kill $! + +# wait again for everything to shutdown +echo "waiting for shutdown..." +sleep 2 +echo "stopping" + +# stop & destroy +lttng stop +lttng destroy From 82b5dd35e68897eb0cd0925a44a5a70154d37364 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 12:56:06 +0200 Subject: [PATCH 011/132] Add README with building instructions --- tracetools/README.md | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) create mode 100644 tracetools/README.md diff --git a/tracetools/README.md b/tracetools/README.md new file mode 100644 index 0000000..5d7516e --- /dev/null +++ b/tracetools/README.md @@ -0,0 +1,26 @@ +# tracetools + +## Building + +If tracing is not enabled when building, or if LTTng is not found, then this package will not do anything. + +To enable tracing: + +1. Install [LTTng](https://lttng.org/docs/v2.10/#doc-ubuntu): + ``` + $ sudo apt-get install lttng-tools lttng-modules-dkms liblttng-ust-dev + ``` +2. Build with the `WITH_LTTNG` flag: + ``` + $ colcon build --cmake-args " -DWITH_LTTNG=ON" + ``` +3. Check if tracing is enabled (after sourcing): + ``` + $ ros2 run tracetools tracetools_status + ``` + +## Tracing + +By default, the steps above will not lead to trace data being generated, and thus they will have no impact on execution. + +LTTng has to be enabled: TODO mention scripts From d0aa25f20585a6e12bc12a9e32f884aeaa27176f Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 13:07:31 +0200 Subject: [PATCH 012/132] Ignore traces directory --- tracetools/.gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 tracetools/.gitignore diff --git a/tracetools/.gitignore b/tracetools/.gitignore new file mode 100644 index 0000000..ff6c930 --- /dev/null +++ b/tracetools/.gitignore @@ -0,0 +1 @@ +traces/ From ccc06079e86fc5fc1ce86509c7ea80dcde14a32d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 13:36:59 +0200 Subject: [PATCH 013/132] Add more rcl tracepoints --- tracetools/include/tracetools/tracetools.h | 15 +++++++++ tracetools/lttng/tp_call.tp | 39 ++++++++++++++++++++++ tracetools/scripts/setup-lttng.sh | 5 ++- tracetools/src/tracetools.c | 18 ++++++++++ 4 files changed, 76 insertions(+), 1 deletion(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 19c977f..fc4896e 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -23,6 +23,21 @@ bool ros_trace_compile_status(); */ void ros_trace_rcl_init(); +/** + * tp: rcl_node_init + */ +void ros_trace_rcl_node_init(const char * node_name, const char * namespace); + +/** + * tp: rcl_publisher_init + */ +void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace); + +/** + * tp: rcl_subscription_init + */ +void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name); + #ifdef __cplusplus } #endif diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 7260326..0d0aa4c 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -8,3 +8,42 @@ TRACEPOINT_EVENT( TP_FIELDS( ) ) + +TRACEPOINT_EVENT( + ros2, + rcl_node_init, + TP_ARGS( + const char*, node_name_arg, + const char*, namespace_arg + ), + TP_FIELDS( + ctf_string(node_name, node_name_arg) + ctf_string(namespace, namespace_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_publisher_init, + TP_ARGS( + const char*, node_name_arg, + const char*, namespace_arg + ), + TP_FIELDS( + ctf_string(node_name, node_name_arg) + ctf_string(namespace, namespace_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_subscription_init, + TP_ARGS( + const char*, node_name_arg, + const char*, topic_name_arg + ), + TP_FIELDS( + ctf_string(node_name, node_name_arg) + ctf_string(topic_name, topic_name_arg) + ) +) diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index e5b6c6a..24a6e17 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -2,7 +2,10 @@ # set up ust ros2 events for event in \ - ros2:rcl_init + ros2:rcl_init \ + ros2:rcl_node_init \ + ros2:rcl_publisher_init \ + ros2:rcl_subscription_init do lttng enable-event -c ros2 -u $event done diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index d3003b1..d9487b3 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -18,3 +18,21 @@ void ros_trace_rcl_init() { tracepoint(ros2, rcl_init); #endif } + +void ros_trace_rcl_node_init(const char * node_name, const char * namespace) { +#ifdef WITH_LTTNG + tracepoint(ros2, rcl_node_init, node_name, namespace); +#endif +} + +void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace) { +#ifdef WITH_LTTNG + tracepoint(ros2, rcl_publisher_init, node_name, namespace); +#endif +} + +void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name) { +#ifdef WITH_LTTNG + tracepoint(ros2, rcl_subscription_init, node_name, topic_name); +#endif +} From 5c4b84520e5b537295779149e1911f4c009ae1d8 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 May 2019 14:16:40 +0200 Subject: [PATCH 014/132] Fix coding style --- tracetools/src/tracetools.c | 27 ++++++++++++++++----------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index d9487b3..5efcaed 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -5,34 +5,39 @@ #endif -bool ros_trace_compile_status() { +bool ros_trace_compile_status() +{ #ifdef WITH_LTTNG - return true; + return true; #else - return false; + return false; #endif } -void ros_trace_rcl_init() { +void ros_trace_rcl_init() +{ #ifdef WITH_LTTNG - tracepoint(ros2, rcl_init); + tracepoint(ros2, rcl_init); #endif } -void ros_trace_rcl_node_init(const char * node_name, const char * namespace) { +void ros_trace_rcl_node_init(const char * node_name, const char * namespace) +{ #ifdef WITH_LTTNG - tracepoint(ros2, rcl_node_init, node_name, namespace); + tracepoint(ros2, rcl_node_init, node_name, namespace); #endif } -void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace) { +void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace) +{ #ifdef WITH_LTTNG - tracepoint(ros2, rcl_publisher_init, node_name, namespace); + tracepoint(ros2, rcl_publisher_init, node_name, namespace); #endif } -void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name) { +void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name) +{ #ifdef WITH_LTTNG - tracepoint(ros2, rcl_subscription_init, node_name, topic_name); + tracepoint(ros2, rcl_subscription_init, node_name, topic_name); #endif } From 7e215289d71f44f307f23a6285364989eb113f0e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 09:03:03 +0200 Subject: [PATCH 015/132] Add rmw_handle to rcl_*_init tracepoint params --- tracetools/include/tracetools/tracetools.h | 4 ++-- tracetools/lttng/tp_call.tp | 4 +++- tracetools/src/tracetools.c | 8 ++++---- 3 files changed, 9 insertions(+), 7 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index fc4896e..bc7060a 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -26,12 +26,12 @@ void ros_trace_rcl_init(); /** * tp: rcl_node_init */ -void ros_trace_rcl_node_init(const char * node_name, const char * namespace); +void ros_trace_rcl_node_init(const char * node_name, const char * node_namespace, const void * rmw_handle); /** * tp: rcl_publisher_init */ -void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace); +void ros_trace_rcl_publisher_init(const char * node_name, const char * node_namespace); /** * tp: rcl_subscription_init diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 0d0aa4c..c02e6d9 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -14,11 +14,13 @@ TRACEPOINT_EVENT( rcl_node_init, TP_ARGS( const char*, node_name_arg, - const char*, namespace_arg + const char*, namespace_arg, + const void*, rmw_handle_arg ), TP_FIELDS( ctf_string(node_name, node_name_arg) ctf_string(namespace, namespace_arg) + ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 5efcaed..a48b9a9 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -21,17 +21,17 @@ void ros_trace_rcl_init() #endif } -void ros_trace_rcl_node_init(const char * node_name, const char * namespace) +void ros_trace_rcl_node_init(const char * node_name, const char * node_namespace, const void * rmw_handle) { #ifdef WITH_LTTNG - tracepoint(ros2, rcl_node_init, node_name, namespace); + tracepoint(ros2, rcl_node_init, node_name, node_namespace, rmw_handle); #endif } -void ros_trace_rcl_publisher_init(const char * node_name, const char * namespace) +void ros_trace_rcl_publisher_init(const char * node_name, const char * node_namespace) { #ifdef WITH_LTTNG - tracepoint(ros2, rcl_publisher_init, node_name, namespace); + tracepoint(ros2, rcl_publisher_init, node_name, node_namespace); #endif } From cd75a0a2e19fc1488d3b6b2042c64bfeb819edee Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 09:05:34 +0200 Subject: [PATCH 016/132] Add callback start/end tracepoints --- tracetools/include/tracetools/tracetools.h | 10 +++++++++ tracetools/lttng/tp_call.tp | 24 ++++++++++++++++++++++ tracetools/scripts/setup-lttng.sh | 4 +++- tracetools/src/tracetools.c | 14 +++++++++++++ 4 files changed, 51 insertions(+), 1 deletion(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index bc7060a..b96a8cd 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -38,6 +38,16 @@ void ros_trace_rcl_publisher_init(const char * node_name, const char * node_name */ void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name); +/** + * tp: rclcpp_callback_start + */ +void ros_trace_rclcpp_callback_start(const void * callback, const bool is_intra_process); + +/** + * tp: rclcpp_callback_end + */ +void ros_trace_rclcpp_callback_end(const void * callback); + #ifdef __cplusplus } #endif diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index c02e6d9..1f62616 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -49,3 +49,27 @@ TRACEPOINT_EVENT( ctf_string(topic_name, topic_name_arg) ) ) + +TRACEPOINT_EVENT( + ros2, + rclcpp_callback_start, + TP_ARGS( + const void*, callback_arg, + int, is_intra_process_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer(int, is_intra_process, is_intra_process_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_callback_end, + TP_ARGS( + const void*, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, callback, callback_arg) + ) +) diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index 24a6e17..b146a0e 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -5,7 +5,9 @@ for event in \ ros2:rcl_init \ ros2:rcl_node_init \ ros2:rcl_publisher_init \ - ros2:rcl_subscription_init + ros2:rcl_subscription_init \ + ros2:rclcpp_callback_start \ + ros2:rclcpp_callback_end do lttng enable-event -c ros2 -u $event done diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index a48b9a9..a335318 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -41,3 +41,17 @@ void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_ tracepoint(ros2, rcl_subscription_init, node_name, topic_name); #endif } + +void ros_trace_rclcpp_callback_start(const void * callback, const bool is_intra_process) +{ +#ifdef WITH_LTTNG + tracepoint(ros2, rclcpp_callback_start, callback, (is_intra_process ? 1 : 0)); +#endif +} + +void ros_trace_rclcpp_callback_end(const void * callback) +{ +#ifdef WITH_LTTNG + tracepoint(ros2, rclcpp_callback_end, callback); +#endif +} \ No newline at end of file From dd85e2af74338935eabc42deed6fcd178087f2ff Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 13:24:21 +0200 Subject: [PATCH 017/132] Rename rclcpp_callback_start|end to rclcpp_subscription_callback_start|end --- tracetools/include/tracetools/tracetools.h | 8 ++++---- tracetools/lttng/tp_call.tp | 4 ++-- tracetools/scripts/setup-lttng.sh | 4 ++-- tracetools/src/tracetools.c | 8 ++++---- 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index b96a8cd..94a7281 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -39,14 +39,14 @@ void ros_trace_rcl_publisher_init(const char * node_name, const char * node_name void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name); /** - * tp: rclcpp_callback_start + * tp: rclcpp_subscription_callback_start */ -void ros_trace_rclcpp_callback_start(const void * callback, const bool is_intra_process); +void ros_trace_rclcpp_subscription_callback_start(const void * callback, const bool is_intra_process); /** - * tp: rclcpp_callback_end + * tp: rclcpp_subscription_callback_end */ -void ros_trace_rclcpp_callback_end(const void * callback); +void ros_trace_rclcpp_subscription_callback_end(const void * callback); #ifdef __cplusplus } diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 1f62616..aa4a07b 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -52,7 +52,7 @@ TRACEPOINT_EVENT( TRACEPOINT_EVENT( ros2, - rclcpp_callback_start, + rclcpp_subscription_callback_start, TP_ARGS( const void*, callback_arg, int, is_intra_process_arg @@ -65,7 +65,7 @@ TRACEPOINT_EVENT( TRACEPOINT_EVENT( ros2, - rclcpp_callback_end, + rclcpp_subscription_callback_end, TP_ARGS( const void*, callback_arg ), diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index b146a0e..40133da 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -6,8 +6,8 @@ for event in \ ros2:rcl_node_init \ ros2:rcl_publisher_init \ ros2:rcl_subscription_init \ - ros2:rclcpp_callback_start \ - ros2:rclcpp_callback_end + ros2:rclcpp_subscription_callback_start \ + ros2:rclcpp_subscription_callback_end do lttng enable-event -c ros2 -u $event done diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index a335318..6d5ba57 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -42,16 +42,16 @@ void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_ #endif } -void ros_trace_rclcpp_callback_start(const void * callback, const bool is_intra_process) +void ros_trace_rclcpp_subscription_callback_start(const void * callback, const bool is_intra_process) { #ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_callback_start, callback, (is_intra_process ? 1 : 0)); + tracepoint(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0)); #endif } -void ros_trace_rclcpp_callback_end(const void * callback) +void ros_trace_rclcpp_subscription_callback_end(const void * callback) { #ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_callback_end, callback); + tracepoint(ros2, rclcpp_subscription_callback_end, callback); #endif } \ No newline at end of file From a595bb06bf290bde6681d2f2870d2758f2683b6c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 13:52:19 +0200 Subject: [PATCH 018/132] Add service callback start/end tracepoints --- tracetools/include/tracetools/tracetools.h | 10 ++++++++++ tracetools/lttng/tp_call.tp | 22 ++++++++++++++++++++++ tracetools/src/tracetools.c | 16 +++++++++++++++- 3 files changed, 47 insertions(+), 1 deletion(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 94a7281..56402b2 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -48,6 +48,16 @@ void ros_trace_rclcpp_subscription_callback_start(const void * callback, const b */ void ros_trace_rclcpp_subscription_callback_end(const void * callback); +/** + * tp: rclcpp_service_callback_start + */ +void ros_trace_rclcpp_service_callback_start(const void * callback); + +/** + * tp: rclcpp_service_callback_end + */ +void ros_trace_rclcpp_service_callback_end(const void * callback); + #ifdef __cplusplus } #endif diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index aa4a07b..c3bd7a1 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -73,3 +73,25 @@ TRACEPOINT_EVENT( ctf_integer_hex(const void*, callback, callback_arg) ) ) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_start, + TP_ARGS( + const void*, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_end, + TP_ARGS( + const void*, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, callback, callback_arg) + ) +) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 6d5ba57..b14d1d2 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -54,4 +54,18 @@ void ros_trace_rclcpp_subscription_callback_end(const void * callback) #ifdef WITH_LTTNG tracepoint(ros2, rclcpp_subscription_callback_end, callback); #endif -} \ No newline at end of file +} + +void ros_trace_rclcpp_service_callback_start(const void * callback) +{ +#ifdef WITH_LTTNG + tracepoint(ros2, rclcpp_service_callback_start, callback); +#endif +} + +void ros_trace_rclcpp_service_callback_end(const void * callback) +{ +#ifdef WITH_LTTNG + tracepoint(ros2, rclcpp_service_callback_end, callback); +#endif +} From 922ba77f97918ada8834bebd68cd4014f4aa812e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 14:57:36 +0200 Subject: [PATCH 019/132] Use macro for tracepoint functions --- tracetools/include/tracetools/tracetools.h | 35 ++++++++--- tracetools/src/tracetools.c | 71 ++++++++++++---------- 2 files changed, 66 insertions(+), 40 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 56402b2..620de75 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -21,42 +21,61 @@ bool ros_trace_compile_status(); /** * tp: rcl_init */ -void ros_trace_rcl_init(); +void TRACEPOINT(rcl_init); /** * tp: rcl_node_init */ -void ros_trace_rcl_node_init(const char * node_name, const char * node_namespace, const void * rmw_handle); +void TRACEPOINT( + rcl_node_init, + const char * node_name, + const char * node_namespace, + const void * rmw_handle); /** * tp: rcl_publisher_init */ -void ros_trace_rcl_publisher_init(const char * node_name, const char * node_namespace); +void TRACEPOINT( + rcl_publisher_init, + const char * node_name, + const char * node_namespace); /** * tp: rcl_subscription_init */ -void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name); +void TRACEPOINT( + rcl_subscription_init, + const char * node_name, + const char * topic_name); /** * tp: rclcpp_subscription_callback_start */ -void ros_trace_rclcpp_subscription_callback_start(const void * callback, const bool is_intra_process); +void TRACEPOINT( + rclcpp_subscription_callback_start, + const void * callback, + const bool is_intra_process); /** * tp: rclcpp_subscription_callback_end */ -void ros_trace_rclcpp_subscription_callback_end(const void * callback); +void TRACEPOINT( + rclcpp_subscription_callback_end, + const void * callback); /** * tp: rclcpp_service_callback_start */ -void ros_trace_rclcpp_service_callback_start(const void * callback); +void TRACEPOINT( + rclcpp_service_callback_start, + const void * callback); /** * tp: rclcpp_service_callback_end */ -void ros_trace_rclcpp_service_callback_end(const void * callback); +void TRACEPOINT( + rclcpp_service_callback_end, + const void * callback); #ifdef __cplusplus } diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index b14d1d2..c98e7fd 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -2,6 +2,10 @@ #ifdef WITH_LTTNG #include "tp_call.h" +#define CONDITIONAL_TP(...) \ + tracepoint(__VA_ARGS__); +#else + #define CONDITIONAL_TP(...) #endif @@ -14,58 +18,61 @@ bool ros_trace_compile_status() #endif } -void ros_trace_rcl_init() +void TRACEPOINT(rcl_init) { -#ifdef WITH_LTTNG - tracepoint(ros2, rcl_init); -#endif + CONDITIONAL_TP(ros2, rcl_init); } -void ros_trace_rcl_node_init(const char * node_name, const char * node_namespace, const void * rmw_handle) +void TRACEPOINT( + rcl_node_init, + const char * node_name, + const char * node_namespace, + const void * rmw_handle) { -#ifdef WITH_LTTNG - tracepoint(ros2, rcl_node_init, node_name, node_namespace, rmw_handle); -#endif + CONDITIONAL_TP(ros2, rcl_node_init, node_name, node_namespace, rmw_handle); } -void ros_trace_rcl_publisher_init(const char * node_name, const char * node_namespace) +void TRACEPOINT( + rcl_publisher_init, + const char * node_name, + const char * node_namespace) { -#ifdef WITH_LTTNG - tracepoint(ros2, rcl_publisher_init, node_name, node_namespace); -#endif + CONDITIONAL_TP(ros2, rcl_publisher_init, node_name, node_namespace); } -void ros_trace_rcl_subscription_init(const char * node_name, const char * topic_name) +void TRACEPOINT( + rcl_subscription_init, + const char * node_name, + const char * topic_name) { -#ifdef WITH_LTTNG - tracepoint(ros2, rcl_subscription_init, node_name, topic_name); -#endif + CONDITIONAL_TP(ros2, rcl_subscription_init, node_name, topic_name); } -void ros_trace_rclcpp_subscription_callback_start(const void * callback, const bool is_intra_process) +void TRACEPOINT( + rclcpp_subscription_callback_start, + const void * callback, + const bool is_intra_process) { -#ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0)); -#endif + CONDITIONAL_TP(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0)); } -void ros_trace_rclcpp_subscription_callback_end(const void * callback) +void TRACEPOINT( + rclcpp_subscription_callback_end, + const void * callback) { -#ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_subscription_callback_end, callback); -#endif + CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback); } -void ros_trace_rclcpp_service_callback_start(const void * callback) +void TRACEPOINT( + rclcpp_service_callback_start, + const void * callback) { -#ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_service_callback_start, callback); -#endif + CONDITIONAL_TP(ros2, rclcpp_service_callback_start, callback); } -void ros_trace_rclcpp_service_callback_end(const void * callback) +void TRACEPOINT( + rclcpp_service_callback_end, + const void * callback) { -#ifdef WITH_LTTNG - tracepoint(ros2, rclcpp_service_callback_end, callback); -#endif + CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback); } From b09f72081c5692f02669f81153c2ae1db1099925 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 14:59:31 +0200 Subject: [PATCH 020/132] Add *subscription_callback_added and link subscription_handle to rcl_subscription_init --- tracetools/include/tracetools/tracetools.h | 9 +++++++++ tracetools/lttng/tp_call.tp | 15 +++++++++++++++ tracetools/src/tracetools.c | 11 ++++++++++- 3 files changed, 34 insertions(+), 1 deletion(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 620de75..81517e7 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -45,9 +45,18 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_subscription_init, + const void * subscription_handle, const char * node_name, const char * topic_name); +/** + * tp: rclcpp_subscription_callback_added + */ +void TRACEPOINT( + rclcpp_subscription_callback_added, + const void * subscription_handle, + const void * callback); + /** * tp: rclcpp_subscription_callback_start */ diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index c3bd7a1..b23e101 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -41,15 +41,30 @@ TRACEPOINT_EVENT( ros2, rcl_subscription_init, TP_ARGS( + const void*, subscription_handle_arg, const char*, node_name_arg, const char*, topic_name_arg ), TP_FIELDS( + ctf_integer_hex(const void*, subscription_handle, subscription_handle_arg) ctf_string(node_name, node_name_arg) ctf_string(topic_name, topic_name_arg) ) ) +TRACEPOINT_EVENT( + ros2, + rclcpp_subscription_callback_added, + TP_ARGS( + const void*, subscription_handle_arg, + const void*, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void*, callback, callback_arg) + ) +) + TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_start, diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index c98e7fd..b78af20 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -42,10 +42,19 @@ void TRACEPOINT( void TRACEPOINT( rcl_subscription_init, + const void * subscription_handle, const char * node_name, const char * topic_name) { - CONDITIONAL_TP(ros2, rcl_subscription_init, node_name, topic_name); + CONDITIONAL_TP(ros2, rcl_subscription_init, subscription_handle, node_name, topic_name); +} + +void TRACEPOINT( + rclcpp_subscription_callback_added, + const void * subscription_handle, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_subscription_callback_added, subscription_handle, callback); } void TRACEPOINT( From 9ae7c8d99c9895aad57616465842b0f297f339b9 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 15:42:30 +0200 Subject: [PATCH 021/132] Add context to rcl_init tracepoint params --- tracetools/include/tracetools/tracetools.h | 4 +++- tracetools/lttng/tp_call.tp | 2 ++ tracetools/src/tracetools.c | 6 ++++-- 3 files changed, 9 insertions(+), 3 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 81517e7..1e84e11 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -21,7 +21,9 @@ bool ros_trace_compile_status(); /** * tp: rcl_init */ -void TRACEPOINT(rcl_init); +void TRACEPOINT( + rcl_init, + const void * context); /** * tp: rcl_node_init diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index b23e101..b6796f6 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -4,8 +4,10 @@ TRACEPOINT_EVENT( ros2, rcl_init, TP_ARGS( + const void*, context_arg ), TP_FIELDS( + ctf_integer_hex(const void*, context, context_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index b78af20..7509512 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -18,9 +18,11 @@ bool ros_trace_compile_status() #endif } -void TRACEPOINT(rcl_init) +void TRACEPOINT( + rcl_init, + const void * context) { - CONDITIONAL_TP(ros2, rcl_init); + CONDITIONAL_TP(ros2, rcl_init, context); } void TRACEPOINT( From 974f4144bb05b5a515c4f3e8cf92215793443035 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 15:43:53 +0200 Subject: [PATCH 022/132] Fix macro --- tracetools/src/tracetools.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 7509512..cefd8e9 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -3,7 +3,7 @@ #ifdef WITH_LTTNG #include "tp_call.h" #define CONDITIONAL_TP(...) \ - tracepoint(__VA_ARGS__); + tracepoint(__VA_ARGS__) #else #define CONDITIONAL_TP(...) #endif From 88d2356bd6c43b87f359bd4c57ec7f448e9df9bf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 16:19:54 +0200 Subject: [PATCH 023/132] Enable *subscription_callback_added event --- tracetools/scripts/setup-lttng.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index 40133da..deb6895 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -6,6 +6,7 @@ for event in \ ros2:rcl_node_init \ ros2:rcl_publisher_init \ ros2:rcl_subscription_init \ + ros2:rclcpp_subscription_callback_added \ ros2:rclcpp_subscription_callback_start \ ros2:rclcpp_subscription_callback_end do From efe47e309d03369ad4f74c5c379f2b6acc647873 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 17 May 2019 16:21:36 +0200 Subject: [PATCH 024/132] Fix indendation --- tracetools/include/tracetools/tracetools.h | 52 +++++++++++----------- 1 file changed, 26 insertions(+), 26 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 1e84e11..f9a3b07 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -6,7 +6,7 @@ #include #define TRACEPOINT(event_name, ...) \ - (ros_trace_##event_name)(__VA_ARGS__) + (ros_trace_##event_name)(__VA_ARGS__) #ifdef __cplusplus extern "C" @@ -22,71 +22,71 @@ bool ros_trace_compile_status(); * tp: rcl_init */ void TRACEPOINT( - rcl_init, - const void * context); + rcl_init, + const void * context); /** * tp: rcl_node_init */ void TRACEPOINT( - rcl_node_init, - const char * node_name, - const char * node_namespace, - const void * rmw_handle); + rcl_node_init, + const char * node_name, + const char * node_namespace, + const void * rmw_handle); /** * tp: rcl_publisher_init */ void TRACEPOINT( - rcl_publisher_init, - const char * node_name, - const char * node_namespace); + rcl_publisher_init, + const char * node_name, + const char * node_namespace); /** * tp: rcl_subscription_init */ void TRACEPOINT( - rcl_subscription_init, - const void * subscription_handle, - const char * node_name, - const char * topic_name); + rcl_subscription_init, + const void * subscription_handle, + const char * node_name, + const char * topic_name); /** * tp: rclcpp_subscription_callback_added */ void TRACEPOINT( - rclcpp_subscription_callback_added, - const void * subscription_handle, - const void * callback); + rclcpp_subscription_callback_added, + const void * subscription_handle, + const void * callback); /** * tp: rclcpp_subscription_callback_start */ void TRACEPOINT( - rclcpp_subscription_callback_start, - const void * callback, - const bool is_intra_process); + rclcpp_subscription_callback_start, + const void * callback, + const bool is_intra_process); /** * tp: rclcpp_subscription_callback_end */ void TRACEPOINT( - rclcpp_subscription_callback_end, - const void * callback); + rclcpp_subscription_callback_end, + const void * callback); /** * tp: rclcpp_service_callback_start */ void TRACEPOINT( - rclcpp_service_callback_start, - const void * callback); + rclcpp_service_callback_start, + const void * callback); /** * tp: rclcpp_service_callback_end */ void TRACEPOINT( - rclcpp_service_callback_end, - const void * callback); + rclcpp_service_callback_end, + const void * callback); #ifdef __cplusplus } From f7fc7f773c8986d793286b28a7791bd255a1971d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 20 May 2019 11:45:19 +0200 Subject: [PATCH 025/132] Add tracepoints for service init and callback_added --- tracetools/include/tracetools/tracetools.h | 17 +++++++++++++ tracetools/lttng/tp_call.tp | 28 ++++++++++++++++++++++ tracetools/scripts/setup-lttng.sh | 6 ++++- tracetools/src/tracetools.c | 17 +++++++++++++ 4 files changed, 67 insertions(+), 1 deletion(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index f9a3b07..9f865ed 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -74,6 +74,23 @@ void TRACEPOINT( rclcpp_subscription_callback_end, const void * callback); +/** + * tp: rcl_service_init + */ +void TRACEPOINT( + rcl_service_init, + const void * service, + const void * node, + const char * service_name); + +/** + * tp: rclcpp_service_callback_added + */ +void TRACEPOINT( + rclcpp_service_callback_added, + const void * service, + const void * callback); + /** * tp: rclcpp_service_callback_start */ diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index b6796f6..3073e24 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -91,6 +91,34 @@ TRACEPOINT_EVENT( ) ) +TRACEPOINT_EVENT( + ros2, + rcl_service_init, + TP_ARGS( + const void*, service_arg, + const void*, node_arg, + const char*, service_name_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, service, service_arg) + ctf_integer_hex(const void*, node, node_arg) + ctf_string(service_name, service_name_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_added, + TP_ARGS( + const void*, service_arg, + const void*, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void*, service, service_arg) + ctf_integer_hex(const void*, callback, callback_arg) + ) +) + TRACEPOINT_EVENT( ros2, rclcpp_service_callback_start, diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index deb6895..ee30661 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -8,7 +8,11 @@ for event in \ ros2:rcl_subscription_init \ ros2:rclcpp_subscription_callback_added \ ros2:rclcpp_subscription_callback_start \ - ros2:rclcpp_subscription_callback_end + ros2:rclcpp_subscription_callback_end \ + ros2:rcl_service_init \ + ros2:rclcpp_service_callback_added \ + ros2:rclcpp_service_callback_start \ + ros2:rclcpp_service_callback_end do lttng enable-event -c ros2 -u $event done diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index cefd8e9..2c57b8c 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -74,6 +74,23 @@ void TRACEPOINT( CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback); } +void TRACEPOINT( + rcl_service_init, + const void * service, + const void * node, + const char * service_name) +{ + CONDITIONAL_TP(ros2, rcl_service_init, service, node, service_name); +} + +void TRACEPOINT( + rclcpp_service_callback_added, + const void * service, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service, callback); +} + void TRACEPOINT( rclcpp_service_callback_start, const void * callback) From a97c980a972cbca85ba9aba83daf882e708496cb Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 20 May 2019 13:58:06 +0200 Subject: [PATCH 026/132] Fix tracepoints arguments --- tracetools/include/tracetools/tracetools.h | 21 +++++++----- tracetools/lttng/tp_call.tp | 40 ++++++++++++++-------- tracetools/src/tracetools.c | 31 ++++++++++------- 3 files changed, 56 insertions(+), 36 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 9f865ed..056fa52 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -30,25 +30,29 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_node_init, + const void * node_handle, + const void * rmw_handle, const char * node_name, - const char * node_namespace, - const void * rmw_handle); + const char * node_namespace); /** * tp: rcl_publisher_init */ void TRACEPOINT( rcl_publisher_init, - const char * node_name, - const char * node_namespace); + const void * node_handle, + const void * rmw_handle, + const void * publisher_handle, + const char * topic_name); /** * tp: rcl_subscription_init */ void TRACEPOINT( rcl_subscription_init, + const void * node_handle, + const void * rmw_handle, const void * subscription_handle, - const char * node_name, const char * topic_name); /** @@ -79,8 +83,9 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_service_init, - const void * service, - const void * node, + const void * node_handle, + const void * rmw_handle, + const void * service_handle, const char * service_name); /** @@ -88,7 +93,7 @@ void TRACEPOINT( */ void TRACEPOINT( rclcpp_service_callback_added, - const void * service, + const void * service_handle, const void * callback); /** diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 3073e24..ec99a59 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -15,14 +15,16 @@ TRACEPOINT_EVENT( ros2, rcl_node_init, TP_ARGS( + const void*, node_handle_arg, + const void*, rmw_handle_arg, const char*, node_name_arg, - const char*, namespace_arg, - const void*, rmw_handle_arg + const char*, namespace_arg ), TP_FIELDS( + ctf_integer_hex(const void*, node_handle, node_handle_arg) + ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) ctf_string(node_name, node_name_arg) ctf_string(namespace, namespace_arg) - ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) ) ) @@ -30,12 +32,16 @@ TRACEPOINT_EVENT( ros2, rcl_publisher_init, TP_ARGS( - const char*, node_name_arg, - const char*, namespace_arg + const void*, node_handle_arg, + const void*, rmw_handle_arg, + const void*, publisher_handle_arg, + const char*, topic_name_arg ), TP_FIELDS( - ctf_string(node_name, node_name_arg) - ctf_string(namespace, namespace_arg) + ctf_integer_hex(const void*, node_handle, node_handle_arg) + ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void*, publisher_handle, publisher_handle_arg) + ctf_string(topic_name, topic_name_arg) ) ) @@ -43,13 +49,15 @@ TRACEPOINT_EVENT( ros2, rcl_subscription_init, TP_ARGS( + const void*, node_handle_arg, + const void*, rmw_handle_arg, const void*, subscription_handle_arg, - const char*, node_name_arg, const char*, topic_name_arg ), TP_FIELDS( + ctf_integer_hex(const void*, node_handle, node_handle_arg) + ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void*, subscription_handle, subscription_handle_arg) - ctf_string(node_name, node_name_arg) ctf_string(topic_name, topic_name_arg) ) ) @@ -95,13 +103,15 @@ TRACEPOINT_EVENT( ros2, rcl_service_init, TP_ARGS( - const void*, service_arg, - const void*, node_arg, + const void*, node_handle_arg, + const void*, rmw_handle_arg, + const void*, service_handle_arg, const char*, service_name_arg ), TP_FIELDS( - ctf_integer_hex(const void*, service, service_arg) - ctf_integer_hex(const void*, node, node_arg) + ctf_integer_hex(const void*, node_handle, node_handle_arg) + ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void*, service_handle, service_handle_arg) ctf_string(service_name, service_name_arg) ) ) @@ -110,11 +120,11 @@ TRACEPOINT_EVENT( ros2, rclcpp_service_callback_added, TP_ARGS( - const void*, service_arg, + const void*, service_handle_arg, const void*, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, service, service_arg) + ctf_integer_hex(const void*, service_handle, service_handle_arg) ctf_integer_hex(const void*, callback, callback_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 2c57b8c..c2255e7 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -27,28 +27,32 @@ void TRACEPOINT( void TRACEPOINT( rcl_node_init, + const void * node_handle, + const void * rmw_handle, const char * node_name, - const char * node_namespace, - const void * rmw_handle) + const char * node_namespace) { - CONDITIONAL_TP(ros2, rcl_node_init, node_name, node_namespace, rmw_handle); + CONDITIONAL_TP(ros2, rcl_node_init, node_handle, rmw_handle, node_name, node_namespace); } void TRACEPOINT( rcl_publisher_init, - const char * node_name, - const char * node_namespace) + const void * node_handle, + const void * rmw_handle, + const void * publisher_handle, + const char * topic_name) { - CONDITIONAL_TP(ros2, rcl_publisher_init, node_name, node_namespace); + CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, rmw_handle, publisher_handle, topic_name); } void TRACEPOINT( rcl_subscription_init, + const void * node_handle, + const void * rmw_handle, const void * subscription_handle, - const char * node_name, const char * topic_name) { - CONDITIONAL_TP(ros2, rcl_subscription_init, subscription_handle, node_name, topic_name); + CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, rmw_handle, subscription_handle, topic_name); } void TRACEPOINT( @@ -76,19 +80,20 @@ void TRACEPOINT( void TRACEPOINT( rcl_service_init, - const void * service, - const void * node, + const void * node_handle, + const void * rmw_handle, + const void * service_handle, const char * service_name) { - CONDITIONAL_TP(ros2, rcl_service_init, service, node, service_name); + CONDITIONAL_TP(ros2, rcl_service_init, node_handle, rmw_handle, service_handle, service_name); } void TRACEPOINT( rclcpp_service_callback_added, - const void * service, + const void * service_handle, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service, callback); + CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service_handle, callback); } void TRACEPOINT( From a5260a0c9178818ae59194485e603d518270b75d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 20 May 2019 15:17:00 +0200 Subject: [PATCH 027/132] Fix preprocessor-related indentation --- tracetools/src/tracetools.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index c2255e7..6267463 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -1,11 +1,11 @@ #include "tracetools/tracetools.h" #ifdef WITH_LTTNG -#include "tp_call.h" -#define CONDITIONAL_TP(...) \ - tracepoint(__VA_ARGS__) +# include "tp_call.h" +# define CONDITIONAL_TP(...) \ + tracepoint(__VA_ARGS__) #else - #define CONDITIONAL_TP(...) +# define CONDITIONAL_TP(...) #endif From 607d68bfcd49f7aa2bdf8b80932da7ff8c147283 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 23 May 2019 11:26:59 +0200 Subject: [PATCH 028/132] Fix style for tp definitions --- tracetools/lttng/tp_call.tp | 90 ++++++++++++++++++------------------- 1 file changed, 45 insertions(+), 45 deletions(-) diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index ec99a59..853cf0d 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -4,10 +4,10 @@ TRACEPOINT_EVENT( ros2, rcl_init, TP_ARGS( - const void*, context_arg + const void *, context_arg ), TP_FIELDS( - ctf_integer_hex(const void*, context, context_arg) + ctf_integer_hex(const void *, context, context_arg) ) ) @@ -15,14 +15,14 @@ TRACEPOINT_EVENT( ros2, rcl_node_init, TP_ARGS( - const void*, node_handle_arg, - const void*, rmw_handle_arg, - const char*, node_name_arg, - const char*, namespace_arg + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const char *, node_name_arg, + const char *, namespace_arg ), TP_FIELDS( - ctf_integer_hex(const void*, node_handle, node_handle_arg) - ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_string(node_name, node_name_arg) ctf_string(namespace, namespace_arg) ) @@ -32,15 +32,15 @@ TRACEPOINT_EVENT( ros2, rcl_publisher_init, TP_ARGS( - const void*, node_handle_arg, - const void*, rmw_handle_arg, - const void*, publisher_handle_arg, - const char*, topic_name_arg + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const void *, publisher_handle_arg, + const char *, topic_name_arg ), TP_FIELDS( - ctf_integer_hex(const void*, node_handle, node_handle_arg) - ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) - ctf_integer_hex(const void*, publisher_handle, publisher_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) ctf_string(topic_name, topic_name_arg) ) ) @@ -49,15 +49,15 @@ TRACEPOINT_EVENT( ros2, rcl_subscription_init, TP_ARGS( - const void*, node_handle_arg, - const void*, rmw_handle_arg, - const void*, subscription_handle_arg, - const char*, topic_name_arg + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const void *, subscription_handle_arg, + const char *, topic_name_arg ), TP_FIELDS( - ctf_integer_hex(const void*, node_handle, node_handle_arg) - ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) - ctf_integer_hex(const void*, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_string(topic_name, topic_name_arg) ) ) @@ -66,12 +66,12 @@ TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_added, TP_ARGS( - const void*, subscription_handle_arg, - const void*, callback_arg + const void *, subscription_handle_arg, + const void *, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, subscription_handle, subscription_handle_arg) - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) ) ) @@ -79,11 +79,11 @@ TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_start, TP_ARGS( - const void*, callback_arg, + const void *, callback_arg, int, is_intra_process_arg ), TP_FIELDS( - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, callback, callback_arg) ctf_integer(int, is_intra_process, is_intra_process_arg) ) ) @@ -92,10 +92,10 @@ TRACEPOINT_EVENT( ros2, rclcpp_subscription_callback_end, TP_ARGS( - const void*, callback_arg + const void *, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, callback, callback_arg) ) ) @@ -103,15 +103,15 @@ TRACEPOINT_EVENT( ros2, rcl_service_init, TP_ARGS( - const void*, node_handle_arg, - const void*, rmw_handle_arg, - const void*, service_handle_arg, - const char*, service_name_arg + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const void *, service_handle_arg, + const char *, service_name_arg ), TP_FIELDS( - ctf_integer_hex(const void*, node_handle, node_handle_arg) - ctf_integer_hex(const void*, rmw_handle, rmw_handle_arg) - ctf_integer_hex(const void*, service_handle, service_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void *, service_handle, service_handle_arg) ctf_string(service_name, service_name_arg) ) ) @@ -120,12 +120,12 @@ TRACEPOINT_EVENT( ros2, rclcpp_service_callback_added, TP_ARGS( - const void*, service_handle_arg, - const void*, callback_arg + const void *, service_handle_arg, + const void *, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, service_handle, service_handle_arg) - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, service_handle, service_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) ) ) @@ -133,10 +133,10 @@ TRACEPOINT_EVENT( ros2, rclcpp_service_callback_start, TP_ARGS( - const void*, callback_arg + const void *, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, callback, callback_arg) ) ) @@ -144,9 +144,9 @@ TRACEPOINT_EVENT( ros2, rclcpp_service_callback_end, TP_ARGS( - const void*, callback_arg + const void *, callback_arg ), TP_FIELDS( - ctf_integer_hex(const void*, callback, callback_arg) + ctf_integer_hex(const void *, callback, callback_arg) ) ) From 48233c709ef471bdd3d1c74106632cf54bf5c03d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 24 May 2019 16:09:30 +0200 Subject: [PATCH 029/132] Add initial draft of ROS 2 design summary --- doc/ros_2.md | 149 +++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 149 insertions(+) create mode 100644 doc/ros_2.md diff --git a/doc/ros_2.md b/doc/ros_2.md new file mode 100644 index 0000000..9b58127 --- /dev/null +++ b/doc/ros_2.md @@ -0,0 +1,149 @@ +# ROS 2 design notes for instrumentation + +The goal is to document ROS 2's design/architecture in order to properly design the instrumentation for it. + +## Notes on client libraries + +ROS 2 has changed the way it deals with client libraries. It offers a base ROS client library (`rcl`) written in C. This client library is the base for any language-specific implementation, such as `rclcpp` and `rclpy`. + +However, `rcl` is obviously fairly basic, and still does leave a fair amount of implementation work up to the client libraries. For example, callbacks are not at all handled in `rcl`, and are left to the client library implementations. + +This means that some instrumentation work might have to be re-done for every client library that we want to trace. We cannot simply instrument `rcl`, nor can we only instrument the base `rmw` interface if we want to dig into that. + +This document will mainly discuss `rcl` and `rclcpp`, but `rclpy` should eventually be added and supported. + +## Flow description + +### Process creation + +In the call to `rclcpp::init(argc, argv)`, an `rclcpp::Context` object is created and CLI arguments are parsed. Much of the work is actually done by `rcl` through a call to `rcl_init()`. + +This has to be done once per process, and usually at the very beginning. The components that are then instanciated share this context. + +```mermaid +sequenceDiagram + participant process + participant rclcpp + participant rcl + + process->>rclcpp: rclcpp::init() + Note over rclcpp: allocates
rclcpp::Context object + rclcpp->>rcl: rcl_init() + Note over rcl: validates & processes context object +``` + +### Note/component creation + +In ROS 2, a process can contain multiple nodes. These are sometimes referred to as "components." + +These components are instanciated by the containing process. They are usually classes that extend `rclcpp::Node`, so that the node initialization work is done by the parent constructor. + +This parent constructor will allocate its own `rcl_node_t` handle and call `rcl_node_init()`, which will validate the node name/namespace. `rcl` will also call `rmw_create_node()` the node's `rmw` handle (`rmw_node_t`) to be used later by publishers and subscriptions. + +```mermaid +sequenceDiagram + participant process + participant component + participant rclcpp + participant rcl + participant rmw + + process->>component: Component() + component->>rclcpp: : Node() + Note over rclcpp: allocates rcl_node_t handle + rclcpp->>rcl: rcl_node_init() + Note over rcl: checks node name/namespace + Note over rcl: populates rcl_note_t + rcl->>rmw: rmw_create_node() + Note over rmw: creates rmw_node_t handle +``` + +### Publisher creation + +The component calls `create_publisher()`, a `rclcpp::Node` method for convenience. That ends up creating an `rclcpp::Publisher` object which extends `rclcpp::PublisherBase`. The latter allocates an `rcl_publisher_t` handle, fetches the corresponding `rcl_node_t` handle, and calls `rcl_publisher_init()` in its constructor. `rcl` does topic name expansion/remapping/validation. It creates an `rmw_publisher_t` handle by calling `rmw_create_publisher()` of the given `rmw` implementation and associates with the node's `rmw_node_t` handle and the publisher's `rcl_publisher_t` handle. + +If intra-process publishing/subscription is enabled, it will be set up after creating the publisher object, through a call to `PublisherBase::setup_intra_process()`, which calls `rcl_publisher_init()`. + +```mermaid +sequenceDiagram + participant component + participant rclcpp + participant rcl + participant rmw + + component->>rclcpp: create_publisher() + Note over rclcpp: through a lot of interfaces + Note over rclcpp: allocates rcl_publisher_t handle + rclcpp->>rcl: rcl_publisher_init() + Note over rcl: populates rcl_publisher_t + rcl->>rmw: rmw_create_publisher() + Note over rmw: creates rmw_publisher_t handle + + opt is intra process + rclcpp->>rcl: rcl_publisher_init() + end +``` + +### Subscription creation + +Subscription creation is done in a very similar manner. + +The componenent calls `create_publisher()`, which ends up creating an `rclcpp::Subscription` object which extends `rclcpp::SubscriptionBase`. The latter allocates an `rcl_subscription_t` handle, fetches its `rcl_node_t` handle, and calls `rcl_subscription_init()` in its constructor. `rcl` does topic name expansion/remapping/validation. It creates an `rmw_subscription_t` handle by calling `rmw_create_subscription()` of the given `rmw` implementation and associates it with the node's `rmw_node_t` handle and the subscription's `rcl_subscription_t` handle. + +If intra-process publishing/subscription is enabled, it will be set up after creating the subscription object, through a call to `Subscription::setup_intra_process()`, which calls `rcl_subscription_init()`. + +```mermaid +sequenceDiagram + participant component + participant rclcpp + participant rcl + participant rmw + + component->>rclcpp: create_subscription() + Note over rclcpp: allocates rcl_subscription_t handle + rclcpp->>rcl: rcl_subscription_init() + Note over rcl: populates rcl_subscription_t + rcl->>rmw: rmw_create_subscription() + Note over rmw: creates rmw_publisher_t handle + + opt is intra process + rclcpp->>rcl: rcl_subscription_init() + end +``` + +### Executors and callbacks + +An `rclcpp::executor::Executor` object is created for a given process. It can be a `SingleThreadedExecutor` or a `MultiThreadedExecutor`. + +Components are instanciated, usually as a `shared_ptr` through `std::make_shared()`, then added to the executor with `Executor::add_node()`. + +After all the components have been added, `Executor::spin()` is called. `SingleThreadedExecutor::spin()` simply loops forever until the process' context isn't valid anymore. It fetches the next `rclcpp::AnyExecutable` (e.g. subscription, timer, service, client), and calls `Executor::execute_any_executable()` with it. This then calls the relevant `execute*()` method (e.g. `execute_timer()`, `execute_subscription()`, `execute_intra_process_subscription()`, `execute_service()`, `execute_client()`). + +For subscriptions, callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. Subscriptions are handled in the `rclcpp` layer. + +In `execute_*subscription()`, the `Executor` allocates a message and calls `rcl_take()`. If that is successful, it then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. Finally, this calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object, which calls the actual `std::function` with the right signature. + + + +```mermaid +sequenceDiagram + participant process + participant executor + participant subscription + participant anycallback + participant rcl + + process->>executor: Executor() + Note over process: instanciates components + process->>executor: add_node(component) + process->>executor: spin() + loop until shutdown + Note over executor: get_next_executable() + Note over executor: execute_any_executable() + Note over executor: execute_subscription() + executor->>rcl: rcl_take() + executor->>subscription: handle_message() + subscription->>anycallback: dispatch() + Note over anycallback: std::function::operator(...) + end +``` From efa3e7bbffa25d23587c782980d5b90615470821 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 09:40:04 +0200 Subject: [PATCH 030/132] Split executors and (subscription) callbacks --- doc/ros_2.md | 62 ++++++++++++++++++++++++++++------------------------ 1 file changed, 34 insertions(+), 28 deletions(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index 9b58127..d8fc315 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -43,13 +43,13 @@ This parent constructor will allocate its own `rcl_node_t` handle and call `rcl_ ```mermaid sequenceDiagram participant process - participant component + participant Component participant rclcpp participant rcl participant rmw - process->>component: Component() - component->>rclcpp: : Node() + process->>Component: Component() + Component->>rclcpp: : Node() Note over rclcpp: allocates rcl_node_t handle rclcpp->>rcl: rcl_node_init() Note over rcl: checks node name/namespace @@ -66,13 +66,12 @@ If intra-process publishing/subscription is enabled, it will be set up after cre ```mermaid sequenceDiagram - participant component + participant Component participant rclcpp participant rcl participant rmw - component->>rclcpp: create_publisher() - Note over rclcpp: through a lot of interfaces + Component->>rclcpp: create_publisher() Note over rclcpp: allocates rcl_publisher_t handle rclcpp->>rcl: rcl_publisher_init() Note over rcl: populates rcl_publisher_t @@ -94,12 +93,12 @@ If intra-process publishing/subscription is enabled, it will be set up after cre ```mermaid sequenceDiagram - participant component + participant Component participant rclcpp participant rcl participant rmw - component->>rclcpp: create_subscription() + Component->>rclcpp: create_subscription() Note over rclcpp: allocates rcl_subscription_t handle rclcpp->>rcl: rcl_subscription_init() Note over rcl: populates rcl_subscription_t @@ -111,7 +110,7 @@ sequenceDiagram end ``` -### Executors and callbacks +### Executors An `rclcpp::executor::Executor` object is created for a given process. It can be a `SingleThreadedExecutor` or a `MultiThreadedExecutor`. @@ -119,31 +118,38 @@ Components are instanciated, usually as a `shared_ptr` through `std::make_shared After all the components have been added, `Executor::spin()` is called. `SingleThreadedExecutor::spin()` simply loops forever until the process' context isn't valid anymore. It fetches the next `rclcpp::AnyExecutable` (e.g. subscription, timer, service, client), and calls `Executor::execute_any_executable()` with it. This then calls the relevant `execute*()` method (e.g. `execute_timer()`, `execute_subscription()`, `execute_intra_process_subscription()`, `execute_service()`, `execute_client()`). +```mermaid +sequenceDiagram + participant process + participant Executor + + process->>Executor: Executor() + Note over process: instanciates components + process->>Executor: add_node(component) + process->>Executor: spin() + loop until shutdown + Note over Executor: get_next_executable() + Note over Executor: execute_any_executable() + Note over Executor: execute_*() + end +``` + +### Subscription callbacks + For subscriptions, callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. Subscriptions are handled in the `rclcpp` layer. In `execute_*subscription()`, the `Executor` allocates a message and calls `rcl_take()`. If that is successful, it then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. Finally, this calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object, which calls the actual `std::function` with the right signature. - - ```mermaid sequenceDiagram - participant process - participant executor - participant subscription - participant anycallback + participant Executor + participant Subscription + participant AnySubscriptionCallback participant rcl - process->>executor: Executor() - Note over process: instanciates components - process->>executor: add_node(component) - process->>executor: spin() - loop until shutdown - Note over executor: get_next_executable() - Note over executor: execute_any_executable() - Note over executor: execute_subscription() - executor->>rcl: rcl_take() - executor->>subscription: handle_message() - subscription->>anycallback: dispatch() - Note over anycallback: std::function::operator(...) - end + Note over Executor: execute_subscription() + Executor->>rcl: rcl_take() + Executor->>Subscription: handle_message() + Subscription->>AnySubscriptionCallback: dispatch() + Note over AnySubscriptionCallback: std::function::operator(...) ``` From 93df2f9a4e8d8cf8b6990ea171d6f322f748d563 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 11:11:33 +0200 Subject: [PATCH 031/132] Add param info for function calls and add instrumentation layer --- doc/ros_2.md | 72 ++++++++++++++++++++++++++++++++++++++-------------- 1 file changed, 53 insertions(+), 19 deletions(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index d8fc315..8f889df 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -10,7 +10,7 @@ However, `rcl` is obviously fairly basic, and still does leave a fair amount of This means that some instrumentation work might have to be re-done for every client library that we want to trace. We cannot simply instrument `rcl`, nor can we only instrument the base `rmw` interface if we want to dig into that. -This document will mainly discuss `rcl` and `rclcpp`, but `rclpy` should eventually be added and supported. +This document will (for now) mainly discuss `rcl` and `rclcpp`, but `rclpy` should eventually be added and supported. ## Flow description @@ -25,11 +25,14 @@ sequenceDiagram participant process participant rclcpp participant rcl + participant tracetools process->>rclcpp: rclcpp::init() Note over rclcpp: allocates
rclcpp::Context object - rclcpp->>rcl: rcl_init() + rclcpp->>rcl: rcl_init(out context) Note over rcl: validates & processes context object + + rcl->>tracetools: TP(rcl_init, context) ``` ### Note/component creation @@ -38,7 +41,7 @@ In ROS 2, a process can contain multiple nodes. These are sometimes referred to These components are instanciated by the containing process. They are usually classes that extend `rclcpp::Node`, so that the node initialization work is done by the parent constructor. -This parent constructor will allocate its own `rcl_node_t` handle and call `rcl_node_init()`, which will validate the node name/namespace. `rcl` will also call `rmw_create_node()` the node's `rmw` handle (`rmw_node_t`) to be used later by publishers and subscriptions. +This parent constructor will allocate its own `rcl_node_t` handle and call `rcl_node_init()`, which will validate the node name/namespace. `rcl` will also call `rmw_create_node()` to get the node's `rmw` handle (`rmw_node_t`). This will be used later by publishers and subscriptions. ```mermaid sequenceDiagram @@ -47,15 +50,20 @@ sequenceDiagram participant rclcpp participant rcl participant rmw + participant tracetools + + Note over rmw: (implementation) process->>Component: Component() Component->>rclcpp: : Node() Note over rclcpp: allocates rcl_node_t handle - rclcpp->>rcl: rcl_node_init() - Note over rcl: checks node name/namespace + rclcpp->>rcl: rcl_node_init(out rcl_node_t, node_name, namespace) + Note over rcl: validates node name/namespace Note over rcl: populates rcl_note_t - rcl->>rmw: rmw_create_node() + rcl->>rmw: rmw_create_node() : rmw_node_t Note over rmw: creates rmw_node_t handle + + rcl->>tracetools: TP(rcl_node_init, &rcl_node_t, &rmw_node_t, node_name, namespace) ``` ### Publisher creation @@ -70,16 +78,21 @@ sequenceDiagram participant rclcpp participant rcl participant rmw + participant tracetools + + Note over rmw: (implementation) Component->>rclcpp: create_publisher() Note over rclcpp: allocates rcl_publisher_t handle - rclcpp->>rcl: rcl_publisher_init() + rclcpp->>rcl: rcl_publisher_init(out rcl_publisher_t, rcl_node_t, topic_name) Note over rcl: populates rcl_publisher_t - rcl->>rmw: rmw_create_publisher() + rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name) : rmw_publisher_t Note over rmw: creates rmw_publisher_t handle + rcl->>tracetools: TP(rcl_publisher_init, &rcl_node_t, &rmw_node_t, &rcl_publisher_t, topic_name) + opt is intra process - rclcpp->>rcl: rcl_publisher_init() + rclcpp->>rcl: rcl_publisher_init(...) end ``` @@ -97,16 +110,21 @@ sequenceDiagram participant rclcpp participant rcl participant rmw + participant tracetools + + Note over rmw: (implementation) Component->>rclcpp: create_subscription() Note over rclcpp: allocates rcl_subscription_t handle - rclcpp->>rcl: rcl_subscription_init() + rclcpp->>rcl: rcl_subscription_init(out rcl_subscription_t, rcl_node_t, topic_name) Note over rcl: populates rcl_subscription_t - rcl->>rmw: rmw_create_subscription() - Note over rmw: creates rmw_publisher_t handle + rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name) : rmw_subscription_t + Note over rmw: creates rmw_subscription_t handle + + rcl->>tracetools: TP(rcl_subscription_init, &rcl_node_t, &rmw_node_t, &rcl_subscription_t, topic_name) opt is intra process - rclcpp->>rcl: rcl_subscription_init() + rclcpp->>rcl: rcl_subscription_init(...) end ``` @@ -122,12 +140,15 @@ After all the components have been added, `Executor::spin()` is called. `SingleT sequenceDiagram participant process participant Executor + participant tracetools process->>Executor: Executor() Note over process: instanciates components process->>Executor: add_node(component) process->>Executor: spin() loop until shutdown + Executor->>tracetools: TP(?) + Note over Executor: get_next_executable() Note over Executor: execute_any_executable() Note over Executor: execute_*() @@ -136,9 +157,11 @@ sequenceDiagram ### Subscription callbacks -For subscriptions, callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. Subscriptions are handled in the `rclcpp` layer. +Subscriptions are handled in the `rclcpp` layer. Callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. -In `execute_*subscription()`, the `Executor` allocates a message and calls `rcl_take()`. If that is successful, it then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. Finally, this calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object, which calls the actual `std::function` with the right signature. +In `execute_*subscription()`, the `Executor` asks the `Subscription` to allocate a message though `Subscription::create_message()`. It then calls `rcl_take*()`. If that is successful, it then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. This checks if it's the right type of subscription (i.e. inter vs. intra process), then it calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object with the message (cast to the actual type). This calls the actual `std::function` with the right signature. + +Finally, it returns the message object through `Subscription::return_message()`. ```mermaid sequenceDiagram @@ -146,10 +169,21 @@ sequenceDiagram participant Subscription participant AnySubscriptionCallback participant rcl + participant rmw + participant tracetools Note over Executor: execute_subscription() - Executor->>rcl: rcl_take() - Executor->>Subscription: handle_message() - Subscription->>AnySubscriptionCallback: dispatch() - Note over AnySubscriptionCallback: std::function::operator(...) + Executor->>Subscription: create_message(): std::shared_ptr + Executor->>rcl: rcl_take*(rcl_subscription_t, &msg) : ret + rcl->>rmw: rmw_take_with_info(rmw_subscription_t, out msg, out taken) + Note over rmw: copies available message to msg if there is one + opt RCL_RET_OK == ret + Executor->>Subscription: handle_message(msg) + Note over Subscription: makes sure it's the right type (intra/inter process), then casts the message to its actual type + Subscription->>AnySubscriptionCallback: dispatch(msg) + AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) + Note over AnySubscriptionCallback: std::function::operator(...) + AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_end, this) + end + Executor->>Subscription: return_message(msg) ``` From e0e6c4b1af3671c3e2d8c3f34c3836b3859e0cb7 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 11:18:43 +0200 Subject: [PATCH 032/132] Change note about message cast --- doc/ros_2.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index 8f889df..f4c5cfc 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -179,8 +179,8 @@ sequenceDiagram Note over rmw: copies available message to msg if there is one opt RCL_RET_OK == ret Executor->>Subscription: handle_message(msg) - Note over Subscription: makes sure it's the right type (intra/inter process), then casts the message to its actual type - Subscription->>AnySubscriptionCallback: dispatch(msg) + Note over Subscription: casts msgs to its actual type + Subscription->>AnySubscriptionCallback: dispatch(typed_msg) AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) Note over AnySubscriptionCallback: std::function::operator(...) AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_end, this) From 56ee174ef19e00d4a09732ade94ab4641a03994b Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 11:47:50 +0200 Subject: [PATCH 033/132] Explicitly disable tracepoints on Windows --- tracetools/src/tracetools.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 6267463..a89cc77 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -1,6 +1,6 @@ #include "tracetools/tracetools.h" -#ifdef WITH_LTTNG +#if defined(WITH_LTTNG) && !defined(_WIN32) # include "tp_call.h" # define CONDITIONAL_TP(...) \ tracepoint(__VA_ARGS__) @@ -11,7 +11,7 @@ bool ros_trace_compile_status() { -#ifdef WITH_LTTNG +#if defined(WITH_LTTNG) && !defined(_WIN32) return true; #else return false; From 1c462f5916be3f41bd48b1146d0c39e3f5c643a3 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 14:45:46 +0200 Subject: [PATCH 034/132] Add first version of 'message publishing' section --- doc/ros_2.md | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/doc/ros_2.md b/doc/ros_2.md index f4c5cfc..fc287aa 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -187,3 +187,24 @@ sequenceDiagram end Executor->>Subscription: return_message(msg) ``` + +### Message publishing + +To publish a message, an object is first allocated and then populated by the `Component` (or equivalent). Then, the message is sent to the `Publisher` through `publish()`. This then passes that on to `rcl`, which itself passes it to `rmw`. + +TODO add inter- vs. intra-process execution flow +TODO talk about IntraProcessManager stuff? + +```mermaid +sequenceDiagram + participant Component + participant Publisher + participant rcl + participant tracetools + + Note over Component: creates a msg + Component->>Publisher: publish(msg) + Note over Publisher: ... + Publisher->>rcl: rcl_publish(rcl_publisher_t, msg) + rcl->>rmw: rmw_publisher(rmw_publisher, msg) +``` From f53b52c682a0168ec5e82ce5e47cd56a270d2fbc Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 14:50:27 +0200 Subject: [PATCH 035/132] Fix type annotations for pointer types --- doc/ros_2.md | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index fc287aa..318719b 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -32,7 +32,7 @@ sequenceDiagram rclcpp->>rcl: rcl_init(out context) Note over rcl: validates & processes context object - rcl->>tracetools: TP(rcl_init, context) + rcl->>tracetools: TP(rcl_init, &context) ``` ### Note/component creation @@ -63,7 +63,7 @@ sequenceDiagram rcl->>rmw: rmw_create_node() : rmw_node_t Note over rmw: creates rmw_node_t handle - rcl->>tracetools: TP(rcl_node_init, &rcl_node_t, &rmw_node_t, node_name, namespace) + rcl->>tracetools: TP(rcl_node_init, rcl_node_t *, rmw_node_t *, node_name, namespace) ``` ### Publisher creation @@ -89,7 +89,7 @@ sequenceDiagram rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name) : rmw_publisher_t Note over rmw: creates rmw_publisher_t handle - rcl->>tracetools: TP(rcl_publisher_init, &rcl_node_t, &rmw_node_t, &rcl_publisher_t, topic_name) + rcl->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name) opt is intra process rclcpp->>rcl: rcl_publisher_init(...) @@ -121,11 +121,13 @@ sequenceDiagram rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name) : rmw_subscription_t Note over rmw: creates rmw_subscription_t handle - rcl->>tracetools: TP(rcl_subscription_init, &rcl_node_t, &rmw_node_t, &rcl_subscription_t, topic_name) + rcl->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name) opt is intra process rclcpp->>rcl: rcl_subscription_init(...) end + + rclcpp->>tracetools: TP(rclcpp_subscription_callback_added, rcl_subscription_t *, &any_callback) ``` ### Executors @@ -174,7 +176,7 @@ sequenceDiagram Note over Executor: execute_subscription() Executor->>Subscription: create_message(): std::shared_ptr - Executor->>rcl: rcl_take*(rcl_subscription_t, &msg) : ret + Executor->>rcl: rcl_take*(rcl_subscription_t, out msg) : ret rcl->>rmw: rmw_take_with_info(rmw_subscription_t, out msg, out taken) Note over rmw: copies available message to msg if there is one opt RCL_RET_OK == ret @@ -200,6 +202,7 @@ sequenceDiagram participant Component participant Publisher participant rcl + participant rmw participant tracetools Note over Component: creates a msg From 5ee44035d43f5bed44cee1221bbf3871a4296046 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:19:11 +0200 Subject: [PATCH 036/132] Add depth field to rcl_publisher_init tracepoint --- tracetools/include/tracetools/tracetools.h | 3 ++- tracetools/lttng/tp_call.tp | 4 +++- tracetools/src/tracetools.c | 5 +++-- 3 files changed, 8 insertions(+), 4 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 056fa52..1f363eb 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -43,7 +43,8 @@ void TRACEPOINT( const void * node_handle, const void * rmw_handle, const void * publisher_handle, - const char * topic_name); + const char * topic_name, + const size_t depth); /** * tp: rcl_subscription_init diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 853cf0d..9bdc7a7 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -35,13 +35,15 @@ TRACEPOINT_EVENT( const void *, node_handle_arg, const void *, rmw_handle_arg, const void *, publisher_handle_arg, - const char *, topic_name_arg + const char *, topic_name_arg, + const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) ctf_string(topic_name, topic_name_arg) + ctf_integer(const size_t, depth, depth_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index a89cc77..13ea3ee 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -40,9 +40,10 @@ void TRACEPOINT( const void * node_handle, const void * rmw_handle, const void * publisher_handle, - const char * topic_name) + const char * topic_name, + const size_t depth) { - CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, rmw_handle, publisher_handle, topic_name); + CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, rmw_handle, publisher_handle, topic_name, depth); } void TRACEPOINT( From 31e971beeff961e0d7578205a9b303e7a363a89e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:37:33 +0200 Subject: [PATCH 037/132] Add detailed information about important parameters for pub & sub sections --- doc/ros_2.md | 36 ++++++++++++++++++++++-------------- 1 file changed, 22 insertions(+), 14 deletions(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index 318719b..9bf1f18 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -76,23 +76,27 @@ If intra-process publishing/subscription is enabled, it will be set up after cre sequenceDiagram participant Component participant rclcpp + participant Publisher participant rcl participant rmw participant tracetools Note over rmw: (implementation) - Component->>rclcpp: create_publisher() - Note over rclcpp: allocates rcl_publisher_t handle - rclcpp->>rcl: rcl_publisher_init(out rcl_publisher_t, rcl_node_t, topic_name) + Component->>rclcpp: create_publisher(topic_name, options, use_intra_process) + Note over rclcpp: (...) + rclcpp->>Publisher: Publisher(topic_name, options) + Note over Publisher: allocates rcl_publisher_t handle + Publisher->>rcl: rcl_publisher_init(out rcl_publisher_t, rcl_node_t, topic_name, options) Note over rcl: populates rcl_publisher_t - rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name) : rmw_publisher_t + rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name, qos_options) : rmw_publisher_t Note over rmw: creates rmw_publisher_t handle - rcl->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name) + rcl->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name, depth) - opt is intra process - rclcpp->>rcl: rcl_publisher_init(...) + opt use_intra_process + rclcpp->>Publisher: setup_intra_process() + Publisher->>rcl: rcl_publisher_init(...) end ``` @@ -102,29 +106,33 @@ Subscription creation is done in a very similar manner. The componenent calls `create_publisher()`, which ends up creating an `rclcpp::Subscription` object which extends `rclcpp::SubscriptionBase`. The latter allocates an `rcl_subscription_t` handle, fetches its `rcl_node_t` handle, and calls `rcl_subscription_init()` in its constructor. `rcl` does topic name expansion/remapping/validation. It creates an `rmw_subscription_t` handle by calling `rmw_create_subscription()` of the given `rmw` implementation and associates it with the node's `rmw_node_t` handle and the subscription's `rcl_subscription_t` handle. -If intra-process publishing/subscription is enabled, it will be set up after creating the subscription object, through a call to `Subscription::setup_intra_process()`, which calls `rcl_subscription_init()`. +If intra-process publishing/subscription is enabled, it will be set up after creating the subscription object, through a call to `Subscription::setup_intra_process()`, which calls `rcl_subscription_init()`. This is very similar to a normal (inter-process) subscription, but it sets some flags for later. ```mermaid sequenceDiagram participant Component participant rclcpp + participant Subscription participant rcl participant rmw participant tracetools Note over rmw: (implementation) - Component->>rclcpp: create_subscription() - Note over rclcpp: allocates rcl_subscription_t handle - rclcpp->>rcl: rcl_subscription_init(out rcl_subscription_t, rcl_node_t, topic_name) + Component->>rclcpp: create_subscription(topic_name, callback, options, use_intra_process) + Note over rclcpp: (...) + rclcpp->>Subscription: Subscription(topic_name, callback, options) + Note over Subscription: allocates rcl_subscription_t handle + Subscription->>rcl: rcl_subscription_init(out rcl_subscription_t, rcl_node_t, topic_name, options) Note over rcl: populates rcl_subscription_t - rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name) : rmw_subscription_t + rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name, qos_options) : rmw_subscription_t Note over rmw: creates rmw_subscription_t handle rcl->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name) - opt is intra process - rclcpp->>rcl: rcl_subscription_init(...) + opt use_intra_process + rclcpp->>Subscription: setup_intra_process() + Subscription->>rcl: rcl_subscription_init(...) end rclcpp->>tracetools: TP(rclcpp_subscription_callback_added, rcl_subscription_t *, &any_callback) From 60adb3f665f4ed095b53eabcfc50d1f8b37ceae2 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:41:15 +0200 Subject: [PATCH 038/132] Fix word --- doc/ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index 9bf1f18..f9fda8e 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -189,7 +189,7 @@ sequenceDiagram Note over rmw: copies available message to msg if there is one opt RCL_RET_OK == ret Executor->>Subscription: handle_message(msg) - Note over Subscription: casts msgs to its actual type + Note over Subscription: casts msg to its actual type Subscription->>AnySubscriptionCallback: dispatch(typed_msg) AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) Note over AnySubscriptionCallback: std::function::operator(...) From d1b2d68e454a8aa1c7a02d2106e9f1623e519552 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:45:50 +0200 Subject: [PATCH 039/132] Re-phrase first sentence --- doc/ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/ros_2.md b/doc/ros_2.md index f9fda8e..923f293 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -1,6 +1,6 @@ # ROS 2 design notes for instrumentation -The goal is to document ROS 2's design/architecture in order to properly design the instrumentation for it. +The goal is to document ROS 2's design/architecture through descriptions of the main execution flows in order to properly design the instrumentation for it. ## Notes on client libraries From cac9b767d178e20d308d95ad2d550ff9e7a1a83e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:47:26 +0200 Subject: [PATCH 040/132] Add empty sub-sections for future work --- doc/ros_2.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/doc/ros_2.md b/doc/ros_2.md index 923f293..b912124 100644 --- a/doc/ros_2.md +++ b/doc/ros_2.md @@ -219,3 +219,11 @@ sequenceDiagram Publisher->>rcl: rcl_publish(rcl_publisher_t, msg) rcl->>rmw: rmw_publisher(rmw_publisher, msg) ``` + +### Service creation + +### Timer creation + +### Service callbacks + +### Timer callbacks From 29cdad21f79f2e389137519d93110b45d3dcccd4 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 15:50:43 +0200 Subject: [PATCH 041/132] Rename doc files to better reflect their content --- doc/{ros_2.md => design_ros_2.md} | 0 design.md => doc/plan.md | 2 +- 2 files changed, 1 insertion(+), 1 deletion(-) rename doc/{ros_2.md => design_ros_2.md} (100%) rename design.md => doc/plan.md (99%) diff --git a/doc/ros_2.md b/doc/design_ros_2.md similarity index 100% rename from doc/ros_2.md rename to doc/design_ros_2.md diff --git a/design.md b/doc/plan.md similarity index 99% rename from design.md rename to doc/plan.md index d442f57..febdcde 100644 --- a/design.md +++ b/doc/plan.md @@ -1,4 +1,4 @@ -# Design +# Plan Plan for ROS 2 tracing & analysis effort. From 77ba2e1fc4c3408e1b47703e5acc94763a1206b3 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:12:56 +0200 Subject: [PATCH 042/132] Add more details about rmw --- doc/design_ros_2.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index b912124..c333d05 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -25,12 +25,14 @@ sequenceDiagram participant process participant rclcpp participant rcl + participant rmw participant tracetools process->>rclcpp: rclcpp::init() Note over rclcpp: allocates
rclcpp::Context object rclcpp->>rcl: rcl_init(out context) Note over rcl: validates & processes context object + rcl->>rmw: rmw_init(out rmw_context_t) rcl->>tracetools: TP(rcl_init, &context) ``` @@ -55,12 +57,12 @@ sequenceDiagram Note over rmw: (implementation) process->>Component: Component() - Component->>rclcpp: : Node() + Component->>rclcpp: : Node(node_name, namespace) Note over rclcpp: allocates rcl_node_t handle rclcpp->>rcl: rcl_node_init(out rcl_node_t, node_name, namespace) Note over rcl: validates node name/namespace Note over rcl: populates rcl_note_t - rcl->>rmw: rmw_create_node() : rmw_node_t + rcl->>rmw: rmw_create_node(node_name, local_namespace) : rmw_node_t Note over rmw: creates rmw_node_t handle rcl->>tracetools: TP(rcl_node_init, rcl_node_t *, rmw_node_t *, node_name, namespace) From 19f64b4658d9446b52b7805fef930322791726dc Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:13:27 +0200 Subject: [PATCH 043/132] Remove
test --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index c333d05..20c8223 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -29,7 +29,7 @@ sequenceDiagram participant tracetools process->>rclcpp: rclcpp::init() - Note over rclcpp: allocates
rclcpp::Context object + Note over rclcpp: allocates rclcpp::Context object rclcpp->>rcl: rcl_init(out context) Note over rcl: validates & processes context object rcl->>rmw: rmw_init(out rmw_context_t) From 5d3ba8720e347e761e7a1b3b37d09af592cf918b Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:34:25 +0200 Subject: [PATCH 044/132] Extract Context from rclcpp participant and add more details about context handles --- doc/design_ros_2.md | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 20c8223..37a67b0 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -16,7 +16,7 @@ This document will (for now) mainly discuss `rcl` and `rclcpp`, but `rclpy` shou ### Process creation -In the call to `rclcpp::init(argc, argv)`, an `rclcpp::Context` object is created and CLI arguments are parsed. Much of the work is actually done by `rcl` through a call to `rcl_init()`. +In the call to `rclcpp::init()`, a process-specific `rclcpp::Context` object is fetched and CLI arguments are parsed. Much of the work is actually done by `rcl` through a call to `rcl_init()`. This call processes the `rcl_context_t` handle, which is wrapped by the `Context` object. Also, inside this call, `rcl` calls `rmw_init()` to process the `rmw` context (`rmw_context_t`) as well. This `rmw` handle is itself part of the `rcl_context_t` handle. This has to be done once per process, and usually at the very beginning. The components that are then instanciated share this context. @@ -24,15 +24,19 @@ This has to be done once per process, and usually at the very beginning. The com sequenceDiagram participant process participant rclcpp + participant Context participant rcl participant rmw participant tracetools - process->>rclcpp: rclcpp::init() - Note over rclcpp: allocates rclcpp::Context object - rclcpp->>rcl: rcl_init(out context) - Note over rcl: validates & processes context object + process->>rclcpp: rclcpp::init(argc, argv) + Note over rclcpp: fetches process-specific Context object + rclcpp->>Context: init(argc, argv) + Note over Context: allocates rcl_context_t handle + Context->>rcl: rcl_init(out rcl_context_t) + Note over rcl: validates & processes rcl_context_t handle rcl->>rmw: rmw_init(out rmw_context_t) + Note over rmw: validates & processes rmw_context_t handle rcl->>tracetools: TP(rcl_init, &context) ``` From ce6ea9d65dae6f8eb5e4a21d3739662a26589d73 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:34:47 +0200 Subject: [PATCH 045/132] Fix typo --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 37a67b0..74dee31 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -41,7 +41,7 @@ sequenceDiagram rcl->>tracetools: TP(rcl_init, &context) ``` -### Note/component creation +### Node/component creation In ROS 2, a process can contain multiple nodes. These are sometimes referred to as "components." From 52e88fbe1e0e87bcbce92c5ba2f7c8f7c70f5faa Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:47:53 +0200 Subject: [PATCH 046/132] Add depth to rcl_subscription_init tracepoint call --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 74dee31..d49f8a4 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -134,7 +134,7 @@ sequenceDiagram rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name, qos_options) : rmw_subscription_t Note over rmw: creates rmw_subscription_t handle - rcl->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name) + rcl->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name, depth) opt use_intra_process rclcpp->>Subscription: setup_intra_process() From eac0db07f8a501f6761e9984b0fd703013c21f05 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 27 May 2019 16:48:45 +0200 Subject: [PATCH 047/132] Add history depth to rcl_subscription_init tracepoint --- tracetools/include/tracetools/tracetools.h | 3 ++- tracetools/lttng/tp_call.tp | 4 +++- tracetools/src/tracetools.c | 5 +++-- 3 files changed, 8 insertions(+), 4 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 1f363eb..439f520 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -54,7 +54,8 @@ void TRACEPOINT( const void * node_handle, const void * rmw_handle, const void * subscription_handle, - const char * topic_name); + const char * topic_name, + const size_t depth); /** * tp: rclcpp_subscription_callback_added diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 9bdc7a7..882b290 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -54,13 +54,15 @@ TRACEPOINT_EVENT( const void *, node_handle_arg, const void *, rmw_handle_arg, const void *, subscription_handle_arg, - const char *, topic_name_arg + const char *, topic_name_arg, + const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_string(topic_name, topic_name_arg) + ctf_integer(const size_t, depth, depth_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 13ea3ee..c2d1aa5 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -51,9 +51,10 @@ void TRACEPOINT( const void * node_handle, const void * rmw_handle, const void * subscription_handle, - const char * topic_name) + const char * topic_name, + const size_t depth) { - CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, rmw_handle, subscription_handle, topic_name); + CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, rmw_handle, subscription_handle, topic_name, depth); } void TRACEPOINT( From 27fba12503203164e286f68eb06bfa887861964a Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 08:44:31 +0200 Subject: [PATCH 048/132] Use dotted lines for tracepoint calls --- doc/design_ros_2.md | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index d49f8a4..35ed76d 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -38,7 +38,7 @@ sequenceDiagram rcl->>rmw: rmw_init(out rmw_context_t) Note over rmw: validates & processes rmw_context_t handle - rcl->>tracetools: TP(rcl_init, &context) + rcl-->>tracetools: TP(rcl_init, &context) ``` ### Node/component creation @@ -69,7 +69,7 @@ sequenceDiagram rcl->>rmw: rmw_create_node(node_name, local_namespace) : rmw_node_t Note over rmw: creates rmw_node_t handle - rcl->>tracetools: TP(rcl_node_init, rcl_node_t *, rmw_node_t *, node_name, namespace) + rcl-->>tracetools: TP(rcl_node_init, rcl_node_t *, rmw_node_t *, node_name, namespace) ``` ### Publisher creation @@ -98,7 +98,7 @@ sequenceDiagram rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name, qos_options) : rmw_publisher_t Note over rmw: creates rmw_publisher_t handle - rcl->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name, depth) + rcl-->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name, depth) opt use_intra_process rclcpp->>Publisher: setup_intra_process() @@ -134,14 +134,14 @@ sequenceDiagram rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name, qos_options) : rmw_subscription_t Note over rmw: creates rmw_subscription_t handle - rcl->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name, depth) + rcl-->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name, depth) opt use_intra_process rclcpp->>Subscription: setup_intra_process() Subscription->>rcl: rcl_subscription_init(...) end - rclcpp->>tracetools: TP(rclcpp_subscription_callback_added, rcl_subscription_t *, &any_callback) + rclcpp-->>tracetools: TP(rclcpp_subscription_callback_added, rcl_subscription_t *, &any_callback) ``` ### Executors @@ -163,7 +163,7 @@ sequenceDiagram process->>Executor: add_node(component) process->>Executor: spin() loop until shutdown - Executor->>tracetools: TP(?) + Executor-->>tracetools: TP(?) Note over Executor: get_next_executable() Note over Executor: execute_any_executable() @@ -197,9 +197,9 @@ sequenceDiagram Executor->>Subscription: handle_message(msg) Note over Subscription: casts msg to its actual type Subscription->>AnySubscriptionCallback: dispatch(typed_msg) - AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) + AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) Note over AnySubscriptionCallback: std::function::operator(...) - AnySubscriptionCallback->>tracetools: TP(rclcpp_subscription_callback_end, this) + AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_end, this) end Executor->>Subscription: return_message(msg) ``` From 717bf93c1575ef362cc2fa12437b4109e23b9791 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 08:50:23 +0200 Subject: [PATCH 049/132] Fix type of context param in rcl_init tracepoint call --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 35ed76d..134a831 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -38,7 +38,7 @@ sequenceDiagram rcl->>rmw: rmw_init(out rmw_context_t) Note over rmw: validates & processes rmw_context_t handle - rcl-->>tracetools: TP(rcl_init, &context) + rcl-->>tracetools: TP(rcl_init, rcl_context_t *) ``` ### Node/component creation From 98f590959830a672b8272e0b037b0cebc0b7657c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 08:54:47 +0200 Subject: [PATCH 050/132] Add notes about rmw implementations and fix call to rmw --- doc/design_ros_2.md | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 134a831..7919487 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -29,6 +29,8 @@ sequenceDiagram participant rmw participant tracetools + Note over rmw: (implementation) + process->>rclcpp: rclcpp::init(argc, argv) Note over rclcpp: fetches process-specific Context object rclcpp->>Context: init(argc, argv) @@ -188,6 +190,8 @@ sequenceDiagram participant rmw participant tracetools + Note over rmw: (implementation) + Note over Executor: execute_subscription() Executor->>Subscription: create_message(): std::shared_ptr Executor->>rcl: rcl_take*(rcl_subscription_t, out msg) : ret @@ -219,11 +223,13 @@ sequenceDiagram participant rmw participant tracetools + Note over rmw: (implementation) + Note over Component: creates a msg Component->>Publisher: publish(msg) Note over Publisher: ... Publisher->>rcl: rcl_publish(rcl_publisher_t, msg) - rcl->>rmw: rmw_publisher(rmw_publisher, msg) + rcl->>rmw: rmw_publish(rmw_publisher_t, msg) ``` ### Service creation From 6bbb9d1816e3c60a30ad93009cf09ba300758085 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 08:57:42 +0200 Subject: [PATCH 051/132] Remove mention of operator() for std::function call --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 7919487..db7a42f 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -202,7 +202,7 @@ sequenceDiagram Note over Subscription: casts msg to its actual type Subscription->>AnySubscriptionCallback: dispatch(typed_msg) AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) - Note over AnySubscriptionCallback: std::function::operator(...) + Note over AnySubscriptionCallback: std::function(...) AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_end, this) end Executor->>Subscription: return_message(msg) From 968928f571f96920494f7c9688a495229791b489 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 10:04:38 +0200 Subject: [PATCH 052/132] Add prospective publishing-related tracepoint in design --- doc/design_ros_2.md | 1 + 1 file changed, 1 insertion(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index db7a42f..f1c6502 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -230,6 +230,7 @@ sequenceDiagram Note over Publisher: ... Publisher->>rcl: rcl_publish(rcl_publisher_t, msg) rcl->>rmw: rmw_publish(rmw_publisher_t, msg) + rmw-->>tracetools: TP(?) ``` ### Service creation From 694817d8458bb94d39f3a2493a0a199a62d90aab Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 10:45:20 +0200 Subject: [PATCH 053/132] Add service creation and callback flow descriptions --- doc/design_ros_2.md | 65 +++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 63 insertions(+), 2 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index f1c6502..b0b8bef 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -177,7 +177,7 @@ sequenceDiagram Subscriptions are handled in the `rclcpp` layer. Callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. -In `execute_*subscription()`, the `Executor` asks the `Subscription` to allocate a message though `Subscription::create_message()`. It then calls `rcl_take*()`. If that is successful, it then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. This checks if it's the right type of subscription (i.e. inter vs. intra process), then it calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object with the message (cast to the actual type). This calls the actual `std::function` with the right signature. +In `execute_*subscription()`, the `Executor` asks the `Subscription` to allocate a message though `Subscription::create_message()`. It then calls `rcl_take*()`, which calls `rmw_take_with_info()`. If that is successful, the `Executor` then passes that on to the subscription through `rclcpp::SubscriptionBase::handle_message()`. This checks if it's the right type of subscription (i.e. inter vs. intra process), then it calls `dispatch()` on the `rclcpp::AnySubscriptionCallback` object with the message (cast to the actual type). This calls the actual `std::function` with the right signature. Finally, it returns the message object through `Subscription::return_message()`. @@ -235,8 +235,69 @@ sequenceDiagram ### Service creation -### Timer creation +Service server creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::Service`. In its constructor, it allocates a `rcl_service_t` handle, then calls `rcl_service_init()`. This processes the handle and validates the service name. It calls `rmw_create_service()` to get the corresponding `rmw_service_t` handle. + +```mermaid +sequenceDiagram + participant Component + participant rclcpp + participant Service + participant rcl + participant rmw + participant tracetools + + Note over rmw: (implementation) + + Component->>rclcpp: create_service(service_name, callback) + Note over rclcpp: (...) + rclcpp->>Service: Service(rcl_node_t, service_name, callback, options) + Note over Service: allocates a rcl_service_t handle + Service->>rcl: rcl_service_init(out rcl_service_t, rcl_node_t, service_name, options) + Note over rcl: validates & processes service handle + rcl->>rmw: rmw_create_service(rmw_node_t, service_name, qos_options) : rmw_service_t + Note over rmw: creates rmw_service_t handle + rcl-->>tracetools: TP(rcl_service_init, rcl_node_t *, rmw_node_t *, rcl_service_t *, service_name) + Service->>tracetools: TP(rclcpp_service_callback_added, rcl_service_t *, &any_callback) +``` ### Service callbacks +Service callbacks are similar to subscription callbacks. In `execute_service()`, the `Executor` allocates request header and request objects. It then calls `rcl_take_request()` and passes them along with the service handle. + +`rcl` calls `rmw_take_request()`. If those are successful, then the `Executor` calls `handle_request()` on the `Service`. This casts the request to its actual type, allocates a response object, and calls `dispatch()` on its `AnyServiceCallback` object, which calls the actual `std::function` with the right signature. + +For the service response, `Service` calls `rcl_send_response()` which calls `rmw_send_response()`. + +```mermaid +sequenceDiagram + participant Executor + participant Service + participant AnyServiceCallback + participant rcl + participant rmw + participant tracetools + + Note over rmw: (implementation) + + Note over Executor: execute_service() + Noter over Executor: allocates request header and request + Executor->>rcl: rcl_take_request(rcl_service, out request_header, out request) : ret + rcl->>rmw: rmw_take_request(rmw_service_t, out request_header, out request, out taken) + opt RCL_RET_OK == ret + Executor->>Service: handle_request(request_header, request) + Note over Service: casts request to its actual type + Note over Service: allocates a response object + Service->>AnyServiceCallback: dispatch(request_header, typed_request, response) + AnyServiceCallback-->>tracetools: TP(rclcpp_service_callback_start, this) + Note over AnyServiceCallback: std::function(...) + AnyServiceCallback-->>tracetools: TP(rclcpp_service_callback_end, this) + Service->>rcl: rcl_send_response(rcl_service_t, request_header, response) + rcl->>rmw: rmw_send_response(rmw_service_t, request_header, response) + end +``` + +### Client creation + +### Timer creation + ### Timer callbacks From f93d40e0ce112de5d88cca91e8bfd48c06f11d67 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 11:55:03 +0200 Subject: [PATCH 054/132] Add timer creation and callback flow descriptions --- doc/design_ros_2.md | 44 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index b0b8bef..63ed3a4 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -300,4 +300,48 @@ sequenceDiagram ### Timer creation +Timer creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::WallTimer`. In its constructor, it creates a `rclcpp::Clock` object, which (for a `WallTimer`) is simply a nanosecond clock. It then allocates a `rcl_timer_t` handle, then calls `rcl_timer_init()`. This processes the handle and validates the period. + +Note that `rcl_timer_init()` can take a callback as a parameter, but right now that feature is not used anywhere (`nullptr` is given), and callbacks are instead handled in the `rclcpp` layer. + +```mermaid +sequenceDiagram + participant Component + participant Node + participant WallTimer + participant rcl + participant tracetools + + Component->>Node: create_wall_timer(period, callback) + Node->>WallTimer: WallTimer(period, callback, Context) + Note over WallTimer: creates a Clock object + Note over WallTimer: allocates a rcl_timer_t handle + WallTimer->>rcl: rcl_timer_init(out rcl_timer_t, Clock, rcl_context_t, period) + Note over rcl: validates and processes rcl_timer_t handle + rcl-->>tracetools: TP(rcl_timer_init, rcl_timer_t *, period) + WallTimer-->>tracetools: TP(rclcpp_timer_callback_added, rcl_timer_t *, &callback) +``` + ### Timer callbacks + +Timer callbacks are similar to susbcription callbacks. In `execute_timer()`, the `Executor` calls `execute_callback()` on the `WallTimer`. The timer then calls `rcl_timer_call()` with its `rcl_timer_t` handle and checks if the callback should be called. + +If it that is the case, then the timer will call the actual `std::function`. Depending on the `std::function` that was given when creating the timer, it will either call the callback without any parameters or it will pass a reference of itself. + +```mermaid +sequenceDiagram + participant Executor + participant WallTimer + participant rcl + participant tracetools + + Note over Executor: execute_timer() + Executor->>WallTimer: execute_callback() + WallTimer->>rcl: rcl_timer_call(rcl_timer_t) : ret + Note over rcl: validates and updates timer + opt RCL_RET_TIMER_CANCELED != ret && RCL_RET_OK == ret + WallTimer-->>tracetools: TP(rclcpp_timer_callback_start, this) + Note over WallTimer: std::function(...) + WallTimer-->>tracetools: TP(rclcpp_timer_callback_end, this) + end +``` From 34c4fa563c825425d6eb118c6b36e0b347d78728 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 11:55:27 +0200 Subject: [PATCH 055/132] Fix service callbacks diagram --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 63ed3a4..5dad2aa 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -280,7 +280,7 @@ sequenceDiagram Note over rmw: (implementation) Note over Executor: execute_service() - Noter over Executor: allocates request header and request + Note over Executor: allocates request header and request Executor->>rcl: rcl_take_request(rcl_service, out request_header, out request) : ret rcl->>rmw: rmw_take_request(rmw_service_t, out request_header, out request, out taken) opt RCL_RET_OK == ret From 6e5f24f7d225e4e253e29ab9d8acce813e23ab81 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 12:02:23 +0200 Subject: [PATCH 056/132] Fix arrow line --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 5dad2aa..55d4711 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -257,7 +257,7 @@ sequenceDiagram rcl->>rmw: rmw_create_service(rmw_node_t, service_name, qos_options) : rmw_service_t Note over rmw: creates rmw_service_t handle rcl-->>tracetools: TP(rcl_service_init, rcl_node_t *, rmw_node_t *, rcl_service_t *, service_name) - Service->>tracetools: TP(rclcpp_service_callback_added, rcl_service_t *, &any_callback) + Service-->>tracetools: TP(rclcpp_service_callback_added, rcl_service_t *, &any_callback) ``` ### Service callbacks From ffbca08d022924f131373e1a7c7a9d6e8dd2e7db Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 13:13:53 +0200 Subject: [PATCH 057/132] Add timer-related tracepoints --- tracetools/include/tracetools/tracetools.h | 30 ++++++++++++++ tracetools/lttng/tp_call.tp | 48 ++++++++++++++++++++++ tracetools/src/tracetools.c | 30 ++++++++++++++ 3 files changed, 108 insertions(+) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 439f520..a34db71 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -112,6 +112,36 @@ void TRACEPOINT( rclcpp_service_callback_end, const void * callback); +/** + * tp: rcl_timer_init + */ +void TRACEPOINT( + rcl_timer_init, + const void * timer_handle, + long period); + +/** + * tp: rclcpp_timer_callback_added + */ +void TRACEPOINT( + rclcpp_timer_callback_added, + const void * timer_handle, + const void * callback); + +/** + * tp: rclcpp_timer_callback_start + */ +void TRACEPOINT( + rclcpp_timer_callback_start, + const void * callback); + +/** + * tp: rclcpp_timer_callback_end + */ +void TRACEPOINT( + rclcpp_timer_callback_end, + const void * callback); + #ifdef __cplusplus } #endif diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 882b290..b15534c 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -154,3 +154,51 @@ TRACEPOINT_EVENT( ctf_integer_hex(const void *, callback, callback_arg) ) ) + +TRACEPOINT_EVENT( + ros2, + rcl_timer_init, + TP_ARGS( + const void *, timer_handle_arg, + long, period_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, timer_handle, timer_handle_arg) + ctf_integer(long, period, period_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_added, + TP_ARGS( + const void *, timer_handle_arg, + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, timer_handle, timer_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_start, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_end, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index c2d1aa5..8e79ce3 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -111,3 +111,33 @@ void TRACEPOINT( { CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback); } + +void TRACEPOINT( + rcl_timer_init, + const void * timer_handle, + long period) +{ + CONDITIONAL_TP(ros2, rcl_timer_init, timer_handle, period); +} + +void TRACEPOINT( + rclcpp_timer_callback_added, + const void * timer_handle, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_timer_callback_added, timer_handle, callback); +} + +void TRACEPOINT( + rclcpp_timer_callback_start, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_timer_callback_start, callback); +} + +void TRACEPOINT( + rclcpp_timer_callback_end, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback); +} From d36c3d824cc269c2761a8969b190debb581e90cd Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 14:15:46 +0200 Subject: [PATCH 058/132] Add rcl_client_init tracepoint --- tracetools/include/tracetools/tracetools.h | 10 ++++++++++ tracetools/lttng/tp_call.tp | 17 +++++++++++++++++ tracetools/src/tracetools.c | 10 ++++++++++ 3 files changed, 37 insertions(+) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index a34db71..849c6ae 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -112,6 +112,16 @@ void TRACEPOINT( rclcpp_service_callback_end, const void * callback); +/** + * tp: rcl_client_init + */ +void TRACEPOINT( + rcl_client_init, + const void * node_handle, + const void * client_handle, + const void * rmw_client_handle, + const char * service_name); + /** * tp: rcl_timer_init */ diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index b15534c..232b2c7 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -155,6 +155,23 @@ TRACEPOINT_EVENT( ) ) +TRACEPOINT_EVENT( + ros2, + rcl_client_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, client_handle_arg, + const void *, rmw_client_handle_arg, + const char *, service_name_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, client_handle, client_handle_arg) + ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg) + ctf_string(service_name, service_name_arg) + ) +) + TRACEPOINT_EVENT( ros2, rcl_timer_init, diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 8e79ce3..ee606bb 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -112,6 +112,16 @@ void TRACEPOINT( CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback); } +void TRACEPOINT( + rcl_client_init, + const void * node_handle, + const void * client_handle, + const void * rmw_client_handle, + const char * service_name) +{ + CONDITIONAL_TP(ros2, rcl_client_init, node_handle, client_handle, rmw_client_handle, service_name); +} + void TRACEPOINT( rcl_timer_init, const void * timer_handle, From 3f13dd34d024741995c18defddfa70c05ac79a5d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 14:16:38 +0200 Subject: [PATCH 059/132] Add prospective callback register tracepoint --- tracetools/include/tracetools/tracetools.h | 8 ++++++++ tracetools/lttng/tp_call.tp | 13 +++++++++++++ tracetools/src/tracetools.c | 20 ++++++++++++++++++++ 3 files changed, 41 insertions(+) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 849c6ae..769fc04 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -152,6 +152,14 @@ void TRACEPOINT( rclcpp_timer_callback_end, const void * callback); +/** + * tp: rclcpp_callback_register + */ +void TRACEPOINT( + rclcpp_callback_register, + const void * handle, + const void * callback); + #ifdef __cplusplus } #endif diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 232b2c7..9750000 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -219,3 +219,16 @@ TRACEPOINT_EVENT( ctf_integer_hex(const void *, callback, callback_arg) ) ) + +TRACEPOINT_EVENT( + ros2, + rclcpp_callback_register, + TP_ARGS( + const void *, handle_arg, + const char *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, handle, handle_arg) + ctf_string(callback, callback_arg) + ) +) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index ee606bb..7044c55 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -1,3 +1,4 @@ +#include #include "tracetools/tracetools.h" #if defined(WITH_LTTNG) && !defined(_WIN32) @@ -9,6 +10,17 @@ #endif +const char * get_symbol(const void * function_ptr) { +#if defined(WITH_LTTNG) && !defined(_WIN32) + char** symbols = backtrace_symbols(&function_ptr, 1); + const char * result = symbols[0]; + free(symbols); + return result; +#else + return ""; +#endif +} + bool ros_trace_compile_status() { #if defined(WITH_LTTNG) && !defined(_WIN32) @@ -151,3 +163,11 @@ void TRACEPOINT( { CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback); } + +void TRACEPOINT( + rclcpp_callback_register, + const void * handle, + const void * callback) +{ + CONDITIONAL_TP(ros2, rclcpp_callback_register, handle, get_symbol(callback)); +} From cee1327930b66affa665d17aec7ae496c4026cb5 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 14:57:15 +0200 Subject: [PATCH 060/132] Use relevant rmw handle instead of the rmw_node_t handle for tracepoints --- tracetools/include/tracetools/tracetools.h | 6 +++--- tracetools/lttng/tp_call.tp | 8 ++++---- tracetools/src/tracetools.c | 12 ++++++------ 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 769fc04..fe040a2 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -41,8 +41,8 @@ void TRACEPOINT( void TRACEPOINT( rcl_publisher_init, const void * node_handle, - const void * rmw_handle, const void * publisher_handle, + const void * rmw_publisher_handle, const char * topic_name, const size_t depth); @@ -52,8 +52,8 @@ void TRACEPOINT( void TRACEPOINT( rcl_subscription_init, const void * node_handle, - const void * rmw_handle, const void * subscription_handle, + const void * rmw_subscription_handle, const char * topic_name, const size_t depth); @@ -86,8 +86,8 @@ void TRACEPOINT( void TRACEPOINT( rcl_service_init, const void * node_handle, - const void * rmw_handle, const void * service_handle, + const void * rmw_service_handle, const char * service_name); /** diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 9750000..1a833c9 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -52,15 +52,15 @@ TRACEPOINT_EVENT( rcl_subscription_init, TP_ARGS( const void *, node_handle_arg, - const void *, rmw_handle_arg, const void *, subscription_handle_arg, + const void *, rmw_subscription_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) ) @@ -108,14 +108,14 @@ TRACEPOINT_EVENT( rcl_service_init, TP_ARGS( const void *, node_handle_arg, - const void *, rmw_handle_arg, const void *, service_handle_arg, + const void *, rmw_service_handle_arg, const char *, service_name_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, service_handle, service_handle_arg) + ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg) ctf_string(service_name, service_name_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 7044c55..dea60bc 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -50,23 +50,23 @@ void TRACEPOINT( void TRACEPOINT( rcl_publisher_init, const void * node_handle, - const void * rmw_handle, const void * publisher_handle, + const void * rmw_publisher_handle, const char * topic_name, const size_t depth) { - CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, rmw_handle, publisher_handle, topic_name, depth); + CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, publisher_handle, rmw_publisher_handle, topic_name, depth); } void TRACEPOINT( rcl_subscription_init, const void * node_handle, - const void * rmw_handle, const void * subscription_handle, + const void * rmw_subscription_handle, const char * topic_name, const size_t depth) { - CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, rmw_handle, subscription_handle, topic_name, depth); + CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, subscription_handle, rmw_subscription_handle, topic_name, depth); } void TRACEPOINT( @@ -95,11 +95,11 @@ void TRACEPOINT( void TRACEPOINT( rcl_service_init, const void * node_handle, - const void * rmw_handle, const void * service_handle, + const void * rmw_service_handle, const char * service_name) { - CONDITIONAL_TP(ros2, rcl_service_init, node_handle, rmw_handle, service_handle, service_name); + CONDITIONAL_TP(ros2, rcl_service_init, node_handle, service_handle, rmw_service_handle, service_name); } void TRACEPOINT( From d7a4c7b3866cba6f52719a9714b432edec85b945 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 15:00:51 +0200 Subject: [PATCH 061/132] Add client creation flow description --- doc/design_ros_2.md | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 55d4711..312e2c5 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -298,6 +298,29 @@ sequenceDiagram ### Client creation +Client creation is similar to publisher creation. The `Component` calls `create_client()` which ends up creating a `rclcpp::Client`. In its constructor, it allocates a `rcl_client_t` handle, then calls `rcl_client_init()`. This validates and processes the handle. It also calls `rmw_create_client()` which creates the `rmw_client_t` handle. + +```mermaid +sequenceDiagram + participant Component + participant Node + participant Client + participant rcl + participant rmw + participant tracetools + + Component->>Node: create_client(service_name, options) + Node->>Client: Client(service_name, options) + Note over Client: allocates a rcl_client_t handle + Client->>rcl: rcl_client_init(out rcl_client_t, rcl_node_t, service_name, options) + Note over rcl: validates and processes rcl_client_t handle + rcl->>rmw: rmw_create_client(rmw_node_t, service_name, qos_options) : rmw_client_t + Note over rmw: creates rmw_client_t handle + rcl-->>tracetools: TP(rcl_client_init, rcl_node_t *, rcl_client_t *, rmw_client_t *, service_name) +``` + +### Client request + ### Timer creation Timer creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::WallTimer`. In its constructor, it creates a `rclcpp::Clock` object, which (for a `WallTimer`) is simply a nanosecond clock. It then allocates a `rcl_timer_t` handle, then calls `rcl_timer_init()`. This processes the handle and validates the period. From 8354fba3439cae4c5372197b437fc4ac0b70cd4c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 15:06:19 +0200 Subject: [PATCH 062/132] Fix rmw handles in flow descriptions --- doc/design_ros_2.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 312e2c5..d758487 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -100,7 +100,7 @@ sequenceDiagram rcl->>rmw: rmw_create_publisher(rmw_node_t, topic_name, qos_options) : rmw_publisher_t Note over rmw: creates rmw_publisher_t handle - rcl-->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rmw_node_t *, rcl_publisher_t *, topic_name, depth) + rcl-->>tracetools: TP(rcl_publisher_init, rcl_node_t *, rcl_publisher_t *, rmw_publisher_t *, topic_name, depth) opt use_intra_process rclcpp->>Publisher: setup_intra_process() @@ -136,7 +136,7 @@ sequenceDiagram rcl->>rmw: rmw_create_subscription(rmw_node_t, topic_name, qos_options) : rmw_subscription_t Note over rmw: creates rmw_subscription_t handle - rcl-->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rmw_node_t *, rcl_subscription_t *, topic_name, depth) + rcl-->>tracetools: TP(rcl_subscription_init, rcl_node_t *, rcl_subscription_t *, rmw_subscription_t *, topic_name, depth) opt use_intra_process rclcpp->>Subscription: setup_intra_process() @@ -256,7 +256,7 @@ sequenceDiagram Note over rcl: validates & processes service handle rcl->>rmw: rmw_create_service(rmw_node_t, service_name, qos_options) : rmw_service_t Note over rmw: creates rmw_service_t handle - rcl-->>tracetools: TP(rcl_service_init, rcl_node_t *, rmw_node_t *, rcl_service_t *, service_name) + rcl-->>tracetools: TP(rcl_service_init, rcl_node_t *, rcl_service_t *, rmw_service_t *, service_name) Service-->>tracetools: TP(rclcpp_service_callback_added, rcl_service_t *, &any_callback) ``` From 372f0296c0953d19c99d83ae9e2488e4d1456b38 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 28 May 2019 16:35:47 +0200 Subject: [PATCH 063/132] Re-structure callback registration tracepoint --- tracetools/include/tracetools/tracetools.h | 4 ++-- tracetools/lttng/tp_call.tp | 8 ++++---- tracetools/src/tracetools.c | 20 ++++++++++++-------- 3 files changed, 18 insertions(+), 14 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index fe040a2..d00d4dd 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -157,8 +157,8 @@ void TRACEPOINT( */ void TRACEPOINT( rclcpp_callback_register, - const void * handle, - const void * callback); + const void * callback, + const void * function_target); #ifdef __cplusplus } diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp index 1a833c9..4a964cd 100644 --- a/tracetools/lttng/tp_call.tp +++ b/tracetools/lttng/tp_call.tp @@ -224,11 +224,11 @@ TRACEPOINT_EVENT( ros2, rclcpp_callback_register, TP_ARGS( - const void *, handle_arg, - const char *, callback_arg + const void *, callback_arg, + const char *, symbol_arg ), TP_FIELDS( - ctf_integer_hex(const void *, handle, handle_arg) - ctf_string(callback, callback_arg) + ctf_integer_hex(const void *, callback, callback_arg) + ctf_string(symbol, symbol_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index dea60bc..b27f290 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -12,12 +12,16 @@ const char * get_symbol(const void * function_ptr) { #if defined(WITH_LTTNG) && !defined(_WIN32) - char** symbols = backtrace_symbols(&function_ptr, 1); - const char * result = symbols[0]; - free(symbols); - return result; + // If it's actually a lambda + if (NULL == function_ptr) { + return ""; + } + char ** symbols = backtrace_symbols(&function_ptr, 1); + const char * result = symbols[0]; + free(symbols); + return result; #else - return ""; + return ""; #endif } @@ -166,8 +170,8 @@ void TRACEPOINT( void TRACEPOINT( rclcpp_callback_register, - const void * handle, - const void * callback) + const void * callback, + const void * function_target) { - CONDITIONAL_TP(ros2, rclcpp_callback_register, handle, get_symbol(callback)); + CONDITIONAL_TP(ros2, rclcpp_callback_register, callback, get_symbol(function_target)); } From 3ef3570ce5b2fd8455fb41887beb75b594846e3c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 10:05:24 +0200 Subject: [PATCH 064/132] Add client request flow description --- doc/design_ros_2.md | 46 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 46 insertions(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index d758487..22cf9b2 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -321,6 +321,52 @@ sequenceDiagram ### Client request +A client request has multiple steps. The `Component` (or the owner of the `Client`) first creates a request object. It then calls `Client::async_send_request()` with the request. It can also provide a callback, but it's optional. The `Client` passes that on to `rcl` by calling `rcl_send_request()`. `rcl` generates a sequence number and assigns it to the request, then calls `rmw_send_request()`. Once this is done, the `Client` puts this sequence number in an internal map along with the created promise and future objects, and the callback (which might simply be empty). + +At this point, the `Client` could simply let its callback be called. It can also use the future object returned by `async_send_request()`, and call `rclcpp::spin_until_future_complete()`. This waits until the future object is ready, or until timeout, and returns. + +If this last call was successful, then the `Component` can get the result and do something with it. + +```mermaid +sequenceDiagram + participant Component + participant Executor + participant Client + participant rclcpp + participant rcl + participant rmw + participant tracetools + + Note over Component: creates request + Component->>Client: async_send_request(request[, callback]) : result_future + Client->>rcl: rcl_send_request(rcl_client_t, request, out sequence_number) + Note over rcl: assigns sequence_number + rcl-->>tracetools: TP?(rcl_send_request, rcl_client_t *, sequence_number) + rcl->>rmw: rmw_send_request(rmw_client_t, request, sequence_number) + Note over Client: puts sequence_number in a map with promise+callback+future + + Component->>rclcpp: spin_until_future_complete(result_future) : result_status + + Note over Executor: execute_client() + Note over Executor: creates request_header and response objects + Executor->>rcl: rcl_take_response(rcl_client_t, out request_header, out response) : ret + rcl-->>tracetools: TP?() + rcl->>rmw: rmw_take_response(rmw_client_t, out request_header, out response, out taken) + opt RCL_RET_OK == ret + Executor->>Client: handle_response(request_header, response) + Note over Client: gets sequence_number from request_header + Client-->>tracetools: TP?() + Note over Client: gets promise+callback+future from its map + Note over Client: callback(future) + end + + rclcpp->>Component: ready or timeout + opt SUCCESS == result_status + Note over Component: result_future.get() : result + Note over Component: do something with result + end +``` + ### Timer creation Timer creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::WallTimer`. In its constructor, it creates a `rclcpp::Clock` object, which (for a `WallTimer`) is simply a nanosecond clock. It then allocates a `rcl_timer_t` handle, then calls `rcl_timer_init()`. This processes the handle and validates the period. From ebf3270b306a9f162bf1e3b9c3d877e0a05ac027 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 10:10:33 +0200 Subject: [PATCH 065/132] Add rmw implementation notes for client flow diagrams --- doc/design_ros_2.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 22cf9b2..6207ebd 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -309,6 +309,8 @@ sequenceDiagram participant rmw participant tracetools + Note over rmw: (implementation) + Component->>Node: create_client(service_name, options) Node->>Client: Client(service_name, options) Note over Client: allocates a rcl_client_t handle @@ -337,6 +339,8 @@ sequenceDiagram participant rmw participant tracetools + Note over rmw: (implementation) + Note over Component: creates request Component->>Client: async_send_request(request[, callback]) : result_future Client->>rcl: rcl_send_request(rcl_client_t, request, out sequence_number) From d2e827e005774279742dc1e0b7a3780ccc2e16ae Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 10:54:13 +0200 Subject: [PATCH 066/132] Move 'plan' document to main design document --- doc/design_ros_2.md | 77 +++++++++++++++++++++++++++++++++++---------- doc/plan.md | 45 -------------------------- 2 files changed, 61 insertions(+), 61 deletions(-) delete mode 100644 doc/plan.md diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 6207ebd..adce66b 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -1,8 +1,53 @@ -# ROS 2 design notes for instrumentation +# ROS 2 tracing + +Design document for ROS 2 tracing, instrumentation, and analysis effort. + +## Overview + +This general effort will be split into a few distinct steps. + +### Instrumentation + +The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). + +This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. + +The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. + +### Analysis & visualization + +After the initial instrumentation, some general statistics analyses can be built. The targeted analysis & visualization tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: + +* Callback duration +* Time between callbacks (between two callback starts and/or a callback end and a start) +* Message age (as the difference between processing time and message timestamp) +* Message size +* Memory usage +* Execution time/proportion accross a process' nodes/components +* Interruptions (noting that these may be more useful as time-based metrics instead of overall statistics): + * scheduling events during a callback + * delay between the moment a thread becomes ready and when it's actually scheduled + * CPU cycles + +with mean, stdev, etc. when applicable. + +Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. + +### Tools/accessibility + +To make tracing ROS 2 more accessible and easier to adopt, we can put effort into integrating LTTng session setup & recording into the ROS 2 launch system. + +This might include converting existing `tracetools` scripts to more flexible Python scripts, and then plugging that into the launch system. + +### ROS 1/2 compatibility + +Finally, we could look into making analyses work on both ROS 1 and ROS 2, through a common instrumentation interface (or other abstraction). + +## Instrumentation design The goal is to document ROS 2's design/architecture through descriptions of the main execution flows in order to properly design the instrumentation for it. -## Notes on client libraries +### Notes on client libraries ROS 2 has changed the way it deals with client libraries. It offers a base ROS client library (`rcl`) written in C. This client library is the base for any language-specific implementation, such as `rclcpp` and `rclpy`. @@ -12,9 +57,9 @@ This means that some instrumentation work might have to be re-done for every cli This document will (for now) mainly discuss `rcl` and `rclcpp`, but `rclpy` should eventually be added and supported. -## Flow description +### Flow description -### Process creation +#### Process creation In the call to `rclcpp::init()`, a process-specific `rclcpp::Context` object is fetched and CLI arguments are parsed. Much of the work is actually done by `rcl` through a call to `rcl_init()`. This call processes the `rcl_context_t` handle, which is wrapped by the `Context` object. Also, inside this call, `rcl` calls `rmw_init()` to process the `rmw` context (`rmw_context_t`) as well. This `rmw` handle is itself part of the `rcl_context_t` handle. @@ -43,7 +88,7 @@ sequenceDiagram rcl-->>tracetools: TP(rcl_init, rcl_context_t *) ``` -### Node/component creation +#### Node/component creation In ROS 2, a process can contain multiple nodes. These are sometimes referred to as "components." @@ -74,7 +119,7 @@ sequenceDiagram rcl-->>tracetools: TP(rcl_node_init, rcl_node_t *, rmw_node_t *, node_name, namespace) ``` -### Publisher creation +#### Publisher creation The component calls `create_publisher()`, a `rclcpp::Node` method for convenience. That ends up creating an `rclcpp::Publisher` object which extends `rclcpp::PublisherBase`. The latter allocates an `rcl_publisher_t` handle, fetches the corresponding `rcl_node_t` handle, and calls `rcl_publisher_init()` in its constructor. `rcl` does topic name expansion/remapping/validation. It creates an `rmw_publisher_t` handle by calling `rmw_create_publisher()` of the given `rmw` implementation and associates with the node's `rmw_node_t` handle and the publisher's `rcl_publisher_t` handle. @@ -108,7 +153,7 @@ sequenceDiagram end ``` -### Subscription creation +#### Subscription creation Subscription creation is done in a very similar manner. @@ -146,7 +191,7 @@ sequenceDiagram rclcpp-->>tracetools: TP(rclcpp_subscription_callback_added, rcl_subscription_t *, &any_callback) ``` -### Executors +#### Executors An `rclcpp::executor::Executor` object is created for a given process. It can be a `SingleThreadedExecutor` or a `MultiThreadedExecutor`. @@ -173,7 +218,7 @@ sequenceDiagram end ``` -### Subscription callbacks +#### Subscription callbacks Subscriptions are handled in the `rclcpp` layer. Callbacks are wrapped by an `rclcpp::AnySubscriptionCallback` object, which is registered when creating the `rclcpp::Subscription` object. @@ -208,7 +253,7 @@ sequenceDiagram Executor->>Subscription: return_message(msg) ``` -### Message publishing +#### Message publishing To publish a message, an object is first allocated and then populated by the `Component` (or equivalent). Then, the message is sent to the `Publisher` through `publish()`. This then passes that on to `rcl`, which itself passes it to `rmw`. @@ -233,7 +278,7 @@ sequenceDiagram rmw-->>tracetools: TP(?) ``` -### Service creation +#### Service creation Service server creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::Service`. In its constructor, it allocates a `rcl_service_t` handle, then calls `rcl_service_init()`. This processes the handle and validates the service name. It calls `rmw_create_service()` to get the corresponding `rmw_service_t` handle. @@ -260,7 +305,7 @@ sequenceDiagram Service-->>tracetools: TP(rclcpp_service_callback_added, rcl_service_t *, &any_callback) ``` -### Service callbacks +#### Service callbacks Service callbacks are similar to subscription callbacks. In `execute_service()`, the `Executor` allocates request header and request objects. It then calls `rcl_take_request()` and passes them along with the service handle. @@ -296,7 +341,7 @@ sequenceDiagram end ``` -### Client creation +#### Client creation Client creation is similar to publisher creation. The `Component` calls `create_client()` which ends up creating a `rclcpp::Client`. In its constructor, it allocates a `rcl_client_t` handle, then calls `rcl_client_init()`. This validates and processes the handle. It also calls `rmw_create_client()` which creates the `rmw_client_t` handle. @@ -321,7 +366,7 @@ sequenceDiagram rcl-->>tracetools: TP(rcl_client_init, rcl_node_t *, rcl_client_t *, rmw_client_t *, service_name) ``` -### Client request +#### Client request A client request has multiple steps. The `Component` (or the owner of the `Client`) first creates a request object. It then calls `Client::async_send_request()` with the request. It can also provide a callback, but it's optional. The `Client` passes that on to `rcl` by calling `rcl_send_request()`. `rcl` generates a sequence number and assigns it to the request, then calls `rmw_send_request()`. Once this is done, the `Client` puts this sequence number in an internal map along with the created promise and future objects, and the callback (which might simply be empty). @@ -371,7 +416,7 @@ sequenceDiagram end ``` -### Timer creation +#### Timer creation Timer creation is similar to subscription creation. The `Component` calls `create_service()` which ends up creating a `rclcpp::WallTimer`. In its constructor, it creates a `rclcpp::Clock` object, which (for a `WallTimer`) is simply a nanosecond clock. It then allocates a `rcl_timer_t` handle, then calls `rcl_timer_init()`. This processes the handle and validates the period. @@ -395,7 +440,7 @@ sequenceDiagram WallTimer-->>tracetools: TP(rclcpp_timer_callback_added, rcl_timer_t *, &callback) ``` -### Timer callbacks +#### Timer callbacks Timer callbacks are similar to susbcription callbacks. In `execute_timer()`, the `Executor` calls `execute_callback()` on the `WallTimer`. The timer then calls `rcl_timer_call()` with its `rcl_timer_t` handle and checks if the callback should be called. diff --git a/doc/plan.md b/doc/plan.md deleted file mode 100644 index febdcde..0000000 --- a/doc/plan.md +++ /dev/null @@ -1,45 +0,0 @@ -# Plan - -Plan for ROS 2 tracing & analysis effort. - -## Steps - -This general effort will be split into a few distinct steps. - -### Instrumentation - -The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). - -This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. - -The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. - -### Analysis & visualization - -After the initial instrumentation, some general statistics analyses can be built. The targeted analysis & visualization tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: - -* Callback duration -* Time between callbacks (between two callback starts and/or a callback end and a start) -* Message age (as the difference between processing time and message timestamp) -* Message size -* Memory usage -* Execution time/proportion accross a process' nodes/components -* Interruptions (noting that these may be more useful as time-based metrics instead of overall statistics): - * scheduling events during a callback - * delay between the moment a thread becomes ready and when it's actually scheduled - * CPU cycles - -with mean, stdev, etc. when applicable. - -Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. - - -### Tools/accessibility - -To make tracing ROS 2 more accessible and easier to adopt, we can put effort into integrating LTTng session setup & recording into the ROS 2 launch system. - -This might include converting existing `tracetools` scripts to more flexible Python scripts, and then plugging that into the launch system. - -### ROS 1/2 compatibility - -Finally, we could look into making analyses work on both ROS 1 and ROS 2, through a common instrumentation interface (or other abstraction). From f6c98deabc55f56ada843978922529feb45a2e81 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 11:08:15 +0200 Subject: [PATCH 067/132] Re-organize design document --- doc/design_ros_2.md | 50 ++++++++++++++++++++++++--------------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index adce66b..078192d 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -4,17 +4,11 @@ Design document for ROS 2 tracing, instrumentation, and analysis effort. ## Overview -This general effort will be split into a few distinct steps. +### Goal -### Instrumentation +Provide low-overhead tools and resources for robotics software development based on ROS 2. -The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). - -This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. - -The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. - -### Analysis & visualization +### Desired results: analysis & visualization After the initial instrumentation, some general statistics analyses can be built. The targeted analysis & visualization tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: @@ -39,24 +33,10 @@ To make tracing ROS 2 more accessible and easier to adopt, we can put effort int This might include converting existing `tracetools` scripts to more flexible Python scripts, and then plugging that into the launch system. -### ROS 1/2 compatibility - -Finally, we could look into making analyses work on both ROS 1 and ROS 2, through a common instrumentation interface (or other abstraction). - ## Instrumentation design The goal is to document ROS 2's design/architecture through descriptions of the main execution flows in order to properly design the instrumentation for it. -### Notes on client libraries - -ROS 2 has changed the way it deals with client libraries. It offers a base ROS client library (`rcl`) written in C. This client library is the base for any language-specific implementation, such as `rclcpp` and `rclpy`. - -However, `rcl` is obviously fairly basic, and still does leave a fair amount of implementation work up to the client libraries. For example, callbacks are not at all handled in `rcl`, and are left to the client library implementations. - -This means that some instrumentation work might have to be re-done for every client library that we want to trace. We cannot simply instrument `rcl`, nor can we only instrument the base `rmw` interface if we want to dig into that. - -This document will (for now) mainly discuss `rcl` and `rclcpp`, but `rclpy` should eventually be added and supported. - ### Flow description #### Process creation @@ -463,3 +443,27 @@ sequenceDiagram WallTimer-->>tracetools: TP(rclcpp_timer_callback_end, this) end ``` + +## Implementation notes + +### Instrumentation + +The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). + +This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. + +The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. + +### Notes on client libraries + +ROS offer a client library (`rcl`) written in C as the base for any language-specific implementation, such as `rclcpp` and `rclpy`. + +However, `rcl` is obviously fairly basic, and still does leave a fair amount of implementation work up to the client libraries. For example, callbacks are not handled in `rcl`, and are left to the client library implementations. + +This means that some instrumentation work will have to be re-done for every client library that we want to trace. We cannot simply instrument `rcl`, nor can we only instrument the base `rmw` interface if we want to dig into that. + +This effort should first focus on `rcl` and `rclcpp` , but `rclpy` should eventually be added and supported. + +### ROS 1/2 compatibility + +We could look into making analyses work on both ROS 1 and ROS 2, through a common instrumentation interface (or other abstraction). From f8b7338b8be9bb047a149737a75bc32ec473f84f Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 11:10:52 +0200 Subject: [PATCH 068/132] Re-phrase instrumentation design sentence --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 078192d..bf7fa4c 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -35,7 +35,7 @@ This might include converting existing `tracetools` scripts to more flexible Pyt ## Instrumentation design -The goal is to document ROS 2's design/architecture through descriptions of the main execution flows in order to properly design the instrumentation for it. +The goal is to document ROS 2's design/architecture through descriptions of the main execution flows. The instrumentation can then be designed around that. ### Flow description From 8763fbad6cec417f121842ad656962300355c9ad Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 11:15:49 +0200 Subject: [PATCH 069/132] Change 'desired results' to 'requirements' --- doc/design_ros_2.md | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index bf7fa4c..b0ac676 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -8,9 +8,13 @@ Design document for ROS 2 tracing, instrumentation, and analysis effort. Provide low-overhead tools and resources for robotics software development based on ROS 2. -### Desired results: analysis & visualization +### Requirements: instrumentation -After the initial instrumentation, some general statistics analyses can be built. The targeted analysis & visualization tools are pandas and Jupyter. The goal is to make analyses general enough to be useful for different use-cases, e.g.: +TODO + +### Requirements: analysis & visualization + +Analyses should be general enough to be useful for different use-cases, e.g.: * Callback duration * Time between callbacks (between two callback starts and/or a callback end and a start) @@ -25,7 +29,7 @@ After the initial instrumentation, some general statistics analyses can be built with mean, stdev, etc. when applicable. -Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics. +Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics and visualization. ### Tools/accessibility @@ -452,8 +456,12 @@ The first goal is to statically instrument ROS 2, aiming for it to be in the ROS This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. +### Targeted tools/dependencies + The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. +The targeted analysis & visualization tools are pandas and Jupyter. + ### Notes on client libraries ROS offer a client library (`rcl`) written in C as the base for any language-specific implementation, such as `rclcpp` and `rclpy`. From c0ee9ab88e5b4c5ea098e7497604cb10cb737a04 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 15:14:19 +0200 Subject: [PATCH 070/132] Add instrumentation requirements --- doc/design_ros_2.md | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index b0ac676..d4dff32 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -2,7 +2,7 @@ Design document for ROS 2 tracing, instrumentation, and analysis effort. -## Overview +## Goals and requirements ### Goal @@ -10,11 +10,26 @@ Provide low-overhead tools and resources for robotics software development based ### Requirements: instrumentation -TODO +Instrumentation should be built around the main uses of ROS 2, and should include relevant information. + +1. In general + 1. When creating a publisher/subscriber/service/client/etc., appropriate references should be kept in order to correlate with other tracepoints related to the same instance. +1. Publisher & subscription + 1. When creating a publisher/subscription, the effective topic name should be included (i.e. including namespace and after remapping). + 2. When publishing a message, some sort of message identifier should be included in the tracepoint so it can be tracked through DDS up to the subscriber's side. +3. Callbacks (subscription, service, client, timer) + 1. Callback function symbol should be included, whenever possible. + 2. Information about callback execution (e.g. start & end) should be available. +4. Timer + 1. Information about the period should be available. +5. Executors + 1. Information about spin cycles & periods should be available. +6. Others + 1. Provide generic tracepoints for user code. ### Requirements: analysis & visualization -Analyses should be general enough to be useful for different use-cases, e.g.: +Analyses process trace data. They should be general enough to be useful for different use-cases, e.g.: * Callback duration * Time between callbacks (between two callback starts and/or a callback end and a start) @@ -29,7 +44,7 @@ Analyses should be general enough to be useful for different use-cases, e.g.: with mean, stdev, etc. when applicable. -Generic tracepoints should also be provided for ROS 2 user code, which could then be applied to a user-provided model for higher-level behaviour statistics and visualization. +Generic tracepoints for ROS 2 user code could be applied to a user-provided model for higher-level behaviour statistics and visualization. ### Tools/accessibility From 78ef1e1f7e6e84721ad8f1a45e81213e973ecae2 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 15:16:23 +0200 Subject: [PATCH 071/132] Make instrumentation requirements list more consistent --- doc/design_ros_2.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index d4dff32..a3d9e10 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -12,15 +12,15 @@ Provide low-overhead tools and resources for robotics software development based Instrumentation should be built around the main uses of ROS 2, and should include relevant information. -1. In general +1. Overall 1. When creating a publisher/subscriber/service/client/etc., appropriate references should be kept in order to correlate with other tracepoints related to the same instance. -1. Publisher & subscription +1. Publishers & subscriptions 1. When creating a publisher/subscription, the effective topic name should be included (i.e. including namespace and after remapping). 2. When publishing a message, some sort of message identifier should be included in the tracepoint so it can be tracked through DDS up to the subscriber's side. 3. Callbacks (subscription, service, client, timer) 1. Callback function symbol should be included, whenever possible. 2. Information about callback execution (e.g. start & end) should be available. -4. Timer +4. Timers 1. Information about the period should be available. 5. Executors 1. Information about spin cycles & periods should be available. From 38fbd075f6ac461d086c51432212f3e66fba927c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 15:21:49 +0200 Subject: [PATCH 072/132] Re-phrase instrumentation design opening --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index a3d9e10..a2d6732 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -54,7 +54,7 @@ This might include converting existing `tracetools` scripts to more flexible Pyt ## Instrumentation design -The goal is to document ROS 2's design/architecture through descriptions of the main execution flows. The instrumentation can then be designed around that. +This section includes information about ROS 2's design & architecture through descriptions of the main execution flows. The instrumentation can then be built around that. ### Flow description From 36b4e207dd6903a088cdd2e94dec91c240b7773d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 29 May 2019 15:22:15 +0200 Subject: [PATCH 073/132] Use semicolon to introduce list --- doc/design_ros_2.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index a2d6732..ddb17b4 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -10,7 +10,7 @@ Provide low-overhead tools and resources for robotics software development based ### Requirements: instrumentation -Instrumentation should be built around the main uses of ROS 2, and should include relevant information. +Instrumentation should be built around the main uses of ROS 2, and should include relevant information: 1. Overall 1. When creating a publisher/subscriber/service/client/etc., appropriate references should be kept in order to correlate with other tracepoints related to the same instance. From 1012efafd676a0c89a66304a5fc4cc7b4cd0190e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 31 May 2019 10:17:33 +0200 Subject: [PATCH 074/132] Re-work last section --- doc/design_ros_2.md | 32 +++++++++++++++++++++++--------- 1 file changed, 23 insertions(+), 9 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index ddb17b4..c9f027c 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -463,19 +463,33 @@ sequenceDiagram end ``` -## Implementation notes - -### Instrumentation - -The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). - -This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer right before `rmw`. +## Design & implementation notes ### Targeted tools/dependencies -The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. +The targeted tools or dependencies are: -The targeted analysis & visualization tools are pandas and Jupyter. +* LTTng for tracing +* pandas and Jupyter for analysis & visualization + +### Design + +The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. The suggested setup is: + +* a tracing package (e.g. `tracetools`) wraps calls to LTTng +* ROS 2 is instrumented with calls to the tracing package, therefore it becomes a dependency and ships with the core stack +* by default, the tracing package's functions are empty -- they do not do anything +* if users wants to enable tracing, they need to + * install LTTng + * compile the tracing package from source, setting the right compile flag(s) + * overlay it on top of their ROS 2 installation +* use other package(s) for analysis and visualization + +### Timeline + +The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). + +This includes transposing the existing ROS 1 instrumentation to ROS 2, wherever applicable. This step may not include instrumenting DDS implementations, and thus may be limited to the layer(s) right before `rmw`. ### Notes on client libraries From 6caaa517644f20d3a6b479a109c9a2df3ce9b546 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 31 May 2019 16:07:11 +0200 Subject: [PATCH 075/132] Add tracetools_test package with simple test --- tracetools_test/.gitignore | 2 + tracetools_test/CMakeLists.txt | 49 ++++++++++++++++++++++ tracetools_test/package.xml | 28 +++++++++++++ tracetools_test/test/test_publisher.cpp | 32 ++++++++++++++ tracetools_test/test/test_publisher.py | 55 +++++++++++++++++++++++++ 5 files changed, 166 insertions(+) create mode 100644 tracetools_test/.gitignore create mode 100644 tracetools_test/CMakeLists.txt create mode 100644 tracetools_test/package.xml create mode 100644 tracetools_test/test/test_publisher.cpp create mode 100644 tracetools_test/test/test_publisher.py diff --git a/tracetools_test/.gitignore b/tracetools_test/.gitignore new file mode 100644 index 0000000..2f836aa --- /dev/null +++ b/tracetools_test/.gitignore @@ -0,0 +1,2 @@ +*~ +*.pyc diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt new file mode 100644 index 0000000..c1479bb --- /dev/null +++ b/tracetools_test/CMakeLists.txt @@ -0,0 +1,49 @@ +cmake_minimum_required(VERSION 3.5) +project(tracetools_test) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic -fPIC) +endif() + +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) + +# Tests +if(BUILD_TESTING) + add_executable(test_publisher + test/test_publisher.cpp + ) + ament_target_dependencies(test_publisher + rclcpp + std_msgs + ) + install(TARGETS + test_publisher + DESTINATION lib/${PROJECT_NAME} + ) + + find_package(ament_cmake_pytest REQUIRED) + + # Run each test in its own pytest invocation + set(_tracetools_test_pytest_tests + test/test_publisher.py + ) + + foreach(_test_path ${_tracetools_test_pytest_tests}) + get_filename_component(_test_name ${_test_path} NAME_WE) + ament_add_pytest_test(${_test_name} ${_test_path} + PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}" + APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path} + PYTHONPATH=${CMAKE_CURRENT_BINARY_DIR} + TIMEOUT 60 + ) + endforeach() +endif() + +ament_package() diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml new file mode 100644 index 0000000..a4d661e --- /dev/null +++ b/tracetools_test/package.xml @@ -0,0 +1,28 @@ + + + + tracetools_test + 0.0.1 + Separate test package for tracetools + Christophe Bedard + Christophe Bedard + APLv2 + + ament_cmake + pkg-config + + rclcpp + std_msgs + + rclcpp + std_msgs + + ament_cmake_pytest + launch_ros + python3-pytest + tracetools_trace + + + ament_cmake + + diff --git a/tracetools_test/test/test_publisher.cpp b/tracetools_test/test/test_publisher.cpp new file mode 100644 index 0000000..05210d5 --- /dev/null +++ b/tracetools_test/test/test_publisher.cpp @@ -0,0 +1,32 @@ +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + + +class PubNode : public rclcpp::Node +{ +public: + PubNode() : Node("pub_node") + { + pub_ = this->create_publisher( + "the_topic", + rclcpp::QoS(10)); + } + +private: + rclcpp::Publisher::SharedPtr pub_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto pub_node = std::make_shared(); + exec.add_node(pub_node); + + printf("spinning once\n"); + exec.spin_once(); + + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py new file mode 100644 index 0000000..c3e0b1e --- /dev/null +++ b/tracetools_test/test/test_publisher.py @@ -0,0 +1,55 @@ +import time +import shutil +from launch import LaunchDescription +from launch import LaunchIntrospector +from launch import LaunchService + +from launch_ros import get_default_launch_description +import launch_ros.actions +import unittest +from tracetools_analysis.test.utils import get_trace_event_names +from tracetools_trace.tools.lttng import ( + lttng_setup, + lttng_start, + lttng_stop, + lttng_destroy, +) + +PKG = 'tracetools_test' + +publisher_creation_events = [ + 'ros2:rcl_publisher_init', +] + +class TestPublisher(unittest.TestCase): + + def test_creation(self): + session_name = f'session-test-publisher-creation-{time.strftime("%Y%m%d%H%M%S")}' + path = '/tmp/' + session_name + print(f'trace directory: {path}') + + lttng_setup(session_name, path, ros_events=publisher_creation_events, kernel_events=None) + lttng_start(session_name) + + ld = LaunchDescription([ + launch_ros.actions.Node( + package=PKG, node_executable='test_publisher', output='screen'), + ]) + ls = LaunchService() + ls.include_launch_description(get_default_launch_description()) + ls.include_launch_description(ld) + + exit_code = ls.run() + self.assertEqual(exit_code, 0) + + lttng_stop(session_name) + lttng_destroy(session_name) + + trace_events = get_trace_event_names(path) + print(f'trace_events: {trace_events}') + self.assertListEqual(publisher_creation_events, list(trace_events)) + + shutil.rmtree(path) + +if __name__ == '__main__': + unittest.main() From cc8187e55b430e171766c2f610f203d6c6e8170e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 31 May 2019 16:43:04 +0200 Subject: [PATCH 076/132] Add subscription creation test --- tracetools_test/CMakeLists.txt | 10 ++++ tracetools_test/test/test_publisher.cpp | 4 +- tracetools_test/test/test_publisher.py | 1 + tracetools_test/test/test_subscription.cpp | 41 ++++++++++++++++ tracetools_test/test/test_subscription.py | 57 ++++++++++++++++++++++ 5 files changed, 111 insertions(+), 2 deletions(-) create mode 100644 tracetools_test/test/test_subscription.cpp create mode 100644 tracetools_test/test/test_subscription.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index c1479bb..7105fd3 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -23,8 +23,17 @@ if(BUILD_TESTING) rclcpp std_msgs ) + add_executable(test_subscription + test/test_subscription.cpp + ) + ament_target_dependencies(test_subscription + rclcpp + std_msgs + ) + install(TARGETS test_publisher + test_subscription DESTINATION lib/${PROJECT_NAME} ) @@ -33,6 +42,7 @@ if(BUILD_TESTING) # Run each test in its own pytest invocation set(_tracetools_test_pytest_tests test/test_publisher.py + test/test_subscription.py ) foreach(_test_path ${_tracetools_test_pytest_tests}) diff --git a/tracetools_test/test/test_publisher.cpp b/tracetools_test/test/test_publisher.cpp index 05210d5..a12c30e 100644 --- a/tracetools_test/test/test_publisher.cpp +++ b/tracetools_test/test/test_publisher.cpp @@ -5,7 +5,7 @@ class PubNode : public rclcpp::Node { public: - PubNode() : Node("pub_node") + PubNode(rclcpp::NodeOptions options) : Node("pub_node", options) { pub_ = this->create_publisher( "the_topic", @@ -21,7 +21,7 @@ int main(int argc, char* argv[]) rclcpp::init(argc, argv); rclcpp::executors::SingleThreadedExecutor exec; - auto pub_node = std::make_shared(); + auto pub_node = std::make_shared(rclcpp::NodeOptions()); exec.add_node(pub_node); printf("spinning once\n"); diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index c3e0b1e..0301091 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -51,5 +51,6 @@ class TestPublisher(unittest.TestCase): shutil.rmtree(path) + if __name__ == '__main__': unittest.main() diff --git a/tracetools_test/test/test_subscription.cpp b/tracetools_test/test/test_subscription.cpp new file mode 100644 index 0000000..9207de4 --- /dev/null +++ b/tracetools_test/test/test_subscription.cpp @@ -0,0 +1,41 @@ +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + + +class SubNode : public rclcpp::Node +{ +public: + SubNode(rclcpp::NodeOptions options) : Node("sub_node", options) + { + sub_ = this->create_subscription( + "the_topic", + rclcpp::QoS(10), + std::bind(&SubNode::callback, this, std::placeholders::_1)); + } + +private: + void callback(const std_msgs::msg::String::SharedPtr msg) + { + // Nothing + (void)msg; + } + + rclcpp::Subscription::SharedPtr sub_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto sub_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(sub_node); + + printf("spinning once\n"); + exec.spin_once(); + + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py new file mode 100644 index 0000000..625fda5 --- /dev/null +++ b/tracetools_test/test/test_subscription.py @@ -0,0 +1,57 @@ +import time +import shutil +from launch import LaunchDescription +from launch import LaunchIntrospector +from launch import LaunchService + +from launch_ros import get_default_launch_description +import launch_ros.actions +import unittest +from tracetools_analysis.test.utils import get_trace_event_names +from tracetools_trace.tools.lttng import ( + lttng_setup, + lttng_start, + lttng_stop, + lttng_destroy, +) + +PKG = 'tracetools_test' + +subscription_creation_events = [ + 'ros2:rcl_subscription_init', + 'ros2:rclcpp_subscription_callback_added', +] + +class TestSubscription(unittest.TestCase): + + def test_creation(self): + session_name = f'session-test-subscription-creation-{time.strftime("%Y%m%d%H%M%S")}' + path = '/tmp/' + session_name + print(f'trace directory: {path}') + + lttng_setup(session_name, path, ros_events=subscription_creation_events, kernel_events=None) + lttng_start(session_name) + + ld = LaunchDescription([ + launch_ros.actions.Node( + package=PKG, node_executable='test_subscription', output='screen'), + ]) + ls = LaunchService() + ls.include_launch_description(get_default_launch_description()) + ls.include_launch_description(ld) + + exit_code = ls.run() + self.assertEqual(exit_code, 0) + + lttng_stop(session_name) + lttng_destroy(session_name) + + trace_events = get_trace_event_names(path) + print(f'trace_events: {trace_events}') + self.assertListEqual(subscription_creation_events, list(trace_events)) + + shutil.rmtree(path) + + +if __name__ == '__main__': + unittest.main() From 58625f27f6b5e12de8f779dfd14ab3f30cbff924 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 09:45:11 +0200 Subject: [PATCH 077/132] Extract common test utils --- tracetools_test/test/test_publisher.py | 46 ++++------------ tracetools_test/test/test_subscription.py | 46 ++++------------ tracetools_test/tracetools_test/__init__.py | 0 tracetools_test/tracetools_test/utils.py | 60 +++++++++++++++++++++ 4 files changed, 82 insertions(+), 70 deletions(-) create mode 100644 tracetools_test/tracetools_test/__init__.py create mode 100644 tracetools_test/tracetools_test/utils.py diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 0301091..f1adab4 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -1,18 +1,8 @@ -import time -import shutil -from launch import LaunchDescription -from launch import LaunchIntrospector -from launch import LaunchService - -from launch_ros import get_default_launch_description -import launch_ros.actions import unittest -from tracetools_analysis.test.utils import get_trace_event_names -from tracetools_trace.tools.lttng import ( - lttng_setup, - lttng_start, - lttng_stop, - lttng_destroy, +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, ) PKG = 'tracetools_test' @@ -24,32 +14,18 @@ publisher_creation_events = [ class TestPublisher(unittest.TestCase): def test_creation(self): - session_name = f'session-test-publisher-creation-{time.strftime("%Y%m%d%H%M%S")}' - path = '/tmp/' + session_name - print(f'trace directory: {path}') + session_name_prefix = 'session-test-publisher-creation' + base_path = '/tmp' + test_node = 'test_publisher' - lttng_setup(session_name, path, ros_events=publisher_creation_events, kernel_events=None) - lttng_start(session_name) - - ld = LaunchDescription([ - launch_ros.actions.Node( - package=PKG, node_executable='test_publisher', output='screen'), - ]) - ls = LaunchService() - ls.include_launch_description(get_default_launch_description()) - ls.include_launch_description(ld) - - exit_code = ls.run() + exit_code, full_path = run_and_trace(session_name_prefix, base_path, publisher_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) - lttng_stop(session_name) - lttng_destroy(session_name) - - trace_events = get_trace_event_names(path) + trace_events = get_trace_event_names(full_path) print(f'trace_events: {trace_events}') - self.assertListEqual(publisher_creation_events, list(trace_events)) + self.assertSetEqual(set(publisher_creation_events), trace_events) - shutil.rmtree(path) + cleanup_trace(full_path) if __name__ == '__main__': diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 625fda5..f5543cd 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -1,18 +1,8 @@ -import time -import shutil -from launch import LaunchDescription -from launch import LaunchIntrospector -from launch import LaunchService - -from launch_ros import get_default_launch_description -import launch_ros.actions import unittest -from tracetools_analysis.test.utils import get_trace_event_names -from tracetools_trace.tools.lttng import ( - lttng_setup, - lttng_start, - lttng_stop, - lttng_destroy, +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, ) PKG = 'tracetools_test' @@ -25,32 +15,18 @@ subscription_creation_events = [ class TestSubscription(unittest.TestCase): def test_creation(self): - session_name = f'session-test-subscription-creation-{time.strftime("%Y%m%d%H%M%S")}' - path = '/tmp/' + session_name - print(f'trace directory: {path}') + session_name_prefix = 'session-test-subscription-creation' + base_path = '/tmp' + test_node = 'test_subscription' - lttng_setup(session_name, path, ros_events=subscription_creation_events, kernel_events=None) - lttng_start(session_name) - - ld = LaunchDescription([ - launch_ros.actions.Node( - package=PKG, node_executable='test_subscription', output='screen'), - ]) - ls = LaunchService() - ls.include_launch_description(get_default_launch_description()) - ls.include_launch_description(ld) - - exit_code = ls.run() + exit_code, full_path = run_and_trace(session_name_prefix, base_path, subscription_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) - lttng_stop(session_name) - lttng_destroy(session_name) - - trace_events = get_trace_event_names(path) + trace_events = get_trace_event_names(full_path) print(f'trace_events: {trace_events}') - self.assertListEqual(subscription_creation_events, list(trace_events)) + self.assertSetEqual(set(subscription_creation_events), trace_events) - shutil.rmtree(path) + cleanup_trace(full_path) if __name__ == '__main__': diff --git a/tracetools_test/tracetools_test/__init__.py b/tracetools_test/tracetools_test/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py new file mode 100644 index 0000000..8fc6b27 --- /dev/null +++ b/tracetools_test/tracetools_test/utils.py @@ -0,0 +1,60 @@ +# Utils for tracetools_test + +import time +import shutil +import subprocess +import babeltrace +from launch import LaunchDescription +from launch import LaunchService +from launch_ros import get_default_launch_description +import launch_ros.actions +from tracetools_trace.tools.lttng import ( + lttng_setup, + lttng_start, + lttng_stop, + lttng_destroy, +) + +def run_and_trace(session_name_prefix, base_path, ros_events, kernel_events, package_name, node_executable): + session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' + full_path = f'{base_path}/{session_name}' + print(f'trace directory: {full_path}') + + lttng_setup(session_name, full_path, ros_events=ros_events, kernel_events=kernel_events) + lttng_start(session_name) + + ld = LaunchDescription([ + launch_ros.actions.Node( + package=package_name, node_executable=node_executable, output='screen'), + ]) + ls = LaunchService() + ls.include_launch_description(get_default_launch_description()) + ls.include_launch_description(ld) + + exit_code = ls.run() + + lttng_stop(session_name) + lttng_destroy(session_name) + + return exit_code, full_path + + +def cleanup_trace(full_path): + shutil.rmtree(full_path) + + +def get_trace_event_names(trace_directory): + """ + Get a set of event names in a trace + :param trace_directory (str): the path to the main/top trace directory + :return: event names (set(str)) + """ + tc = babeltrace.TraceCollection() + tc.add_traces_recursive(trace_directory, 'ctf') + + event_names = set() + + for event in tc.events: + event_names.add(event.name) + + return event_names From 29637221cac4148ee01810e3276f637c1fd7e27c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 09:48:09 +0200 Subject: [PATCH 078/132] Change param order --- tracetools_test/test/test_publisher.py | 2 +- tracetools_test/test/test_subscription.py | 2 +- tracetools_test/tracetools_test/utils.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index f1adab4..0c15283 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -18,7 +18,7 @@ class TestPublisher(unittest.TestCase): base_path = '/tmp' test_node = 'test_publisher' - exit_code, full_path = run_and_trace(session_name_prefix, base_path, publisher_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(base_path, session_name_prefix, publisher_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index f5543cd..5caac19 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -19,7 +19,7 @@ class TestSubscription(unittest.TestCase): base_path = '/tmp' test_node = 'test_subscription' - exit_code, full_path = run_and_trace(session_name_prefix, base_path, subscription_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index 8fc6b27..823b946 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -15,7 +15,7 @@ from tracetools_trace.tools.lttng import ( lttng_destroy, ) -def run_and_trace(session_name_prefix, base_path, ros_events, kernel_events, package_name, node_executable): +def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_executable): session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' full_path = f'{base_path}/{session_name}' print(f'trace directory: {full_path}') From 82ef066b169335bbdb0b7c5fc260666498262e48 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 09:52:20 +0200 Subject: [PATCH 079/132] Document test utils --- tracetools_test/tracetools_test/utils.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index 823b946..f104867 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -16,6 +16,15 @@ from tracetools_trace.tools.lttng import ( ) def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_executable): + """ + Run a node while tracing + :param base_path (str): the base path where to put the trace directory + :param session_name_prefix (str): the session name prefix for the trace directory + :param ros_events (list(str)): the list of ROS UST events to enable + :param kernel_events (list(str)): the list of kernel events to enable + :param package_name (str): the name of the package to use + :param node_executable (str): the name of the node to execute + """ session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' full_path = f'{base_path}/{session_name}' print(f'trace directory: {full_path}') @@ -40,6 +49,10 @@ def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, pac def cleanup_trace(full_path): + """ + Cleanup trace data + :param full_path (str): the full path to the main trace directory + """ shutil.rmtree(full_path) From 198fa8b03982716630a8e2c9ff2bf556d51a4e53 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 10:02:03 +0200 Subject: [PATCH 080/132] Move test nodes to src/ --- tracetools_test/CMakeLists.txt | 4 ++-- tracetools_test/{test => src}/test_publisher.cpp | 0 tracetools_test/{test => src}/test_subscription.cpp | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename tracetools_test/{test => src}/test_publisher.cpp (100%) rename tracetools_test/{test => src}/test_subscription.cpp (100%) diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 7105fd3..a0ebd1a 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -17,14 +17,14 @@ find_package(std_msgs REQUIRED) # Tests if(BUILD_TESTING) add_executable(test_publisher - test/test_publisher.cpp + src/test_publisher.cpp ) ament_target_dependencies(test_publisher rclcpp std_msgs ) add_executable(test_subscription - test/test_subscription.cpp + src/test_subscription.cpp ) ament_target_dependencies(test_subscription rclcpp diff --git a/tracetools_test/test/test_publisher.cpp b/tracetools_test/src/test_publisher.cpp similarity index 100% rename from tracetools_test/test/test_publisher.cpp rename to tracetools_test/src/test_publisher.cpp diff --git a/tracetools_test/test/test_subscription.cpp b/tracetools_test/src/test_subscription.cpp similarity index 100% rename from tracetools_test/test/test_subscription.cpp rename to tracetools_test/src/test_subscription.cpp From 3b85b3cbd815aa3a4e05d43a84e4cc08d901417f Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 10:07:43 +0200 Subject: [PATCH 081/132] Add node creation test --- tracetools_test/CMakeLists.txt | 1 + tracetools_test/test/test_node.py | 33 +++++++++++++++++++++++++++++++ 2 files changed, 34 insertions(+) create mode 100644 tracetools_test/test/test_node.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index a0ebd1a..b0ee45f 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -41,6 +41,7 @@ if(BUILD_TESTING) # Run each test in its own pytest invocation set(_tracetools_test_pytest_tests + test/test_node.py test/test_publisher.py test/test_subscription.py ) diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py new file mode 100644 index 0000000..2757948 --- /dev/null +++ b/tracetools_test/test/test_node.py @@ -0,0 +1,33 @@ +import unittest +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, +) + +PKG = 'tracetools_test' + +node_creation_events = [ + 'ros2:rcl_init', + 'ros2:rcl_node_init', +] + +class TestNode(unittest.TestCase): + + def test_creation(self): + session_name_prefix = 'session-test-node-creation' + base_path = '/tmp' + test_node = 'test_publisher' + + exit_code, full_path = run_and_trace(base_path, session_name_prefix, node_creation_events, None, PKG, test_node) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(node_creation_events), trace_events) + + cleanup_trace(full_path) + + +if __name__ == '__main__': + unittest.main() From 8f09ce339d0470c2476dd3d6076b110acae6e698 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:16:05 +0200 Subject: [PATCH 082/132] Add subscription callback test with ping+pong nodes --- tracetools_test/CMakeLists.txt | 16 ++++++ tracetools_test/src/test_ping.cpp | 62 +++++++++++++++++++++++ tracetools_test/src/test_pong.cpp | 49 ++++++++++++++++++ tracetools_test/test/test_node.py | 2 +- tracetools_test/test/test_publisher.py | 2 +- tracetools_test/test/test_subscription.py | 21 +++++++- tracetools_test/tracetools_test/utils.py | 15 +++--- 7 files changed, 158 insertions(+), 9 deletions(-) create mode 100644 tracetools_test/src/test_ping.cpp create mode 100644 tracetools_test/src/test_pong.cpp diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index b0ee45f..4690fb8 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -30,10 +30,26 @@ if(BUILD_TESTING) rclcpp std_msgs ) + add_executable(test_ping + src/test_ping.cpp + ) + ament_target_dependencies(test_ping + rclcpp + std_msgs + ) + add_executable(test_pong + src/test_pong.cpp + ) + ament_target_dependencies(test_pong + rclcpp + std_msgs + ) install(TARGETS test_publisher test_subscription + test_ping + test_pong DESTINATION lib/${PROJECT_NAME} ) diff --git a/tracetools_test/src/test_ping.cpp b/tracetools_test/src/test_ping.cpp new file mode 100644 index 0000000..611afeb --- /dev/null +++ b/tracetools_test/src/test_ping.cpp @@ -0,0 +1,62 @@ +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/rate.hpp" +#include "std_msgs/msg/string.hpp" + +using namespace std::chrono_literals; + + +class PingNode : public rclcpp::Node +{ +public: + PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) + { + sub_ = this->create_subscription( + "pong", + rclcpp::QoS(10), + std::bind(&PingNode::callback, this, std::placeholders::_1)); + pub_ = this->create_publisher( + "ping", + rclcpp::QoS(10)); + timer_ = this->create_wall_timer( + 500ms, + std::bind(&PingNode::timer_callback, this)); + } + + +private: + void callback(const std_msgs::msg::String::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); + rclcpp::shutdown(); + } + + void timer_callback() + { + auto msg = std::make_shared(); + msg->data = "some random ping string"; + pub_->publish(*msg); + } + + rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; + rclcpp::TimerBase::SharedPtr timer_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto ping_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(ping_node); + + printf("spinning\n"); + exec.spin(); + + // Will actually be called inside the node's callback + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/src/test_pong.cpp b/tracetools_test/src/test_pong.cpp new file mode 100644 index 0000000..99e35ce --- /dev/null +++ b/tracetools_test/src/test_pong.cpp @@ -0,0 +1,49 @@ +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + + +class PongNode : public rclcpp::Node +{ +public: + PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) + { + sub_ = this->create_subscription( + "ping", + rclcpp::QoS(10), + std::bind(&PongNode::callback, this, std::placeholders::_1)); + pub_ = this->create_publisher( + "pong", + rclcpp::QoS(10)); + } + +private: + void callback(const std_msgs::msg::String::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); + auto next_msg = std::make_shared(); + next_msg->data = "some random pong string"; + pub_->publish(*next_msg); + rclcpp::shutdown(); + } + + rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto pong_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(pong_node); + + printf("spinning\n"); + exec.spin(); + + // Will actually be called inside the node's callback + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index 2757948..cd25e4a 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -17,7 +17,7 @@ class TestNode(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-node-creation' base_path = '/tmp' - test_node = 'test_publisher' + test_node = ['test_publisher'] exit_code, full_path = run_and_trace(base_path, session_name_prefix, node_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 0c15283..e2ce3d0 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -16,7 +16,7 @@ class TestPublisher(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-publisher-creation' base_path = '/tmp' - test_node = 'test_publisher' + test_node = ['test_publisher'] exit_code, full_path = run_and_trace(base_path, session_name_prefix, publisher_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 5caac19..693ba85 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -12,12 +12,17 @@ subscription_creation_events = [ 'ros2:rclcpp_subscription_callback_added', ] +subscription_callback_events = [ + 'ros2:rclcpp_subscription_callback_start', + 'ros2:rclcpp_subscription_callback_end', +] + class TestSubscription(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-subscription-creation' base_path = '/tmp' - test_node = 'test_subscription' + test_node = ['test_subscription'] exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) @@ -28,6 +33,20 @@ class TestSubscription(unittest.TestCase): cleanup_trace(full_path) + def test_callback(self): + session_name_prefix = 'session-test-subscription-callback' + base_path = '/tmp' + test_nodes = ['test_ping', 'test_pong'] + + exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(subscription_callback_events), trace_events) + + cleanup_trace(full_path) + if __name__ == '__main__': unittest.main() diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index f104867..462cb23 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -15,7 +15,7 @@ from tracetools_trace.tools.lttng import ( lttng_destroy, ) -def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_executable): +def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_names): """ Run a node while tracing :param base_path (str): the base path where to put the trace directory @@ -23,7 +23,7 @@ def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, pac :param ros_events (list(str)): the list of ROS UST events to enable :param kernel_events (list(str)): the list of kernel events to enable :param package_name (str): the name of the package to use - :param node_executable (str): the name of the node to execute + :param node_names (list(str)): the names of the nodes to execute """ session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' full_path = f'{base_path}/{session_name}' @@ -32,10 +32,13 @@ def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, pac lttng_setup(session_name, full_path, ros_events=ros_events, kernel_events=kernel_events) lttng_start(session_name) - ld = LaunchDescription([ - launch_ros.actions.Node( - package=package_name, node_executable=node_executable, output='screen'), - ]) + nodes = [] + for node_name in node_names: + n = launch_ros.actions.Node(package=package_name, + node_executable=node_name, + output='screen') + nodes.append(n) + ld = LaunchDescription(nodes) ls = LaunchService() ls.include_launch_description(get_default_launch_description()) ls.include_launch_description(ld) From 39bd95b51f299b4f7130b1af602dda36a4601b81 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:20:02 +0200 Subject: [PATCH 083/132] Fix tests by splitting them into two separate files --- tracetools_test/CMakeLists.txt | 1 + tracetools_test/test/test_subscription.py | 19 ----------- .../test/test_subscription_callback.py | 33 +++++++++++++++++++ 3 files changed, 34 insertions(+), 19 deletions(-) create mode 100644 tracetools_test/test/test_subscription_callback.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 4690fb8..3b3f755 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -60,6 +60,7 @@ if(BUILD_TESTING) test/test_node.py test/test_publisher.py test/test_subscription.py + test/test_subscription_callback.py ) foreach(_test_path ${_tracetools_test_pytest_tests}) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 693ba85..5d9e99f 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -12,11 +12,6 @@ subscription_creation_events = [ 'ros2:rclcpp_subscription_callback_added', ] -subscription_callback_events = [ - 'ros2:rclcpp_subscription_callback_start', - 'ros2:rclcpp_subscription_callback_end', -] - class TestSubscription(unittest.TestCase): def test_creation(self): @@ -33,20 +28,6 @@ class TestSubscription(unittest.TestCase): cleanup_trace(full_path) - def test_callback(self): - session_name_prefix = 'session-test-subscription-callback' - base_path = '/tmp' - test_nodes = ['test_ping', 'test_pong'] - - exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) - self.assertEqual(exit_code, 0) - - trace_events = get_trace_event_names(full_path) - print(f'trace_events: {trace_events}') - self.assertSetEqual(set(subscription_callback_events), trace_events) - - cleanup_trace(full_path) - if __name__ == '__main__': unittest.main() diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py new file mode 100644 index 0000000..c86b58a --- /dev/null +++ b/tracetools_test/test/test_subscription_callback.py @@ -0,0 +1,33 @@ +import unittest +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, +) + +PKG = 'tracetools_test' + +subscription_callback_events = [ + 'ros2:rclcpp_subscription_callback_start', + 'ros2:rclcpp_subscription_callback_end', +] + +class TestSubscriptionCallback(unittest.TestCase): + + def test_callback(self): + session_name_prefix = 'session-test-subscription-callback' + base_path = '/tmp' + test_nodes = ['test_ping', 'test_pong'] + + exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(subscription_callback_events), trace_events) + + cleanup_trace(full_path) + + +if __name__ == '__main__': + unittest.main() From d198de3958b2c72080205f6f70184bbe6b73c094 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:22:23 +0200 Subject: [PATCH 084/132] Remove unused #include --- tracetools_test/src/test_ping.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/tracetools_test/src/test_ping.cpp b/tracetools_test/src/test_ping.cpp index 611afeb..51eeab4 100644 --- a/tracetools_test/src/test_ping.cpp +++ b/tracetools_test/src/test_ping.cpp @@ -2,7 +2,6 @@ #include #include "rclcpp/rclcpp.hpp" -#include "rclcpp/rate.hpp" #include "std_msgs/msg/string.hpp" using namespace std::chrono_literals; From d6fec8171c100d72be1dfd621aa4e3d29bd7c47c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:36:16 +0200 Subject: [PATCH 085/132] Add timer test --- tracetools_test/CMakeLists.txt | 9 ++++++ tracetools_test/src/test_timer.cpp | 47 ++++++++++++++++++++++++++++++ tracetools_test/test/test_timer.py | 35 ++++++++++++++++++++++ 3 files changed, 91 insertions(+) create mode 100644 tracetools_test/src/test_timer.cpp create mode 100644 tracetools_test/test/test_timer.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 3b3f755..05cca81 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -44,12 +44,20 @@ if(BUILD_TESTING) rclcpp std_msgs ) + add_executable(test_timer + src/test_timer.cpp + ) + ament_target_dependencies(test_timer + rclcpp + std_msgs + ) install(TARGETS test_publisher test_subscription test_ping test_pong + test_timer DESTINATION lib/${PROJECT_NAME} ) @@ -61,6 +69,7 @@ if(BUILD_TESTING) test/test_publisher.py test/test_subscription.py test/test_subscription_callback.py + test/test_timer.py ) foreach(_test_path ${_tracetools_test_pytest_tests}) diff --git a/tracetools_test/src/test_timer.cpp b/tracetools_test/src/test_timer.cpp new file mode 100644 index 0000000..2c787f0 --- /dev/null +++ b/tracetools_test/src/test_timer.cpp @@ -0,0 +1,47 @@ +#include + +#include "rclcpp/rclcpp.hpp" + +using namespace std::chrono_literals; + + +class TimerNode : public rclcpp::Node +{ +public: + TimerNode(rclcpp::NodeOptions options) : Node("timer_node", options) + { + is_done_ = false; + timer_ = this->create_wall_timer( + 1ms, + std::bind(&TimerNode::timer_callback, this)); + } + +private: + void timer_callback() + { + if (is_done_) { + rclcpp::shutdown(); + } else { + is_done_ = true; + } + } + + rclcpp::TimerBase::SharedPtr timer_; + bool is_done_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto timer_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(timer_node); + + printf("spinning\n"); + exec.spin(); + + // Will actually be called inside the timer's callback + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py new file mode 100644 index 0000000..12e7c4c --- /dev/null +++ b/tracetools_test/test/test_timer.py @@ -0,0 +1,35 @@ +import unittest +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, +) + +PKG = 'tracetools_test' + +timer_events = [ + 'ros2:rcl_timer_init', + 'ros2:rclcpp_timer_callback_added', + 'ros2:rclcpp_timer_callback_start', + 'ros2:rclcpp_timer_callback_end', +] + +class TestTimer(unittest.TestCase): + + def test_all(self): + session_name_prefix = 'session-test-timer-all' + base_path = '/tmp' + test_nodes = ['test_timer'] + + exit_code, full_path = run_and_trace(base_path, session_name_prefix, timer_events, None, PKG, test_nodes) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(timer_events), trace_events) + + cleanup_trace(full_path) + + +if __name__ == '__main__': + unittest.main() From 6296fc0016a8ab08f7d1b7eb2b17b22277d84f5d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:39:37 +0200 Subject: [PATCH 086/132] Extract base path constant --- tracetools_test/test/test_node.py | 5 ++--- tracetools_test/test/test_publisher.py | 5 ++--- tracetools_test/test/test_subscription.py | 5 ++--- tracetools_test/test/test_subscription_callback.py | 5 ++--- tracetools_test/test/test_timer.py | 5 ++--- 5 files changed, 10 insertions(+), 15 deletions(-) diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index cd25e4a..b2086de 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -5,8 +5,8 @@ from tracetools_test.utils import ( cleanup_trace, ) +BASE_PATH = '/tmp' PKG = 'tracetools_test' - node_creation_events = [ 'ros2:rcl_init', 'ros2:rcl_node_init', @@ -16,10 +16,9 @@ class TestNode(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-node-creation' - base_path = '/tmp' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(base_path, session_name_prefix, node_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, node_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index e2ce3d0..ea7da55 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -5,8 +5,8 @@ from tracetools_test.utils import ( cleanup_trace, ) +BASE_PATH = '/tmp' PKG = 'tracetools_test' - publisher_creation_events = [ 'ros2:rcl_publisher_init', ] @@ -15,10 +15,9 @@ class TestPublisher(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-publisher-creation' - base_path = '/tmp' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(base_path, session_name_prefix, publisher_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, publisher_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 5d9e99f..09e63fb 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -5,8 +5,8 @@ from tracetools_test.utils import ( cleanup_trace, ) +BASE_PATH = '/tmp' PKG = 'tracetools_test' - subscription_creation_events = [ 'ros2:rcl_subscription_init', 'ros2:rclcpp_subscription_callback_added', @@ -16,10 +16,9 @@ class TestSubscription(unittest.TestCase): def test_creation(self): session_name_prefix = 'session-test-subscription-creation' - base_path = '/tmp' test_node = ['test_subscription'] - exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, subscription_creation_events, None, PKG, test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index c86b58a..cdd5b94 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -5,8 +5,8 @@ from tracetools_test.utils import ( cleanup_trace, ) +BASE_PATH = '/tmp' PKG = 'tracetools_test' - subscription_callback_events = [ 'ros2:rclcpp_subscription_callback_start', 'ros2:rclcpp_subscription_callback_end', @@ -16,10 +16,9 @@ class TestSubscriptionCallback(unittest.TestCase): def test_callback(self): session_name_prefix = 'session-test-subscription-callback' - base_path = '/tmp' test_nodes = ['test_ping', 'test_pong'] - exit_code, full_path = run_and_trace(base_path, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) + exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index 12e7c4c..950ce47 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -5,8 +5,8 @@ from tracetools_test.utils import ( cleanup_trace, ) +BASE_PATH = '/tmp' PKG = 'tracetools_test' - timer_events = [ 'ros2:rcl_timer_init', 'ros2:rclcpp_timer_callback_added', @@ -18,10 +18,9 @@ class TestTimer(unittest.TestCase): def test_all(self): session_name_prefix = 'session-test-timer-all' - base_path = '/tmp' test_nodes = ['test_timer'] - exit_code, full_path = run_and_trace(base_path, session_name_prefix, timer_events, None, PKG, test_nodes) + exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, timer_events, None, PKG, test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) From 9dcac8ad3db08a8c6dec94c4f944d235030bb3b7 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:42:23 +0200 Subject: [PATCH 087/132] Format long calls --- tracetools_test/test/test_node.py | 7 ++++++- tracetools_test/test/test_publisher.py | 7 ++++++- tracetools_test/test/test_subscription.py | 7 ++++++- tracetools_test/test/test_subscription_callback.py | 7 ++++++- tracetools_test/test/test_timer.py | 7 ++++++- 5 files changed, 30 insertions(+), 5 deletions(-) diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index b2086de..08973e2 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -18,7 +18,12 @@ class TestNode(unittest.TestCase): session_name_prefix = 'session-test-node-creation' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, node_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + node_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index ea7da55..2c058b9 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -17,7 +17,12 @@ class TestPublisher(unittest.TestCase): session_name_prefix = 'session-test-publisher-creation' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, publisher_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + publisher_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 09e63fb..d689c8f 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -18,7 +18,12 @@ class TestSubscription(unittest.TestCase): session_name_prefix = 'session-test-subscription-creation' test_node = ['test_subscription'] - exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, subscription_creation_events, None, PKG, test_node) + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + subscription_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index cdd5b94..c0112f0 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -18,7 +18,12 @@ class TestSubscriptionCallback(unittest.TestCase): session_name_prefix = 'session-test-subscription-callback' test_nodes = ['test_ping', 'test_pong'] - exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, subscription_callback_events, None, PKG, test_nodes) + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + subscription_callback_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index 950ce47..6716ee7 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -20,7 +20,12 @@ class TestTimer(unittest.TestCase): session_name_prefix = 'session-test-timer-all' test_nodes = ['test_timer'] - exit_code, full_path = run_and_trace(BASE_PATH, session_name_prefix, timer_events, None, PKG, test_nodes) + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + timer_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) From e37ce0df61235732b67f76e761c49e8a4681dcbf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:57:19 +0200 Subject: [PATCH 088/132] Add service creation test --- tracetools_test/CMakeLists.txt | 10 ++++++ tracetools_test/package.xml | 2 ++ tracetools_test/src/test_service.cpp | 48 ++++++++++++++++++++++++++++ tracetools_test/test/test_service.py | 37 +++++++++++++++++++++ 4 files changed, 97 insertions(+) create mode 100644 tracetools_test/src/test_service.cpp create mode 100644 tracetools_test/test/test_service.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 05cca81..0866792 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -13,6 +13,7 @@ endif() find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) +find_package(std_srvs REQUIRED) # Tests if(BUILD_TESTING) @@ -51,6 +52,13 @@ if(BUILD_TESTING) rclcpp std_msgs ) + add_executable(test_service + src/test_service.cpp + ) + ament_target_dependencies(test_service + rclcpp + std_srvs + ) install(TARGETS test_publisher @@ -58,6 +66,7 @@ if(BUILD_TESTING) test_ping test_pong test_timer + test_service DESTINATION lib/${PROJECT_NAME} ) @@ -70,6 +79,7 @@ if(BUILD_TESTING) test/test_subscription.py test/test_subscription_callback.py test/test_timer.py + test/test_service.py ) foreach(_test_path ${_tracetools_test_pytest_tests}) diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index a4d661e..884375e 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -13,9 +13,11 @@ rclcpp std_msgs + std_srvs rclcpp std_msgs + std_srvs ament_cmake_pytest launch_ros diff --git a/tracetools_test/src/test_service.cpp b/tracetools_test/src/test_service.cpp new file mode 100644 index 0000000..c347b21 --- /dev/null +++ b/tracetools_test/src/test_service.cpp @@ -0,0 +1,48 @@ +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_srvs/srv/empty.hpp" + +class ServiceNode : public rclcpp::Node +{ +public: + ServiceNode(rclcpp::NodeOptions options) : Node("service_node", options) + { + srv_ = this->create_service( + "service", + std::bind(&ServiceNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + } + +private: + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + // Nothing + (void)request_header; + (void)request; + (void)response; + } + + rclcpp::Service::SharedPtr srv_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto service_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(service_node); + + printf("spinning once\n"); + exec.spin_once(); + + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_service.py b/tracetools_test/test/test_service.py new file mode 100644 index 0000000..4230c4d --- /dev/null +++ b/tracetools_test/test/test_service.py @@ -0,0 +1,37 @@ +import unittest +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, +) + +BASE_PATH = '/tmp' +PKG = 'tracetools_test' +service_creation_events = [ + 'ros2:rcl_service_init', + 'ros2:rclcpp_service_callback_added', +] + +class TestService(unittest.TestCase): + + def test_creation(self): + session_name_prefix = 'session-test-service-creation' + test_nodes = ['test_service'] + + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + service_creation_events, + None, + PKG, + test_nodes) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(service_creation_events), trace_events) + + cleanup_trace(full_path) + + +if __name__ == '__main__': + unittest.main() From 77645f2a527ae9cbaf76ee60341918af438e16eb Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 11:58:45 +0200 Subject: [PATCH 089/132] Remove useless dependency --- tracetools_test/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 0866792..cc516c3 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -50,7 +50,6 @@ if(BUILD_TESTING) ) ament_target_dependencies(test_timer rclcpp - std_msgs ) add_executable(test_service src/test_service.cpp From ce9d6eff958620b3a01b4290e87ac964292a5636 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 13:05:05 +0200 Subject: [PATCH 090/132] Add service callback test --- tracetools_test/CMakeLists.txt | 17 +++++ tracetools_test/src/test_service_ping.cpp | 68 +++++++++++++++++++ tracetools_test/src/test_service_pong.cpp | 57 ++++++++++++++++ tracetools_test/test/test_service_callback.py | 37 ++++++++++ 4 files changed, 179 insertions(+) create mode 100644 tracetools_test/src/test_service_ping.cpp create mode 100644 tracetools_test/src/test_service_pong.cpp create mode 100644 tracetools_test/test/test_service_callback.py diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index cc516c3..3ef2871 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -58,6 +58,20 @@ if(BUILD_TESTING) rclcpp std_srvs ) + add_executable(test_service_ping + src/test_service_ping.cpp + ) + ament_target_dependencies(test_service_ping + rclcpp + std_srvs + ) + add_executable(test_service_pong + src/test_service_pong.cpp + ) + ament_target_dependencies(test_service_pong + rclcpp + std_srvs + ) install(TARGETS test_publisher @@ -66,6 +80,8 @@ if(BUILD_TESTING) test_pong test_timer test_service + test_service_ping + test_service_pong DESTINATION lib/${PROJECT_NAME} ) @@ -79,6 +95,7 @@ if(BUILD_TESTING) test/test_subscription_callback.py test/test_timer.py test/test_service.py + test/test_service_callback.py ) foreach(_test_path ${_tracetools_test_pytest_tests}) diff --git a/tracetools_test/src/test_service_ping.cpp b/tracetools_test/src/test_service_ping.cpp new file mode 100644 index 0000000..cbc5fec --- /dev/null +++ b/tracetools_test/src/test_service_ping.cpp @@ -0,0 +1,68 @@ +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_srvs/srv/empty.hpp" + +using namespace std::chrono_literals; + + +class PingNode : public rclcpp::Node +{ +public: + PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) + { + srv_ = this->create_service( + "pong", + std::bind(&PingNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + client_ = this->create_client( + "ping"); + timer_ = this->create_wall_timer( + 500ms, + std::bind(&PingNode::timer_callback, this)); + } + + +private: + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + (void)request_header; + (void)request; + (void)response; + RCLCPP_INFO(this->get_logger(), "got request"); + rclcpp::shutdown(); + } + + void timer_callback() + { + auto req = std::make_shared(); + client_->async_send_request(req); + } + + rclcpp::Service::SharedPtr srv_; + rclcpp::Client::SharedPtr client_; + rclcpp::TimerBase::SharedPtr timer_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto ping_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(ping_node); + + printf("spinning\n"); + exec.spin(); + + // Will actually be called inside the node's service callback + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/src/test_service_pong.cpp b/tracetools_test/src/test_service_pong.cpp new file mode 100644 index 0000000..f09f761 --- /dev/null +++ b/tracetools_test/src/test_service_pong.cpp @@ -0,0 +1,57 @@ +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_srvs/srv/empty.hpp" + + +class PongNode : public rclcpp::Node +{ +public: + PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) + { + srv_ = this->create_service( + "ping", + std::bind(&PongNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + client_ = this->create_client( + "pong"); + } + + +private: + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + (void)request_header; + (void)request; + (void)response; + RCLCPP_INFO(this->get_logger(), "got request"); + auto req = std::make_shared(); + client_->async_send_request(req); + rclcpp::shutdown(); + } + + rclcpp::Service::SharedPtr srv_; + rclcpp::Client::SharedPtr client_; +}; + +int main(int argc, char* argv[]) +{ + rclcpp::init(argc, argv); + + rclcpp::executors::SingleThreadedExecutor exec; + auto pong_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(pong_node); + + printf("spinning\n"); + exec.spin(); + + // Will actually be called inside the node's service callback + rclcpp::shutdown(); + return 0; +} diff --git a/tracetools_test/test/test_service_callback.py b/tracetools_test/test/test_service_callback.py new file mode 100644 index 0000000..8992f9a --- /dev/null +++ b/tracetools_test/test/test_service_callback.py @@ -0,0 +1,37 @@ +import unittest +from tracetools_test.utils import ( + get_trace_event_names, + run_and_trace, + cleanup_trace, +) + +BASE_PATH = '/tmp' +PKG = 'tracetools_test' +service_callback_events = [ + 'ros2:rclcpp_service_callback_start', + 'ros2:rclcpp_service_callback_end', +] + +class TestServiceCallback(unittest.TestCase): + + def test_callback(self): + session_name_prefix = 'session-test-service-callback' + test_nodes = ['test_service_ping', 'test_service_pong'] + + exit_code, full_path = run_and_trace(BASE_PATH, + session_name_prefix, + service_callback_events, + None, + PKG, + test_nodes) + self.assertEqual(exit_code, 0) + + trace_events = get_trace_event_names(full_path) + print(f'trace_events: {trace_events}') + self.assertSetEqual(set(service_callback_events), trace_events) + + cleanup_trace(full_path) + + +if __name__ == '__main__': + unittest.main() From c642351e96371e40aeda287f8d8866c2298fbd2a Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 3 Jun 2019 16:14:21 +0200 Subject: [PATCH 091/132] Add public post plan --- doc/public_post_plan.md | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) create mode 100644 doc/public_post_plan.md diff --git a/doc/public_post_plan.md b/doc/public_post_plan.md new file mode 100644 index 0000000..67a0c17 --- /dev/null +++ b/doc/public_post_plan.md @@ -0,0 +1,23 @@ + +Plan for a first public post/announcement. +This week. + +Simple example: +* Jupyter notebook to plot: + * subscription callback duration + * CPU cycles/callback +* and resolve/demangle symbols +* Include all files/scripts needed to get the result, but keep it simple +* To be hosted somewhere +* With some documentation/guide on how to try it out + +Post: +* Mention that we're working on this +* Talk about goals in general +* Target = next release +* Show off example +* Invite people to ask questions/discuss + +Architecture considerations (right now but also later): +* Try to use a dataframe as a ROS model abstraction, instead of first going through a layer with python data structures +* \ No newline at end of file From 3022d678f91c048e8aff19c904c515c63c03e7d1 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 4 Jun 2019 13:51:56 +0200 Subject: [PATCH 092/132] Move find_package() lines to test section --- tracetools_test/CMakeLists.txt | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 3ef2871..2c17289 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -11,12 +11,13 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") endif() find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) -find_package(std_srvs REQUIRED) # Tests if(BUILD_TESTING) + find_package(rclcpp REQUIRED) + find_package(std_msgs REQUIRED) + find_package(std_srvs REQUIRED) + add_executable(test_publisher src/test_publisher.cpp ) From 51f3c16205c02af7f1811bab07a3e2c1f69955c2 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 4 Jun 2019 13:53:05 +0200 Subject: [PATCH 093/132] Add linting tests to both tracetools* packages --- tracetools/CMakeLists.txt | 5 +++++ tracetools/package.xml | 3 +++ tracetools_test/CMakeLists.txt | 3 +++ tracetools_test/package.xml | 2 ++ 4 files changed, 13 insertions(+) diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index 328185e..f989644 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -91,4 +91,9 @@ else() ament_export_libraries(${PROJECT_NAME}) endif() +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + ament_package() diff --git a/tracetools/package.xml b/tracetools/package.xml index 2d80723..6794a9e 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -13,6 +13,9 @@ + ament_lint_auto + ament_lint_common + ament_cmake diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 2c17289..02ab483 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -86,6 +86,9 @@ if(BUILD_TESTING) DESTINATION lib/${PROJECT_NAME} ) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + find_package(ament_cmake_pytest REQUIRED) # Run each test in its own pytest invocation diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index 884375e..008337e 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -20,6 +20,8 @@ std_srvs ament_cmake_pytest + ament_lint_auto + ament_lint_common launch_ros python3-pytest tracetools_trace From ee813caaf1b2dc7a2f86bc4a138a481b0582d70d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 4 Jun 2019 16:37:11 +0200 Subject: [PATCH 094/132] Extract util methods --- tracetools/CMakeLists.txt | 2 ++ tracetools/include/tracetools/tracetools.h | 2 +- tracetools/include/tracetools/utils.hpp | 19 +++++++++++++++ tracetools/src/tracetools.c | 21 ++-------------- tracetools/src/utils.cpp | 28 ++++++++++++++++++++++ 5 files changed, 52 insertions(+), 20 deletions(-) create mode 100644 tracetools/include/tracetools/utils.hpp create mode 100644 tracetools/src/utils.cpp diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index f989644..cc9f735 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -42,6 +42,7 @@ include_directories(include) add_executable(${PROJECT_NAME}_status src/status.c src/tracetools.c + src/utils.cpp ) target_link_libraries(${PROJECT_NAME}_status ${PROJECT_NAME} @@ -57,6 +58,7 @@ install(TARGETS # Tracetools lib set(SOURCES src/tracetools.c + src/utils.cpp ) if(TRACING_ENABLED) list(APPEND SOURCES ${LTTNG_GENERATED}) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index d00d4dd..944e6ce 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -158,7 +158,7 @@ void TRACEPOINT( void TRACEPOINT( rclcpp_callback_register, const void * callback, - const void * function_target); + const char * function_symbol); #ifdef __cplusplus } diff --git a/tracetools/include/tracetools/utils.hpp b/tracetools/include/tracetools/utils.hpp new file mode 100644 index 0000000..70a06e0 --- /dev/null +++ b/tracetools/include/tracetools/utils.hpp @@ -0,0 +1,19 @@ +#ifndef __TRACETOOLS_UTILS_H_ +#define __TRACETOOLS_UTILS_H_ + +#include + +template +size_t get_address(std::function f) { + typedef T(fnType)(U...); + fnType ** fnPointer = f.template target(); + // Might be a lambda + if (fnPointer == nullptr) { + return 0; + } + return (size_t)*fnPointer; +} + +const char * get_symbol(void * funptr); + +#endif /* __TRACETOOLS_UTILS_H_ */ diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index b27f290..1915333 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -1,4 +1,3 @@ -#include #include "tracetools/tracetools.h" #if defined(WITH_LTTNG) && !defined(_WIN32) @@ -9,22 +8,6 @@ # define CONDITIONAL_TP(...) #endif - -const char * get_symbol(const void * function_ptr) { -#if defined(WITH_LTTNG) && !defined(_WIN32) - // If it's actually a lambda - if (NULL == function_ptr) { - return ""; - } - char ** symbols = backtrace_symbols(&function_ptr, 1); - const char * result = symbols[0]; - free(symbols); - return result; -#else - return ""; -#endif -} - bool ros_trace_compile_status() { #if defined(WITH_LTTNG) && !defined(_WIN32) @@ -171,7 +154,7 @@ void TRACEPOINT( void TRACEPOINT( rclcpp_callback_register, const void * callback, - const void * function_target) + const char * function_symbol) { - CONDITIONAL_TP(ros2, rclcpp_callback_register, callback, get_symbol(function_target)); + CONDITIONAL_TP(ros2, rclcpp_callback_register, callback, function_symbol); } diff --git a/tracetools/src/utils.cpp b/tracetools/src/utils.cpp new file mode 100644 index 0000000..56396de --- /dev/null +++ b/tracetools/src/utils.cpp @@ -0,0 +1,28 @@ +#if defined(WITH_LTTNG) && !defined(_WIN32) +#include +#include +#endif + +const char * get_symbol(void * funptr) { +#define SYMBOL_UNKNOWN "UNKNOWN" +#if defined(WITH_LTTNG) && !defined(_WIN32) +#define SYMBOL_LAMBDA "[lambda]" + if (funptr == 0) { + return SYMBOL_LAMBDA; + } + + Dl_info info; + if (dladdr(funptr, &info) == 0) { + return SYMBOL_UNKNOWN; + } + + char * demangled = nullptr; + int status; + demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status); + // Use demangled symbol if possible + const char * demangled_val = (status == 0 ? demangled : info.dli_sname); + return (demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN); +#else + return SYMBOL_UNKNOWN; +#endif +} From 53cf0803374b5c0e6470d262582598b54abe0c1c Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 5 Jun 2019 09:56:21 +0200 Subject: [PATCH 095/132] Add 'make tracing easier to use' as a goal --- doc/design_ros_2.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index c9f027c..3d7f58f 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -4,9 +4,10 @@ Design document for ROS 2 tracing, instrumentation, and analysis effort. ## Goals and requirements -### Goal +### Goals -Provide low-overhead tools and resources for robotics software development based on ROS 2. +1. Provide low-overhead tools and resources for robotics software development based on ROS 2. +2. Make tracing easier to use with ROS. ### Requirements: instrumentation From 6cce113f04825d2fd057ffa314fa15a33a5cacbf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 5 Jun 2019 10:43:45 +0200 Subject: [PATCH 096/132] Fix authors/maintainer --- tracetools/package.xml | 5 +++-- tracetools_test/package.xml | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/tracetools/package.xml b/tracetools/package.xml index 6794a9e..14cc17c 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -4,8 +4,9 @@ tracetools 0.0.1 ROS 2 wrapper for instrumentation - Christophe Bedard - Christophe Bedard + Christophe Bedard + Ingo Luetkebohle + Christophe Bedard APLv2 ament_cmake diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index 008337e..622deb1 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -4,8 +4,8 @@ tracetools_test 0.0.1 Separate test package for tracetools - Christophe Bedard - Christophe Bedard + Christophe Bedard + Christophe Bedard APLv2 ament_cmake From 33f227b7720f1873f52f40c16221f3cd51527067 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 5 Jun 2019 15:35:46 +0200 Subject: [PATCH 097/132] Fix linting errors --- tracetools/.gitignore | 4 + tracetools/CMakeLists.txt | 10 +- tracetools/include/tracetools/tracetools.h | 10 +- tracetools/include/tracetools/utils.hpp | 26 +- tracetools/lttng/tp_call.tp | 234 ------------------ tracetools/package.xml | 2 +- tracetools/src/.gitignore | 3 - tracetools/src/tp_call.tp | 234 ++++++++++++++++++ tracetools/src/tracetools.c | 118 +++++++-- tracetools/src/utils.cpp | 30 +-- tracetools_test/package.xml | 2 +- tracetools_test/src/test_ping.cpp | 77 +++--- tracetools_test/src/test_pong.cpp | 62 ++--- tracetools_test/src/test_publisher.cpp | 36 +-- tracetools_test/src/test_service.cpp | 62 ++--- tracetools_test/src/test_service_ping.cpp | 92 +++---- tracetools_test/src/test_service_pong.cpp | 77 +++--- tracetools_test/src/test_subscription.cpp | 46 ++-- tracetools_test/src/test_timer.cpp | 55 ++-- tracetools_test/test/test_node.py | 4 +- tracetools_test/test/test_publisher.py | 4 +- tracetools_test/test/test_service.py | 4 +- tracetools_test/test/test_service_callback.py | 4 +- tracetools_test/test/test_subscription.py | 4 +- .../test/test_subscription_callback.py | 4 +- tracetools_test/test/test_timer.py | 4 +- tracetools_test/tracetools_test/utils.py | 23 +- 27 files changed, 668 insertions(+), 563 deletions(-) delete mode 100644 tracetools/lttng/tp_call.tp delete mode 100644 tracetools/src/.gitignore create mode 100644 tracetools/src/tp_call.tp diff --git a/tracetools/.gitignore b/tracetools/.gitignore index ff6c930..a9f1530 100644 --- a/tracetools/.gitignore +++ b/tracetools/.gitignore @@ -1 +1,5 @@ traces/ + +# generated files (LTTng) +tp_call.c +tp_call.h diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index cc9f735..f5f38cc 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -21,13 +21,13 @@ endif() if(LTTNG_FOUND) # Generate necessary LTTng files # If successful, enable tracing - add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c - COMMAND lttng-gen-tp tp_call.tp -o ../src/tp_call.c -o ../src/tp_call.h - WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/lttng - DEPENDS ${PROJECT_SOURCE_DIR}/lttng/tp_call.tp + add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c ${PROJECT_SOURCE_DIR}/include/tp_call.h + COMMAND lttng-gen-tp tp_call.tp -o tp_call.c -o ../include/tp_call.h + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/src + DEPENDS ${PROJECT_SOURCE_DIR}/src/tp_call.tp ) set(LTTNG_GENERATED - src/tp_call.h + include/tp_call.h src/tp_call.c ) set(TRACING_ENABLED TRUE) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 944e6ce..bc4c018 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -1,12 +1,12 @@ -#ifndef __TRACETOOLS_TRACETOOLS_H_ -#define __TRACETOOLS_TRACETOOLS_H_ +#ifndef TRACETOOLS__TRACETOOLS_H_ +#define TRACETOOLS__TRACETOOLS_H_ #include #include #include #define TRACEPOINT(event_name, ...) \ - (ros_trace_##event_name)(__VA_ARGS__) + (ros_trace_ ## event_name)(__VA_ARGS__) #ifdef __cplusplus extern "C" @@ -128,7 +128,7 @@ void TRACEPOINT( void TRACEPOINT( rcl_timer_init, const void * timer_handle, - long period); + int64_t period); /** * tp: rclcpp_timer_callback_added @@ -164,4 +164,4 @@ void TRACEPOINT( } #endif -#endif /* __TRACETOOLS_TRACETOOLS_H_ */ +#endif /* TRACETOOLS__TRACETOOLS_H_ */ diff --git a/tracetools/include/tracetools/utils.hpp b/tracetools/include/tracetools/utils.hpp index 70a06e0..d5b6377 100644 --- a/tracetools/include/tracetools/utils.hpp +++ b/tracetools/include/tracetools/utils.hpp @@ -1,19 +1,21 @@ -#ifndef __TRACETOOLS_UTILS_H_ -#define __TRACETOOLS_UTILS_H_ +#ifndef TRACETOOLS__UTILS_HPP_ +#define TRACETOOLS__UTILS_HPP_ #include +#include -template -size_t get_address(std::function f) { - typedef T(fnType)(U...); - fnType ** fnPointer = f.template target(); - // Might be a lambda - if (fnPointer == nullptr) { - return 0; - } - return (size_t)*fnPointer; +template +size_t get_address(std::function f) +{ + typedef T (fnType)(U...); + fnType ** fnPointer = f.template target(); + // Might be a lambda + if (fnPointer == nullptr) { + return 0; + } + return (size_t)*fnPointer; } const char * get_symbol(void * funptr); -#endif /* __TRACETOOLS_UTILS_H_ */ +#endif // TRACETOOLS__UTILS_HPP_ diff --git a/tracetools/lttng/tp_call.tp b/tracetools/lttng/tp_call.tp deleted file mode 100644 index 4a964cd..0000000 --- a/tracetools/lttng/tp_call.tp +++ /dev/null @@ -1,234 +0,0 @@ -#include - -TRACEPOINT_EVENT( - ros2, - rcl_init, - TP_ARGS( - const void *, context_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, context, context_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_node_init, - TP_ARGS( - const void *, node_handle_arg, - const void *, rmw_handle_arg, - const char *, node_name_arg, - const char *, namespace_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) - ctf_string(node_name, node_name_arg) - ctf_string(namespace, namespace_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_publisher_init, - TP_ARGS( - const void *, node_handle_arg, - const void *, rmw_handle_arg, - const void *, publisher_handle_arg, - const char *, topic_name_arg, - const size_t, depth_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) - ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) - ctf_string(topic_name, topic_name_arg) - ctf_integer(const size_t, depth, depth_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_subscription_init, - TP_ARGS( - const void *, node_handle_arg, - const void *, subscription_handle_arg, - const void *, rmw_subscription_handle_arg, - const char *, topic_name_arg, - const size_t, depth_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) - ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) - ctf_string(topic_name, topic_name_arg) - ctf_integer(const size_t, depth, depth_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_subscription_callback_added, - TP_ARGS( - const void *, subscription_handle_arg, - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_subscription_callback_start, - TP_ARGS( - const void *, callback_arg, - int, is_intra_process_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ctf_integer(int, is_intra_process, is_intra_process_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_subscription_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_service_init, - TP_ARGS( - const void *, node_handle_arg, - const void *, service_handle_arg, - const void *, rmw_service_handle_arg, - const char *, service_name_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, service_handle, service_handle_arg) - ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg) - ctf_string(service_name, service_name_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_service_callback_added, - TP_ARGS( - const void *, service_handle_arg, - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, service_handle, service_handle_arg) - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_service_callback_start, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_service_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_client_init, - TP_ARGS( - const void *, node_handle_arg, - const void *, client_handle_arg, - const void *, rmw_client_handle_arg, - const char *, service_name_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, client_handle, client_handle_arg) - ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg) - ctf_string(service_name, service_name_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rcl_timer_init, - TP_ARGS( - const void *, timer_handle_arg, - long, period_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, timer_handle, timer_handle_arg) - ctf_integer(long, period, period_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_timer_callback_added, - TP_ARGS( - const void *, timer_handle_arg, - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, timer_handle, timer_handle_arg) - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_timer_callback_start, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_timer_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_callback_register, - TP_ARGS( - const void *, callback_arg, - const char *, symbol_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ctf_string(symbol, symbol_arg) - ) -) diff --git a/tracetools/package.xml b/tracetools/package.xml index 14cc17c..f44f76f 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -5,9 +5,9 @@ 0.0.1 ROS 2 wrapper for instrumentation Christophe Bedard + APLv2 Ingo Luetkebohle Christophe Bedard - APLv2 ament_cmake pkg-config diff --git a/tracetools/src/.gitignore b/tracetools/src/.gitignore deleted file mode 100644 index 2b36a18..0000000 --- a/tracetools/src/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -# generated files (LTTng) -tp_call.c -tp_call.h diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp new file mode 100644 index 0000000..cf4ecac --- /dev/null +++ b/tracetools/src/tp_call.tp @@ -0,0 +1,234 @@ +#include + +TRACEPOINT_EVENT( + ros2, + rcl_init, + TP_ARGS( + const void *, context_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, context, context_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_node_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const char *, node_name_arg, + const char *, namespace_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) + ctf_string(node_name, node_name_arg) + ctf_string(namespace, namespace_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_publisher_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, rmw_handle_arg, + const void *, publisher_handle_arg, + const char *, topic_name_arg, + const size_t, depth_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) + ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) + ctf_string(topic_name, topic_name_arg) + ctf_integer(const size_t, depth, depth_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_subscription_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, subscription_handle_arg, + const void *, rmw_subscription_handle_arg, + const char *, topic_name_arg, + const size_t, depth_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) + ctf_string(topic_name, topic_name_arg) + ctf_integer(const size_t, depth, depth_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_subscription_callback_added, + TP_ARGS( + const void *, subscription_handle_arg, + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_subscription_callback_start, + TP_ARGS( + const void *, callback_arg, + int, is_intra_process_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ctf_integer(int, is_intra_process, is_intra_process_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_subscription_callback_end, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_service_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, service_handle_arg, + const void *, rmw_service_handle_arg, + const char *, service_name_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, service_handle, service_handle_arg) + ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg) + ctf_string(service_name, service_name_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_added, + TP_ARGS( + const void *, service_handle_arg, + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, service_handle, service_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_start, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_service_callback_end, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_client_init, + TP_ARGS( + const void *, node_handle_arg, + const void *, client_handle_arg, + const void *, rmw_client_handle_arg, + const char *, service_name_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, node_handle, node_handle_arg) + ctf_integer_hex(const void *, client_handle, client_handle_arg) + ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg) + ctf_string(service_name, service_name_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rcl_timer_init, + TP_ARGS( + const void *, timer_handle_arg, + int64_t, period_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, timer_handle, timer_handle_arg) + ctf_integer(int64_t, period, period_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_added, + TP_ARGS( + const void *, timer_handle_arg, + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, timer_handle, timer_handle_arg) + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_start, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_timer_callback_end, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + rclcpp_callback_register, + TP_ARGS( + const void *, callback_arg, + const char *, symbol_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ctf_string(symbol, symbol_arg) + ) +) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 1915333..d1063b2 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -3,7 +3,7 @@ #if defined(WITH_LTTNG) && !defined(_WIN32) # include "tp_call.h" # define CONDITIONAL_TP(...) \ - tracepoint(__VA_ARGS__) + tracepoint(__VA_ARGS__) #else # define CONDITIONAL_TP(...) #endif @@ -21,7 +21,10 @@ void TRACEPOINT( rcl_init, const void * context) { - CONDITIONAL_TP(ros2, rcl_init, context); + CONDITIONAL_TP( + ros2, + rcl_init, + context); } void TRACEPOINT( @@ -31,7 +34,13 @@ void TRACEPOINT( const char * node_name, const char * node_namespace) { - CONDITIONAL_TP(ros2, rcl_node_init, node_handle, rmw_handle, node_name, node_namespace); + CONDITIONAL_TP( + ros2, + rcl_node_init, + node_handle, + rmw_handle, + node_name, + node_namespace); } void TRACEPOINT( @@ -42,7 +51,14 @@ void TRACEPOINT( const char * topic_name, const size_t depth) { - CONDITIONAL_TP(ros2, rcl_publisher_init, node_handle, publisher_handle, rmw_publisher_handle, topic_name, depth); + CONDITIONAL_TP( + ros2, + rcl_publisher_init, + node_handle, + publisher_handle, + rmw_publisher_handle, + topic_name, + depth); } void TRACEPOINT( @@ -53,15 +69,26 @@ void TRACEPOINT( const char * topic_name, const size_t depth) { - CONDITIONAL_TP(ros2, rcl_subscription_init, node_handle, subscription_handle, rmw_subscription_handle, topic_name, depth); + CONDITIONAL_TP( + ros2, + rcl_subscription_init, + node_handle, + subscription_handle, + rmw_subscription_handle, + topic_name, + depth); } void TRACEPOINT( - rclcpp_subscription_callback_added, - const void * subscription_handle, - const void * callback) + rclcpp_subscription_callback_added, + const void * subscription_handle, + const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_subscription_callback_added, subscription_handle, callback); + CONDITIONAL_TP( + ros2, + rclcpp_subscription_callback_added, + subscription_handle, + callback); } void TRACEPOINT( @@ -69,14 +96,21 @@ void TRACEPOINT( const void * callback, const bool is_intra_process) { - CONDITIONAL_TP(ros2, rclcpp_subscription_callback_start, callback, (is_intra_process ? 1 : 0)); + CONDITIONAL_TP( + ros2, + rclcpp_subscription_callback_start, + callback, + (is_intra_process ? 1 : 0)); } void TRACEPOINT( rclcpp_subscription_callback_end, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_subscription_callback_end, callback); + CONDITIONAL_TP( + ros2, + rclcpp_subscription_callback_end, + callback); } void TRACEPOINT( @@ -86,7 +120,13 @@ void TRACEPOINT( const void * rmw_service_handle, const char * service_name) { - CONDITIONAL_TP(ros2, rcl_service_init, node_handle, service_handle, rmw_service_handle, service_name); + CONDITIONAL_TP( + ros2, + rcl_service_init, + node_handle, + service_handle, + rmw_service_handle, + service_name); } void TRACEPOINT( @@ -94,21 +134,31 @@ void TRACEPOINT( const void * service_handle, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_service_callback_added, service_handle, callback); + CONDITIONAL_TP( + ros2, + rclcpp_service_callback_added, + service_handle, + callback); } void TRACEPOINT( rclcpp_service_callback_start, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_service_callback_start, callback); + CONDITIONAL_TP( + ros2, + rclcpp_service_callback_start, + callback); } void TRACEPOINT( rclcpp_service_callback_end, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_service_callback_end, callback); + CONDITIONAL_TP( + ros2, + rclcpp_service_callback_end, + callback); } void TRACEPOINT( @@ -118,15 +168,25 @@ void TRACEPOINT( const void * rmw_client_handle, const char * service_name) { - CONDITIONAL_TP(ros2, rcl_client_init, node_handle, client_handle, rmw_client_handle, service_name); + CONDITIONAL_TP( + ros2, + rcl_client_init, + node_handle, + client_handle, + rmw_client_handle, + service_name); } void TRACEPOINT( rcl_timer_init, const void * timer_handle, - long period) + int64_t period) { - CONDITIONAL_TP(ros2, rcl_timer_init, timer_handle, period); + CONDITIONAL_TP( + ros2, + rcl_timer_init, + timer_handle, + period); } void TRACEPOINT( @@ -134,21 +194,31 @@ void TRACEPOINT( const void * timer_handle, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_timer_callback_added, timer_handle, callback); + CONDITIONAL_TP( + ros2, + rclcpp_timer_callback_added, + timer_handle, + callback); } void TRACEPOINT( rclcpp_timer_callback_start, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_timer_callback_start, callback); + CONDITIONAL_TP( + ros2, + rclcpp_timer_callback_start, + callback); } void TRACEPOINT( rclcpp_timer_callback_end, const void * callback) { - CONDITIONAL_TP(ros2, rclcpp_timer_callback_end, callback); + CONDITIONAL_TP( + ros2, + rclcpp_timer_callback_end, + callback); } void TRACEPOINT( @@ -156,5 +226,9 @@ void TRACEPOINT( const void * callback, const char * function_symbol) { - CONDITIONAL_TP(ros2, rclcpp_callback_register, callback, function_symbol); + CONDITIONAL_TP( + ros2, + rclcpp_callback_register, + callback, + function_symbol); } diff --git a/tracetools/src/utils.cpp b/tracetools/src/utils.cpp index 56396de..8286bc5 100644 --- a/tracetools/src/utils.cpp +++ b/tracetools/src/utils.cpp @@ -2,26 +2,28 @@ #include #include #endif +#include "tracetools/utils.hpp" -const char * get_symbol(void * funptr) { +const char * get_symbol(void * funptr) +{ #define SYMBOL_UNKNOWN "UNKNOWN" #if defined(WITH_LTTNG) && !defined(_WIN32) #define SYMBOL_LAMBDA "[lambda]" - if (funptr == 0) { - return SYMBOL_LAMBDA; - } + if (funptr == 0) { + return SYMBOL_LAMBDA; + } - Dl_info info; - if (dladdr(funptr, &info) == 0) { - return SYMBOL_UNKNOWN; - } + Dl_info info; + if (dladdr(funptr, &info) == 0) { + return SYMBOL_UNKNOWN; + } - char * demangled = nullptr; - int status; - demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status); - // Use demangled symbol if possible - const char * demangled_val = (status == 0 ? demangled : info.dli_sname); - return (demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN); + char * demangled = nullptr; + int status; + demangled = abi::__cxa_demangle(info.dli_sname, NULL, 0, &status); + // Use demangled symbol if possible + const char * demangled_val = (status == 0 ? demangled : info.dli_sname); + return demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN; #else return SYMBOL_UNKNOWN; #endif diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index 622deb1..bfd77bf 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -5,8 +5,8 @@ 0.0.1 Separate test package for tracetools Christophe Bedard - Christophe Bedard APLv2 + Christophe Bedard ament_cmake pkg-config diff --git a/tracetools_test/src/test_ping.cpp b/tracetools_test/src/test_ping.cpp index 51eeab4..9491eda 100644 --- a/tracetools_test/src/test_ping.cpp +++ b/tracetools_test/src/test_ping.cpp @@ -6,56 +6,55 @@ using namespace std::chrono_literals; - class PingNode : public rclcpp::Node { public: - PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) - { - sub_ = this->create_subscription( - "pong", - rclcpp::QoS(10), - std::bind(&PingNode::callback, this, std::placeholders::_1)); - pub_ = this->create_publisher( - "ping", - rclcpp::QoS(10)); - timer_ = this->create_wall_timer( - 500ms, - std::bind(&PingNode::timer_callback, this)); - } - + explicit PingNode(rclcpp::NodeOptions options) + : Node("ping_node", options) + { + sub_ = this->create_subscription( + "pong", + rclcpp::QoS(10), + std::bind(&PingNode::callback, this, std::placeholders::_1)); + pub_ = this->create_publisher( + "ping", + rclcpp::QoS(10)); + timer_ = this->create_wall_timer( + 500ms, + std::bind(&PingNode::timer_callback, this)); + } private: - void callback(const std_msgs::msg::String::SharedPtr msg) - { - RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); - rclcpp::shutdown(); - } + void callback(const std_msgs::msg::String::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); + rclcpp::shutdown(); + } - void timer_callback() - { - auto msg = std::make_shared(); - msg->data = "some random ping string"; - pub_->publish(*msg); - } + void timer_callback() + { + auto msg = std::make_shared(); + msg->data = "some random ping string"; + pub_->publish(*msg); + } - rclcpp::Subscription::SharedPtr sub_; - rclcpp::Publisher::SharedPtr pub_; - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; + rclcpp::TimerBase::SharedPtr timer_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto ping_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(ping_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto ping_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(ping_node); - printf("spinning\n"); - exec.spin(); + printf("spinning\n"); + exec.spin(); - // Will actually be called inside the node's callback - rclcpp::shutdown(); - return 0; + // Will actually be called inside the node's callback + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_pong.cpp b/tracetools_test/src/test_pong.cpp index 99e35ce..4dc167b 100644 --- a/tracetools_test/src/test_pong.cpp +++ b/tracetools_test/src/test_pong.cpp @@ -3,47 +3,47 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" - class PongNode : public rclcpp::Node { public: - PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) - { - sub_ = this->create_subscription( - "ping", - rclcpp::QoS(10), - std::bind(&PongNode::callback, this, std::placeholders::_1)); - pub_ = this->create_publisher( - "pong", - rclcpp::QoS(10)); - } + explicit PongNode(rclcpp::NodeOptions options) + : Node("pong_node", options) + { + sub_ = this->create_subscription( + "ping", + rclcpp::QoS(10), + std::bind(&PongNode::callback, this, std::placeholders::_1)); + pub_ = this->create_publisher( + "pong", + rclcpp::QoS(10)); + } private: - void callback(const std_msgs::msg::String::SharedPtr msg) - { - RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); - auto next_msg = std::make_shared(); - next_msg->data = "some random pong string"; - pub_->publish(*next_msg); - rclcpp::shutdown(); - } + void callback(const std_msgs::msg::String::SharedPtr msg) + { + RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str()); + auto next_msg = std::make_shared(); + next_msg->data = "some random pong string"; + pub_->publish(*next_msg); + rclcpp::shutdown(); + } - rclcpp::Subscription::SharedPtr sub_; - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Subscription::SharedPtr sub_; + rclcpp::Publisher::SharedPtr pub_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto pong_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(pong_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto pong_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(pong_node); - printf("spinning\n"); - exec.spin(); + printf("spinning\n"); + exec.spin(); - // Will actually be called inside the node's callback - rclcpp::shutdown(); - return 0; + // Will actually be called inside the node's callback + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_publisher.cpp b/tracetools_test/src/test_publisher.cpp index a12c30e..886e571 100644 --- a/tracetools_test/src/test_publisher.cpp +++ b/tracetools_test/src/test_publisher.cpp @@ -1,32 +1,34 @@ +#include + #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" - class PubNode : public rclcpp::Node { public: - PubNode(rclcpp::NodeOptions options) : Node("pub_node", options) - { - pub_ = this->create_publisher( - "the_topic", - rclcpp::QoS(10)); - } + explicit PubNode(rclcpp::NodeOptions options) + : Node("pub_node", options) + { + pub_ = this->create_publisher( + "the_topic", + rclcpp::QoS(10)); + } private: - rclcpp::Publisher::SharedPtr pub_; + rclcpp::Publisher::SharedPtr pub_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto pub_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(pub_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto pub_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(pub_node); - printf("spinning once\n"); - exec.spin_once(); + printf("spinning once\n"); + exec.spin_once(); - rclcpp::shutdown(); - return 0; + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_service.cpp b/tracetools_test/src/test_service.cpp index c347b21..f44cfbb 100644 --- a/tracetools_test/src/test_service.cpp +++ b/tracetools_test/src/test_service.cpp @@ -6,43 +6,45 @@ class ServiceNode : public rclcpp::Node { public: - ServiceNode(rclcpp::NodeOptions options) : Node("service_node", options) - { - srv_ = this->create_service( - "service", - std::bind(&ServiceNode::service_callback, - this, - std::placeholders::_1, - std::placeholders::_2, - std::placeholders::_3)); - } + explicit ServiceNode(rclcpp::NodeOptions options) + : Node("service_node", options) + { + srv_ = this->create_service( + "service", + std::bind( + &ServiceNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + } private: - void service_callback( - const std::shared_ptr request_header, - const std::shared_ptr request, - const std::shared_ptr response) - { - // Nothing - (void)request_header; - (void)request; - (void)response; - } + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + // Nothing + (void)request_header; + (void)request; + (void)response; + } - rclcpp::Service::SharedPtr srv_; + rclcpp::Service::SharedPtr srv_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto service_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(service_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto service_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(service_node); - printf("spinning once\n"); - exec.spin_once(); + printf("spinning once\n"); + exec.spin_once(); - rclcpp::shutdown(); - return 0; + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_service_ping.cpp b/tracetools_test/src/test_service_ping.cpp index cbc5fec..43a63dd 100644 --- a/tracetools_test/src/test_service_ping.cpp +++ b/tracetools_test/src/test_service_ping.cpp @@ -6,63 +6,63 @@ using namespace std::chrono_literals; - class PingNode : public rclcpp::Node { public: - PingNode(rclcpp::NodeOptions options) : Node("ping_node", options) - { - srv_ = this->create_service( - "pong", - std::bind(&PingNode::service_callback, - this, - std::placeholders::_1, - std::placeholders::_2, - std::placeholders::_3)); - client_ = this->create_client( - "ping"); - timer_ = this->create_wall_timer( - 500ms, - std::bind(&PingNode::timer_callback, this)); - } - + explicit PingNode(rclcpp::NodeOptions options) + : Node("ping_node", options) + { + srv_ = this->create_service( + "pong", + std::bind( + &PingNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + client_ = this->create_client( + "ping"); + timer_ = this->create_wall_timer( + 500ms, + std::bind(&PingNode::timer_callback, this)); + } private: - void service_callback( - const std::shared_ptr request_header, - const std::shared_ptr request, - const std::shared_ptr response) - { - (void)request_header; - (void)request; - (void)response; - RCLCPP_INFO(this->get_logger(), "got request"); - rclcpp::shutdown(); - } + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + (void)request_header; + (void)request; + (void)response; + RCLCPP_INFO(this->get_logger(), "got request"); + rclcpp::shutdown(); + } - void timer_callback() - { - auto req = std::make_shared(); - client_->async_send_request(req); - } + void timer_callback() + { + auto req = std::make_shared(); + client_->async_send_request(req); + } - rclcpp::Service::SharedPtr srv_; - rclcpp::Client::SharedPtr client_; - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::Service::SharedPtr srv_; + rclcpp::Client::SharedPtr client_; + rclcpp::TimerBase::SharedPtr timer_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto ping_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(ping_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto ping_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(ping_node); - printf("spinning\n"); - exec.spin(); + printf("spinning\n"); + exec.spin(); - // Will actually be called inside the node's service callback - rclcpp::shutdown(); - return 0; + // Will actually be called inside the node's service callback + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_service_pong.cpp b/tracetools_test/src/test_service_pong.cpp index f09f761..29be746 100644 --- a/tracetools_test/src/test_service_pong.cpp +++ b/tracetools_test/src/test_service_pong.cpp @@ -3,55 +3,54 @@ #include "rclcpp/rclcpp.hpp" #include "std_srvs/srv/empty.hpp" - class PongNode : public rclcpp::Node { public: - PongNode(rclcpp::NodeOptions options) : Node("pong_node", options) - { - srv_ = this->create_service( - "ping", - std::bind(&PongNode::service_callback, - this, - std::placeholders::_1, - std::placeholders::_2, - std::placeholders::_3)); - client_ = this->create_client( - "pong"); - } - + explicit PongNode(rclcpp::NodeOptions options) + : Node("pong_node", options) + { + srv_ = this->create_service( + "ping", + std::bind( + &PongNode::service_callback, + this, + std::placeholders::_1, + std::placeholders::_2, + std::placeholders::_3)); + client_ = this->create_client("pong"); + } private: - void service_callback( - const std::shared_ptr request_header, - const std::shared_ptr request, - const std::shared_ptr response) - { - (void)request_header; - (void)request; - (void)response; - RCLCPP_INFO(this->get_logger(), "got request"); - auto req = std::make_shared(); - client_->async_send_request(req); - rclcpp::shutdown(); - } + void service_callback( + const std::shared_ptr request_header, + const std::shared_ptr request, + const std::shared_ptr response) + { + (void)request_header; + (void)request; + (void)response; + RCLCPP_INFO(this->get_logger(), "got request"); + auto req = std::make_shared(); + client_->async_send_request(req); + rclcpp::shutdown(); + } - rclcpp::Service::SharedPtr srv_; - rclcpp::Client::SharedPtr client_; + rclcpp::Service::SharedPtr srv_; + rclcpp::Client::SharedPtr client_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto pong_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(pong_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto pong_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(pong_node); - printf("spinning\n"); - exec.spin(); + printf("spinning\n"); + exec.spin(); - // Will actually be called inside the node's service callback - rclcpp::shutdown(); - return 0; + // Will actually be called inside the node's service callback + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_subscription.cpp b/tracetools_test/src/test_subscription.cpp index 9207de4..f8d1002 100644 --- a/tracetools_test/src/test_subscription.cpp +++ b/tracetools_test/src/test_subscription.cpp @@ -3,39 +3,39 @@ #include "rclcpp/rclcpp.hpp" #include "std_msgs/msg/string.hpp" - class SubNode : public rclcpp::Node { public: - SubNode(rclcpp::NodeOptions options) : Node("sub_node", options) - { - sub_ = this->create_subscription( - "the_topic", - rclcpp::QoS(10), - std::bind(&SubNode::callback, this, std::placeholders::_1)); - } + explicit SubNode(rclcpp::NodeOptions options) + : Node("sub_node", options) + { + sub_ = this->create_subscription( + "the_topic", + rclcpp::QoS(10), + std::bind(&SubNode::callback, this, std::placeholders::_1)); + } private: - void callback(const std_msgs::msg::String::SharedPtr msg) - { - // Nothing - (void)msg; - } + void callback(const std_msgs::msg::String::SharedPtr msg) + { + // Nothing + (void)msg; + } - rclcpp::Subscription::SharedPtr sub_; + rclcpp::Subscription::SharedPtr sub_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto sub_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(sub_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto sub_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(sub_node); - printf("spinning once\n"); - exec.spin_once(); + printf("spinning once\n"); + exec.spin_once(); - rclcpp::shutdown(); - return 0; + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/src/test_timer.cpp b/tracetools_test/src/test_timer.cpp index 2c787f0..2727184 100644 --- a/tracetools_test/src/test_timer.cpp +++ b/tracetools_test/src/test_timer.cpp @@ -1,47 +1,48 @@ +#include #include #include "rclcpp/rclcpp.hpp" using namespace std::chrono_literals; - class TimerNode : public rclcpp::Node { public: - TimerNode(rclcpp::NodeOptions options) : Node("timer_node", options) - { - is_done_ = false; - timer_ = this->create_wall_timer( - 1ms, - std::bind(&TimerNode::timer_callback, this)); - } + explicit TimerNode(rclcpp::NodeOptions options) + : Node("timer_node", options) + { + is_done_ = false; + timer_ = this->create_wall_timer( + 1ms, + std::bind(&TimerNode::timer_callback, this)); + } private: - void timer_callback() - { - if (is_done_) { - rclcpp::shutdown(); - } else { - is_done_ = true; - } + void timer_callback() + { + if (is_done_) { + rclcpp::shutdown(); + } else { + is_done_ = true; } + } - rclcpp::TimerBase::SharedPtr timer_; - bool is_done_; + rclcpp::TimerBase::SharedPtr timer_; + bool is_done_; }; -int main(int argc, char* argv[]) +int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); + rclcpp::init(argc, argv); - rclcpp::executors::SingleThreadedExecutor exec; - auto timer_node = std::make_shared(rclcpp::NodeOptions()); - exec.add_node(timer_node); + rclcpp::executors::SingleThreadedExecutor exec; + auto timer_node = std::make_shared(rclcpp::NodeOptions()); + exec.add_node(timer_node); - printf("spinning\n"); - exec.spin(); + printf("spinning\n"); + exec.spin(); - // Will actually be called inside the timer's callback - rclcpp::shutdown(); - return 0; + // Will actually be called inside the timer's callback + rclcpp::shutdown(); + return 0; } diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index 08973e2..18aae36 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -12,6 +13,7 @@ node_creation_events = [ 'ros2:rcl_node_init', ] + class TestNode(unittest.TestCase): def test_creation(self): diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 2c058b9..1eb4544 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -11,6 +12,7 @@ publisher_creation_events = [ 'ros2:rcl_publisher_init', ] + class TestPublisher(unittest.TestCase): def test_creation(self): diff --git a/tracetools_test/test/test_service.py b/tracetools_test/test/test_service.py index 4230c4d..0e10508 100644 --- a/tracetools_test/test/test_service.py +++ b/tracetools_test/test/test_service.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -12,6 +13,7 @@ service_creation_events = [ 'ros2:rclcpp_service_callback_added', ] + class TestService(unittest.TestCase): def test_creation(self): diff --git a/tracetools_test/test/test_service_callback.py b/tracetools_test/test/test_service_callback.py index 8992f9a..fccdccd 100644 --- a/tracetools_test/test/test_service_callback.py +++ b/tracetools_test/test/test_service_callback.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -12,6 +13,7 @@ service_callback_events = [ 'ros2:rclcpp_service_callback_end', ] + class TestServiceCallback(unittest.TestCase): def test_callback(self): diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index d689c8f..54e3166 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -12,6 +13,7 @@ subscription_creation_events = [ 'ros2:rclcpp_subscription_callback_added', ] + class TestSubscription(unittest.TestCase): def test_creation(self): diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index c0112f0..d51b2ae 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -12,6 +13,7 @@ subscription_callback_events = [ 'ros2:rclcpp_subscription_callback_end', ] + class TestSubscriptionCallback(unittest.TestCase): def test_callback(self): diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index 6716ee7..fc12b42 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -1,8 +1,9 @@ import unittest + from tracetools_test.utils import ( + cleanup_trace, get_trace_event_names, run_and_trace, - cleanup_trace, ) BASE_PATH = '/tmp' @@ -14,6 +15,7 @@ timer_events = [ 'ros2:rclcpp_timer_callback_end', ] + class TestTimer(unittest.TestCase): def test_all(self): diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index 462cb23..af9e0ae 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -1,23 +1,30 @@ # Utils for tracetools_test -import time import shutil -import subprocess +import time + import babeltrace from launch import LaunchDescription from launch import LaunchService from launch_ros import get_default_launch_description import launch_ros.actions from tracetools_trace.tools.lttng import ( + lttng_destroy, lttng_setup, lttng_start, lttng_stop, - lttng_destroy, ) -def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, package_name, node_names): + +def run_and_trace(base_path, + session_name_prefix, + ros_events, + kernel_events, + package_name, + node_names): """ - Run a node while tracing + Run a node while tracing. + :param base_path (str): the base path where to put the trace directory :param session_name_prefix (str): the session name prefix for the trace directory :param ros_events (list(str)): the list of ROS UST events to enable @@ -53,7 +60,8 @@ def run_and_trace(base_path, session_name_prefix, ros_events, kernel_events, pac def cleanup_trace(full_path): """ - Cleanup trace data + Cleanup trace data. + :param full_path (str): the full path to the main trace directory """ shutil.rmtree(full_path) @@ -61,7 +69,8 @@ def cleanup_trace(full_path): def get_trace_event_names(trace_directory): """ - Get a set of event names in a trace + Get a set of event names in a trace. + :param trace_directory (str): the path to the main/top trace directory :return: event names (set(str)) """ From 40349ea3cfe12cc5c66a7bbd0fc58083a0376601 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Wed, 5 Jun 2019 15:38:49 +0200 Subject: [PATCH 098/132] Rename status executable --- tracetools/CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index f5f38cc..3913967 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -39,19 +39,19 @@ endif() include_directories(include) # Status checking tool -add_executable(${PROJECT_NAME}_status +add_executable(status src/status.c src/tracetools.c src/utils.cpp ) -target_link_libraries(${PROJECT_NAME}_status +target_link_libraries(status ${PROJECT_NAME} ) -ament_target_dependencies(${PROJECT_NAME}_status +ament_target_dependencies(status ${PROJECT_NAME} ) install(TARGETS - ${PROJECT_NAME}_status + status DESTINATION lib/${PROJECT_NAME} ) From d93915da53c50d8c955e3ea9ada550506ec758f8 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 6 Jun 2019 09:56:13 +0200 Subject: [PATCH 099/132] Mark license as TODO --- tracetools/package.xml | 2 +- tracetools_test/package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tracetools/package.xml b/tracetools/package.xml index f44f76f..ca68c2f 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -5,7 +5,7 @@ 0.0.1 ROS 2 wrapper for instrumentation Christophe Bedard - APLv2 + TODO Ingo Luetkebohle Christophe Bedard diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index bfd77bf..075b068 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -5,7 +5,7 @@ 0.0.1 Separate test package for tracetools Christophe Bedard - APLv2 + TODO Christophe Bedard ament_cmake From 5011fb022f2f12617641e76498918cf0da3190d2 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 7 Jun 2019 10:30:42 +0200 Subject: [PATCH 100/132] Add architecture diagram --- doc/design_ros_2.md | 4 ++++ doc/img/tracing_architecture.png | Bin 0 -> 108257 bytes 2 files changed, 4 insertions(+) create mode 100644 doc/img/tracing_architecture.png diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 3d7f58f..8cbddde 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -486,6 +486,10 @@ The plan is to use LTTng with a ROS wrapper package like `tracetools` for ROS 1. * overlay it on top of their ROS 2 installation * use other package(s) for analysis and visualization +## Architecture + +![](img/tracing_architecture.png) + ### Timeline The first goal is to statically instrument ROS 2, aiming for it to be in the ROS 2 E-turtle release (Nov 2019). diff --git a/doc/img/tracing_architecture.png b/doc/img/tracing_architecture.png new file mode 100644 index 0000000000000000000000000000000000000000..ae5cfeee4653f68ab9298daca40752baa47e78d8 GIT binary patch literal 108257 zcmd42WmuGJ_dYy?bV&$^ba!_n0@92qGIV!$gCK~s4k6tg(jC$;q#!kPh=6qWd$XUt zpZe|RIQ}1BKEZI`SFAkGwbq2ItIA_zJjDQkK-e!8WWgZNqXG~Jkq!+7_yprB@el;U zO7zxz>uTpI?`-5~sp4R2W(xwTc=mlS5v%z<;rn_M>x_fPTtR^JvypQ|steb_iTuqH z#XJj!sg;$seXTeDo%HM-+cw9&bf*8%cJ@d$CG=Vv5BXh@B;Fw^4f(Ir;O}Uc^ULj= z>qJ3Dcm`2BXJps6{`cleH@7-5?a!UQ;NJJv9F{k8+({$fa3Y7^F$S(sLJ`<&Db5JQ zMu`va(S8R=N2KR-oFB^;)iYAi-)DF8zVH%Fz6$=Dx$tAR`VF@l{P0WX8`w-RMG*4V zeKsBXt)IAoN#Bc>$$NtY3+>A%iR~qdlg0wE!>1l=5hn>G+e%!Yz@#n%Q961!Gag&Z!BE~~LTiXIIwlCC}{hHc>3Z21cM&P%`k zrSoVUMJ2nLDk3pZH?lC^M26)?`!Uxe=f|Jw17z3vq>$-EKIDGlUPj14<2ee&;Iy*n zKtFNy`5HImn}lsDM}bye#>C(C3o}`#M&U=TUS>+Aqa-NC6G70r#oI%;H8*qYoNT}( zwa0?+zHlidsL{VNKB5@3|V)sCMA}Tx({&ZM)=Zygt$B&kl zvC&Qea!SwZ_s+9%Nj)4vE`^G(X{|LT!md+-Cr`SQb^B28&z>{AeLRdDBb zVL7F*lPIM8&@weTB--LP2~ze+G0e14Ckfs7O~3OGVeSF+bm_YeaaapnJHJ!kmk8vk z>F8E+{jxMbnMjqzcBY|vDs;0B$AGcHU(}ODi2y1t*&ODum1RHsuo*IedWn9S92R}Uy(B3s+s+Q zYW#cQtlLVqO#CS~hN-tzQ|%mX3pJAHj_X&HMYcV%o`u=oPYJmr*p(A6%Bef8oH zAE&PSeXpQZIE*&smv8u0l1y49d*1!oFBJzJEor1KeD~Vo&&oWX?F4xJJj<#WK=>X7 zc+7;i+Ctj!sxRT1mFt1x#7;qUQEJD*yxDr`M0i>j&>WKt-QUNn@JMBxpw$8+f(Q#y4(xL$I&mS}n6(8-H zSP&kcMl@8;^Kq}FAh#_?>ApEHWw#rQxt!!RuMhY1_ImNm?)`G4n(avmL;Wf{ zK~C?B0hWnjp&gFp&^th7`nh9Q8K*_%U5`FuLxQhJC7txx(m5>D{T;)4{+ryYR`|Zd zu&3PNuS&-CcheZuj`)_aRwrfWQ;gB@E@|#aMl!@I7B*kgqtVa&xcTTt+aW_DfiY2? z91_0_8vOU%o55qki!p;y-baO%Zyl#aFAC>Gsn^Of+h(!TjQyIivmyrSzcLgj6DKQ^ zXcm8!>^F66(9h0o96*b}gi;`}HL zHJT%iR;a?55^eh)&K;K~n?gnfrZx_!-Y38y)7#}roZ#ahLc0fJ5kP)T4tPI z?c>;CxiC7>kr1Q--{%P?k?f@HqdTv-uPBHWP>hBd@A%H;`(=$Ock2*I(E85erd;~- zSd=@TX8RQ}lcIPHl#j|KM3HNi;%)TV%)R+O*GhvK#OyboTHu)jYvv z^Fa~crrnr$sn#^*cfXH2AO~5~S3$hrQi2%#2hvg&Jo-e;YDFnuz7d-ulUR!trP!ie zT#L4f95U_nLCLV8NG=Ac^5qQG*uvzMI>Corax)i0ervL=RI1fPs4K(;Z*gComoL)E zgz|>guktDNomNJs>QFMy8{6u4T17dp{>-q&Yp+)jea3=dW2o3r+arMZW*WIKOxRAH zFbgXUmfT{Aewy=iyP~E3pl>MX3csb+VcjzOM;Kn-mE)67)xyu6%KN)S$V`T#o;WFN zt-4u1&-Gjpiyq*jEcnd%n{}TcAW!U3R2}{}Sn_e(d#m$)o#WqOMN+s)ok<~5`toTj z>Mq`@&YEFl;{oS+aB|wA1V^uwS7KC;#dc46FzXc^N6K_!RQf-@Ia+y~@BL$xQ$PHC zKZ;KQ>{K~q;r)vJq>hPHWBYVf)m-&ZQCkmsg3c&A@hZ2R;3keu_7ak^A;U$Gkn01J zwO?mV>{V}Ule`f($ghjCOZ@t@wJ0$08-mdJ% zxaVY9qu&G>$*&j9DY(+pztl(J&tw@;9>dDt@R>jN`e6`Fs9v#gTk2H$8ojNaGI>SV zGS+ygj|a;W8y1Vi>Y;BQw=$>3iS?Tc+79U*^TKFe1Pa&xHPhsghVZ}RQ9m1$+s;8ie7*B%Vo%Co}Uh3hP(=Q zE#P|3_g?3vMe(NIuxU)L%Gi_ddbgq>N0W}SN&I2(wCP6OtGfmxA!)StDuOGf6DQ*z z$fjMp(+$caiMZE(XiB;gXwFW*DL-GqeIk=JXUb1eBtww*oK{53NwkHrxA5|WIT8m} zg}3P4Ljp#iRh2%X6k#Rbh*#WmSk-u(t!GQQ3Wedlupx6`>YJ_pl$lTD!lDyWP<)L^ zDvJ56LZRyliGEXmqg$sZbTP5r+0;=)?3qO?zBF6StU?kVSxGa??O23%a5Bdlm~QH# zVWAS5Tfp|@`{r&v>8$YZmpQ>jok$6IRl=&aP)m{SeD(LB_Ck^tzpp4+bhDd|DP-rA z6+zmM+eSq%Tq@P#F3x-JmUcuhZuU9xp!bp_()N!)AS%#HS!qpA{of1dsjt`WQ4dC4 zEb`MdKWSo6TYd4t$(Ch~FZ*C>AX7zH6_1Z!^_k9}eF{AADUZqKgV3gG#0Q$@s$9P> zKPB#`&xI`RJoaqQN9ILcM$<;UT3eJi(|tx<7Dx3Y&xM!d5yqBfg6@$CshOk@Fw_GP z2{S>D{_9uGkid{Qd{tg(DcbI&1PUc;(SoEc`F}t4=eyq(16N!jZWfKIp)0P97oHaX zV^MV~3WU&!L(9DLI;?_;<^V7EzuEa=O$BD)Ip!ba@pB}h6Y+zi!LR=Ikm{M%=v=Ag zkXya)vplIkO@jXJCJ*ZsaslfR$)z2k8VjWz>2;%k|Id0X@*RA`dLW*fDPCK+M2R!x zTMqEh7DI=l$bxsx@69g9rr+)@jQ>XhRArAyR14hBkJg#gtq`#aSfeC1aE2U3Hkv}P zi`jw@d1sFGUu?Cf^86p02<;}O8;de8a{{us+paLJ zOIUH`acguiK&!D|Xo5sN<=@j()WgnvgB5l6sKXFer5|MkSDfwUihKnHyVOio+rcGr zz)!ygKL}5uN~-w%M7|XS6gfXXU-xi~^z{j~xxI-Eu}>)7qQ@6%B8q~9jyh&WeB6i4*9~4{$>Mz{xT@1G_bEvbsZqpPy zH01L1pu!^=aTFo)3A4)vJ;JBQBUQC2GZ=&P@neYKq4}C=Pwj_W#zcN}kt{L05>8c3 zJXVm+aHf1PMtpihl3x5g&1Od-F$goi0&{KRly{*W9G7vMWMCe*Ys+-od5N&F32^|e zzyajguH=mt=uphz&^emA;@bJL@i~SN;+IgPmNKZw2zGw^8^tsW?F79@wNR_%X@my( zJyz*D@HQc=YEhYAZGvwJb?p6$Yw;--{5b*!9hizGwGCFc8y7wwAa;#`65NM^7=*hn z;g3@QNOg5f)Lsd2SE?_F-wY3uq^J(EuJ6WJczKVl8;xJt+@{&VQDGNJrWBHoug!(h z&|d5X11fl8D70JAhumcqa7wJRLx3>B7Y6d2#Lm}Z$`gSk&}%V48<2y)RU-yZQXA@buGgt7!Whbv`Q?|ypD!{W0!k`}{m&~~%=3yI%uuEsn^E~>6+ zrw@|AFD5G5tVD$uTStMAnFY4anYw}j^5bS?+^p^QBMCjs0}rzOL{6P^FVm?ne^qTh ztg`1NX$3#a%&v17&wdewg8kIi#er3wc$6!0M6oDly{@IDrCiiwPZt7gavcw5M4Zu? z+E`x~qK>L32_47jh*xArA5H=FBOWAz6-UhEm*sC1Jh9SQ*Z$2)BLWZ(j^(MxxP z_?PPDLPeBqTIrwR)C1P1{R&!RL{c3O_S--mbQJQ{rNS%BfqJ(#=no7J+ts;leK%P3 zTi{dSWqpQ|L5YT}It{5u{mKZs#JXn;j0JCN!>Y{VPb|4qs>`P!GO>#w2;z*2zDMm; z214xgeLXFkTJ(n4#jgi9lnS~)R-S-f8eAc~wbg!uI>9Fjik&vPe6~Q#$Y|m37h%sxu+Hv&KtufcMIehxEKOW5l^QFicS#Tl(HZ5jP{*Y!r_XO&-6Zq%&R5&-8h%^^d?BEHFff(#J(Hbn2f|*i- z7+k5Uv*pZHMpy;6KMZWkaFN%Q+NU6c?tD&4UZ(K6R=%lx)ZlNT^Hr1%Zxc?n)^C+3 zS`a%-Ks<^wOLCwBz*cBeG1>C1M5ODdyb(cG6Ucd*nT38 zS{$alVz2XY2C?mRyK}qo@$vNEDqGTtn=Q)>D($X^ zKA3Dc>`?4u@84!7oyRiQ+2KNc>86gEYF{-V{1MyNF_ZF{=@9}xm2h;e91vxxTV~H& zl7wPK#vyQ208;q8^`z0%0{AgC?f3Z{GU1096nOJixT#^cb}HBw?$2{|hU_aDcV2^4 z2Do+IsPpIwx5o&@^z2E6cQJ(hIp90QfRQ$m9R^t{*K6+8*4E}h+~dg8v@1K! z(5bT(HryDDA7L_g;Krg=+v7AU6Qx;Aa};8$Kw@>@nM_4=Ev%vd)I}@Fgyf0WaSAe>>?2!oe0y{^-Kr55YBZkU-cnO~N>2f$y%Vv{| zy4B`h4jRMi&>|DC<z~6S=x=yMdX^VV)KgWH-OaJw|WdG^S2|a8!Xy@BF7-@pA!@7+40b7aF7v?kaoD8 zQHuheV!XGHI29}IMv7p3`4BXv5qUD{fx{qDY02%a>E)4Pp@g9zB3xpn)tmH1-+pY$ z1}7UPo9lRd{fMRe1!GwTbR=;K1#kBOqH_VKl|#Kd$WN$|44>*GZ0LoD%lb+(7njOw z!qcnlu8*>3<_9*X2bpZjPJujr?pzPE1)`d{(6ll0p@{MHvBfJjkvuJ+z#Du<+85ghvBX+M2Dcc2jPt~&tMem|97#cqt}P;gl%N)n zl+3fn5Z`#8z8nN!aJOpiUTGx77MdX^=;-~LJjnTSfEMJ>yejb-q>CtJJ(7+k<$nw1 zWW+C5aI7H>)HOa1B%3Gvah42Pe^DV^WiqTbH*_M7QqC+SbIQBP4jvpKG~El?;ol3}umY0Ij%ybE zDpC_N{jE&am{RyJ+=pDH;1DDmHUSps;!`25^lb@gg4a7Z)Ef7E43Hh?Q(;Epm$hl- z1tMiX5XHm2cR9FIqfgzcRZ;|oi?u2^a()4bO-DTTi zZg4yDcw|%*WoGN_UM%kEN3)w{LXc+aTsB7-UexEKR$V{ z(8{YU0j!MACK_Rt>|aAD?GEU9Oh`L?g4uWli6z*wAYqf}*0~uJ4m+$oWSW z_p!UU7@r&{&+t2>rh| zt4dMECT;`x(vg+$m0>iAsr_MBSD^JoS#(GH1l)_g-7tg?H?bU94Z0GX-)h+42nuP^ z=!IsKRsEbX&a9aT)%BYZVtAq~zF;kvnci)Lrx^PJ}|f}l@6V8wat&iybN_(UH;FmC8k zGbaJQAFe8W^dbu6&PndU5cLDHWC5>hk=WqWSUE8o&w5v%WtB{c^oy@704J6eX3=Y(SRncU$W8atd7O`R{9vrG-b6n z9YQRG80_Hy4s-i?_J90_o#6*O6M(0 z3eTe{fmD1RCgV~=5*jDz5IE)i)eipYm5>rmdj{cSRfAG!@~Zz-I~5^@II$nj<9)3F z2Ox%I5V5}b&9=oop0AQ3_oGBBkuvZ+VV~5?%j@SSdZo6gsx^; z@cNYx0~*fvairuxQ;)vlOO+JLe~R2rP?|Gq>>)Q|cTjX*1h>DI(^P!Ru?c|ivh+}~ zFN1_!D#x!ue)9q~HEc@$H^s5^Bv=Ai$cT$Jld`a?TsgNp{Ku+FOygf0a0-?Hp*7#MNV%v?Kv~t+Ykyn7s@D5@jfp4tHu~BL%xbdj;73U0 z#1F)i9)pfHH33QP5r*?+Wy|8AMTZ(2?2|Le`*%S?U0cQmf+oApU0f7eih9iO{h3OW z{S8>6QUi6OgU3*R|3NukOHWm)kMTl*t=61ZcQxl9pgWTV6M(Vd$_*UCfo9s{!hyUZ zKxz~EOdZ;_QvEz@EMi$oGHMl>SvtN+8PAZ{R&PFy?UV& zR>y?v;hJ@UMkE!?d8r~3&F;G*LRZrlM|EoEQwd;6MdmM!5V`i3QC6EQkMf|pWh+CL zWwrj_>vpB%`XUOq7)}#6YRme2(q?4KuVQg)HbZ2xwiZK)o~bSYHcjwJo-^NSP+<%I z`BwHGu`tHh7Qb)T08iXv#UoOMSv+U9csx-BBxA~ml0#V-g;Rz`Ywpo>JSc^8w&TE^>7@Xfe0{&~$ zV%&paVHjdWLd=|JYA9D}B>z$htH8wj!jbkLmLfaCn_1g7P`7&>(GZMW$s=VhS#~M| zuS;tL(If(hD2EN!R9%Q9Z?82UFO7cX|4EWMdm5*UtCuye{8Ndri;IhnT$>tz+W`g@ zcufAnW}&SH{TFsuKjmX~{yIB&^pO6MTG|r#1#+&GH(D-4i2XEI%?-)0XjXTgCI>OE zd|L;Ui&DaNq?88jj2)lmS=DCPV6l!YsF_<&V#Y}4N4cAcuh_=1gxcCT!&GPfpF z(3k;;cpSv5y9_+f_CX!2lw(MNll;()NE$_d&-29OckDvWBI4=3ViA*gK;O0)yiIc+ z49#}x?x_>nvp$PS`gHLFl6g%!N+ zRTHf@x5_JjO}M!JXn!XC;IrF6qA%N3J7j)a|<1t(!hhv*pCb& z&9pzI2t^1|DcIZsWfOVmNo@bf$R0E4d6lVGjzpHYw#6n z9U*e~FggStuN5zP1z1HCk5gvLSJ>Iej-KqTWn;zfoWd8|(o1`bK-Btiq=XF9uLr8@sBqZ2OvgJ@NqnNUo`==+X8!Fr@~dt0K{5ls|OU5O}?o zzmDmg=PIU@i!J&=lRN!nwHiY7IMV1 zWg_&fjfN28WziH(;#8T=bcJ?xK2$&6IUnxq;u7<=$#v^!wQkcR(v#xNd;($-Ypf!G zjy)6bXck{yu2;!58ko*TtN{fgtm|1&>Hu1{wW?1}<=Pf|5iL7^mDypZRS_jCz060* z`qABsJ#3z}CPD5TWRpc%OP(tAHb=r*Pq#8s)xHTOU~zi127^1vc$Jzd0{|iDX+Qp~ z17MC4t&%ro?(1|R-weO{QQ;kI&j#3PCx|U!zApvJ9ae8zz1^4@H6cQ`(Pr95PqhF< zoIm+A-dVOPquLgpzG9d30Wd9X(8ct^rYRuGBQ}fh)8Hy25=o{!h-FzowVe)!^rp-M z8!4(nQ>&QkwXnXQ^xqb@i#tun#a%8Id3dy5Q^^CSC5 zIAp?=4(Mj$A5&9{b8(n<#qg)R<{v-6RX!pvl~*W}M6Y{ux_LRQKOMeZ68(r-KyZ7T z+u$fdf`tQ^&*z1G`UQZUavG;W_3VIKt&{fnRSaa{D%gmR)$QWLTn|O%k|n%6A+J@b z;ybrQ9%q$?RFj$fj(WbpLmc;+dJxTw(U!$H?j=#)vkz=>v<2x}O_eU`v4$b`7wK zFY5gHJ$%Ec8^NC^1s58e)^-8;&smc6O65V7Gg)Ab31(iBABbiwG?T!#!&aaYcGxG8 zs}~$`1T=edwIy8u5^DJ*O&^`=&d4!KBl-g(X$L>+c|lIK-R1bDbE`jYeZ|qULY;|l zXUA6gwj&CVRWW;PspA}1q(wY<)23{Cf4=cJ7N{>SWI>ze$%lz_n_P>Oo%IZv*(am; z4FRz-Bv_Z$-i_4l27laH`JiF_NKRG$_QD$=&WkOK+~RK)MPriOJAsuEFf{doZuUt4 zjsy6bM-)v(!{G<4u3sh4j|5pkVmhm$U_DoxDZQdmKg5 zOjK2)k*DZ6fKOfXCfP_|FrJRt!tEI=OuiX9T2kS8 zs_&&HCQbuItG+LOqTbwCCec6*Q`-PMY}F_(DClvYrFyOPcT_loYj!74V3Rab3ezkMd7byu183@9N5 zS?FN{cw6z($OB-5=H})bb{wg(q!=+ zrc{?F&To4ippyB{3ZQSyML%mMn-T&vY4~Z$^O|wprm!0rLMqW#r_p2b4l{Oyd9g{lgQUjaI;^R z(|2UsshI-ua~qwvB*3C@%}q_;+OtpAv%!uS!rcU-&;%E2?Q|3$zo>sMcRTPw?DC-A z;lvDJO|>@3@$p26RHv0@%&&wNn%s6;Z6*s3b9|Sf-zk7HE?)wtfxe{-$pl}sb=i{J z=;l*cRqtWkLpeK>?}7CLOTbxqd0iU8#aUC{<#urWC{>`!mXQ<}w}SOy46n_(SP~4WwPx2;+(nWa z=!$nm8)W4{iAaV0$K0V%;1ixMC^X&{ka5ry|l+=_k*PDmIR zGE_f0tny#%9P^8EH#1ko} z7v~Wob@OFnK#EK~8AR*96iqymWhX6QIJG$sMcyPhi?C_)v;+M3{<8% zjhgb#0T*)zK8J$wX?%=!-;|wh#nnm$e>3a?N`keyHVTD!IANn0Kq-2_A7If-BDAz7 zg(u@B`9cNbid!|A|bprOI+W0fkza`lBf41fL|TV~9udly?X~d0Vr`02Bh1g6<F;*Ma)cTS~q8=m#8Sy;9R+30vo^!a`jBVH-sVb$n|c82{B>Su>WEV5&cl)1dj@ z!<;+jt*PcZ{PBG>Rsp?hTpZk)G#q++p#Ln#M@^q8FYOhAY&4WvO^7{5FZZrkx0lu+ zG}qt#gr?T8pn;WCwP4TXBl~fs6ks1EuPgNZWC54Z7zcBfb-%E=T>(VO!I}Tl@&uU) z9|IW*25afd1fl|w2B_>+=*E;T=GE$Ns*sRyJ3}PC&O&ys7w~C#npE^LH{8awKVElO zko4{<7QwSs>DohUMMc!*SO^7Qu2cc7$336`j^FZ|OfN-bDz-GQS&jUDmI1|EjIQ_P34Bp!cVq$$|#>%2)9AoSv=EU$X#^b6vGMHW;hq(}}H={H^$B!;i-1t4fzl zfLvt1Uh}Ns1Nu`Kz=&#+$280cj)6e@!xyN*waX#(6BW7bOf66lL^f-ze{l97YB%Xd z>bGN#eTO)JQ?P-5^dm2|esb$rE~kIvkf-V3tp~V++8&K9(Y^os)4<51&rO9#GVIbP z^^dO;1p~tt0$`=(JWm~~ulFTD>2b+E_I6g<}46hnWF!({;j_-k`4nd?Vr$@&-?_j-1k<@I7Xx{yR#wBUp|YMT2_g zAZ9~Wu-Lw-X_fBF%K96}yxIiLo052N1`un9fr{^CE*;yKN#qW^JWX{Q_R)={jlNo- z#W>z9J1U-lObKuud;!iAMHku0VE=KzQx-lEYa#twPN1C2ghHO-gi!*i8S|rcgpSLJ zeI7J&-G)vp$+C=irp~Xez7;?ZD^u)>MFcfdD)Hc>o&G*}& zBVt$;1nT(0GmZr)%;k;1z21rA zFjE8kQqP>y*6YC!aUS!II#UB?zj=a^kYU*K-$|Wk*L2Tu#(`8O3x#vKIV3LYattTN zMLP?(hiq2$Z!kG;d6~B69)(T-rA24iZLR^Dz63+v5uJBrUt;AM#6KVC$?Pl`e~U69 z3!QK>bb5uM86qVsq_-N@{?QUMMjCLhe;fCpdIB`T&A6g;4>|bDA81HLq!pXTrT~!d zi3k*W93f3oGREi`d7&D0WMhM7kvyGO?4Zx{V~vG-pT@(d8*`#?9p&FDeZg%MbE%3{ zbw#pmbnpRzUkP{%;{+;GOpKFTF;Ukm8&VN)3|0~oIb{Inu2O2eaY@nhqA0CH9Z_nPQ&FHpJV?mOB* zU?DtCL`&yt)4dB|K*FC7aR?R4fupWpIq(1HQ7@5A!CfM5+ml#fU8g*}yqxNaQL(J8 zwNnwmP)%}9K5P@_^9qP{xjI7Z->RWKvB#f8rUK;MvL|yBUbg0zAESbr-n>_hK70mH zb+n#gCUuR6nHt69zK4GBzb-LIgNKFEjEWd^sc{aBtW=w6^K1$KS^aoe`!kc`xSw!^ z+I%>6yVE1OQVQJ6nCtz|^H)E7Kin{OI3~v+W8@|QS0LQM6A1f{u^}d^SO8^k1IULX z5W=ICICT{dq#045O;nez`EXm~#|rh1kP&T$=e}dug&Rve-VlZ-w$Cc}1VA|^2*omR zU?fQEf6#o8 z0!EJNB@%b4>LrIU(tnuBzut$VR9z8+7YM1MDYJ`5=#r_+cEvScw$=Y z)k9eDCs_7@E_p}p<^{$8gIw1Q$N2NEp%dsR8+%OZ=!iQAHAn|8^v_blav#JB40K#1 zlV=duKSWZgppU@InmyXb3WSA6fOJZ3o>Ni&u`l64dtk_SK~U1l{i_wyhv=i=16;De zkN6n*LB1DnfRncEiU_14-Vp#3I_(llZz4!l8I=;Q^Q3yvm65(O21Zt%mwNQ2C;#7 z5!OL(f8A|X@EY4ZY@J&HGN_)YcknWQSonscankbwa#L@r?`nUW?H1ZNRS zwcm?AD8)4NIB$O%E=s-^j%Y>yl}Jh)bo8tUN2=U)hB#0xX8rkk0Z1S8m2I{38u8cf zyK~Y&F%a3py}!qP;u{4qQVco;L!WLJGo-+F(9PRuzvJ8TXPy$RtOnJ7b58LywrzWw zG!nQfK`aa%=Y=d&D`I*Wnwe5xBuBrN%0D^-f21s?8T2+q`n4Kr2JR|m09~$f27S2+ zkpDX<=$BsTlxanei2H*?>6ZxQ;hxtR#0cE9g+!xx&JV^3vDSmNmx7@YNHm@5X*|`h5zPex;dOV zRs<1PGp)@~=?`ZB41g&`N;$)VL^TmxkbFOW$nnY(L=K94DKC^x@W)D;%t4PqPmq!f zy0rlzDT)(%Ry~X@0s`VSI;;e$jdZU9D?|q-H`@Mk>_W7lY>81|V)Mn=^%@CKh*SfOJ?<#G zGc;uV^N~D^`7Kph5kX_6wx#&NUTi=d&S(d21XVzKz?9}Vf6@2{ z)Atid3llyp{HmYJ{)|OXoy@{>0bqfYcv0XZMZD!597>A6qS}RCX8*qOGvVEHdllVl z!1PBx`2e$ez)mMm3>Bb@x3KCQDHe_}C$zNv09|8Z-n zFUTbL@!?S(z+;2d9n)#f%ZKHEZIl}V1Rv1OLde{7Pkc#RFj`M=`9zvGiXLo;AO zSOu>NI9ZzMfdtr$>goF*DCWP=VGnV`m;kB><1j@ z5*K>q{xrD1?E6oxt5fYh%)@#S10nku=jWEj->#+JQ2^Wy2mzG>DJ!m}V1TFo_X+=$ zTA{+ja@9z=hN@OUMRxZAiPTaM{ zw{MtE@jn*yWdV{;0XeZvHGo7|dUpT&o`2md=p!MZdg(dQItO|96SuDxU2+$$vlT?H znt+GB*Ep8?9~aA%dWP7BQNSqXOB}u9g#oFxC+=g;@68wW_$@V>qm$zw9GWD)U+v7# zLV*fkxa^;4fBElUlK$rj=+G}1Qt$kKD4vL1sn1K^k)8;z&C@yM-r29Y0hhh<8+`JR zS^xVzKtP!+7{IIkR#%$y&I@MT?(&0HGI(C8N z{mFCX^aHAdkS8X`z1W5AoBF>zl?8RZcG)f43}C)&W&DucSJ+`S1HD6nlHa=J_rKY2 zwgyW2-#=>JeM6kqeAe+5zAqmve(ty5PdcV1kIHRTOgIP`{@YLd5;>pyi+QG(P zJJ;D68TWqFEEw?Wqga*HxEx^Tq`HLbFJ{~`q^F&bv_Y&*U_Vu6a`cgs$VFDFO6+Cf zzq^hEIg5X~(vW}j0jAi_Ze5^^|LMX1^ogJvLWQ?N;%k>LN!-?m3N>;VRDZiLoLMz- zzVUCxI$rW7a&w21kG9{G6C8QNvaY9O*8GxJmZ$70y(Z*RU9AHqi(kXhizIzLIHG@f zmby@C>-(NDw+Q$=Egh9~SM+{1HzMV;hK7tQia~s~6Z8UescR$Hp_i36qldfiR3-um zN4E9K$GCee=$DtXftY}mdDcj?-^`DsvlH3KHV4F!CPONUrp-5ubcuBVcLS(G_n%6} zeD9GCyNctJPA-su*#}XEb|GSNQOd;j3P#FiV%$Z3M4!o$n9r)>m{Di;k(2>%qoxhM z;E?029TsusD4i3e?nb2GackfJSn%j_;PYRB`M=CdY7T>rF7<9VF=H%eg1UdGzq_8Fl8#uFzwR#ZfU&ARz{U03e&u8f_# z4j+S3nF(|D)Kd>E%6G*1s!WL(9nq^u>E)et_CU zU>6Wx_BQEKXwK>rZ}91f4}5lX)D^F@fsvWGNyYy zTJTO^Ej{b}2@AvOI<1dncE!=}xLe(!{3g^w+oCR36&2^v%4JF z571smroA{=+{EiW;bDS5Q2O7fg!ADd8BQ|tY}mH}7drD_a9ho=P_RjV&aeG81o!oxzNv^RVsx$+>gYuXH3TK$XZA8^kzqud~3q{*^2Tzq2uA0I6De$%j-VMr@`|3 z&Ef&F9zctXU`Yh8KODav^Jdbtd#zf+(K2a5_3Z) zsyF>Y>t@4ls$A6Ef#O>uuEU|6>JrbDv@YL4vdned z;~5@&pYJt-PD4)O$6Z^b4s5Or=8^inlAesc3jtxg8f&Mtdn``td;o=_{2wL(uqlSv zSjVfuh%4i7EyAAbMO#9Z9_>k31mez34USid8Pl2Y$Ed~?t>@q5&z@p6pW(OgtZBu7>e^>>#c7S^@}%ud&1Uv{6lWr%I!?6Wgr^Ub$uI)W}On$en z_MJ+f1@X+udkb+QB2^`m7LCzY`l%7riKp^8y((PiIcAUMw7-XZfY;k~8I_%Nm(T0^ zHXdkY<}U#@6~K_GoEA8s6>U$MTGZZ-jZ+Ke73(9RS} zHfbOWr@~jU3;GtF2=c`a@#N+&@io!;DEbg`t4H3DC$DG$~n_6^S; zhO9eC2JG21Y_CpKE+L>AE%q4*XZZrN6~vqB^UwLBV^!o3U2-iWN8LgvxMeO~tA)}9 zCB&Z#r2L(wYPLzqbXo~VZH*zt9&&(W?+;GxR3Z@IiIVI z;K!M|=XWLS>9P3iA%*hUwNbt)(+v{T_j>$ATibIb{(Nll*TH?(DFLo@=c@N9S?2lH zX0~)!>%s0cjC=nyQN7h0TlovOU^|5y&@5Vg2Eg9mpTk#Nd%U$y#(_U-gkt3X! zmW5tOoC!rVGcb)9Ln4A#ov-puL*Ao@mvfkNa#~+Vd^_D~rrnHH>~4&t^sV)Cn<#;Kk!0_e!d#fm% zTt&LJguePVSUnphqf94HQU1R&09e!WOvR81pxO7!e_eW{|7Xl^N{t+ImC%Xzl)x7k z);v{#!89aTSPFofj0!3T{swYhs6MRVu^=+Z-0C!}QomN5MH}%u_oj*h;DXJlPG)>b zE3RgRTJzih!%O9l`HT7fNdO-lO6muZ0^HI2)MIHmZ|hZMw|*q2q|S#ayWph5D;doS zjo=m6@feTj)aW%g0D?bzD=`mUslgSEQu&*7(BXk-MWz~Xw-q*G8V+=go{7;2lC^Ll`YTTFore);7D^G;&HhseUGbv$@CmtAZP_` zbg8U)E?yk`o-zF!wJ^m#ec*UGl%J+P3dslnmDLl(|0g8?*Rno&{vGldP@SVlw7#Jb zIcfr~VAPt|T35Bn=f4ZqQr2hysg3eifUvHj%>ri|$NckBPGSzep6-8pD?$ZqfPEE> zsm^7^TMkT-&QeHMdp^v6|i!^&zEBScM|hX`)fkiov<_$O(<>Gma_-*pQVfc@V*m3l+DlAfYZo!>|{^=H0B+f8Ki*T6Rq0 z@O_B|wR^YxJzPO}<~PY6e}PwQ6Z6nhyng;o6WdKU@)RexP@C!XR5$q3A8Ta&dhw zGxqQ6;)aOc8?kxaF=QqEBAx~iG`>kVAf0nNHoQ54q5_Wofb9;K?6$70*!(i~ zvr*rsYIOCpe=ty(w5dR|PS7O2#2%C`WN@Sz;AkqU=^keIl-QyJ#pZp9ws=x3bnkyh zLlPo1e(Tw<<-D*UGNrfN;eL2VP zOA&w35?6q)!k6&=GH(9MFGCBwm$sxvvWZ{wi<_`SKG*lDF)o&umyD)Qemh#yxZIsN z*mttswj`xwce78>egpgOUVuY;lgfQJDm!5ij1c46$h-kr|JI_8@*J9sc^){+bvTS; z2`P)oQaqf~?EtE?b%(9X@u941q?ba^fwh0r{_G!BCLSc~;^O;B>GPXker4R&1347c zJLvm&U|3s+;p*{viXCC-&d8&Ie(krq8b}2>axUpHO{a=iw==msQ1hZC^V zI!^sk7aI*#FaL^khktD*^Vu&Qc%8RB#PPP9#g{NO_RXl+^*)~Kr{cv*a-G%peg2m% zz)~2!_$>KP5T%C!fTG{Fch$fGuAC^5gGR$xDZFP$fnY*uwV=`Tz(=n7`s8<2GAmYT zG)EFA%Dz92&VBClwxP*u{aKPG9*)ec*z%DOV&_g-A8~6O8d{1R8~eSs$bGI1@xFvd zoCHqojt7B%rXyFCduOG0^!AA;tX(s=*Jb{vesCtcMLJIxKAl^r zx%=0Vs5K31S-_gC-rX9uU70};>$XK8jbHAWJ~x!#3fm`ALEhK6_g=;BSsC7*?>U)X z!|cuLFBHaAI*Tl=YK~V=cU@ucxxI&63~4c&N1v9uV3cT2l@`}&Pu-PW+gojCG0M)G zf8TAYb?*~v%6OR$axrOP6 zm8*uCUBg?QJx=T2zI*e-;uZ}%b)MjRkHW623gTdQhuutjo$MQSTIpw)I#0%W1;HMI z2v-Zs2hug&O6uxD2yLPs-pVUrt*O@3uEpHGx?SylPf(&gHflHCD_99=x>DbBGq|<0 zZzwp{CN!9j*#1;K-FuY`m{wGKeO~E*Itp=UD%yn{%p+5gZnFUr1&?M<@%Ef9bIi62 z?Jd^s|J(CFB=JaSQ_c}B>+5cV(6$F)23xg+o;CCB&6hUj)TQD;>UWFc z5~Leuno@&Q-C;a1W={to-?s0xX0C!D4!Vl|*RuA`YVLu~nrip8b$96Y4L3H{ZBBTC z`(JjHAoXgDhPOW+IGexc#)N2@aDCq9f2txGU}fLn(6saLE%`7>i=Wx%b_p(X3gQ~k z?mHpBt*h{07v7xjOHho-gd~>DoT9=V_>T5ol|2Z?<{qaAjO2XRk?zQq&FrpW!$~{? z7i{=x=?qDUc8cnH-F7Fe!`!XLm`tkFwc%~q-qj+ceo}rvR8g$n+ICi$p-|~vw}0ic zKogA>r_B$O+EX{)b$tR5g9Zlcy*Z~J&Xhvf-PRZo$AT{M?W}$9c5PyeQvXZc^L+wx zKuT{I%hKL$+S2Ea`#&?>!iE4X7d<_F!cPsXh%OCz60x(Ap8@t!1H<~;v4fM?g{8-VTwa1mrbl_Hoc{qrgw{QntaiL zq^UNRIkLBofO(MV5nL4aQ`3z-a?m}3ME@kZ>SFQz^l|fzeNu(l$M#W`W}L;iu#jjJh`~f zZH%-FHZXMCOEHdzmp^`9{(&KH=mF$wa>Y^V1+cpf^IUutI6rGlu}7T*cUoZ|La--l zzsPu6Ud;`0eK_()wA$7RTey)~kv_ZE`A+B;y-F+3y({ZKQEUFZxc@$*`7Z0GQ&xmY zJm?m+jp$r(ZzlH1qV4C;MQmjHdqtY{_w65dM!V=KZgh@Y7g;zhrZ%D(1B~^!iNdg} zvOFvvednx*wmR&|zc>?}u>2#^a>MecPdeL{dVgxitX=;0s-|3wx-HPKZum@z>NB$i zcLP9e+*zLnk(}3=G(&@*c1wEfPFF4_cpAT=zPh%VCBZ#!!rS=L<4)yh%zrL4^b7v7DbuYIyOzeJhCQ}2Nc&(jn`Qe2M)k6Ge8a<-qV(91ZHTHmk< z99L2-Y4vcZ{48tOU9@X+t^*w&^u9~` zO=F7}nd*Amv3cnm~f;;PU))7u%(Mo)}wT_%6&CU2Ma+oNJn&01k&gBuPi3zZ> zmHm{DaveHeX{^3D`h+}s!c>?D6pI>kC4|3+1$%2oMd+bh1rDr#XqF4*LoVrWBBzh|z7!mQ8I+wnI>bP<=61)J2^As*+U~P4M~$9q(}jymCF{yjpYm7 zoNeOgdm@VT4)K8B!!7#n9bBN&ABZJ+X?eArq+IRXqv=w4<7_rp3+K!=LDaxY95{`b z^3@f8FQQmE=lFTK+1PU)=x0XK>V@NCs~hF8g?@Uc4=YqOiz}Zxm;1uvuqKQazY~-= z@8X-dpC#kESuqoi+PMd(oKQEa-xA~*8fHwR6&?(JxgD&xf?IdfDN^-nWv)gXPjV$B zu4#1lbPY*5z~4(a!Zt{iFs|}0|I}MabUAHc0RMCQnC3-69FH|G&j^4F%Ly->4Y`wF z2(;L}O?wT$QWlQ6z5kv}V)@noKn)$ztX5N`2>Av#*n}NrRIh9M_7vxlmZf61=C(-^ zo)+7FWQrl(Fy8*|HhejE&^rI-+bLO!^EO*>?G7b8>KsldJZjsNJ7>n1rfI8-bjF`< z%kO8LHUmr=?crQ>U4!^&ngXyx2y`!lr;|zv551ul44Q!o80)0vN5;Pi`JRuKu?}5N zoMD|k2iTtQBk&6$zWOWyl(=N)c%q9(^k_$4ixS$lw-GLNb~i! zhzXo|aq}CU#%><@`-!26%sT-kUe_I9ZnuLKZ|UH$7?XDUurEQ#vJ0>36`cjZW{YQ#+E4CYnsk%w_I9KP~PnqXj)nH-@r|tE_n8ugV)aB-d+bcTe#l^?WPK*3|iLe*hA@>&}we}(yW}b zldnkQFO$|Vo&XiNeq}lTy^6)uU>_S&?woyiBa~upcrIqH6YJ^?v-4&@WpVOP(D6_m zkb|Wokdt>h{h-OY#>4M0i-+s9cj)tb`m71ASLNP!W`LTMjg3N&B8Pcz7EMW9OLf8F z-fZG4!mMwG(ly+{;YuRFw@|jU;PqdYwZWExHPenbT7m7yDR*cd_2NC~1NY05mDR3s zh9o3#+_=s5kj6&`9FWUXrU9BAGwMe#WJn@emCl{-@HBM)L}cykb5)Xu=+S~4%e~Uo#LlV9*@>Lyol8M z3&iUbenNpzvyiGz9VLBkS7`NQ_5Gy%Ps`yDZr-{q8~(8*xuzV@mvOQU?P5E!QVTPJ zpuk%`_vnC#LvUerUpt-S4urz4qIbdmd?Z|9z3XHD2WArXtbU}(nWTNRJJ2O){Is8c zt}WR4N$liAxgp;ck$p0ososW9M8DMdwi6Nlz8Vg_(X2K^?^gk;R%9?$I@ z&V1T57V3w=&CZ2@#r0pGrm>6(gOFPL=`8En`~-Z|kQqRxRtWR<3+T%Ld(<2>wwEny zbCqI-pve$}&h6%1&~*k+89fJ|=7hzg1KNfDCd{7EXp)nb>YqZq=r2`|jl&hK6vo;Mv1IHRUJap1u}>JsGDWXINVsmN}wWGz(_=WcSj zCrujT*f6{PkJicO%y?5w@1?re%ZLjF(b)*L6gVR;1%IXnN{klbG~>UFV&P+-TFvBM zSK)5q9lQ~XL_i@SmulPh0bJXv-1OG2cHL{frq+e^5{IGJ#iGJeow4{;C1xt=yYi!6 zpg(jpMe0r6Fhde{G#kuQL=blogMLF&Md2Q&6L^+5hW}Bdk_T}{ZoL^$;ilrD{MNWu zusry4?z3w7iSwJJTQZc7bB}{k@j|CK?g=(*dzXtBQhpp;$`woySxj)6dyhdZymdv`S+y>lHk?+vkk)N{B6&c z^9KJzw)svq0ThXY1*7oVF>5BQ5|B^~Wd$KXb#{+7lqCsU9q-jGmW<2yp3LBX^o+pd zZ>Gq{6?A;-w$K|Y-7hhmMxn_SER^9C*S6O8ROp(vUsmWQ?nM7M9xt$uCF$O}v%RZ9pS;#j2A_&`OIeOpZO903{xV}5O+eY-*#m9X31DfWaVFW znJ|C%x=BxdF@Llvy<7V-)JK2nzkQsY9w z6;cYqe~@+t z6&&`E*3DOtDY)uiezTz0kyH&EGOZ`m`?YWF{W8IzV4fS^7Sv;v;wBowfPk8u3m__?&iFxLM z{%GF5>tyg5-iHrrDj61=63baU8iaUwk7$BlA;oBZ191)bV*TKPbI60$kchB=ykOoU3V4Pi5@Oj!+9}fGV?jZy@*Ik+#u;jIhoxymdsJ5U3 z>4TA!?6c&RZnhu;$%BcMk69<5{w3`lm0X|2{*=`K&^Ve*D|Nr`w^)9E9d0b_sR};^ zH-QQ+@M#VRt&hH0RbK9t4X_yf#=SWn5c)q)^ z0+6<4XBbJCi-_#zQ<&pg08;e0-rt^g`lC_&1j}YLEn6NroJ|@Jff4AN+hnJ$9~;A2 z$VClj>h%{(LEl&n18ru8G9@yN2U4mReF;d{xlM;D>km5!F1CxCexA=c^JQLBv7E=M z=(u7*vt?V0o9+VfIX;5bt=F6%M;^Ovt27$?A%?jx09W#*<>TB^p61AKEn#CyB6>DK z2%ieS-g+JM<|mHU*ayG?x#yQqd7*Tt(=C(nBBG+EJ0}{CXtB@EN8L1sfC=mS7GMUO zd-HqL!9go3pCL*8P-Q2vb3xfII7!l=;#id_l=|KcJy`Je1S)qK>UuVbh@roX>bQx?c0blro^d2YVP7>W}-qyxY+sGHN(TAz5K}x92+R^XLw!#QeBm z6sd)=Y9^9IPG)ygNsi|c*gI%_R^xhY$A8caCpR%$@kwRI<+u;@zA`tQpcA{ED6Df2 zV>rV<}G|7(&>Gn~|~QZg9D@*0dcG!{xRlbvoJb z1m!c{Oxy8dov=-44&QkgRZ^_38muT1ilKKw@I=g@66~5V-Ow3YPCo{c??N&{QrDq^S0=_ntoWM!3dDY1 z2+w*fQq5?>BEYu1Nu(vJ;5#6Y$;T0^U{8*n+e$czkbW-DEx*S-Ugv=Bv#sG8u0^cG!PCYHcyahMtk5wAB;7k!|NwQ2U4j?YOWM#$HwzG|(M^SfAzD#{3;wSiS%Umt&< zv+6bt5RLQ0QpjA-3gLej?uJ31W9Y_Xvo_L+1;dCcA)2I;`<861QF^4>e*?^PZ$+H+ zC31~J!@J_YL_4h5VngmBU0ao@>T<#Gk{*A14bytU_ipwTYL7n|$&D9(`F++fdAbTG zzgc>cTwSLJJ%wj3yy&l(N2HOw?*r&^s7h6b$t7z;@>Pnr$j2236-tpn-y1tY z5RQz;R_0Rp40#9@sx|1^IX%ITjJuE$TPa^*(=IiTTA3!VpLgCD(Bfb3i9rT$fKqr< zDNZO*Vo5G{gq*r`p@-0$zM_QHG{~3yjZP&kX;7#=3mq2PnJkmQNN0#>6$`=+@sV9A zUC|1?yaRF<3Im6*;S9E`s%go|e6JBL z-J855p_T*6mha`Metw$CiH7o%Pzu8;AZb1#gm2RJdUA2zbVKsD@P*eqKbjW>{w5=D*oI0;y_OTOZ<12X@FB) z(hy3?c0p1K@M3Pnl!f9Ws6w1sr-)Uz;OnDAKxx(YS~@g@-SM^H>NAobitros5Syuc2ek zg-JA&E;I=)(xVQe8dms7&HrCaFs+e%YmmAUZx{XT(nst>y2mG%j%ejbwA*o~`uR)2 z5{3vU`sqxAv%P>%Ym~H$tK=2xW+s^AzshoZ8T6g>@bom~?5M_O{lr8gA_MF%kD=Z2 zc7e8;pIz+D)+Kc5bhj`zeeZG$_=$~xPRC@*L0RFqVrGXKU>h4vOTIxxKB>mD8{UJi zw=bCkOdpcKleq{Rbz=CgB%|No($|UO$Z?nhzs2^Vrc&ont(O-lkgpIqR%8{f2*gQ# zlsY88EHs?8R?Erc{(c5LtbrVHMe%2wW^OceQkcKJB#mIBq1{ipM>3E&|J@5vQI`Xz zeu)+?C>QMDnc%{oYebBcNWbA>{G~K(*p=lSO0ED!7ufZ$#d=8>hq5={B*cp4MUi9m zdi4Z=pB#x%Bd{f4D$9jjAxrXO;KfS$2^s8r^7PEL!q{BX8i$uUjV@P@0<61rl6k+7 zk5ecreXl&3FHmC(i~LrqWBoF1YQ8o#f^cQnJZ(BE|;v-a!I-CwD(ur#iw1C-KmVXJ@{D`0mC@2n5?J3n)i{$ z+F5rFZnD4e3$Ra;`hjKeV_LOYNp^9`3;e)7Kh}gL)ypUUu^a=9qLKIgeij~tL=;CN zU7q*d5|_;=IAu#D<2zMYnSTp5qxu3c1hw4Jy%*>dU;+q7`lP(;L(TWMZJAvv0e7k@qk}0&2zop7k4fNNj5mq>2#d-0rE0Z$2 zYxCz%7J*V%VCQS28MW)V!NzlVcXxMJSMv27`P8CyuUL~05f`QM z!$>eao9vB4(NI$tuNr=INq)~D$P2jVQbff`jrRK~OzBjL>fWi}l{df&E+%`b;{C1& ziqmLhWE`fE)uIt*<-BMnf2sywQNbY5H~y-z-TuPBWRo*f33!X1^D5d>mZPFYBV#jo zXg1R>v67Ms$E95!uaA$@N4{5#kd#L4mIvlRPk_o-^u$TM-!uXmAOzbDea%F6a(MWv zBY4RPCSvW#L%2UsQ!qZk2ZubH+BH=6Ptze!Bg~WBA&@A0WwdOT-rgKbB8T$CGT&EQ$ZBEo(ON0zk&YSp*9JvU8+wNO_-Db$e7?1 zu}%mCA9i9VV{ziy-z@%v0}zHqVzK7+OpC0W3WY-)thR73&(%TgZM+&bY*mn}drHMe z?pgkNf!|{b9H8^XUNkj1hli3}4#MdQ2^4z9aT#C<|ECIAqQWx8K~o3fgR(0=rkfq= z@0I+b{7ud=2KeF~qK|=2>iPXSH)0w!Bw{2Q`ttExed<-olK-U*f*~|m$4wH*4 zOv!-^cozPsSqM^!j_|+i>p{1SPjV~KcAcqqrJ33h+L(Kmd41lxVG4cew#Q$PaKgc) zSrd3@v%YlJaBt~+UmS57XFlWYm_NR7a%tlvRAaLuT=>K&cw-j1{RyVO*y_Y4+l5O% z;f^w6we!8;la;=pwbLzq%k}=Q6vnG2=KER)1riWMbVTVL04=Ce<)p8&$;ZN@_u!^+&~&pnyRowZs;7g^>SH13FBbrv@Wpu3Gt90oa>u|#U57`6F3;oFlvtjgu-`~p`938g&4wKkKCgJ#!z@&S; z)*q7n689P5`v~YbP7||6Mz68Nq%o3c84R3m#nee-N^cB-Ul_@_dknoc z;q-d{*rRgH-he2F3VEHG%Y7mCLM`MwDw(C>icc3-$JqRjpS9a(il^BeuQ|P`e3uKO`uwIaolf!P?@3#y=a};{bIy&&63#+SH=Z0mIgZhJf6Gz(?wVLh? z+FAzv(MU}sJQ+>Y`cC6tFS}CD9UJbVR!)ZQlg0b`wbD%S6UGa@$eA0wol%K(p>wVm z$G;xgnji8S1rwsJF9Kb!7{ErPhOwtQpaFnHRIvW3$Ur{xC-J0J^JMSOQOL^-yn6ac7&tivsaYy zfd1LHp^b?GQ-gWq{#1#O(BxB-HKlEL@suQ<)AN){UnY`}X4FK^<>XKzmb+Pd^6L`y zLX(+dAv+S@U<*HY5A8yY&3!3MhbDO;kH_8`Kr5{_9t3M9VbaoR5i|LFQqL3d1$GY=82|4^WPitOe;Gc{cNF0n z)=t88RV;d43*0!@q?DLss3Pg6&4+Bp2h#h3L*Mtm@8c|cSx_&|$`Ku2@_8-o^eR-{ zYnZ>Z+6Y(uGQK|-@_ru$fN82y^&TM3o(q||vsv^#akQRry|Hau>ubq;4(Xp=Z@+dD zH0_OM+4O(pcz$(2b~o8TANxBN=)6wt*?2KX*CPpz;1dr-$U5{x=%}ml|(0s~>+rL}?x@(pvhynoB@3jG&yadt3g) zsRGE^Gv~9kRlfanz0o{XF7qCYx?aT+R?2oi%_G_$ua8Cw3UiLCkFPD{3+8j}b#{1d zX<19JOmWENwCmwh`x1QW?q|oZBQ!^! zNfG~1k3BJCpy-Cnv*m^ikD)8&?05SuaAvpWLX>^o{cwm@dp%eU169*it#MxS zK~XUO(J+`EQ`8AcxtC%{Z{>1mKck5M33kGezSk!0-7HF|Haa4wU@Gr+;Sq6I^ESRC zQsA=hiOj;~J^XYV`MRcng=|&I`f9M`L+<1c+H5Rg;FqiT$j(xC1*1(k2@2tFKTRFI!!&*sts}h z(bgm?%7d4swnP_3{_AZ2s}}!qvhU=2#eC2w8RCe0R{cVcMsFVB@)+j1dFuTxCpHJO ztW!jMEcQFNW{Yd$hVH-jIvp}_|iRlO1jkddp{AJ0;@xZ|veX(dI z9`E9(H)^%-FJqFl;NNd3;159hPG>j=!{-py3IPB+&Hkmh&hE`{}{x4wP}2Ue~bjM0y5*)xI_z%PBR}7A1M=0gVlg`{b7Gy zR|*HcQ@INqPnmINdS>U(mvGL+MU!)241Dw4ff_cWQABP!{I{s!lXpT^90^_DP& zI&OILVI(*;F!CC$6^UF5buub9Uk)Qva5Roog&rfdfZMXVn&HuU!F+p!OdCk*!_=YC zz=w;jtd*hrs(vU<5Im^rgdd8opj99Yvy&i%Q)A6v>%J)!0X=?S{OW$7gG{2*%tXB| zwz2=3jO>DuRx*sUShJF$vM>Ibg~g@#Q55p3ZJui-Hw#iVz2`DS9Yk7vuVE=6U8qlw zA>~y6s5uLYJd8t)0^+X0AEkxvZuTU`9cZD6_5?jvz;j~_XuKcI(IwKpp^H&ZiIZf73610@(Rh^q@B z#@SRE_VS0s^7l2Wm2Ld07J+6vos^2u$^_*UzM6{y5#7}I?o(c-jp!Rmb2WPNI>VvIo0}t!vMVq5OZI03zT>Fq@Gu&fBxIvI!{fG?=i3bk( z5$2zuO!x(w<&Pw}EDp;FZV;0lJAgN|ky>JUtZ1SCi=o0ieQf`eV)`KtQcRe2@n63rZ2e&r@u$x}IzR}p&_{BILx4s?9z;qQdm2l4VTu1w$p`iu z|0){q8^~&L+hC#}kix!#@cwn*e_lJAj}Fe|A?;&upItGTXpP1z|8fnm%_6R14MQFY?YGJ@c(k05>wjLDiZ&3Iw|rV z)>AbC-;?Y@Ni=9sLAGFJaf`D-QLe7svAF{&43nPd>sVZoG9ZLOI%6W-em}hqeDgFPA z%mnyGgh5ncZja{>Jcwj@?v2{fZt0&=36*(^2x@Q~)2LDM3m~nikWds|rIJmX|lKHD2a?A_`~| zd@IM-8CDqOC!Dcjo336FWsJSUG5PqW!k7!cP?P?eP-h5KX|-K$4_txNpHs5H2)jcB z&o%>+>~1CnjDM>|2=_eiLRjE~>?#>?hXSMVZz1XiJiS8Gi1>+^Z7V4_NIb>1TJHB* z6F=4N>*`7N`{FRUWrpFMBW$r5nj+M_8RnW>L&nj5t&eY=(fm_M`t0EZ%I!IX}w2t0blnXqqr4t$-<2 zQ+0ZGdo3Uba*!ejobhkCu*4$LO5 z(D3juuMep|E{A$#p@&D$O>LEvxA z`=z>WIX4=*S52RUfm9vqant-l0ZIXOI-8I0guwI1dbs4L72Qw_eNbr*i28SJpqde; zY?1+XD%*5Q0+i*nzER1<4vS}633%KB+GDg(bRJpCLd#RBoY+`c4&Dk2H){lDFpRL9 zM~{BgT3lT{&B&l-W0$S_RHFJq%HRw5|Hob}EImeLr=#rVVM8Wn;2bPs3gG#Za`K3S z>d+@!U_xTl?Z{H5i8>E>6h(-#`;0Nhu_-6V>KXN3z`T6;#j22y7ngPR=H?Z94rc-{No}SY? z$3a(&K74t3YvJRoY$hzYzMm4Px2vBmbUv*2t#dfk_pi4QI!~nwRFs3VXSzNc-X~tS zqr0uhPLgwXzAML4k~?My7bZt?DJ@coZ2TD4r8jJLDvexB6=oP1n0(w zXuqLW0>VG0RyekWK5E7qe}_mqK~}T7iw(OG{g%g^Gm%R1Dj|b*AAD&fK3KTlzp%Vq zHeyuP$BrL@xV!J3o|h*o&$q@!Ak2ss4lc|bqT}uDZ6IW|B>L^$!SS(kzX>}wxAjWb zD;4W(U=)o&0jt|!DwkGTPZsK=UO46skW3zIc&-cDz^C1Ha~h8f&cwp}7Ts!Ev6SmrJEqIR&yM@_C@rgM^dqCyN>_x8T??ZP2`)Zu^mN4ANTO4&490y7u4zgagrk_HO!sYjHwp;HE6gHeD6_HMx2s52~t6EI2P2O*vm< ziQ#4DZPA3A|b^uFE3Nr_XL-#GNkfsed}9mgov`PD=42jxtI!2 zUMVR=3jm!`1Ui-e%@P(C_9J)lqInu7B~39orSAzK!M$DB1j@I|0C(E4Hq z>|PdUqE3;h96?N}t_w)8o0}W+gjuBqja<@&{MExo^f6Fio`td(hP3Nn4l(@{VVB+B zlHAtgOhkn|4!U~VZNMr8)>jn1-2d>JPy{VCynuYSo+#eSfQu(0qKuNF&5>6G;9^W9;U6 z?fMZ(!%i>b-<)EKO%|D|D+je7)oIBw|5RmgTJaT4#1HAv;7r`zZEkL+3$-IJ6#E8) zON@=p$tL3al#6PLO?+?N4iZcGT5fx20x-o8FeR*grka*qt0UxQEjNSKIxIx;WEeYW z)!_1IwHG&}gDfzEy)~0h07X<(^hCgV#b4B;t^oLNKh~GlQ;j*1Mk3_dWqjg*xSDo- z)9wBJ`9Tx*&lQtqSa5J~s1iK$`IusKdU4RB1%vQ*{ce2l47q`JRE1S`4=!b8EwWSe zqql9Hot>ET7sGLrW^P);TeN|S2*T8z{FFp;y1EPY^5IbNvPr@`(4ponld4K3Jt@DnpuS^vMHFwFeU_3Ty zw=FmOy_xtp0cSfj6N(IRIYfB)r$CbTnC6fiB4a)QAJ9qFo`~W{5aQ~1=nuU ztdbWP;YcoCbt}>LLEP|`>}%KHOD?y6$Fo@%hh*a3+}`HnhlqFcXkj+X6xGj!0&qE? z`g*loYl3*3eHZwy24!UdIMQEcocmGZqH>9Evatg*3dYzAzX35gKhk!rd1gI4ygtt5n0PUljyZl$8aA z$WvQEftDy@v{YLbTA;9ANGmOVdGjNWH`AayvZmCao3+ht=tt7&F_0&(=4N53)0W7` z0HOwX#B}5<%HUdGNqvC;tt{o=15Iygo4-aT%tL+WZjU)@Zk@ zE?1+;2>L_>e;bv78*KufO#yQ=r&n0wdtSG}6|x6D$2u_1k-4K>gb#Q^2f`xsvC$-| z+m=w+zsuA)y7Id@ZhqdD>a{9DRCl=&w4CRBZ}z%-d|bs^v1z?ait)=zX?=M3^XVT- zIiDpH5EA>09zT5=JwohcC25}6_nrj+g`|8r1mL16F<#{K#xd)3_x5gkP}G7a&PIbictQ<9R;Qj;BO`hQk}3udYyI~ zwXhxk|M=V;_#Nx3bbsyc26}~T;3`V8O%oZgWf1GSVvx}&piW(%fDg8ik~4;o0QD_6 zIXZd)PG%+xWm08`ax6nwd~g~VXx{v zyGzJE4FN0!PP!4n>y={kJ7A-HG~>5~SJ+YGY~Vq0o}P)NAN~3BxAVFzW~sI3l3n zptBE9H-A*UE5eT-1Rh^k3`65>c=M8&)XQ@%V2K0U_!jkv!8CVpgtR zC;&X)=V>uj1|G&@U`%Y;aG#36U=FeGR%Xx&0VtFnY6n_z`o0M`pZ!4B$}>$^@tA`w zNQf!ChjDnNJW5agd^Pg5n8J&X33k11YWmm^SqAK&reKQOi>oWQBHF-}{IgMZMoEQe zy}Z1=GK@3U#J)_3Ekd|T8>dG_dU`s^1ao{8J5r=lU2?W5Gi)_|sb*VkUS5u7jZE+Z zMtV(=(`RJ!+3_OHG~v4kUZH716TjtKOtGV+b!22@=T)#l@m|uqX(h8#z0jJo2rs0= zD$-9=0aJFRTmY+22S`ci>A5+l#(RKr1J2kQu1rk@3}OxiFiXY*Y+T&k?>hjF_v$m+ zhS816pk;(ezOyrzg}NzXuDU8K?|1^}K= zIAm~e5FLO8b^tGTA#q3czH6VE(^RP_+;MO`M75in_XKq904SrAQlkHV=_G zGnHL20vk^Xl;DBg*j=jPfOHex)n}U`Vu@{LnySM|LY6Vb zUYaJne<^L?h5_OOn76_T(I4LDe@O#!Ws67fPMHXp@COXS`*Ee*H3Bf_6>R6d=CCWS&3>kl|fR@ zC;(dhCj*sq52*!1?wl#wXy^~$6gUty0fNj~|4onsSw`>MQi^}4(ZQ1wXmc=JsY_wQ zX-8?WReClD{T2_pX~)B=jjev~ug^*hx*XV6MMJ5hq!cyyi)p3zff1709)fQc1tt!} zwkDYZ_T`%XbfZ=hzS}xy5bE$-zv%JB=dl#zDl}>%*?84PLCv@>1(oA_Cxlj z-<2KAz{uOVxH?ZdKcv! zT~QSDp-lIxBuiVTe7J1R0-QU1f%#l}qU`jqE0--R!}& zouNh1?R}WbZ|?T!Xl-~MvtlQi4U^+0h#ILppCYF>hW@+&JkbmUFZhtI0@DP|@QWCL zCVKf#6@g=t297C`xD7~aejY2cEBpu3Do2C`-3-;^w#_iT=Q z7>IxhdY&-laLBf{4*DH*Q`*;3HUc=Cf~P@=41*N+16lV|=}Eubf9HkJMbe&mh(X9# zhQ%OW5KVjA@OM17>+S9eC#Pt&&*$t8D5tpcf?qSQ{c7eswcK6Pdbe}Jvv-5@_0D4K zRX6Ow@=}Gyw?=EOqS<;so$P0?8I`PDpRm2(6K^_{QOGjWyD&KT<-AKk`T+ql~TdHx!M26qyy&`CzeNYHOzX=ox+7uL_OxpSrUa+-K{CE-w$BJ>9+u)IK*o z&R4A^%`Tn@+2^_oRS-xdO%rt+c|z-JT-uu)8^Bx?3k^tx(Fhkd143bX^A6-TAE1z8 zjIed@ro5lKuiEkI5)3B*$AN8)5HY4_v`JK?q8k0ksy*#VG zEMu1%^nSg0bi7I^cZS`k+cgmBm%?D_q#p+^lm~3?EM3NZwb${S)!K z*OwIZ;-aEyE`sjSOe*+LY}xkf+c}AFC-_^x6OsRit+#-xvhBKsH{BtrAR!{%9U>sz zqO_EBH_|O2Eg-!K1=(~E^%iIq&zp-#I@684h8{eP6L+t~u9=32^%3 zxB`Inm6URnf71t$+~pu4YSOBI@JYu*VEL}F?Io80CoNf!yv^-c-ZlL(X&LmYTbG8w zIMY#qV-w~hP_~4WtkCP@7ZYB^2sgu)CvwLPCGp8?Ih`+<|8;fodd-WCUb&Q#oRw8J zYR_P0>Z#vKX{M+|8>!O{LH$m0@WW#b5k)eVp&QjYH&LS7-L93x6XDv53x&0wL~W`a z%cJ<7o#i)EwWc~TE)FDhKZvNo!9x7>#u*(PteoL;xDbL{Jlqd@j%3ekhZbgGcVOkC z$F_L4|Kh#fztMfQo@7#*N>!^;Ji{*W* z!J;KX_3TDodXoLj$fIevy%TeF#en7}I#XHq2^BMbX!;5(R{CD^>F@CoY zcQ3D}S+5~xEEy#=uDKxblZdg^lWo;({(_O!gmq=2`9Ikd_>2Ds`ZS~KdJM6#g0RO4 z5qK0WGB?hQ5LbwRljaA+Po@4t`D)+IM9tS+;>k?QeaHNJn(CZxaP=*CSQeUIllmdQ z>AjA1@|?Z0|6*XBva(uX(=T3iWx>{U>VxyNo?kpHG27vErNzD0Pp8PfjBU1zDqU3H ze;BQ*6-|#!s&6a#D1JeY5!QbOjaq8$Sd{b-qZY*yrX-QPsa(5yfhu}=)ZSOay zgfSW@ir4t+ak`H$fwo6HRzb$%-GAVF-(y#Vvivb<>do11aCx^U96TEUY%bk{t1Cf` z=f4Wca8+{q{a-YZv1bTj-if*&occ4-w;;Wd2(1LGQ@h9`4^&x=baJY$pPG^R$3ph# zc#A`ya@E}wCX~7V&IU@9A>G;#BUb75mLCe|jef^!;i{XAg1OIbLY@|Pw{z-^M_?T4=H?e&%?Hd-~H6fgMc0uvV>QUZe29zj-7as}ju z->}swQB}zkX}N@S|0WY+f{#g{$kX`IKR|DxD|%3v!|%jftw4hlf%PX0bG_>7H;Q@O zDSB-hbfNY=VaVyDaGU0t5o1HQai4FL;Y94$k_R`!r`;t6?~M-|mAW@w2B8OiiMio(v?AxSmEg^ARD=6%!j}W)Lqy$(wKiAXo(7tTW9ahp&JLw#1qopTha;LL{m*zIXV|zk< zcaV=^n5N)qO#kmS`gDr1R*hwO5gOQI5jz%hgdkLNo4LD1OF1w0FuPVqS>eos47;ld z?MrRrmcsM+`B=HN(N<7N41F&6Y^M{b1K=usf+E`unVj#3P_H>k=w};s5m-Y8T4(jd z137<`*jzwGuYGZmM3(UT&ZB-%pZ$^Q~7Ya8v*`=Kt(9;7Bqe#+hi_ z;S|}Cjz!CEeI}#oeFD3RG6;Xf>}KpzYIa_mgzPWMM3dVOW&>^J#U<^rliBOB%IlAy86O! zvtjY`h8;PH-!BaCFuNFGEjm@i9nE^d69y;Z5%qDb&$gaDuoNNS{^+fzN&Edeu0eOr zjf6m!1C;%cv%db%a!}W;ADdG}cZ_)`WPh7^Az#J^QGx;sxf~l9PE)^vI&EZNP{XV|THfMV`^fCI^r0#RkmCx|# z>+ys>q918E%vrg9s%nSKpL1Ac=>#cU*_t2&$kbc<@98Y#Y(DRyyMKUY@VyhtRY{J{ z$AVFxRo0y-G)ALRN?2GhU=lNa+(Yupl8fjn=TkY%XG^Jk*d3&@bnAB(`_vpanJI0g z$&dg1;;OUYZuKiwxyu3<^lImEh1pkmCTr8a^JRZ zM@fJM84R3wwrKZn*2VhwfCD2Xkl9v z+k31%nlDG}J+{f~?)B*DPUwe_ch~KMTGi|LLwa=>nb`UqNlgA_cWqP(VC$fI{trfbgehrU;|Li6`IyWO$pyj7a$eMnUjRBIZ=9 z#S>{^`;sI)fgxOhl+Ac@O}p0ZjB=wmmGol5d8SS9&BjvNFx?Zcq2CtQp2p9wyeXk~ zJBWNmGg+cdsa$t&$E{v5J5@??shpe8csrl3obabT?dBGATywy`b=&5_Bw_n_<8>+% z4|m)DDFxd|cf1_8)N|1+Rwu@jkSO~a@Bq2dc4m8%_E!loI`B5H)plw5zgby&wt-OlT<@aaNLH4XVd! z2T>lUXn&57MrSRJES*D9bXxGZFNMTME zl!W6cD8$Bm#XVwq4YidgI6xQN#UG?m^_{N5HtkCaGs*E=zv*zaSjZLZQo2?2yZOCU zSzp_`okq-DQ}QuUMZI}pp;+DRdD5AnjYySL%=^T=?b&sJiVgMIGQTP^Det+Z7!5gW zzn(Z!&DW8-X)33R?8L)L+)*9NrjLw{j7!uloqu~a;#@bR^;{$sqS71X8Yv~1PBt!R z=K18)Pp8YS6LJgP?_n7d^$M9o4Ax9AtSyj|e7P+=InLYGIkA4%6(?gUqQRmc#wpQF z{r1!*?@C^8&4-iyCFO@!r`E3qzFG^qlvq=2{xvl<`hFMf>kqHmVD;X1KfiKj_$_-h z-4*ZDtSqE^om>2raWAx<>)FkLDznoI&lkr#3C-IIk^*?;pMpF-9)gEO3tFo##Gsat z6~OTCp9Zg2DQX-h$`ZK>Li_~yy{eT9k)O*eN7%%UQ>yldEfHGW9Hyb?{fg<_A=$C- z)tr)Ia-$ld*pG7OpInfWG#pu`9=LF&Igg&vO)=@-dCRKRHar~qpspJb5 zWhj&+Oz*oSucX$~GGTYpip?I%;=w)JhS5?9zs8@xO})9VcGN_KLC74Q83c1g>}7?a zEP_0Z&WBG<#WY7;;>*|Ik$g>=@ghw^-oA0kZ`%nReiMzdV@?lNDo{k1#>?N-daUMV ze3fN;?p^H4U1c*x@FKuz6w0iMxvB#M9$Mo11*--V*`%^dZiQUViip=6-~pqb#g zTskz4sOY~SQyfOkoLqpIBh!ye&N+GBg+8q8{C>-!xSHgOtP61bc4 zXw>=6DgT)l%U+K5yQCWXe3|4Onb!c<>drpLNq>H9?1X{$^)r$|-4AXujS-Yc z_1y)Fr4pjQ7pm!BEAP)Yllsh_MV+y@n;%GzT(r9HJTpfDfeG)V8G$x&00e_<^If`jLXPU2P9&xw8yy@3JdjT?BP z{xzwut|$lf&dl$2swAnE`Ygk&5`S&<9?^XfUqvlH-GMJ>ZjpxLkc$wdU%7N0W579W z+mB(nC+^w43fGR;F|vZJb-Hi)EP%(vGM>-KoWFejO1a_W)WL~T`JT&!^ADG)Arita z>GI#Do24(vlL*NehD{B_nc(LroR9=rvCbd*pZAOo6^9hVF#~uQVNyI14trxYSRua8 zX(#ms$9!3I8t^xm%xo?#2}6!4!>xcLKRuio-CnHoLHph}DJ|*#V-@Q`$1W+2wB#?r zZ%5CQ=yk}`26GKqHqt~+;5@3zu!I<2^DU)H)XXrh!ik|7$zgQGoe2qQ;MkkunEZNeKTrP8DeSk>cW^5_a5`1{6rSA0wo z#*ZgglUt1Zc8iTsLbtB(DrXN?C#h5`6vKKhojg`R9QVaiCkL9y-|fpmBFdr_O=A0Y z2`*=xO_4pbIMnr-J$EIjd_P;S=6$~B55R#V7DZE8{rkX%|9M~&$SbT?zNC|$=zrM} zt=#Bp5Dp|Uso`X{`_rIY7YjW_D#I4j-qZl_OMqDFXLtoCmKjT{rZF8g@Tnt3rf=5z z;<4_8J;>fp*-C{(KH~7YD6+W7qxXC9sFH42IENCpXfA(D&}*FBB^`i0aTtx2z^CXDXvW_Yf-jMK!9Mwqd+hj%hN{<)Si z8B8Qrw^Hl+6ccK=H}2tid_3@N@r!g5S?nOKYxnimk*g!CEg)xnI_qq-n67#vbhh^a zq?)g9yaDKTN#cNLnS6h<(-i&^=>Cn!?oSFmI%vL!;@=(D5jOO?fD!yy&b*?s*V-c& zJGALbIppUrm7RCuz%3Bk`aKM{ z$?9fashs@52FozV${!D}NN$3JAWd)n?3uO2rWOl(H!OV<6*h`<7i9Ai;7L-UxB3$MA24qzct=RiB!G|0JW) z3nN*0-35`l920{!R!k=z4vS8I*^gTMs$543;9R0%Y6J_BPD0B?THM+gA3wi9Ui!1! z+bi@~nEpR^hdMxw{(#)S4RQ**R3s1txr`)Ygz7wi{|7i8ig`g~(%(|N^Q)Rvm zc_{5(ou?Ir947|W31j3d&p)KXhDd)rNUvMX{Qov#4hDz>yz>NNerM?`aC7j!KTGQJ zp?jEFwIWTS&R8baF(8-Rjh#z8kb9#{4<)va6EgzKMW3j3eEAOy@W0bRM1(rzKdAof z@gsZ_X#jbuL9qiBTO=*?*2TJs^6xNEBRw5YS6FIfgb|{LPux2mAV-9-$`k&*h`j#` z|D+9QeFtgUb+e=W;<3$l{~j%AeU{qe6cBcV+MS=6GqZ&ETenj3%xLJo$lY0RU(xGj zgxSy627^q&Xfsi-_H>x{{z`82nH^J&;ay;@$MC($7dGG4{XJWcrOBojFlr$g(2g>a z=ke6#_b9?6A1>)a5I~uF-)v1yx170s2>Gz>Dtv4aGq&EBWqOkcvK#Bv5OoDj_f;%r`r`~0e<~J<1=oarPlskhQ7|1{t4JO(jP{f6Kat{M zjtCpHAunRZ=vl<_VX(quYDE``HZ`!fImJxD0fd?_i3 z{N8RROjP+=#a?u?d*CPh(Ms$uT(hj5h^vQ|5=^!Rtx~I$QGUN z#k_60`UM2CY=R;y>9JZz9c0+ve$NYLfU73?;9=Ba)P8XSMJZEnZERc_P&x z?*@LM!V4?1{;o5+I+!7Fz9Sy_Sd_rFp=xw7?Q()=AXxyZl+XSH1~SSQ6jkCR|ayVs^#(7Hvk|uj_aC zkFDmg5E2l}&Nuf@&S$;ewf>58kE{&1CVPJT1|%HD4ks6UYLX19*(a z3wiSMi=?*0!Twd~mz)WUshlRtiAJlrJ}uY%pY=gj-wK|-*-#YlKE;=`WArv8`41N$ z4KwutB}vJho_>tZ>F#vs!tSMHJe)W}tsMYW2Xpxbu_B>4c@g?Lyf#tsGAc$pUsydU zw|@}zZT%QA();&_0XWJbycG+Aiy-?GZ&w+ow~O`@1L9kRNTf1m)ncugRSa4!Wv^@b zI{))~{jMiFBG5z&V93^|WS>Sn2xFqSKSnZX6vM9>VICy1)Un8M>dI63A=;t?^2uNr zkKGJu-_`?oz$T0P`N5L{qSA2eN8G>sVzdKU+uREs8)OAsJv`!tVzJ2Q)SUrROhsQR{iME8r3-9d0i&s&g$yX<17&@soq@e?}`sJ3f&|n z-BBM+_4f-8^jlzSM#`h}>}H^Lhyqxmd1Tu>hY`3qk{dP zJ&2*@KopaPJQZ;|g}QiBQ>)&1AYjYkMXZxifp}@d(gELajb|7UgEmggsmHQA_~V1+ z2h+|j{1uy#8Jixm`%h|}uW;#x(}0dBYx8rpw3e&KV{ZDYr@J!iWC@)1>$*O!gI0VU zGjP9mf9m%iyyB#u4R0aiMgYO!M>^R0OQ|}oKWT!COY6Bf#t-5eCpkBhUqyoO;#sF> zuOe{FDF~HUFhY*B!8&60O!*Y`KU4@s{y%jCT9xJrX(zWNl3`%T~k`2dp*q6ZSjC#Z6_3lIByP% z*1Bv}obI3Oym-WABH(m3G|!Fq^5rR6)d3P39%W;j&p%2~SvTZn1P9#K9G4m=w&^$M zF5h7pTN{jo8_)GXp?{Y5G5jS!zb)U9)`bu~`}7#ZkR1QVG*@k1(@FbqGC3&;^X<2` zve|dE1d7sjSALE`jcT1;w;nAwNAu=54eF_1-aJ<|2AXy1e?*G`f0;K7T=kt}C1Rs^NUIttF3LdT5#Lm#e3jyt<=WVV_3VKV0 z>5^vsanR2?=U&zmHg?dy>g>h)6_btZHkkxMdSx=IkWf8b9E=%X z(0`2Oo~+@Qo6U5oJpsX?Fk}c18g-z~VRmKCJ*8;NqH?$mBJy5WhO;F~P<}9+>#{w+ z8g3aavy{+#sjy(dI8~zGL4NY~`0&v%Y8eA`AYF)gySYcJRdHd!n{x%6wAwMkL>%A(>*LQr=%SZNGnDZn!v00thmI?}og`Wk1~tg8SC!0-^vUt#37S+Xf8lW5yjss0vLfwj z>7+40gy=c4p;XIPN71`_FWyFj5?}QIMD^`m(qK0!rI*$<)37-oM&4LW7TH;Awdh;K zwg*ehTVeot?Br&Wt+4m$&1E402??j|6+1bVUvXDDU0>Zlk{ba9Ls5S>gzG&U85O#g~UvMUuswfF`ypZYdu`gb#_C>DU9zAs-`m z;u<^3&W@$C+L)D6-5*88H@Ix$1D$s|nsm0R@1)Zl!Gi~1e$O`1_Xh?qdWFhpEiP1> zB0b&t`MySg^WMhE5(L~KSRgLB#OYK%z@QZkAcZ_eq;_jB`+v_P*bSP1&ODHL1I^O= zM+o{Ke{p^OEsOq{S#xiO;936wi*`YdLCXuDJ+q#r^~u*l8zsTP!HjV8fnyPm?U?ND z+uO=bM*WPQpufFKEQ9@ZLzoTP8dEe#ez@icB07-{utHMCe)iR73EVqd%>o^Gwr|-+ zvnZW|!`*^Ruh}ZwXZW87D_6AmLHF683}7+|`r7OgAv_qnfIKdfG3(hsbYm<!bwfzK04oeCa+9&uGEasz9NUrq&WuxS<)=$&_p~41%zwf z{*%JM&}A`W_92fEIFQ9qA$17eNFXYufv^ejB9g;|5h)tn&bVhkXVNL3zohXUQ}j4% zdN*uxppgn#!J&adgTI+bf$Rtr8BLHJF#PR>bcK_CYlBWl97we*+VBmVbU?t_#TLP{ z068y0+7CugmV1D!IvR9!xgIb(!c>Cu0iGC&+)hC8Z{!k0cidJzh&kl*eG?HUh^<^0 zGT`4huJU6(2hGcd!VIES;tdjf?GMUyr}h>K>MT#JUR22qv>E;li5#d96^%Duc(tYc zP+Ai3pM)smt6km`fV$2ATQ$m_BPpri9{A``5xhyxoUu98Q0IOAL~_vVNLva10zeAr z#R5B3XdH01913Ep>1VtsP`Eo>1B%!VF6l`@VEoZ^lNq?JbJIA zPe1in=xzB~Ob%iV`7EEkvsy8R8{h+3Ks&IW)h5s+paK!bIl9OB)n_$Q$Dp!41fYuICB+Rca!!7>7R|U|FtR1_2srHQ*yoA^~K(AE*a} z0sGX0Na{jI^)o8q-IaVl3jeC8u72{?t04~z&QMk74Q-^v$3I8}BApV;)FO!=qcKw@ zdgSl_tVs3Fpo)sNBypJy2&lq&Qff+bE&ULZP0F>*1ZyHF7iS-c>}sKB=Zg3$yzxa) z(zhCW$W2(pXo|h&@M)wM%l?ajmKOn2C zsuDL8@qYy2%ZXZdAjY`gL40{i-B735ApV#)ZeGC34B4v6_X8ezBcYfopvg@ba_9nW z%VYnFe}qQEY<^ORZc{wPErVuP>Z+eF!Rw)NwEiQ5k|LH8#GxKBtHc2$)&^dsLUz($ zjNxO_>Y$Du3G_Ih){ZM@Y?^?Gt=T(jo$^eQIB~5l_3EI%WI#suM97MP)85QE)?KZsDOWb8!#rRK2bchnt3H^bHKP!ZU{z~>S=&}Vs%0Ug%12h7D$0)#JF6G)>G$e68GHG?9y;3U)taduTlfxOOgW3&2g1JxWP7%@3i$ofSmBH zV0)Uub;u&Mde*2M8?2T)*cBTh%iWKkQ4K+`N6(`)XIrl22^j8S$r-lab<%(|(AMR6 zb#wC!+GaQs7!*`0s1G=ypkGot>xia z{uF4cmX=lZoKaL_D%u?=MzEjC_z={;AH)o6HU1|cJa~-A3UNU`2-#Fj;Z}kn(`v~E z2GD*Ad6te3GM80ypoY0u-zuozpTcDoIlDtpQzi$K#H^cT2-!PsWwZZD<`rOpm2-qT8c{-6r^H^eaMd1bJEmM{|=Q< zp0lYo2fCCy*KtPB>g`eXsDQXCQCRZOo;wgft^+l~F5z00q-Cg8>S+oPc2Rtzl6yz< zV3L)Uq~9vOmq$hQa}7ihs4B_9+SHx_(&)RPUBgsM)+DOF^*E{DHPf(^V85BEyW0jjgXPFZE?P@J#uy!a7& zsWIKq#mYMMEdhlXUjo8!_k-(KObMu%$brp9<;kaySP8;P;Kp)oTXD}6%z8gFzIk{O zFaPcMneqZMVt`<8*vC$zF&pmpuC5e@CMM&mObPWE$cSW>iYz4XBvC;zmC67@Y+XSk z*yA`@x3^978Y_o`s*IU6E2?ZZ9jgq#rLLc0KgnQ=l_NQsf#+R-#3{W>x}NX#F9gq0 z_|}F-Ii^?Cuc}c0xffF@F)lx4Y`j1wDgH+)6ODWzY+4+90#U8I8>7`hLWEj)s)fYR zVYW3pu+0+5jYBv?gSC|lc9CKbp8|jRr7S~?T7ZIrg7x_9>?~ndmzE$_+9k|gVD||= z`Yn+1x8D4KVPRl+nA+N=Yhnn9q=ZwvPH+F=`~!S|u4y6)n9514Zzl(T{8&p=V{%QB zrG0^MDjWC2Exs2@SBKvR)n~#-&nx@-^6KX540d(4@27H}B}>~!Nlrf3+0$cz>#tg2 z6mi{n;dWdQ+mIurdkC9yvB@xDIT+aIMP>Qjy7Lu>n@tp}YInrL4TifbnedZ2?P}U!cf%zc3{M7u53%t&db1f-&p4(qNlCJJMC(d zM$qBv3<=>=4#mXtcTw76NvyA^#6%%Vt{(9=_FL8ns4%$UFt4@uNXy*=o5cl^bfKFL z$}x`Y%McEM;umujDPRaAbb}Nr^#hzH_9HDh17Tg77R!RX@G$69mtC8XJ=D+U@{*&SJW%ub@lbLGLn)%Uie<0rztuMeH*a+@=8mS8Xp=K6~(%~vqS#L zkP^lYt~f3>cBCw(azlOnBo`M~Jw646-t6My-IFM1N5^~{8ym$G_!TXI98mmIiqI1D znr%NN!fZl8Y!fcmQhb$e4FtzL+h0q->Vpzy)!{{wX=d5+#Zor#~LeJe{__y zVi5?(@fw#MW}MNL(^^`~?Y9hpzs~KC_*uuStR9+qDUPc)--*Zfhi7WKdp!Q> z`TKDvh9n~eC^iUI-`jl~c(E^eXZCBPyl{7ho8INcvlIk@`Dj+wmqPP=k*M#x^~uRN zoVXM$IQO-$gg z-!c&%hebv{CdJ3cFQJ7>r*N4%B_}7pde?ypEMbHgwfnOK`6+o?0>pXbJ}(5V%va7r zw|^!f8;CvN8}?Ypfxh72@JyXT+{LeQZomR?LVSO8btRr29bGMNZ_nye<3}RB(xt}# zfK*FDNXVT^D`}xmN}6=o)zx(e?BzOmEMhBf3Ucy>g{djG2cqn^!l|apuo|iOjF>jd z+xHt-FlNo-2Yh~eMKzt_BvDH(6o-n`(1uX#V$Tm*sWXDp;hQxE^{1Y z(-dB|7Og$KEMLCW!Y&zI&YT z(uhvvU~L67EDnKmTxm5UOrIb)xcIHLj;msK-@kur;QhXM-o8~ZVU2dSJ$fS35pu$< zc6$7WkbalXcE;>xaUJXZ?3q!YupvabMkJ?wpJ@KYN6NkECcdgo9@b6~%h=bp1Yb^- zGklpVjcTrK^U*pj8X$Qn{sbW|&E?5!`!r3VfVPDC)%$`NGcixSkb_M(D~D%kFl|4X zZx?YW-7AFMz_-1t3vqAng2VE)Qf=M3`a_tFL89QG=)pAh0Ah&Y-@~E`cM#Gy7EBVO z{zXnfp;SRhD_PIM$5$PjnYqa53wxJs3fzYdcX{g)kDu^SFr3$F;$l2UE_+c=$o2Y% zAO9tH$E2;W6Q!u*?Al=`H*S5iHR_VfoPnZJzE*DP8x)Bh6q)&iyGFlXKFU^llW=KGJS z#qEv3G*xqz%%0L6G_${3`b-u!Cp|i{H*GB;5u$ALh_&;^sBaFbwYPuEYjwrV1EvASqk+hH^0>>ZXMiuc5WnbMV&B_orPqM>NV*v+3B z?`Ux1Qtd^W4a)ZxyY4Tbp$GS?mgw4f_^DrV2@J9yOk0>CNR&f@;MdRdEd>VcYiz12 z?zd1|;m-~*MViGr#6YI^qrq)oARi}in3!4PM~+&8_=jx#OKVDeO?pnN_zIAGE~H{hD=fa3BVvX-?-2#kwLH z&|tf^PS|aah5tiR5^2VBkM=>I|~B&F&QbSD>j;r6Deh!-=jW0rV`ZDB_H^yleXH`&^Xhn3~x9hUiO z;YHf8r*G)qAfqUq)5Bp->l3veM>x&iDcHgd1M+8s8S@0-Twy)uOVw_D#R6`Ms0!GM zVc&Y8)HcgO_YihyiFPGjWMm`RqIJ{16a9`WcRYzSlOSLB7${ME{9)LLnWv)9K-q+`< z&jduwhaQ*QC36~o;Ni@#HQDtA>y_4>(@unxOer}X!b+l_bg~d_KVF?V0?qa zo!vsCptq0DXoH)*B2*wYXjRnry0yZz|6p^N3XDY;oL@SQ`Gmh3jFlvSLpFVT zTl(DgJu3^(tZ=HRpWAc%fPZpwk`r5*92)W6iJDbhs2Hj~MPllp<3$PXd%QQrH!^a` zC}gm>ou!m*mT`u^@vT?Mfrie&Mhibj0s6Rkr_G8yoZk zIV6IJktX!#c&z_vZ#;cM2>dgn(t#J~c409uRHDx)Zi+a_s#7JlHTJD;v%z(zE5J!R z`?pP)WS~SSt|NY$;qgSF<~u8^KG%!WU2>3vwnnLx4p^r03!I1cHlkpqZ;zLpd^d~Q zev%r7I9TNLXN7nUD~Ww3id^LIdsLJXb}>jY%xvs`6SFbOHnLhxLK_>imu&OgTMyTAs@w3daGAK4Swn~0o{t3_%hm9!mh?+q^%@7Ri=>R4Jj0E8n|^dz=t znS#5k5-D))guS<45c|Q|dw+lSmj9l;=Knr>ik_`oe73U={#uh@a7%}{X-tkRSk)buFLaXsi1R7mU`hBgRVfs>{%hqK?l>} zdlz;tCw|Xxf+s3$tIPm_D4TrgJYCo4?*bMB6Uh~oK98N8O19h)8g^%)teICv;I@ZM zBjAo{W6PaCo@Dv|SjXbV8%df`-+VRC*EF#$Qa~qKla2G79`2voN#oh`2 z)J|H_IWi(>brm$SJ$QF%UsTa9VWA1ns3SyJz$K3`m7kr}PnX6c#%W!{!E>CH?RbS! z^BX&e0uW=O%t$zhK%hD}9FMKcY%dxsd;FRyVF)~@N7^IL;bVU|7_Xo)60culN0G$q zb8%>@rKNQpFQ~+~JDyLNbkPWGNnKdJsHuEBA1|>|j?E63#lc{q3_luIL4}d?ShNQG z{@^*9!)j}1H`Hd?HwNr09~fZNd87KYRk1ZSM?%)_Lk1P6(Ffi5)JxDhCtX1{OXP+7 zfj_x~6s4&W>h~BbQDp)ut6+EqFYtNRdz<@7>kBub8bJD=`%OL(omsuW#N8L>tt#kb z0rOu0VTY1Ii-+;;!8@_UP=uIbo66a1M>ch)0rg)58=v|2_s8``v6W$FPfi=T?)T#n zb3RPP$-(o-M?$T}bI$??A+Ez1<<=eJZp4wQEj|##+d!eHWkjuyP9)>ro0(F7%A7yJ zSBBd@R)r}3*GX@)G~et*M?a5rTrKEWSRm*KQ5S#pilHyzZS=?p12&bi`iAq;dcPry zwiA-7>S(QR6II`5$EBh?c>`d6Q7G@tFT-E+OMe1UPWveNl@U@8Qb}FN!WgM{m}I-E zAjmI*KI4KUzv)9FK4!4mgLw^_ShcV0s`&$|FRAg7L4KtHS_w+5L`+;0pd)*A8gc5` zMiGZex(MeM1q0k^ZtR=FCNDp~0Z2+Mq2JY*d{7L-Kn~nJ%zQ0VIbeCqr)Cxc_FRqj zlbAgi?e*t$_pNeaN<~I~9`*MhDe&Wmz0R*%+Jex6!kJJ}P#kZZHwG{Q=f=@>2@UC} zl~4%46^rf&#aji4j+21WquI}Gim9V&-m#Z&sFpdDO&e63REYk1#C@B zavlhzk7TL|sIojT_qbh=+L$U`Gz||A=NU?$cpi&_wH8xW{ynU^KXErEJzbAS z{QZk4T4gXq$Lw(TZJDKoMc$u?q*AUHud|`RifmRE79&iOp1VTBw!jDLk|pn|tE+Xt zNSKlb!TWT=PZWAVc3{o^A}$cFU7^?poNB4kBXaU5LY^cVrKfHF2r>fs13_q1h9Cm3 ze^30bGd%Yv!u#FB)ywC;*TLlbYbFtita2~&g(^%qH3in@YD76K$F!j$SJ+>^#4>1c zkb538gg%jA>KH#RjYRK_P|Wm2pjUa()g7~3R$eZ)-lv=_P>$M{G~7QplQ&ATckuyC z`tr?t{Y><1334xQ@;L3$5<_8lz zb7IhXHPifm2fy1wK+_=E4><;4%U`Gl9XU`3pi31hsB*M%CnY5%K~a&BB#31oi+*B) z6Dw=-G(lce;oF!h08skhq)9Lkk&vJx4@1rYP!P=tkT9kMd20lLXZYx|;hiftAaxkD zH8LUqCmc;iT6zx?9UYwnGnf=$uTqMN0}fB0X79hwABO{gQP4lcsQmn~=p(~Jb_tr!{tkHQBkceEedSwPqs{qlh6=oM9~xX468u1G#ZTN z>FXZV1uTFL5J%Sym@@gwY7ZHAMJ_MBKm9#ZSI%uVuq4J=ETatvmG{Rzzq)%pCkyR$RcE5k&Z&t}>m@GO>grb-`A=QiOB3_}IEjf{*0#FSP={cf=p6clh1 z;YZ+iXr^scRlLaY1@S`{$P_Bvk4}p_&w#~8L|T0N;X??4B42qQ7z{HzNhg$MJ1OcC z+&BJ1%gW4*#2Un*H~b6I(tfws55U{a{Zetk4y_FG^XA97d0<39LTP7YYfE8kYkzaUcV5&sY)Uk|H+^Sm8FFa;_|oJi5!Eb;4QUf>Du!?VxFVwz|hQ&Y2Zc0Q6toM0S`g(#~$i0IVEnDk&vkjDdeg%ccynzG8u z2!Phjn^sW1{KBC{jnAUYllxLlZF~oCnY>pvANgkg4dzW{K=fp{*xaPcB{AcQlb`8t zZslZ^3iq}>VHKFB6##!&u3?TQk{|x;i~1q^`QAk%jr!d>SWa-gvb8d!IeT8c$EbIi z0X0(QpAGzxNKF-d4oeSYX~hM+s?myyS=VA}tiA{JS2X+iJ(N$%O&h-Lvv|EIT`7>JRs-1P|pjYQKj?{m8WG^x8e*ZuIx@14yx_Wf4Fk~$DGJSZ?Diu|4sjIaaHw*tszjZ*joPvrr}dV3^Bc)4oqS7e-74cDJ{65-O67jf|{7?L#j%U5$b0JrO#xu?f)R}{3J$429=~*H!cUycrj`V zJVSLGo8S3)d3pCeu=2Nm93CY*fnC)YQug-Z6d0Te90>!i8#Xe84SZDhUPyHTX3HDw z-CsJQF-#7g-M9uWdyS+%m$mP9XGs|MMCj-ek(w*b^xDSrHyy9tHF>Pm0?Ff9=UlY3 zQ&tDb>xJ*^y)F*P7aA`R%r|u(pI29=wFNk6+va`nX>gqzZaZQ(pmX+#4}>>2?>`}8 zlbNeFEi+d^3;ynVbBXhIZi_*OM;J_P#8tl>lLR5UsX3JhnSY_?m6P^d9}iBa$h?%y zBlu>*OnmdnJK$})j~^>1!FCiOKhL$F`25XVLF9Nbqrxs-c(B~PRHg6!+4gnPU+BdC z7Z(&5^C)D*HphH5`Bu%63l@CzUki$F^3`-evhdu=)peI1ADsj==``mDAA@nv`pqFX zKaBopm~KE0LYG_sKyPbcu!zMKff@WV5bg^WTJyC7nSXg<;SK~ihiKp&lmIG?phZU# z0qZs=I&j8~83kLahTDpNnoZLZ%Q`xL?b=2H0fT2;~PxpyshDlaq2*r)dn=Ty%{u$(I%_wvTwI=Da+ z3UGd`wBchq(__Hg_D=zT;KgAqZL64}C~p~FY}n?Z+mzqalk(~t`(WHd<#-L(-C1%_ z1L{vNe!okT_XhUy`P=9DK^D||bBGqob4nARJZA%dnTm!x12aX1orMmGD;W*zGK$M2 z2bhVuXw$>u_D}#PcrL3}%js3zV}gxeRvl&~sPV7SKx3P$FcmTag2QcKWK@AuK9!c1 zrZO@%W=vqH1m%&9PoF+PK}d#2j2WCi^bS-2`J)_knxDnWeiq^5OI(xOfINIg5+TR@ z);bEnT*(>i(8&QdS1)3KpzcwDFLuIwhovZL=jrVOi9;l^SWx|zW)#np%d{d{UKA!x z{SHgfcuHPk@v52{Wa8I3U&EL++$B(9nWA^$G*Tph_(LG@zR0=)7JCB9Uq61&xW?~l zmK(j8o;8yvP`00TAaC-bYHtt50f|MosI!1DJ1S$=&Bc+Z%?yo3eQ8+OA5n)?I=}04 z?nIWlHq%#xA7B~_wY z=EaAX%Tf^gX9RL?w#~|*NEUf=(P}yPd*nb{~udl9aaUi?u#@?2uPO- zl9GZfKw3a*fpmi)E!|xb(gKP!N-RLSyF*%7bT=#->Au6a_rB+xd#-<>kIKWWdEc4& z)k{c}ybXtOuJ)dY#IvUoo$cc*jwQ+Tc;CBIh~x$jZNXKOW^23(%TSlYMo!%Uy>8pxfO zW_Xk5`F~;kKI?re-Cb-U+i--9vfl3uu%;ZbObpCVz6Qkhc>5jBAX66FJj^{ za#H;K#^LR$uB9Ur3T)*}e2U}hZQTkSrdSM~FBjmsOA{3tsb>i&R0{#|Jk>fGmaljx zCns|qLoctTtgxZgJEMe2kh)}!#N7% zJ9EEs`4x^#2Lw{#)u$)a$e`8!WNt-#q7<@Q6xObu|LlIWWqiD8iEXB2JgbN*`qx3V zVJ3sJ)3(@SFfYyie=sZlEf#-qWW1anD1BZftXyLuiMxKG$khWb#FSgt=ETC+V2ioi zmf>zC-Ba8f1bQLxcr>7K$U(}uQl!pOX7*kZAtWc~X9p4Kx-K4OW*Y?nNlD*4?QxTd z&PDwuV~Fj|RUp{LARLg|3IbOD#qo(TAQb~1WdcYp*q1kmZ!;^gV1dF7-SZOl z!@sNyG)+pCA^m@OlVjxY{%eBt2z1-cSXSI-J7jc=YsWkzY6-xR-@P>GR{TJ`v+fz zMcQ|PF%@ABe+0M5x1Zuc4G@Pb0^fP^a%8}A zc@J@wPmUz}jq|*V{_%P3r054BLW&<$e#uCixPc$YdFKHY_L4vDWbuEsbU%T`<8%>w zQZEGsg|EUaaVJXCss)+oFESJ$jgAX0^52Egg-JW@ey=f!?1pO$y(|BM@vUDgYCV#F zjJVMjEbc-OK=1KV7&yNPd78R;D0@Gjv&}lZT5Od@yD@Oy1^k7xmU{gW0|pEOU%1yo zl1K@NTHc)PJ-dI`rV8#$8bNN3Hf$fWzou1v{6*BZ$*T%T@6p)xz5FkZwlfuy^>Ve! zA0?>GWy#3kk%YhLJ6w^b_c&pRzP>15-Wp2)@;I(KCjz5wb(W(CUbj?Hf7dhs-GnOS z5ijwT<)Rij*lK*X4W_sRaWA6;)2RDTgxn5JkGA`Kvs9Adrrod(YJPTFDMQaoM>durPIA&iux$v&E# z9LsKho)aRV%?i;8TG;4C@8R*26BxzX)idE6fEh@k`8!sni2c$Qe?0h$i8wQ#4fheW zPu`BWg&oOCtrBbD_65U5H$8xfDT4%r^}(9}9p*fn@X@o*>_L;=^p%M1u_c^R@5)&+ zQeceBIE8e+!7XsNyXr>)6MNq(A`_-rZqBynu^{Q@265PMep7gvw#lE1QBbhLEuj(s zPZ-kgs;ZoMWOql9KpoqxGnKe!DFru|!1(vD_J{fBpOY?5tltK;!{p33=+1RGcgkjdKr^SwcuXI? zDA&x{{b-l! zyin;WZILdbJvDBfQE1C?Bh6l^-mvxK=6oYnFisxo%a=s8Y`GbZB3{70O~gs;g( z@@5is))t|vmK@zRlE3of?#}H{ovy!79E{2)s!Pywe7sWjtSpK;qPU~T%b)y8qoaG zcwooMug7QIVj&=xYRY@dKQf5x$z`tU>vcy^a4?(EB*EqJ8&a`5jx6ljaJV?GqFdud zLRnSV4Vsc6J!gO%`O~iG@0c6P_M~AS*f^OU9gz&R@$UaRCnoU!85C|LTKqIuv+0>G zOG1DZ`O~N!;hy$}UR;wzc<c&5)_OEL} zPMx`cYs~Kcq?#`eb!}Ly#oCTsisNIyVI*j`#1=*`u0qv>lrp0c7gjDSgIWOmb!tzr zRS&Xk*xXA<;q$u^lamQ#uce9wJrSpmqgYx6Wf{PTxhYcCJWB?&M&_Ee1oMqPA#5S9 zGE)R)EIKQh>2ekqizIaK#4<4$uwV;KJ|SH+kzWSbDNoZEy8W#!<8kMHyq9LD^Mto5 z}!8&6+N$ASFkUg_M;t1hcX=NZS0)vI;eZB zKhBpv7*~IFzTdAfIo)9*e1mxr<-zv)aLM>lZ*AR=uzHNQ8<(4TbY!ERm?TBtL$KFa zj26b*EnV3I;g)<{Y@#COZ<}Lm@Ut~F{6_Oz5CF1UpDHz$9voeC0ywfL?P4WfE8;Cu z){$bO^4)A#GKHT`$)ZREjkoO6?;o@)_#Fq|d?w@v;}1}PZ46(vViyjR`JFZw8%OzF z=!zTo>%#D9+YGI(2Z=S4xwAp(1DhRA#q}~;Uzc%nwhl&N^u57N`^14&<%FFO;VF;K(_w`TX~()>U$ zc|U!fy>6PlB5?*n;mPBcCrDy-_W4c=owzKgxQo6>rVMF9g4rvh$04 z<3*HX8a9P;BZ$}HOM18Rgs0V9E9ccf<;|oE=A16EZmGqZ>5F6S-!lI4=d_0@S%4y# zj#}g?=6J?S#zH3ZcN1xI>l2l-6$+G;RlIr3Z(8Bk3gU?I?ze}08vlbC7u#Fu@l3h& z(;ANzYzM*BuEh2PL+cX_(z1mTeTerhJ;}B0J!aWAAmTekRiIh_7go$nM$h(H~_Ovg%}oBG!<%BZn2%zyX+>d0oAetxJR{c z)6;i!3=Zx^D>31u11kGUJP7*+>Q)96CrN;uA2yEA+$a&moSK-+ilE>p@oS2b^h!=x}9h0RnerCVHRK0g)AMhTtSw=Uwo3*#LVguYE<&@oj`CVqd1EH2` zeB`ks29BNd;qoaa-ffWcw#~}!3@wm~@a1c8F!8NbSdemhU!p<7GGyWisYLbbPhYuS z-JNXTtonKE&9aj5?cp$ni+VmS@mgwg+?n&lKiMK)b8=zsyXyU#kn+veA6bjb)y5mB zJv-*lM=2HGCR`$uS7YcsJ;XTRq%kCncxRs1_=>v-G3xu5 zr%Ooh1cC0yErls-pn3XK01`7kqNP5_v<;_Ke0y>g2(XRJUe)Z&6nKqVCi8s z?GNKdY^InQyug|9j*Ug7_12JOkpHa&m7Ek-et^}NxtTNXM(m(9?Z z;=;TUkjm(C4R>yhK$~o^d>9->8z3xk^?QkDZu*6fGwC|XI<|3|fB_S#gy z!#NV(9$$H)GhwveU_mx&hAD*~S^rzPSdt9{A^T-|LR&kv4uAHCVoBH?Z2Ew2Ff%-z z9$m!qXBR&DER+qL@?V^{`8>+3y2p$2tPlVEkaz`VsM`T3MrIuh18V9AR)LRw-`FJ7 zf#1=4BufU`Lqmb|A1y#6CExA({=ThNv3}z|P%2%?47q!Hn%NBhl(e_9+TH{e>ecg= zbs`%Ar5r$K6N!n9%{^1=Xck2);`4oHvUDX61~YTB-1xEK zj0uIi_#pqLYPRjQNf6s&v)QBhQmx#Bm%SXYxA%+FtczwY2F$)jvS60ELOewh=@4pc!OS9v$vLZCn`S!B5t6fC zEK$C`Jl2czv3v0|yaOykGaMPV;Ef~IB(?J1(kQ}_HRNYq?)PiA8`Is6;LHhot3F7m zETo4P#+5w{mF9w_)RbEzpPeTKY7G0Hvaj|e5)a|IGye`yMeyVET^lTpmEJvVHg>@i zcTI01mYA97i2Y*UgE!jdBh{82NE*--yx5-TUQ*c`5q~P3II*HZWm-mqAc|RC?8Umx zrQq(Ql&Kxo!&-O{!|>!r<5c=CXJ@-3@`*DFpKEmS3kLWeRh?nmqSN%QnK>PK$}67e zvZLHNWCR*4E}$m7f#m&4uL7B{JsC_aRT)@1s(&q{!C~{x4zPwABL~Odi%uugVVCN^aN7O`-jIkP=FK;~S8KxFH5{=0q zWyM{KPI(TJ1TH74@P7kQam7b}KnR=O`?OlOTRye89WHmCzBC)`=d&2ess^fujj-$E zohdj1{N<@?o4LyZaNHedhFK{j@i2R>bm1n4lX3_<+1r2KnW?sI0to*UsHy9BK;5vW zH3F0quTBmQn08lJAG_aNo=Eqe^8u-15nyY-m<6)Flxp|h^eUg76*A2s1~!t{v>f_g z5=wtiA&~3FU(XKtnc|YTSF)6!IIj0F>5M;c-N#$6BT!|iX>fP6a@v;SOTD%R|7r!h z1}mucUJHOjO)(K&mPPa`V7}7Iwj)DqPqV3k`Ak*WuFe8p2yxjVpb?_*U+#2d>gTdw z*6L4kCcip!ee+9wP$}Ei2(r6DimEYTGAkTSz1@qjgH?7))K%amMAqXx;qWs<+I)G+ z<)`Mw$m@6beC2((^|cme!JmXzy>4#57b{L*ryxOz!g~@oqnk8(GI&hzR0zU}oT#~P z*=amlhf}S}M4WGRQXS#9D#_`Dw3u%hy-;!@CNw~4Ny3qlQAE6@=Yv<2MwuDYs8W7B zLUpN>YI$0Z%U%$FQ*nOfRE^NFAHRCqq^lXaQ>C?PC%|QwL%ZVI zQ$A-d0Vs#&T!JC7tril;EP`>`Y%%(FbxCGw1=Byy1!d7;Aqr$+^Aa8~x2X6<9usjD zDJNM4bePrnug_~b-)`V)3{! z-Cm2wISR>Tku*YeqCjxdRAkV6t02qxGn@`p42TO-vaM&TI_q3^FD<|+gUT8s;_E{i zy8+@?ezb860HIY-{3p;eh`b}>gd&$B7=1^90wzF~z?15_Kdb_x!;i)5w za=))9FFu9z6w}2n5Z(@_(w2#kw>%G(BjrFu?|uJr(_D8~*i#uR@UW+=5^88txA``` z$9ry8$mj0^f81Y?l@3B>>CaZQO~EatG+)`@)_!)C|5V~8%%7sqUnPWIQB=ffel|6; z$!Sm5aLL!2m4^GSVC``O&UFCO{@1%EzVu_Mi98)nPbJ5QZFNOF7}0(-$y-H8s+fro z;pOM7XhKt{3Pa@!$0R~RLQ{G8-Cd~fi@BFD6H$yP=nFR3MB;YB>5EIuLhenc#O~rN)(^- zWDTi7*b>T$0+VPLU(zilD=4(KTSz86dYpXcEy81=k=|<29_F05&SPQ=T0^IRG;#b` zN=}oE3AAtVIQLy9a(6VXVu{Q=rWDwrvuR~8gGLXNFG}S}0?s>=hev=mng0@8QC{w- z#m86u2ar4}>*leMSt7mP*pl-f9RL|Oaan#`vSP?0&pX57bMM}aV~VM!uRVAQ(D6V3 z39QnhqIb=8u~`B6mDEa?&KJI7TnvxAMZ+9<`$`JHOb!sgi*H3hQ%?;ypdz82fwee@ z)uaMiVuP%<02yAE4$UGe?*e*U*wJcY5D@--3Wna9owo*_4d;(R|kC8dBARYM#9qo#6sEv7mb#G506?hx{75&EyX`!V0SL zZ>&Edj-o277MvtMMCb@S)Ld3J77+OQ@fl;2&E9b{w2?qu?)qYc8jEc?+hOyD^T&Dx zx5cXEaEd7x`Gy8?9|<<$S|X#vaC=jCIFm~J1ePjZT-AJX#G-;I=0EbCf#IifzW@CO zLfjw1>mPV*|hr`X* zDE2e<^lD@)l0q3Zjv2oto*Shsj@Ma4V%4-1+HoDEs9%W1RexjisY0j$jM~P2A*#Kt z_`LYNkvNuu?+oGy_QzHe$P#c_rxm*;kO_wpBrK)~;18jm?(U7`oQ8e@E+=4fI@khl zga#17wF3*yZK6}wz`#KE8Bl8T0DI>(H{|C0(D(=#*Aq?;K-#jyDy9qt{nUq>u*b}V zT<_aZ*;fSe)U##3ri1@srJ_K^QUDdkoSf?OK{=;_O1AH`2oIvycqyRUcu5HOSqa35 zukG;d5o2(lxr@u-iQ+o28+gB~WO;7+eD3m0B!bt13cf64- zh@VczbNZ?3fz05&;-8(b^K%DDwvzFQLi16s9n+1yLgGYl{=>4{UMOH?Pur;jUBaf$iRTwGvvZ8tz2tKg;Cc;v2@HDc zhB@Lt>CKMW_5Xh6IY+dG|nREOX~IF#Ax(^t-fe(*IwO^I@PIhS5Ky*v$+3-nW|B=KZ`?yU8OWD&F*$I zXZmDX9of_{)`mEHj^8Jf0-5U&<9LnF=G`Of?Mf7coB@DL6S>V|i=}UVjpv7bozeJh ztMc$6u0%P-z~SMI^hXg8_Kn@c_=21>c^3ItqsGexitWd4tNnH(0tu^sRQ8750s?zVim}d zV3z9@ad0YjiHj>&Nk4nUh~sE}r9V978)&&aFpUE9Fn<){^6e_ygeL+5By;r%?P0`x zTy6(k5j1+lN9(*w5IMkt0KwS1nEto2WQLImU} z$ccY#%4@Zl5}>zMuG&#<@F4Ctv4saUj3&j#uvc0rd#05|$@H2^T2ec2UI-pKGsjLy z$$`0rD@zacp1=ejuG8-o^;=1V?7UafkujcykFn(&aC6)iHTa$cPvgk+I%xL$f^rc zs}XXaWEkmE7&Rde6dMXZANcjkxHTfEq~GW>$TV-8ZA0cOp6$4D-5)NnetB(cp^F?T zKOQK00+$|A%Kyk5qknv6+X`vez-()8;~KQ00$H*hCkcgSX0{>AfEPNSaaAo=p&psk zOnL1UhO*Uz&|o}{c+hS!fSM6i^iu&cm#d&R>+6OO!`Bz>SQ2i?%(!kJ-gDR>a za)-T~-y}dRMjuoAwDw1D!z)z-^&7hJf&SPaUVN)%wV>xi0osIJ(+qJ0GNjB7>8u6^ zDmXo}+&a(v+miY$jr!yY|5NI12&1j=(oJ6NZws@?RG94#_^JZgND;%gC`;CKz8y1q z*{a0gKL?nosfieU^6P*WyOyzwFH)+v6@xa43q#~8BBvSdE<4va9^r{gh<_0>a~UnrAqtej|D>RP znfkS2y`o>9RMDX0^hEHH9S738ckk?27C(KX*3K|4j&jgKCQm7X*WgJ(Y5XPi!|kuu zt*>$JdQMe*U`E{ zGI$|fPEAeO8*1k8r)rJ^t(W+{0rNe0O!>|=xW{o<*ShS_3x%KV&X8W5A7*O(QZH;O z(5pXX6PnMI#)sV_^ac%Xhkamdv(gexk@M!CA1zbmX632;jtm(9(I)^nL0`4+ozK++ z6m(Q~cX#iY6FSb_rKNWxQ&Sfkfa-c|=;k2INe{UJ!f7h1TMSQ6xd^f){{Xb|A8M>- zcr1+B{EgJVOU1qCnpZybXs`(qW@ z1#E03E5~fQXP!~Fh57HtYVdp)Y%$n7vjwAv3rhuG&&e)IYod-*Hw9k}Ef}|F4Q>v{ zTOK`?gs{P3F05Z^tt}G*L*(Aqe1+<>vplz@W<3&#tLQgX1yf2eE!>)VwYIbYjIq75xMX(YmNvY+1-|0b)DN?0V6UTK z;Puyoc24EIJ&p^u>2Wcb-|i*oycK`4Ih^^BKAV3IIBVO0UAz1#=I-7e&FyLrQMmWj z=@fXqU7LW3$KfA<1=Iro%l?3ax+I{Y`lt)aAod=n2G-j1dzd;`r`kqq_*^QI!h5F9 znN{QMHUQfg($dnN3;W)F90v~dV&GKAxdSDH0IuepX5jIu16;q^$<`Ph=Qqoj^gsfe z3dq{^fh&BFdT_j@MgyebiX>2J>2AZWi15j(0n&8gAbawDi4b+EVtpH6N5`sjo{0_( z6`8F3B}DP+#o&}fd+-cZ3qy&OwY5Js@n56$egP&GsY8-|K-BtYi87%GzETeZ%B7#) zo}|#d_Sx&=!JDaa#bKZ=^17pGC6>u5u(Yh$OX1gmWGImLlaMex`ux{!WqX1nXHmoC ziUBYiSDDU52ELK^;SAH$_cA5vW*_3=(#&w>SelANrvRtCE>@&`FR40~#&|?Qr!XB8 zmp)Nl8xST8^&zOv9&-TSR+HzY)xK(yo)-0!80f*F6{hJ&$Y-L7y``0ECFp#ncpfs@ zLL*Hs+0TNW#bdl;8ceL{mNKD)1C~w7vKdpcgkWN>Oar3tNq^WPTKCFb z57s3(U-ZjAVOjb#oVuOivo`YAhne`zH4$~-DbcIN;{lA>rf*Rn14(${>ic6zOFVk+ zCr>+j&g(>yaNqJiM#NJ;q3g^Vu}kv#XgS;dvDK;6FIGe!us@_$W#!->8PBo(fBx>*INrgV6pRE9io8t zCa-3FcV_?KWSe8P*8~ke`ugB+e!IzKpEeBYS>gzz^||@G%mc5sjJVGAVH$cR0gk+D;DeII(IIZF9Ht3Ygj z54Qrbs*j1ouxLsus)B>-3%&yV-9X@sdi01>7thl3^tGQt^4?GPBW2(NTnr<{Mr|q3 z(tue1jil7+<^7|U$Y(FsK_i4`2=vDHmQofCbuYPRyXLVqKajJ7uuUZLl*14A^e|xv z{e~JL4SJ^ucHhv>{Zdz3&k7s8;Fq385Cy|Vs|jyA*P#%X-ChTeQ4qw{k;GfARG{f{ zeu?M*h2W5DEh%ZmN8~FHlIWpLNhGip6!AWSG{!dtbT4qV3_U?`-dm9A{>ioQ;L;AF zEe3~Hkn|LT^Sx~n=$GUUb6GvPK0p+v$5K5iI}7WDnY3%jEL97GLPHH8z86%&UO3|I zb&;i(1an^tZ*$r<>M!}?#54e2)QZ5NxI_RhQKGKn3I|;Y)33qYypEdQo8jlLR2b4I zG##Ow_MFWwDa^`d>e+f(%rCX8U(NMKoeDTKUJRxTg!K(c{(ou;_dIF3#^HeP+9x6|V zI?x1t@1ms2O=sQ#r-6K;a`=qmf1E{Uz{d%PU~*X1yIj~K`J8N->ONI5Nk(73rSmI8 z5@xPv^xnRA5k!*%7XdTAhscCSS4BV3y*@NcHt9ZeYq9znWuZOLy03g~wTSc#VaweI z&TL2_n+RFSdPS9dKG8M>H*g@_U7rvo194m_T>3zm=@D0HDU)gjr#6pG&|a!X+vK_J z11e{MH$g+L&Ng%sL%`P<2q(Wpi@^(-K+2M<=_^LcWm&CunyeGZDG9~cNF3#IU*-pV zCD9N8C1oG+UW5G#ZoY;=$QL>xAbFA~N(Q@GVC*K{C?%0wK^*A%Ya&*%v}KQgX^y8! zHBS-~2dA|=IxdD;WtLh2h&M$0z6qANSUVmgR37;Fh}k*o1$&%?El-vfaq=qMmJ4vD z*o=RqjH1D9`3I}Ad@#Q^EIJ#9$!+pA7QI;Pm35$~H(!2Qy9FOoUtUfT`-MN)S+*tp z7Cxu&@L`r~HxMAg@w)d_p4>lHX+9h>sNe&)_91~w!RbFs6-91R;78Y+Dr?;Z?{$FJ zvFGx7Jpsu=pBOLYsfb!gacNbi)-Yv>AVUQ^NWwQG$S^F5xcJWX0V7mYuQs4SeOx6f zFaomD)@kBe5h3^?nIB{%^K5lyEPlszqvO-yY+UAZ1Jul8_@@;a|6h8S9rN%gYQ0+i znaY_U<8GS!l!KH4%*w9F>cx)F-6?y{D_x!MeyP9T8|v-VU84HDbPW8u@9Iy{-$-}2 z!OJ-nVPfSmR|;szoVQ2s;u_nF;L#r8ilImuXY1I@OSbA3DDbuspmv>t_wrN z{PH-kbRo*1wjko?9E9x_YU>KvP~V$NqFTqH$w73UO;Fxt#4QCb3P!q1rZxHKC1He!#{(8kttV} z9d0-)g8GL-)K8XjG;r`foFkT|9YKjCg;LWqgp3fm?>5P0|FtIu{%}fir1ZSXbNpvh z$o*q*`geRuCg>%mui_tQy#J?{kewntJ^=gbwCf`z0zZ6&N9b{KLaX4ASBvLD&=#ki3fm`c)~%@t3-w z{jHaxn+J)^2qs{$?1IQOikmubs^v(ZR@qp`y-4|{@a(Is{rCL4VSg z`7y5UK8fnWz1?r=m=)<-66+#S!zvRTV-X0obFYd1VD3eh`?j05&}*MCDm~^6aFHupn?@Flg#l2?*cl24Wr&E1(w2JyraEjVIu=m2|TMI-m2D^koSj zu0-7g5>um^#zPV~zGm-M)%d4<)vqTRLcA7b#NE*%%TJstEzu4RmKY0kTq)~aDkTEZ zbz)wckpQ87G~9#c)eh<_n})#A#fto+y~(BU+nZ>RH&eAa%3O5*qhR2>J%I`=ZR0l4 zO)p@Rn5E#&dVkL5xWXrZFZj0{^~5Pcw4(p5v6-FhNP+`XUPmylE6BRxDk6J^P;GWQ zjP&gP{npR(EVy;}oqM$fWRDqs%;*OZvqrJFFZ?W;HVYOKIZ~~Fi~kChX+@-7RT;M( za~;$&1xv6?`+OT-zISAqdsTrno-nX(+LD3Kw`^MMre#8Wum1uX6zm=Kwzr5sL9GZU z&Syi+PPkAEG_=G5?MjwzAXN;Eh|G&=yrcl}LFLv`Nm}hOd(Zu}k=}a9kx~vTfOQ-0 zSO;fCvlrGz2C(4|)%*+umSi{gvEUHt2mLATSdJU|{$IcHCuj*-jPPeKRj?e<@c-r1 zg0RJ59v=LTzPsH%izdIh5iuN0VNGE;N#GCxrpc(ElI58O&0(99!$EP!8Q%baxYY4n zuE-c%(i*(TBXV=i@ua}pnasFbT^hLI)f^IoSJFWY<_2fT0NUPM1Dp{Ess;))Bzw$};RHiXd>p|S%?tNC6d9^7C#Xv=UB135J zUv^8|YjN{(9fv-H6=WU%eVeZdW!&PH0be$;^Xw|{7cw*7RH`JU=+`;r8H3n3J@7)a zAD*7pZootA{zw_8oPNVw;{SZk8)*#bwGz{Zr`er(dmn;B6)E|xLu*$1OHBt%D$GmO z1$qEX=EE<6s4VtBYt)qELVAhxcw)N^2Lh4Ics(h_0JBAY#OrL+qf_bQ>8RMdlKjNs za&#(Av&4y=-JlWE*Vh-qpDl`5Hu+O-W&5G`eC;;(Rci9eZ!AT5Dk0*5S?vxjL_qct zr^{ca(Ol(+ciY4GYTFv;!5u(ut5o+!3$b!bd&A}X8N+3N=Cc_`T5H=ZmDWo$36<(~ z^YwA=K}oDQGib}s#mj^J9TT_1Ei}`CbUZMgZnp6p^VzBC?%aWN^5Eu3DF(y!OLXaI z&*i{{;O2J@z0`^bV-w*KC)1f>i<8Zv#Cl(Gks#x8+8Dd%U(Z7eS@ zcFm`Si@NZZme@UZKkc8(fqUv1@Gqa@Nnmv=t~eTfk48@`m$oTEp_<9U(rxFqP#!+K zY4Us{x1-F5vVXOyB=jJZD0i6}Rq9R&wO8&3L65~@(j2a+wL9y$ukD_Udju{!Y@)#6 zb89Ag%k(sbbN+1(a+W+GD>aINnu?Nq$fIzWgW3*v{eF z%ijOoEnC1Oo9on8=-HS%A!E+Qtsus{uzqX-i7}QvTi4mik>tv&6Z?&M>+3YWX8MA_ z0F=`GMH(5^`Z22r->!j(r~Fp)PV$Mo1bTv}Eq}-4lxoG*CN*aaW3NPN>@HqYR29%g zdas;1$G=dgcpmocjiD$K37di675@GY*Rv*NoZ+D#nHa-)W`ZEiC__6t>20zATUw)A z*xZ%tv)8Yw9-6XCjfJIe>wFGz(4NmRwI$@F2h$1ME7V@VI`I<>d}dhi?xv3Y!Q?$t^VRP!m6ORvretz+Zo3NJ5jP<8bg+TlJ(F?@p91E^~i zB%k@c&L7;n?t&gldRx)%Opnow<(o_x(YHHu9W+JjPkJD2BYotYl|A7j0(Dg-MGupd zNm4*^`K?oWdtX<^AC>rTmd6}bbG0abqR)?4*2f50MSb6N-JS8bx!b1iS+U-B>Gtwk z89&*4xmpZCu9Yjsn{+hfTUWRv<;@?Bu+YiYcb{$a-AFE@@vX;i3#;t=Gg^qo5RpRV zD0`{W!dS60iJDNP-w|8O`mVHqNesPT3qll^6CKi+Dnv4%A8ZuV+;FwF{Pm&vpXDPC z>tI~6AdzX8s6>O`w)O#n-qXjB(mUP$ZmT-AFKqlt4hiyZp9gOo_K-~L^{#TA^` zkGz1aRWv9J%+njby>D9PzcitJD8{Re%rM+I(O!#oyW6Q3)4d4oN=p+#@5>5rka+6_ za_&xB`}+F4#`4ve_4M=t2h&AtNp+x#>B4hUb8|w*AombuYc%f&8oCA|j2P!?9bqa< zZ9z8x*kpwU8o_fE@Kkc-Wjr?qQ|Un#jGMW!G11cc`ua9d@@kiT=y?s|^htm|@DRj0 zdM<(t?170wosH}D0m?prPt5_`Dc{%2LK)hfKsMtW?dShIb!35p9V#ClOBWS9$!5vV zKi7Q64h|sXqM|4=!77&7*}vq-=>_~a4f~nK)JUQ!r<6>rZb42tnDGgibg}Saq|jtV zgTDXv!BTratCb7cBO7s@4faQK-($xTZ=gOwvafhWd2DXU801;r{Lfx^gNHRs;O?JczhM12KDx6mC35o zMO3w=X7E;9^UvBN7hxNrj??_wP*?LgEIRbaC^(}wl$1pYHCf%}%CzApG4^8Qgq5zK zx3qx!%?S||VMI#{(wjG4w^KjmE0<&YNgM>~puGR9km}#)S<>Ujd^x@Eh|B-!h;%Rz z(60h&MQ9Gp7ofd6?54Ffj^1Bi|JDhIznq#d5i+VKc)rx}(sDGH2OzLA^&sZ(3YYTL zF){5`TFR}!EwHa3uKpYx*u{Z68YzfD)mi*Z#JKF;^XR{=HL<81(!{^lnm*|1a%Rda z)V2Mg_lw@N)SqIAmfxh*xWPAROML~$u6Gl*HEXt6cr4EP{8h(A?f5;nzJG2@7-QH< zV74Zvfjy=<%W8P>S%~>nR?Waw0;S3xe)37u*u8Ddhy2iQK5#e_ZeTxcJynak^tm3gnIf%*K>Gz!#~k^?h^IlbaevD{aPsRlyR+prl|zVA*{v^WrSuEz zu)sOZGPohFKo-@>Dx5HP{!S}qzsF)|C1kit?%{{G2@h;elCI;w)%;d!sN~j$;_vcN zrOt$hi#5MK{0d)IbvgQ%(PCr|MLFMAVrL(ST?n*Lgq^xQXr@hTu|u>uPVOv#v-XVN79F z&5b#_JlU4n2K~MYL{094&Q1=Z4oJYnK3N#xA9Ak0rp!0EmrH=RSy>JUrp%H{U@txb zj2F|Edbm3XLyUoUc0LaUb8XL*jUw+aXV3hikbJzgS>6+Z6=mX&9eD&-fl>ziJ=@>} zeS*4!1?i^^V(XKRkQu{+NUYF__AaF5n}<%3W`+`y1e{o^BRdP#KD)JiQ7MYKi)rOXLt23a(y&AMZeJp4LzFb zNoUi?TT2-qX^~|NymyY;qn+zL7Lm&BQuG;+`-4*XrxE`Rrr)pE0$nr74%3{qpuTW6 z(g#Lrw0^;l*84f573oC;frs98|Cm+1;4Lv5>}+?&Y@)&aXa`(KeVV~iL7aa8VMvM# zkRVz3JO{b$MJX#FimQlv;ghYl)YQC;u2>ob)Q<^*TRo*CchyM z`ju3E?**&X0NHr#OsE)celj2ApuHdZmCN7%%zH=D72`>-r@Rt6mXsK>2>lcGa3T@K z&*4TFAe|mP4(>=Y*pY=;8LpDVh@cTTrEF+wqBXSLe!#fy&Z zM$mezVzSX*DJYF*2)_rhLQb`t1omRtEogc<|D7xz-l1 zxs$_cX!9<&>F-Ac7CeB?Ot6&nEnas5TE^o6t>-G9?&(nT z1{t=v#KX})6?Uqke{(W>5GwFxqXKj6kzU7Vi+A{fd-w$&Nr?uO9>~91OVH=fO6dq~ z9}Z!NzO@vl&-j2``EwpIqSPbC{c4U7>^YyqE&l(**H?!{*?nsdI4IpE-JJ@;kfU@s zq%=rNN_P#?AuTy{DuN(gf=DPxBPB{mgCIzW0^c6>eb4!wbFS~YQ2%(}i)Us(d#}CL zz3%&7Jd=C`WI8%Kr!ImoZQfDVkqYjK+0DEpG`D0i^`_>}jY_1CwW*}CS~2&jcR7lh z44(RRJ@bYK=3K*0w3b|7PrO!}il|AO8%3KK1AG_dXDM^h^pgpQ9r5qdh`d=5o>(3w z>kiy{t}@;mbtgMcDZ|}=^I3?n<@|!(Tn&t)<&x~?$@h$ru~){tPp>vKr|pmLZ@a2r z{IIk&i>~-cFg&IV&xeMirq)j#7~3{(2&OR}oCs!sxgYq?TxJdi+em_8#I)4m$fSu` zJhr*8FIO%2I9dWWNm@0WU%$W$Bf0c0D&seLVgI4XurP%^_NP5fU+9%?XyJXzQ^(k_s=C0)<)nM&#_qH>L7-}KWzai1ej>y%Z(9N45>_J33ncbkk5 z@_-}sKG_BV+(hWI^S+o3UIQ_B)s$U&)y9O(aj7$Gw?AbQl#q=I-tX+G4w3}I!niTH z{=&Q8y-7dnJkTiei&EtJW_;Vpq=jH?p*?P5^p5;Oiw|w(r75FMe(Ok5XN}voKPU*P zBJe1I_oyz}U)vz+V?5(Q#tJkjW4`X~9 z*c3B+p;haB{b{vlvH#s9el>5Yz+c3Y$4vlkA zvo&q=4tgRJbe3e*pD-IU@geLQQSj$V{TJ_n;nVTne9L!Q;6%0nh!NJrUKQw)LI5P6 z81xdJzHLB}TdtDIQ7Q;7mk?kh83g81z6Y6V)=O{$e+JIZYToB(ULQLzFMiqsHp995 z%G<&*oNq_8w_tno4L(!HRkUSxt-Ik4{dlpYvF&T$X})P!r$WwR8E=Xv4j1r8q){H# zOi)|uF_#kv6Rn@hgw~ZOu=faNL}XHympk4RWGisREQUnif0?M~i^A84g5vX(E6j6_ zpt`zkzPoM?CYmc(ID8)pg%&u3;Q~)H3h#$AQFOEJeTFZa4YW}8 zhzt(;V<#Et$C5_hvtQi)1UsR$VlQ4#O;NtN_E_=UD1QNqN!925{pC>UpFS#I`Q8sD z-?}TIf_pjEh_~}qezSBWQ2@NFeS!OJ;W3x-y^lYN5tEQ4pk_Ua)uJ9&XcyA-V8wM@ zyWq|(cxcch%n_fh4y$@IG*qYzUqF`xBzmGLE#86W+>1k!9qdD+3zuysZ`Pu1h5_1;dBf8#yYb(44 zs8-G(_@ef~0abZFG{g#QVRnIH>+}H_9EIMe1OjLf4{u_91~96N4x>w+?;|&2Ske`bJMt z1~3w102o%vCKW1i^hrRSPOMMr-m|nq9LC2NtYG?C>1xeVaag018PFluxm_h49rjK#@7^w_jg6ctLcw+^*q!5u{;&B znG}5`l;~&Pcxnmbf0$uAX5;rU4AgL3*t*pw9Y(dJy=%vt=hKqK*ao&qI%NnCsemQz z^{@aRh9nqyTPm^;2h5+u@6wXfc)k?4+*9BDTsSxK>ufx9S&fMmvad#?6`VkX!<7Z* zTzX*a=(;Dx-)#bW!D~>*tyl}eE5MGgtbpDd>^i+5@1s8Ez#tXk!6f*Uy}LL4!e@?d zw(c6uy~Ta}M8-}l!DwjKKFcym&bq}b6nM2ZrgmXkjEfxy3`8aGHY!7CyY zY4Zz8SF|htBXE|IkyKLvqcp=pTL8wI5br)0om#H4kv5U7X-P{ung9}b@A;wtEyUoL ze)M)6U`i6azqz8Iwjz1c{ui~ZjeJQy*Hr=rhmhT!%_1P&y(q}PF3y9q@ucfE#0rCM ze4B5MNT3A$rNfTpYB+Izr66Z6DMDsr36z;EaONSS)Lld21YvcwDd17e_MBZNV3;x_ zSBHbn{#tZju zLToqi)F|M&GgNA)(nW(jW$%2Pem*;-j03)~{jvx_j=PbLwv!U(J|`STA7Wb@07|vE zrjE9O;y37*-KSar54|xgP;I}qGL$MAlDPZn7eD_{ZyR^~8V(MQaMoAhh26fR?F_S5 zzH{e0vvtq-?pcc9SQNCf)R1-2LE1b;3ljQC*k6Z>zc2aX2BX92;i$prqJhxHL_o<^ znfQ?&kRJBhKvFQJ-2MqC_%y3HYX_uhU?)iZ;z^%4=&BLJNkZ~~gQi!R9?>%U-rLzY zN{{RQZfaImRuQ|GfkEcGr8i0`e5S9)S@@*dr$aj=Bi?_J!*pP-q3;TWNRqcQF_#j3 z&-jQtl;Gc;jkk!4^xFbcON(w``V|LV#3;I%uZ{XCgYmtYFTI z48d@U(-(XrO1al8fz4F6RJNiXlZ2E+nnSEem*!fmzc6W1B4^51<5^7k{H_U5gkh`u?0zB&Ts z6k!S-f}~^2Sa!j_+A^E_PNsGIj6qn0e}Ljr31m$RM_2{X(r#z#>FL=Y ztPVP6OZrqN1^T&P6NkYfwye76GSB|u0_+0~KjpN`XI1wvYy5+b`Y#lK_h~0SF5&Fa z=k-tN9_xtt(S8(NDwJFi{_DVo0(loVj#q+iz&?UQ(Z)jbswOVnF&aXDX!*RO3`|8pyeB+Z}mir~mjeIxlg;Q40WhC&{|>8P09bjZTGF@KqLojoQgsyLuqWb^%WMUPx#_+e z8XK2mvgma8^a$LL8t34XnrGqTo75J%A=ZQ~EOrx5RQM*2ymd(koB9Iu8kWD`&-ON3 zQj!a{Ns;Bv{wA0F&p<7HdmxH!O3M9HEE`i#y}0ywK1=aWzEYnnZ_7qcsnh+j=P^ei zUCu{*F}zwNp|ubh4C?YCQ8#WH^hV zKuK!YP5rPN%p6Y7xB`mRU+ANO{QU#B!Yuk+pVV0?x@$2Lc}LadTGE@E3HL^MY~lvLkCVoit$l`}nK?QfGMK++W%pO- z4fN=)cHzRCYoYJOz2rc&5u^JcgnN0dG?LGq;3_-li4ir$u8Q2(_;b~uhmnqg`|yzH zHUAY?;x2dov8^`R)%sUB9=~Rw@AE|_aVFi?;h@jPXM4<^c+k0I`~4tIuAD{#ai z;*QTnhvU+@iVc6TXss%L8IX-}ltoEpzsQi7|YM2g56PM>Fi~t0T0d(1mlsi%m2tiC&Tx8OuYG8Pp z84*(=X_%GzGd7{Ca3*AJU!w$b`N(^RqrsZEBNLpvbLZ|%Peh4L$a%`oAthH9U))$R zNw^Bti2Sjgn%5wDt!W&<_n35^#h?M)2`QK zEy@hCNQaDwRh`K&2Ve0T(~CP_tPHl;h%uSCk(yRU3;=(1;?_m119(Z0BB@E@_?8~# zv*ZadA?xSR)aOQIYO2m`&9~?U{`W(46Qy@)vsofi4F}SODH9S9h1@7QIeNO3C_{s6 z1tVia1p^}^Mc|~bU;zGr!Zrtl>72;$@JuKc_%|{#`!x8Q=*jVZEtqT85s{JMQ;|6G zv1VP+%s?Sr=`=Gd%XHuGQ0^zis&Cs+hS8Q;^lXJf_vw*<{z9d>wqPxrHC^KL&l z{_MK{K4wC(^*UGiV-Yue$t7$q6~su+Eyg;I;XC~d^fmtPXml%#7=WjqYyO%5hS72@ zR7X)m!M%KiOTUHgJ^y>RgSRT}fybl-IbzZFO0cTb^PXv)T=NyCKT&6&ooVGT9EZ$x zu?qvAS_lFv(JlZHxo(Uy1LY8<{X|(W5MGpq05KgknB3C`U}>S?U%nzvGsKra^Ih*H zSvQ>adI5z6dj8qz>FHvk?8WZ^eRiWvhkFZ*W@csvjZTK@(LjQy1j^!4KhVSmp2M_( zXNNd)k@%r?bvLJ8+)o4!U>3lI2;7;x46?y|F*^Y6RSj8xn|uYBq1*NXqILiaNXWEte)TVwhFT3(Fe)CqRgw3=EU_5F;eF)BY%vvoOOgnW02 zL2dU1aMxbKc>)EzkGi@Cf-|{N9umvDUnQ4Fk~szg7Xr{$z-bjr)_g=Zv9;E*Zak65 zl$FEoEIi?$dHk8#j~2%-4Y^E;T=C1x6Y~oZSrV?E?mcJcm&_3!xSJlK7@>ArmF&Bp zTjP3ZsfrDr7D>UXaz6D=>wI!u;rjb}*cSKp7`YJ?00O51La=oIIIdPdnIQ(IegNqAO?UU5lnDU=flM(CI`NBN*f2hXB#<(gNc8fp9D{jD zNjGd%H@_FrMO9Gn%O8LSSjog3I7E+O-1HuV?W zjbAU+*iLVW7px(2<7QLW7e_9nN2^?##PcQn7r79=dGH_4R<(+pa0cu@In^pbOuTNA zEBzV8&V(_9W76&`{8FbJF&?uf<@c(?7yxY^8&g%Z0KQ>TS>E6@x)nEw4M-P!?>3)- zadoH?%CF&F$6#b4=pqu6le0aUI^BNJIa;DZ7Ol;4$3HH0>g&g*esHPO+KsWOXe(vl zl2`#u<|>e;W+3#H2JPL(jpHfK1NqB+c4nAk9L5xXaU0ch?R@=Oy0+g;>{eF6hH0L@ zCPFZ$t-MJAk(oAIlEaK-XF_~UOgO_zuy`9e;$G}GYxogtzhaI3ySg{4+WG>cFV zKRugxaN7(!SQugmOr@!#$6mbfOTo7tq~vSrwyN; zk+>V8u6P1CdK6^bnaq}h_WQTp+|NKv1#7!;Q6$sAMb9!9 zdqBTT?!Cha=rM$ZgyZkF?SK}4n2wxRkFRWY+TAGdP8vQ5XB$xP;t4AP+_dy1BaqHy z=b`clLE+&WS;j{&kM4)FDwyE*ML|g)AsLaLkY8k$2dD2jM&t$Mlsav_5!#yP=30lXIq2TC~><0~OMF7xdT*8PolzfiPWaFtV_=pxJ1 zF;&whI<8(u40lNMV@y3)^e}1jB&hVM?%sHS>(qFYur zNe)~cL+hA}F$l%wzjp^4F%f2PaBwoXpOXay$wPWr9i;Ir_yun9nYPyJR?DRw6LY2& z=L5(Ro;E^E#T|QtF8l2!;7mlfgilg(mMXv!%kK6D>2-nmqdhhe(E?q13UgMTLv1TT z9vFid(zc{^Jz?f_*D>X_IlQQ^Z8e_w|e_ z(+>9%Osi6qp1C%4%1a#TI8=hbwy@Q{r*8F+(y}in8`_9%>yiBZyI4Qfa^w?^XXl6nKm=9)oZQ#OVr4~$q*R2{?qSdH`lYsC~XN0 z--5S#ZjRPi$kp48-ElZBe#ubOLA<_9!eZJZ>pUm&^mF}-7cbblfbSu1?)%1uh7Vw; zK)x|__4u-g>UuDjQemDpQpOdsEJ~rTD5d=ykb-2=LQTZrVC*K<)RaYN6Z^$!ky1ky3BL=ePvG%WCn)wK-nP$wLqcTMow>GiF& z>MM@4j?X{VQD(igPFakEMin@Rc{ls-^H4rFMQX3Afz4$5F$OQ=e_TG;uqr>tFD~|^ z&J!UWX>M9n9o$ER04-a;!u4yrv<3?Y^cI^75GG7USjfcNwv(=;1NH>B&kM3JS3Kn) z{20yejBx@gW01=$p1Y*%bRG{pJH!{P(u>R>URj3-(*SYlcAvJc)xiwe4R@0)P*M*< z-|ogFB5U8;CugxUs0rB|>asQ5ja3!p=^mJ);gr@`?yaM$Sg4oj8>VJuPXabj3o>i5 zf9ktQP&A)KwU94tKx5y`;0`q=jeB5_Yk}?ouNx_`OVbQd0Tt54MeHsUD5Va%IBQVD zbPeS%-x^~DR6a(3#6rtbRehfO4}WxF1l`jgXZ8QCo+0qvsq zHIW2c-dppvVHwYq`;Fc|Qc%-=IQKGWtVKtuM@&W45A+^VaQZAnplNL7kFOd%hv%RF z5E~%+@iU_^Ab~b)i?-3uNarBq%k_d#JS6AU%qSf+Hi3pG=s-;_J5RiP$AAC(FjvIG z>u#3*gvcV?$B7ona7oBAJ@zU@N?Dl>EY${Q0ZIl^AON+`Xzww z>s>!sOgxR~V}`&m=B-qf7XzSaoaJ$8JLxcwvUfMj?zULj*p#+XlhCZ4CWlw>%5cwB?UGNKP0Kh8|()<@y z|Fc9AY(h}DHbl-#yi6d9RNJ2hN!m)6W|fT0!6L620GS=VsJ&^{C^8X=k$M>mv3qXy#B}T@vyYXhRILR)R(g5&l027X)V` z8`y0VYO&m%w%WD?Z`)LJg&IepKzDLFz1hd+2J#IgZ<9B(hpYVlk5d-sBa9j8I?iVq z?|Jd6FjhQIDtsPAPmEucz9)!>FUiS;(K}$@6nPYsClh2V>e#3h30fPcw;oQ8O5Rp^ zm-(ynh&FfRe)HmJoze+tOqLLRZnjqgXwP-{>=P*Y9e|gav4BEq-^%6hnPUP>B7Ddq z)V!ci8vmmvDl-qapv0nl)rqY@2eUi7@#-jD*EPs8+mQf2)aEtU?5ER!u}y6tmx$_~ z8@N+W>iEpFT3qzcNR=_A6VK?<-CP;aJj4BY4)jUOjrlOD;*G@2o+%kfYtSK z#s+XKD9aV|-u~&P{PW&NiQqht^S|%i2qjLzsre%bNrSy|MH3Hx7xJT6z9H$u^2pEo zd_s6gM@aY!2Tb#Tont`kHBK~R_W6=bJ=Su|L|fA08*0cEVH@YTEwhk%HrG#8Ou5@N z{AK#vSrsFlle6a52_N-bAxG@WJ94t__YF~_jsp@ZOd6@F^gpos7RP=Ujk%CMbzs}srb{su- zIobI%Jw`=1fQ{Sb0mxVv+4-MQCI~=vqx#cVw(X>tOF1#Qs*3l;@o~6fkfv!BlrN2b zwcvKCoz7IqiWOfFKBlOzsa@+1r#-#7=5d#BlLf3Y#?D5EE#7nH+C3ExLNY)J*3(?s1 zL3~Fwk3)OI>w4*w2900H_4Z)Ak2@XIm7Y5L`a*d;&#(0he3IMF?$s(a5b*6d=^y{f z>305FO?_vU_{yAK>f8m_E0&g%0+Mns?s|G$z`amE+Qfp7ryrE_d0@NF?uj~-C7%5% z;%=)L49>K1>h?Oyq^;)_HX9$>S;|hFX>L|umNTumEG1;fyz*^$K$Oh578o$HByZ0>}``9Q9Pd|SgcJrxf-Qb0*%*3gydFUBVsg?4L+RN`Vp5g z<4;jGh&Fl8| z77W)(X>5UaB^XOeX-h*&<3M_y1P9QeJOH%gahZ5w%XluEeeEh%mT$mMPcU7o z4x^a;;6Mv_!t1$BZhr}NR(i2G6{+<$i`xqYi}H7R-Q3$&8*KSNlwtWc>&^6eA)axQT;}ErdrvAc~V1EkqLXk>f7S#r_26O+X1&zNs^zyzi4zqVlH4 zWpZa{r+eq?&YQ3FJ8$TA=(~aY0%1dKZSp-u(BqBE9S~qEfTP-dtH;&{bL?J3Txf;JZ>H^?H|Z)y z5aCciLOKAd#G<|AwblB@m6=3nngaTYl=)v*Lg#16jqtLCeXE zVMCTlSRjdnK$syHSVFR`;o*%o(nT5^P0zK+c|XZchf|K6KQMbcWlnvt{ua3}y>*!s zUm?st;3A)KWN_;l{oEuEN%?u19M#e-^H-iR%bB}JNw3!6r$M-n7Lurr`<%~-9iz2`yWvAN}Awmqcr+gglaAE)7nrloO(D8TiVE_`qW-|6S- z%Hi|@%Ka>Z+u{lZ$QuzzHf;na#1o-{>5op`h@Qo+da^BB_17rFg`uAO<-Oe~-jj$BII-Do9#ko6#-cq{ipP-s%|TRqMoiZ6gIAYI;vA4He#ROpDl>Tx#5Y`^lQ^ zm(11W)jSnt2dg6;n6%#y8T`x^k{k{ng)rRZ6Q?;@zU@M3$>T{zP%xa=o-e)qL-R>N zGGOyu&glKa1pujN7+@3pVQT}y;NMj*ki#tMdd@}oGm5Z(a#a)ErhQkddl$~=KDV9A z7+ZfmaouchtneXs+HgLFV27;v=e}a!@54lr<(Dz43LYvZ#Tp2Gz7!pYOQnwS8V!fX zPufNnPgj3#OjXcHU2RC3QPI!> z3!edajQ5jd*NGLAZMAf`lHdZ1!VTm4r}yZJ+omESS`5{Hb`=n-8#G>XJkEQQs=sIM zY@cwa#bmV8>)s^S6S1;SBP*VE2IAR7hT)$$U#PhaZG40h@KR3l^ruZ2Sy*vOgGTz) z&BZ+ejsHBOAXxrp!~FdYeb70@4;~N8-H6`YBG>j8LJmacrq?AS_enN2Y%MQ6kTZ(D9CW*N|IBp7NuKcu-E>9fHIaoG6K#p5r)VK9YAB`Zb!)5}Fd ztx1Kh5mSmPIzsM2>XTt*uUhfArG1x-!ZLl59~(J?1wth}+F9uEVVi*QMSp!)OnZ2lpa+ z-UunfYkxl=@}CFX8`uOH)*R69a83Zqj}u_9k}Pg+`bj!YJ@5QDI~xJetj$O`%wtV` z9r)$jprrf`iV5i@+9!xU?ybkkIo~4lZQwXbde&t#(6F} zu;5l$`()a!f=CD4*qFj3Bnx1B465OQSQ)%i#fbSVZ33VwBYt1!8cINOGAI>j5xNk$ z5*^NCMGAsr|MY%(W=O5y+mh83y&NKQRzy?|1uT-h9rtmTL>kFGL0kL&7n24nqzcKe7WcF z5~BNu=b;NO1|u^E?%y@uIk9Fb%G=vpAPsym4W&ee4$v~#?^^o6Ub-WhWbf-5v_BF>g{S~l;U7K#68cJR5er$b#YiPu7KhnfETnx$^(6LL zTvg2|H6adH96F^91nUZDjc3dSJTTzwmgf(6JDZlp1E5ixRB^M)eh5q&(%{Sj2I4fgMH$ggSmOY+1kSo9-(Yt4vCX z)wjbQrao3dv_X!Cg9HphyU(mglFvCv}M7BCpa7fq@bO`f<$NLS+wy2-}? z&5aUqo|^(f|Qhj(&#*q$ZfwI$T@6#Qnjq;nPcb@WbOz1{1cy(gdC zB>FFT#`Er?Fp?ai3TZCee(fb>b{8TInM9K%A3=5RqTiMOzwhb^DnaqE<0S*Y*&kuy zt>F+7-jen^SRuG}Eh>6r|KjIfr!`;>53&dt{94Zs$s4?jwOViTXh#Fwqv$P3^uI!j z{A@f2M8Xb@(*R-XU{2k2Vf1ReEB?D0NO%8(6(uzH+y}tiIiNGP_HeWybObbw6--}d za&e|(~PDWU&5 zk>3bHS$fr`K{@;hFpQs^w0NwlC&TJ^Us~Vt7p(FsW0VSv25O|`soXXhfaa@FGBB9! z{mLS1t7k}}SLs3%S_jq0{|Ojr6I$+bKm^tcdH^O4)79rwLqlIbow(*?XBT;Yom-B4 zU<@>}tSh!38aKCbuAm}>~9(Y|l+1o62fS8yR0lF!_ z3*JAc4{%S}fl0GLa=QZEPg6B4f?|)-r zL2$4!tLD6CvN?UKRZS(l)OjwXJ<_k4TR!r%pMazChSNpyoSdD>2>3!S6PrUWWf-Ia z!`Dadcg@e!g&c42RE6yRipYNmT5%7KVoM*B5)ccBjFF)6L-*f-+E^AGkm8j?5OAw_ z0ll2lXLlY05JTFIM0Wuop95ra66#d;;L^lWNVtuOqk%pfgt~m?tQgUkod^G(_oUnK zw1c-fVk1RQQ~Sz+h*2(X>g#Bu7w_aV?p?7JR&1w*7Cc`4s@Gc-YRrfymoN6zKan+sdZSuh|aXvJuqz!;!pmxsg1XTN>w*5xnY7=*VV+`sWTG*felA zVggV0OaY>^a`eUJY;InV1^7>Po8zTHQTW#n26}rH8Z#+9G!femZhGjF3W=cOP7laW zRzofR3wlg@s_EyISZ$gu0pk#pcH6?gIIE+5`s-0wd{&)Sqx$vs{e#%dro{zOC89k? z1v|EaTj*NzhU(v-faF=N57yj#2)6d8+7)HCq(55l^54pabr{&#n;myJL;^Ll!OXm#*OZ`bRP1=&Dzja#|+?{6!^Z=>a6TqqzoKG2m} zAQcbTqJHga#T5&}5N1gjNKFeoR7pp#pud#n|4O=;+{h~SrdF1gBfgtlBe)(}c9*6Q zez8C%Mogd=vOjKveOo$s$IkP#c>4=~&V^N$FhO%I&YyNeHz~TKVNjww*m<$DWmfJz z77pI-1OmtE+`09VK9+@zrCz1oa zANDflwppCXrdj~Dtv(Nsq5zY42vC)kPx~FhP64rJta1eMtF7zG2geUrG?cbdZ}tD- z9gb37Gr1`_t61yjBM@n89;{l1xtTtVc(qV4;rui-Ro@b zn0*}OK>HXA%o{9#4<}AGY+w`GJM!+&j;LoU5Qp(kElxH6XmqnuY$;J*B7fGKP5x>1 zaYjb(HF!1r zI2Pgq=ol`j^dC1xMHccE0C#Ke+pbUdhyir zW$3~E)srLUV*cPk6rjBnhg@E8X%&Tshk&*%wM?KdN*5%VP+&`tD${83<|?0AJ2mh? zkb}b^H>}?xK^9X0NNoO3i-%Gt94?+M&Y|-@crKKjyBuqaW5_68K<~NTwzsoU=RLf$ zUbXa6@qpd=<)iJXc)i7JK)1*wk1TOQpUZ<{OW0SyF_4n@_xg>=LCUOvY`>gc*vZ8O zh#uPHCbMJ$Plejs+rgN7zh5A!5q38+5ikJi>307kTzX0GG%#WGWDiWGx*-*EK?i#1 zw?S0d|F$FtY=N(UfxT&c564SzK;;k$%!Dn0eKv^CNVbko^Yegx6b7hJ79d1&88?Hjd7`UIhL04!IasXaT8`yT_Zi7KAm7la>0; zPFWKZlVuc&@`mAL_(iKgz4$o_fXOSvxj(^=fMEFO{E(Jf+Rb%$yub=U20i#NYgSqoo;Y^9}_Q0+b|wvNt35 z+iL<(7Ym2JaB5WL%Z6rLHn-Dr5yksEBUI(iR9l3tP5KMamnSV5SuoTDq^34iQq;JL@LRzM5$OmJG7s; zDk%ZWF7-s%FKuK>O>!&5j;;_AT7V@;2Kpiry(#b~J$*dn8X%-!jRJ)9Ygjq4mxQ2I z;J3H!crn%Azx=7~gc3ND74Ch0MHFzc96^B;vn{jLZx8xRzkhysaqz@r{b7Zav zDaPcH1rD_;!pG^?H3XyNV_E-;(5g#kg{;`pr4)9ui_wk@mpn8 zwnS>-=J2N{{US2U+y|;e-b80bIT=q z?8+y%m1msVCF;yU58oFE8`OF7Pwkq81!5i8W0?Rru>ErS9xvC9{6C036Uk^4it-Ck z>s$v6=qCtyU{{j z$!*%*9Q1R2uitYY6nT$W`u~Kq-_Ce)<9f#?X%hp(M8!Hx7;=M~S!%Wg+K*M;l;wf% zQG#6BYV>)%;|xO){>3yVOq`1v>n24C!f;QrNq_5x#S9d%#cq^UHSd(mC!}b%B!O{U z#lb(WX5I+7;V}6#@TJmZ&hh^7>wVgOa|Z`dB7?Bnu>2bFx4!|$ypO%1hN#RHUag#MF#;Fu6pR11ktxL|Z!=W}pyqJH5i4{wJT8-KjYZsjJak(^wb)3)KvK~%{ zt$B>OOE^c?&xAb8Kip@%mQWB-$q>!3zMK_jXZnJ`mOnQJ_XAIX?(TSn)(eTqyVO^; zT#Nwa`7-Z@?5_RSQ>Uu~o2R3e#(ygUWfM?CHw=O?~8{=5yUZ|T4BuC@Q|6+q zHb$nbstyb!gLlLy01(2z8@B5u!`v=F5}e=FGX6mU?tmAB;5rz{$#6IFgIUPqau(cz z@w;BW&|%#9_=;%O-S%ghQ~z_7I^n&1KVT4=zNKw!X#8$~_%HPM=NCWY=t`ZKD+Rwp z^5Krc@24fXf`ubX=oq&xL+KeQQYS8>FK1qc@N^8o2m*Lu5j*8S$sPvjVnnpj9{6BY zW3{Y*J{TtYgE4)>MS;pSRK-Gh;CCxT78K!u(og;y=54;iS)QAlt5pEU0Mm^HKhK)H zw8l9*{u&3QTZO>kWPeKoMlWdM^k)qUAYegpl^@-?Q=qP;%t9Tx|C@Hm`x~PBM}s=4 zj&#p^A0X2uOV}ae9FM(o-rl=mQ9lXCx5)Kf>1;>dHuDdxRVoml3uhv~B4?jQf zlRg<(N{!l6U{Zo&vwBz;W^rI*Hw(hWbF;aZJRO2f9z!s(nUL^Xcp}#8hb!+=ZGaQu z!LRQlgXQ_bJVermNxHhaZw1eGl2{f_ZVG0y@9Hx&pi1d7cFFWs3<8V z7HNzagHM+Z1_e9cMo^h?fgyA$pnQVeZVE1YeG>fh>pJQufE)&E`x&;wr>X7-)^4Z~ zH&g+g;D8ci5E~G=ya1D!8*X@RXl4PPEXsS%{)X!!yu1U593<91yASfa|5(kC{7Q;g zKkgXWA%R0eO~{x~!wnPeYT-M1 zfd?vMrZc_0y&rfB3y%w<7DR3Iqxy@ z4vWg9biv*2A1=V+&dVub#YEr^KA5b;u(@-1v68A`-S)MS6}5Jug#M6kxxs5e89n5P zgJ3?yB}SB&seoO_sLzT-Z@Hu)OoCY$JwdrB-Ty1?OTeM--oINUlAUakCQD_HvWpNc zCZ)(&OV+Wk*_&j`mNwg1QW?can1m1tMRp_0*!Q)vWq*sv#bBOO{z1{)fRhKm+S+AfoT{KfNUVnVA($C(2MD8Y3rK*QCXn_&*Zytg} zP+!sIKV`G}6iKi2Q@P}4Kh0RflK>r2wVgALGVeZKQtOPM#nmgV*m{Cg%^{DjLr#1h zfW>(L4FsQ`MkyVw;`Z3z2Ws^7ml~N0Z7;XB-$Pa?%#J(Fw0ANJg~KYw)DcaJzpK$D zYTU;6D1RA##ndXOr4t(#|J)b2TwnEzF_7{*%-jbRgpEwFzmKcsSa zBD!-?DVHooXRTX~a&5ZUCB&^;Xc*s%ixy5YiJW`?lHx7pv*wD^#f!$W6PdYh_TUJ4 zRaf+kSf#O%L9KmW?*lgBNRJWNK0!V0}n z6KC7pvR&j7W^9Lp$l9Q-bIUQ_dk0yyQ{cOH_PrFX>31y52=Pgbr~6xDI(I}cA~W7j z8{5NP`t0rUQ5x2#LQWqTH8c;iFp;j2-q;xct{299sV!4>tuOe1oS1AlUKamcb#7O9 zp$n=rRMBtsyM}dJR-%+cch^#^qg?)suSFDm{~+1SvhXsq>f5%rQBdJ@p4Rp|cHE^Z zElqRxcHEq@awLtEu8gAdpk|zcXU_R}sWXwX!?EL6e*PSY8v0g2?=gN6+KgxGMo?9# z3H_MIk3T~rP)2<#n=lfJjxa|Q`YM`xa&*42wj@EML*jVGn=DETTG2}Ssk`q zCcEKC>Tkg#`wbk^z-FeY!DcMB*h~Z~lH9rpy)k^K_<__g(ff)EUsd;s84EKDA|FCW z=-D%8LMIDGlIYgB9NrzoC3(FZ92)wRygnyr$uQ>Tg{eHPj+)jd#E#0mjy-LQN@!9lXgwy^MGhm*+uhx4$q3`zOz z%bFY+tT7*gq|@AIL)IBkSA&$-<eamUfR^JAR$C%?Vlc???I^z*Eu^Xy3-)-$(h zMDIO7%Dq@tC?D%8S&UO8yAZNL6ujxLW!p|c_L<0tV_>;0rf)gPz8^;O>|mdiEkc9! zfY_^&AE~qT^xfVGCudxA$O=q#W}E*VkcaQ%8M$45O-VbveX74$IL z@@Ti+)k>``2J(2LSZw|pYmh`)2d($d7ez-Rf#o_V&+cmqYlj0W( z-8-*Dima>JKW&j%VKZKSC2XR5kd3xfd)mLZ%uQ@CvZ8g&n)H5uFu~YoI&K)w-n*xB;iN(3`n>yCcjAmcx|=82 z|FyP#ky+mPxYcwx4pRlGU_M&8Xi?gJx07m9pD<~>una7^p%RE&%BS~O$s|VaL?Z&m z7qld;dxT$gH)g#s6tawneLtf&f7WToUw)E5yMBE)>tZKFQ2ztcX{yj7gLPW)bgs0< zeSTe)9UxcORA{yw_oDvOK-AhfAEjhNzoFJ1|2Ms}l1evcrrL5Q>`hPna=Ay}A6UqB zGmm26<3DKGB_=e0dE3Dq^Od8IXL2*)8DSK;gI#PPM%FO zil^w)jQh+HASTtM9chz|IgTb)v(c13420hfF~ZSy9kv4xe>4nWb{{}(3>)MMmVECJ z(i_}M#k~1^s~=!&T7J}VWOsc_If!~R(#y~POSbwona$B@>Gggq)95L!5ly_n<1sQC zDPr*Ep>}%})1JT~$er%bz@>|DQsoKKCw|!h?R>ajsX{|KSv@ZS-@x_U_|v9xzZ+M>=j->JEB;I>P*Z!u%A zTHEI6siZV-ITph4l6QVh&k&=IDDRAatFq}w7&HTvO_O&9ZtzQSHY$;w0!?F?m)zvXq#bZe$ft=WD7;)&w5H0EDw`s;a{N!(vA zn5*DCrg#5O|Gm8)rmHB3QzgFvBg{5>6k%eyv_FpLmwx>kJ=xNZ(16mP*WCH*Uu+M) zr(rBOxb^EamBC83^C4A!sSGukCSSG;>#vdiJp^74_(~U#sW{n9342lO3)NhllhVrg z=gWTmbR!Dvc_EWu^4H@wpZUj2d^o(}f&Nj-yPIPD_sjp~6B;NeA{nDkhE>1TGR@q} z_~)>w5;Qo7Ve-F=)jTh^l_>gilpLV{Qa#^j8 zHJVk{_I=B*4EvuI(ge+rJ1BrW_4h}&%G42Zmkuqhj?FhzU%}8Ja^&;`>)&mCkW~l> zL$&2C<>s(48)A<4L$HDf|82Xr%wszR6O0bobyxDQZ2t&CMD2zV>qjBPu?uQh0lyyb z`-kq6qhDQEF1#OO%P@KbAsAN8jQF9|dS_i{9&vK5UR8bY%gcJpD{IopVOJU3g%KNq zho#L88)hg9V%FJk5@S|jk(lY-+}ZO#;j@PxGp zi7$A9i9R~H3m8;A!}ZCf7whL&)`}w}X7Pmlug~ zikY2H3K3?Dj)D6SJXS1|eHV(8n5ih{Mix=%sD06=%xcBaQ=*lzGkC&Yg1~pJ za&jBM@dE}!LqkSWvr9)HL-^wHwlmjVsZRCTx{=H5EuB{A$o7m)fyD*Nycx|28P23o2t-i5N}N`m=tJc2vg~0E)#QVP z;6pHH5@xu}hz97H6P30M(JpF(u8eU^dnxNfvW$5dVviyO_0hP{>dcqDt7>MoDhTIu z;_Ulb729SOdo02W2rs8%G6{AO68^CJL+sf3bh{f|vwdpzONo34M}ct4d~`AkW3jaC zRsn$GhBH9H5n^6lqQb|FTv=NO`3*@ z1C#6JL(O=?h&m!V4Bk+3_~=p2>DeV7mS}!J|JSBp^Q*jc_dlSmuisvrnQ7|;^;`!5 z&QvaVNosG!5T?`YdrH>yDq|m)nQEJ0(~8~{E&G&+;R!Q$PCZe%B6jrw+?G8_zL%I@ zs*5i0lpw!k&ty?RY;@R;HT6LrM%mhrC#?7UTL(1Bsh#;L&U7u_PmasZX0<2L)1q1J z_UGdwPQq5tdh6HZd^pT3*!8q8kFe0Kec07A;zSm6wEUsy>h?azo6gu1*c^Vp(v9P0wSA@Q%jj;Pezd`- zX&Yx=6W3q7?9!MY0z4qVSE+}-%vAhgtxo|BW4fwoh@W+;xwH0v@q@?Cz{nry9tx|x ze_n>0io!jc=w}r^W`SR;W}mg;V~XRU3+{=SKAN@1^FUK!y_HG>ug@ovZg@nSm*q7JV?~Ej<=hNx@ zw;)x`2zIw$-|7`E?z{}%Y@!)g?+yqNk&Pkgdia>pabvuS;t7^L)@OE*FspARPM@`Bz0?Na7V5j)tz-C2dcXE^U-H~ZPjI@(HxJ5;TX zI=JG&_0DfAYl7@%X)t%rJ%RQw$7jqKtlz`xurIo!V>=eS3!=LvgSSjpBxA1<+ODn9zKIGtanyA|b~7qa@1J-3L6 z0S(-srr3en@Vp7Sab!PT+tT&?~o##0*iHryM~62 ziOe$Yr3_p1+u*N^UBMIl=>t!-eR%UijK>z(AvM6T$!x5DK!wXlICAu;+^3OQEdtS) zc~9WF@r5sA@@j(?=&1%6qAM@M>w?k!pyY<$c-HDejR_BOiJNbo`nK3A?9#uHj#F zRo(=3SH=!=Rtie?2p8DJ2CeKM%>||+obRt_H6#8l@q3#CGJx#^-AMs#$uX8a zYmx$3V>sG9tppxofFD6Kbc5XPNmxX|jV7*S^iB8Y+PYI^EE*AA{T-C^`Ahc*Vg%8& zfxWq}&BR|M_N2exM?hK&A@jF=@>oD0@R@D^)OylKR@VGPEPsS9Qv{S9{8Ssm#fXvF zv3#t7P5l|$sjW#LB>!oEOjvf@z47VhOB+ppyYR-|`6f-ioN9Jv@k&D*e50uTd zUDnS@*5Prs_(UNDrHX9h3?4RJ21iOY5`+Rz8t9`t49%vbCPD~`Itgkf-3sVCHm&ho1JGv zPaQ&}x;-NV5lSw92Y;2$&+KaG&0(g*5dBL1MmXU_|Ljtp(gLXXF|*nTV#oK&*edXt zSY=-EvugHC(b{}Wjfq2@oMv@w(Qi=6a_oES&RLY`J9moHF7A@M8`AyCqo7Ah1o5{v z|09nVWPoP4s@08(g_U*6GQ5%dV;~}Rv11ZIQIkfX!5F9y&b>@*e$=7H%fNmeU#zCK z9I9C&VeveKLP$tx!x;P((pDPG=>{W*HGaw={JTDy%>bQjm}~K+=c)Xw3E+eYLr~5# z%O*}+gj@3?YSeCcnVS#2&B-}NO2lJk9U+{j5OgbM?bHX4q3t{v_07W@y_)l3A+;J` zFRiWXL`W0{7z9kuWD+i{0jw`QGBo7&W67t`z%XE;Xl~ctD=x%ah80uY%Rkf@3tfb5v3D|!A>3vjtS)#qwZ}bSq(&+q? zk^fyd36pX1oL%N}WTdRf^31si0moY*;Tc{S%cr!rBe&+?kYaQ|Emj}~xd&#F^{bXz zBun(}T#vi8d;b-TSL+5vipz zTe2HxZHSM%*+@^1^avpGy;|5vn{SuW!gRuCOMACWty+Z~lnh;?(rW9hqf*8wF>(~{ zY|+K)H};&Rx{!RtVDw`J-Aoy*`ZX7t}

kd{;rS=_d6SznlO$DBbuGLZ!i4<7k)Eqy8&k{P)Qy^G=YV z2fxtbWYdcm8-Ll}!lnf*9&*H0*~SISbLQRt_h@-<-711XOnWuOhuk=qo***Yn^tSR zy)?vD2$2i>o}d0bl+zI2EeCU?rc}%~KVa42!Tj{X#a=PQC0>Ny^RIL<|N6|f9a#VY z6d}(B7zY*tVHI6`^LzjN7}KH+&lu;)DFiQ~?XKo-#sWIpe@~CM87xE6PCds|;rl5P zxW-Fr(~Qv?x6671T%=o(T4bzmQ zQJ*W&Q}+Sw>`idw$Oq;NJ`;_wYj$p94R)LqZ^Dkx?pe?4bPoiy;#=O>b^0G4K19B- zWC)t3W?Ev+s)I_3T*q=uKi%gqeiu(upCZ3e|LKlpLxy*d-xhUjIs^*C(}uMtywQe` zyZ1E_DOtHH&A!*>t>F=b00Y%KVT1+>eSkT-9nnN&f2uOC%vhkrzBlqpE!2#&kP9Co zc4$OMtb|s#X!8BICbQq~)6C*V4ZBMcVZoDe=@TmB8X>4rn%#^N%8J>FzHg-&`}pIO zn&+=;2p-;mw7_Lq$;s>oY%DI3yr&2;kF%^Y0|>5XAcik=+}A4=d~Gj^H=tAq5dCt; zV$0w;Ro`durbrB*PLANymc;Tv_eeL~LcM2{#|+2I! zkZzfj_kANZI-=CFpdj4{VMfky&;^gQ{frChJ9oRx)MQP8fr_uovaoy%Zc~eRO*B5h zJp%RYbJg9xmfRXgca*OFsELJcB~t8JF50(m4oSZgc*nfPUvIW_54Hrs{UHo{bFbs;$ zWZ>2ra@aPo7yQEL{}YCI zCCLuWj627M<+!R*X^;QIkcaGM-Fqnm0@V0YnHN^p>N(AjnVFfwqL7M(s*gg$STJx& z#_A@%Tp5u&j#KArO>CxKjLULFN#EC)U}-b_31^?4Az!^V4#n-KXF@HR=Auq*_r0GI z)jlkBRkibIk_ARNr3KY#30C4=3!BD?2J*NyKmT&y6Q^bHv!$@fd;{*1r2F_qx<^== z)(X=MpLzKbNilC_0SDf)ve2{R2(Dx%;- zMfY5B@5G5p$fM+>Py~L4S-`c^?ee@_YXYVv7xp8+0+Y+jQFHuW74!g;it9 zOdTUb)&=@@Z`;PeSmD=2b{bL?VsoT6WurjOW{@KX7mc7AqtwgdF)NTnFR0k-~j8aS^N8ikV| z!+DEKVIkOS_^Bg^(!13@X02i|LpPeDAQsjWXU7Hup{KBx66{=DTUfNfaqdlHKIc`~%6Ryr5!0N*EB$9;g5K9z$M8dI>bu4wH3b0a_l9zK2? zDJCo&&J}-&SV1tT3X6Hoh%9a|R-ORVehw8ys8lP#V-*IKf-~ML+qfM+xH265BELoRM zg(K-_$r(6#i+EBhUd@y8dC~hNeQXPC|Nb0#6PPeYgXy8T$&s+z<8~)Tpf7KC*gjmC z6gkrDu89kBn>B55CFkgW<-Fvd{!jsRu_!UWtl{)kp0!D&1~>T5@{ztKR@%`u&{xWn@!I#H)`v~pn2&W5I3H|ookmaUhHd{JN7hA>JC<) z6#j7UeFo>pusE$Yi4aRYw_N zGLProJkbE|c4lh4l?UwXrd-PlvO^Dbu-UfYq9Z!11e1Lb%mU{fvo@9|UJb!z;?Z_* z+E2Ta-1KAz@2L(pofCTmgdIVJN=`wq@5kQc1vNJkAV4@kmM7{aXZtl`uGNc7?-PVG1WHG90fFy1XKdW9J0b$~ z6!&gV%MmP4=tGr)N3brD`@JV$JH!1Cf^z%C>Sp^n=C1Q>R;s^Q!94*edZo&mgm-+W zfD^P&RHD3n-z7sww|*vpdgtk#wF8mzb?vfT-d0v?fSf@uQdnXXWCtSB-8Y}k&X5D4 zmCSzc+63tfCClSNf(+}V8Nd9G^^|n`54V|YbY@H2cO8x~a*tD(Yf!E8M{g@0N%B4m z7pf&16@kxX3RS~yvuk>G2Fa^8+fZLGKcny>GxH&oKANx_qdxKj^6Y9LewhQqh`hPr zIbAR^NbmnswVX#n(2FtL{Jac_AtlW@qO&irv)(i{5_HG8M4@5Cd3|+>;P)MPe)-kV zz=sup3cwRi)vwn5vN3XU!zqb-EyubtoFmk|hkeBJ``#0k??##bbgb|B!9HVnttl~T zySnHq$2*NOR2IopHaN1O#Ht#HaeYUshIKCJg7rYkr1iPI8wi)Iy9Wm?%cyih0w4$~ zks}2MqAbs`3h7n@!EyXf8>HAV`8|G}?Zw=RQrPBRl*fwF(%^%-`Padeo%tm91W7tl zD8A@CZ0IE(e(hrXw{f2_dbs+DtkwL!>Tm8e%Q>xa?IJe`0IBC(*1I2{@xlw;-VP%) zNs#J(A~Pm|nAA0neWDutx%t9L5sx0OA2GPv#oeL+5__U;n9$1U0ow^`>9u8UO8+ei+6SDMYe^{M;9dsbe4;`|Z z&W^OZ>R}zlA$hvcV@A}(=exSwEp8Eq6qT;s2Yj?Au1Z}#aKbj$b+kdn)sWLd(B&<+ zRppqxS@~Fp4RQm>tq&^bCLicUW`bIInJhd9=p+$>ah#vJS zEPhNjr8?Dm9b9g`k^x-*Ck)w1Pk$4nb#*T|vQ7fzon!GO9{<^Yluf$ubYT#giaH4? z@FjyUV>jBA;$-=}vN|UoTa{vi|BNFIu8{I3)S)DrCK(;)&28tWu#q`qqO}@4o@$j5 zTq6{Z2;8A}no(y>0Zc#UK6zDeGIQc9+$YSOWUU{qXYBdBP@xLAmqNSuJKkcp^#}I^ z(5az`QPl0%;dHpC^I;bhzN_IxUuPu-wE}|uz<+%>S9Dy9| zy^5Of<+6T>JCQF zDtb{ebL`oKync(MfCu)u28r&i_-u@Ui*LTe_JNbCj&zNemHsx`g9O)rY1>xis~$Hh ziNTSNvc$0Kz+`@IS)YVdUK@xyDUhd$(pjEsz7PZcq~nMXlcH4Y`oMt=;1PRSEd>YA z$!RY1`1_9}b7IqO-h^l&z=(7xU0cZUS#q{+O#Qg;87f|Vh7rF;f*$f`9!L$Y=51Fh zE)~}Y(I1$eoNN8TVs37p^W{Y6v$x^>Eoa#n+x$wMS3nZCJ-R({U5*vBo5XCma0FXJ z2#<&#%YANw7|XH|=^^tvW%^v^8pODyZW5bh8o9^Z0-Hm#d~;khzxjwIl~DwjTmL2p zawv&A+}m+rLDI=NoEmeUMYD~DaUvmu=-~%+#zY30Zn6@{n?b|fOpB0l&W$s^Msg?H z5<3dzU3=eSkm>upt(JC^6y@O5@J7x82!{Ce*V7+bNkly(w@0~L`P+lp%C5rh)A4Wq zBZ(ew5G`&kY%^nQw48TO+!)C_@v`hC<@3f%Ob*5Kk7t?APqjra-~k>c+F^vjoJmE6?w zIMn9R!iLnld|6XP1*0SA0rao=<0GqvH7r&IJ8097hh$AOI8$<_+N9u*za*TD?+Ei@0DrsV{-+n_V^6v)3F({NVsGazTziP{!N zxk?iZG~NU@kEe=Jx1uH+_4CPolIl`tLjRg=%UJx|26Ry%vvAG@ygkpm!LS&2D(%hzQ@ z*rIFupvuBIl#d-{r@aCPjr6a^lw>UAQ?O9Gq-w9wBSSgL2mpJ z-*08R<^6M&O=8pQV|i@SO^zBtL_>c0HhNA=P%D1$os5Ln4I7!Mg~H<>;?Tb>8o63J zW&oQ3xoyFX=D1rKVrCf=a7cc${=~*O-3{839T?@r)cL?>ukQ^{R1=L7$jMD^MsAjB zjk{HZ4e6j9nkXy_2~5U?HdIw3gQzhV=UH@I0J))Ieg2g{znk<;mT>bcGWfDlI{C@$ zkLQ@o8r|4df)DtOt~N2TG^)M=BBJ8Qk=ak=qP;vG#KQxm1|* zWFp6%E2eu31bS`6b@gQM*~{ew$ZciBR98ozM!oSmVl3>3=$lJ$C>d*EBRU^MncaMU zYr9k1Or-quJp+g0E6~|9(Nc%s!;wfzL6xYU^B4_d8sG-1u(NRvn?bO2W5V-i&u*M@ za&qcoyCBekR2(5s+T^;G;=t6K&bsz8$P?q(eXk`GaakNl4UbXu)Hkz8*~$XJJhiZH zhr)#yJnigA^b#{|?7VD~nD?9mHE^R(X8|8V)d#Nr>S}2DlEZT}^SKNp(bMN#?+45m z6fR1swfeWI)?BoTyPKMdh?BI81lqg8r{|qNT%oSZPc92WBEJ~l?AwJ4nuETJLr=7; zCBhU_{k?g;kapYM(}J22{U0U2YWrnvbv@g__3XV$5p>UB$C%f_e#jz)mTwnzL_&Q6 z8E8H;FM3-VKf8@Q6D^Kl7(5+9OgSHLgZ2g4^S(QL@f;nwJtdW&I&VK_dQWSK8U0#2 zWb`5zl$M^&I_2Awp23a9NO>qf0^sr#lai%jE=$}zghXS@6yqw=fV%kb85u>mPs$n! z5xmY++pA=q3vlo9d>z|%&Yx&mHpRS$VSW?O z(!|Y$4k?`XzIj>@tGkihwW%r-sLaQ z`qKMQwb7`h(7v(Mh`~Jwm<^cDr()Gg88j{qcA+YM1v&WY>br0O^#njRC+D!9l%>^AfeE6z9VEYn{vs^cm z1p8c#%;cfa!^(ZM4{QeGsTdSYx>???g6CI?RQRDe^87K%%+RDC_uRD_KR;M@{_K=5Um}`I{)kgf52Cm zwB8-u1WM}dss2}l@ZJ$Ivl@)~4+Oi}NZxMg`0H$i|(Q=5Hw1;qK{&d9KUqQ?)zMpo0;w8n8*;&1qn3$2Ooli1@ z<@4`$Vl1#10g}r#bbHgkfcml5E8EKY=cTfQi_J8Ds_{QSNhx&;ht=@VQ0RKUrq=r@ z);@lyRGrFCbLB>`9-^@&al5n@=6PhiLa3xbM&OLT#3^}BYLdlh6XN%igoz>3M`lb3ms@*GC*8h%`w=TED|zpt zPPczL$wGwG=pm0KUi`kdF!zKTp}$WucKuVs&OZgNjDlrrEdxf2 z;t_6)1$QE`@bR7Ic~PBHg3p}5P?%Aepu~rjZs@PK-fm$O@(#dLB<;_zYl~95P7tRO zAmO%*`6>(ikInT)~flR46g;Dox3j5 zmnWZp=AYWg6&Hg?wIfmluM%73+F%h zV}tf~!4|#-+rvG&ZO1LdD^Z1S!V$)Iny*xtlMD@|8LewA8%S{tod1)grLMjoe?*kq z=+#vDkBza!YtCOH9=lTZazb%0F0m>Kh7wqF3tmGT{%XwmTT04gVoCGqa}`ul=S|@z zr+SEBYXjtF&;dB^AP6laKl9GzW7G3<2b%mxWz3fX7&m+p=~Qyfi9u@4>^% zZVyxqN%x)cxg-^j_2hy1!l7xn9O4gmgh>a_ From eb22d00bba76f923781202c84fe85ab194cc16f6 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 10:04:13 +0200 Subject: [PATCH 109/132] Set license --- tracetools/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools/package.xml b/tracetools/package.xml index ca68c2f..0556e28 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -5,7 +5,7 @@ 0.0.1 ROS 2 wrapper for instrumentation Christophe Bedard - TODO + Apache Software License 2.0 Ingo Luetkebohle Christophe Bedard From 9c0f08aae029995c1af8186f31822e84a76439fc Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 10:05:06 +0200 Subject: [PATCH 110/132] Add another maintainer --- tracetools/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/tracetools/package.xml b/tracetools/package.xml index 0556e28..fcc90f1 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -5,6 +5,7 @@ 0.0.1 ROS 2 wrapper for instrumentation Christophe Bedard + Ingo Luetkebohle Apache Software License 2.0 Ingo Luetkebohle Christophe Bedard From 2b6966fd703de0bf3baa2d901fa9bf7c6f200044 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 10:13:55 +0200 Subject: [PATCH 111/132] Rename 'depth' to 'queue_depth' --- tracetools/include/tracetools/tracetools.h | 4 ++-- tracetools/src/tp_call.tp | 8 ++++---- tracetools/src/tracetools.c | 8 ++++---- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 26c8fd4..388bcf3 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -44,7 +44,7 @@ void TRACEPOINT( const void * node_handle, const void * rmw_publisher_handle, const char * topic_name, - const size_t depth); + const size_t queue_depth); /** * tp: rcl_subscription_init @@ -55,7 +55,7 @@ void TRACEPOINT( const void * node_handle, const void * rmw_subscription_handle, const char * topic_name, - const size_t depth); + const size_t queue_depth); /** * tp: rclcpp_subscription_callback_added diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index dc58fb4..932118a 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -36,14 +36,14 @@ TRACEPOINT_EVENT( const void *, node_handle_arg, const void *, rmw_publisher_handle_arg, const char *, topic_name_arg, - const size_t, depth_arg + const size_t, queue_depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_publisher_handle, rmw_publisher_handle_arg) ctf_string(topic_name, topic_name_arg) - ctf_integer(const size_t, depth, depth_arg) + ctf_integer(const size_t, queue_depth, queue_depth_arg) ) ) @@ -55,14 +55,14 @@ TRACEPOINT_EVENT( const void *, node_handle_arg, const void *, rmw_subscription_handle_arg, const char *, topic_name_arg, - const size_t, depth_arg + const size_t, queue_depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) ctf_string(topic_name, topic_name_arg) - ctf_integer(const size_t, depth, depth_arg) + ctf_integer(const size_t, queue_depth, queue_depth_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 97123e7..9a21713 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -49,7 +49,7 @@ void TRACEPOINT( const void * node_handle, const void * rmw_publisher_handle, const char * topic_name, - const size_t depth) + const size_t queue_depth) { CONDITIONAL_TP( ros2, @@ -58,7 +58,7 @@ void TRACEPOINT( node_handle, rmw_publisher_handle, topic_name, - depth); + queue_depth); } void TRACEPOINT( @@ -67,7 +67,7 @@ void TRACEPOINT( const void * node_handle, const void * rmw_subscription_handle, const char * topic_name, - const size_t depth) + const size_t queue_depth) { CONDITIONAL_TP( ros2, @@ -76,7 +76,7 @@ void TRACEPOINT( node_handle, rmw_subscription_handle, topic_name, - depth); + queue_depth); } void TRACEPOINT( From 8704f0591d81285df19f89985f81a3ed1de117c1 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 10:20:15 +0200 Subject: [PATCH 112/132] Fix Python indent --- tracetools_test/test/test_node.py | 13 ++++++------ tracetools_test/test/test_publisher.py | 13 ++++++------ tracetools_test/test/test_service.py | 13 ++++++------ tracetools_test/test/test_service_callback.py | 13 ++++++------ tracetools_test/test/test_subscription.py | 13 ++++++------ .../test/test_subscription_callback.py | 13 ++++++------ tracetools_test/test/test_timer.py | 13 ++++++------ tracetools_test/tracetools_test/utils.py | 20 ++++++++++--------- 8 files changed, 60 insertions(+), 51 deletions(-) diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index 18aae36..51e0a6e 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -20,12 +20,13 @@ class TestNode(unittest.TestCase): session_name_prefix = 'session-test-node-creation' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - node_creation_events, - None, - PKG, - test_node) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + node_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 1eb4544..3ad4c23 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -19,12 +19,13 @@ class TestPublisher(unittest.TestCase): session_name_prefix = 'session-test-publisher-creation' test_node = ['test_publisher'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - publisher_creation_events, - None, - PKG, - test_node) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + publisher_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_service.py b/tracetools_test/test/test_service.py index 0e10508..e61937a 100644 --- a/tracetools_test/test/test_service.py +++ b/tracetools_test/test/test_service.py @@ -20,12 +20,13 @@ class TestService(unittest.TestCase): session_name_prefix = 'session-test-service-creation' test_nodes = ['test_service'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - service_creation_events, - None, - PKG, - test_nodes) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + service_creation_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_service_callback.py b/tracetools_test/test/test_service_callback.py index fccdccd..40c8b87 100644 --- a/tracetools_test/test/test_service_callback.py +++ b/tracetools_test/test/test_service_callback.py @@ -20,12 +20,13 @@ class TestServiceCallback(unittest.TestCase): session_name_prefix = 'session-test-service-callback' test_nodes = ['test_service_ping', 'test_service_pong'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - service_callback_events, - None, - PKG, - test_nodes) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + service_callback_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index 54e3166..ae25980 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -20,12 +20,13 @@ class TestSubscription(unittest.TestCase): session_name_prefix = 'session-test-subscription-creation' test_node = ['test_subscription'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - subscription_creation_events, - None, - PKG, - test_node) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + subscription_creation_events, + None, + PKG, + test_node) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index d51b2ae..eb3e7d1 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -20,12 +20,13 @@ class TestSubscriptionCallback(unittest.TestCase): session_name_prefix = 'session-test-subscription-callback' test_nodes = ['test_ping', 'test_pong'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - subscription_callback_events, - None, - PKG, - test_nodes) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + subscription_callback_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index fc12b42..999f78e 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -22,12 +22,13 @@ class TestTimer(unittest.TestCase): session_name_prefix = 'session-test-timer-all' test_nodes = ['test_timer'] - exit_code, full_path = run_and_trace(BASE_PATH, - session_name_prefix, - timer_events, - None, - PKG, - test_nodes) + exit_code, full_path = run_and_trace( + BASE_PATH, + session_name_prefix, + timer_events, + None, + PKG, + test_nodes) self.assertEqual(exit_code, 0) trace_events = get_trace_event_names(full_path) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index af9e0ae..660dc8d 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -16,12 +16,13 @@ from tracetools_trace.tools.lttng import ( ) -def run_and_trace(base_path, - session_name_prefix, - ros_events, - kernel_events, - package_name, - node_names): +def run_and_trace( + base_path, + session_name_prefix, + ros_events, + kernel_events, + package_name, + node_names): """ Run a node while tracing. @@ -41,9 +42,10 @@ def run_and_trace(base_path, nodes = [] for node_name in node_names: - n = launch_ros.actions.Node(package=package_name, - node_executable=node_name, - output='screen') + n = launch_ros.actions.Node( + package=package_name, + node_executable=node_name, + output='screen') nodes.append(n) ld = LaunchDescription(nodes) ls = LaunchService() From bcc8540fe825a4947704eb6aa308a10915515042 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 10:25:25 +0200 Subject: [PATCH 113/132] Include tracetools version string as an arg for rcl_init --- tracetools/include/tracetools/tracetools.h | 2 ++ tracetools/src/tp_call.tp | 4 +++- tracetools/src/tracetools.c | 3 ++- 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 388bcf3..a266dbd 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -8,6 +8,8 @@ #define TRACEPOINT(event_name, ...) \ (ros_trace_ ## event_name)(__VA_ARGS__) +#define TRACETOOLS_VERSION "0.0.1" + #ifdef __cplusplus extern "C" { diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index 932118a..871ac09 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -4,10 +4,12 @@ TRACEPOINT_EVENT( ros2, rcl_init, TP_ARGS( - const void *, context_handle_arg + const void *, context_handle_arg, + const char *, version_arg ), TP_FIELDS( ctf_integer_hex(const void *, context_handle, context_handle_arg) + ctf_string(version, version_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 9a21713..33505ba 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -24,7 +24,8 @@ void TRACEPOINT( CONDITIONAL_TP( ros2, rcl_init, - context_handle); + context_handle, + TRACETOOLS_VERSION); } void TRACEPOINT( From e7ed83217ef43bc6ef10afaaf820e6c40c1a1e12 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ingo=20L=C3=BCtkebohle?= Date: Mon, 17 Jun 2019 08:48:37 +0000 Subject: [PATCH 114/132] Add a short intro. --- doc/design_ros_2.md | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 668aea2..d2bfa37 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -2,6 +2,13 @@ Design document for ROS 2 tracing, instrumentation, and analysis effort. +## Introduction + +Tracing allows to record run-time data from a system, both for system data (e.g., when a process +is being scheduled, or when I/O occurs) and for user-defined data. This package helps with +user-defined trace data within the ROS2 framework, e.g. to trace when messages arrive, +when timers fire, when callbacks are being run, etc. + ## Goals and requirements ### Goals From d0425d2c57363d71fa665bc6475a587051e14e9d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 11:15:57 +0200 Subject: [PATCH 115/132] Get package version directly from ament --- tracetools/CMakeLists.txt | 2 ++ tracetools/include/tracetools/tracetools.h | 2 -- tracetools/src/tracetools.c | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index 3913967..0b1d47c 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -99,3 +99,5 @@ if(BUILD_TESTING) endif() ament_package() + +add_definitions("-D${PROJECT_NAME}_VERSION=\"${${PROJECT_NAME}_VERSION}\"") diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index a266dbd..388bcf3 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -8,8 +8,6 @@ #define TRACEPOINT(event_name, ...) \ (ros_trace_ ## event_name)(__VA_ARGS__) -#define TRACETOOLS_VERSION "0.0.1" - #ifdef __cplusplus extern "C" { diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 33505ba..0e573d1 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -25,7 +25,7 @@ void TRACEPOINT( ros2, rcl_init, context_handle, - TRACETOOLS_VERSION); + tracetools_VERSION); } void TRACEPOINT( From 55127d0c3176549b9c293068e61c006165feac8a Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 11:41:42 +0200 Subject: [PATCH 116/132] Use void* as return type of get_address() --- tracetools/include/tracetools/utils.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tracetools/include/tracetools/utils.hpp b/tracetools/include/tracetools/utils.hpp index d5b6377..46b091b 100644 --- a/tracetools/include/tracetools/utils.hpp +++ b/tracetools/include/tracetools/utils.hpp @@ -5,7 +5,7 @@ #include template -size_t get_address(std::function f) +void * get_address(std::function f) { typedef T (fnType)(U...); fnType ** fnPointer = f.template target(); @@ -13,7 +13,7 @@ size_t get_address(std::function f) if (fnPointer == nullptr) { return 0; } - return (size_t)*fnPointer; + return (void *)*fnPointer; } const char * get_symbol(void * funptr); From b41c59fbddc719d692cd4192965d3d37e1f480c4 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 15:58:20 +0200 Subject: [PATCH 117/132] Fix unused params when lttng not enabled --- tracetools/src/tracetools.c | 9 +++++++++ tracetools/src/utils.cpp | 1 + 2 files changed, 10 insertions(+) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 0e573d1..ec264f6 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -17,6 +17,11 @@ bool ros_trace_compile_status() #endif } +#ifndef _WIN32 +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wunused-parameter" +#endif + void TRACEPOINT( rcl_init, const void * context_handle) @@ -193,3 +198,7 @@ void TRACEPOINT( callback_end, callback); } + +#ifndef _WIN32 +# pragma GCC diagnostic pop +#endif diff --git a/tracetools/src/utils.cpp b/tracetools/src/utils.cpp index 8286bc5..8ced911 100644 --- a/tracetools/src/utils.cpp +++ b/tracetools/src/utils.cpp @@ -25,6 +25,7 @@ const char * get_symbol(void * funptr) const char * demangled_val = (status == 0 ? demangled : info.dli_sname); return demangled_val != 0 ? demangled_val : SYMBOL_UNKNOWN; #else + (void)funptr; return SYMBOL_UNKNOWN; #endif } From f720c450fc165c85b3507f9aa61ea5b75a00d294 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ingo=20L=C3=BCtkebohle?= Date: Mon, 17 Jun 2019 14:08:59 +0000 Subject: [PATCH 118/132] Initial gitlab-ci.yml --- .gitlab-ci.yml | 26 ++++++++++++++++++++++++++ tracetools/package.xml | 2 +- tracetools_test/CMakeLists.txt | 1 + tracetools_test/package.xml | 2 +- 4 files changed, 29 insertions(+), 2 deletions(-) create mode 100644 .gitlab-ci.yml diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml new file mode 100644 index 0000000..f7dadea --- /dev/null +++ b/.gitlab-ci.yml @@ -0,0 +1,26 @@ +image: ros:dashing-ros-base + +variables: + DOCKER_DRIVER: overlay2 + +before_script: + - apt update + - rosdep update + - rosdep install -y --from-paths . -i . + - ln -s src + +build: + script: + - colcon build + - colcon test + artifacts: + paths: + - install + +build_enabled: + script: + - colcon build --cmake-args -DWITH_LTTNG=ON + - colcon test + artifacts: + paths: + - install \ No newline at end of file diff --git a/tracetools/package.xml b/tracetools/package.xml index fcc90f1..6bb4256 100644 --- a/tracetools/package.xml +++ b/tracetools/package.xml @@ -13,7 +13,7 @@ ament_cmake pkg-config - + liblttng-ust-dev ament_lint_auto ament_lint_common diff --git a/tracetools_test/CMakeLists.txt b/tracetools_test/CMakeLists.txt index 02ab483..a7d339e 100644 --- a/tracetools_test/CMakeLists.txt +++ b/tracetools_test/CMakeLists.txt @@ -17,6 +17,7 @@ if(BUILD_TESTING) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) find_package(std_srvs REQUIRED) + find_package(tracetools REQUIRED) add_executable(test_publisher src/test_publisher.cpp diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index 075b068..ad628fd 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -24,7 +24,7 @@ ament_lint_common launch_ros python3-pytest - tracetools_trace + tracetools ament_cmake From 8e80d8b4fdf3b84a53ea8e59b1fdbfed35f468d3 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Mon, 17 Jun 2019 16:29:57 +0200 Subject: [PATCH 119/132] Update event names in tests --- tracetools_test/test/test_service_callback.py | 4 ++-- tracetools_test/test/test_subscription_callback.py | 4 ++-- tracetools_test/test/test_timer.py | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/tracetools_test/test/test_service_callback.py b/tracetools_test/test/test_service_callback.py index 40c8b87..7a1f928 100644 --- a/tracetools_test/test/test_service_callback.py +++ b/tracetools_test/test/test_service_callback.py @@ -9,8 +9,8 @@ from tracetools_test.utils import ( BASE_PATH = '/tmp' PKG = 'tracetools_test' service_callback_events = [ - 'ros2:rclcpp_service_callback_start', - 'ros2:rclcpp_service_callback_end', + 'ros2:callback_start', + 'ros2:callback_end', ] diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index eb3e7d1..7e80437 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -9,8 +9,8 @@ from tracetools_test.utils import ( BASE_PATH = '/tmp' PKG = 'tracetools_test' subscription_callback_events = [ - 'ros2:rclcpp_subscription_callback_start', - 'ros2:rclcpp_subscription_callback_end', + 'ros2:callback_start', + 'ros2:callback_end', ] diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index 999f78e..c577efc 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -11,8 +11,8 @@ PKG = 'tracetools_test' timer_events = [ 'ros2:rcl_timer_init', 'ros2:rclcpp_timer_callback_added', - 'ros2:rclcpp_timer_callback_start', - 'ros2:rclcpp_timer_callback_end', + 'ros2:callback_start', + 'ros2:callback_end', ] From 2a1d2db8f00b50ad8fd1f9ddfc2688bf73174c01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Ingo=20L=C3=BCtkebohle?= Date: Mon, 17 Jun 2019 14:50:07 +0000 Subject: [PATCH 120/132] Ci reporting --- .gitlab-ci.yml | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index f7dadea..92d356a 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -16,6 +16,9 @@ build: artifacts: paths: - install + - build + reports: + junit: build/**/Test.xml build_enabled: script: @@ -23,4 +26,7 @@ build_enabled: - colcon test artifacts: paths: - - install \ No newline at end of file + - install + - build + reports: + junit: build/**/Test.xml From f1d38ab6fd2c6386e84aa8b62d41467f20874326 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 08:53:46 +0200 Subject: [PATCH 121/132] Add license file --- LICENSE | 202 ++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 202 insertions(+) create mode 100644 LICENSE diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + 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. From 9cc1f5f29b2e8f587e7c7e08cc6717adec3c1393 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 09:10:05 +0200 Subject: [PATCH 122/132] Add copyright headers --- tracetools/include/tracetools/tracetools.h | 14 ++++++++++++++ tracetools/include/tracetools/utils.hpp | 14 ++++++++++++++ tracetools/scripts/setup-lttng.sh | 14 ++++++++++++++ tracetools/scripts/trace.sh | 17 +++++++++++++++-- tracetools/src/status.c | 14 ++++++++++++++ tracetools/src/tp_call.tp | 14 ++++++++++++++ tracetools/src/tracetools.c | 14 ++++++++++++++ tracetools/src/utils.cpp | 14 ++++++++++++++ tracetools_test/src/test_ping.cpp | 14 ++++++++++++++ tracetools_test/src/test_pong.cpp | 14 ++++++++++++++ tracetools_test/src/test_publisher.cpp | 14 ++++++++++++++ tracetools_test/src/test_service.cpp | 14 ++++++++++++++ tracetools_test/src/test_service_ping.cpp | 14 ++++++++++++++ tracetools_test/src/test_service_pong.cpp | 14 ++++++++++++++ tracetools_test/src/test_subscription.cpp | 14 ++++++++++++++ tracetools_test/src/test_timer.cpp | 14 ++++++++++++++ tracetools_test/test/test_node.py | 14 ++++++++++++++ tracetools_test/test/test_publisher.py | 14 ++++++++++++++ tracetools_test/test/test_service.py | 14 ++++++++++++++ tracetools_test/test/test_service_callback.py | 14 ++++++++++++++ tracetools_test/test/test_subscription.py | 14 ++++++++++++++ .../test/test_subscription_callback.py | 14 ++++++++++++++ tracetools_test/test/test_timer.py | 14 ++++++++++++++ tracetools_test/tracetools_test/__init__.py | 13 +++++++++++++ tracetools_test/tracetools_test/utils.py | 14 ++++++++++++++ 25 files changed, 350 insertions(+), 2 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 388bcf3..93a3374 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #ifndef TRACETOOLS__TRACETOOLS_H_ #define TRACETOOLS__TRACETOOLS_H_ diff --git a/tracetools/include/tracetools/utils.hpp b/tracetools/include/tracetools/utils.hpp index 46b091b..a1a55a7 100644 --- a/tracetools/include/tracetools/utils.hpp +++ b/tracetools/include/tracetools/utils.hpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #ifndef TRACETOOLS__UTILS_HPP_ #define TRACETOOLS__UTILS_HPP_ diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index da5ae8e..84dbaf2 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -1,4 +1,18 @@ #!/bin/bash +# Copyright 2019 Robert Bosch GmbH +# +# 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. + # set up ust ros2 events for event in \ diff --git a/tracetools/scripts/trace.sh b/tracetools/scripts/trace.sh index 68dc29d..e29a01c 100755 --- a/tracetools/scripts/trace.sh +++ b/tracetools/scripts/trace.sh @@ -1,7 +1,20 @@ #!/bin/bash +# Copyright 2019 Robert Bosch GmbH +# +# 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. + ## Helper script for ROS tracing -## Christophe Bedard -## see: https://github.com/bosch-robotics-cr/tracetools/blob/devel/scripts/example-run-script.sh +## ## Call this by providing these arguments: ## 1. a session name [optional; 'ros2' will be used] ## 2. a wait time before killing and stopping (in seconds) diff --git a/tracetools/src/status.c b/tracetools/src/status.c index fc54ea0..006ad72 100644 --- a/tracetools/src/status.c +++ b/tracetools/src/status.c @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "tracetools/tracetools.h" diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index 871ac09..76be2d3 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include TRACEPOINT_EVENT( diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index ec264f6..c7bf5f7 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include "tracetools/tracetools.h" #if defined(WITH_LTTNG) && !defined(_WIN32) diff --git a/tracetools/src/utils.cpp b/tracetools/src/utils.cpp index 8ced911..2d48ffa 100644 --- a/tracetools/src/utils.cpp +++ b/tracetools/src/utils.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #if defined(WITH_LTTNG) && !defined(_WIN32) #include #include diff --git a/tracetools_test/src/test_ping.cpp b/tracetools_test/src/test_ping.cpp index 9491eda..237e074 100644 --- a/tracetools_test/src/test_ping.cpp +++ b/tracetools_test/src/test_ping.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include diff --git a/tracetools_test/src/test_pong.cpp b/tracetools_test/src/test_pong.cpp index 4dc167b..6d640b3 100644 --- a/tracetools_test/src/test_pong.cpp +++ b/tracetools_test/src/test_pong.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "rclcpp/rclcpp.hpp" diff --git a/tracetools_test/src/test_publisher.cpp b/tracetools_test/src/test_publisher.cpp index 886e571..cb0068d 100644 --- a/tracetools_test/src/test_publisher.cpp +++ b/tracetools_test/src/test_publisher.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "rclcpp/rclcpp.hpp" diff --git a/tracetools_test/src/test_service.cpp b/tracetools_test/src/test_service.cpp index f44cfbb..091bb4e 100644 --- a/tracetools_test/src/test_service.cpp +++ b/tracetools_test/src/test_service.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "rclcpp/rclcpp.hpp" diff --git a/tracetools_test/src/test_service_ping.cpp b/tracetools_test/src/test_service_ping.cpp index 43a63dd..5e097eb 100644 --- a/tracetools_test/src/test_service_ping.cpp +++ b/tracetools_test/src/test_service_ping.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include diff --git a/tracetools_test/src/test_service_pong.cpp b/tracetools_test/src/test_service_pong.cpp index 29be746..79b098b 100644 --- a/tracetools_test/src/test_service_pong.cpp +++ b/tracetools_test/src/test_service_pong.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "rclcpp/rclcpp.hpp" diff --git a/tracetools_test/src/test_subscription.cpp b/tracetools_test/src/test_subscription.cpp index f8d1002..48593cc 100644 --- a/tracetools_test/src/test_subscription.cpp +++ b/tracetools_test/src/test_subscription.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include "rclcpp/rclcpp.hpp" diff --git a/tracetools_test/src/test_timer.cpp b/tracetools_test/src/test_timer.cpp index 2727184..3ad04d7 100644 --- a/tracetools_test/src/test_timer.cpp +++ b/tracetools_test/src/test_timer.cpp @@ -1,3 +1,17 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + #include #include diff --git a/tracetools_test/test/test_node.py b/tracetools_test/test/test_node.py index 51e0a6e..a3d0c9f 100644 --- a/tracetools_test/test/test_node.py +++ b/tracetools_test/test/test_node.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_publisher.py b/tracetools_test/test/test_publisher.py index 3ad4c23..decbbd2 100644 --- a/tracetools_test/test/test_publisher.py +++ b/tracetools_test/test/test_publisher.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_service.py b/tracetools_test/test/test_service.py index e61937a..7bcf697 100644 --- a/tracetools_test/test/test_service.py +++ b/tracetools_test/test/test_service.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_service_callback.py b/tracetools_test/test/test_service_callback.py index 7a1f928..8b6a1e0 100644 --- a/tracetools_test/test/test_service_callback.py +++ b/tracetools_test/test/test_service_callback.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_subscription.py b/tracetools_test/test/test_subscription.py index ae25980..1562934 100644 --- a/tracetools_test/test/test_subscription.py +++ b/tracetools_test/test/test_subscription.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_subscription_callback.py b/tracetools_test/test/test_subscription_callback.py index 7e80437..251eb4f 100644 --- a/tracetools_test/test/test_subscription_callback.py +++ b/tracetools_test/test/test_subscription_callback.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/test/test_timer.py b/tracetools_test/test/test_timer.py index c577efc..9b1b3e8 100644 --- a/tracetools_test/test/test_timer.py +++ b/tracetools_test/test/test_timer.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + import unittest from tracetools_test.utils import ( diff --git a/tracetools_test/tracetools_test/__init__.py b/tracetools_test/tracetools_test/__init__.py index e69de29..4b18865 100644 --- a/tracetools_test/tracetools_test/__init__.py +++ b/tracetools_test/tracetools_test/__init__.py @@ -0,0 +1,13 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index 660dc8d..a830737 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -1,3 +1,17 @@ +# Copyright 2019 Robert Bosch GmbH +# +# 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. + # Utils for tracetools_test import shutil From 89dd6415064e2afcfa6a3d1ad8820a64e51f3066 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 09:10:56 +0200 Subject: [PATCH 123/132] Fix python file doc --- tracetools_test/tracetools_test/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index a830737..adbb7f7 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -12,7 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -# Utils for tracetools_test +"""Utils for tracetools_test.""" import shutil import time From 20341cbeeb0b6500aae75710121d00a9841e12ad Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 09:18:05 +0200 Subject: [PATCH 124/132] Set license for tracetools_test --- tracetools_test/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index ad628fd..6c828ec 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -5,7 +5,7 @@ 0.0.1 Separate test package for tracetools Christophe Bedard - TODO + Apache Software License 2.0 Christophe Bedard ament_cmake From 4cfd83809aef66838da1c4761f814534a7f9976e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 09:18:34 +0200 Subject: [PATCH 125/132] Add 2nd maintainer for tracetools_test --- tracetools_test/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/tracetools_test/package.xml b/tracetools_test/package.xml index 6c828ec..2a62e8d 100644 --- a/tracetools_test/package.xml +++ b/tracetools_test/package.xml @@ -5,6 +5,7 @@ 0.0.1 Separate test package for tracetools Christophe Bedard + Ingo Luetkebohle Apache Software License 2.0 Christophe Bedard From f728cd467b7b4219bc5eff1848addbd1c7940d7b Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 10:01:54 +0200 Subject: [PATCH 126/132] Use tracepoint definition files directly --- tracetools/.gitignore | 5 --- tracetools/CMakeLists.txt | 13 ++---- .../tracetools/tp_call.h} | 41 +++++++++++++------ tracetools/src/tp_call.c | 20 +++++++++ tracetools/src/tracetools.c | 2 +- 5 files changed, 52 insertions(+), 29 deletions(-) delete mode 100644 tracetools/.gitignore rename tracetools/{src/tp_call.tp => include/tracetools/tp_call.h} (88%) create mode 100644 tracetools/src/tp_call.c diff --git a/tracetools/.gitignore b/tracetools/.gitignore deleted file mode 100644 index a9f1530..0000000 --- a/tracetools/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -traces/ - -# generated files (LTTng) -tp_call.c -tp_call.h diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index 0b1d47c..e97c8d1 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -19,15 +19,8 @@ if(WITH_LTTNG) pkg_check_modules(LTTNG REQUIRED lttng-ust) endif() if(LTTNG_FOUND) - # Generate necessary LTTng files - # If successful, enable tracing - add_custom_command(OUTPUT ${PROJECT_SOURCE_DIR}/src/tp_call.c ${PROJECT_SOURCE_DIR}/include/tp_call.h - COMMAND lttng-gen-tp tp_call.tp -o tp_call.c -o ../include/tp_call.h - WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/src - DEPENDS ${PROJECT_SOURCE_DIR}/src/tp_call.tp - ) - set(LTTNG_GENERATED - include/tp_call.h + set(LTTNG_TP_FILES + include/tracetools/tp_call.h src/tp_call.c ) set(TRACING_ENABLED TRUE) @@ -61,7 +54,7 @@ set(SOURCES src/utils.cpp ) if(TRACING_ENABLED) - list(APPEND SOURCES ${LTTNG_GENERATED}) + list(APPEND SOURCES ${LTTNG_TP_FILES}) endif() add_library(${PROJECT_NAME} ${SOURCES}) diff --git a/tracetools/src/tp_call.tp b/tracetools/include/tracetools/tp_call.h similarity index 88% rename from tracetools/src/tp_call.tp rename to tracetools/include/tracetools/tp_call.h index 76be2d3..fe91eea 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/include/tracetools/tp_call.h @@ -12,10 +12,21 @@ // See the License for the specific language governing permissions and // limitations under the License. +#undef TRACEPOINT_PROVIDER +#define TRACEPOINT_PROVIDER ros2 + +#undef TRACEPOINT_INCLUDE +#define TRACEPOINT_INCLUDE "tracetools/tp_call.h" + +#if !defined(___INCLUDE_TP_CALL_H) || defined(TRACEPOINT_HEADER_MULTI_READ) +#define ___INCLUDE_TP_CALL_H + +#include + #include TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_init, TP_ARGS( const void *, context_handle_arg, @@ -28,7 +39,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_node_init, TP_ARGS( const void *, node_handle_arg, @@ -45,7 +56,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_publisher_init, TP_ARGS( const void *, publisher_handle_arg, @@ -64,7 +75,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_subscription_init, TP_ARGS( const void *, subscription_handle_arg, @@ -83,7 +94,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rclcpp_subscription_callback_added, TP_ARGS( const void *, subscription_handle_arg, @@ -96,7 +107,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_service_init, TP_ARGS( const void *, service_handle_arg, @@ -113,7 +124,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rclcpp_service_callback_added, TP_ARGS( const void *, service_handle_arg, @@ -126,7 +137,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_client_init, TP_ARGS( const void *, client_handle_arg, @@ -143,7 +154,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rcl_timer_init, TP_ARGS( const void *, timer_handle_arg, @@ -156,7 +167,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rclcpp_timer_callback_added, TP_ARGS( const void *, timer_handle_arg, @@ -169,7 +180,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, rclcpp_callback_register, TP_ARGS( const void *, callback_arg, @@ -182,7 +193,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, callback_start, TP_ARGS( const void *, callback_arg, @@ -195,7 +206,7 @@ TRACEPOINT_EVENT( ) TRACEPOINT_EVENT( - ros2, + TRACEPOINT_PROVIDER, callback_end, TP_ARGS( const void *, callback_arg @@ -204,3 +215,7 @@ TRACEPOINT_EVENT( ctf_integer_hex(const void *, callback, callback_arg) ) ) + +#endif /* ___INCLUDE_TP_CALL_H */ + +#include diff --git a/tracetools/src/tp_call.c b/tracetools/src/tp_call.c new file mode 100644 index 0000000..778e139 --- /dev/null +++ b/tracetools/src/tp_call.c @@ -0,0 +1,20 @@ +// Copyright 2019 Robert Bosch GmbH +// +// 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. + +#define TRACEPOINT_CREATE_PROBES +/* + * The header containing our TRACEPOINT_EVENTs. + */ +#define TRACEPOINT_DEFINE +#include "tracetools/tp_call.h" diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index c7bf5f7..0755f85 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -15,7 +15,7 @@ #include "tracetools/tracetools.h" #if defined(WITH_LTTNG) && !defined(_WIN32) -# include "tp_call.h" +# include "tracetools/tp_call.h" # define CONDITIONAL_TP(...) \ tracepoint(__VA_ARGS__) #else From f4d20163bd3760e91120b6a063c25b6c8717b3a6 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 10:11:05 +0200 Subject: [PATCH 127/132] Cleanup and fix lint errors --- tracetools/include/tracetools/tp_call.h | 6 +++--- tracetools/include/tracetools/tracetools.h | 2 +- tracetools/include/tracetools/utils.hpp | 2 +- tracetools/src/tp_call.c | 4 +--- 4 files changed, 6 insertions(+), 8 deletions(-) diff --git a/tracetools/include/tracetools/tp_call.h b/tracetools/include/tracetools/tp_call.h index fe91eea..fb6c457 100644 --- a/tracetools/include/tracetools/tp_call.h +++ b/tracetools/include/tracetools/tp_call.h @@ -18,8 +18,8 @@ #undef TRACEPOINT_INCLUDE #define TRACEPOINT_INCLUDE "tracetools/tp_call.h" -#if !defined(___INCLUDE_TP_CALL_H) || defined(TRACEPOINT_HEADER_MULTI_READ) -#define ___INCLUDE_TP_CALL_H +#if !defined(TRACETOOLS__TP_CALL_H_) || defined(TRACEPOINT_HEADER_MULTI_READ) +#define TRACETOOLS__TP_CALL_H_ #include @@ -216,6 +216,6 @@ TRACEPOINT_EVENT( ) ) -#endif /* ___INCLUDE_TP_CALL_H */ +#endif // TRACETOOLS__TP_CALL_H_ #include diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index 93a3374..2bf082d 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -150,4 +150,4 @@ void TRACEPOINT( } #endif -#endif /* TRACETOOLS__TRACETOOLS_H_ */ +#endif // TRACETOOLS__TRACETOOLS_H_ diff --git a/tracetools/include/tracetools/utils.hpp b/tracetools/include/tracetools/utils.hpp index a1a55a7..e73030b 100644 --- a/tracetools/include/tracetools/utils.hpp +++ b/tracetools/include/tracetools/utils.hpp @@ -27,7 +27,7 @@ void * get_address(std::function f) if (fnPointer == nullptr) { return 0; } - return (void *)*fnPointer; + return reinterpret_cast(*fnPointer); } const char * get_symbol(void * funptr); diff --git a/tracetools/src/tp_call.c b/tracetools/src/tp_call.c index 778e139..6a24fba 100644 --- a/tracetools/src/tp_call.c +++ b/tracetools/src/tp_call.c @@ -13,8 +13,6 @@ // limitations under the License. #define TRACEPOINT_CREATE_PROBES -/* - * The header containing our TRACEPOINT_EVENTs. - */ + #define TRACEPOINT_DEFINE #include "tracetools/tp_call.h" From 8f7d5e99eb2f231450cd4585051c5257952d6090 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 11:13:49 +0200 Subject: [PATCH 128/132] Add workaround for cpplint --- tracetools/include/tracetools/tp_call.h | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/tracetools/include/tracetools/tp_call.h b/tracetools/include/tracetools/tp_call.h index fb6c457..a1aaa13 100644 --- a/tracetools/include/tracetools/tp_call.h +++ b/tracetools/include/tracetools/tp_call.h @@ -12,14 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. +// Provide fake header guard for cpplint +#undef TRACETOOLS__TP_CALL_H_ +#ifndef TRACETOOLS__TP_CALL_H_ +#define TRACETOOLS__TP_CALL_H_ + #undef TRACEPOINT_PROVIDER #define TRACEPOINT_PROVIDER ros2 #undef TRACEPOINT_INCLUDE #define TRACEPOINT_INCLUDE "tracetools/tp_call.h" -#if !defined(TRACETOOLS__TP_CALL_H_) || defined(TRACEPOINT_HEADER_MULTI_READ) -#define TRACETOOLS__TP_CALL_H_ +#if !defined(_TRACETOOLS__TP_CALL_H_) || defined(TRACEPOINT_HEADER_MULTI_READ) +#define _TRACETOOLS__TP_CALL_H_ #include @@ -216,6 +221,8 @@ TRACEPOINT_EVENT( ) ) -#endif // TRACETOOLS__TP_CALL_H_ +#endif // _TRACETOOLS__TP_CALL_H_ #include + +#endif // TRACETOOLS__TP_CALL_H_ From a85d4ade5de20f2ad6fa995ee6c7fddb4bc62ce2 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 11:44:57 +0200 Subject: [PATCH 129/132] Use TRACETOOLS_LTTNG_ENABLED instead of WITH_LTTNG in the code --- tracetools/CMakeLists.txt | 2 +- tracetools/src/tracetools.c | 4 ++-- tracetools/src/utils.cpp | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/tracetools/CMakeLists.txt b/tracetools/CMakeLists.txt index e97c8d1..a6327a5 100644 --- a/tracetools/CMakeLists.txt +++ b/tracetools/CMakeLists.txt @@ -59,7 +59,7 @@ endif() add_library(${PROJECT_NAME} ${SOURCES}) if(TRACING_ENABLED) - target_compile_definitions(${PROJECT_NAME} PUBLIC WITH_LTTNG) + target_compile_definitions(${PROJECT_NAME} PUBLIC TRACETOOLS_LTTNG_ENABLED) target_link_libraries(${PROJECT_NAME} ${LTTNG_LIBRARIES} -ldl) else() target_link_libraries(${PROJECT_NAME}) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 0755f85..fc2b996 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -14,7 +14,7 @@ #include "tracetools/tracetools.h" -#if defined(WITH_LTTNG) && !defined(_WIN32) +#if defined(TRACETOOLS_LTTNG_ENABLED) && !defined(_WIN32) # include "tracetools/tp_call.h" # define CONDITIONAL_TP(...) \ tracepoint(__VA_ARGS__) @@ -24,7 +24,7 @@ bool ros_trace_compile_status() { -#if defined(WITH_LTTNG) && !defined(_WIN32) +#if defined(TRACETOOLS_LTTNG_ENABLED) && !defined(_WIN32) return true; #else return false; diff --git a/tracetools/src/utils.cpp b/tracetools/src/utils.cpp index 2d48ffa..acb49cb 100644 --- a/tracetools/src/utils.cpp +++ b/tracetools/src/utils.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#if defined(WITH_LTTNG) && !defined(_WIN32) +#if defined(TRACETOOLS_LTTNG_ENABLED) && !defined(_WIN32) #include #include #endif @@ -21,7 +21,7 @@ const char * get_symbol(void * funptr) { #define SYMBOL_UNKNOWN "UNKNOWN" -#if defined(WITH_LTTNG) && !defined(_WIN32) +#if defined(TRACETOOLS_LTTNG_ENABLED) && !defined(_WIN32) #define SYMBOL_LAMBDA "[lambda]" if (funptr == 0) { return SYMBOL_LAMBDA; From 7808724be81acd5091e882c7a7e0c67015002076 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 13:34:56 +0200 Subject: [PATCH 130/132] Use os to join paths --- tracetools_test/tracetools_test/utils.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index adbb7f7..01cd6d7 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -14,6 +14,7 @@ """Utils for tracetools_test.""" +import os import shutil import time @@ -48,7 +49,7 @@ def run_and_trace( :param node_names (list(str)): the names of the nodes to execute """ session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' - full_path = f'{base_path}/{session_name}' + full_path = os.path.join(base_path, session_name) print(f'trace directory: {full_path}') lttng_setup(session_name, full_path, ros_events=ros_events, kernel_events=kernel_events) From f016523c1741ed2059aa933c5778ce9c9711346b Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 13:38:42 +0200 Subject: [PATCH 131/132] Add typing info --- tracetools_test/tracetools_test/utils.py | 37 +++++++++++++----------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index 01cd6d7..eb11350 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -17,6 +17,8 @@ import os import shutil import time +from typing import List +from typing import Set import babeltrace from launch import LaunchDescription @@ -32,21 +34,22 @@ from tracetools_trace.tools.lttng import ( def run_and_trace( - base_path, - session_name_prefix, - ros_events, - kernel_events, - package_name, - node_names): + base_path: str, + session_name_prefix: str, + ros_events: List[str], + kernel_events: List[str], + package_name: str, + node_names: List[str] + ) -> None: """ Run a node while tracing. - :param base_path (str): the base path where to put the trace directory - :param session_name_prefix (str): the session name prefix for the trace directory - :param ros_events (list(str)): the list of ROS UST events to enable - :param kernel_events (list(str)): the list of kernel events to enable - :param package_name (str): the name of the package to use - :param node_names (list(str)): the names of the nodes to execute + :param base_path: the base path where to put the trace directory + :param session_name_prefix: the session name prefix for the trace directory + :param ros_events: the list of ROS UST events to enable + :param kernel_events: the list of kernel events to enable + :param package_name: the name of the package to use + :param node_names: the names of the nodes to execute """ session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' full_path = os.path.join(base_path, session_name) @@ -75,21 +78,21 @@ def run_and_trace( return exit_code, full_path -def cleanup_trace(full_path): +def cleanup_trace(full_path: str) -> None: """ Cleanup trace data. - :param full_path (str): the full path to the main trace directory + :param full_path: the full path to the main trace directory """ shutil.rmtree(full_path) -def get_trace_event_names(trace_directory): +def get_trace_event_names(trace_directory: str) -> Set[str]: """ Get a set of event names in a trace. - :param trace_directory (str): the path to the main/top trace directory - :return: event names (set(str)) + :param trace_directory: the path to the main/top trace directory + :return: event names """ tc = babeltrace.TraceCollection() tc.add_traces_recursive(trace_directory, 'ctf') From e43eed71ab3a77395785f8feb8bf0957d66d8e78 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Tue, 18 Jun 2019 13:45:30 +0200 Subject: [PATCH 132/132] Fix return type --- tracetools_test/tracetools_test/utils.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tracetools_test/tracetools_test/utils.py b/tracetools_test/tracetools_test/utils.py index eb11350..94f8e31 100644 --- a/tracetools_test/tracetools_test/utils.py +++ b/tracetools_test/tracetools_test/utils.py @@ -19,6 +19,7 @@ import shutil import time from typing import List from typing import Set +from typing import Tuple import babeltrace from launch import LaunchDescription @@ -40,7 +41,7 @@ def run_and_trace( kernel_events: List[str], package_name: str, node_names: List[str] - ) -> None: + ) -> Tuple[int, str]: """ Run a node while tracing. @@ -50,6 +51,7 @@ def run_and_trace( :param kernel_events: the list of kernel events to enable :param package_name: the name of the package to use :param node_names: the names of the nodes to execute + :return: exit code, full generated path """ session_name = f'{session_name_prefix}-{time.strftime("%Y%m%d%H%M%S")}' full_path = os.path.join(base_path, session_name)

kd{;rS=_d6SznlO$DBbuGLZ!i4<7k)Eqy8&k{P)Qy^G=YV z2fxtbWYdcm8-Ll}!lnf*9&*H0*~SISbLQRt_h@-<-711XOnWuOhuk=qo***Yn^tSR zy)?vD2$2i>o}d0bl+zI2EeCU?rc}%~KVa42!Tj{X#a=PQC0>Ny^RIL<|N6|f9a#VY z6d}(B7zY*tVHI6`^LzjN7}KH+&lu;)DFiQ~?XKo-#sWIpe@~CM87xE6PCds|;rl5P zxW-Fr(~Qv?x6671T%=o(T4bzmQ zQJ*W&Q}+Sw>`idw$Oq;NJ`;_wYj$p94R)LqZ^Dkx?pe?4bPoiy;#=O>b^0G4K19B- zWC)t3W?Ev+s)I_3T*q=uKi%gqeiu(upCZ3e|LKlpLxy*d-xhUjIs^*C(}uMtywQe` zyZ1E_DOtHH&A!*>t>F=b00Y%KVT1+>eSkT-9nnN&f2uOC%vhkrzBlqpE!2#&kP9Co zc4$OMtb|s#X!8BICbQq~)6C*V4ZBMcVZoDe=@TmB8X>4rn%#^N%8J>FzHg-&`}pIO zn&+=;2p-;mw7_Lq$;s>oY%DI3yr&2;kF%^Y0|>5XAcik=+}A4=d~Gj^H=tAq5dCt; zV$0w;Ro`durbrB*PLANymc;Tv_eeL~LcM2{#|+2I! zkZzfj_kANZI-=CFpdj4{VMfky&;^gQ{frChJ9oRx)MQP8fr_uovaoy%Zc~eRO*B5h zJp%RYbJg9xmfRXgca*OFsELJcB~t8JF50(m4oSZgc*nfPUvIW_54Hrs{UHo{bFbs;$ zWZ>2ra@aPo7yQEL{}YCI zCCLuWj627M<+!R*X^;QIkcaGM-Fqnm0@V0YnHN^p>N(AjnVFfwqL7M(s*gg$STJx& z#_A@%Tp5u&j#KArO>CxKjLULFN#EC)U}-b_31^?4Az!^V4#n-KXF@HR=Auq*_r0GI z)jlkBRkibIk_ARNr3KY#30C4=3!BD?2J*NyKmT&y6Q^bHv!$@fd;{*1r2F_qx<^== z)(X=MpLzKbNilC_0SDf)ve2{R2(Dx%;- zMfY5B@5G5p$fM+>Py~L4S-`c^?ee@_YXYVv7xp8+0+Y+jQFHuW74!g;it9 zOdTUb)&=@@Z`;PeSmD=2b{bL?VsoT6WurjOW{@KX7mc7AqtwgdF)NTnFR0k-~j8aS^N8ikV| z!+DEKVIkOS_^Bg^(!13@X02i|LpPeDAQsjWXU7Hup{KBx66{=DTUfNfaqdlHKIc`~%6Ryr5!0N*EB$9;g5K9z$M8dI>bu4wH3b0a_l9zK2? zDJCo&&J}-&SV1tT3X6Hoh%9a|R-ORVehw8ys8lP#V-*IKf-~ML+qfM+xH265BELoRM zg(K-_$r(6#i+EBhUd@y8dC~hNeQXPC|Nb0#6PPeYgXy8T$&s+z<8~)Tpf7KC*gjmC z6gkrDu89kBn>B55CFkgW<-Fvd{!jsRu_!UWtl{)kp0!D&1~>T5@{ztKR@%`u&{xWn@!I#H)`v~pn2&W5I3H|ookmaUhHd{JN7hA>JC<) z6#j7UeFo>pusE$Yi4aRYw_N zGLProJkbE|c4lh4l?UwXrd-PlvO^Dbu-UfYq9Z!11e1Lb%mU{fvo@9|UJb!z;?Z_* z+E2Ta-1KAz@2L(pofCTmgdIVJN=`wq@5kQc1vNJkAV4@kmM7{aXZtl`uGNc7?-PVG1WHG90fFy1XKdW9J0b$~ z6!&gV%MmP4=tGr)N3brD`@JV$JH!1Cf^z%C>Sp^n=C1Q>R;s^Q!94*edZo&mgm-+W zfD^P&RHD3n-z7sww|*vpdgtk#wF8mzb?vfT-d0v?fSf@uQdnXXWCtSB-8Y}k&X5D4 zmCSzc+63tfCClSNf(+}V8Nd9G^^|n`54V|YbY@H2cO8x~a*tD(Yf!E8M{g@0N%B4m z7pf&16@kxX3RS~yvuk>G2Fa^8+fZLGKcny>GxH&oKANx_qdxKj^6Y9LewhQqh`hPr zIbAR^NbmnswVX#n(2FtL{Jac_AtlW@qO&irv)(i{5_HG8M4@5Cd3|+>;P)MPe)-kV zz=sup3cwRi)vwn5vN3XU!zqb-EyubtoFmk|hkeBJ``#0k??##bbgb|B!9HVnttl~T zySnHq$2*NOR2IopHaN1O#Ht#HaeYUshIKCJg7rYkr1iPI8wi)Iy9Wm?%cyih0w4$~ zks}2MqAbs`3h7n@!EyXf8>HAV`8|G}?Zw=RQrPBRl*fwF(%^%-`Padeo%tm91W7tl zD8A@CZ0IE(e(hrXw{f2_dbs+DtkwL!>Tm8e%Q>xa?IJe`0IBC(*1I2{@xlw;-VP%) zNs#J(A~Pm|nAA0neWDutx%t9L5sx0OA2GPv#oeL+5__U;n9$1U0ow^`>9u8UO8+ei+6SDMYe^{M;9dsbe4;`|Z z&W^OZ>R}zlA$hvcV@A}(=exSwEp8Eq6qT;s2Yj?Au1Z}#aKbj$b+kdn)sWLd(B&<+ zRppqxS@~Fp4RQm>tq&^bCLicUW`bIInJhd9=p+$>ah#vJS zEPhNjr8?Dm9b9g`k^x-*Ck)w1Pk$4nb#*T|vQ7fzon!GO9{<^Yluf$ubYT#giaH4? z@FjyUV>jBA;$-=}vN|UoTa{vi|BNFIu8{I3)S)DrCK(;)&28tWu#q`qqO}@4o@$j5 zTq6{Z2;8A}no(y>0Zc#UK6zDeGIQc9+$YSOWUU{qXYBdBP@xLAmqNSuJKkcp^#}I^ z(5az`QPl0%;dHpC^I;bhzN_IxUuPu-wE}|uz<+%>S9Dy9| zy^5Of<+6T>JCQF zDtb{ebL`oKync(MfCu)u28r&i_-u@Ui*LTe_JNbCj&zNemHsx`g9O)rY1>xis~$Hh ziNTSNvc$0Kz+`@IS)YVdUK@xyDUhd$(pjEsz7PZcq~nMXlcH4Y`oMt=;1PRSEd>YA z$!RY1`1_9}b7IqO-h^l&z=(7xU0cZUS#q{+O#Qg;87f|Vh7rF;f*$f`9!L$Y=51Fh zE)~}Y(I1$eoNN8TVs37p^W{Y6v$x^>Eoa#n+x$wMS3nZCJ-R({U5*vBo5XCma0FXJ z2#<&#%YANw7|XH|=^^tvW%^v^8pODyZW5bh8o9^Z0-Hm#d~;khzxjwIl~DwjTmL2p zawv&A+}m+rLDI=NoEmeUMYD~DaUvmu=-~%+#zY30Zn6@{n?b|fOpB0l&W$s^Msg?H z5<3dzU3=eSkm>upt(JC^6y@O5@J7x82!{Ce*V7+bNkly(w@0~L`P+lp%C5rh)A4Wq zBZ(ew5G`&kY%^nQw48TO+!)C_@v`hC<@3f%Ob*5Kk7t?APqjra-~k>c+F^vjoJmE6?w zIMn9R!iLnld|6XP1*0SA0rao=<0GqvH7r&IJ8097hh$AOI8$<_+N9u*za*TD?+Ei@0DrsV{-+n_V^6v)3F({NVsGazTziP{!N zxk?iZG~NU@kEe=Jx1uH+_4CPolIl`tLjRg=%UJx|26Ry%vvAG@ygkpm!LS&2D(%hzQ@ z*rIFupvuBIl#d-{r@aCPjr6a^lw>UAQ?O9Gq-w9wBSSgL2mpJ z-*08R<^6M&O=8pQV|i@SO^zBtL_>c0HhNA=P%D1$os5Ln4I7!Mg~H<>;?Tb>8o63J zW&oQ3xoyFX=D1rKVrCf=a7cc${=~*O-3{839T?@r)cL?>ukQ^{R1=L7$jMD^MsAjB zjk{HZ4e6j9nkXy_2~5U?HdIw3gQzhV=UH@I0J))Ieg2g{znk<;mT>bcGWfDlI{C@$ zkLQ@o8r|4df)DtOt~N2TG^)M=BBJ8Qk=ak=qP;vG#KQxm1|* zWFp6%E2eu31bS`6b@gQM*~{ew$ZciBR98ozM!oSmVl3>3=$lJ$C>d*EBRU^MncaMU zYr9k1Or-quJp+g0E6~|9(Nc%s!;wfzL6xYU^B4_d8sG-1u(NRvn?bO2W5V-i&u*M@ za&qcoyCBekR2(5s+T^;G;=t6K&bsz8$P?q(eXk`GaakNl4UbXu)Hkz8*~$XJJhiZH zhr)#yJnigA^b#{|?7VD~nD?9mHE^R(X8|8V)d#Nr>S}2DlEZT}^SKNp(bMN#?+45m z6fR1swfeWI)?BoTyPKMdh?BI81lqg8r{|qNT%oSZPc92WBEJ~l?AwJ4nuETJLr=7; zCBhU_{k?g;kapYM(}J22{U0U2YWrnvbv@g__3XV$5p>UB$C%f_e#jz)mTwnzL_&Q6 z8E8H;FM3-VKf8@Q6D^Kl7(5+9OgSHLgZ2g4^S(QL@f;nwJtdW&I&VK_dQWSK8U0#2 zWb`5zl$M^&I_2Awp23a9NO>qf0^sr#lai%jE=$}zghXS@6yqw=fV%kb85u>mPs$n! z5xmY++pA=q3vlo9d>z|%&Yx&mHpRS$VSW?O z(!|Y$4k?`XzIj>@tGkihwW%r-sLaQ z`qKMQwb7`h(7v(Mh`~Jwm<^cDr()Gg88j{qcA+YM1v&WY>br0O^#njRC+D!9l%>^AfeE6z9VEYn{vs^cm z1p8c#%;cfa!^(ZM4{QeGsTdSYx>???g6CI?RQRDe^87K%%+RDC_uRD_KR;M@{_K=5Um}`I{)kgf52Cm zwB8-u1WM}dss2}l@ZJ$Ivl@)~4+Oi}NZxMg`0H$i|(Q=5Hw1;qK{&d9KUqQ?)zMpo0;w8n8*;&1qn3$2Ooli1@ z<@4`$Vl1#10g}r#bbHgkfcml5E8EKY=cTfQi_J8Ds_{QSNhx&;ht=@VQ0RKUrq=r@ z);@lyRGrFCbLB>`9-^@&al5n@=6PhiLa3xbM&OLT#3^}BYLdlh6XN%igoz>3M`lb3ms@*GC*8h%`w=TED|zpt zPPczL$wGwG=pm0KUi`kdF!zKTp}$WucKuVs&OZgNjDlrrEdxf2 z;t_6)1$QE`@bR7Ic~PBHg3p}5P?%Aepu~rjZs@PK-fm$O@(#dLB<;_zYl~95P7tRO zAmO%*`6>(ikInT)~flR46g;Dox3j5 zmnWZp=AYWg6&Hg?wIfmluM%73+F%h zV}tf~!4|#-+rvG&ZO1LdD^Z1S!V$)Iny*xtlMD@|8LewA8%S{tod1)grLMjoe?*kq z=+#vDkBza!YtCOH9=lTZazb%0F0m>Kh7wqF3tmGT{%XwmTT04gVoCGqa}`ul=S|@z zr+SEBYXjtF&;dB^AP6laKl9GzW7G3<2b%mxWz3fX7&m+p=~Qyfi9u@4>^% zZVyxqN%x)cxg-^j_2hy1!l7xn9O4gmgh>a_ literal 0 HcmV?d00001 From bdbacfcde8d3634ab0b5d4cf9b2e654e9e6d42e6 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 7 Jun 2019 13:25:16 +0200 Subject: [PATCH 101/132] Rename context arg to context_handle for consistency --- tracetools/include/tracetools/tracetools.h | 2 +- tracetools/src/tp_call.tp | 4 ++-- tracetools/src/tracetools.c | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index bc4c018..f8c3f59 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -23,7 +23,7 @@ bool ros_trace_compile_status(); */ void TRACEPOINT( rcl_init, - const void * context); + const void * context_handle); /** * tp: rcl_node_init diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index cf4ecac..76ba9a8 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -4,10 +4,10 @@ TRACEPOINT_EVENT( ros2, rcl_init, TP_ARGS( - const void *, context_arg + const void *, context_handle_arg ), TP_FIELDS( - ctf_integer_hex(const void *, context, context_arg) + ctf_integer_hex(const void *, context_handle, context_handle_arg) ) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index d1063b2..8203706 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -19,12 +19,12 @@ bool ros_trace_compile_status() void TRACEPOINT( rcl_init, - const void * context) + const void * context_handle) { CONDITIONAL_TP( ros2, rcl_init, - context); + context_handle); } void TRACEPOINT( From 0671d021c0d845231ea01072bc99f25e9cdd3aba Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 7 Jun 2019 14:27:31 +0200 Subject: [PATCH 102/132] Fix tracepoint arguments order --- tracetools/src/tp_call.tp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index 76ba9a8..cb419f9 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -33,15 +33,15 @@ TRACEPOINT_EVENT( rcl_publisher_init, TP_ARGS( const void *, node_handle_arg, - const void *, rmw_handle_arg, const void *, publisher_handle_arg, + const void *, rmw_publisher_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( ctf_integer_hex(const void *, node_handle, node_handle_arg) - ctf_integer_hex(const void *, rmw_handle, rmw_handle_arg) ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) + ctf_integer_hex(const void *, rmw_publisher_handle, rmw_publisher_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) ) From ae62cc95314d1ce4004208b623f9b7c5aa46323e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 7 Jun 2019 14:35:29 +0200 Subject: [PATCH 103/132] Change tracepoint arguments order to put index-like arg first --- tracetools/include/tracetools/tracetools.h | 8 ++++---- tracetools/src/tp_call.tp | 16 ++++++++-------- tracetools/src/tracetools.c | 16 ++++++++-------- 3 files changed, 20 insertions(+), 20 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index f8c3f59..d04ead3 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -40,8 +40,8 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_publisher_init, - const void * node_handle, const void * publisher_handle, + const void * node_handle, const void * rmw_publisher_handle, const char * topic_name, const size_t depth); @@ -51,8 +51,8 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_subscription_init, - const void * node_handle, const void * subscription_handle, + const void * node_handle, const void * rmw_subscription_handle, const char * topic_name, const size_t depth); @@ -85,8 +85,8 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_service_init, - const void * node_handle, const void * service_handle, + const void * node_handle, const void * rmw_service_handle, const char * service_name); @@ -117,8 +117,8 @@ void TRACEPOINT( */ void TRACEPOINT( rcl_client_init, - const void * node_handle, const void * client_handle, + const void * node_handle, const void * rmw_client_handle, const char * service_name); diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index cb419f9..5f62f3e 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -32,15 +32,15 @@ TRACEPOINT_EVENT( ros2, rcl_publisher_init, TP_ARGS( - const void *, node_handle_arg, const void *, publisher_handle_arg, + const void *, node_handle_arg, const void *, rmw_publisher_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, publisher_handle, publisher_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_publisher_handle, rmw_publisher_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) @@ -51,15 +51,15 @@ TRACEPOINT_EVENT( ros2, rcl_subscription_init, TP_ARGS( - const void *, node_handle_arg, const void *, subscription_handle_arg, + const void *, node_handle_arg, const void *, rmw_subscription_handle_arg, const char *, topic_name_arg, const size_t, depth_arg ), TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, subscription_handle, subscription_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_subscription_handle, rmw_subscription_handle_arg) ctf_string(topic_name, topic_name_arg) ctf_integer(const size_t, depth, depth_arg) @@ -107,14 +107,14 @@ TRACEPOINT_EVENT( ros2, rcl_service_init, TP_ARGS( - const void *, node_handle_arg, const void *, service_handle_arg, + const void *, node_handle_arg, const void *, rmw_service_handle_arg, const char *, service_name_arg ), TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, service_handle, service_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_service_handle, rmw_service_handle_arg) ctf_string(service_name, service_name_arg) ) @@ -159,14 +159,14 @@ TRACEPOINT_EVENT( ros2, rcl_client_init, TP_ARGS( - const void *, node_handle_arg, const void *, client_handle_arg, + const void *, node_handle_arg, const void *, rmw_client_handle_arg, const char *, service_name_arg ), TP_FIELDS( - ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, client_handle, client_handle_arg) + ctf_integer_hex(const void *, node_handle, node_handle_arg) ctf_integer_hex(const void *, rmw_client_handle, rmw_client_handle_arg) ctf_string(service_name, service_name_arg) ) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 8203706..948929b 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -45,8 +45,8 @@ void TRACEPOINT( void TRACEPOINT( rcl_publisher_init, - const void * node_handle, const void * publisher_handle, + const void * node_handle, const void * rmw_publisher_handle, const char * topic_name, const size_t depth) @@ -54,8 +54,8 @@ void TRACEPOINT( CONDITIONAL_TP( ros2, rcl_publisher_init, - node_handle, publisher_handle, + node_handle, rmw_publisher_handle, topic_name, depth); @@ -63,8 +63,8 @@ void TRACEPOINT( void TRACEPOINT( rcl_subscription_init, - const void * node_handle, const void * subscription_handle, + const void * node_handle, const void * rmw_subscription_handle, const char * topic_name, const size_t depth) @@ -72,8 +72,8 @@ void TRACEPOINT( CONDITIONAL_TP( ros2, rcl_subscription_init, - node_handle, subscription_handle, + node_handle, rmw_subscription_handle, topic_name, depth); @@ -115,16 +115,16 @@ void TRACEPOINT( void TRACEPOINT( rcl_service_init, - const void * node_handle, const void * service_handle, + const void * node_handle, const void * rmw_service_handle, const char * service_name) { CONDITIONAL_TP( ros2, rcl_service_init, - node_handle, service_handle, + node_handle, rmw_service_handle, service_name); } @@ -163,16 +163,16 @@ void TRACEPOINT( void TRACEPOINT( rcl_client_init, - const void * node_handle, const void * client_handle, + const void * node_handle, const void * rmw_client_handle, const char * service_name) { CONDITIONAL_TP( ros2, rcl_client_init, - node_handle, client_handle, + node_handle, rmw_client_handle, service_name); } From e3f9fa036aab3793a7f41dda0551a8c624e88f78 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 14 Jun 2019 10:07:58 +0200 Subject: [PATCH 104/132] Use events list --- tracetools/scripts/setup-lttng.sh | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index ee30661..7305f53 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -12,7 +12,11 @@ for event in \ ros2:rcl_service_init \ ros2:rclcpp_service_callback_added \ ros2:rclcpp_service_callback_start \ - ros2:rclcpp_service_callback_end + ros2:rclcpp_service_callback_end \ + ros2:rcl_client_init \ + ros2:rcl_timer_init \ + ros2:rclcpp_timer_callback_added \ + ros2:rclcpp_register_callback do lttng enable-event -c ros2 -u $event done From 35092f89ffc2c4967a39b08dea8e9c66d9984494 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 14 Jun 2019 10:08:24 +0200 Subject: [PATCH 105/132] Switch to generic 'callback_start|end' event --- tracetools/include/tracetools/tracetools.h | 66 ++++++--------- tracetools/scripts/setup-lttng.sh | 8 +- tracetools/src/tp_call.tp | 92 ++++++--------------- tracetools/src/tracetools.c | 95 ++++++++-------------- 4 files changed, 83 insertions(+), 178 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index d04ead3..a03079e 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -65,21 +65,6 @@ void TRACEPOINT( const void * subscription_handle, const void * callback); -/** - * tp: rclcpp_subscription_callback_start - */ -void TRACEPOINT( - rclcpp_subscription_callback_start, - const void * callback, - const bool is_intra_process); - -/** - * tp: rclcpp_subscription_callback_end - */ -void TRACEPOINT( - rclcpp_subscription_callback_end, - const void * callback); - /** * tp: rcl_service_init */ @@ -98,20 +83,6 @@ void TRACEPOINT( const void * service_handle, const void * callback); -/** - * tp: rclcpp_service_callback_start - */ -void TRACEPOINT( - rclcpp_service_callback_start, - const void * callback); - -/** - * tp: rclcpp_service_callback_end - */ -void TRACEPOINT( - rclcpp_service_callback_end, - const void * callback); - /** * tp: rcl_client_init */ @@ -138,20 +109,6 @@ void TRACEPOINT( const void * timer_handle, const void * callback); -/** - * tp: rclcpp_timer_callback_start - */ -void TRACEPOINT( - rclcpp_timer_callback_start, - const void * callback); - -/** - * tp: rclcpp_timer_callback_end - */ -void TRACEPOINT( - rclcpp_timer_callback_end, - const void * callback); - /** * tp: rclcpp_callback_register */ @@ -160,6 +117,29 @@ void TRACEPOINT( const void * callback, const char * function_symbol); +/** + * tp: callback_start + */ +void TRACEPOINT( + callback_start, + const void * callback, + const bool is_intra_process); + +/** + * tp: callback_start + * (is_intra_process=false) + */ +void TRACEPOINT( + callback_start, + const void * callback); + +/** + * tp: callback_end + */ +void TRACEPOINT( + callback_end, + const void * callback); + #ifdef __cplusplus } #endif diff --git a/tracetools/scripts/setup-lttng.sh b/tracetools/scripts/setup-lttng.sh index 7305f53..da5ae8e 100755 --- a/tracetools/scripts/setup-lttng.sh +++ b/tracetools/scripts/setup-lttng.sh @@ -7,16 +7,14 @@ for event in \ ros2:rcl_publisher_init \ ros2:rcl_subscription_init \ ros2:rclcpp_subscription_callback_added \ - ros2:rclcpp_subscription_callback_start \ - ros2:rclcpp_subscription_callback_end \ ros2:rcl_service_init \ ros2:rclcpp_service_callback_added \ - ros2:rclcpp_service_callback_start \ - ros2:rclcpp_service_callback_end \ ros2:rcl_client_init \ ros2:rcl_timer_init \ ros2:rclcpp_timer_callback_added \ - ros2:rclcpp_register_callback + ros2:rclcpp_register_callback \ + ros2:callback_start \ + ros2:callback_end do lttng enable-event -c ros2 -u $event done diff --git a/tracetools/src/tp_call.tp b/tracetools/src/tp_call.tp index 5f62f3e..dc58fb4 100644 --- a/tracetools/src/tp_call.tp +++ b/tracetools/src/tp_call.tp @@ -79,30 +79,6 @@ TRACEPOINT_EVENT( ) ) -TRACEPOINT_EVENT( - ros2, - rclcpp_subscription_callback_start, - TP_ARGS( - const void *, callback_arg, - int, is_intra_process_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ctf_integer(int, is_intra_process, is_intra_process_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_subscription_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - TRACEPOINT_EVENT( ros2, rcl_service_init, @@ -133,28 +109,6 @@ TRACEPOINT_EVENT( ) ) -TRACEPOINT_EVENT( - ros2, - rclcpp_service_callback_start, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_service_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - TRACEPOINT_EVENT( ros2, rcl_client_init, @@ -198,28 +152,6 @@ TRACEPOINT_EVENT( ) ) -TRACEPOINT_EVENT( - ros2, - rclcpp_timer_callback_start, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - -TRACEPOINT_EVENT( - ros2, - rclcpp_timer_callback_end, - TP_ARGS( - const void *, callback_arg - ), - TP_FIELDS( - ctf_integer_hex(const void *, callback, callback_arg) - ) -) - TRACEPOINT_EVENT( ros2, rclcpp_callback_register, @@ -232,3 +164,27 @@ TRACEPOINT_EVENT( ctf_string(symbol, symbol_arg) ) ) + +TRACEPOINT_EVENT( + ros2, + callback_start, + TP_ARGS( + const void *, callback_arg, + int, is_intra_process_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ctf_integer(int, is_intra_process, is_intra_process_arg) + ) +) + +TRACEPOINT_EVENT( + ros2, + callback_end, + TP_ARGS( + const void *, callback_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, callback, callback_arg) + ) +) diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 948929b..668cac0 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -91,28 +91,6 @@ void TRACEPOINT( callback); } -void TRACEPOINT( - rclcpp_subscription_callback_start, - const void * callback, - const bool is_intra_process) -{ - CONDITIONAL_TP( - ros2, - rclcpp_subscription_callback_start, - callback, - (is_intra_process ? 1 : 0)); -} - -void TRACEPOINT( - rclcpp_subscription_callback_end, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - rclcpp_subscription_callback_end, - callback); -} - void TRACEPOINT( rcl_service_init, const void * service_handle, @@ -141,26 +119,6 @@ void TRACEPOINT( callback); } -void TRACEPOINT( - rclcpp_service_callback_start, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - rclcpp_service_callback_start, - callback); -} - -void TRACEPOINT( - rclcpp_service_callback_end, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - rclcpp_service_callback_end, - callback); -} - void TRACEPOINT( rcl_client_init, const void * client_handle, @@ -201,26 +159,6 @@ void TRACEPOINT( callback); } -void TRACEPOINT( - rclcpp_timer_callback_start, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - rclcpp_timer_callback_start, - callback); -} - -void TRACEPOINT( - rclcpp_timer_callback_end, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - rclcpp_timer_callback_end, - callback); -} - void TRACEPOINT( rclcpp_callback_register, const void * callback, @@ -232,3 +170,36 @@ void TRACEPOINT( callback, function_symbol); } + +void TRACEPOINT( + callback_start, + const void * callback, + const bool is_intra_process) +{ + CONDITIONAL_TP( + ros2, + callback_start, + callback, + (is_intra_process ? 1 : 0)); +} + +void TRACEPOINT( + callback_start, + const void * callback) +{ + CONDITIONAL_TP( + ros2, + callback_start, + callback, + 0); +} + +void TRACEPOINT( + callback_end, + const void * callback) +{ + CONDITIONAL_TP( + ros2, + callback_end, + callback); +} From febd4317dcf06b1a753268f75f06f83ea8db6e38 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 14 Jun 2019 10:19:03 +0200 Subject: [PATCH 106/132] Remove overloading --- tracetools/include/tracetools/tracetools.h | 8 -------- tracetools/src/tracetools.c | 11 ----------- 2 files changed, 19 deletions(-) diff --git a/tracetools/include/tracetools/tracetools.h b/tracetools/include/tracetools/tracetools.h index a03079e..26c8fd4 100644 --- a/tracetools/include/tracetools/tracetools.h +++ b/tracetools/include/tracetools/tracetools.h @@ -125,14 +125,6 @@ void TRACEPOINT( const void * callback, const bool is_intra_process); -/** - * tp: callback_start - * (is_intra_process=false) - */ -void TRACEPOINT( - callback_start, - const void * callback); - /** * tp: callback_end */ diff --git a/tracetools/src/tracetools.c b/tracetools/src/tracetools.c index 668cac0..97123e7 100644 --- a/tracetools/src/tracetools.c +++ b/tracetools/src/tracetools.c @@ -183,17 +183,6 @@ void TRACEPOINT( (is_intra_process ? 1 : 0)); } -void TRACEPOINT( - callback_start, - const void * callback) -{ - CONDITIONAL_TP( - ros2, - callback_start, - callback, - 0); -} - void TRACEPOINT( callback_end, const void * callback) From 8a32d292bbda4a988ad385037ae499e0aa63e83b Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 14 Jun 2019 10:35:31 +0200 Subject: [PATCH 107/132] Update callback_* events --- doc/design_ros_2.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/doc/design_ros_2.md b/doc/design_ros_2.md index 8cbddde..668aea2 100644 --- a/doc/design_ros_2.md +++ b/doc/design_ros_2.md @@ -246,9 +246,9 @@ sequenceDiagram Executor->>Subscription: handle_message(msg) Note over Subscription: casts msg to its actual type Subscription->>AnySubscriptionCallback: dispatch(typed_msg) - AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_start, this, is_intra_process) + AnySubscriptionCallback-->>tracetools: TP(callback_start, this, is_intra_process) Note over AnySubscriptionCallback: std::function(...) - AnySubscriptionCallback-->>tracetools: TP(rclcpp_subscription_callback_end, this) + AnySubscriptionCallback-->>tracetools: TP(callback_end, this) end Executor->>Subscription: return_message(msg) ``` @@ -333,9 +333,9 @@ sequenceDiagram Note over Service: casts request to its actual type Note over Service: allocates a response object Service->>AnyServiceCallback: dispatch(request_header, typed_request, response) - AnyServiceCallback-->>tracetools: TP(rclcpp_service_callback_start, this) + AnyServiceCallback-->>tracetools: TP(callback_start, this) Note over AnyServiceCallback: std::function(...) - AnyServiceCallback-->>tracetools: TP(rclcpp_service_callback_end, this) + AnyServiceCallback-->>tracetools: TP(callback_end, this) Service->>rcl: rcl_send_response(rcl_service_t, request_header, response) rcl->>rmw: rmw_send_response(rmw_service_t, request_header, response) end @@ -458,9 +458,9 @@ sequenceDiagram WallTimer->>rcl: rcl_timer_call(rcl_timer_t) : ret Note over rcl: validates and updates timer opt RCL_RET_TIMER_CANCELED != ret && RCL_RET_OK == ret - WallTimer-->>tracetools: TP(rclcpp_timer_callback_start, this) + WallTimer-->>tracetools: TP(callback_start, &callback) Note over WallTimer: std::function(...) - WallTimer-->>tracetools: TP(rclcpp_timer_callback_end, this) + WallTimer-->>tracetools: TP(callback_end, &callback) end ``` From b83a89503123fbc80bc2ce257539f6839b5c33fa Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Fri, 14 Jun 2019 10:35:40 +0200 Subject: [PATCH 108/132] Update tracing architecture image --- doc/img/tracing_architecture.png | Bin 108257 -> 109230 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/img/tracing_architecture.png b/doc/img/tracing_architecture.png index ae5cfeee4653f68ab9298daca40752baa47e78d8..5396b13f314272f512df32c81b93fec1c946f514 100644 GIT binary patch literal 109230 zcma%iby$?^+V4=30wN$F-9vYmfYLQeN~c2(-6c|z(hRAzbazNdgF190-AGEG7x%Z$ z_3gday3XMbt`}zJexAF3cTBjts@y{?GAs}X^iV-w76JmH6@Wm<3>Xi9|9r`peFXyH zBznElak2A|b25RwQE@Q0umyosbmR~@6;(I~Ef%nP(BhHb}@+uVp z9bE;^YO&+IpLxv6?|AlKzX~Y*lYa70-Ii{x7`Pi;V?X*OiLZ01hSAloP8?a|HKlgw z4e7pnH0A##EH$44?`T!iAx2E`_F1^qpwgMk-jmKiNA3EUQb=aqN_B8?QYAVsE#}zW zGX;W68S&l*$48u}cZj2uL2<-!XfPzs3v+8cleS`*j;{;(4rO z1@FO+vZkHL2Yb!>IA8q^cG9ItR+>ZkK(l`ruG4|izMK_xDjAbcAN>+P{Pu+j{5Hyz z^fZlwdQ&i@gDa9o_C4`t4CF^>d;%Bua>SR5E04xojl$pAUz{V-DpFhe15TDsAA_M^ zBi?ajcNlf#eWFWEm8CUhOssBdX@q=|d5&dw#d-5%-HfNq=2xw$ zI@9-}_+X8_!r6yyZ>FHy{Odz13VO(@$-Vdv-+xHO4x^fO77J5g(P zt=_AQe4+HYprhM{m!Hs8_QX?01lcX1qblukJpZ%stPs2tNsZu)yesEuhmg{l=LnnfDWH z%)USI2>Uxt0q*mhpR>8I7wD;&=UYZ9R!2TA(0Y;!(Ara~j~QyDu|9WsX#f6##xv*@ ze(O%K33!!#ohZW^hqnTWGxvhTdQbs1Yi#3|WOyLQ7c$4S9&i@&wgrENW^ni21pb zrMARY-#NCoYkGg*z5@+Tty$KJR%Nc^DN!p1S(X{*&rEqs_QdIf1M0}<8x! z(QXW`Y@Tefur6VFUW}11)zXFG+YinoLC;GV!!SQdhqmyPpQ07*TW=+9Cdw@zsP**Y zj&2tYhre)7=ifw+GviBn4Tq8`I9V&dubB71q@T}m0^6p3gu>mwsZIXyWXVyIvZY0IFnnUrWu3!s3w(K7&ZfP6&*td#mj?c^MLoLV@y5$>L zE0S|Mgg)!0Z2P6@?HBT>XWhPCHm^ReQb)W{DjLwZ(m7qpbEw3BJy0K3@_xLhPmq5M zxtOST#_;uoff-p(LFnEqCjP5uOnjEvpJGX!w8p2NnB$NQb;`LMYH1v^!Lvwsw5VM8 zS3E-pwQnQ6{!Bh>_uDdD|3?5|0~c=e(W7JhEYh<74v4jo_LV-LYc-D`46&z{h^tFBE;er=VLQ;VrddvvPh z&}$}zsq-ypiju!5Oi3LduS8q8omyfbKKA=-FCF~;*H&NI&3^Dcs2ovaRkL^>lJ0n# zSY7F@81hpZbG=I$)o9vj_7U0G7TbJu>rdx&KlkxUT0(T5L@o;>r*H6&Ur@tjPo|q! z7A|TM)M}-0)JG^!`q>*_23hv~R9+{z!miErNd>bmoL>xgW2T!|ND-Jy$*2{dV||4c zOW1gXN>9>g9{R+ZmqtY=9Y}1j_mKoYEA_y)q^U^`3LXq)?5@HXHU?w1d(a<9V`9_D7x{1WZsN0Zm$lQ~aJI-tO+9 z^4AKVG;FF2R*z3UeA2^U7jVPfVB8B>>M9FO?8wLH^++^#zk@udY)&9motf+{6Zex% z_P|$dS&{C;YU96VOmK_4dFixyx>NK54qzXMC7#YQkN*z5NUfSba9`)2G!-tr1|=EOc-#L z#FP`P>^sL>ey*8B1Zi@p{rcwjc_A*w1CtdNvSzN7IT}!MVnqj!&@r9h3eKHqA6w#= z>?V%eMLa`LN@utwPfN3?YE5Nyg zYV*0QRFK54+PZAfRl`@LYl?{7EnE#Jj$lJ10%Q00|+0$#@`>rCq9?D}}5%l8jz zy+$C7?8WIP4a>rjdLPIq+_9vv^c+7C+Y7lu#GV*Mu26)V@pD%Eoa(U{O)%rI6l3QI zebGcLy+HZe`lG+$R2qoymuBV!+RH87y-0z~XK|kSY~|g8fpmJhR9Y*?zh!9ZMu`i9 z%1-c*U-;T3-LCDtj`x&B4&%mhja&{!6K9G#q#Q};ZPMpnh>5_R3)5L?^c>bNOWm#0 zr-k_e&xDCoNBJa>7f#(%!>3&rfHb0+z$WJx@ zDPC%Yuy#wwN>ymmwTd^>kym&iebjgX=@y(Z!Ep10lrU{IQ&<%z9^$0%sr$4`S5b*B zh0@EzL}gO?-q+>#3MPaa&g|RwFG|?^QXY=z9a@0wIg{7J1~7}i%xr3fROG8ajns|z z{g|>XGu75;0ygsTM{Kzc%Pr)Hbt(6OzY$&^1&?hvn)@3!QPEbt{OB^A%~%v6N_}2d z@q|Tq{6aa&VKZLOX*w} zDkV3Fbn|V!)`^qvipOkf_=61Zi?z3!Qf{(Re5USQwZ!iUy&~yz*Oe}}iNAg+)!(qf z(zO@yY{GC1=3n>{*Rc2VnJ9~-hpFHwMZ=(uX}%Diw!rg?cP^n~s&1bfF}-7F19b`K z%M|%^g9aA_Dj&2CGd~~bv$y*~9*#U{q{zE~EGx(RQ}*$*AEGh&Fj?~F2>l)F(~a+( zPuiX^Y)H5_#d&coF`uKZE*jh%^iYW1T^*wk-J+L#w;BO~s6h&{&t7>L?#`q8JYKs) zKOBv(vwfcQz7Iwx4RvaeGRJz){2m*f1y}0XD_Ax)@~5Aj;Q?3;QW}m+ASNZG;N}FH z_isP_49FVDv~#|jJa5^#n_;w*ju%Mw+dnXe3R$)Is{SV>nAMo4{xMT1a)oYicqZ0kcJ@E21bKk{?`Tn(91T( zPLnNH-yQ zQGT?A7NdxSl?w+h@=7%4N|G`Japlk}2l=myK=kgJ&oab~MqXp=fHlo+#_xCF6vXc* zRLHC`ES+ENT==vpA-RCQb@C01C>D`{+>n0{^9|dAsF?E>CS1h}S}sY49bebH(O{*c zTd@QcKkV|LgZEZEyq9)4CMt3uZz81nynZnsdd7{j(sSeMv)qe@9C(aWGc-Kx>(=w0 zDD7wMV%37$=g6Frc@MFBp?*N+Qz^EDuOBED1?>vNyBf5Qu$tl&v^wQasbP621uWOp zk7(0+55hz~G|kmBp~CrXw2BlHS=0Hg(#?mC z@ZqdcBECP?!P29&6A#d$w*EpxO!~6RoI;}vmJae(pwyCC-YYrLlv`D>YjD}l3)Cz= z6@)$7VYZmoTid)b;ifYG6x&RA{xI6N%w?CV4AQeuWWullsgJNrzb>wjUgx{Y-NA$N z`r`|q<5g}$+=7=Da4U7k~cu7 zSY!{vO`HYnr!@BKG@v8KfTxKN0=OV37HP>LFCo(61s6#=67{P%$%6twNK0Nu{pG@T za7$<>^rF(K67o3_3Ky06sD2FG=yW+3C9p#|@0Hp`AP*sy>&b-=e*)w{PJ~rhSoooK ziB2WW#JP$Jf=BwJxfwowa<2PFQBtseBHp+#cFBVikEhvgqpSTIJ^D`I^=@YEPbihvy3m%Y|nj)lYNb=wcW4eLWyy zII2WKi_-$a)sIYg1%;W=Ug>eqf|rz3+eunJ*g}+SDo?Bmr%UIN-QaPZL8RC;EW7N{)xpLG9SM^ z{9+9IGzWNvxoM;_%u{>PRaaSXHz^VLNlIe$Poq!YUp~HA?H&03VJ0nqdXXzqA^0Gs z>-_OWS`rY7ak{v?rp-KN46EgC&j}4C+oQ+IrKq`d!LCu)Wvq|gT@3E{DVO=$%?^8B zAUR-jrJqe){9he)_t%B-XZq!20)Z3T&Mv64n88pX@QV~<2#ExC$vfZW9;0(;GjAV<@T$EFkx-CJukPqk79>I0cX%#vPExlG^z}A*uNn3WkOY z_F1EoLmS8acqIjcD7m*#E|M0(8OK*)OvLC4_aR;tndf8A#&HygTKfg%x_;i)`4#$= zkHiH|M!oyN0$rzp2H4;mUum$o?sLX6Wi%KO=tA@~9kQLQ&P;CuG00Bv8p}MPd2GDB z)3mQ29`4~IiK#u2qrRBQi<4s{B;ft)B8q2lhHp6LVV4lXK6xQmA^t>u3}7<}Z70vC zB+|FVgrv%&^-A<{yIJ>^=fJ#rb_;48e|nN`h&FPp(NFVyd3MmzI?HMCA`;gZzn3wq zZo&aONPT%LiAdKt#$+H&$5n!(+A|b2ltayw4EcH8RPi5V9bZ7J*u9*f)uVVOkS)e> z$`g=2wv_dV8#;Bn-$3$XOl^9h86+u=O3yJ|`_9u=7LX^R6}98TnWI1IAxnT2NUQ_x z(cn&A=Su!(01q9}I40bf6l9r@jP{t7jFf<`u>G%$x!#N?J3GMh=WW{y`p`=kLQMK> z#QmKmuBUzDr@gJ7;M%;dv-N~{c{TBhE-M*K&Jtf%Bz=R;+?c$w#DM2tz)eU5gGp_C z5qy)gR7nLpO&kY^=K_=HE|`iOSPz06dRBa3RD{`5*4W*m=}A?j@cjPBHD3C$`D!aQ z#CWmx9qW5|z5;3CvwY}2cCa*)74Y-K>wrTbJ^IYI+Vgn*A**&7TlKDa8bI48pRHor zB6-z$|08GuFc}8XIe)oKbXdladVHLEh{@*u)!txb9?mOXQ1kiT?4*0{5ZB0_LyhB3PZIIs zIaXVkGLOgWdy2$|OkJEcScfa6eYF_;i(V(rSWlpFRaRnb@&R=_y<&iKflo*Mfdg8{ z4UK`cW22AZTj=x|C{`qhKz&fcJl=?Mt*XBhJ4?ZXjrZ1kk!MGiBP&5q-buLNWOl1r zKcCYz-;#K{VeIw_Ip9P=AoUrTrh&XU+K!gjXf@*PSZCs|Zs&ME;pFLF=k~cLXmNTS z6to-b>zOS+7e@|1zngg1&6q&$R3=YHJBLAaoD}uMQGobNy0}(v!2Ya+s`V`7EJ6?Y zRjvr6o~GuvSdC^jsRq!VGkLAoTm@AD8T&qt=`52jxk>J8Db91=QD6nbQG=dcd@1j< zOxFECN>uw(I9{A`BjF0rR-ASRg=+82pgOaQ8W#!q%ioUdfH}q{CDr}#ll1z|6)6#H znL(6V#CF9DU3aNDNaN`$0gwof?lXy}ccnXCQ_sHwxWGmcyz^r_>ZzcXGcuB>$8DBx zaI|-bUf@S-xEn=4u?ixAibM`I=*!yoNIEU6x_h*tu7P&#cb6xTHQI#S%QuX8*rl^s z2Y?>l1V|jW{Qh_K$st>9a?Yg3YtYhUK77fRIleMW*Ee8XutU9st%Ge0kG=#_=$ z<-q(swA(7Zzu^L!S~>`rCW^*$6gT^@$^a*j~zz zokXTKf@2Fc9sYzw?T}Qpl*%SW&DwKkA=$2x9$?b=H4B6Z?g17|~Lnn7MuzCr*3z4%qEEYQAaGzxgZfyQH3gJiPt zi!|2sB=t{*xvBu52u*;vPfM5N)5H4c;=gsRrnUEZzPzc^vLp@mZwCPDG#8`x@M`oVwiK78VKqy$_dXI|29fEkY zD3~L@1|a?x$o30pI}rY50DQ}^9HQSgFT&0~+$eo$Z!k#}>6Z1QEZ4ESit`TwSN{N9 zt3$hLsc99|RQ6;9sbu;KpnE+WZbB>rGMooSoV%LL>3$1_OxYO4-UcZBM5ew6F=tl_ z%P>6zUuxueXofpsMvWqIR|eI}<@~lgEwQG7{emi2=bllO;I{ z-GrHtXvrIT0N~kD@yS!gQ15haVq@qi8kHJQc9#J~ke7dC35vcJ>~^GX zS-|tz*jV|m-R~<-{YIxXwMPpF@7Y5&n2p1Jw{7h`nu#QB~J%E}@r;N~lLlRO;9N^9RYQpSY+0J>eXhpL@E^E-wlN);fXR-xUfP_f% z#z2j5UM8lEH|L8A0N5SeIM!X%P)6A5{y;tnl%n>3Q8P9rfYX)Hx{8;v$o(5RSIQcL z{igD32IW%535Tbob2Z97?3S8u=Dw_1|+NAzsi*O2_U5&eWyeB%h?Bchl z-E5!5ze7L7$og}^j7mw-Mu^uEcwyOzX2gDO`FB4k{RqhbByS)y&4KgssLQiujL^0- z6;br-=L&P23^hK6vZkVeoxeJZQ|kQf83a)S&xf{^B{&gZGP`LryhBvubipj$pG>O( zQj!K+7>HQGEd!gTEyz{z1aZ1p<~8os=J!gJOH0lD8^Mm*bS5%kp%5}=p>ReF(=sei zF>%#exS)HMy{T-F$l0VmPI_K?*`@njW!jS(Kh{;Aap0%M_w-@u%y)s5pL6p=M(O2-RR0oZ2L?rO`X-Its&1*hW_?>Za=(AADw9S{aQ>$`__m43V=Xw=m4lX&GPVihAhJxBUGVSSAj-~D$u;K zD*xLHtK-Ylojlo?TF`snaoI}Vf;DR#gUK#~D3iT~gL9*;;|s&87}wUaog6#%*I^AiN0BrlE( zBXOS>#q&BqL2niXfvT@aB1>&ME?pzV`x&T84`x0a9vmkLAb9^lCpR7$!R9H#<8ysp{Q# zmE`v>DCm+3h-M+wo@jC4^d!K-_HMUB2 zwD*rH+OIj|81tbVyf|HrRkSSiIWZDVPJlUoZhk^@a&^P*E0Ohb^cKLhYo~_v=5`A$ zo?So%r6l|@u5(Kb$Uo-|6>0fUh|Q~kNBw?Yq#@j0P?8wHv~)pJrU%YdWjj?KNwv@a zDCxQ+!P*qQP6eQ6hRwNq8Fs5sYb@8?+%i>9lEL%A5pU4xb8&;EgWi5wLM%T}hZH{D zyUGWea74jJ3w}u^B&weE$f2&ByRVgXV=5wE61gKQlF7}fQo76D7dX$+_*CLCU6%(u z2t|LwA|mCk>ggat6bA=PAMPu0|0tk$Wb4nlWlr+-N!e`fuC=ehB*SRfNh_njI5mRr ziY!FKHkHG#SN{7Gyim<$R6y=!%UBi+>GQ;E(?VZ3oRA=XTAqONMR zQss;fk32(;fZPegRglRxBHlh$ZMJfLvLKfWo59S;^IemU5NkSL9wM<4q8Oewd5R^= zw1nW>lPg*Q4+DLf7-KGG?9VT1q42X5A6VRF{%oDy(?++w8M{EK>~e@Av3la3lfh&L zRX5gdwR#FcU0ql&Pf*XooNmU z%a>%K95y2!FGh$(L5}kv$2Ti#Tdd*{0Ng6k2#8eCkpq(xA+0KixfYje!%;scZ%nBZh5-|S8r$U_c*#W*D6JkRCbPK21vWO@}*kH4F5*>(|6XN09 z{g59*pJp(hY5=|B!Up7vMQ$K}IFN++Ok#NVM9C0hpn9?7SukkjK-SGxu^lxSGct78;HcnSVRZ6?nMV=Pjp5)Nt-1YR*b+m?~ku7=S z`5$L!>l>0zea8N*JfSJfB7X4YYLtS2dw*o-RqTxK$aXytuq^ckSIq0o*pkyluQ*kN zZty`?k1Bs!st&%jf`qgHC5I?-bf{1-WI zER82Zb^9Y}$OrI&nP0nq#ps5&GG%&l@+5<(=&YV^^C8e+umtCge3*?W7G^)+SY0J= zH0{AE5;Zahas|hg#9q6laIIE}jtSaG6_KE`-o86~)9*?X5|bS>K=iYT5WLyuIY2=M z5@;P!O=W6f?{?0wyjk_Uw%WCT8~BM0u6b~V2%{j44+_Zx%*vlN z&-}|?cG=DkfjJ2dXJQhdW^>xuPK*1h@l(MB;p~TH?0bRLJxIWQs znlHl{&_I5TT`)+zw-{||soHybrQo>iNR3Yds6oSTYIt~f9Ka!yEO|a3)eC*ONL&=t zh&|liz=^q3oGTMckHsE#f)R zM{KtukXlHWzqq5ohuK^?0i(stIfHW;K52Idrw zZ-3)s5ztEg4bU5C<>s@nK|SBsHighJDsA7%>dz7p(!N z4DEgBs^Gm!z|T59YZkv}!^nZ^p#ur2zSp_BY)9=^s?vSKk3P^N6ah4r&*@hgX?UA^xE z1{}E4)6-huZ*T702p_B7H`S{~lCH&>PtW5CI-%#CVLX`XisS={*>SFfsp5Wfj=dD> ztzND&VAmQb{0dYP?G}gCZkF&n!4w6{Lz;TJ6N;I@kdV|geDq9|^R1~@%4KQQ+a^@S zs(Ex{*>}AIPf)GS!bQ_5K})1p-0UD(mL{tGsiTS??+`rBKfrX};F`Q?4j$DI zM5c#lWxOFlg?7205qNxJs~!qx1@$3A7Sr+@Rlu559lsR8m>)7K+>)X2Ck-}%mp8Xw z03@(h(EgxKLx^<>aB9@&2NcxPZ0ziI6_9N*AXTvDt@aktsUWU>C(8`j+wX3@H++Z0 zi#;15pBsVr3t)Az7N@m=Ec3t;DQZ}Vfkf_y`3+hcc_7GXfyb4l(Lo#iDLxWL6jo?3 zuoALy#m#TE@JF9t8u)<3zn`g z0NUQ4cP+NyTV3AE}!wocG@epOAjTJW;j$v8U=F(JK>fYN?!T9iv9k= z@9FU|P;UblH1Mfh zk##7H+~h-X0c_W%O*jpB0YTW2xK!ONfKI9kdhFsJuZ7NCM?c!Dj@V<4ZTZtGNULMJ zrG4!WQXST+&wkfcg+*DF^Eq3Mf?Ns{1$gHx17nudJ=#<4H6F?f9{SU2YzGLo+k0QSuB}yHl}am0;x`i| zx_JO#!n<$(v+8Z<5jCgg3rh+L)*HQp=LA2I`k>xXkPz2&M1U-2P4aaQ7-Fn>t*+}M z_ymQqA2b0O3tga#Z&+@ZfR?9OWdVE5_uCAu?-HOhxFMbsKxdAig^xu)O=KpvN22ZM>gJp^FJy+QA)_sHcX~xtuzj?@e~Y*%QbA!O_#7BB z6R831ql3}SHFPncL52Pt96BZkw(wn#qk8nPi}}cNEVK4HW2odoh2_fED8G%~8e(?6 zv4Ot6-wI&Y*k(>(Mk|1`G7f-gewAX@JedSYl)=@9(SQjyD2N~>s}iv048WS>l=9bj zOKhv$24Ncm@qpbv21b(TXLw!K;HJNJ0U}L2cZ;3PZ{A&p(=bGt`KMoy{7Fd9fcj0W zETO4~(#9PKcSkuI4~-Cf1*>mx1HRr5HGzaA4-^X>Cd6;%0JO(2{*L3705>Nf<_G`t^pP#oB>m-yw(N7OW8*xiUn)-aZko)>u9ANHv%m zF(ib=QXmiJQB?7xP*-2)a(r&lP{O|nvbj4#Uvj*5VkWvpSB-+@Bzdm9fMYks`JVbWeq%IdtO=Z)Dkh4hYr{;r=eoun)h}YKE zhWkcFZa)jL>5idxQ0FBq@~L>T-+?8|fJh!b!r*mQN&kB@HzBUV^W#f+mnPn&YZn(s zt&$-QDy+)D?@cjeJ58PWM3#%>noZwm7oLO1oM+CsNaGY74uxj{U5r_1ITX&;;93va zW<&7dX)E@7?|XTFT{MGq0bQI%_$n%bue41lCh9Dxs@Wk>N{Zt&zKRjDVI=K%VWMg~ zft+&R=@k?*YwB#r!ITP2LH$Vt%*+|JKlPcT>!O&KmF;BEvKtd&pmJy^>h7eZmG1p*yP-h?IFLE0H!*g13Fh=59UAjCQp3I_(^3p4c& zi}a}qcD~uCSKi>fRcBkeyfG?ZHe^c@qJLp#=j5u+OxOh2Xjww+OT~WaRY;o|z~bYF zT`;wUzIsl3a_$Ujf%}oY`ZHAXFOH40KW+n^g35MO-Z#>UmAub~RuOmbU5$9V8c+UqG1YtMgt!G3jGyNGGkn`oH=LktLoNw}7Yt&_Djaejlt$-I;}oB&4mRYi zhK-rTsYJ7XX^4FN_Ni{H9I<%(p@H-c%BL?;A0KvYkyK12AY0HZVHHH&9BLE$E_462 zBmy*l?jL38fKjb-{s-2Dysxf6L9&^^9ksq}D+AQHT!H2|1#5)z@@&i1V_XAOD0+>N z8kRc#s7q*~F1YSZ=59Yr&umw6c1b57>oOdp>1@@H_du^HX9)tv64+Z@QK=((YwE1X z6#Lk*N&4PKIPLbBP`;dj>A8WE{c&ptL;4ufo%B;lZ+SqCCwGe8jE$(11UkLWWmZXI6V9 zJbUPPz!=s;j+&?oN*bT=Yl?80Po82+!%f9TSDi8c=hcF6E%$lCvdfUU4+xEb6!3O(Vx3mqH9C;Q?-*^k{q(_JrTHGAdaoLBn64@-bv1u z84VZo`2!>`l(VJcfaN09s>hxCe_bE24&V_DwW_L055OG557bpAwt=yC29RkqfSJ>r zGRyrNzGLL-39*|c_25%gqgY?~r;4*|%V3RwLXc@mTYxt%x0`{QHOSV(PFa)I59e?F$pfqeZ` zlVewm8I2_$*s^->xzH5_U*^lgCOmBGU<9Fi`;(C0kKqHcXgbb!u^i#T^7ou%5-u$= zt7Qtf!I2jL^W7UhP6{*RO;>%#a;^|qMKpz(?KMpqCzo??4}mv?OWtRGoxe=}92pBk zx{Xp4;>H8G7rIxnJ`9ya^|(YpsCii@lMhRp92flpuN2cWosQxG-{)32CjJj0~IGaw;1F#25Kr= z-!mIoL#Aefz*JN#2D{-ss(^H=pdU!DIJcg)WFZs1lJWyN8L}QZc((G_luM^r86~O{ zJiJ>-q)(VRKNc6Q9d)36(R-dDTj-Pps7VOW=+9#y0?Q|K`1xm=2xSz${MmZLD3acW z0qi63pFO$$F(iGQ$>FX1$GZ)QW2Z-*7&w~Ac%1)%qPZE+Daj@T_yMC)Qr)ix{xN6>#=9%AE|>^dRmI7LR%6-4$lGI-p_gkK z`+we0gw}aux3bs_sdhpKB+CsDSVjc>71qkJ-`$LKry>j`OMmT1c5VIEbyEA67tbK$ zghQ^bom>dzUm&#|(68v4Wc`)I!=3}zX4508VDH+(^7tWa{^zVIPNWdotDdjuKo=jW;4bN(oJF4ulKHeMLbdx4jpZ#MAeK(ub&~&K zzla^kZh&DF$@RjT#@+!tF8AlZ!Us+vT9tK9A(W@Rzu5PFW9`2#c7FxLRgab^k#zGll8=qRdJ7G;N zqo5dIa`vCZ{zO46dVE(QaoC(bCTF9k`cmo_idC`X8t!xsg|PdQ=f5cbA>;Ts44h8s zqC49_ks`|SG_W9_6Od0;<+{dSEdAGoHql5_eJ!ht%e|sAszyRx>TZEE5 zI0Y}SQJp>h{&>Q}LLl14WH!8M2KE^Bz;%BD`rk1)0J*nR>*TIV64hiB5xo2Lp1)-( zff>kTva}9@K-Snh?p^o?)~PiCHVU>=YkPZOB0Xwcp>qE~Fa`_Q(b^1;sGG$p$VoI6 z{fA@Kv)KTG$sf)Z#J#_LQg}F4>W)ENdfgfs4Sb%1*P1fyA2dK1_N?RO@=0~fVobEb z=re?6DmMgS@q z%8_TpSil+KlvJsr-V&)g;2s7vLf7w{rm~xP{?$6ivpPeRApr`(Gx^RPEg` z1n#cXkanNiH$JV$rHE1*wL`y2E3dE}UL+AcavQoZX1p#{{Zf`8S~{EM?Mgi3zOS_^ zt6=1PzKgn-E8t-_;S)*Wik`1b5^BZR9v-Qf$n~qg^7nFcVr-kDq(hV4JN~53**P`I z?mOfVR~ z9_ID6nA5m>PcR#pBW+Hsn3B7B(3M=+Gf3QQ8jJ}oNwr*_ZD{rF*fQ~b4!I2F?{*y4 zGwwaJ6S`_qQZLnWWzEgJyRc0kYsxq!nKtyl5N;847C9+zuTk_$k0q5F>`*wY7a`I% z7(uF7$mw;lAk!C%HMS z-gLDviu69DWTj7T^S>DvJ85$Rkx_Z#_!%}o;EePq^giGJvN~y%<2oCCaRom)k@48Q zH4!S*vP<_hFyk&UXiWuu*6kq-Km7B zL}5xoH@zW7-}8ol$*U>#rd2;#PFYdyLr*)tRmN$$C8+5WdBnTHHqzeexw0Mm99cAL zybE5sdwfxH1+?708Hys`&7M4I(`h0O6|^;-m)I_QmLhOEO=}@uw&hCPmVOS77TVTn zIa}}UU&2uF<_St~xZpzcsQ>fHJ#&)rdC_?Kx8pVe4U2ku6 z$2%sM+!<_4$O=;QMJpRpRqf31o8v#QTm>3vT}XH zdF#Yc)^vzN4rxbP=P(EbYMZcSmlkqbaT#G}5euVca-bgjE5iR2W=ND`;B*)fL4ufeItl{qKi5A-}8<( zg4Dz%yPD=P3-VlgBOHA6jU@>zv!-e?`Ma)m#-EmE&qAs88;+Kgn(Cj!rcG^(sz!l^ z(#l!~Yz9#-;|9$7|10qWH{?DJG_z z4F+x9b0y}qY6mKFXy>`E7}pB7*?H{bNHr?)99`Ifm;aaYUhAcYN>ky zChh1>HILWiFvad+am3r;+%3~^_LT;Z(=S-q$Vb8uO-aDhIfc3nd4-v zZ||sXUyxlaHTP!UWq+KQCs0))jor;fP`CYBPVW1m3jX1D-N5Z}wEW?Mw<#h`m;w*|zH8rF8UOcE2k`wL1NvldS26c{ z22QkB)~c^_(fv}b7i>4fM4z51Y=x<3Ud!TSn&s!hx0)q!kN0p$%z*}k{)hnqee+tl!z&J#RGuimnY<&#J}Vm)kL;)P7lT?w(%K4zPb zUunAbIo;Ozx}a^8{~$-8ea(1p*KT)K6+T$=^IkX*IS8^dqjP z{+T)7{QWc3V0C@fcpBcWu@Zn%Iz4q1lK}bvp$---*zG-W-}p2Rwj)(#+Qig1Y)*uE zeY3C|+&L7pe~V^XIG(wb2|NG0yHUHM{UlJmt6bK0fjW!%NKh?Y{C-OAy8G+GG)>?( z+;DytS#i0`b5NsJkAJ64r)#S+XTKu>bA@ZS&9Pzo^4Z0eyS1tuT$uggqUQ?HoNyr? z8NV=Adzlfs`<{)JoGQ?gNV#1Qv-vJ#mB#bSF_OYlRMl?w5ohZ~xa%>eWO;8OMmvB8 z-W|QECNUJGq@Zb5`MZEWU<8DQ8l08dWJZ(KZ-Iqcr6MB|?N7F;+=Ong%}^w6jT!6g z=HEWT6AK=^nv0eE32>KM-X7L$--zqFL-Dq3o>Qvpg$l4r`~4lF*?muXXXpWtmYa#P zM-7^APoMI!Wdl~TVF)9Y$l}Ge%5ulVb?`x*DASF?TkxdVA|*{Z8+r1EROsSPW(RYH z+QhMR#uc`YmYk#78uY8ny_jp`re3|#iAXt>TeO|hwWV`Q9)MJXXFc7pCfnA*%QwIu zdg;A?13|NCvAWsQiN$oe)GY-Ee};+HImiISOP^zT8@WH$tKZY<5S)PBui8)SZg^(- zy&3Lo%bpx3ky!s#*a;Or1XA;_^%JnrX$`K&R;gMCM&h*DBPTHAjwPD&G6YYkZ%=>>+w^^^L?qN-jUIlQj ztx+3r>51l&n6I#=k{-`L-wOK=vt#)rrQfw>{=jA1RPto(Rl2|9LErKTike<+^-GHg z8gnyX4_{T}zGo^n#TPOeg)Z02@pl+Aa23B0f7wM<6;~w7sf54UGw>Jo=U1fzu%^x9 zm}M87a)l5Cx3Omh7-*kl^0}q{O#&Ikd=&<}y!C$YI#1BP&5Zs54khIo{aW(r(hzi1 zJbW;x3*bhkbvL>n*0fvVN&h#1lch{*AOx}FcTMTgDnK+CZUxpwk#h|-9f0N%cAInd}W}K~PpHV~u;uNCj5(YZBC`ssPUk{spEp1L&{0$$> zvE)F251VE{la`Z%`2up7S$Sc6<<<4TW48Vph~^O*O5x%@3xgz~t6 z1p6H+2__;)qy+$Brlb8!qEMXjr+CrP2KRG>{{lPxH25!tGRO@qIZcT?EMe%vqYQRH z-9q3rKME6hz=kJaA++};{_Eda*phHyVHb2XDv}~v6W|iZ^#4QhK#|w@GN}R=*zO8U z`j;dIU^78XQGa*44rf5*;_d?k6D9yB-+<=wy$ncIy$^FM2mixs?m6>N1-?Oi>HW9WKDo-k3csprR5*ew^t6qNDU6 z(AMXr4xwXkK&(d<(}}ZFOiS9ayE3&Km@KuK)Gsw_POAfX;)3;X=KoOk7En=d-5c;w zA|XgfNF!2G(hY(N5<@9n(nxoglG5Fv5~I@Hp>&I*bT`7#4FlidzVH3td%f?szV)p& zi^Z^*`JLEj?`J=IpS|VdccysojekflI;_7y78)lcf>5k#w(8dZbXWf49)G}wU#~C> zFtN9X?CZVG*)DdFtQnr#n3SVzL`ckA9XcgSRj9voLS{moIBO%o{|+hfUtdZ5*M{qZ za0Mc$;yJ&Mi6GS*9zfv)!OxGjo`f^pExa1F?42oiQ#(cClds7uD49*;FA z1#_fdqB!C3Ln{}f z2FFM13){OZl`JZw88c-*6#DK*54|tuC&zX+hGdn7T2;Czqr*8i-h^|sRQntA!czHQ zIVwgJ|4Z*E3xiX(E<~DT&M#hMvmVtclU&!zX~5B*YS;8&wJsMZm1k1L=Zgf;tIJ8w z+T3%?liB>1Z`IPIly2U@fKR@TmPiR>Prs^?T5fnMmge^ZnDM#tj@n!=9cRQ0QGte; z&S8dkI?&c1){+5mLW&U13S)gyFdwcYUW&Rvq$EZKpE>=Y`NHx+ zReqNk7bPG5XVakNa=mXGuM|9gy$2RI)x$?C`e?*g+axpenuM4UYuFv%Jf@w$@*q9# zY*SKphu?{|KMNp`E{r*upa_{8 zB*0%j-WxsKupe1xHw>22Z2YD4pfZtt#C{@Gkv%#wM(3-oc|5HK37vED_nSddYZLk8 zOD84G$htcmB9s3`1Z0AA0$*(Y%mrAY#;r%{ZEm~2j`)k6eMDOYbgym*f1G9s?c>#X#107y*KC7nJE(To~wgYwPzoSHEq2k zSM_~p5F*)k4tao?`0?EOI_mH*wQ!{4KY!p0_gD|HgJpBfJWjtNeGVcuV&(8ARt?uq_W_#SL;i^)nF4w{{7gE+2p9Ay4 zN$2+VMHUkH5xaZ+L)evxt)9QynZ6waD(HScKfAEkCgDk-J7=Z*92I&wf6(l6ZolB*5}TeJ{^Wu05Po+i+Ti)-y@RF&-3*UG4EJBBu^xTiLJ$P;uJ=nF7>+TYb37LOoyEV6OU9`t`!pl4M9xDW7@vt ze+{x4!N#(tL?|d7Lw==$3SoY2MjWTe#eBLOT~>gI3&Lmsj0AvP2`{0Ewn*IBYqtxP~ z;i=240;ESVGO$5U{li78Z3RZF(2*ah+j)qqMBWutk;rm8LjGv68ELF>&ZB$omOm_i z9%n0YvsL%JEFHzU@~WYBlC*w8q{<}MCwH=?@|*=}iI})D8ugv3;Vhe!_k&hX$`)nV zZC+gp^iF0PNaQxHOep0}YSbRhe*Y={9q|C++k2Tli7Ne40I9cwG%S+NR5Wpuq*h0tLpdgW4vaY3Z6e* zychNK=jWe=coM)-CX*-aFkNvjoIm(4hj9PveQ81VioU$S?)h8ka~JZ(Y}G@moI0N@ zMs8qG`Lpg6>c(DsW8~zLK(wpO^xHI5vfwl_2I3#(kQ{`M%hV3&X#A} z*TB#OJAPhTowtNH=)KllhaJecRoN|1M4!82>1H1F=^-j~5%Tq7wLUCqu5_-K zuuT_njlE{%Xv|gkU=JS}eR=8aM~7Iz43XjQTEBEme$C2Ap-|cJLkTUG+;q$@mjCJmEx2wc*Q5{51+OSy+C* z?AkRLHq!YYdYc)<5^-V2L+o48XA2u8!-!xM!4@@{#-r{whe;4it5qQxQ?YDY=bJ5R z7oxgQ9~1GKXU)xf_7lx;XluH*&W^KN%I}(9&GPiUF(|r3?@d&1 zzaF@{d=qWf6wn%0 z0C-;Id}V~|qJiJs{IDC?_?4HF)$A5yYqAH8OL7P6eh;dxFG%L)^;M+N)udrR% z=?P(F&@}jwsiP-<4Gg;%ZTq(1d?o@ek`<-~6(ojLT1F?E`zFmEEmSBy;7Xq;ni`oU zQ!O?I)E7=d(~0jPwu1Wwig%NRI3RE$JVCM~ta#Pv8{&8YxXSx(v262|&a!fDjXRsh zCrfQ^JCh|6bYfy?A$%5r#nWCNlv;G&{y5-R9|t4_1Ko^LKmuVcUMmL#uJ-CVCGKzM z4gY34Uxx2`)A2XEA3iEUa1podr-z?k#78kFJ#4So$Av9^N=!mJyW_1&X>$ zE&d!7fBEg$0-Q6Cu|NV9SR2E-vL4r-W0o#yx^WM4Dl~Qx!2BLHuKh5F6U0ypm+PL1 z^>{Oy4vAml>}6H7nQ`yr_FR{NU)hn`@w+$no)2!doga2QjHDo4M}DRmUHC$(-zqiT zTAe8}T0g0teEG)38_WOd?3{*Dxk(sm?Tc!Qn5IA|2|sMn zb1;s1>Ss6eTE@VefQCaeboTNLXWi0LuwF%4cPtO*hW-T33swyd`>Bi!T?Nm5#qP0@ zLWAgxDP3N{6GLYk_}v-vDw)OT}#y)*OR`#VDO8k4Fh-FO!YJ=dM{TY@)r3M%k4q7#~ zJ2bPzOw|@qYTP_@d>JxgBGM%_&YP_=7`z{(KJBVr*8HEkgbkcDCO>`^ibc6ZKkO{Vu$Z z>Q$^sYzDT|j9(5KNnsyUkkUm*^Iz8!B`!j%HS})5d53ePy(oW{(p7Iy1dZdgwAau2 zN@wp6wFPMc(=aadBOUk^RwG*=X;lpmDy3d9~O-VGi+1d9n0<( zJ4L7O?ZWptTa_sI=i*nH?u=<%4Ij^UxXreeHjgf5T_OvW1?-3KpKQTEDb$a#Yd+B9 z3!f6?p+?5YIja@_{xMCzRFn1sHgy6t1 zB`$7e`S{#moc2=k_2;lT-kJ<4_Bl5`RNB}yGug~v zBj15^mi`;|)fd%Z-Io5fZttwWuFK>%hk9lC-e9V-h{E7(()9P)IHJ-_$h?(DJSbYE z7;rAGRe5t2k1{ZdDLXKlQPgU><{OuNr;E?MWe zN3H$Ygx6EUi4YnslxpNI!U?gNpdS6OFQ1`clYw=X$8A7#Ww5#?pzacO zqtN2KTVJ`fZ!Ab2*9o#cDy2`kHRRq2*YG8z=u@wgy9g5>;h=E@`gq zkw!@~Zjn|+>HGl&jbFrr?Ym|Jf-OZuKLuevBD`V?p>ac>3ozQ&Q))lh0>bPSs}jG7 zAfgA}2~~T?iz*N4=3Mf~8^@x#zV`DEC$tPJ!BSA{RcmDJ{)E-r17(AzyT%47*6g;m zrsqfW#|`ET_+EP~qDSBRYPa(PYMX|Bc0`R>>JUC#Ra5$cxtLv+24*FpTM8ka;wCfC z@MN8#xpE$xej%}IA{&OUwWJ~!^uua$kafAtrRPH_VrbJ1ZG~MgO`<~h`|D7pX5m}M z633L)h%rlq%&QmK!)MPA#8)XZNOqEWc|q<*tVPRRu8bK@{vpxO`AT!>9g+XRK>3GY z^zvpTr4Dj0jyLtZ4x%b)!c)zcGUIX+Txa<4NsGwRQoNw}p!J-Fjmv2QD?PiyQ#MIf-UM`awqYpwOT)+0~W{q>v3`}wU`$NmFu<0GKUfRpmNQZygIe^p6j1q zSa>b}v~cKus42WyMc;7hwNFAh^N9!VqdwJ@j^Hfoh6+qkXLF(g({Jz`wF*zPwAIHeyF8T~?D=hZ8j3E=lTjTqa3oHJJ*PO*iu zPuYgw^`^5>=WzC;8|{J{ni_4L&T`NMsX&d2Su{-ykgPwpc;D+N5p|h?w#Bf|D)iqF z|Gi{g2;8Qm5nEovC*8nnTSg~MB-}NL=PmN`(NT0^R3C4lBZI8b>qY|bQ;2hPyU1mSFnSiwL zTL??xv3%{4!7+N=hN{;!sU#X@3#(zb-yE2%e*bcnCnh#4s%2%Ms@E?tT?jdp#2!;E zBk<~Z?zS z@_y)a_2pNwwxV<#Py*xb(np?#FRS}6cMm`{5BL@$j;?00sm^J4rM9aui0~eWJrM2R zH51Gv8#Ng(2x(il59CJEHG3`}>&b%h72KI;W-TRcMS&a=;= ztCHg&n<)&OD<)n`dotT~AB?v^;b@oM7PG6n!)NuQ)rIunaZwsyne#Ghzuws`Go=i} z0m-C2vNu2@Zy_e-ZArd4a_0T)y)~(zF$yqpiN9i;1{Nfr3ph z%(cy))4*#Vt|(?k2xC&2RN)Iac>>gH*owrTdxwT6dF%?)S)8i#5+E@(*Qpp#vK>av zZrTy$=Kg+9+!%=63W%8sKP>JkA0@_t1s&2u+)ynN**byhh*Ow*070O13aqY4x_ty{!%zoR&(di3dYsnAcXS40tq7XCXB6yU7M+Ul(4z_&irB3AtyxW;y^BIdq(^pTIY;<+gZD_bP&#C^{v5P=gE~R-MOay?mq;qfmQh?A4Z$ydmrl7QHZ`Q ziTTn0Wx)Pr3j^M=gL7GLq{g_q2B7*%V}IR_Xp)R9uFdz&!~U8XqpEWxV2fLgeZS1{J~2;!4@J!N_t(AYV%0DeWX=tO`Ty}@mbP_nK^O>fL+U8; zW53Q<27Yfr`KT4u2$J99R9f*3h5VJdU8AmRnf~1d$9%pX^-!r}`DuFnrrT8D5} z7J*bI?(2U4!>=Dj5<`CQ6p}!$`E+2r7(~oJ-=s%4mj_3BT z{AG^ofYdl?mOz~246)!wkz041>PUqI?7)#YTTpaQEc$jZ|fc6=&9@MOUZm-|XS_ zuZ^rA@vXp|;}U5mNad%t6^q)#Nc;Yv27+fM2vU>BvogZAl(6QVN&FKbdxX>YTiL(c zi%SE4aIfW7)b({6Qs$U5R6;pK_+!WPMPu^4>sx@no0@Hc2QQ`y$U?t`26#Xl;TDX`SF!X>5G_8xR288rteTcnAsz z89)R{TcfxU#MgJm{toHiy#|FXi|3ReqdVl+H*W%dkP70qszPoVVZlJ*w@3|r4~&+} zvj?mi#S#7e3b^Fl=pi(|wN(^#cHeWKo$U2-?z=TOEI!TfIU0Ar*zGEsb6orOe#8gd z@2{A!ov6f;q4vmi@!DS**ryS&8o4TSqn=ZIVMBQ}n;TS)ee)wTHZwO4FP2x2D#7E& zw~3Wgdv80;lRP1QqN4R0m%R6ODqg;|a?)`%#^a0Do&>Q#smUepA+Kk0I#1IXZQ>97 zvO;7mhunv@rzB682fUg)etc3J*aOWkoQbIYE*z%(S_Gw2q@H)W{Q7~F^EC2xp$fPu z-?yS!@BB#!@J7fWsUYn6;)boSa3zVz(9oMsSt%)G-e>Euu?lni3@B4?GG{bc+%L8@ zZ&Kl-z68#jV+8!^?5Cm?i}&Lb5&}z0xw4b7J1Y)7;2Hktvj2RcWgJpy= zBTMUuv6gP5#C}gl(XH&&uuyFgG#yx{5^;S8DrveegfZD4PrCt2?nK68h6~LQ4A81D zOXV?n3=P*LVbQHHQxx6r=gGGwe#rjXV=zN#MO5Nq2Tk7#!FPa|Bn5RWgI|*6Pf_z* zlQA%+8lN8_YL}CA`aQ?g3+~vpAghH&c)Gwv@7?e6oT;h}E*m3bEq)R+KF4}$qVhs- zPfpw`ErwB#r<|g-G;~;kN?I=O&iY-6k#Ooqd=0|sn+<>TbE*IFTyI@y%GGwumBPHZ zVJqZ$iT?DIyp$AbXB1WVa$j=#eWACcoKareO{8&H2!a;+U9W?+fO|4gk~0jo_VcfM z5Rn2iw>dtl!Jw=hs^6st#Z9%M$Hp|hcfMer><>u{2ykZk9BEZtgftS+nKwACLPd|p zj87KAIYBPi^3o}_`y2`{s3G9Z-+cD#fkKw(xUR;a#^A3YQhonT2Oy3sT2x}5!~!$! zIUd3E{bDxrUxQMFobo-k_RIp?IgRaV=Y!vQFVcOaetbh7l|k|!uT)w|p-e0bI^jS^ z;m7z%lk@?^=#S;>(Czzve#}jT(=$I&mm{g@FnSnLWY98`5JfLs(y&#J+qVwZ^5uBB zX?HSbwor8U+@m))Qprc@37;@0vuP26weodzkE7H3@EA)?>TQO8lP4dzpdLv7=D2C{5*E-wJH>+0+czJ z>mW7YT}Ez>SCqZ_$*OkHJ07-_INP$<`yii~q~~hJYkU3+CJpb9YFhUzf=j)6=YVb_ zg4R7oe_3OXd-Fh%t!zJWKi;0D!N4JDFDPkFV}m_W?V~^iU(LHJ>USv`j89`LE&-}P zKb+<54$a6CapQOzMQK@luPk&a$$-Z9gs%B?g~EyYbS8;ir~h>M*k-btZ}wshFr6%4 zmKAS@X=Kr`h|trEW%gT^owRf>wn{ww?OcGj<=isN){~`YC<9H9Zhvs1&bC3+hht@_174S{No_ z#NzJYQ3w(XYik5do9H=DyZa1a67-_z;5|!S_ZC^0IF(@L7#W29{M?^;mvdWY5!A9idKsxHr|^IMZtxR$?*yVWpn_U0!8G=>A>4 zR}9-<;_q;pv(VRr0y1V)d;B&NDR!c=BegIUsMjeBqahxG74!F(B>(LlIcQD6sWX3I z`~8b&hBG57?=p^`uG2LWGggvMr+e^0Blo2o3rjMS z+(_}NRQo}Dxd~K$q~eDt36@7*(hQ~QrSyvX$$ZE_Ik9DW0&Q4Cgu>x6sIfBHe{uAK zwOIMR)YF-MoR1-f)AcTLf#oK6$qzKP%Euma$WJd<&dyd^#0x;)=r z@sRUlnWra*@8t)YM8odE{2)w$5hgt*jK?n7B6mG{)`QyjrJ(TU62^gh> ztu`7IN$ODf$d@e1bjgICX(o#DN0l-+-;O29V}eR8DQrYyT6N@!aL1R^pz7LNR1EA~ z)(3Q7)zZ3u9xPS%)0xsR5DA-3zv@X#3Mb98Ez?b4GG)z;Du;!6lYU~~ud$sLURyc< z@ToA@r0ZmNaUhPuauU3?PWmdFF2v5)mS&nEVxwuq$lI@ zaMWPH3F<}n!KA2ixOq8@v>!f>E@9vMwExRq!f-4_)V zT^k%}NEYz=ml*62yvx9A=GkX8>a{GfFXO=q6b4o}j?UBT>2js60#lw?Zc@qWo^+4y z9V{XD9m5KfHzv>Ismxgj=t$wn-7cDwwVY_$Wd^WIS%kOZ#Mt*VIan@E7NZBw+EhvC z?*aKi5@E5THd(^+L!+Ywc-|Nr8xPdC)63+w2blzV{UVotcC$`Wg*zNnYNBvP-9K1| z%Po~O#?rRrhS`(8WG7!LSDI%!C-K;}q`zF2dN$r-!f?(C6I0dt74Ow+>CPc}@FOFM zo0Sk=>#*1_kCWHa5l)}Kyw_F$&W#YeSHjssR{aF`QF|DX8Do`h49j7W=`1L!BtMfQ z^U4pP3PQDSnKmD<0@{(We?K7Czb`w7N}wgc>3mzKsIlB-z^UMdB#-*q55@C4X>&9X zVX>!vkNe4Hr2Omb?Nnm_4`5u|5`tB?HJ6GHN}hj;V+qY`48EyMFhEYwNBH`t2}>Vs zRo)Z(-sR9NLMrl1~|02J^`O}@!A zw*GKqRH@|Pjay~Kr<#n^n-`{iNvTr+xw!VH3k+Q}{qRqUaOkln#S*jlM!SzHt2a8Z z={UbpC;D9j$Wr#TomCU=+owy0%4yvu_b_WeV<{IQS_AX&Rz|2bZNoUG7%<6mqJZJU*xJL;pzJB9*8ZlKMk;I0m`oT&EjH2UuKLSE91i$ zLW`-_!z_1Df@hO1Vz$jJ|eCXf2{#4!b?9o6>MZD&f!rzekFZ{4?R-7D(rw>Izj z++3k;%)rQCwDne~HfMpV2iX;!;;*tD&Fv>)dP)4_GgI~%MsTAjx`AS*joGsnzKfzI zwsj}-q4!pMspj{}ZR(9!G5k*JjJXW#K6Hog7x9nYVQ-$64-6&n{}uWFoSJu@!ZAn>Hmw znvbZ>yv5NtaXqQ0&s=$)RNq8w`83R*J{mF@xr$B7>{qZ*S~=i!XnEHrMy2xJ(WBph z@2dP#)hri!T5r~Qgs+plx`y`TuhGVSCqfZKW#{UYMio*pSq0}6CLja zyo-ZVr)KO0UY_pLOzG6zXMO(3|MbCX>TI0CtDcWpbrv^1i*U3YTTOLkzwE~}j^il^ zX*xw|CcDDO@N0-Su6@ zpj>@MI{NEtjk^nZg|4@Rn}S}R1a#EM-ty*eo;HL16I42O7&v%T!+d`{T4s@JrA=wL z!cR%`e1eCJ--4_;Whd|SYOksi(F1KNd-*fiM2H;}ENeJTN*~Z39ew4Ky^W?w)Gq{Q zhB*a`XxtBg+^2oAFM(mdel!NTmGClFlAq{=TG9;?QsJS;A@eU)mL@6NYuWQEX>%nu zUgn)g-%2vojz~#kxR#pPd`HcVh25EG@^pV$OO`1Ekp|Kg&)=u~AEzxQ>H4t*1N0dUN9%6` z?3(SzKY8`~dY9SXrF5ax+#4Wl+*y+R(NMv`IGE&Em^|?*9`^0yuS{7vg?eW?qYvj& z?YRsU`OaY!a=CXG9qV>xQ?G7o337L33-9t0;&7UF`+!rTe;`~PqjMX&;MLBEP0 zMHDm97Z`iS;INyW-cr)3Gr6C&#SbyH<$SX(;BB5XCFpU%a92hkpl|)_XkW|I4%Rzy z=Y7jzJWNA@s;pYjK7o+`sDj99{F)Atd%?M$o{Ujxp~G#RbIWv`@70c>LT4sG6EOR7 zKv4spf^jizh0mh0^IuEtvv;iivk-cif2GcBiL^oDAsH38K2b{e6WxG zDs-ms*O=dN_(wy2;8eDf;bSdv1xTRqqU>nkb$wZW_D`lymR5t{rj`&ptac@&Dn;Bu z*f;DP0}!&(yM!Go4KHm(cbz$Tz_s)E{x!}{zW^cls?n^(xpJxUqaT*a6r7ExsNys{ zQ219XM~q4hi(d?UES#IJA z{TI&okKpOw2L3jxI+tr+241I{aX&+hDS#V&w~F1&#<4R}e&6@=l z_9)A{UuwGO`Fh@%Kp7pdM85odp`2r()b zresJ4cEm=UB!nOZf6fwej>^m!{P%Mo6AW3dw2MXuKQ07?t!^qq&2NqRrzScI8%Dhj zh>?U6-o~01SA?uWp1+Ie>oK06_-lTDD36)zJq#XM_F;kfEOrfRNdq~ss=d))2=ty4 zF>WBbW1J*8WD+0zC&rKu4$d39m{lwW%R}Ls?>z zPN14^7lUZSw689_vIa7BYmOQQ*P`d=Kgu02+jws|vA_38MiD*;(R2mO_bQ+d=TEi7 z`)zBYW7^UnLeN{1+R?eQ?x2hU}aq`wwxf-81_; z2!kD9hxD3NG})GE-l)?p7MJ_vqF!*wk@q7U^w1eXnhmVu_O6#fs8!{}Fbt#fEs=Q) z@8Ii&Boq|q$!+tu$;YKZf&67hlXrSY=s;Uk45SBeW~M$hP#qN$$dWujLJ6S z1%x2aU2s-DuC1-nlY}oTDZ-7w;GH0QI&4X?Ku`-4((K4O)$l@c==}{)tX=DLjrkPA z`EZSOJg;|&Q!QWNF=!oe)R%rA3UdnWFscI%+>(~>_jPCW(D3ldZIUTMuPeZR4}l2S zszds~$e>YKcMC!AeMUxTnRZc)7F!b5b;GckI>3%%d~It3m0`_#DEQ=96ycS=Y56XS zva-xopfx2?bLR7{yNW`Y4TI;}4S5+W6_Tj>gzo1JOx%YmBAm%s<6BkvRD(M++WmUn z<z*jE4%XoTYlAZXeF6dj9YVpN4pUc5rtb%RwD|hZId?_&}`SOj~oOk zRpYipi#OsFZTP{V%+9x*1$AQ2;(l7!OfIV#Op3-$irL=v@8V_!Y9ho$j%I`xp`|za zL^TH#-}a!Vr#GwDE#6fxa0x#@Zv*9^H!YRCiBNdsHZ?=qb}MBYPfkw0inwhl#NYvn zLO`=<B#N#O-p`w;5-pFL^sc^>fZkGJ^&T*GARP z>9E3(w)rt!TDs+p5!;$RCY)wx;mjH^Vxu^gqJ&qVrG@A5r@(RR>NApX(}LoSRd10` zQ+#QT!fu(zRj%?v1LgtfjSRGo^?Hh@LJ{md=tts*!gpKFJnN-LaeXio;Oj<4n15rc z0w4@?NpLt=GbPK^fqSWmsz2{b|6qr;JjBh(*6Dwi8o8gAe`~}AX){y{mP3z*nwsOj z*jYzcm(ttNP(l2;TWwr3hX-H>eITJGgUTzFCSq1;)r0HKBX1)kr_)H@513h*lxZ?- zR6et|-b^F*iczJ910Ad*YB$p;5F8X_LyT3Da5lB<$etXrQ7DK9Fu+I8doVy)>36)U zl1shSlftp7rNzQG$rTZjlasSuu3glp$DuKhl9H0GCQ7jn+5v+p>{;V+;pQ0jb}zfU zPdH=E%ee9F(dePjcg}l5dXFCmiZvZhm%uQW;&IaQU!cSc5rud!&@wWvR6OXmEC5QS zB*Al(3zwzFxSE)J1Od$!Z(;^zZJxp_r6A&os$!r~427J6VPE?_xqrkqdxZhAXf6Yk zdL)g^d7}TtJJ!SPB^r0@zYfBj0IDsP0At=#`6NP-Pf_Pn!e=Y8PR5#ytXE{gsdaRD zw+q!bu#)=@oq@WwP~uXh&@LB3X^e}B;SyKM679+(ev~#blnLqIk%Fd=kA;PWy{G|_ zdJoa57V4}epw(!ZW`;sb*i`}A_D=^0Q{U0-2 zaV8BCRL^-8y;MgJ#UOFOI^F<=$`S~(I=u2!?vn`U*0!BKU|ZvtZ>fzI3&#tQmea2U zeIK9qb^{;)^yk|I$BAXf>E%yonX#*Qk{t&l$*bIKYzkRlh9Hfg6GOr`g3}ClJ|Vq2 zM^l~(?IX}7H9tZJUfBpa`&BPqY}E0#1Dlw6=XFDpw@?omu%et@?d`Ik@cB6bpz=a_ z(B7a54LLz^^11}n8iGRY4@6jLfF&E*Pz`ZCby0^t{S)NHY+%*$z|7a`#aq$t2@BUp z{(PmkM(`EHJawe{@~rG&{ebGn0X^mJ)Qud2Sa3WJDF@qlW(oLv^|&>Xoh1B6=#dFD z+riur)_B_?Sa*++lzzgxS_IhjyFgnDGBQ5>^%V9htN&HcD~wVx#IaJQ@ZoBfm={Ox zN&S8B#NwZ?64T)Ho3_I)V#5abr~rg9@UZ?Nx)0dctSeS;5f6RF3o(vX{bgR0VGD3Y zTy8FdSFZpah-sQgXgKz*AEO+A4-4&UuQ&=)%1n`u^_Yr%@3!R0xzZleGchrVKNzW* zM5r=87T2RC6=v+2$a16|?artMGtc8cTD1&gVqmyPug-S{0ouNhprBjN<(`RI=_n{D zWY{q!He8$F;{E0k+doXOe=>mCP3TGaB7eZei4yP@`8GcO|M;Zb7!TFvx#)z$T!ia+ zdK}XGWM}>Z$bbk}dH|c=gMx0+KrIBBb13D1hDE%dw!I?q&njO53NJYh8{c!O5~wa5 zL%CkhVb=yEDP)%(Hmx(~mc^l5of|NCV7-^7tU~{SlRX#ue`Dz-<(NJM_C*xl zD(V-bG6fAecChN2k~vcw*F>$Umqgz4Z17;Rf}eK* zTFia?3|N5PvkJVD?)7&*WT*@~>=dIgukpsVd1j8)f`mA>^O^+JVaI&XJCr3=6$=aN z7?g)tGze*XFE92A20s<_Zv%!Kw4EO2-8x3||1%drF)YK?{QT-uLL4_gCxCFT!9;0L zYV}z7u3njnO${ycWsA6FTNTq#QB8k;RmI_0rz?iSHq5Ii&d#DW?#7zeJj{!@uQ#eB zM2T0|x?=??UvbS#NPwm0BzV49Kv!-BKo<4gm(%^#2TKF#qc6)e)luD99zNXl3Iicf z-N#21aT!G$!Vz?k_zLm~*98H78IzpXC89 zw=im}5ez>50Js!OKbIc9Q^MPyyoe`y zqXM;9AwrZ?BT&(%aeA_Gx(+Cw#`3gZRHs%O6iv>NjN(K z=`~1f61I~W-z{2e= zTKpZ@v@+3No2tmru&`KeRBLg+qxO1*E8Mg5o}BLf_oyFgQ8gi z3RB-*gYqqzob^cS*q6DA0brb}0~vdLjowp8v+jpI!l3^JJfhI4N}OD4Hu+SD-|MFP zeVD-24_2=a3#`8PlpAK~firN6iHSbo`5$MU_Rq7fOx{WZ>8D8<|BDZ5HMrKkPxcl> z>r|jLqMq0SRqh1xPY-3nJypa}4r?;1f!?23cnS`uf}C7jIW;|=1Q7D$j?PXF*U_k? z?;hW`ZCH-yIbfsw;^NI0gP9`BuZI+B4n~F!+9^|tz_(Z2aXaFCDwK)ruQS@ByCy`m z)S%~`(K$#tN!u(xbpIckCjX~+Xi-`K0dPbi*V4DXPfAD-D=^i9a^}FVCT7ocKLjyu9ae`IcqRo;~C2 z>gafebj;R%I&y4@f;UJ4z|#0@p;eOi8G}Mcx}s$w zw3x+=;gqU&D9em&fw1&EG!Keu!K0SW+TnUU?MsyP>l=EewruK3IO5fAB8OIg1dFMT zgeC3W$H{%fhJNNybJm-9^nd7g>5JIwNH*Hakz<0SZ8BVrMOV-dh2V4vO1e$4TzT9t zNZ)s}JCCEJr-MVQ8kLFhPrVO_7}@AnmxVACN{nyYa&f{Hj%UX{GRj*4ql$EmMtvn~ zQy=(yXLNCqBK#fmi!hb_vSa&SE$#;!-^lLB&xZPhC>d@}RS9}u;QF38L++0ErI$sg zH<0+uW`_yCu#_jBXI=+I@YeUu0Nd|KRTUR;x?U zGF1N0$!&lwH5Xf?)C+JFmf3aMz0DN!)A1}*W2U2!rDA8R+igd(3sZGC0>1d|(+l&d z@kWA9C{6lBlR?eZTdW*LdNX-kD5XdMY7q9^2zSlGWr+6Td@+8TQLKC;XBE4IO~;Qi zwNiF7k--e{H%1-d@1Z%uYsmii+N#Z>9;*1bIOV42ysR1p5lSs&Z<5cN12x6)kos%k zSx7IlU%4zWo}kD#e;q+UJ<}#&^+Ud4wX#4kA)*+DiRNvoiEuA`s;;8rrq?@M50deGvh0)@h$NdM?41#l1*OyBAQdp@lbEMWON)N*|21@++?by#61&H!&ncq(D zhvc&2e1F%4dGc_}?cx;C!0e>vpeE%;A$kjq+VU;Ikefo*asT*!=oT+JW>nVKFL^ZY zWZz%Zs(Z(IAbV3VP_#zwCD1(HVn4s88EG~swZg!1mO2gVO3{8>I38-{PHv*z`cStvgbT>$M!#COc-EW+8z90HW zxLj+ldG{FO<`ZE}PFb8Ci0e0d;0vvypIFWidJwr8+GD=VY3t2rGrN9|M#B9J3k%D9 zG!H>0{?(`XmU|3({1WjtQ3Mv}dt9}!?}>9QGlS!UJa!GMoVzz>q~9f_mWLYl#mDgF z*_>D6#*%(^iTrnnqr&Wi{~8?pyNq^gVGZS?bG!*=tLhJ@lMTuI%lSLmVEaCwn|lF& zZLOxT<6OH|yORY4j%JODO{H=-gTl+xr2dUPUbh$VHn#{;@4P;&NIaqL->&?riReLf zOc2>d+pV?eTsZ^Llxx?>rb8k&x}w^(47!N@L2!23!8~5Q@de*>SUILVY>F&Bwho1l_1lp%XoF76$+TZm*&SR5} zye)vI8d=p4!uf^1PMxEKZE2zu_d6UP>JeJ^pbjLEtNP6rx(B`H4R|H) zr?se%@4vs#+DE>I*1rw>e(Cdp%1F-|DKh=1Jfp7MMcCd1n+>ePzl1L%M{h41y!3P=p=qGl-I_q z+)rrTX|zGNvlpj(4cq>zPTeQ1;pc;F*R>CXrIDF`UMi6IRu}|K3`{upCw<$(g2Y|; zyYR5`3N61L@Vxjo`MlT-xV7dMDex9LK8SzVtaHLSGs_6;-ZID;ZL;Iy7uve&kH|I( zjhMo^L2cG-VAgy;D>F-;?Rh&eJd$Yvmk}8WoiY26+Ug6xhIC*HF}&k?Y4#uBh5vgg z;k61WajAxf7F<8>i;}017!~AE`cI>?5C%BR?K~RqdpI&@j=ah5vxkk~s7{)yn7w;C zlSh7??+S$R%{2ROJ*io0@+pv|%i|X)U}0S6;x`evgqALHz6G)9DlLCYLo6jGv8P5NBGP3QA}k!AY@>WI$)mJ2pRZRI53+@Yq*zA!9>+ zBk9ADohh!FnOvFFKF|xX(QMS`rw|T30&X;eIhm>RQqjX4^>MS_JX+yOkSufQg)kT+ zeE{wyvsXag!PEU}djELhVAMzBq+Kg4l^=Fco3o{`y_8F+m0-0+`t89CWj@#aISvJ? zr_Z~A+i4XAvvgvq>oky2E=EH||H)tc--~9#L&}BHRJbq|sS}T1HHc+Sx ziTO04=|`AF3{0dpC*R&(Oj*pi4GTZUsp?@Lws|E1sK*?A+DOBETEVq%ojDGPr{k00 zb5BT#Qv(6s>{Hg)yp8WRz{=OzmE7*vCJJU%sY4w>A7hrOVzhjw=O4br&^LUA=kiZ zdG`3khCrWW3`Y8>?cvHsQbGKmA|K$U1`^-Eu^xHmeM7i)46*lE>mN|Hx_@ zIof|=e)E%?;XO`hn&X0KZuv{q!JA*-t}d5CO*Af*Nh|Bvcc)g$&A-d^W-1&yCcN5rd1d8`)5FgRprIQhXRl44`$du_vfY^r%Em1 zI13m2!gsiqTXpH4Bl4fG8M#>;c6wMs9acDvQs|28>eusrP?RXwAX-kgTyB2vu_$1> zJ0aD+gNnzE`Ly-C`QJFzfEZAMK_#*GeU=kj*{@{j<#dcq-@l4#R z@v6hSS2i@U`22A88}VCwRG~jsKJ%3McCVD-`AjiHM|(n9Z$w2Yc6Amy?R+0X??OYC zgAJn-%Z%CT8(E$!3eDkC>TM1^)L)YCLe)A7J zlyc2*9x;lr;v|i26WeJ%o=#H_+BTxRW{PqJ~egzQ= z0hxa$*<&^^uO4E!v6fUIW98Obs9lEcU4Pn{Hb`i&ds;TRR^{Gq+BkLbl1RV{SC8@P z$y*!cf5FB6d_F5E;e5XCq{JVO7V|$N&+>p)ZOAK_%W1~kNV86g?Z<<;K0F%xb~WWW z<$4KUzoZr? zeUXfFSHs=@w1H-(1XR~E!cT9tU9+rq>dke3U@N45>i&SRQ|3MFBj<6a>|{sTyHX2A zRloC#-{zw6&b@_un$w^4E{@yaKpVejJ5Gcjc1hRa48r7d8y^nODhw`A<-Fh%_hSvZ z{4pZleh=fNx2;T6QEy;18S_J01c+3-6gqz#GzSa`@aBI$K2fAuT_q>Yj~Szh%;*3( z2BqujUkQ8Ww;xfSo!!$m9^DhV)mll(5piHq21khJ@24HkDAj3GImfzxEw0S#)x#kG zlV)mCTy#`K*e~;>VqXaR|Emn~gJ;5uDt~%1*Mhjoo>&+)R-P{=rMSHJCiL*`+J@U{ zw^DN<$K^}8Tdp>0kIBdMjo#FB!LNJ@cLb5jdPP4okRr0&q66Ft-x4>@-}rn8(Tu(6 z&QNT<8H+cZC@;FaS#l6xLkY}Lu|V@WwVl%zdR4br#Uw5#2VIF)r!nYN7aZd5!t+{Pc-ycPDbcS&|`AQOC4G>`f1Q6 z;zvM%*v-Qt^KYlV`;sgH%LQqKNr}qHbiJ~r)P3zV!Om4GA-?L4!=`#LRvxN#?#Sl% z5@HH@7H>niCMxpg@zr}{k2ESaFr2oSaZLL0J4+2NR<3tYvvr$(O*LFlS^j<&SYd`U z(&8(iRse-N-{lEb&hcSyp@wZRXb&X~I?Q_wOh#}AEgAk+f$YcnX<1J9NVzS2MX=N4 zLS)YOrewOWX7WivrWc$X72gRttUfrfF~y%HvUxKhVi1Li27!g*0`f}78!;b+2r!H) z40L@o=9P)Z@D(K7YTwtQ4Wx4tis|}v#|<;iR(FJR0R_^Q+naT6$3JMggx4p7|R>;_F}2c)je-uKoEFWLasFoP8FGnFnxD zyeoqcZtu|a9I-FLBmEY`ZQ|mM5nEd^1$`b)d%Q?vdD|MLOUnF*!e7?d=BoF|cF#w@ zDX(s<-7lPiVgGmn+=T?}0#=VD594UZw!^cdePrv%X&8i{^7X!zG8z(z_PnQ~nKEL( zzw4o@ZpbU3zh@FnE!tAMlas+%#9)ArR$ zn9b$EfG@3wj@U(6=!qpWxcxpvUSdIK}r3*$YOW)=x(Sk0bEqf6BZE9NJ~3 z<)hSw=E?{4Lj%b^3(_T+9vB`*m_?K&n+sp>S%_2!m4DP1P&?u>@;sy=_OtbBy>IuRmkCxigdi1Ze4I{8~Ef!(?HX9*dH|C)qHb86L#pdfo!_ zA0MYaj2ldiYPY=eSiAoRiYW>OHVCqdgqifIY?}20=%WnqQ02cguUj=i_mfS^X|@T< z5&J0I)3+Unq_~=w5}a)@Hd_W=Ur+epav(^cns*x(PI!~;v`z7RUps%O2q2PAVVB-X zw-SJasd)tM@9xL{)DKH$u-!0o=u00mHqU0A0M6&GI+`e%7HPe5w^qO}0z%T4wdXhu zd5KvL^%zdisa=g&HlMG@ZoWG|>OZ_VczD_sHvN&*XUm_}->!+u#qH-T*4^3wmOw@T)}M2?9ny!PfjS%@6yhHS5urp7NV!jmx_ zGcLOP9L*9ZGhRQ<5;IdOUu!V`wdPW&<$N}(GPW+E|S_#r)G2LqIs&i7} zJ^NHD)me0d~7t3s8b?yc#_t489x9|-S7 z`8W{~0;cp=2S=aH?;cWp`QH z^B3;v*@i_}5UzuEViH`)9oL=y;lPNcw&}dR(iy3?Q9GV|Y9s_)iqS-lZdrEzm9yP7 z7|8t085W50J9zAA8A<;IsX3?jr-KB;U3QjKKw1Csa4^^a_U;Vh1)r&_AL35O3x+oe zul&|d1t94NBR^}19h_(}k)QMERQ;iusykuU^{Hc#iKF#1OSkZYLs9^&(ot^jYuI$} zYM58*&5x{8B1*~IkEjGOr3PYlYCqon;+OjWd7S@lqmaRnq7*_7N&LPD4#nEEgFdYo zu`pDN^O((#24<^y?{iLI+T$^p^xvDA3T1F(MZVyWF*y4}Gf*)N{ON+1BSJjW-BYQE z)K2HgbuP9%q^Fj_GGB@noqe9~$?_2IMhdLbz&t#ndBQ3G8l?O$g5HbFKEI(*)QEJW z=R6C1cXAA7o_YM%90{trw?AS0!Nq+(sEtR z7J+UGOt8(%? z5{{kmj^9^Mq4yJLA zfyL&%h@8ML;6Er$e~-8d;wTxd3#Gr@BN`085?Ab>=VpH1+6{5}KQF#iCXXLz;o!Mt z<&t8pJ6(qrk5dY-JLy3>VH)>l_qlmBfO|mN=`~@t?b}8RFyzASfd{ZLIpLht^QSMQ z{)g-2X9vIb)Vgu|`|R3!4}=ygXK&NCrH{&%mn1KS@+B+IZnm%i-@w-8*fOqAE;eO9|xcyYor z!Jroyc!TlNvMT%3CU-Pj9+iKl0`*vOO@92Lbph`3GA**q;f^{rQpoOn?^gvIXp9B8 z49@7hbJU^>a%bB#YAZwldlt9=B*Wo^kt+wFcekcnke=Yb+Im?RIuDvqs#DywR>*3Q zQqopmO*R3u|HLtWKQen_zj?@K1abBxR^)VaC_fU4y6pHK%px*Q&%{3j1tr}nrtt?MrBtW0sK@){NA;d8JaqSMq9`4a&&tDYcW_~(0 zl$F)*?>h5G-gpXGh9DkwKuI4-GeVA!f9c!4mU?_wpSvWk(xo2=TMsI}r#|PsYXYCi z@Ri@^*glohW*!I34R5`l*;k<>Rf_6pUME3o%?kNA0(_@G<4J3l!Y>wE+jZ8>l=KHe zG7RUWR_*Ol@Sh3#xIulfR`ybaKD39RgQ7sTMd$Noh8xTyYQC?r_ag(5MMSjqpRAIm zkfd0%Y|lkoH=mIc-3$b_{3gjR7)>eQ1$L&OrvLbC|5kEl{8kspDl83^q$n)4za%6W zQX9+vf4@#pszPm)Up?NANMJCj?|jsEs*wKmpPnTxkpV$ZG8bEYq@|^Wn?9e(Bks5s zie*XDjXD?H)o#%6A06V9j+Yw%Sa9-URN?lb&(%}5=8TA~7o!E&kvErYVORQcuXyHH zv(l$3eQ>(uNkb(E*EfS?_f8AO%%6=TM@L6%JoNLH3&4n3P~eCn2OIXsWq3ZG?1xsNvr|UAI--&&=>iTj^gn$ z2BqG=+$V6V&8N)H{-J;VYkD$Fy3f+da(sHgGQGxd-^5!njXTKW%O6U;d#}r@$Rf-- zo7bzthN9V5o>v}y)du5;{L=-luXuD$&b7E*&xw3y&M2P{(0NV2*gNn*Zn1s9>#t#A z+fnia==!ECunPLW^RFcw{}hNd!qPm(o*-jy8`Tn?|64HnWvJT3t6n-tH30Ip+Uw}Q zz}#j~>cgX3z=L|+^_^|a*J1qODu_g>=+a}$9`B!AD(FtHH(j*kQV)r{WWN737>Z`K zsN6l!6~CBo!)NH4X%rd~3;3DwTeRAgVrs>4pVAhD|J5@6pXcF%jbWL`Y|Yj3^GQj@ ziT2Y&ma}j1r^v80?w0@_&vDd1RpF%cO=}B$xtao3aR`cD@8Y03!17#jJyQ+HEK*u7GVx;sLwd|?MI7>C8Jjon+2T2g_oWK7W!(`H zp)>UFcT=n2*Mdg_Aw$M{tf^`LWqo0Ox59dO!iz+qeyFjnRVa-ZOYnXM@Lw80XZ&wy zL(;!MPvCrJR3~yo*N+ohEbloeXGkiDF&1x-izhCCH#JwvC4WS=GkS8SJpWy-y|>|8 zqBdc)9`nVme%4RTL_pj$gU1_j$E8rBY^Af2%4u&Ov|&1Xd%Y-2U$p8&th`c!bKU@V z{@2*HRHID0T_;}qOQ%-7_|eXHNpbNx$Txr-4T@7;mxc1S$Hriv^vD<(ETb5_v&uFd zU&;FY9HGC3V5pl^5PEv)GPr)rH@b4Y36{6rPgj@?BP>$p(xHl$nz{y$r4ZLKcS+eK;Y-NB| zb-WpBu2yRw4JE*4QlnRHyu3=WYkouTy;F2$$Kamx34LF z6y@<+FOKW=?`?t2mDNdYwUrGZML@Lb{x^PfjTe>_ZVGiN_I-_`Ew={pDZCP)aEU%j zqQf<4V^;cd2mfS<8_Tl)JSSF-4bF~{(Cr@wed&gT_JWhvUGYbJvFJmwB4xcK``50D z%1Ok=h@c9Bl~G-t!{exg*qhI5K8-f&(ghI)8O@P5GxKIX2Z1$$9hJj*|Dr=3pKN!Y z59@gz9X4Tz89NSoa6HahPImrr)a&$LxF!em$b65VdB;ZV?|Cj2zZ(RLE$mCCRTVtL z!{EvzTFoF|tLN7{rz&jahf-xxet%Pb{oVXiw#|vuS_7Be0{_b&YQ-_QZ>yeUzfu=e zZ*(i`C~SqEZjBxi^Z5?8c+a}nY!2xa5n$t>r$$EVIo)pc+Ev@$9VHZM#5(>B#D*vG z2dj%=FDaHNjD)G|qlL90k+5!2!cYS6f#;kTCTAGe*)tG;=7I3L-fbhP$Sl?Vp{a{u z!N*d!K8N@GU_R2BeuA7r58jk9{Sy?gFKJX}aj1yb=wR_iDc^utm7zN$wEJ@>{o&++ z?{e|YKI_ZM-{J8tmm>!JQ-#D|*Q7W+IevdzZ9Oug8MxnTsN`bHxB6Y=Z-JUeJ@#yB zQ-VRa^w~?9S9{~d z7_K>u?{8MS48Uq5Zr6UsTQrXuQQjut28VQr&Q9WXKi;#SR^F2eLG0J z)oo&tg2wR=($n`-cSwTnuJAq!mlf`B47ba3N9)YY*sVr?7b-JmYr@y&_Xd3iNla^i zCaN4=8c@i=o=gxk@*9e00K2!L_f{5$?$XKWvWq1+{iNw0Q_7po60cP?}r+}yJ#hapIheni+0JF4G)oiec- zj$JTV0`}@F^rfFH0de%3;zwm0`UoDel&`5nnA9#5fF28~63-WZmnMQ(wCMUYeorB~ z@XREw4Uj(AXUq5826h?mmX_YXSvuY`-4nLJS38tj zid~U}TQ|!2pBEpgZBp+rM!5$StH^Ss=CJA%dzlp~!QcQ7Z9!aA7 zF5!Gosy!qPIX7JBW-fGc9c5Arkp4df@W!FXdy>Oo_t?NcsT0D(PnzW%xQ)Ls9 zEheSQ<@ILn7uibMH)3`WrgRBl8Fex{Vtv zxB|E+d!0!fHqr5A``fHIj}#~`Wo7YncdWqPHWdLyALH^s^7(U{{iICGaYTt68`naj zqh5P;+5?Z)3OGi->gV!6fkH9(Sg?-k@ez=fVew!XAWC%N7u_~N=>BIAU5A84)HEFj znn^0~6e}3WKn8-8xh5g!@nW=R;6UqvU;q~YX1?(@D5!A-Bn=e5pMQ}wJPf|%_z)k(Y8kY7rRY<|9ZXZSYSXDUd_#*nzeOpth1T=?8 zcKHT%y0@6EoRHUq!Q^N6AQ&6({*Wn1hX^7u_cMo?S#xTm$d3t5uou;-$owg~%lVr# zQrDf!P~j{yc}8*UoHBS0*aPkobT4l(-B16`=J;(Rrl$6r5#VO;r0HHdNWIFvkGt** zHjq2qqYCsmmER}a5ttquNJjs&I*_!aJ->KTc|IR{I;2!-Fziu?L z??t>~CjU2Pah>+DsdNZX$N<8nRd9HC*d$Z15NsfQUis0yH}T8BmKen&1Ir-yH$a01 zZ`U(TkC{4h6CLk+Q}z}skmn<9*9%ffWC+L!EoynU=9ja`NGQ%U8 z0^9U*65u7+{NQya3G<#&s$9$FkGadfe?RB*H$zMDSI7Gspq}Qt_lO)_RABoi1r&CW zEqaIai?%Zb`*ty!&*1h>4a62v8kU21*wkWZZYWO=J_Avbo|CT3n&H>)nWb0{r~a<# z148~zc9`8nO~2N~`FWL}*disnrbs&@9sayi_?6*F}r zgdqAgkylXKQuRM3kooQn=NJ)g+3Jxen#~#zM&|vBPgew9H#$PzCy_DZ9e=~>F^S+w z;K-)OB9WwO!&nJ$qTtEt{kR-i0^ip-KQ=a?|L$&lOdT491b7{3jiKip{V2(A2;~r4 z6bY?ET|c1DNS?Q~`(ZKTmHV4G*kJca&a`G$XpFtc|B-6&7rTcpSA2##qa@D)AF?b{ z&#5(|OX>8M!3KgoixpHZRvvuKMRzB1gvetYv`?Rs;tm$q> zVCvi)Jve$#b~uTzr6aquU()wt@coq|Q>Jzi@6*c{C|fwN)z&kuY)=l^4Bg1ZmgpeR z*KZ!8rm?uNzr$Y^2LI{RHPU-jYuWl+vPCxnTYsa{?y`c6`#>%dt5-h zhy--33z){GI_uFIoF?watYVya)Z~^0Z?hKBf4p&`v^(-%3<+EKO%m_Q9>Meiw zud=b6ih3uHDdiH|w6VHvgS(^r@MyM{%4|Y&$3ZfVnPpcelA@P8IW}iV_?476ND%g?&B)N`GN$GUw3@xDnQ-V5bTxo|P<SA75bPQ81ZWPwWV zv5xQEnJ-}CX{YVIWFZ=6=K<^vNFNX}z) zu6zF$+&-7Q#Qf7}N-6Y%*_zk)GSC^*3XTd526~XWX0NQQ_(VI5j*gxI__MKsFCZCq zuxin$$jy~@zA#2#&8komM0!e%~k$8e-hK;@Di6MiMTNyr)w{pHB7gHy?Dpry97u) zOk%oY!)6~<6geycq{o{Zf$eunnrOh|=mQSv!sz@~bL;9dmR7A)X@mrQ-D!k`7;ZS| zF>T>H-Hji^E^1#M$&IKO+m7?_3@LiIqeM5JWs!`{v$xOoq?J;pz=tWp3e}Gl&<&W@ zF2PH2J_p)sqV3D})?cnb=w*{B@ckNGnP-s!`wS3IY1CuJVn!Ku0M!r>dsSp40NZhr zL!J*1TE9d^*+;(D-LmH%g1OY{gGvY2sQh`@O+!#q)5Z;c$m)Q_#aW-$`Cw>B{t@;w zql>F60r+#FngQct^fZ&!CE#Na_7hrWyFEBI)-^QOnTAP27`FUz75fky{ya$xPz}y0oe-N8L@y6+W}0HfUs+w%5hlBfWT$2)*ein|ClHG z{?D&TtM)qqm_ewT=6iXE_F7go5qg(;TQDRFj0u~(b93UWSEWk zpTr5hyuCHow=0*Ney#37Kq4zmg*}gj3=bzxq09ogfoc5e{OekrVw4-Qh=Yy&>gMLg zx2C%K91|HH2NFks46h6+22GpDmnc{-Cj0un2RAq06Gcm_>5yS6Wp!}@Zb!=P?QJ}C z_RaQ!*G45pQ_{W03}XIphEOC54mId1CM6Ygy-6DQiKj4Gv`7mb4X8Wl`@%?AgoX4q zTY}&Fn&D;&CHB6~;Vh=hEbtJbAR!XnY4IC*yS&zLe!DA!@XxF)N0-2xxPg+$WKY;df&BQy5Ewoe;9tYZpbnZf2utjZCaji$>SgwzYM1g*>`xdPc33vVR zP*1+{E>#v4*+c-bR?2|7mGRlBsZ{WGiyuVEMGO|WJ^Vt(h=^&8T)}tW`i7PazWW&= zZ}8dn_+3M&Y(>i}&+C@h{DB(VMGNTJFL%fNhRiuEH%R{b2Pm;lcvQsBuc~GtU)yhX zsN=X7POeLWkhi~G*FL8ty>{uJPtZ~dtA+zrE-zF_Ydx~Ho642+2a&?fT-~Se*~zvC z|JT4{8Q7*{oLNpAZTVr*-YcT?Vma?@`qOhUfq~7-t*N}&-_f>n%_NTagW_yb1Ytz{ zhzk1!Rg4$bf_@%VI~6|B%F$D$HjG250zsJBU#~~|FDfFARy3t8TxLh z`_EJQQj;_E#)m_aADj$Q;>PglSIvk;O-93g$B(@C7>O-ke`ZBnb$hip)dl#Bb@}ian&mDYw{)6;$)5Zjk)GMQ%h= z`}@o*d6%4Gx}fC#!XrXVOcBNc(qUlds%XHEmX-$#Td9r)^rKRYj7S)t*|?P;>WOOoTQpC6Q%cCEl!n$3m?Wl zMFzfi?2V4iRpQ!)`{y@ber|h*xEQSrI52Z^2B$d6YTz;j&KAGbEIzq>bOs5Q-?Uzw|C6++qI`Z)+PxqwBPu(dzK3p9b-V1q19P zyN{bV_l&b+H#je)qH;XA36`=^ZqK$*|393Jvj*GmV|L{#-|i$B9eqc5HsZvN4o=-g>k zRb`^Uj`6mLD55_;p<+5dJ6jKJx1UvbV+ZV~CprnO9hhy29%+;3g`|=aX6y{v<$EA8 zCzr%3LD2v}Hz4C)Bn4uX0g;gyRtbErwnTg`XboVKnY}$TbYtKX(Bm{(>xpLOQoJpc zG-A{&hX*pTPfW zJiMTClYT?MO8oY&D0%G)$gZveCEm;9b<`(#ui!B-07y!>m-CaP)qI2N>xCBIVL`r` zsi{Ya@JDI1&47>cDRs>SZ^xLl2a{c}IQA@~A{vHf@Ee%5`*zQ^o!jSydd&!fL@BZ}yw%np&0eSH#hfLs@W3>j z9{^pnG-lr}iZ}76kr_fGb*`S50*9T|&JClr&2WTPgLz*xYQ0G0pegz%e~7`jBLHivSQIj20T*(NqrR>S9ga z;V|cs{z{~N=5=#!1IU7KSy@@owrxObt2kfn3J=W9eTh!Q?H5Y$+VJ824pil>*%G1l zx0eoKq(bR1JD>#8KU(SBeE^ki+wd?3P%`KQm*hDS_+h?x#qU2Yw)h&&R@*!Q(bx6h zlGS*s2O3H+PX)T6L{d z!Oq%prOJHD@{;9e&w9QncCUw4{Ifd0lL3C@wGC0mfU&P!-p^YNY^4fs7rf-4CuK6r zmE4qdz9k}w>>ifizce`8cLj!A06$?uXFu<1u9(`i738grK}k*hLIBA*sKJV`P=l-} zG#wu(xZV(apJ0l-taY1ffRg6r{X%eK(&ZWMvf5w!?A*^;#!)oi_yje6Fv$5WA zjAfc3cUm{Y>wVpGv+0rEq8Od$;&&f^IzH4ev$7j1>NL0`=r#LD$|g*x9Fwz@vCx{S z2E6fWY$T<69t?azK=Q$$r|=h&rDb+5yA%85ln3@IE{y!Q6>RU9D+2@J0AQz$tbD54 zZZQJrbuR-M&YpAuzGM!oU?5A%w#87bkj6_6c>|dU|?9 z0v>T9)&ZmH#qXoNOmD8w=motlTdy6*Q}YHa0>&2G+s}YPxUO~2lD`NLd$Wom? zZ)}$azZuU=-9sJm$w|VnJ=6}FZH)i&?uNkU?mpZRu;yV0E!wvIq%M|c7M|nvz5Osb zidxVpq4n#n<(Jq#7yR~ZU7Z`l>kpbL-W~Qc6ZMD@`-0Jy{0)*5mzQ+7Fg5Ar13Pi} zH}v?Uqe9b+#m49IRxF9~_F9FigY6c!B7+wj0+})(dM2mTxN{E<`X1bS0Dz@$&e)*LW`Nr1vEnTYZbQ#Yr+%2olQ7sk@OYH%3flIdnap$3f zQx?WlrDaN-WJRrkmi_gws?aSKGRHyRK4_k`87oUF37;2i@F^iv6*@~QwL5yuwzLHY z;VjwdDiZ&pJFF^>>iKE@>x@#vJ?zvLuLyyJ_#=DXvC<{NLy{5c$77$Zemwhs+sS9Y zF|dTf%umDG^f+_?J_si$}+p;`ZHdHqg!pAWIiq)2sL%T-qk!O{wy1vP>Ns{eV@j(a=5>9; zRcP?6W%f4f`^;n*?b9}xJZ_bvAio{z!M3T`KB4oeoN&80;44D@YrU2a`*(b8$NnDgkqr)I5q$aaXC0WE5>XVBA_7@KH1?%KzjkA!qBv1Sj|&N#k+h zY50wKXcm+?;-5HJ>#g?M0+BSTEb-`J-LFqAVy-i1=ruXZ3c+5W{e_dkb?@`SI)8ui zWDe(Bl_ITiQq6Snr^E+~zELM(39ikTm+S)HCLfPW#qI$jr!r8fD! z%a_LKFLB^m9DOD{LtQY>r=-iEGu2uY$%5 z_qI4>Ia|l;f(GbYC>w*&1!giu=7Y)7HfAqumk)=G$SlIw;_*}SL_erSl{)pZ)*ddt zP1;bSN?q_YC!ijB);-Z|)UI1FKyn=;o;>z7bkIzpzmmg?aslqe=3k{OHYleyg|xM2 z#VDe;;z~*mT&_I6S95^avT7&Mx(yaNNN>Nfo2!jBk=LttLh0)2Dqzju?x}a$-q@ga z`v(i~lQl!VVH@P{g_7@*$!5=^E8temxw|PhQ zT1g9U7pJz{w!Lp|M+?S$#HBocPHEIP$6UWlxgQ`E6mR`$$TXC?jbgS5mC?(_|7l?c zapJ3WX{_z74dh3T8&%$B9~0%4@09os6E#G#zJVBYzF`!T!uR$`{-m|mr=b4LEYE!1 zL=Ja_?_WYfd_z8cD!^@h>AjIxM5H0o=19Y|3R3!A-%wF}ZpSsEaLJlId*F}uNTfKae;Lw1SX#9S4T z%|cT3NWxOl=Gzp-oxJ3#ho>hS;|>T?%RSMQyS~3Vn6xTs!HN(n_jIQM3r5*^1`*I9 zFLT;fsZI|>!Z2Lv_(ZE-OyqNW+4h+e5fL$9sWLr1T?J%n=O7nN7<_2s9GtD0CJ}fta7KIh#2h>`zgeW^u% z?sVz&n=(zA_4JwCvXk6^UAW&QjRJhONq-uDs)CSdLG}?3q=4g1755Mbg*GRZmtx1%d%4N41KfxXl z8vV(8V)MoCl=y?X)axv;8?x^hje{^yl4I$x73>x(5XLqYL_#J=G`8y0SY7R&i{Qj-vRF;uL?(D6l_my{lPoZf^ecK}o*L4CEU} zAW(nhk$>JtD|kKO~&yl;JbI z{|IJ&WdkO!e55spKs{n)&!^YyRd`USS@DcE?~2w6jEj=}tpkRQ+0p%N|A^_=0Y79- zLQhYB&i|6sdZF<-jbeI7!fU-}Q+ZXG+{4k7NGq$W&olGxGX%Xw!9t?v4EdX&xGBaR z+#YbrctZ2UJE%^#(JN_nFeP)htc>Ma;FYilAs@M{@hb5>Zftrf9_scF{} z;y%lI*nEQ5&7aGRw%4yC-92~>`r^81HS9TGsnPm%hNk3b*95vnbPy^& z{yivnhJ^PNLjP_~Uvt#K0fknR^))|#;WKV7R@T-g&o)5a8P-AlJ>8bYK9r$&n|`|5 z{W_|nElUi>?PP-xZVC){I-vvZor=)d_HwI3)o&TVSisk5AT87m-hZ-EONq$pqkKu51o*znAw4E$|D%|AJ zIW0C>($Y3pmmti_t*qRl^i7E=UPr)45=TQLQTi;l%0??`ECd5df4z@z_mYy*NV&EY z<-Jb7(X|s&V#=l*p6siL8*WG?3bd)q>KdgrP}r95Yp#9rlT0O-KZdqaC8>XvoIhli z*%_TL{L{!ZQYk&rE6o=^n+S(|2wpm!j{W!%t-G+-ada>TiSJbgAJ_8e55~eDGfO@D zIC1koN%F1DVMi4+gxVGuL#VEQ=TJXwk6sN?D)2HAl$`?;(5Tu!~-rvIE)^*e)ZlY3CC zZa0g?fSOx|5Ztd$+l?*Q8dJvQU%$ga5Hb9#{>=R=h`3t8rB+u}>7ZoRfTnyZm=lPR zVR9qG2jD@1LI2yfytu4?>WoZ`=e5;);DfcaK-F3Z8Cm(o}3~N!sc&Pq=?A zp0ek!A1N9ef4v6{knqK3PqW*-S=Yd&rHig*EG+ogr_jwlJTpVn7YUOL!*=z&Cgz#1 zfzX@`GdsI+i$%I#i_iAm{hfBJ56C5G@%VRdxY|D+EF(rMDR}HSLySf;XK3{Vg?|3@FGGGyWB*?{Yzu{wAPDE9qnLq z_^iX~i&E#_G0vB%5uu?{xibBjxVRB*fjE&FWUC8J7v#9j-TrVS=9Bx8aSD=~fuG6K z`1A9IYUEKBGWf5ajpd~UX6PZKlk9%5o<;-DD`7niCGfr`5{V?KK0I;{aoPKxDH)!< zTgPGL#cbT;Fg1hkA0oxE)?)xqno%=V)sGQQm|(aWI3*p>KH-Ab>>DX^urRLN=thD+ zOrt1hQ0jSe-r-?}TjPWkyrM&714^0>*Ww&mA@zZ;8%M`$jgZm{a<%Rgi<~ zkIc+_(|pEd=^V+bnwH4rbKSB{n?;kmxxt9_GjgBF`!L4mdY$cg5x5(m+8r?-#g>l+ z3oAO!zuvbVn6b!=(v5i|66ByLv1Sbko2>HN5Fx7}9#`R(NAiYmC4orQxeFit74TKR zv|DKH56*IxT6B9{&RpkuHTG$Zjr;#!5*`f0Vi^#~W>#6z1l%eDbQ4+wc}M zUSz&rf^Q(B?&JSu+PtawVy6DWrNXqhpwGglt*!liL|cy*H@>2(ije{PQvd?2h_s`A_U$NWKO4r85#wbPf zw|tF>_O32!IWkNJ+0lGcAU&B9B2Mw!m_PMh_$sIm=ZBLa`E0zOOAHJUfuIpEFribU z?3^>-yL-mVyB&3kkN0;eZ(=@*RAog+_w0XbxS5;9kQ*UBll*!4KDSHM?!zW8c7Qc2+eS-V0pgh$ij6`rQNZ|f_ zj|=?dM-wmI+7T%g{r&xUvZ?8!=*pLe@3K2!YwO>&wmi6enW?~{yf>QuO`~}37b?5r zN@280S6cpx;pL79X1&?4*fYUKruf&cv0)-fsqfy=YXqN!V8j}j#;3tpfw%~&+)K-e z_ko{q2o3k=gt(qY?|y2yVM1I+!R<4A^}(r}VY9?CHoY*U;^ZBOXR$G7zyuQJ1%wH# zNcf+%371SEVhAGYEn>QPUIcvlRJL|hZR1+Ou;b^4_3eFu~P)eZ5frhy#g)$##{7|BzC9&NOd-IXee40FDRXh%$Td-wX7)S~z@ia`KEdN)#k!eFn^v_0cHc2i!?8 zP#Xho{(U~|O=LEAbadoK`uCIw)37ftCT7sJ?=1;tsG2o77{5s6&EjUnKu`^O)LZTu zi3?QZpll76y>#4+MYbmxKfKy!KYsiO2U4IZWE2$siO7u_`_zlg757akEqN@_#U*Vu z=A3aqbo9TeaE?)t{(?^f2oCkq&Da2x3@%e2e6yCD$oP2WJ)zsv=w%Y?r&01Uu~gcc zB}NwWjlxNS%s*6Jyyt2>ICcfprm^Da+qKk4S#c}IT`^UUTM8=sEp#W z@;(`|st|Hsg2wOM?M&!5`Cn%$uRZxEB%IwPQ)f`h1LI7m1d2NIXQ^r%lXbb+opMM=7*7vpw&Y~?%fVgM(NHWi3@_wMVJmlaj zRWUI!MKW~%)ENly|9*KZg@uYdmdZyIAx{jLMp{sO@Bqmj)$#lHF@P`!c>vU$4Z(hb z87gi?9zs-v0R=IeB3GA}nWVlG-Q8i!RjuH&Cz515`sVEDD5<2bURJ5ZP(g@+szYa$ zufdX`{H|%p5PM{v#wk`Rp(tsW;fl%E^hC44X*> z3!1`SOIBtUN-yN$!A6c$e%jXLJ*0|mkX2)A3vH}-e4~Zk6}b_VZtPv)t0s*~v%yRJ zT+BQ9bgF6)GsCRvhiGDrvJ(S>&-Yw`N}S}6`%u7rvL1GhIFeF$#!x=UJ?ELBNZ3#s zR=Vo=ZRu2SO-F=lP3i%*)%E#ht~Tseb;^HdeBAJcQH9IOlc2M6AWXv1R+Du_z*bjW z%*lr0$lZYfwzjVGB7rk&GUx~0f%2;llnVnXKc7`sA>kp{J7y$z*ot{IXw4A@iVLf= zlnT=(&inNOO#2QVx%ke{dt;?aZ;z!_N$vRIvA7>b(q`)$B;!IXbDg(G_!9*e4=><$ zwJXZN-hTJS$H#}3fPjD{lO-JVY&AgP7|dmULqwFwf#qTrDexyT8_KEY)L~xf)*s-uju!bg<`b+im+|8GDg~7xSL0 z-Y4QUc-FSBc5$hC>XT?AUw*f1Gc+`OwJ1@Dms#`K4_kR0K(4~hEg>!bahAOV zq|p>#SSZux3v~>;-KPWYvpN`@tQ_rMeaps#!t2~)Im|zVSZfe|WX?VDLTHh)UJ@Kp z=sdY_&$s6ZY;2&Ie>jPiVh~s_l8!(Y+uu9@~ zZmmR#Z>%n2TwJ&lkw)ztW#mq%W>XBL)^#MHF6XPH2=Vgr(l>8w0&mGRQ~8u2hge=n`RpPrsJ zf&3ksno6m7JZ|}L-_LD$1?Ue3-~Bf961nyKjR?aL28Bgm%cz0qE{XT$$k)8bS|GpD zqyN4w=)MBkE*#JEMY@nKpJY1N>l^*t7JLlk*3jYX!)S2L|M#sB>sU8;k`$y|O>GVD zYiACf794)PMmL2I&g(!BeCD0zv$FUuX_4ew_|Sw%`rfbWLhpABlQlE>+!{1=GG) z8;Oo5OP*&|vChU`;B$ZXSBFphW$bk<#18q-ymzXPz8j^+&ADTi_sWDCj8-PuBh5Fj z&yf6bBX(F2I%d;nm^z<(jxvHASTrw5JRbz^Ox*mhd4WlfUmlwa)r%UNHgEhpX49tn zu`BY=+Z*p~4!W1fprgJ3H55JyzJb=Gitzt=hsmU}bOA9{vUVmr_#E;_!}6~djOm`J zDhI=xK|N*E&Euz(BN550O3sGhCb$F15bY8Xhr!=3N(@)RKwBN!(jt|=GyO?ErvyB_ z>aw$!^qd+K&lU@>nnns#ROU|_Ln;Ap#+H$BHes)>4sOost#4Hh`4Sm-;w$dumM4Z` z$FND2BEXktRXFKU+VyCFxu_bY# zSm`R&Q86(cW#&g(3FP2R>Xmq`OqVNSU{iHf)Fx6AyO`Ad#f+ui4NK-^2VXk1-S$WV zb+b^{IB2S@!{EF|=8>`|qnsG0uY%_OJ7OeQtz%=jSu<`Wa)!<){`!fsR+_2O=Fe@m zKCuEY9Go+J3Nb@AsVu46Xt%AbkTyYUs;%L}$877$K8JbzS@Ti>v9fnJ^$d9VXt2Yj z`?koy8fSB2bX+BSaQeKD2dqdx-`s>f2REYa3m36VF+5sanMM!aUoIB>(bRJ?J7h^@ z7coexkLZjQv?jtbWZ&fe+h5DL3~d@TLyFJOlqH3sg?u)5M};QVnnE-*eHzqOgBs?C zdl-a=wN;M+XN4!&^1tWvsIiw@1OC9~JBjDuxTIBl18ootiSGOGZy*Ob&5Qd#+A;#) zZ!f>Fc}GV_OCkSDWkBGk4~Ub;(xYc&F%d*`BmK*YkJliVA@}#c6$Nd0gACmt++{Uc z+22gyL7qSF5oYZC{x>2X@6dI5Tj~_CNL%l=kt`MuR4=*8&zN;s^gqub*(o`LFD_`+ z)liE~1KoX;(c&wN;o)J=<6uBtZ1DWCK}2#^vEpEwz008)Pm5n_q=Yv?J2_HWfm$uk zh_$V47_<6|${yvAl&e!rKjvd{m1zUytP2r$OJFaNgf}1N z=B6m)?%&g>svtR8 zCjMTW{~mEVO{4IWr%nqLAGPua7*C>BPUmWup3r0&88MXTLl|Yn7JS<^|KjJP!%R(T zR!$Kx46Jmf2xr&loki5%6@S*o-#!i9&Xb$^u4l=RYKz4Z*H! zL(AKvTyG~Lr6_`I+d!M}F;ibXJNEf#PC){1GIwk2=V$7_;qb?RLP;*-#7UrnZuKTo zdw3LSHhSP3dw4Py@Xm zF;(xBvumt+n^X(vBt@Ft5rWY){*l(+=Le?L;{o7lzP;4S)NjIsv#DET^vxDtfxQ^H zf%C)5`1)M;2@OpMXpL8T;>`aZk$3Wm^pgA!nxRpkDwS-V$q%Ck?RcpF^+8AbccP)J zea>DX#=-fvHg(mLv`I-zdCB;@vfMQilcs+OhdZhX=Fefd=1@tZ2FIGu~0sPGM|2+3{ zyieX0lRdR9OKifGEPye$g`husW$}D|FOHS|U>E6YN|NZ6{>SqrOyn)+3t3}y%A}g4 z7V#I0YE#ceI6c~T@^b#VZ?X4s77hU3ktPv{MEid0N)q-SZF~ub@60^?pvQR*(HGfw zn?U!Uy->J7S{VKFlio({Z|7W!bNOy3RHssHfY1BCRB~{4HU|N@-{KGB&+K5cr%uT;%Pd0Fp z+R;0KFV~Ipe8?n#uXSwJhO;+gauq{&cx>V^Oc6>Inahj|3x+4DNjmMY0AT|&gS&^G z_p&^^-nV86 zqIBQX$N|an=vOso-<7bv9@LHtU`dFU9#4^<{I(>@ar z!1O+`d9yXx84<(a`9wo}%m+4L-?z&2IG&h&ex%{O<)gE~bm!CqK~tWm@z8G#xn`)?-3Uf;=f;USSZXu$^^_?RL4MKzbtx>tmYC`?^6et{g!To8J^$GqP z2wf+CtF5IJ3(_oO!u*}DbL{(_Tn?9GcT-ApP4eHd82o@-Vef}nGDbc3Qu*|O<`$op zHZBZ`^O-w93iTh_^7nhWNsp--*f(q*7cY{Kp$-E zZjBIbw-*-TfU$+qY+neti6S^f7|5_v2D=2a+5eGK$5iC^TWVxm{LsxMDc;cw{$H&c zBAvbGx^ZkOCzo&?MJ7~%G~d(jxD5g1Gh5V>KJF2K?7gO-q|}xT)JuQVZaZecXqf%z zE#m)Z0dfV@8%`k^dgA8cBxSFZU~*ZSci;bRg&q56EMj9uUI#;jAYMs%{3R_YT0;YQ z>1qlsZ~=wjwy)DmJVQ*^)J1)w^QVf$Wrv+#uHTCKaN@zNmmp&Z3beqAdJL_@&&~E} zocc&~G2i6Xz7uu#FyO&NyHgH4QvkY@En0HD(nk9|Sh9^6dcAa__-2ah&lho0AMEYe zpj_4?`qAxV!k+oYRh-Lp<3b6ct-ge)!oI@mg2PdA zTey6`)LzVtWSWRoM(>p<*5ufjihts-LtKL4jNeqUxf1FztQyBv#_^kum-$px)fi4j zU&nH({qn<_Kvxw&p4!h8`*kF|XBy`dgMfBa0V)L(S7`!UKRe+Z@)3njb3%vqbQ}qW zwa(qfS1{#h7&2@wWwE}@tLoN}nv2C{+W0BpUOc$5rFOKh1gB7^xUa3UMEAY>{#Hbb!}&u=S5~G8Pg# z0oHujhsQkwYRs-XJ`mZ~7i|Li9^)l?n2ElEiZL&{7}1;F-78?5`vnHAq7N^D{e9 zcWh23E$tORs#(Sv1fOxU3Lj2P=MhL4q9L31eo|^y*GDJN{?@fXD5iS1lWTg~P{rG3 zH_g#twf>`WkZKw~??T}G~G30B+du8)1yakhX9qj#Zkt_+pWc*nAW!&e#MKw zkh#TF{V^t-5)Oaq$*U$~F14L(dxb2QotQ^g zUF_1J^!e!|026#xiGdPs1`uzyy}AL>o1)F75Iak-=>LMw{W~{oyO~I=gVj`IX{QfVw3IF zS`VH-7FN`>$NsE8xuD%RGq9Q|7YOx6fg2tUNG|&VK<5b#r1HOM`tn70{44KkDKLg; z3s!74K_{Z7a)%tqb~4IIpz}4^ERig46DgxuyfDiHGthmomG_t~mvWy9!k^x29~T*VQb&)N=7}L`r+M=Bz&^%I~d1i5G9S z(pWS*spP~3x?#UC#R$A3!=Qds5G>CKU@%rHI1o6VVt-Ra;x)&cNV5?lV&>W`hV`a5EU|Y1K zH|_S$v#=oQ4QF>v^&GF?D$gn9qB=4R4H@ZU*&%(ptI$s={UP)AZ(Jd%s(%Vl(#JB5 z^hEq!W0})vMY*6jpVZG+f?ladvLCqH42S1PUq1r%tBY;Drew_a)-?LzPs`j@|rZXsYnftHyr{T%vhqi&d$+iOr3kPsj#GVreAp8oZ7yqhRXUn}F`^ zDgyIVn5%5zOnwUu?=K5fQ?&*L2lsbxuP@xh#Ki-Oz(7bmpP`-}X2spflK%9sUpuRv zm+suY%Z7ev^*QVN*A|3w36O9?KR-X3O<-Ri@$OLT1@?-(8-2x!0EnvcU5&rQb+5Su=tPNb!I39F?%<1G&C2L zgLblfsj1Ft81K_ey4ro4;^l9N8)>}$`bopq05#dcC|SQEGn06{!riAJU1s%(E}B;^Dh-Yh=1y$(wqNO|xKb?b2YDJBx93`ohob?GRS(LCME4 z1nV4Ay=Jk#-R!_wFo#Q;SVLW1QvLhgWaW2;alk^bPA%+Y^0@C)3s9fG3PMI(?Mwuc zE2gFIa^V~UPz=8^Js$hafz+I>F-BzSUa-^~ zpe2=jd_SlBDhR^SYcRq&cWUus(YU741(jlHLm1-9sD{j*hb5CbegQD@mSz5qp}B}XUnNsMBRq6qa5*N#?FS7=8`C_}(X0?AuyB(QqCm}CU|Lh`G z250cYy6y`IOOndo_NAEk_3b2Ri2F$W_#)TcTx8E~PNnyK-W1OU8le;up=4Kw?O8Lk z?dkw{BXydtOy!NzXb@#MfpOuJ2WIT=i!DVYEyr9=sV9Zyq^(e4tb}QNIs8D7@3c2h zR#a1_I-$dXKjy3C9G%9e1-5PadUweih8adjOXY+@A>H!B(?xe!GBMOVOPq2jJg)bt zdfv|?S=x8oSUII+#1XkN_;Mb|V6IDa-rP<#KJ?zR4NI3@g;Z)jzzeTioi^luT^FCC zBjq>JtW!@F+e*gyvhI*Ryqzhp?^_n&-u<2ck8rv^MW&nd{m$Jt1&LqStQQsGC)*8zoTDK52G((YpObr0Y*9%+XImdg0EL{F|_ zTplVb2#Byb1?~$6z(tRuwx}erSSZllbVd;VM6PpQYGK64k_O_^5AT$+7J~&;Cttg2 z>HXjh{F=AN%w{FpURvXi40hYQQY%{mQ9dPp%2o)ZVJT~j?(wmv2W2Kqr|l(av3OvD zvS-vN^=pQy=QAIY1fgvSA7E#~y$d(^eQKwu*5A0QiyWn6q=m-`DU@B+Jr|yMO{g0w z9N*>+>$)R-rcuF@(H3s_rku@)-a&5N~V%>a?Yv-SgM%*{j1>ac91h`Qo*) z9ky&ba%CnoX;eW( z_*;FS09w`H*;QqXswc~o4*GM8*#M%8h|a6aMhWC99PxCSl};d_vwa#|&XA(V{y2FQ zZIm6dU7EbUEb2{C?Sm^{UrF;wCP9s;QYSo!?@pQYtD)YRf0s*x8^8G8x$5{wCSUy1 z$JRz_p}L|f1C)DN2cJK83-mgFvX=B1*b8#va;LtIqi)`g5?T}b^)#{)y;^>Ba}EFK z*&}>?y*!GGKWOGv)b}vZaOTDWw=tCqYAzTGlfX4Lnqq@Ib}CmEl}hfvsAP5+@(rxR z>$oG{Uhr5#{uE&5@nALfFhAn-#^b?bA%sR%#5cWC;eV4ga?CRgpLgnF z>A$`mJ4@ZM-sQ~pSbaSQZphtAnf3#4QIaC+&F4#j z1#dKwNzIac$`+Vv&pv?Jhbgv(Z>%U#VK9_$w5%+gX5x4-{yF6{sWK}dHd8ceMn$Uk zx7UkHS1SD&_}Fx>0E_3?=p^sLeryONzG6bjmUYv+*5|nGVad7mQo?phUBBtJKgEx zv(O188+lrBGVUo$hadf>%j9c7tj_)#KId++i0?NO_b?j|tPM}byu$!^q2p|^-qoR^jJ9TrgJuME4- z$K(kUBA>ntTN}o~&Dxk2jB-`iLVgd?kkB3#N+`8>kM2HBg_NOkI8B6uY@2nX_Tt&` z8*JGj4tX=X5s12FXl{ z2}t`G>;AQjJ?MvN@te@sPXqaY5IVF1cI`>g7WnR#=}fau$>IqI(=U?(KXSdj_;0R8 zE@@ZJ#*H}Ol?X6>(Up;6-U@QcwatxmFWOU@1L}F+H(d@MotB1p$P>df(u(K&LSMCb|#%PlgRe|;06+`aV^YSzkk=3`$RzCvaQO;p-Jv3_W5RjLn4hxGP8pwdVB7PP3(JKS_OGME zIPmNGmp96<8ti%ue;C%I#&Rl4aCW)OK5ZqZq4^pn!4$y*aul7X-BUwg&eE&52sD@P-y7u@a8{ z-VIZlO9!AK*^^#uk_p&6>7N~Xcpxi}7S~n(AcV%H31BP6(#qx^f6-j%#>LqY`Y0!- zNOj{W-3=v=xY@iM9q1)aR=9uON`peCk&F&)^}l#DI48!3vGAvb*P&$p2^GP|dnj$k z-=JI`&j@Bb7%}Nf3h4w1m)XI=l2eeopa#0wO=l;kp|)QJZesbxitg@JZDV6&1;Feg z4Mw{wi{%c`NO-;4TUpU$5)c@FNPx>0c9?E!aRG5vMbk%XJtyE%x2FpdBb2fe4PnsC zmmn2j>+JX#vlw{uP6Lrp?nK?UHSV5=JPP&l@k!8o%8v{`KR+if()kH22BW!JJQB@n z03EXH(4KJtX#&g!^~X#P{OTi|?NaNBugG+n#aNk1c~gxVlel(vinAR$!_SR`Up|gn zS#iID?vLBjzS|V|U7*IGUgV|yY90@LIXOweU*(8>Vjlks60&rt!nYT--WYeMIL$`m z3X(-*7?(HHyKyF6J-;wAjHFO;Jt8~@BUaqkC^ihQr8sxn8DP8~+4V8IcicR`98roh zM{xEn=KlmkR^x6?I4bpCYs3 zdg0Bww$r)=S3i!^aXS#tARm>r%-O!^t^Y6SbmwNM?+f}Dea~cRu6*x6_6)t*-|JKc z*f45S>T*B+1OJgs8L^GV5b9~g?_g_+>K!Nm%m;Q@pI1@J#3t><#s??~(cP1==`4Nkk^JMI7#tY1cOR8A zdyRWb5NnvOzOr78j&V!TzAkB}#}*VJnfbiyNf%QXyiwAZUV@E+{ldI+H@@u8n`Ep7 z6FZB^KoTB-Z}w^tB-AHZC!Ssw*%ziww@)6ueugrw#}ZaZAT1hKsLB;vfT@|DNs>N?)&%}BwQX0=Pw>YRlwn8UjtDO_fkHm+m-D4rRy*8pxQzw z;5>3VFEm&aP*N7@xAM^0{x+_0U`+x7>VN$y+~`II2A!k-_-zJQ zfbZ?~@&AF*A3pPcFgjZvixkaRR+gZBau-NMRC}zn1%?~9fF}>A3o)40wYB&3{jS=S z53yXVT~%u<0&k=zUp5S;V-nj}j5=;#u<~lpM1hEo3dxMSe=h^!0yEDcNs?;uMq8Xk zbQ+qmz+G-y>GNIXBrTFc&w6c}ETbSQ4i3?{x>Wok%G)LX5ZTdWf`;Ea(+vu6zfjJ3)m8ek zJ22=04NqhUI_>iQob%p6)L8x?ua}GC>9$4x9kVYm`Sc|jMzd;Dc^idYrugbsu)eCRh&CwUwm1P*0t+e;W3mbAfP+2EX56{P$A zbAjlUHU$B9%QHSc5+IIio2Zs3Q1=Y1_s)UZ8KuGL>G8ix-}6DUKVV*oE8@!O6zV*A zrZ^eWculJoz@=Hlpp-J1aE$DgmGou6y0`DZ7paX3Li$BgQ*Y(8#Q5-+%L?&)J>f@g z^A9;1-{*hTa^tG2GZS%VDOT)pnV!EM1|xoM5E1om+!k9sa4wtyc9==iaZ0KV`3d==_HzYk3o$lbD1wpA5 z2dM;WS*Py>3nYsJwTJmy~Yl2w? z(Q^s^79-CCselzRL$B)O^2mJ=1-vL%+{K=^(8?%gN+XSl%9w`1|0hl&#KPVb1-*tk z2xKgs{06+|+nG@`=f&pk1GQ@lb6C(=EqExu^mHvC{OfXMb)=e^xB18r&80VGp>%=f zk=I<+&*&F1FX_3skQ8H4mw^}Rt6)FAHcaf-=JV%EN5j%5qg5bM$M2Fjkx5WC6ccTE z_nId6MW!WW|MG-)WNPa5zBP5qEK@k#dC^aN0*!qo`aBb*FxF zFy9a6-lNqx*oK%j+x@Ek!|&7={HfW8y1T~l!sYe~GG4-dn;<_sdVRj|CKN~IOCP(N zDhO_<06XU(HDT=oXP`KwroVyAncwCAXaQ&(9eRKjvXKe>*{aazcfP*JJV-LLyLJyP zn`6*?Dja;!O_%ql$!np&tG+W$_W@dR{@=+hnLsMe>)PeZVA|i|@)uh^Z#HHzZlI!= z@RV^sRnKU2Cjq4P^4K_zeTtJ#!kheXAWMHapRvLKP#k{|YGUH3$r8_J0e2bGm0QDt zihVvzGB>;W5>f$BRV{2>-0=JjiDaCeLuqW#W+!*zAz31ucpl0R7_m*75q;@FN z+6^|4QBXXcCOGvAIl^sAOy%kpc*{L6On>O^(yFE>V{FuaO`tdJ%OBlebf^5w%w?}< zY2GmFO%a$&uoaJ;Ni5O~G;6?qXJz=O7wb)_nLnXicvf4XE+>zb619+Gwv^&8>weQJ zM`N^b-1o@?*H`b!#63++`at3q&7P}wx7uSE*nv?E@29@2XH#gQVFQ(Xu1wI(50iR2 zr$wqxzGmwfM3Rfqex|Zzo?LkI zSIN1@iOj;u*!tBw?;b>&waz`2(QiF3GDSW}Jkc*bRlL1o9K+d5a+zI{MxC5wU)eJu zVTQVggY+u1DIEwRf%XI)k{3e2Hb-81tk(@`LHbh~nOcbq(=KJFr$>7H`00Gz5eW{Z zQ|I>Rxk1x(s32hn0uJ-dF|2&2Wm@?rI~e4g{TjHf;>dLc;=&#CpJQ4cccEd>=jVG7 zo&wa8S5F*g_qxMyN=C}e)&39yjHIe~>vQpSL2w;6Y8zf#HoH{?7gS~TCnc&~MEaO% z0adgTAzrmWAU~w4_CeawNR$5coaWuuDU2V1pVGB zQfqFbzYIjcC31u$@hSIOfhq=kYDw)Td4D7TT4kD3ts?fH-u~TFw@m?SH%WAD$l0DJ0;hRsrXO3Nd+!tl zb|70yv;H&^iw7N$!l1?|6WGiN(IcZsuWk)5Y0=P8BR2XMre6b`Y zUs0-(KKrn-oqGS<*cpoqgF0*o%dB@ce}4Y}+Sqp6-iH5ciFmkZCL^ggNPj9n02Q?h zBNigJ`mI?&lRf86Zw~_ZKxea24N{N}I&6`LCJIYHDRPdcoC+lVz|Y&;ohKfKBaTFy z?Wyz_Chl4D`(RTopuZr#F ztK74qzKl|R4Et|MZ#Vk!h*Cqv()b zu(AJQ-7RM?e7M2AwQyf_IzH{XD2PT7Lz;-B1#0mhk}jklqCB(p9xD1)Ss1HPdFstm z!J&tXyN2<`kPKV#t0eB@JVw(8aG?Ce~*yIoN= zqvsUK^ou`S%1!M)`~Uku6n%%7zhlxs1(e z?|0u%H=I2(Yo=hlHK}o^#|4#KvBXF@;P~F&SBzDZx^}wkmddt)6T9xP3+Hn`wr-CJ z{A@ReTH%{Sq>;!|Z$d=P1sx=(bW(N!w6hWkkLKJbJL6zt$|ZAX|2=x`Rk2)|AZ!vMFjoWNqz7UO@ONNLv zEOK_&-1noyou7Ju8kCu8_ayt7+C^B<#jPu3b#jt0t@{o3J`3`Ob+6KfJ4PTjM0TUZ zOuD%qEYAd3o*x%KUl`3-`n3v6-KRChPa996%Ez+6-m86C``pI-ureOOU}YqDUM!}A z1$ms8A%wkEHYh7v@2puU~|2UiG_wK+Rzrj}KW=toyjn;S^oU$uwYYfZ|f zyLM%O|C?RUMCRhaIRD+V6t3nZ%ktWL9drFpCw$f<-~GJxIm{QIj_SoG+T~RBs7veK z#bucNT25l19M0MgpRcE0yY7x?f~hY(qkEOJM=Oh>(r^uFLHR4=v3x}?lXUVIEnZK$ zgPBHmu7V~<=f!N*nntk!iAl@Np+Z=#^YwD$p`Pqs#A0**>Xdo9GGW(5#+{xao@38# zLI#O1zkX@zSnmO)@ZziO5w^d7e-O65bv$CTZm^PDxmgv&8MET#q6YuUyuW^;G`osjGRH8Z8X5_@E$roVsJt4deg zBqj*IWhAFq_St&hB+WjoWa{_-S;-uGQAvOtZ~zFPuK{FtT*puf9eV5;P|Z~2%boARzeQwB z+RRs2yZLECv0Ry;E>Vf|Ps0T5XBl1^4QCmb`(2`qmt~tbU~7&?fB5$|^Hi`r8PpAW zd%f%XKeqH#{mG^rC6y{E34gxyKTlZjJ)i&5=L2F&aI|5QiOmW)9EgKR@uN=DqzV); zg$C?a%ib8uvTpN$g=7Zc?Qp8|KH*H}l8igsoy+-ftNSOZmjn)*O0<*2qo|^6z5jr; zlmMTNZS>eDKHYDWo87e>X7*d%DUB-gmnswTy*f#Rr``Q`%$p7s3|8}O#UK`G-9Jt} zh=Pv!@|=d^K%@e8Dxz#);Pm=paQrDu;ZE4GfhqGTiPqGNDCaClBFp?kl!7H>S4DAg zcx~|~z7GUf=@~<1=Axcx(I4dx z8-iNg>4PS;=L-gYHiL+3&Ts&oeFIE7<$o5t4EtfRb6%8rx!HU!;ALwDMYRdrcIDH$ zT3-6%zU7jELs|ODDL>{#oHeNgG zm813d=XeW(qpP9e?~FXBMYY(#fDcaYQMP3G&#SYfcSeiDp#{yXFhR!rR*#p7a3JM+ zN5*IMX$~MR+`!))HAUYn`BNFXi<5&3x~kY0E5A?jw4T*E;Y>#GOg=ZDz_WOz?1>U6 zVpKXV9H$@}R||0ve8iIby~bM7O4a&TDW#B!!u2_2e&YQ8EHVFd(=60#*`ND2A!&FC zl7`Nl!I#;rry6E9RW9^pw<~LEHw0k zwB*xgI&uM)bX?;o5cy^^*WlT0T2Ogd1)hqUVzqsm?swSWG#Y*=JV-*AqW;G_D5|FA zcyF8~euppfSb0<_He()q9Vx=E5QD`rzcRj5T<<-IF52y~uDX{BA6|H|e|NGxTFcw* z?i?5vLSix8+Zn)oWF&=sZd;;Rm5Khsqa^%T;hn|Uv1HxlUt$i<0nJKPq?==H_BxwO zcltkF#_AdkCj!_G`Y0!145j-*-EPd_frrIwlW*xww|Yf(?Cj0V&#x_?W&D)e&FFM; zHI!L5`xK7Mnw}sd0p`1Sr$6s{XLLiK`0tU0_mAj8VX%s03Zjl=L+0s>_3y;!=-S)? zyTcWZM?3U{ipl{*WsvZ>EVoU09?X}U{d)DhX4oDYMK~I8a}<7($gEy0Cnu-I|7M8F z3}EyZ0DALz{pJlRr{zF0r?Kl%bDfu(n%c_luCMaVJshUaS)iVswE_D0bD+7ZR01Tk zJBZ2%0dbXA4K{;mvuM85{ zK?8DKp$0Sw-m5e)nv3Upd91==%(P>CZE?6*`omb*obLsn2`S3qbzNu)$}jXbpNzSl+n6|$SfR%8*>S4B79PsNeJ(P{yQTK1_h^=gCzIsYq}^c|O%&QT}Av};o( z%nZE#?-$5K3hqyPnbkH<4G$In&ihf>p92yo3r9mD09S`Ki`4lRMf1l5YLdrr#6?g$ z*<7xa3BUO2biVK3fBtyyY+O5I)YkGVsAm5l7R;u252j4(-d%{^Wh`Rpk!-#-nQ+Pe z@jqvFahT8-_Fr3+P--d4i5LC(q98*^6`2)=(_u*at^v>--osgv_U2${MIb=9?|?wy zbqh$ujdpT!`cBGiR;9uM+Zs&Y0*uOM@XkhVkD(AeCbhf-+9KPFy_q!w5HtD>1-M63 z8UfeBxd5c1m5a^3!h-;8cB(9?fD=GBKvcFaX2XK zIJizbGW^mmRz%xC%#7JUc5xFE(% zugU^u$PvCPqtq&Gbs5q$`BRZ(c*>cob4|! zTEey`a(mqV!_Va50t(Ah&f?h=5_CcsZnU}>E>tn z@VQc@OsDCyx&mlA@c4yabzZ#Z^_Ou&*r)Z`j_R3&iM$&QrgQAl|9{t?d} zfviB2Wk8xA_L#DH-rxE67wQ%@fWcm=Oi6G+Dh#>;t%U%%f*T$(TMacs7D3{F)nyRZjnqh-U_k6h||bS!>yP7X-Pj2Luep{J3f-EyfmO? z-+A#AR*52lMi<^RK~W$KcK;CQCG-y@vtEAad8x{>_Xy)1ry!V z3?&*8;0h=8H!y)uB95jlyV&mbCity!yAS1gsr>)P*IR&9wRPXahZLl{Q@UFYts)4> zAqAvE5KyF*4ukIQlu$uJx&>(g;n3aP-F)ldz3;F7&*uev9=x#kUVE(>V~jcHeaw76 zgn8EdsspR#JZ)xnRe)yz%Yq)^^yj04?j3w{+(>HZ7TA-n;JA-j{7%^W40<~65c+{8 zOu>^tBBylY`aJxjO;%Rc=bKbfd(*hqV6vA6ppVao<(}j_0Y%KrdD2E%qL&Oj{lP&& z0`~Uy>}jCuY6RGVQ^TZaOJx_wwUFUMNKd3U|pW4|!wM(+|Dw(PT z;e1hp`hT9r#D9A+*&Mc?b^34z=T2|-)#?oY7ZtORt^Qf*LI+`rQ0;~r`olxhHFvN~ zh1Rh#UA9afh8Jk`uj=R2x7J$Hq}5;>%nQ^ps3GBqbxQf71ABG2@>RmEYfBkwlQ5|Y zqw+f#u}}z0*`BVi-2gh&l!`Y~Zh2sP&=G}6zaA}q&8bz;k)jFqdcCG;qX2RXg%>p6O9tXng1k49CC&22mE>2cER{qZ| zvo;!q{*pKeN3C~(8RGuvS6*Bxt)Fqu1{8!QM1J0^TE`SuIRWNf&yq4W>ONQO^`=XH zaq1l;eF#+3dfJsG`E^jQa5@6oPsm{N!C=w%)Flg9eyWzOUAr@un|i}3A-iI$fw z#G>H_RN75J_A{(WebTe{s9)jAwPsb@@1M+pROf_7o*wBL7+D(^FZX{V^(boSROX{Q zl|aER4h+`HTVVa(gJl6EAs6Vz`FvrqOmt2kD3y@!znOe8k*}8h4#e_a=^z?=A}IJH z0TgeD0rfinLgnHi5UazFHpc{2fd01`)OlRBO-)J44i=Igh`bsu@cH)b72A?i*G|qL zr7y5tWImA)7)K1)$`6UMH;QkUq>;2q3Nr5?E5(%Iggn2m%dq^NT~f6zj|w>`7EXny zFH_s!&0q5FUdYDSuJkt&*1XohyxG0Bf>QH-Lc7S%60v{q8XDZ@P$OKeOTLWtB*Aj=fG zg(Guzf4@U%h75$!8KWFTG~z9j+e2k8LWayMivG&PF8WYooisfEj2nU1=%!@4>C^g?%G8Irara<6vmXo zU?&$Q#*4W)uez;%9LHF8!!y|*7#u)BUJ`~vjy3ynnSip4d8zDyect2?V8$`Y#(9rl zTpz~hNxo!33dJBV`yDAqP!c(f$)*J}sy(4@9aoXt7-ufA(w!HedO-ImGP6x(Am@|z zaA+jGdHyv~sc241VNalR>TLBH`FY=HMhRG|<--}W?F@^V>Q#8w-MElVpQ_RGih{d+ z=@YDq>Kp0trU!FMF>tq;niL;Y^)$p;qt4fXb)%Rqg0L4SS_a??cGu%v%1PxCk|vkr zwbWxj{H-W^KxOu4-F}6klmj?2At+r3F5^GHI3{YPV9sO(JaYPO&^Y z1;)Og)bk3&&zdo>?$|y3v5Gyd7<1r)OP|VMvE1j!z{V=+4~$ha{dpU08h%s~9wu9& z4_oT)Js&wm+^CYZI3LrcvV8ye##Yg~!?Qc@Dq-)HaUWSgs1zhSzZ zpVM64T%&2lk*e$Q%Z>5C?dO)GWo=qJE$o|JCkmu2wd$(|k9(uLzxiTO&tCq=U7I$0Cgu3D`pFkmh$XxM?gt>4xB}G%{ft}_ zYAKJ=3gu*xGoak3ssbnW0w~zjN5Ig4=ObVQNJLdW9}EUYLckmJD&M#Q-tY7+n5)M- zzpPX3kkbNmvW}=|Xo)?k;wNf=A)X1|0YzABeE>3t11q`nH9I@o$&616k#!3U zrkrmiB`3EW2V24eRIOBY0v+WkH~?>~DH|={tshcc98ujj7_EAve8=WIM^rI9DRSJrzm!^AO5IkVJQdg*7I{fs??MKm*I1a9k)gQmS6lA1yHggk1t(@t*G6Qc22~8}TRtz< zMz%BGdz)J2N7U_?yjuxMsRyXz2b z#ky*)UuB|_S2IapeuJ|d+$0KlSQo0Tr4u5Tj!Fz-*Jc$X_khmEomPq+`BQR2mcVt3 zp&*l|C+C4M27kZD#+SC6 zqf-y$v|ch4s%Lu}?)ln&pmrptTyztPA>2(IlO*lBo+uGw_6v1tVzUKb@IrUNE$Y}|% zp6?T*KdU3W4`Gohv_~bYV}f#18CmW@hUOQCa@{g(sUq$0?aXo1%jF)b1A=>URVkwO zjGmU3`CpQg^*S;hd@yYEzL|av=1f9C_|`>Lg1s%J&>{>o_xQOMSXJ4N;V7}8-t79mU6=tQ)_ZQE zDoY!S`-J$abtxj674uzgPPXa<-R*Bh2Fu*i0rIjF0DZv0f@Hj%Ii^y`Y ztTl&1gEjeOR}4SnQg**LYLQ`mDYf_;_0_Pg^qbF1q^?e5UMK$}4gqF1h&H(1H>m{yRbaU>G@0xpkVXstWUwQ$2a->*C_ZEmZIZ%3B{f!G128KPzi7fk9TR{EU29c^Flefx*J}0C zDFP6+wW|YAftLK31&pNTKifs`CD5GHOVuO#F2H zL6U46b&90pxVTxcL9~lM_RZMXBvbAalAh7 zA(xsJJUsFSsD?;vn6u?IK+)t83SyV8lRMxG(eI@k#AIIAQ}AA&vnWgt8`~1{DI%xV zyyJaMYE$aiyGgMV>VRZ~ah~_Hg@%j!DJ7Rt!(~O%aBKNzG2~>^*2DC>2GwjUd-y&d z9xj;atkc_J$zVY|B(>$GhHCDru_)KE_&<0;5e(D<1TmT?E?oxmJTa1D9%pU z^Fk$jv5oo>Yn&qw)|g6$z|{#X@slPUOk!Tcv9TfU?)m2JPeDgJBlkN72J}6Wnk~~1 z!Rq6*#<8h7`-QG=@qOp1(%y!#If@}H4A`35sKZF3D8}{Q(FgZLW8h-wU2{=P8Hf8K zPpL3ppxEL1V5xoP0j708g_`)>UD?0Ei5d8 z;szrlBUwN)tMX$#yqpyDU`D~C8@(q>OGl`Rzq9Baw zg=UA=Wc&3w0a=y^^1M&Di{PHOwI2D%fivP3W*ER16~6fREW`@T<$==`jyT65A7pyQ zkM8K{B;BZ1JG8Ej3%~lf+#9Q;CQM8xqDvox*3lEy4gxqTU#kh`!^)2Z`1YME!2ikNOok0V5+REBl3=7;8ps%Jy^Vy<{?w z9k;I-!CgO6tCAu`W*@w)lTB+p+C?t1C73@^m=#2Lfr^iSo)Y&--d`;S2F_<3L-V`V z4|5=~y?D_Z!|vWgIrRJPVjo?UWNmN+D!O-?r1u-=i{pAB`EZ(GkAvf_18-#HI2Rhp zx}jNLyN85))V_eYg%k))#_0CQLJLWFL|`nwbV!Tne0+&lW1*;r${7?sFi6sdJ7ZW8 z7jjbfnnNrL8>f?8HoNb^OBL%V@h&T6-%=XPUxcjm@n`wHA$ev-@=b&|W{ zqEMmol9KPX=H{_EPa>OhKiwt4=AAcW8}0Ase@GX6a&YjY%6{W5n342G&&}v03>OQ_ zorIFK;iNwOCJc)Vw$~%%DYKHGc(0hNB5che2aS{}oNdLP%qRNqx%zWghPlhinMot( z+bU89mrojp0bTqN8Zu?K6``giQWx=1UINyjFyb)Fvj1znfQKo4p}_*u0+AdOC6C@ERJ!%`@?W?3AD80_z@L>BEus6!^2wrU<5+H=@A11 zLvCiKNiIX?{D~^OxY#cG-Ssu8tzjd-=kca%2bfROb9r?IfAJ*!+Qjb3?p0o2+Ky0Y zplG`iZm9Q;9hxo?zVKUKB%QC$DlJYK2zqQ#DwxXW9>gK%ExvxEDJFJ!VZHRj5&{9f zdXS_KV`*hm$2g3$!P_!4qJW{2I0p>FG~|~#tp{R!whS0>v%gqU>g@E}guo{0UfbaB zp|Q@)fbw!@7J8O@PoHj@W|_Wb%+BHhV=TE^n*hW-w`^fSz+%C|5DfBE@fnJzhT}t*_>kod+)p#F(DXtt4UcsU_``PoNL&Ipwne6an zK8#|CmTz_~GiAI(h9lM8;d`_rXpj6DcquJSF?AvGt~KJ;zRu7{L~d9BaF}kCmTAP4 z^xKabmST)18%VITWN}y<(UOF$N3R%VcuPc6JO)J<#i9Zu&S4Z)1K{jhv${9sc-jbShAp=f2~8ZhISJ3J3@%pit*EVk~5 zgLeD-R->BqAu33};Y%4})WHtA{(R6uZA=}=DTWLOUaLPUv7C=T3rQUQqfd{ZHf#f3 z>HfUPU3~=iG|3Tr4^yoqWqIREUE$Avo?HL}$Q1&l{ndNSOidZDl`jfk;`+oxyw0>* zh|e3?Rv4y7dlMcWIF1iKo@Mh1goNdMH+L+*%L?FFV#qUML@0s+ezByC@Bjn5Mu?C- zw)hf8z8WkYYL70ddm_8#SI%!+E&AefBZ!W?Uqc0MA46sxJYVXI?UzU{SjH6(-=W{4 zECa<}=n=S0Ph!7^cMHIfvynz2H9%cIw&kj=~a%nCK%&n%+Q|Ln0Lu_hW@GoB~eq1Lf!n z_~h>Hn@V}NDMhQKbR^4OOy7Y7s8mxAHgLL=i-Sv;^<`|&=lu=D6fpq*q*QiG%Y)GO z@179=-(84*^L%x|iI^C2q_u zWOdTxt2r!Vr>U7z?eTgJWRZB7eeyG zIez>D7DkTqa@VJ)*-G&|XqHXGqe&oV(`zHQ4I)ylNx{X%l>@UC%jSQT((2BcngK_L z_)w)r67E=&zPTg&&qOg%tJsclrr%76imBN0H0Q%)rx{8_*+)?qe7E3 z(sF~B7wOJSW99DNUg++DJK5R%lG3-;d`oEn_r3DE-hp{wVAQys?N@KK)gTf6Qic}3 zXL7*wW6ofL)*GKAUy9hWlU|iz6d5(N**bbZQZ>fsk*+4jTUzzaK3%Akw(GtS`DLI0 zbzG6%=q>Cou+d0JOjOtc>WotVNi$yIflg!UkGH$c2epjB__u?YfB+$2$`SyjgGS2^lS7H~};NI3E?ARXw&1$9Ful_i9H)=-12 z*R2lEQ&RPk5;9DFK19pbFE#)1u6vC#idAJh0x>>ym6IKT_j;VJmK-g#tGqUBa3it1 z7`8b`Am8-b+NfRHuhw{ZBwUo%4&*h0#<)dN$cj<$#@;I&te0G}C)ZQOUQ6hjMH)E6 zBE!208w|ciYt@85SbH9zw`1q)e&hJf{oDTh)T++y`fksJaImdBv@qJUYeXZ}c#;0^ zM(<>xUo4BL1A2+(>#GYy9mQgIJRTsEfI8=K4ns>z%N!Uf2h!-~nHf4540gI*yYr{^ zovi|Ha2{xXvpQWb4n|9Z9zr}HKYhvswTR@P=R!eYVb0FU`Vba?AOrCP85tj*y8)zU zuLV!~iCJH&I2lOy{Z3`I0dK%>+ysf?xmvTE1lfK6cLOjoK$;G4Ac$F?1G&nf+84kpArn`I2Z911~y|b5Q#H-uIu! zKtxHFkolM(3+I$_N?qwt;GFHB<)<{@fRID{?}lz#U33ED)@(LuQoMwO`PX#mjii3; zFLfoyaO-h&0AE~3l*Xu{sv0qNb`ZY_OBbi|-07XlUnP$oLfY{}^c9lxaQdx7+eK{F zNxYzmjl|r!W{wqSGCg=!{G+lZYY0p2Yu)LK!Mv5R=oL%NY65C%n&PuR>2?lpqZ()l zsox*th|NxKx$BfTqjhO9^P7_2yEnsFi<>01E|}!-MN-XN%yy} z$ICFiZ?5ix<}CrB4~8kI_8YhXm4AdF@_Aobc|TV<*$)sb3wh~YQ5Gbnx*nxp&Dz5( z0Wb_^bpOeg$J6|#g#+w>pdStuIvpKdfnmLvR2QIqO+k(EfCL~NS0}5%yr0VeP<8Qh zY>WaRH$a~~QT%pG7w`>tz>LpG*|%V#R?ZA4J`Cr2UYY^!5I{Em#Eq$`G+@vwd*RQP z78HQzs5i1}8iLSL5o6c|hF?|V2oV~nD3)8;p7h#YLCFMZ~_OXooLqlYbE6z;T8om=_W8_?%D;N2PV5olnOOe_AD z@hWahoXe)5aM-ZX&2=A8n^J5X9iKmBKIMPU#4l@3pc<88*kA`;h9&yn#GcZLY#O9v z3`RkfiYpj)C)Revd$e#Eg3;HKa zMpaccMD&@&iw^uU>mkK;E|?HNEp(&$(C!k;05~c~V*q>&rqfT+pDr~ALs=y6Vqsw^ zz(D^IpqBCuwY|4kEV^~sPUrn3FX7YVG$^YPupoZMP9M8~U!L{piInqtjFYZ=XB6`u zYYsp$a}s`Gz9#4c%iLe^T+nHKP{Eq&Bmh1N`dNkWZt#O5xiwUmW}S~2BK-UWTSAfW zY)AlQZFYIKRq=2P9Q{#GU=+O_y%x5Y5V{zM?n^(*Ks}LsPUY7hyKK8iQ;8W3Z{g-mQ-j zNV_vho&IUm@TL}bqE357ro=4Sa9mvAzkf_|kMY*y&?DJk=r?#kb3swpK%m9DclJ0B z=T|`UmDPz#-Z&lu4u$zDR+va|H-_U<7dSa$&g;L@Ka*~KY?6ArNe+l0-#>p;zm&Cw zOJ4^J7wSEVAtV^kODWqPFXse81V2!iq!cCgT{D2(3{;E(XxGoFMhpf6Osi=@)run& zjH`a5pcyPOubn7hZftAID?GCMP-;N1K1^@!_g1Q@1u*L}IbXw!DOrrzP?yA7PU z4!z3?jnzMsJ=%wG>98qMI%}lKFwm#`>N`zck&D??nlqd3zD8juuVf6oYw}e{&_7;A zh}jNkqR7>f9(5S0i7gz+cbMA~o*nFf0!yv0MBIv&#O&&_QEZu$B1L3A{{1tN+<{+(SOrBaXsYH2Kz(#wa+0ZBm1$TG=Qy5<5> zjF+r#98Y04I5PTCPMXtSM<+%x*>qv=Hilol9dpRpsC?ZoF*^Fd_R>*lygR;V`_gla zFlX2yD@Ej3x$P7OCKKr3wpzuoI$rdOk<{M7ZECxmP3!BZHWW~&FQ@{|tnWJu5Z+<< zXSZ-;>espO%f)P-ZdJ~J{HgQiu)$?7OA~$ubZmf}Q=`%y{6u<`B^(LQLJi25=03ms zlS|PHqnex6-r5cD>^hB7_SO7*k{TKsUvkSt9K_x*%>Swo4V8Q~%=Ja<2w;lfh&(b? zVa6LG%*#vyLbV{Fl`~4;Fvxn_@Xa$Wb`bM?QHx07xns=Zv%jzPYucJVLkBwb{n3gQ zAdajLJo9j`ts&gQ#nwlZ?O0$^+jNyzA)##`I2+w^3u4%EO*)HC`p?79IF~cEuDqoM zl8M>6tWsaoHKeVh-uvf4pWym}VN(f!vr~#E3o@D~C{O!TOiD(j^;J`WV}wD`J%Fgo zz7KGs3|%h+f{7nf;3_XV>FALE(tl_j96gYgBA+Z`^O>P91$vK%Q&vAQqRQ2<(JK_2 zLZE4U{QR4P?qDsca6#)mnEOh1yoy*P%?ZX?z2gdu;0KF??&N*~P1EcmpRf$VRTBDm zlUe#GK+!On9vD+Y1R)EtiXfUdv>;~6BSRiVn~kU=DXFByU{i-_f7PsCy$K>6+vc~b zv;O5YX+Z(CNNK5`IH95wf4l3~EP`(y)J)iH7o&n$gvn0~QQKE% z`}_N|IGoEvs*x_;H%tXa*GqtEnRd>>vJkTXeV5#a5O2uWL3hK0WjzBQDv9P(<>UCZ zZm76Y7qLv0mP5xyRvIiTc22+XGfDs0Z-8*Noc#Wq`Djo(Eu=O&&Za>ehwqo|f!xLj ziYHvd5PJ{E8*@vk3p$ zqML9m955^cIe~y1i(YNy2mjyJxPXDU#U;(iiU2gQR5O6 zhu^SShQ`3}DxyE)$3?6UT2E{mC%^ju_2+Ws;G~%$pV)F?7@c@%e4kO4RdQ~EfOjcs zs<~u{*$%(rKTi6T5HOV*L^RQ&$=64ZgY{@yQ}Kg{Y)VXm9calQFO-z47j#KfWG*KI z(i6Wzh!*h`$`@OV=}y*oVP(mE{+7(CTV@-ED=GG* zoEe~>W;6eFhm-)}XIcx;Wo|_}R9oE!iI=4*Iq6*_QQQn(A8y6j2Y_V2V&}?x%#QaG z@^fG7=d|^`3{j{-jmJ_+PqOg#*f;n4bmc$8^!f&tI0fHK?2YVWy$n-P|3e8t{updO zQ)<*0ro7M(I`eGlH+<+ra-nAytN(DdLT4S@_uBF*uJIV-kr%w0K+ZG{O{Q$TK8G5@Qs z+7ZXF&TiU37@6$Vy0o$C^#vZ?mBZR3JM)x}60~p_r`>rC0e(xA0Zhq5GPY6}0sSIS zC3M7E%sHc|63D!xusj-j7IPqar|I!+o*khe6LXr6Y)t0kEYPm__8miB^i(1ZGxAEG z3&sAdiUP#D-OFu>Ktl#ufj~743{uLp{jLvv*^@4Q@jW&+cHPkFA!5o3m;t&! z=PT6rEW)eGmQNP(V(Zc*ps5mX?CY^T9Nfr#L?G4>j2JSg`?o}&`9-HMrLk_pw&RxX zi_+7V64a!n)u=85X*C=zdZM7OyDL(Oc+>z6fIQ&@*w+Lfeb52x0NmA@nZii zF8y~a(-5v=XR!F}IE&`;_-CaIGb@LgV<1D30?s{fATE$yp@`}d8tSD{DNK8yrmeO71a=Kp7 zsKVp%FlkTHx!X)t;@h?TSPigQCBKD8mm?(hl_&sk{Rb@nds7BPtB_f72+hA>S}&yI zd-k3vHYRzHj0MCDsVw-)Q_|<;JVipdYi+~}sYBOR^q8C6$BpD}ck?R<)PStX2ttW6 z%FC(q7AB0~$n}J5*MW-B@!O|hi68Oo8e$pGx|bW;l47Or+d4OZ=`%He_?7HSn__;w zQ9%Rrp>0XZZOX_uw}3DeIK6-QqQAEniiu%Aj3MJ5>P}w4093H9jv`Y;9T1rqyH%7~ zxz`5ksgP|}v#+Hk!lTifUzMOVl%zSZzJ8o|IF#lB; zLg1JA>-nIJOuvH|?rz1Fc!WO8Pi4 zua;1;Rdn0VyeWtb+>XiVFfHW(izf&(vd#e_AKcko39rH1Yyppa_E>nw$uR;4!mBrg%9jy~{ zDbu9W$!$stjeA&4zsze(RzBaKuEUZQ)1%VlN}|fH9g??tr`Ea%|6#l^LoVtb%@kBL z;~khYQNMe+Fiuq zq|MSW6+iFTGtbrtdZpy@*eyB zdi>syRb?z)+?&Bu(+PWjxsybn-l$>rJsKAJ#HfyZo)hV#hYyuO8@yC7X3X6Rv=E7D z8yrM6?~b|7Q(RI+N;lek0!{qb5KpFzSIFFEyi3+O8@|p$ zX#m8(D}zfD+HUehh8^`T1V2hQ#sxo~ohLjte%`5^?>mwLDhF(;H-KcK(bMpUXtl%n z9G20dm6#l1vwz==oWGm-TwD(U%J`s9xHrAxyEH!^JciYo8p^v>7HwGRC%cml)Kb?E zM9W<0zsBItp(s^Q%QvoVsC|FJqobE(X6LV4Tw2z&KJ~KL>&DgU(mA?T$p(OYYW01* zyEP7Usq68Nwo1|F4x})?U5kZM;Tf5<`7D!P*XO@S@?dWm_~g*+cwk>J=1#icCL*(U z302K;F%pA|} zB5y@2>6Oyf*~u^A-QYnd_~Hp&B(vl4?rWa0=ELWC=c$d2XWeAHg@*NBHfPuAkOTL3 zJ7eed?k^L&d$>haw)KCu29aGwOtms^D%FNKBuRTSW#A&#e*ek;#=k?r*Q}kzIV(^AXECB&y+hV|Zaz+(uGg zz`W_ohBmP4z2>?UQQmjSUke5r5rW^MnKEl(`k}sC*2dHLdq`m_Du3EliC^vbYI`BM z)O)iGOyv9=nI~c`lIIyuBQ%%%jTED_`^{rB89ghmET5CxYmWhG3^ha@=H0OFA5QyR z+V%3+dTY1#u&t*@frqCDcT4lV-_$gMAM-$wYS%D`$Wv1dVp0nYUWmD0JV{7u8fa#0 zo1Byw9~cm58)%kbkzgEPl8~5W5)c>=l3;9RVi804_4Ng%{|}ZQ(7pdHh3d(NhlwM+ zcXaflqM|g&p?8%!4XTk_3?QCQV3;ChRCmu-u)z6&3wxgVjvlTIau7X2jer9@>OAl8 zJnzIUO>>Kv$2`bj_t`O1a%a1j^-JxRoCxW}NBuQT=52d@8IR}l6cZVrwLlx0TrJmQ zsn`*#(X;Z4C__r|RB$C|e*d$tV?~K=jJVzz6 z$#jRg0*hMnl%NL7{=!vu$1mDO2iUW;s!o}^@|i9TP7BW=LCB)Xv+-3`N3jed=qpbQ zP&I+iSA1?~SG=Z2M;F}WBXiKyL=Qe?eq`W1SSBEdWcm5?rv(840gGCHKg)dXic8eL zT7Y*GWmefz9+#FDCME=C7S@#ayi}sWYjTnA>FwninC_M8l1lY_A$H*unJ5622dGj9 z$GwNp)EcjjD%~T5cZt^nUfI?7pHKx6t&E`lG7p%)x0+SvLkRMx7ObX5d68IhW-~^l z7JPiPv{nDy6eU;zBOg z8qDX>XmI!pbh~r40y-OeUs%dqXeCY_Ok0?#ae2Rey1^^;BJ%K__0!;eDtmKDEtSpp zy*RS5!QSaM-bQl4bBzk|Y_RPSRGuSw`du?NjwPqN zGAn?Nzk@J|8NeO2L-4&D_W#8*2vyO2#UOsa4BK);0tn?9x?HL6(05VnGWZTYm6=pu zg~$ww!1nvgQ%IvlM=0NC%&OLn-zUOd8(>KqIq}3#5gcvx=7zyopErz11)MB{F^5Ku>_+LCD~6mA?rUkQ>L{e<^5+d>#S6$}MV- z;%?{9)V>$8GsKq`h7Z4aC5~y1Rcq3o;x#a`u;`?>O$4$3pI=)^Yy!Of;MdD-ZIwf5;{SCGL&kcAJPm86i8RRvJBpZ%px z!B@5qGR`3O98{GPy$O8ppqm+JqSJLR0}r|d^sWP`d2^ro+!3`6AWZqmIpe*%F-+vL zK^Gu-;3d-|kltksbitH4SWmXxg}$I(lnv|D?oh)FJ$)LuzcnAM9IH>Pu38RmOVfE9 zRej(I?aJ0le1FQyhN@KQ{`2Ce5*HmDb1F#_G-E1UcGCA;7ubgO*SuxdLP7q4 z9XTN%I^wOEPT5`}^I4tIZXVZ!-QPjZ*{3z1n&K;cB^l6-zmO&htsl;&LYDey{Ijib z?{r99G^g_M3i=WssBHlLwY3sBnfAk>i;}q}GzrfwyjMz&z`X{Uq^{4_27OwX@KlD$ z|3`-CM?3;Vi2ZePfiH4`9mJlGjwCDXwQzJzrrA|#4dt-$0^lvNg;@vQgI7&j>@*a^n&NWLS_KA(16!nh-v$ro6sB&K;0G8^XvVA0q6U5~v@P@Y*b-0|)Ya z?tDm%Jx>E7mdAu7iO90iwNZ7I`{B5-8TA#WjRNT*J9GNOb}A)N1hy8>U=cRtBnz zlK0(ml@36;dZQyZx=*ddDcka$arR^L0pYyzpmyFXk@kik5&F#HR8RUqos{`ok ze@blV>3m!v>#rtTigAEixjXp>1wUfrcV_={NgoHd;evKRx*aq+twkxPiaFm!lyleu zQk0iy9+W$ad{NDO?~W)8;?=LRQ+mSzwiV$EZ{V8|zsFUzB;^=gRhE_pp@#e`lz0*( z^JPEwTu)C&tGKv~E4g>NcX4RreioCTnlu5yoXf#Fb7^gjRascUa{=kQ7}!BTnITF= zNcwhpzdAZtc)df8DFYetG*N$(qz!)ntresgf~vrl2!=-u=as%-riLugEnf!xKUSX` z5BuMxhhSd%%K$|jWnxm&n}{8tn6<&(@&(h+HGb#+Aozl{Tnpr9at;wj?4>$d_) z|J=$6F0UcW`Ruo^B>+k$0j(B0QoC`OL7UUg`Bo62`_4&+dtHE~HN#t)ah`IYmZS5`oYcCH52Dq=eluxee_DJ{Hd@^)gMiHgz&oSuVuah z4kRoV4s^%m-=F`;bq9l0-q+XFz3~pa0HFDDqTtK0!N-&Usece@h7g7$JOv6#_Zm55 zzE4}~ACOfBSpXwIo%Rz}EpNJ@qi$PA$CI+1LA057>jCIT8=d6O3=D3@e~`Tzv1vLN z{zeary%Boxv9D*MvPNIR-8#KSt7|CYpEe@M|NWin&T>C5{d|F_+y=$GPL*1Px^(jq zKtMWL0hID*Ks#{lF#V|iB~3Ju8r5&$p20g#(|c;)V?S!H=N0q zSK)J;ba|~)OF1_;XE~mw{A*03ox7YifaXaP#_c{M{I7e$1fr5ZVEo4KmsVC3Q(rV# z>9n;+ia}HAQJ`Mv90Lj1I#4rI8tCgYF6M%WjpxBJE0BC6R_)IJfkK~5p(@4}4mO%x z)kJ$y|CxCZv)_@*N=E6?P6Rg^C-L5z4hG`KIe#xtKHHy+H{cwEN_h`&j11NXSGft_ zW^%xN{B_!Fc|;vnzNdg)vjRl}u}i>VRRE=>1+WwZu^i9tl7mX3SK8XzW2U;l9{~T- z^IJ`!=?}se5oniy5W??YNtzF;YPDP8(bdJ_n}yYgpNE5qj;DM64WIXMkPpbX9>#XX z?hUuIo{!`-+KSpA8p}Vthg5zWKdAkCDia7P|*r|(;|FBAil zEx;!NPWg$5=$=7Z*GeO5Z~7i1`5SD6ToUH%r22o-ssHGGZxe#gZ;+Ms%Dl=<$BN!a zhf@ZN6zXNUlw^IO3PAtX=&{7{F(XaHoUrC-_25N&h4hrrY8%VH975JDaT4==bgrH5 z+(pP*XGZ#Q=c@fa=z9YFZL|s9-miwgIuZ@7coh7O?rb};VsKRI+3ivB0x!KGt?Rb< z`@{Ivt8dyIz^1Sn)`{ZMO5~5Y9zsvS#^$rzwYzK>Bs!uL zLQ;`mj}~eFYsdePAOWU4%A8Z{>$B|hnz={b`$I#Fu_C>P6hCOfTxm93=6)x_?*@em zJbut=%+~g|$O63P|3Z^h1${-K+)Uph2G6|!Mg>ai0oH&7T5ZGMiLcxFvv&#P|Nx2QnmQKlb0pBzpt*}Hb!BYsq07dEM`Qw(T2C5#p| zDTEh={tZL_5o^lypdLCqod3yulpyBJ0cxK)hf2O{7tu;cNJQMXH6-TL;!^8b1KkHq zf&NPr1Xt4yo>=1I;-KR=MvEWLBOu6PzC;Mp0N+cPV+u-($if4rwLv8so3s?I0~NFpIfQCzohbu&Ue(Gs6JF|LrRHMJYm;lKx_^pv zs>jzZKVfl-*pBll_`U+cpRqc5ROxN-7Y^RV|2YRB+XB*+*k8r<^^#z0%N@0s=b+my zAas9%N_Mp}%YGLqHxF5XezgFCfCnuCl=jboj7_KBP1vx`#TVGW4D}pEm%~*8FeWP$ zlZfSs8PHx*0wIQcnuKey$C(2*os@pmG`DVljPSG7JD!MAJ5S?GT+o2A5>eOY z7$RJy1EQ>JM8j3@!@q`0hSyvYqzcTb@1^W!A&T)lG%Btg5e%TRk{Mi>gg5V#EXYIk`4Kbb66nuwGErd@IP2%<#|SFYZzACjr9dtJ zJn%jk7#I;iO>wVH%zpmkVWW{4*iwoqf-iB8x2J-^?qgtNWbCg4KLk{CI8I5HKu$8h zX#96I(CLAIOV^GK=!=s)(C&uf;Nosg);*6d{`!mqZFFqxF@;a0mIk6!mPUFm_RU5` zs+QGjc!8Mv{>OF@EIcfyWHP7JfaPJo>$U!Mn+>Y`r{wEzEc^#_Z~#_TF-PJTTENCg z(G8x7yuAFLZSQF*?HxQ?Sx}MpSz`d)SyY#;j-H;EbGHg6}SMCB|{; zvHY2qT9S1(HqICub0pgY71(5+H*+n!39AXQDs(eOcA)i!-M#S_F>tvUF2AqX$n5NS zkKR8rj&75qppT+JTXGWkSwi(s`u7)MKi=zAjhw|>?98pS*C*j-Ux4LG=^$V1taH8^WOIjFP;kuzIf z^~^uM10v_*aIW;6)1W5HeZ0&nNL&o66&Mu8gC3pml;`;mKd7i!g1J+#<=kupLvw#8 zJL97or$|y#QhqHht$r;~JEIjBH{gwE&f@pUKl$S)zr>)Muz&zQS2}#->)yV;=9!!N zPvJ!>A8%?;B6$rP%8+-5e-CaZ6{X+o`GoHj8P?i8z#)9^ki?701Uw;l2it{ivjrp1 z56SGb_sL*6n+OgJk1o3svOB=A9yvccIBmilz}*^ly4oL(Di)3i>eHX+9vr?=JIT-^GF zTwJfSO`njqU47#QG2L_x8?3!E?=P6X8>l?REYmh&lntC-}9uoLSEth}&PIiQ{@u~?zA zvvUY|S?Mw7@HlrO3n`=&m!k3kt)|M zmR#N>KRIryR_~pw+LQc6LyGGCnmOL0#?M9fzYge#DRV3OCnP5;84;;V%%($xY)7c0 zY@kId}4R+&6)_xqwtOorrMPgWv54kA+^wY&9^ogbpOqBdo3?+t`%2$Y_i&1R;7 z2I%x6VX_kw6H4)VlT)$`6-+C+3KNzC_VH zCYKvUD&BPPR^Y_3f~Y^-o};D+-~w?J^u`?3V4UL8AuwN5Z0GELYbe|&c8I-mW7q8`6ymS@&eTE1t~YA(HWpdHcmN$AxC zvGO?Hc;i&s~;3>dF7d{760z&8j!89@`7HgoeOP-f4|8Nuo1DPQBE6+E~^~# zk9%xsKAB60xmQ$bRXQg19cus^)nrp8Ao=#}*Ss{TNoNYPj>H5}-kVg}8tgTMXk5bk z9Jv;@DXU+<)_EZDr@-dNixmZghw-80=~90CW-Rib2w@S#S1{TKU2BW>X1uouoo~!N zP-5n=87m^VR5l>c>;jldWe43RQgfN@>2q)Q6C|2viP!d*uKql&#w{2eL1+ZXiE8}@ z;yNElTEh&~G&PAYzH(;ecXJFByxJL6CYF7-l`ly2GlPwh!&sJ>BqGW6W~JI|s}t$PGpp!SXBXqk4+6`%{QKK0 zI~^azSwxR=XYQ&*!#<@_*2AFGu!9@8+zg3+00bF>-lxe3`6E2EmIxz{YNhQN_yz=7 znN>z~%IP?9SkOcvayL&x>&COd`4qA`V2SBb+=$F~$`wwp42 z7^Pk5!fAVm_~QT4xjwr=mwJF}lX_+@^I%&WZ1u&I`# z5qexh*8Ieg_mDXA!WIgTds!FTSnBu^=Wn%#`BhDl%%td$COttH5+5;O^R2~?1Y#2< z<~Tfgw{PLIw5A@w0Uw(w@p@A-1CN$a>#kTG>5& zNoi!ga@a!34gle}>l}U(jss@By%5{UH)KDKp*YoGO(fitjmTUMm3+cqSOC5!T-hoS zGbL6PdflNVR>wJ`YE>ff_fQfJ>Du|0PudUCBGW$B)$EK&KAN{jBJKG5QlOpP$T^sF zk9R5^d%UIihRRf|wKz`Q=bKTfm&TBNt-O$}7tmquJc2&NXh?wgQCQ>`-++*E;u=-! ze1ER-G^|l!o~esx$exV%pnQYH-m1wCJg0xP*_LNq52o_-&xx-T%*7Ab<5XW27HUGk zI&#T;iy*TdF;wl}`0{F$5d=lA>RuO3ILg4ebG}Aidtkita(SgXBNW>u3vJV>5O5jjbQq|I8~^KO&M6kY3v_rATPM~=)0Xt!>E#?phIx>-4*YFAu33py`is<%9h>pVhVNU&ZJZ>**3s zcznNfIgAZ@iEb90*DKW&x1V4ynJvz^bwHekJhK{#X>P-_GLM@QrL+NT&w1d4+uJ@M zZ_egQuX2*KJ3d_u+KZVp$#|4XE;b1YSPe*;LEGQyJRH)tS&V>fQ#zrG;}uS`TWh{+ zxpPAKu!|y2B12pT0*V~TTF+rQoaS^aBB;Z@keSGzd%S-fGgT4YT*6&%bS5Nl9$>Nd z%Cqc8HH(fArN!Xb*NkjOxvxb1t*Gd$V_msl?amzzC=DueTmGzpB-g!td(;bUS_b`4 z8k0P?xJ;7V3+(3xbjvqav^gj6EkfT148x@2?PS&`PKiywt&X2x|FPJ@;7;+pARn4M zuED&ooaP3Ehw}2(LuIz^J5OQWkNVId!@-slpOM;_&TTH*{$3|DIvmXB*uxRuJm;F! zO=Oj|GqR!yR@}{Qw6Y(BiR^jSPBcE%&(r)p*)LXVeVxNrd`fHI1glfuP3iAn_VJHr z%giFQoy{V_k_IyW;Nju&7nE^&T#uOI^6^u+?` z%Dif3Vm~TpWF$-`I=f;ECGI#q@%T{N2MLzL*||sC91W|9Z(TKJWS5_VZedQ2s5&-k znICWaT&6G!t@70ML;fd_q6v*67wzPU3(>spWgYj71b#9l-nvsmZ}=Mjd+WS!S4~RH z7FKgj(n`U)q&SyY`Tz9MaUOdjoCJlFo!$MJC23$djy&FiNR&UFX2tj6;3=LDz6^S2 zp-ieU_f|2W^&#|c0#=iA%$o!W~yON$+r|Z;;4+jKy;3-x(>Uyh zYkP}wx+3%KBi$6Hie5wK#hs9Ry2ZB(23)2b9FcPnylQS_a9GX5KgpUi zAlUN`b~jNG?`Lwso*|)CQlfIY0$hH%>W+SN_0Uo?LMkVKUhnNc{aXW91L zckw~h#3A|@+%_Nf9=LM$=#ldkj%o_r`^5!yVg*pM{Yx4xE;DJwY9Sl5}XpJ3r9kUGBQ@kED}maQP-4} zjR^_Md{+ZY*T$dO_Sw{3h0>8RkU&n3H?Kdts0vvq4tVP;e5Rl`D|P&rK#CQ2cmsk$ z+7>n!TrT>ph>%FvZ^o)k{mfcCX3k>Vk9ebRXv1A`{r|lysRz^UxPwlx1tBMXX%SM3 zufUf=vVLvktLUT1Fr@BR+|2geY)t1McA6yY4;1OQkD7)VbL!7L!}eNL=-L(g^^Vkq z#Q<&9i6Yjlzc?Q^pk(ndQz~34dE18B;WJiDy9+VU~GvB8jTz}HM-@>c?4O4xOQqs2kDX1 zAYD^bPQXA>#DRFwuntr}4nmmqFNs&NKUC7C^*!}~O#0Ll4Smi!R*4%y!5gC@S4eWH zeH+KR35hYdeZQ9dY0-$tm+iLr|__3o{{(WH$b`gGQ+fBJq#*;b5IV}UO_4FFL z5`-BM{lW5~3{fx|c1$VyFVronQ`hHU12sDvVEdgC)4g*aIQ`@8@ZXMGl?Ik>47l2U zQ)C!ju-A?4eJW9RtzvT}>V)T;#~ZWm^MUUNT}Do8FsITI$KFfYeilyVvQFIPJ>GrC zKoi_^2Q8M!g(y?Q{Uyp4v<+g)T@Onw1nhm$a>5qb3t5wTyzcwR>T8ETSv_{SyFJ{P zjSV}*Jyv?sq_Ka5lh`hq96|X@ zfOvVGdb=^WsNA9!3}-x>uT2^p7-iJPn$Z{Cc)tTe%17wuLjh<_^D;k{cKZZ)IM)Cb0EOzF%z2hY_P59a%!1wdWj&x}$oQr#7w+>>9 zco$+w4|9pRRq46TIQN9xHJiU!WES}&GE-NZBjNqo$CmvCPgn~EkzjMhDBsF*;)O01 zPqGPar|ibvPRTSS@g2|W{=hYsQujS@HS@=y#GIm&CE2%@3|5Cj6A zTMwoabRtj9^*JBvw!o^_$n$X7p^wi;db|hp98Y4!s3t z2R{3hwXEIEYFZmVzV;`6T7ST83gej3nJFzPy7`bxRrGZ6PlF`+CX5>L=Lq5_%MKrG z0ypaWj>XLG<+VZL-M=OMQuUd-C%WzV*x<$K)`9as-U-Yd`O0%pBxz&ggz`+BaE6TL zJM+&6D#HenM$3hG5IgSPmykU}c_PhA4|ZhA|M-LEl&t8dnVrx6uRp#N!S@NH_B&2$ z_y~za@D;_-mWaudyFMJA19G9kN9gBYe-I}rrHMFB6xKgow4GDi<4p?kl1_H`=+D27 zq=DN=5`62I8~5`wdr22Gz}E2WOpM*}R$eL@5S@_gxV#-c_}8?uvmo^d%_sr7-)H%I zQg$>!*?Z;0lh?+^0#}osT;0=cSLhgAkB*O2an&Mi2Pk z)=FO1J*-NoOFQ3|-G3$+OGCTHbof78daV!YPhw}G|4j7HPao`H%9i>`nw=>R?7w&< zLf_6>?|=#xDn5{F-qm01L_L+AnXWY!8*S_we-gY^sFn{u44}W1BPTOV5d9)JG+wmVG?2c zH~?XtJ6mb+)_KXUV(Y%Tjpt)}L7`dMo+V!|$oHm+(LMQ3un}5ESd-oFxLs;M3N_fPdo0%^X zgmtQYs=bswaNuF3-umM3@UY<{euls+PKGM3v}-pN^mO5&)DV4-wJ|;yBs)!O(x5R$ zNt13G9gSGT|wnv?Zm*qK)tf& zMy-vO5vrA>4^)UgZYWfE9D&G{PYItrA3{pvy{KUHAb;hQVbeAA45MMwIa;wh3doKE zIGn3DAIP%LX9lnsViL|HtTYY~_J#1f24ZC%RDMxyv)lC8rmB59mC@_bjq1fS+GPdg z<=|(Ts9pyL2h+vzi6BU*$W8A}Dk+ZcfB8QMph64&$Kxm1cQ&W#kQwDd{+YG8(%=Sq9M9rWv5hory5RnY_60^a4CHFH z3(P-%b*0t1b?1(QfwS|Pr{RMkHNz%vMEglb$}J{3-Xv3u)TtwZ@fv!1TMjlh-)NFr zL~bgKZ!a|R_0~m`rVngxuD*Hm=3YZ%BVidFJYB$U3hn9W?-usXpG}=@O{vx~RB1H0 z@R|>a)9uyXa4WaU%%Ag@OY!*3rx_*fzCPUpo@M#EG6zwLrX~3jT`$B zIcX)I+L`}*hr;8CW}b%*s}g&?_4=QNO%>=l-mHFmmDms*ynL|cGTovLJdPtQs^;TE z5BbV5s2?bi3BYPp8d%qL+3oZ8ie?f+90{DJJM2Fg_&%V`x(DT|arS6&q55%+AS_SB z6(eg=7CdXZ11qxoNX6i`AOGELdT#Z+BmipW$g(G&Tu;FF;4&KBJ9M;lbovGfi<``p zWb*Y*F~@1WT}TgOc(vsd%q;&a`mtxhN_vC}?PF3A7_w)l>H3J;2;@)A$X~f-*fa(6 znv1e*u@`3)ijS5lO-XmA8DZQxjvi!XqeE64qa-`faWLB9z~pV(HkZ#{#!nkWQKlymH!BSCoYGsOA1>m`Xot1vk1H0(fk{mbn~cyipHgm2^nBftri-|U z@971$L7}%V)M^?w!M|+$L-zJ;d;3ok*Yj=%NP8cQdOeClfq0(4|8Z{ipglvxafQ+QPS0Km z|E8*b65Ig@-a%!Sa(HjWVD^|;V%BD)e8r&52gb#qfZK}I#4~sqFuepFg_aTknf}Jq zPEk?unXuKs4<%Y>VPN()Xo%hn5Y;43LG$`pJh1cD;>mu zWT2+LtrF3ml)b{T@F23(o}E*_Yeed#{D>?2qEloj4< z|Gc)?BC}mTw;Fb__ECTWLdmCkC?=y<7$t&I2!;2MbO1Lr1QO}o2EcCeL9^K93DrZ+ z(@3-4?7Q?iom|Fed@(OE{DeWHMq;C+{pcUW5vj@=>@)r3Gv)}r3H}_%Rhb;jfq}n zq&e*0xYP&QnA=Ty5QFc@4&g^h8x{pjn_#3aDWv+!rR-Duh<|Sf;p09|1hY!a*G3ve zBi{gfT+1W=h%2Ynjvn@BsP(~FF&P$XqURWBF{d!Xnai(&=pI%kN2|2j%>4OiO;e$q zF5)J>C!mFZTkrBjp&LW^J2laDOonWS$R6VMd4Etv*kS^F5D@{h=LcIE?NS5sKCgFx zG`%aZ_$i{-&#aK|##w}aAhv8)L^b%o;zQOP%p?erIY^O!-gjj*v{$l;2$(2a832!q z&upM{Z5d(v=W_GpxqAp2auzd8nXH0K;1zHFyAc7T;1pW&@$q@e6g&eC$PA#&#jjkf z{hpb>n3;baV2VpC6U|d(4K6~5NJ$u`7&G&GnGI2aSUK8Q)SWxR#igY>PA2Ftk{>}E z0W=Tkt(;TM$T^f~ZDC5s;*R zm^p7-SwC4*%7h9l+&6GlKk+OAC;S#P7IS+iOCV9||8BGWvQ#V}2h&_YZ&;d0@zDpD z<|CI!1Ou9_0id*u}uFN+9(5LRzVia$p08*XQw%u;4uX= z@KyVlX9rC1{c;|LDSl`uEHNDTeLPt<$Wjo7p1TT-frN1hTYr9>C}F&(j~3okSXw=_ z%k%J-gy4B|wc@I2!*u)#d7LH9Yo+9v0Mq_S!c94L`TbpD2`PuF-~LW;KCmClZlqGf zz{zH$NcxCPh0(m!$wa+fo*r@D??A0SR$yq^*@H)evC)VH+gW5p?0;^$Yyqs>WU7JR z^1lM{r&J6ED;{bC7{!0z@ZUNh90OBz7u!BM4##V%nVcP9e>9@=xbzdj-&emgz7-5s zwwy}Lk9|<~9zv*{MZ`FFbGiR#U3*9Z;T$=ie-tC`!SSHZ%`&_7hG`b*7ymgeZyg9f zHIIEZhQv|$9Eoe-l|!`7+=C~d%KT@=Mu~9b#MGtSZ!GiALT&Zn$O$opW@j{Ybbj5u z#3KiN+0bz}Uk;$Nnoc=TpmuBOov}XXf~V*tWrjhqYsmHM#2yg2J8*D`4m{Kay@7)l zZ2m)DtR`HSN4jy-Y?@g<#YF;P)8)??-4Bwy55`_c*eV^oXU+AW^|OZ`gD>U1ZGWwi zVhOKzXtw~g$hi1pS)5XF?e!98zIiL!HKf99lPkrZe>U~&C-xEGA3@8jwuZ9b7n0!G@zLS6TP}*|@SOb!@vFwNqZS;X4 zY&y7=U~zt!Ta~%{NNf^1ANC}}D^eQ4SOeN_m4{;JnU^=t+Q$TRnQ8~F#D-cILs^6! z6i(q)>xl2*IkCA+q&O`NUYD53E91PLSPI&5d>(r$OtKyN9v+BW2!z1!au~NpR$nPs zUHBn)r^$BX6?k2(#8sFf@siV4QWQl?vc@Xq=B`k}OK|zcrLvp{&2>{O*=a=EQ4-yZ zi`OnNc36XWQDLXKe@EeP4qjSE_xO7Z=(Dfo2-`as7)$S50_UY=Y0Yg_8+}5ccKRfu zMS--#+CVR6pLJ$AGK|3*& z)}thP`}eByi>zD7dG`$2L(#%*L7tv$6wAZj)oUq#v92PEIFw= z+qFazFEJcbRglyXaUxUU-lZ>@Am)|8FGiMnc+VbIg{umeZYxJWj6aru8JzPRV6^K1d#5;Cw`65i(-&AU{uDw4=x+%0H>w!)%;6uuiJmC~ zldrGK?!}P(=_6u7EQe!0uXi7$T@zrWJT^tBUy2RQVKX*19tjEx^82bu1Y84ty$Mre z^`Kkm57BX-co&)*CAsr@nH(+25@`C~Acm>&t=DF|bl<sNxeEc=i& zjuuI*gL|C6@@9e&XuwS@(rJ^ZEHNYIRbN~jbX!E1PPI*@pNT({?08+e{}N|QvMa1l zjZW&}WGp4-XRPt>5Zit5WM(Mrwj7R7IVc*X2jn@aNut9*nWN~6$LBXT7ZqRLP`EbC zh0)3#&w%V>a|lIR%VDyIsM;6f0kiQ1c*_$9eaFGi5+AY`aCf0a(wP^px-lAFF0dNh z5?@7GynW?RWrokWlFZ&OsMNJB_4%uJ2R2c~e z_Mpe^)p;L@_iljJKei1C_GiU7)I&@r1Cq}EqG|Lz#pJ=)&SZ3Y4=yK6d=uVJ!SOQ zaj05dxC2gjUe&4b<}arEe>b1l4T&Q5E|)Eu-NCmQ{zcSpBB5N|0G) zD=5OCQYZ@-&*r+`jaVs1 zpSQ`q;953SD>%`-Z71nMX1Bf9!0)$PD|`45*e&zJ7sooj9&~u$YgwXx+_G?p6Oj`Y zFwI0smKGd9K}wPxgiXQsnAJW_%go0pjw*l`3&&jyOrIl;bu=abJEfkA=jG-;u5tUe zkkG*TqvImT%OSQouAv>ImO{0C;V3#PJzXno`YTjsh{s^Nfp$EN(g#Mu`*WQh6~jzR z)9Q=xr-gvM&+k(4OSu=?v&+fTH1Fvr63|-kzF{KBu2wIXA!xa|4sa7!Gh$cR0yEs* z!hm=%kC6)M0oe0~P2UYJd{^kG#3bN)^qvz}mo;T<@eZw;JlT^lr+DGA=uD4ojTLsr zI?kl^q2flyA-=>*EobDFexnW~Y=Jx_R@Z{bJGf;pjDMn1)6^_{os*MuE6(*)JW}xO z#p|Lodu^GE=O>s{se|++Y-BznnbaZSMWx!2=F@Vzq?q*{Pvs%&=oJlgVu` zY0qnvVG7HlB_Fb#M=_V*p1<3%JFD>J6(kE{dX{_v%(hGx2Q?xLn>7(}UcKIDAeuB4 z(eT+!Q#rBn_Oa8IXxv*%ij^j_UAyQe#z1(uYeem?dKol5{Cu8=C*g*g+L6_oC|)Y> z1RU=re5VSt95V3|HU85JAV_TM{$01M7&sfpp+Z5j z?sI|6es$6PB>bma>IMoWp7QeL>DgdTU1oBLG~EZ8*|9=C@j!yiXG%Z-!IVS4Q_S0* zm{?Gbb_93*hPwL2Ea*IIX?jhIy3>+XFJOY%7*ug&&|$wTB=z@= zfwMPRl{GV)^ofj&EaXeHH)Cgd4~_(P_G6;SO9Z+>Jr=KOuGzDz^4Qp0Lrc(eofj}h zF?{9U<%$8`l^0BpD^Y4OsBMbz-gUO8`G7G?nKanLBV~af3qd#)rkEKvxby)W&9$z_!xAdIWlL(4ttk)fW<9qz^t%B{7a4b5lqDKs$sIbmf7Tpyp07MG z_E|&!NsIJ`3M4ET+O`V1{yfy}I#*^4h1Biutp*F-iFlB$#iVU4w7xI~n050q^JUA@ zZ?!p#%@U38>e#qV;%)o@3?rFtQ3;zA8^UAC|kx0r=dS= z^`Nusp%8QofJ;t}_bR{}m=baVSRfXP8;n|{R_z`2tO|$xrhWh*zv5W`)i;;&{e}St zYE#t#$gbdX+}sizZkI-or{gW-wbeAnu89(RITNh*O)M@$=ux6Yb2_D^(QEHMqYO+z zBmhDy*VN1wKZ)oQ;sJ%I1|USvZqpYbMvzOJ%8xi|5qEtBl;YxfQ?}ogB6|YJhRKds z_ej6eoIQJ1Q|;!>n>5s%Pjc9(o_Kr*w4f2tI_kj#5-7F1njn8gD1K#Q6UnughyQ|E z`^!Q!rsU1C4plqb{V#h>7#x-YqQzQo%mNA!lN$oy&i-y=7l4mp1343)&P$DfmQ5RZ zbSQ1=jaV5#)f%?9R%M9b&;&kmp^46L$h3%YXygegu+zMb9p2BN!wwLo?A#wd9z}4K zT(4Zc8o20N1(3vZQm!k22%kXeQy~qhH`U}?N;YOo6npPA4XvP3N0?OX^-zw6vwcMi z041!4nygg^-r(ZxDgEt8z!Y~*p4dcOOY#LTv9G8+D-Ktm<@|i)`ncr#PM+9uF@{|P zk^o(sYnZ@jY)MhLB~YN?h~!Qot3f%+E1OP)5{g3=s?2ye--3`3mrFm9vbELDu4^y6-uSyisuKH=AX)-MVcX zc@n&CH)1AY=%FUW#&P6pgo-GJfc~C&GS8zs*`X<8W(*K;;V;6Zd$>BEFNeQK;@l8T z`-4Zr+CTbj$2dlcG#2t0Um$6 z@LasKP3FVq;QQC+ONBDE1^VrHf7cwc$B5>9C4&EBJe{=^qq0zZsNctu>73vR-mk=+ zPXhDmZLPIMQs^x{C^RNlngdQV;7X1MPMR1_2d_ zV^kmW85%ABN2{dw8cRVCJJ%59^zN&rDpgRD^EeYh(a(W3&?rkT)zI5 zJ677g_!jE4%fun3e7*eg?{5JqjEtqg7-K5zog5(+!R&hL{x<=5_Lm56Jr$#4TQ8ot z9vdBAxc)U`Z2Xy(qX+&e?8LGgTHJ6x#z&qkPDLdS1JKjX@l%>@AuBSC$nYM_=dA$U z*KGG%zr+6Pl7^PO`z&ASd{tb9V)F9mx#B5a!mAg|(o-q=7fdHIB|7p|l$T!f#Ut%M z(Xo0)5}dzLo)J5ZRQf#8S{7l(MjC zSAxp?>ymtjG*d0DSh}}0Z19Lll+p?J4la#kiDKw#GV-GklF7|QpjrCGy&dHjGq;Ku zDmB%8anRk|#@wlnt=NwcZx_0lb9FQ4QW&HeT>76`l}}C|9Dvt866SAjoa5n9wJsV? z8vm&uW3OIz%8*%VmACzxo+ch+u5}bsmR0hKh{Yy|wTVx!zds6I6B!{M;IbWBr`-KO zA}+-7P8~|4(_J*GP5M}*C;9LyrT=bFjsOt=OssMkEtM62@Xk~#?B4r+eEJlN>xA+l zhq|0{Syg@8v}NBZi6azg{*+7zB4)o2Ag|9I9?^;A8F@$ZwtAtInLkS8jc3hf;d^RO zmct;do#ei9Cb_8zbto^L{b??*bry6iv1-vH(ev5*M?SKx4tiF^yRURNGaPd{G1=B- zjmrLTM&1a^|ie$4jnfaAdu0S5qm`xBkb!yNF^H>^xSs; z6x=;5%;HY_0w0cN=XKFUC$y^erq8vq&%t_a*W0~#BdT8*oad}I!?`Jb~SUU3^S@lDD%}+i-Ek|>&->eWF0-d z*$%H0P>(^UFjq2HE}ZsNFry_ax)n5P;9`4yFmEw7U6Iul0_+(rYrA~KSfa1U#a$`7 zaP`BoL1qfvI8xKAdoVLUh=msLz|61z@f(Qj zlK?7q&}(OKRoI8?8Cn7mOhV*Imn8Qe-|CP|(NF^*F=n*1b!7}&1M*2aop0Zr5h9*A z??*GS#}$e}+Qn_9+XSgaP4yBkvXe8!LtbSux5FX2f_G?(w&B^OZRo(i7x_lg>b^zs z_{ozH?sMmYj>i@2;!mB+05Mx3Pf^lyW4!N*9bm6FGcuSr1W<%(I^~JA!Iy&{h;=?FQ@s|B-nD)y;8SSexDo>Oy!g50C0r8T)^^R0$K!dNk{Nq+iUv&5Weim`p& zgk{Oh8RlBEqA=e>3_;~h_ddl5BLg;Tk6U3c_F6DR+sGS^0VxgTKPEaRiJ&0Lxbz-;;FKg)BT6jaG+`I3@^9zn`dB*0K<;t zam<&3P-7?hvQyGjvz?Su5C6!x3fCcr?WRHh zw>QQ@LiTQBPc-5aI`YF5oRCV{+VB4Ky%qf>JuUGFDEu*ri(Ll$h@}hD?+4*>Po_yo zWR9>F(=8>s&PEXJ)FQo&)ipOH7d6$zFwtT1v=Hd@!Re56^w=@pH<_8!k2@6Wlcu#q z`&(O|F9-FLr{!mdNv~s_CtuC_;Q0=LYsw3XJCMZ|dlHGwL~r1=t;9-RIrTeev?brE z$TY>JeiE1e%=!)W(B;bq?}a|Q7Ga?fanHnzp*+8~b&dyY#2R4B{$h-XCspdQ73)Nb zL+P^CYj*(h%(OwA)io%1R|ZKy9(0u;-uvcg#6OXgTb3$XVUokj_up6^h_ew#x&o%f z$L_nr`_4#{)@RRZW*ip(zXMuX6*RP6%ljn{){>`56|S|vg-BR;ktN%sINn|JmqN;P zMeSKR9LUNv+u47Iuzak0II!z+C;zX3pufF!E@LU3k~_A;z5!WgMmF-6{y52piT#wI ztP@rJcIUhMpq|fh@bNL)*Bb1sd~;azWDAHI zukjjxv(6EA#zg~RWo2c~$B!R>bpQ5JS>AwiX-?tl@n}~tGpJjCPQ#xkobJNc5O4fAieUuLR5{;^nrmzSu#}NS)R(GGtKwZ{)tKUPa2o0<0)QK zr1itQV^|1lHj96@d=;2jxuoK!zROSfXM1Aa(8?lYW}s}t*M;6#Dl#{NFrDhcq^&Be z3KO7GCF1cn7buH!)$>tiZ%i)mM5WyPH+w@m{qL|aGxrytIMTR~G3~kHRLWXS<<97v zAA_xnT?#Xw1y7wpsIE~KOVFWq0p_j*gDyj9njQ7Nd`Ppb9Yr|7!bSeqsXdmXOV?{a zrJmDtFY_PDTm1eFmSW8`PgyKT`wJib_jS8MtQqSuHDmOyrGRAUwr~2aG>;W9W*o#p z=lGj)LwTR#7(Ame+vZ7F{K#^#+bC)Q`cpB8Skm_uy@5=(3?DT7pmRbs4yuuTpI?`-5~sp4R2W(xwTc=mlS5v%z<;rn_M>x_fPTtR^JvypQ|steb_iTuqH z#XJj!sg;$seXTeDo%HM-+cw9&bf*8%cJ@d$CG=Vv5BXh@B;Fw^4f(Ir;O}Uc^ULj= z>qJ3Dcm`2BXJps6{`cleH@7-5?a!UQ;NJJv9F{k8+({$fa3Y7^F$S(sLJ`<&Db5JQ zMu`va(S8R=N2KR-oFB^;)iYAi-)DF8zVH%Fz6$=Dx$tAR`VF@l{P0WX8`w-RMG*4V zeKsBXt)IAoN#Bc>$$NtY3+>A%iR~qdlg0wE!>1l=5hn>G+e%!Yz@#n%Q961!Gag&Z!BE~~LTiXIIwlCC}{hHc>3Z21cM&P%`k zrSoVUMJ2nLDk3pZH?lC^M26)?`!Uxe=f|Jw17z3vq>$-EKIDGlUPj14<2ee&;Iy*n zKtFNy`5HImn}lsDM}bye#>C(C3o}`#M&U=TUS>+Aqa-NC6G70r#oI%;H8*qYoNT}( zwa0?+zHlidsL{VNKB5@3|V)sCMA}Tx({&ZM)=Zygt$B&kl zvC&Qea!SwZ_s+9%Nj)4vE`^G(X{|LT!md+-Cr`SQb^B28&z>{AeLRdDBb zVL7F*lPIM8&@weTB--LP2~ze+G0e14Ckfs7O~3OGVeSF+bm_YeaaapnJHJ!kmk8vk z>F8E+{jxMbnMjqzcBY|vDs;0B$AGcHU(}ODi2y1t*&ODum1RHsuo*IedWn9S92R}Uy(B3s+s+Q zYW#cQtlLVqO#CS~hN-tzQ|%mX3pJAHj_X&HMYcV%o`u=oPYJmr*p(A6%Bef8oH zAE&PSeXpQZIE*&smv8u0l1y49d*1!oFBJzJEor1KeD~Vo&&oWX?F4xJJj<#WK=>X7 zc+7;i+Ctj!sxRT1mFt1x#7;qUQEJD*yxDr`M0i>j&>WKt-QUNn@JMBxpw$8+f(Q#y4(xL$I&mS}n6(8-H zSP&kcMl@8;^Kq}FAh#_?>ApEHWw#rQxt!!RuMhY1_ImNm?)`G4n(avmL;Wf{ zK~C?B0hWnjp&gFp&^th7`nh9Q8K*_%U5`FuLxQhJC7txx(m5>D{T;)4{+ryYR`|Zd zu&3PNuS&-CcheZuj`)_aRwrfWQ;gB@E@|#aMl!@I7B*kgqtVa&xcTTt+aW_DfiY2? z91_0_8vOU%o55qki!p;y-baO%Zyl#aFAC>Gsn^Of+h(!TjQyIivmyrSzcLgj6DKQ^ zXcm8!>^F66(9h0o96*b}gi;`}HL zHJT%iR;a?55^eh)&K;K~n?gnfrZx_!-Y38y)7#}roZ#ahLc0fJ5kP)T4tPI z?c>;CxiC7>kr1Q--{%P?k?f@HqdTv-uPBHWP>hBd@A%H;`(=$Ock2*I(E85erd;~- zSd=@TX8RQ}lcIPHl#j|KM3HNi;%)TV%)R+O*GhvK#OyboTHu)jYvv z^Fa~crrnr$sn#^*cfXH2AO~5~S3$hrQi2%#2hvg&Jo-e;YDFnuz7d-ulUR!trP!ie zT#L4f95U_nLCLV8NG=Ac^5qQG*uvzMI>Corax)i0ervL=RI1fPs4K(;Z*gComoL)E zgz|>guktDNomNJs>QFMy8{6u4T17dp{>-q&Yp+)jea3=dW2o3r+arMZW*WIKOxRAH zFbgXUmfT{Aewy=iyP~E3pl>MX3csb+VcjzOM;Kn-mE)67)xyu6%KN)S$V`T#o;WFN zt-4u1&-Gjpiyq*jEcnd%n{}TcAW!U3R2}{}Sn_e(d#m$)o#WqOMN+s)ok<~5`toTj z>Mq`@&YEFl;{oS+aB|wA1V^uwS7KC;#dc46FzXc^N6K_!RQf-@Ia+y~@BL$xQ$PHC zKZ;KQ>{K~q;r)vJq>hPHWBYVf)m-&ZQCkmsg3c&A@hZ2R;3keu_7ak^A;U$Gkn01J zwO?mV>{V}Ule`f($ghjCOZ@t@wJ0$08-mdJ% zxaVY9qu&G>$*&j9DY(+pztl(J&tw@;9>dDt@R>jN`e6`Fs9v#gTk2H$8ojNaGI>SV zGS+ygj|a;W8y1Vi>Y;BQw=$>3iS?Tc+79U*^TKFe1Pa&xHPhsghVZ}RQ9m1$+s;8ie7*B%Vo%Co}Uh3hP(=Q zE#P|3_g?3vMe(NIuxU)L%Gi_ddbgq>N0W}SN&I2(wCP6OtGfmxA!)StDuOGf6DQ*z z$fjMp(+$caiMZE(XiB;gXwFW*DL-GqeIk=JXUb1eBtww*oK{53NwkHrxA5|WIT8m} zg}3P4Ljp#iRh2%X6k#Rbh*#WmSk-u(t!GQQ3Wedlupx6`>YJ_pl$lTD!lDyWP<)L^ zDvJ56LZRyliGEXmqg$sZbTP5r+0;=)?3qO?zBF6StU?kVSxGa??O23%a5Bdlm~QH# zVWAS5Tfp|@`{r&v>8$YZmpQ>jok$6IRl=&aP)m{SeD(LB_Ck^tzpp4+bhDd|DP-rA z6+zmM+eSq%Tq@P#F3x-JmUcuhZuU9xp!bp_()N!)AS%#HS!qpA{of1dsjt`WQ4dC4 zEb`MdKWSo6TYd4t$(Ch~FZ*C>AX7zH6_1Z!^_k9}eF{AADUZqKgV3gG#0Q$@s$9P> zKPB#`&xI`RJoaqQN9ILcM$<;UT3eJi(|tx<7Dx3Y&xM!d5yqBfg6@$CshOk@Fw_GP z2{S>D{_9uGkid{Qd{tg(DcbI&1PUc;(SoEc`F}t4=eyq(16N!jZWfKIp)0P97oHaX zV^MV~3WU&!L(9DLI;?_;<^V7EzuEa=O$BD)Ip!ba@pB}h6Y+zi!LR=Ikm{M%=v=Ag zkXya)vplIkO@jXJCJ*ZsaslfR$)z2k8VjWz>2;%k|Id0X@*RA`dLW*fDPCK+M2R!x zTMqEh7DI=l$bxsx@69g9rr+)@jQ>XhRArAyR14hBkJg#gtq`#aSfeC1aE2U3Hkv}P zi`jw@d1sFGUu?Cf^86p02<;}O8;de8a{{us+paLJ zOIUH`acguiK&!D|Xo5sN<=@j()WgnvgB5l6sKXFer5|MkSDfwUihKnHyVOio+rcGr zz)!ygKL}5uN~-w%M7|XS6gfXXU-xi~^z{j~xxI-Eu}>)7qQ@6%B8q~9jyh&WeB6i4*9~4{$>Mz{xT@1G_bEvbsZqpPy zH01L1pu!^=aTFo)3A4)vJ;JBQBUQC2GZ=&P@neYKq4}C=Pwj_W#zcN}kt{L05>8c3 zJXVm+aHf1PMtpihl3x5g&1Od-F$goi0&{KRly{*W9G7vMWMCe*Ys+-od5N&F32^|e zzyajguH=mt=uphz&^emA;@bJL@i~SN;+IgPmNKZw2zGw^8^tsW?F79@wNR_%X@my( zJyz*D@HQc=YEhYAZGvwJb?p6$Yw;--{5b*!9hizGwGCFc8y7wwAa;#`65NM^7=*hn z;g3@QNOg5f)Lsd2SE?_F-wY3uq^J(EuJ6WJczKVl8;xJt+@{&VQDGNJrWBHoug!(h z&|d5X11fl8D70JAhumcqa7wJRLx3>B7Y6d2#Lm}Z$`gSk&}%V48<2y)RU-yZQXA@buGgt7!Whbv`Q?|ypD!{W0!k`}{m&~~%=3yI%uuEsn^E~>6+ zrw@|AFD5G5tVD$uTStMAnFY4anYw}j^5bS?+^p^QBMCjs0}rzOL{6P^FVm?ne^qTh ztg`1NX$3#a%&v17&wdewg8kIi#er3wc$6!0M6oDly{@IDrCiiwPZt7gavcw5M4Zu? z+E`x~qK>L32_47jh*xArA5H=FBOWAz6-UhEm*sC1Jh9SQ*Z$2)BLWZ(j^(MxxP z_?PPDLPeBqTIrwR)C1P1{R&!RL{c3O_S--mbQJQ{rNS%BfqJ(#=no7J+ts;leK%P3 zTi{dSWqpQ|L5YT}It{5u{mKZs#JXn;j0JCN!>Y{VPb|4qs>`P!GO>#w2;z*2zDMm; z214xgeLXFkTJ(n4#jgi9lnS~)R-S-f8eAc~wbg!uI>9Fjik&vPe6~Q#$Y|m37h%sxu+Hv&KtufcMIehxEKOW5l^QFicS#Tl(HZ5jP{*Y!r_XO&-6Zq%&R5&-8h%^^d?BEHFff(#J(Hbn2f|*i- z7+k5Uv*pZHMpy;6KMZWkaFN%Q+NU6c?tD&4UZ(K6R=%lx)ZlNT^Hr1%Zxc?n)^C+3 zS`a%-Ks<^wOLCwBz*cBeG1>C1M5ODdyb(cG6Ucd*nT38 zS{$alVz2XY2C?mRyK}qo@$vNEDqGTtn=Q)>D($X^ zKA3Dc>`?4u@84!7oyRiQ+2KNc>86gEYF{-V{1MyNF_ZF{=@9}xm2h;e91vxxTV~H& zl7wPK#vyQ208;q8^`z0%0{AgC?f3Z{GU1096nOJixT#^cb}HBw?$2{|hU_aDcV2^4 z2Do+IsPpIwx5o&@^z2E6cQJ(hIp90QfRQ$m9R^t{*K6+8*4E}h+~dg8v@1K! z(5bT(HryDDA7L_g;Krg=+v7AU6Qx;Aa};8$Kw@>@nM_4=Ev%vd)I}@Fgyf0WaSAe>>?2!oe0y{^-Kr55YBZkU-cnO~N>2f$y%Vv{| zy4B`h4jRMi&>|DC<z~6S=x=yMdX^VV)KgWH-OaJw|WdG^S2|a8!Xy@BF7-@pA!@7+40b7aF7v?kaoD8 zQHuheV!XGHI29}IMv7p3`4BXv5qUD{fx{qDY02%a>E)4Pp@g9zB3xpn)tmH1-+pY$ z1}7UPo9lRd{fMRe1!GwTbR=;K1#kBOqH_VKl|#Kd$WN$|44>*GZ0LoD%lb+(7njOw z!qcnlu8*>3<_9*X2bpZjPJujr?pzPE1)`d{(6ll0p@{MHvBfJjkvuJ+z#Du<+85ghvBX+M2Dcc2jPt~&tMem|97#cqt}P;gl%N)n zl+3fn5Z`#8z8nN!aJOpiUTGx77MdX^=;-~LJjnTSfEMJ>yejb-q>CtJJ(7+k<$nw1 zWW+C5aI7H>)HOa1B%3Gvah42Pe^DV^WiqTbH*_M7QqC+SbIQBP4jvpKG~El?;ol3}umY0Ij%ybE zDpC_N{jE&am{RyJ+=pDH;1DDmHUSps;!`25^lb@gg4a7Z)Ef7E43Hh?Q(;Epm$hl- z1tMiX5XHm2cR9FIqfgzcRZ;|oi?u2^a()4bO-DTTi zZg4yDcw|%*WoGN_UM%kEN3)w{LXc+aTsB7-UexEKR$V{ z(8{YU0j!MACK_Rt>|aAD?GEU9Oh`L?g4uWli6z*wAYqf}*0~uJ4m+$oWSW z_p!UU7@r&{&+t2>rh| zt4dMECT;`x(vg+$m0>iAsr_MBSD^JoS#(GH1l)_g-7tg?H?bU94Z0GX-)h+42nuP^ z=!IsKRsEbX&a9aT)%BYZVtAq~zF;kvnci)Lrx^PJ}|f}l@6V8wat&iybN_(UH;FmC8k zGbaJQAFe8W^dbu6&PndU5cLDHWC5>hk=WqWSUE8o&w5v%WtB{c^oy@704J6eX3=Y(SRncU$W8atd7O`R{9vrG-b6n z9YQRG80_Hy4s-i?_J90_o#6*O6M(0 z3eTe{fmD1RCgV~=5*jDz5IE)i)eipYm5>rmdj{cSRfAG!@~Zz-I~5^@II$nj<9)3F z2Ox%I5V5}b&9=oop0AQ3_oGBBkuvZ+VV~5?%j@SSdZo6gsx^; z@cNYx0~*fvairuxQ;)vlOO+JLe~R2rP?|Gq>>)Q|cTjX*1h>DI(^P!Ru?c|ivh+}~ zFN1_!D#x!ue)9q~HEc@$H^s5^Bv=Ai$cT$Jld`a?TsgNp{Ku+FOygf0a0-?Hp*7#MNV%v?Kv~t+Ykyn7s@D5@jfp4tHu~BL%xbdj;73U0 z#1F)i9)pfHH33QP5r*?+Wy|8AMTZ(2?2|Le`*%S?U0cQmf+oApU0f7eih9iO{h3OW z{S8>6QUi6OgU3*R|3NukOHWm)kMTl*t=61ZcQxl9pgWTV6M(Vd$_*UCfo9s{!hyUZ zKxz~EOdZ;_QvEz@EMi$oGHMl>SvtN+8PAZ{R&PFy?UV& zR>y?v;hJ@UMkE!?d8r~3&F;G*LRZrlM|EoEQwd;6MdmM!5V`i3QC6EQkMf|pWh+CL zWwrj_>vpB%`XUOq7)}#6YRme2(q?4KuVQg)HbZ2xwiZK)o~bSYHcjwJo-^NSP+<%I z`BwHGu`tHh7Qb)T08iXv#UoOMSv+U9csx-BBxA~ml0#V-g;Rz`Ywpo>JSc^8w&TE^>7@Xfe0{&~$ zV%&paVHjdWLd=|JYA9D}B>z$htH8wj!jbkLmLfaCn_1g7P`7&>(GZMW$s=VhS#~M| zuS;tL(If(hD2EN!R9%Q9Z?82UFO7cX|4EWMdm5*UtCuye{8Ndri;IhnT$>tz+W`g@ zcufAnW}&SH{TFsuKjmX~{yIB&^pO6MTG|r#1#+&GH(D-4i2XEI%?-)0XjXTgCI>OE zd|L;Ui&DaNq?88jj2)lmS=DCPV6l!YsF_<&V#Y}4N4cAcuh_=1gxcCT!&GPfpF z(3k;;cpSv5y9_+f_CX!2lw(MNll;()NE$_d&-29OckDvWBI4=3ViA*gK;O0)yiIc+ z49#}x?x_>nvp$PS`gHLFl6g%!N+ zRTHf@x5_JjO}M!JXn!XC;IrF6qA%N3J7j)a|<1t(!hhv*pCb& z&9pzI2t^1|DcIZsWfOVmNo@bf$R0E4d6lVGjzpHYw#6n z9U*e~FggStuN5zP1z1HCk5gvLSJ>Iej-KqTWn;zfoWd8|(o1`bK-Btiq=XF9uLr8@sBqZ2OvgJ@NqnNUo`==+X8!Fr@~dt0K{5ls|OU5O}?o zzmDmg=PIU@i!J&=lRN!nwHiY7IMV1 zWg_&fjfN28WziH(;#8T=bcJ?xK2$&6IUnxq;u7<=$#v^!wQkcR(v#xNd;($-Ypf!G zjy)6bXck{yu2;!58ko*TtN{fgtm|1&>Hu1{wW?1}<=Pf|5iL7^mDypZRS_jCz060* z`qABsJ#3z}CPD5TWRpc%OP(tAHb=r*Pq#8s)xHTOU~zi127^1vc$Jzd0{|iDX+Qp~ z17MC4t&%ro?(1|R-weO{QQ;kI&j#3PCx|U!zApvJ9ae8zz1^4@H6cQ`(Pr95PqhF< zoIm+A-dVOPquLgpzG9d30Wd9X(8ct^rYRuGBQ}fh)8Hy25=o{!h-FzowVe)!^rp-M z8!4(nQ>&QkwXnXQ^xqb@i#tun#a%8Id3dy5Q^^CSC5 zIAp?=4(Mj$A5&9{b8(n<#qg)R<{v-6RX!pvl~*W}M6Y{ux_LRQKOMeZ68(r-KyZ7T z+u$fdf`tQ^&*z1G`UQZUavG;W_3VIKt&{fnRSaa{D%gmR)$QWLTn|O%k|n%6A+J@b z;ybrQ9%q$?RFj$fj(WbpLmc;+dJxTw(U!$H?j=#)vkz=>v<2x}O_eU`v4$b`7wK zFY5gHJ$%Ec8^NC^1s58e)^-8;&smc6O65V7Gg)Ab31(iBABbiwG?T!#!&aaYcGxG8 zs}~$`1T=edwIy8u5^DJ*O&^`=&d4!KBl-g(X$L>+c|lIK-R1bDbE`jYeZ|qULY;|l zXUA6gwj&CVRWW;PspA}1q(wY<)23{Cf4=cJ7N{>SWI>ze$%lz_n_P>Oo%IZv*(am; z4FRz-Bv_Z$-i_4l27laH`JiF_NKRG$_QD$=&WkOK+~RK)MPriOJAsuEFf{doZuUt4 zjsy6bM-)v(!{G<4u3sh4j|5pkVmhm$U_DoxDZQdmKg5 zOjK2)k*DZ6fKOfXCfP_|FrJRt!tEI=OuiX9T2kS8 zs_&&HCQbuItG+LOqTbwCCec6*Q`-PMY}F_(DClvYrFyOPcT_loYj!74V3Rab3ezkMd7byu183@9N5 zS?FN{cw6z($OB-5=H})bb{wg(q!=+ zrc{?F&To4ippyB{3ZQSyML%mMn-T&vY4~Z$^O|wprm!0rLMqW#r_p2b4l{Oyd9g{lgQUjaI;^R z(|2UsshI-ua~qwvB*3C@%}q_;+OtpAv%!uS!rcU-&;%E2?Q|3$zo>sMcRTPw?DC-A z;lvDJO|>@3@$p26RHv0@%&&wNn%s6;Z6*s3b9|Sf-zk7HE?)wtfxe{-$pl}sb=i{J z=;l*cRqtWkLpeK>?}7CLOTbxqd0iU8#aUC{<#urWC{>`!mXQ<}w}SOy46n_(SP~4WwPx2;+(nWa z=!$nm8)W4{iAaV0$K0V%;1ixMC^X&{ka5ry|l+=_k*PDmIR zGE_f0tny#%9P^8EH#1ko} z7v~Wob@OFnK#EK~8AR*96iqymWhX6QIJG$sMcyPhi?C_)v;+M3{<8% zjhgb#0T*)zK8J$wX?%=!-;|wh#nnm$e>3a?N`keyHVTD!IANn0Kq-2_A7If-BDAz7 zg(u@B`9cNbid!|A|bprOI+W0fkza`lBf41fL|TV~9udly?X~d0Vr`02Bh1g6<F;*Ma)cTS~q8=m#8Sy;9R+30vo^!a`jBVH-sVb$n|c82{B>Su>WEV5&cl)1dj@ z!<;+jt*PcZ{PBG>Rsp?hTpZk)G#q++p#Ln#M@^q8FYOhAY&4WvO^7{5FZZrkx0lu+ zG}qt#gr?T8pn;WCwP4TXBl~fs6ks1EuPgNZWC54Z7zcBfb-%E=T>(VO!I}Tl@&uU) z9|IW*25afd1fl|w2B_>+=*E;T=GE$Ns*sRyJ3}PC&O&ys7w~C#npE^LH{8awKVElO zko4{<7QwSs>DohUMMc!*SO^7Qu2cc7$336`j^FZ|OfN-bDz-GQS&jUDmI1|EjIQ_P34Bp!cVq$$|#>%2)9AoSv=EU$X#^b6vGMHW;hq(}}H={H^$B!;i-1t4fzl zfLvt1Uh}Ns1Nu`Kz=&#+$280cj)6e@!xyN*waX#(6BW7bOf66lL^f-ze{l97YB%Xd z>bGN#eTO)JQ?P-5^dm2|esb$rE~kIvkf-V3tp~V++8&K9(Y^os)4<51&rO9#GVIbP z^^dO;1p~tt0$`=(JWm~~ulFTD>2b+E_I6g<}46hnWF!({;j_-k`4nd?Vr$@&-?_j-1k<@I7Xx{yR#wBUp|YMT2_g zAZ9~Wu-Lw-X_fBF%K96}yxIiLo052N1`un9fr{^CE*;yKN#qW^JWX{Q_R)={jlNo- z#W>z9J1U-lObKuud;!iAMHku0VE=KzQx-lEYa#twPN1C2ghHO-gi!*i8S|rcgpSLJ zeI7J&-G)vp$+C=irp~Xez7;?ZD^u)>MFcfdD)Hc>o&G*}& zBVt$;1nT(0GmZr)%;k;1z21rA zFjE8kQqP>y*6YC!aUS!II#UB?zj=a^kYU*K-$|Wk*L2Tu#(`8O3x#vKIV3LYattTN zMLP?(hiq2$Z!kG;d6~B69)(T-rA24iZLR^Dz63+v5uJBrUt;AM#6KVC$?Pl`e~U69 z3!QK>bb5uM86qVsq_-N@{?QUMMjCLhe;fCpdIB`T&A6g;4>|bDA81HLq!pXTrT~!d zi3k*W93f3oGREi`d7&D0WMhM7kvyGO?4Zx{V~vG-pT@(d8*`#?9p&FDeZg%MbE%3{ zbw#pmbnpRzUkP{%;{+;GOpKFTF;Ukm8&VN)3|0~oIb{Inu2O2eaY@nhqA0CH9Z_nPQ&FHpJV?mOB* zU?DtCL`&yt)4dB|K*FC7aR?R4fupWpIq(1HQ7@5A!CfM5+ml#fU8g*}yqxNaQL(J8 zwNnwmP)%}9K5P@_^9qP{xjI7Z->RWKvB#f8rUK;MvL|yBUbg0zAESbr-n>_hK70mH zb+n#gCUuR6nHt69zK4GBzb-LIgNKFEjEWd^sc{aBtW=w6^K1$KS^aoe`!kc`xSw!^ z+I%>6yVE1OQVQJ6nCtz|^H)E7Kin{OI3~v+W8@|QS0LQM6A1f{u^}d^SO8^k1IULX z5W=ICICT{dq#045O;nez`EXm~#|rh1kP&T$=e}dug&Rve-VlZ-w$Cc}1VA|^2*omR zU?fQEf6#o8 z0!EJNB@%b4>LrIU(tnuBzut$VR9z8+7YM1MDYJ`5=#r_+cEvScw$=Y z)k9eDCs_7@E_p}p<^{$8gIw1Q$N2NEp%dsR8+%OZ=!iQAHAn|8^v_blav#JB40K#1 zlV=duKSWZgppU@InmyXb3WSA6fOJZ3o>Ni&u`l64dtk_SK~U1l{i_wyhv=i=16;De zkN6n*LB1DnfRncEiU_14-Vp#3I_(llZz4!l8I=;Q^Q3yvm65(O21Zt%mwNQ2C;#7 z5!OL(f8A|X@EY4ZY@J&HGN_)YcknWQSonscankbwa#L@r?`nUW?H1ZNRS zwcm?AD8)4NIB$O%E=s-^j%Y>yl}Jh)bo8tUN2=U)hB#0xX8rkk0Z1S8m2I{38u8cf zyK~Y&F%a3py}!qP;u{4qQVco;L!WLJGo-+F(9PRuzvJ8TXPy$RtOnJ7b58LywrzWw zG!nQfK`aa%=Y=d&D`I*Wnwe5xBuBrN%0D^-f21s?8T2+q`n4Kr2JR|m09~$f27S2+ zkpDX<=$BsTlxanei2H*?>6ZxQ;hxtR#0cE9g+!xx&JV^3vDSmNmx7@YNHm@5X*|`h5zPex;dOV zRs<1PGp)@~=?`ZB41g&`N;$)VL^TmxkbFOW$nnY(L=K94DKC^x@W)D;%t4PqPmq!f zy0rlzDT)(%Ry~X@0s`VSI;;e$jdZU9D?|q-H`@Mk>_W7lY>81|V)Mn=^%@CKh*SfOJ?<#G zGc;uV^N~D^`7Kph5kX_6wx#&NUTi=d&S(d21XVzKz?9}Vf6@2{ z)Atid3llyp{HmYJ{)|OXoy@{>0bqfYcv0XZMZD!597>A6qS}RCX8*qOGvVEHdllVl z!1PBx`2e$ez)mMm3>Bb@x3KCQDHe_}C$zNv09|8Z-n zFUTbL@!?S(z+;2d9n)#f%ZKHEZIl}V1Rv1OLde{7Pkc#RFj`M=`9zvGiXLo;AO zSOu>NI9ZzMfdtr$>goF*DCWP=VGnV`m;kB><1j@ z5*K>q{xrD1?E6oxt5fYh%)@#S10nku=jWEj->#+JQ2^Wy2mzG>DJ!m}V1TFo_X+=$ zTA{+ja@9z=hN@OUMRxZAiPTaM{ zw{MtE@jn*yWdV{;0XeZvHGo7|dUpT&o`2md=p!MZdg(dQItO|96SuDxU2+$$vlT?H znt+GB*Ep8?9~aA%dWP7BQNSqXOB}u9g#oFxC+=g;@68wW_$@V>qm$zw9GWD)U+v7# zLV*fkxa^;4fBElUlK$rj=+G}1Qt$kKD4vL1sn1K^k)8;z&C@yM-r29Y0hhh<8+`JR zS^xVzKtP!+7{IIkR#%$y&I@MT?(&0HGI(C8N z{mFCX^aHAdkS8X`z1W5AoBF>zl?8RZcG)f43}C)&W&DucSJ+`S1HD6nlHa=J_rKY2 zwgyW2-#=>JeM6kqeAe+5zAqmve(ty5PdcV1kIHRTOgIP`{@YLd5;>pyi+QG(P zJJ;D68TWqFEEw?Wqga*HxEx^Tq`HLbFJ{~`q^F&bv_Y&*U_Vu6a`cgs$VFDFO6+Cf zzq^hEIg5X~(vW}j0jAi_Ze5^^|LMX1^ogJvLWQ?N;%k>LN!-?m3N>;VRDZiLoLMz- zzVUCxI$rW7a&w21kG9{G6C8QNvaY9O*8GxJmZ$70y(Z*RU9AHqi(kXhizIzLIHG@f zmby@C>-(NDw+Q$=Egh9~SM+{1HzMV;hK7tQia~s~6Z8UescR$Hp_i36qldfiR3-um zN4E9K$GCee=$DtXftY}mdDcj?-^`DsvlH3KHV4F!CPONUrp-5ubcuBVcLS(G_n%6} zeD9GCyNctJPA-su*#}XEb|GSNQOd;j3P#FiV%$Z3M4!o$n9r)>m{Di;k(2>%qoxhM z;E?029TsusD4i3e?nb2GackfJSn%j_;PYRB`M=CdY7T>rF7<9VF=H%eg1UdGzq_8Fl8#uFzwR#ZfU&ARz{U03e&u8f_# z4j+S3nF(|D)Kd>E%6G*1s!WL(9nq^u>E)et_CU zU>6Wx_BQEKXwK>rZ}91f4}5lX)D^F@fsvWGNyYy zTJTO^Ej{b}2@AvOI<1dncE!=}xLe(!{3g^w+oCR36&2^v%4JF z571smroA{=+{EiW;bDS5Q2O7fg!ADd8BQ|tY}mH}7drD_a9ho=P_RjV&aeG81o!oxzNv^RVsx$+>gYuXH3TK$XZA8^kzqud~3q{*^2Tzq2uA0I6De$%j-VMr@`|3 z&Ef&F9zctXU`Yh8KODav^Jdbtd#zf+(K2a5_3Z) zsyF>Y>t@4ls$A6Ef#O>uuEU|6>JrbDv@YL4vdned z;~5@&pYJt-PD4)O$6Z^b4s5Or=8^inlAesc3jtxg8f&Mtdn``td;o=_{2wL(uqlSv zSjVfuh%4i7EyAAbMO#9Z9_>k31mez34USid8Pl2Y$Ed~?t>@q5&z@p6pW(OgtZBu7>e^>>#c7S^@}%ud&1Uv{6lWr%I!?6Wgr^Ub$uI)W}On$en z_MJ+f1@X+udkb+QB2^`m7LCzY`l%7riKp^8y((PiIcAUMw7-XZfY;k~8I_%Nm(T0^ zHXdkY<}U#@6~K_GoEA8s6>U$MTGZZ-jZ+Ke73(9RS} zHfbOWr@~jU3;GtF2=c`a@#N+&@io!;DEbg`t4H3DC$DG$~n_6^S; zhO9eC2JG21Y_CpKE+L>AE%q4*XZZrN6~vqB^UwLBV^!o3U2-iWN8LgvxMeO~tA)}9 zCB&Z#r2L(wYPLzqbXo~VZH*zt9&&(W?+;GxR3Z@IiIVI z;K!M|=XWLS>9P3iA%*hUwNbt)(+v{T_j>$ATibIb{(Nll*TH?(DFLo@=c@N9S?2lH zX0~)!>%s0cjC=nyQN7h0TlovOU^|5y&@5Vg2Eg9mpTk#Nd%U$y#(_U-gkt3X! zmW5tOoC!rVGcb)9Ln4A#ov-puL*Ao@mvfkNa#~+Vd^_D~rrnHH>~4&t^sV)Cn<#;Kk!0_e!d#fm% zTt&LJguePVSUnphqf94HQU1R&09e!WOvR81pxO7!e_eW{|7Xl^N{t+ImC%Xzl)x7k z);v{#!89aTSPFofj0!3T{swYhs6MRVu^=+Z-0C!}QomN5MH}%u_oj*h;DXJlPG)>b zE3RgRTJzih!%O9l`HT7fNdO-lO6muZ0^HI2)MIHmZ|hZMw|*q2q|S#ayWph5D;doS zjo=m6@feTj)aW%g0D?bzD=`mUslgSEQu&*7(BXk-MWz~Xw-q*G8V+=go{7;2lC^Ll`YTTFore);7D^G;&HhseUGbv$@CmtAZP_` zbg8U)E?yk`o-zF!wJ^m#ec*UGl%J+P3dslnmDLl(|0g8?*Rno&{vGldP@SVlw7#Jb zIcfr~VAPt|T35Bn=f4ZqQr2hysg3eifUvHj%>ri|$NckBPGSzep6-8pD?$ZqfPEE> zsm^7^TMkT-&QeHMdp^v6|i!^&zEBScM|hX`)fkiov<_$O(<>Gma_-*pQVfc@V*m3l+DlAfYZo!>|{^=H0B+f8Ki*T6Rq0 z@O_B|wR^YxJzPO}<~PY6e}PwQ6Z6nhyng;o6WdKU@)RexP@C!XR5$q3A8Ta&dhw zGxqQ6;)aOc8?kxaF=QqEBAx~iG`>kVAf0nNHoQ54q5_Wofb9;K?6$70*!(i~ zvr*rsYIOCpe=ty(w5dR|PS7O2#2%C`WN@Sz;AkqU=^keIl-QyJ#pZp9ws=x3bnkyh zLlPo1e(Tw<<-D*UGNrfN;eL2VP zOA&w35?6q)!k6&=GH(9MFGCBwm$sxvvWZ{wi<_`SKG*lDF)o&umyD)Qemh#yxZIsN z*mttswj`xwce78>egpgOUVuY;lgfQJDm!5ij1c46$h-kr|JI_8@*J9sc^){+bvTS; z2`P)oQaqf~?EtE?b%(9X@u941q?ba^fwh0r{_G!BCLSc~;^O;B>GPXker4R&1347c zJLvm&U|3s+;p*{viXCC-&d8&Ie(krq8b}2>axUpHO{a=iw==msQ1hZC^V zI!^sk7aI*#FaL^khktD*^Vu&Qc%8RB#PPP9#g{NO_RXl+^*)~Kr{cv*a-G%peg2m% zz)~2!_$>KP5T%C!fTG{Fch$fGuAC^5gGR$xDZFP$fnY*uwV=`Tz(=n7`s8<2GAmYT zG)EFA%Dz92&VBClwxP*u{aKPG9*)ec*z%DOV&_g-A8~6O8d{1R8~eSs$bGI1@xFvd zoCHqojt7B%rXyFCduOG0^!AA;tX(s=*Jb{vesCtcMLJIxKAl^r zx%=0Vs5K31S-_gC-rX9uU70};>$XK8jbHAWJ~x!#3fm`ALEhK6_g=;BSsC7*?>U)X z!|cuLFBHaAI*Tl=YK~V=cU@ucxxI&63~4c&N1v9uV3cT2l@`}&Pu-PW+gojCG0M)G zf8TAYb?*~v%6OR$axrOP6 zm8*uCUBg?QJx=T2zI*e-;uZ}%b)MjRkHW623gTdQhuutjo$MQSTIpw)I#0%W1;HMI z2v-Zs2hug&O6uxD2yLPs-pVUrt*O@3uEpHGx?SylPf(&gHflHCD_99=x>DbBGq|<0 zZzwp{CN!9j*#1;K-FuY`m{wGKeO~E*Itp=UD%yn{%p+5gZnFUr1&?M<@%Ef9bIi62 z?Jd^s|J(CFB=JaSQ_c}B>+5cV(6$F)23xg+o;CCB&6hUj)TQD;>UWFc z5~Leuno@&Q-C;a1W={to-?s0xX0C!D4!Vl|*RuA`YVLu~nrip8b$96Y4L3H{ZBBTC z`(JjHAoXgDhPOW+IGexc#)N2@aDCq9f2txGU}fLn(6saLE%`7>i=Wx%b_p(X3gQ~k z?mHpBt*h{07v7xjOHho-gd~>DoT9=V_>T5ol|2Z?<{qaAjO2XRk?zQq&FrpW!$~{? z7i{=x=?qDUc8cnH-F7Fe!`!XLm`tkFwc%~q-qj+ceo}rvR8g$n+ICi$p-|~vw}0ic zKogA>r_B$O+EX{)b$tR5g9Zlcy*Z~J&Xhvf-PRZo$AT{M?W}$9c5PyeQvXZc^L+wx zKuT{I%hKL$+S2Ea`#&?>!iE4X7d<_F!cPsXh%OCz60x(Ap8@t!1H<~;v4fM?g{8-VTwa1mrbl_Hoc{qrgw{QntaiL zq^UNRIkLBofO(MV5nL4aQ`3z-a?m}3ME@kZ>SFQz^l|fzeNu(l$M#W`W}L;iu#jjJh`~f zZH%-FHZXMCOEHdzmp^`9{(&KH=mF$wa>Y^V1+cpf^IUutI6rGlu}7T*cUoZ|La--l zzsPu6Ud;`0eK_()wA$7RTey)~kv_ZE`A+B;y-F+3y({ZKQEUFZxc@$*`7Z0GQ&xmY zJm?m+jp$r(ZzlH1qV4C;MQmjHdqtY{_w65dM!V=KZgh@Y7g;zhrZ%D(1B~^!iNdg} zvOFvvednx*wmR&|zc>?}u>2#^a>MecPdeL{dVgxitX=;0s-|3wx-HPKZum@z>NB$i zcLP9e+*zLnk(}3=G(&@*c1wEfPFF4_cpAT=zPh%VCBZ#!!rS=L<4)yh%zrL4^b7v7DbuYIyOzeJhCQ}2Nc&(jn`Qe2M)k6Ge8a<-qV(91ZHTHmk< z99L2-Y4vcZ{48tOU9@X+t^*w&^u9~` zO=F7}nd*Amv3cnm~f;;PU))7u%(Mo)}wT_%6&CU2Ma+oNJn&01k&gBuPi3zZ> zmHm{DaveHeX{^3D`h+}s!c>?D6pI>kC4|3+1$%2oMd+bh1rDr#XqF4*LoVrWBBzh|z7!mQ8I+wnI>bP<=61)J2^As*+U~P4M~$9q(}jymCF{yjpYm7 zoNeOgdm@VT4)K8B!!7#n9bBN&ABZJ+X?eArq+IRXqv=w4<7_rp3+K!=LDaxY95{`b z^3@f8FQQmE=lFTK+1PU)=x0XK>V@NCs~hF8g?@Uc4=YqOiz}Zxm;1uvuqKQazY~-= z@8X-dpC#kESuqoi+PMd(oKQEa-xA~*8fHwR6&?(JxgD&xf?IdfDN^-nWv)gXPjV$B zu4#1lbPY*5z~4(a!Zt{iFs|}0|I}MabUAHc0RMCQnC3-69FH|G&j^4F%Ly->4Y`wF z2(;L}O?wT$QWlQ6z5kv}V)@noKn)$ztX5N`2>Av#*n}NrRIh9M_7vxlmZf61=C(-^ zo)+7FWQrl(Fy8*|HhejE&^rI-+bLO!^EO*>?G7b8>KsldJZjsNJ7>n1rfI8-bjF`< z%kO8LHUmr=?crQ>U4!^&ngXyx2y`!lr;|zv551ul44Q!o80)0vN5;Pi`JRuKu?}5N zoMD|k2iTtQBk&6$zWOWyl(=N)c%q9(^k_$4ixS$lw-GLNb~i! zhzXo|aq}CU#%><@`-!26%sT-kUe_I9ZnuLKZ|UH$7?XDUurEQ#vJ0>36`cjZW{YQ#+E4CYnsk%w_I9KP~PnqXj)nH-@r|tE_n8ugV)aB-d+bcTe#l^?WPK*3|iLe*hA@>&}we}(yW}b zldnkQFO$|Vo&XiNeq}lTy^6)uU>_S&?woyiBa~upcrIqH6YJ^?v-4&@WpVOP(D6_m zkb|Wokdt>h{h-OY#>4M0i-+s9cj)tb`m71ASLNP!W`LTMjg3N&B8Pcz7EMW9OLf8F z-fZG4!mMwG(ly+{;YuRFw@|jU;PqdYwZWExHPenbT7m7yDR*cd_2NC~1NY05mDR3s zh9o3#+_=s5kj6&`9FWUXrU9BAGwMe#WJn@emCl{-@HBM)L}cykb5)Xu=+S~4%e~Uo#LlV9*@>Lyol8M z3&iUbenNpzvyiGz9VLBkS7`NQ_5Gy%Ps`yDZr-{q8~(8*xuzV@mvOQU?P5E!QVTPJ zpuk%`_vnC#LvUerUpt-S4urz4qIbdmd?Z|9z3XHD2WArXtbU}(nWTNRJJ2O){Is8c zt}WR4N$liAxgp;ck$p0ososW9M8DMdwi6Nlz8Vg_(X2K^?^gk;R%9?$I@ z&V1T57V3w=&CZ2@#r0pGrm>6(gOFPL=`8En`~-Z|kQqRxRtWR<3+T%Ld(<2>wwEny zbCqI-pve$}&h6%1&~*k+89fJ|=7hzg1KNfDCd{7EXp)nb>YqZq=r2`|jl&hK6vo;Mv1IHRUJap1u}>JsGDWXINVsmN}wWGz(_=WcSj zCrujT*f6{PkJicO%y?5w@1?re%ZLjF(b)*L6gVR;1%IXnN{klbG~>UFV&P+-TFvBM zSK)5q9lQ~XL_i@SmulPh0bJXv-1OG2cHL{frq+e^5{IGJ#iGJeow4{;C1xt=yYi!6 zpg(jpMe0r6Fhde{G#kuQL=blogMLF&Md2Q&6L^+5hW}Bdk_T}{ZoL^$;ilrD{MNWu zusry4?z3w7iSwJJTQZc7bB}{k@j|CK?g=(*dzXtBQhpp;$`woySxj)6dyhdZymdv`S+y>lHk?+vkk)N{B6&c z^9KJzw)svq0ThXY1*7oVF>5BQ5|B^~Wd$KXb#{+7lqCsU9q-jGmW<2yp3LBX^o+pd zZ>Gq{6?A;-w$K|Y-7hhmMxn_SER^9C*S6O8ROp(vUsmWQ?nM7M9xt$uCF$O}v%RZ9pS;#j2A_&`OIeOpZO903{xV}5O+eY-*#m9X31DfWaVFW znJ|C%x=BxdF@Llvy<7V-)JK2nzkQsY9w z6;cYqe~@+t z6&&`E*3DOtDY)uiezTz0kyH&EGOZ`m`?YWF{W8IzV4fS^7Sv;v;wBowfPk8u3m__?&iFxLM z{%GF5>tyg5-iHrrDj61=63baU8iaUwk7$BlA;oBZ191)bV*TKPbI60$kchB=ykOoU3V4Pi5@Oj!+9}fGV?jZy@*Ik+#u;jIhoxymdsJ5U3 z>4TA!?6c&RZnhu;$%BcMk69<5{w3`lm0X|2{*=`K&^Ve*D|Nr`w^)9E9d0b_sR};^ zH-QQ+@M#VRt&hH0RbK9t4X_yf#=SWn5c)q)^ z0+6<4XBbJCi-_#zQ<&pg08;e0-rt^g`lC_&1j}YLEn6NroJ|@Jff4AN+hnJ$9~;A2 z$VClj>h%{(LEl&n18ru8G9@yN2U4mReF;d{xlM;D>km5!F1CxCexA=c^JQLBv7E=M z=(u7*vt?V0o9+VfIX;5bt=F6%M;^Ovt27$?A%?jx09W#*<>TB^p61AKEn#CyB6>DK z2%ieS-g+JM<|mHU*ayG?x#yQqd7*Tt(=C(nBBG+EJ0}{CXtB@EN8L1sfC=mS7GMUO zd-HqL!9go3pCL*8P-Q2vb3xfII7!l=;#id_l=|KcJy`Je1S)qK>UuVbh@roX>bQx?c0blro^d2YVP7>W}-qyxY+sGHN(TAz5K}x92+R^XLw!#QeBm z6sd)=Y9^9IPG)ygNsi|c*gI%_R^xhY$A8caCpR%$@kwRI<+u;@zA`tQpcA{ED6Df2 zV>rV<}G|7(&>Gn~|~QZg9D@*0dcG!{xRlbvoJb z1m!c{Oxy8dov=-44&QkgRZ^_38muT1ilKKw@I=g@66~5V-Ow3YPCo{c??N&{QrDq^S0=_ntoWM!3dDY1 z2+w*fQq5?>BEYu1Nu(vJ;5#6Y$;T0^U{8*n+e$czkbW-DEx*S-Ugv=Bv#sG8u0^cG!PCYHcyahMtk5wAB;7k!|NwQ2U4j?YOWM#$HwzG|(M^SfAzD#{3;wSiS%Umt&< zv+6bt5RLQ0QpjA-3gLej?uJ31W9Y_Xvo_L+1;dCcA)2I;`<861QF^4>e*?^PZ$+H+ zC31~J!@J_YL_4h5VngmBU0ao@>T<#Gk{*A14bytU_ipwTYL7n|$&D9(`F++fdAbTG zzgc>cTwSLJJ%wj3yy&l(N2HOw?*r&^s7h6b$t7z;@>Pnr$j2236-tpn-y1tY z5RQz;R_0Rp40#9@sx|1^IX%ITjJuE$TPa^*(=IiTTA3!VpLgCD(Bfb3i9rT$fKqr< zDNZO*Vo5G{gq*r`p@-0$zM_QHG{~3yjZP&kX;7#=3mq2PnJkmQNN0#>6$`=+@sV9A zUC|1?yaRF<3Im6*;S9E`s%go|e6JBL z-J855p_T*6mha`Metw$CiH7o%Pzu8;AZb1#gm2RJdUA2zbVKsD@P*eqKbjW>{w5=D*oI0;y_OTOZ<12X@FB) z(hy3?c0p1K@M3Pnl!f9Ws6w1sr-)Uz;OnDAKxx(YS~@g@-SM^H>NAobitros5Syuc2ek zg-JA&E;I=)(xVQe8dms7&HrCaFs+e%YmmAUZx{XT(nst>y2mG%j%ejbwA*o~`uR)2 z5{3vU`sqxAv%P>%Ym~H$tK=2xW+s^AzshoZ8T6g>@bom~?5M_O{lr8gA_MF%kD=Z2 zc7e8;pIz+D)+Kc5bhj`zeeZG$_=$~xPRC@*L0RFqVrGXKU>h4vOTIxxKB>mD8{UJi zw=bCkOdpcKleq{Rbz=CgB%|No($|UO$Z?nhzs2^Vrc&ont(O-lkgpIqR%8{f2*gQ# zlsY88EHs?8R?Erc{(c5LtbrVHMe%2wW^OceQkcKJB#mIBq1{ipM>3E&|J@5vQI`Xz zeu)+?C>QMDnc%{oYebBcNWbA>{G~K(*p=lSO0ED!7ufZ$#d=8>hq5={B*cp4MUi9m zdi4Z=pB#x%Bd{f4D$9jjAxrXO;KfS$2^s8r^7PEL!q{BX8i$uUjV@P@0<61rl6k+7 zk5ecreXl&3FHmC(i~LrqWBoF1YQ8o#f^cQnJZ(BE|;v-a!I-CwD(ur#iw1C-KmVXJ@{D`0mC@2n5?J3n)i{$ z+F5rFZnD4e3$Ra;`hjKeV_LOYNp^9`3;e)7Kh}gL)ypUUu^a=9qLKIgeij~tL=;CN zU7q*d5|_;=IAu#D<2zMYnSTp5qxu3c1hw4Jy%*>dU;+q7`lP(;L(TWMZJAvv0e7k@qk}0&2zop7k4fNNj5mq>2#d-0rE0Z$2 zYxCz%7J*V%VCQS28MW)V!NzlVcXxMJSMv27`P8CyuUL~05f`QM z!$>eao9vB4(NI$tuNr=INq)~D$P2jVQbff`jrRK~OzBjL>fWi}l{df&E+%`b;{C1& ziqmLhWE`fE)uIt*<-BMnf2sywQNbY5H~y-z-TuPBWRo*f33!X1^D5d>mZPFYBV#jo zXg1R>v67Ms$E95!uaA$@N4{5#kd#L4mIvlRPk_o-^u$TM-!uXmAOzbDea%F6a(MWv zBY4RPCSvW#L%2UsQ!qZk2ZubH+BH=6Ptze!Bg~WBA&@A0WwdOT-rgKbB8T$CGT&EQ$ZBEo(ON0zk&YSp*9JvU8+wNO_-Db$e7?1 zu}%mCA9i9VV{ziy-z@%v0}zHqVzK7+OpC0W3WY-)thR73&(%TgZM+&bY*mn}drHMe z?pgkNf!|{b9H8^XUNkj1hli3}4#MdQ2^4z9aT#C<|ECIAqQWx8K~o3fgR(0=rkfq= z@0I+b{7ud=2KeF~qK|=2>iPXSH)0w!Bw{2Q`ttExed<-olK-U*f*~|m$4wH*4 zOv!-^cozPsSqM^!j_|+i>p{1SPjV~KcAcqqrJ33h+L(Kmd41lxVG4cew#Q$PaKgc) zSrd3@v%YlJaBt~+UmS57XFlWYm_NR7a%tlvRAaLuT=>K&cw-j1{RyVO*y_Y4+l5O% z;f^w6we!8;la;=pwbLzq%k}=Q6vnG2=KER)1riWMbVTVL04=Ce<)p8&$;ZN@_u!^+&~&pnyRowZs;7g^>SH13FBbrv@Wpu3Gt90oa>u|#U57`6F3;oFlvtjgu-`~p`938g&4wKkKCgJ#!z@&S; z)*q7n689P5`v~YbP7||6Mz68Nq%o3c84R3m#nee-N^cB-Ul_@_dknoc z;q-d{*rRgH-he2F3VEHG%Y7mCLM`MwDw(C>icc3-$JqRjpS9a(il^BeuQ|P`e3uKO`uwIaolf!P?@3#y=a};{bIy&&63#+SH=Z0mIgZhJf6Gz(?wVLh? z+FAzv(MU}sJQ+>Y`cC6tFS}CD9UJbVR!)ZQlg0b`wbD%S6UGa@$eA0wol%K(p>wVm z$G;xgnji8S1rwsJF9Kb!7{ErPhOwtQpaFnHRIvW3$Ur{xC-J0J^JMSOQOL^-yn6ac7&tivsaYy zfd1LHp^b?GQ-gWq{#1#O(BxB-HKlEL@suQ<)AN){UnY`}X4FK^<>XKzmb+Pd^6L`y zLX(+dAv+S@U<*HY5A8yY&3!3MhbDO;kH_8`Kr5{_9t3M9VbaoR5i|LFQqL3d1$GY=82|4^WPitOe;Gc{cNF0n z)=t88RV;d43*0!@q?DLss3Pg6&4+Bp2h#h3L*Mtm@8c|cSx_&|$`Ku2@_8-o^eR-{ zYnZ>Z+6Y(uGQK|-@_ru$fN82y^&TM3o(q||vsv^#akQRry|Hau>ubq;4(Xp=Z@+dD zH0_OM+4O(pcz$(2b~o8TANxBN=)6wt*?2KX*CPpz;1dr-$U5{x=%}ml|(0s~>+rL}?x@(pvhynoB@3jG&yadt3g) zsRGE^Gv~9kRlfanz0o{XF7qCYx?aT+R?2oi%_G_$ua8Cw3UiLCkFPD{3+8j}b#{1d zX<19JOmWENwCmwh`x1QW?q|oZBQ!^! zNfG~1k3BJCpy-Cnv*m^ikD)8&?05SuaAvpWLX>^o{cwm@dp%eU169*it#MxS zK~XUO(J+`EQ`8AcxtC%{Z{>1mKck5M33kGezSk!0-7HF|Haa4wU@Gr+;Sq6I^ESRC zQsA=hiOj;~J^XYV`MRcng=|&I`f9M`L+<1c+H5Rg;FqiT$j(xC1*1(k2@2tFKTRFI!!&*sts}h z(bgm?%7d4swnP_3{_AZ2s}}!qvhU=2#eC2w8RCe0R{cVcMsFVB@)+j1dFuTxCpHJO ztW!jMEcQFNW{Yd$hVH-jIvp}_|iRlO1jkddp{AJ0;@xZ|veX(dI z9`E9(H)^%-FJqFl;NNd3;159hPG>j=!{-py3IPB+&Hkmh&hE`{}{x4wP}2Ue~bjM0y5*)xI_z%PBR}7A1M=0gVlg`{b7Gy zR|*HcQ@INqPnmINdS>U(mvGL+MU!)241Dw4ff_cWQABP!{I{s!lXpT^90^_DP& zI&OILVI(*;F!CC$6^UF5buub9Uk)Qva5Roog&rfdfZMXVn&HuU!F+p!OdCk*!_=YC zz=w;jtd*hrs(vU<5Im^rgdd8opj99Yvy&i%Q)A6v>%J)!0X=?S{OW$7gG{2*%tXB| zwz2=3jO>DuRx*sUShJF$vM>Ibg~g@#Q55p3ZJui-Hw#iVz2`DS9Yk7vuVE=6U8qlw zA>~y6s5uLYJd8t)0^+X0AEkxvZuTU`9cZD6_5?jvz;j~_XuKcI(IwKpp^H&ZiIZf73610@(Rh^q@B z#@SRE_VS0s^7l2Wm2Ld07J+6vos^2u$^_*UzM6{y5#7}I?o(c-jp!Rmb2WPNI>VvIo0}t!vMVq5OZI03zT>Fq@Gu&fBxIvI!{fG?=i3bk( z5$2zuO!x(w<&Pw}EDp;FZV;0lJAgN|ky>JUtZ1SCi=o0ieQf`eV)`KtQcRe2@n63rZ2e&r@u$x}IzR}p&_{BILx4s?9z;qQdm2l4VTu1w$p`iu z|0){q8^~&L+hC#}kix!#@cwn*e_lJAj}Fe|A?;&upItGTXpP1z|8fnm%_6R14MQFY?YGJ@c(k05>wjLDiZ&3Iw|rV z)>AbC-;?Y@Ni=9sLAGFJaf`D-QLe7svAF{&43nPd>sVZoG9ZLOI%6W-em}hqeDgFPA z%mnyGgh5ncZja{>Jcwj@?v2{fZt0&=36*(^2x@Q~)2LDM3m~nikWds|rIJmX|lKHD2a?A_`~| zd@IM-8CDqOC!Dcjo336FWsJSUG5PqW!k7!cP?P?eP-h5KX|-K$4_txNpHs5H2)jcB z&o%>+>~1CnjDM>|2=_eiLRjE~>?#>?hXSMVZz1XiJiS8Gi1>+^Z7V4_NIb>1TJHB* z6F=4N>*`7N`{FRUWrpFMBW$r5nj+M_8RnW>L&nj5t&eY=(fm_M`t0EZ%I!IX}w2t0blnXqqr4t$-<2 zQ+0ZGdo3Uba*!ejobhkCu*4$LO5 z(D3juuMep|E{A$#p@&D$O>LEvxA z`=z>WIX4=*S52RUfm9vqant-l0ZIXOI-8I0guwI1dbs4L72Qw_eNbr*i28SJpqde; zY?1+XD%*5Q0+i*nzER1<4vS}633%KB+GDg(bRJpCLd#RBoY+`c4&Dk2H){lDFpRL9 zM~{BgT3lT{&B&l-W0$S_RHFJq%HRw5|Hob}EImeLr=#rVVM8Wn;2bPs3gG#Za`K3S z>d+@!U_xTl?Z{H5i8>E>6h(-#`;0Nhu_-6V>KXN3z`T6;#j22y7ngPR=H?Z94rc-{No}SY? z$3a(&K74t3YvJRoY$hzYzMm4Px2vBmbUv*2t#dfk_pi4QI!~nwRFs3VXSzNc-X~tS zqr0uhPLgwXzAML4k~?My7bZt?DJ@coZ2TD4r8jJLDvexB6=oP1n0(w zXuqLW0>VG0RyekWK5E7qe}_mqK~}T7iw(OG{g%g^Gm%R1Dj|b*AAD&fK3KTlzp%Vq zHeyuP$BrL@xV!J3o|h*o&$q@!Ak2ss4lc|bqT}uDZ6IW|B>L^$!SS(kzX>}wxAjWb zD;4W(U=)o&0jt|!DwkGTPZsK=UO46skW3zIc&-cDz^C1Ha~h8f&cwp}7Ts!Ev6SmrJEqIR&yM@_C@rgM^dqCyN>_x8T??ZP2`)Zu^mN4ANTO4&490y7u4zgagrk_HO!sYjHwp;HE6gHeD6_HMx2s52~t6EI2P2O*vm< ziQ#4DZPA3A|b^uFE3Nr_XL-#GNkfsed}9mgov`PD=42jxtI!2 zUMVR=3jm!`1Ui-e%@P(C_9J)lqInu7B~39orSAzK!M$DB1j@I|0C(E4Hq z>|PdUqE3;h96?N}t_w)8o0}W+gjuBqja<@&{MExo^f6Fio`td(hP3Nn4l(@{VVB+B zlHAtgOhkn|4!U~VZNMr8)>jn1-2d>JPy{VCynuYSo+#eSfQu(0qKuNF&5>6G;9^W9;U6 z?fMZ(!%i>b-<)EKO%|D|D+je7)oIBw|5RmgTJaT4#1HAv;7r`zZEkL+3$-IJ6#E8) zON@=p$tL3al#6PLO?+?N4iZcGT5fx20x-o8FeR*grka*qt0UxQEjNSKIxIx;WEeYW z)!_1IwHG&}gDfzEy)~0h07X<(^hCgV#b4B;t^oLNKh~GlQ;j*1Mk3_dWqjg*xSDo- z)9wBJ`9Tx*&lQtqSa5J~s1iK$`IusKdU4RB1%vQ*{ce2l47q`JRE1S`4=!b8EwWSe zqql9Hot>ET7sGLrW^P);TeN|S2*T8z{FFp;y1EPY^5IbNvPr@`(4ponld4K3Jt@DnpuS^vMHFwFeU_3Ty zw=FmOy_xtp0cSfj6N(IRIYfB)r$CbTnC6fiB4a)QAJ9qFo`~W{5aQ~1=nuU ztdbWP;YcoCbt}>LLEP|`>}%KHOD?y6$Fo@%hh*a3+}`HnhlqFcXkj+X6xGj!0&qE? z`g*loYl3*3eHZwy24!UdIMQEcocmGZqH>9Evatg*3dYzAzX35gKhk!rd1gI4ygtt5n0PUljyZl$8aA z$WvQEftDy@v{YLbTA;9ANGmOVdGjNWH`AayvZmCao3+ht=tt7&F_0&(=4N53)0W7` z0HOwX#B}5<%HUdGNqvC;tt{o=15Iygo4-aT%tL+WZjU)@Zk@ zE?1+;2>L_>e;bv78*KufO#yQ=r&n0wdtSG}6|x6D$2u_1k-4K>gb#Q^2f`xsvC$-| z+m=w+zsuA)y7Id@ZhqdD>a{9DRCl=&w4CRBZ}z%-d|bs^v1z?ait)=zX?=M3^XVT- zIiDpH5EA>09zT5=JwohcC25}6_nrj+g`|8r1mL16F<#{K#xd)3_x5gkP}G7a&PIbictQ<9R;Qj;BO`hQk}3udYyI~ zwXhxk|M=V;_#Nx3bbsyc26}~T;3`V8O%oZgWf1GSVvx}&piW(%fDg8ik~4;o0QD_6 zIXZd)PG%+xWm08`ax6nwd~g~VXx{v zyGzJE4FN0!PP!4n>y={kJ7A-HG~>5~SJ+YGY~Vq0o}P)NAN~3BxAVFzW~sI3l3n zptBE9H-A*UE5eT-1Rh^k3`65>c=M8&)XQ@%V2K0U_!jkv!8CVpgtR zC;&X)=V>uj1|G&@U`%Y;aG#36U=FeGR%Xx&0VtFnY6n_z`o0M`pZ!4B$}>$^@tA`w zNQf!ChjDnNJW5agd^Pg5n8J&X33k11YWmm^SqAK&reKQOi>oWQBHF-}{IgMZMoEQe zy}Z1=GK@3U#J)_3Ekd|T8>dG_dU`s^1ao{8J5r=lU2?W5Gi)_|sb*VkUS5u7jZE+Z zMtV(=(`RJ!+3_OHG~v4kUZH716TjtKOtGV+b!22@=T)#l@m|uqX(h8#z0jJo2rs0= zD$-9=0aJFRTmY+22S`ci>A5+l#(RKr1J2kQu1rk@3}OxiFiXY*Y+T&k?>hjF_v$m+ zhS816pk;(ezOyrzg}NzXuDU8K?|1^}K= zIAm~e5FLO8b^tGTA#q3czH6VE(^RP_+;MO`M75in_XKq904SrAQlkHV=_G zGnHL20vk^Xl;DBg*j=jPfOHex)n}U`Vu@{LnySM|LY6Vb zUYaJne<^L?h5_OOn76_T(I4LDe@O#!Ws67fPMHXp@COXS`*Ee*H3Bf_6>R6d=CCWS&3>kl|fR@ zC;(dhCj*sq52*!1?wl#wXy^~$6gUty0fNj~|4onsSw`>MQi^}4(ZQ1wXmc=JsY_wQ zX-8?WReClD{T2_pX~)B=jjev~ug^*hx*XV6MMJ5hq!cyyi)p3zff1709)fQc1tt!} zwkDYZ_T`%XbfZ=hzS}xy5bE$-zv%JB=dl#zDl}>%*?84PLCv@>1(oA_Cxlj z-<2KAz{uOVxH?ZdKcv! zT~QSDp-lIxBuiVTe7J1R0-QU1f%#l}qU`jqE0--R!}& zouNh1?R}WbZ|?T!Xl-~MvtlQi4U^+0h#ILppCYF>hW@+&JkbmUFZhtI0@DP|@QWCL zCVKf#6@g=t297C`xD7~aejY2cEBpu3Do2C`-3-;^w#_iT=Q z7>IxhdY&-laLBf{4*DH*Q`*;3HUc=Cf~P@=41*N+16lV|=}Eubf9HkJMbe&mh(X9# zhQ%OW5KVjA@OM17>+S9eC#Pt&&*$t8D5tpcf?qSQ{c7eswcK6Pdbe}Jvv-5@_0D4K zRX6Ow@=}Gyw?=EOqS<;so$P0?8I`PDpRm2(6K^_{QOGjWyD&KT<-AKk`T+ql~TdHx!M26qyy&`CzeNYHOzX=ox+7uL_OxpSrUa+-K{CE-w$BJ>9+u)IK*o z&R4A^%`Tn@+2^_oRS-xdO%rt+c|z-JT-uu)8^Bx?3k^tx(Fhkd143bX^A6-TAE1z8 zjIed@ro5lKuiEkI5)3B*$AN8)5HY4_v`JK?q8k0ksy*#VG zEMu1%^nSg0bi7I^cZS`k+cgmBm%?D_q#p+^lm~3?EM3NZwb${S)!K z*OwIZ;-aEyE`sjSOe*+LY}xkf+c}AFC-_^x6OsRit+#-xvhBKsH{BtrAR!{%9U>sz zqO_EBH_|O2Eg-!K1=(~E^%iIq&zp-#I@684h8{eP6L+t~u9=32^%3 zxB`Inm6URnf71t$+~pu4YSOBI@JYu*VEL}F?Io80CoNf!yv^-c-ZlL(X&LmYTbG8w zIMY#qV-w~hP_~4WtkCP@7ZYB^2sgu)CvwLPCGp8?Ih`+<|8;fodd-WCUb&Q#oRw8J zYR_P0>Z#vKX{M+|8>!O{LH$m0@WW#b5k)eVp&QjYH&LS7-L93x6XDv53x&0wL~W`a z%cJ<7o#i)EwWc~TE)FDhKZvNo!9x7>#u*(PteoL;xDbL{Jlqd@j%3ekhZbgGcVOkC z$F_L4|Kh#fztMfQo@7#*N>!^;Ji{*W* z!J;KX_3TDodXoLj$fIevy%TeF#en7}I#XHq2^BMbX!;5(R{CD^>F@CoY zcQ3D}S+5~xEEy#=uDKxblZdg^lWo;({(_O!gmq=2`9Ikd_>2Ds`ZS~KdJM6#g0RO4 z5qK0WGB?hQ5LbwRljaA+Po@4t`D)+IM9tS+;>k?QeaHNJn(CZxaP=*CSQeUIllmdQ z>AjA1@|?Z0|6*XBva(uX(=T3iWx>{U>VxyNo?kpHG27vErNzD0Pp8PfjBU1zDqU3H ze;BQ*6-|#!s&6a#D1JeY5!QbOjaq8$Sd{b-qZY*yrX-QPsa(5yfhu}=)ZSOay zgfSW@ir4t+ak`H$fwo6HRzb$%-GAVF-(y#Vvivb<>do11aCx^U96TEUY%bk{t1Cf` z=f4Wca8+{q{a-YZv1bTj-if*&occ4-w;;Wd2(1LGQ@h9`4^&x=baJY$pPG^R$3ph# zc#A`ya@E}wCX~7V&IU@9A>G;#BUb75mLCe|jef^!;i{XAg1OIbLY@|Pw{z-^M_?T4=H?e&%?Hd-~H6fgMc0uvV>QUZe29zj-7as}ju z->}swQB}zkX}N@S|0WY+f{#g{$kX`IKR|DxD|%3v!|%jftw4hlf%PX0bG_>7H;Q@O zDSB-hbfNY=VaVyDaGU0t5o1HQai4FL;Y94$k_R`!r`;t6?~M-|mAW@w2B8OiiMio(v?AxSmEg^ARD=6%!j}W)Lqy$(wKiAXo(7tTW9ahp&JLw#1qopTha;LL{m*zIXV|zk< zcaV=^n5N)qO#kmS`gDr1R*hwO5gOQI5jz%hgdkLNo4LD1OF1w0FuPVqS>eos47;ld z?MrRrmcsM+`B=HN(N<7N41F&6Y^M{b1K=usf+E`unVj#3P_H>k=w};s5m-Y8T4(jd z137<`*jzwGuYGZmM3(UT&ZB-%pZ$^Q~7Ya8v*`=Kt(9;7Bqe#+hi_ z;S|}Cjz!CEeI}#oeFD3RG6;Xf>}KpzYIa_mgzPWMM3dVOW&>^J#U<^rliBOB%IlAy86O! zvtjY`h8;PH-!BaCFuNFGEjm@i9nE^d69y;Z5%qDb&$gaDuoNNS{^+fzN&Edeu0eOr zjf6m!1C;%cv%db%a!}W;ADdG}cZ_)`WPh7^Az#J^QGx;sxf~l9PE)^vI&EZNP{XV|THfMV`^fCI^r0#RkmCx|# z>+ys>q918E%vrg9s%nSKpL1Ac=>#cU*_t2&$kbc<@98Y#Y(DRyyMKUY@VyhtRY{J{ z$AVFxRo0y-G)ALRN?2GhU=lNa+(Yupl8fjn=TkY%XG^Jk*d3&@bnAB(`_vpanJI0g z$&dg1;;OUYZuKiwxyu3<^lImEh1pkmCTr8a^JRZ zM@fJM84R3wwrKZn*2VhwfCD2Xkl9v z+k31%nlDG}J+{f~?)B*DPUwe_ch~KMTGi|LLwa=>nb`UqNlgA_cWqP(VC$fI{trfbgehrU;|Li6`IyWO$pyj7a$eMnUjRBIZ=9 z#S>{^`;sI)fgxOhl+Ac@O}p0ZjB=wmmGol5d8SS9&BjvNFx?Zcq2CtQp2p9wyeXk~ zJBWNmGg+cdsa$t&$E{v5J5@??shpe8csrl3obabT?dBGATywy`b=&5_Bw_n_<8>+% z4|m)DDFxd|cf1_8)N|1+Rwu@jkSO~a@Bq2dc4m8%_E!loI`B5H)plw5zgby&wt-OlT<@aaNLH4XVd! z2T>lUXn&57MrSRJES*D9bXxGZFNMTME zl!W6cD8$Bm#XVwq4YidgI6xQN#UG?m^_{N5HtkCaGs*E=zv*zaSjZLZQo2?2yZOCU zSzp_`okq-DQ}QuUMZI}pp;+DRdD5AnjYySL%=^T=?b&sJiVgMIGQTP^Det+Z7!5gW zzn(Z!&DW8-X)33R?8L)L+)*9NrjLw{j7!uloqu~a;#@bR^;{$sqS71X8Yv~1PBt!R z=K18)Pp8YS6LJgP?_n7d^$M9o4Ax9AtSyj|e7P+=InLYGIkA4%6(?gUqQRmc#wpQF z{r1!*?@C^8&4-iyCFO@!r`E3qzFG^qlvq=2{xvl<`hFMf>kqHmVD;X1KfiKj_$_-h z-4*ZDtSqE^om>2raWAx<>)FkLDznoI&lkr#3C-IIk^*?;pMpF-9)gEO3tFo##Gsat z6~OTCp9Zg2DQX-h$`ZK>Li_~yy{eT9k)O*eN7%%UQ>yldEfHGW9Hyb?{fg<_A=$C- z)tr)Ia-$ld*pG7OpInfWG#pu`9=LF&Igg&vO)=@-dCRKRHar~qpspJb5 zWhj&+Oz*oSucX$~GGTYpip?I%;=w)JhS5?9zs8@xO})9VcGN_KLC74Q83c1g>}7?a zEP_0Z&WBG<#WY7;;>*|Ik$g>=@ghw^-oA0kZ`%nReiMzdV@?lNDo{k1#>?N-daUMV ze3fN;?p^H4U1c*x@FKuz6w0iMxvB#M9$Mo11*--V*`%^dZiQUViip=6-~pqb#g zTskz4sOY~SQyfOkoLqpIBh!ye&N+GBg+8q8{C>-!xSHgOtP61bc4 zXw>=6DgT)l%U+K5yQCWXe3|4Onb!c<>drpLNq>H9?1X{$^)r$|-4AXujS-Yc z_1y)Fr4pjQ7pm!BEAP)Yllsh_MV+y@n;%GzT(r9HJTpfDfeG)V8G$x&00e_<^If`jLXPU2P9&xw8yy@3JdjT?BP z{xzwut|$lf&dl$2swAnE`Ygk&5`S&<9?^XfUqvlH-GMJ>ZjpxLkc$wdU%7N0W579W z+mB(nC+^w43fGR;F|vZJb-Hi)EP%(vGM>-KoWFejO1a_W)WL~T`JT&!^ADG)Arita z>GI#Do24(vlL*NehD{B_nc(LroR9=rvCbd*pZAOo6^9hVF#~uQVNyI14trxYSRua8 zX(#ms$9!3I8t^xm%xo?#2}6!4!>xcLKRuio-CnHoLHph}DJ|*#V-@Q`$1W+2wB#?r zZ%5CQ=yk}`26GKqHqt~+;5@3zu!I<2^DU)H)XXrh!ik|7$zgQGoe2qQ;MkkunEZNeKTrP8DeSk>cW^5_a5`1{6rSA0wo z#*ZgglUt1Zc8iTsLbtB(DrXN?C#h5`6vKKhojg`R9QVaiCkL9y-|fpmBFdr_O=A0Y z2`*=xO_4pbIMnr-J$EIjd_P;S=6$~B55R#V7DZE8{rkX%|9M~&$SbT?zNC|$=zrM} zt=#Bp5Dp|Uso`X{`_rIY7YjW_D#I4j-qZl_OMqDFXLtoCmKjT{rZF8g@Tnt3rf=5z z;<4_8J;>fp*-C{(KH~7YD6+W7qxXC9sFH42IENCpXfA(D&}*FBB^`i0aTtx2z^CXDXvW_Yf-jMK!9Mwqd+hj%hN{<)Si z8B8Qrw^Hl+6ccK=H}2tid_3@N@r!g5S?nOKYxnimk*g!CEg)xnI_qq-n67#vbhh^a zq?)g9yaDKTN#cNLnS6h<(-i&^=>Cn!?oSFmI%vL!;@=(D5jOO?fD!yy&b*?s*V-c& zJGALbIppUrm7RCuz%3Bk`aKM{ z$?9fashs@52FozV${!D}NN$3JAWd)n?3uO2rWOl(H!OV<6*h`<7i9Ai;7L-UxB3$MA24qzct=RiB!G|0JW) z3nN*0-35`l920{!R!k=z4vS8I*^gTMs$543;9R0%Y6J_BPD0B?THM+gA3wi9Ui!1! z+bi@~nEpR^hdMxw{(#)S4RQ**R3s1txr`)Ygz7wi{|7i8ig`g~(%(|N^Q)Rvm zc_{5(ou?Ir947|W31j3d&p)KXhDd)rNUvMX{Qov#4hDz>yz>NNerM?`aC7j!KTGQJ zp?jEFwIWTS&R8baF(8-Rjh#z8kb9#{4<)va6EgzKMW3j3eEAOy@W0bRM1(rzKdAof z@gsZ_X#jbuL9qiBTO=*?*2TJs^6xNEBRw5YS6FIfgb|{LPux2mAV-9-$`k&*h`j#` z|D+9QeFtgUb+e=W;<3$l{~j%AeU{qe6cBcV+MS=6GqZ&ETenj3%xLJo$lY0RU(xGj zgxSy627^q&Xfsi-_H>x{{z`82nH^J&;ay;@$MC($7dGG4{XJWcrOBojFlr$g(2g>a z=ke6#_b9?6A1>)a5I~uF-)v1yx170s2>Gz>Dtv4aGq&EBWqOkcvK#Bv5OoDj_f;%r`r`~0e<~J<1=oarPlskhQ7|1{t4JO(jP{f6Kat{M zjtCpHAunRZ=vl<_VX(quYDE``HZ`!fImJxD0fd?_i3 z{N8RROjP+=#a?u?d*CPh(Ms$uT(hj5h^vQ|5=^!Rtx~I$QGUN z#k_60`UM2CY=R;y>9JZz9c0+ve$NYLfU73?;9=Ba)P8XSMJZEnZERc_P&x z?*@LM!V4?1{;o5+I+!7Fz9Sy_Sd_rFp=xw7?Q()=AXxyZl+XSH1~SSQ6jkCR|ayVs^#(7Hvk|uj_aC zkFDmg5E2l}&Nuf@&S$;ewf>58kE{&1CVPJT1|%HD4ks6UYLX19*(a z3wiSMi=?*0!Twd~mz)WUshlRtiAJlrJ}uY%pY=gj-wK|-*-#YlKE;=`WArv8`41N$ z4KwutB}vJho_>tZ>F#vs!tSMHJe)W}tsMYW2Xpxbu_B>4c@g?Lyf#tsGAc$pUsydU zw|@}zZT%QA();&_0XWJbycG+Aiy-?GZ&w+ow~O`@1L9kRNTf1m)ncugRSa4!Wv^@b zI{))~{jMiFBG5z&V93^|WS>Sn2xFqSKSnZX6vM9>VICy1)Un8M>dI63A=;t?^2uNr zkKGJu-_`?oz$T0P`N5L{qSA2eN8G>sVzdKU+uREs8)OAsJv`!tVzJ2Q)SUrROhsQR{iME8r3-9d0i&s&g$yX<17&@soq@e?}`sJ3f&|n z-BBM+_4f-8^jlzSM#`h}>}H^Lhyqxmd1Tu>hY`3qk{dP zJ&2*@KopaPJQZ;|g}QiBQ>)&1AYjYkMXZxifp}@d(gELajb|7UgEmggsmHQA_~V1+ z2h+|j{1uy#8Jixm`%h|}uW;#x(}0dBYx8rpw3e&KV{ZDYr@J!iWC@)1>$*O!gI0VU zGjP9mf9m%iyyB#u4R0aiMgYO!M>^R0OQ|}oKWT!COY6Bf#t-5eCpkBhUqyoO;#sF> zuOe{FDF~HUFhY*B!8&60O!*Y`KU4@s{y%jCT9xJrX(zWNl3`%T~k`2dp*q6ZSjC#Z6_3lIByP% z*1Bv}obI3Oym-WABH(m3G|!Fq^5rR6)d3P39%W;j&p%2~SvTZn1P9#K9G4m=w&^$M zF5h7pTN{jo8_)GXp?{Y5G5jS!zb)U9)`bu~`}7#ZkR1QVG*@k1(@FbqGC3&;^X<2` zve|dE1d7sjSALE`jcT1;w;nAwNAu=54eF_1-aJ<|2AXy1e?*G`f0;K7T=kt}C1Rs^NUIttF3LdT5#Lm#e3jyt<=WVV_3VKV0 z>5^vsanR2?=U&zmHg?dy>g>h)6_btZHkkxMdSx=IkWf8b9E=%X z(0`2Oo~+@Qo6U5oJpsX?Fk}c18g-z~VRmKCJ*8;NqH?$mBJy5WhO;F~P<}9+>#{w+ z8g3aavy{+#sjy(dI8~zGL4NY~`0&v%Y8eA`AYF)gySYcJRdHd!n{x%6wAwMkL>%A(>*LQr=%SZNGnDZn!v00thmI?}og`Wk1~tg8SC!0-^vUt#37S+Xf8lW5yjss0vLfwj z>7+40gy=c4p;XIPN71`_FWyFj5?}QIMD^`m(qK0!rI*$<)37-oM&4LW7TH;Awdh;K zwg*ehTVeot?Br&Wt+4m$&1E402??j|6+1bVUvXDDU0>Zlk{ba9Ls5S>gzG&U85O#g~UvMUuswfF`ypZYdu`gb#_C>DU9zAs-`m z;u<^3&W@$C+L)D6-5*88H@Ix$1D$s|nsm0R@1)Zl!Gi~1e$O`1_Xh?qdWFhpEiP1> zB0b&t`MySg^WMhE5(L~KSRgLB#OYK%z@QZkAcZ_eq;_jB`+v_P*bSP1&ODHL1I^O= zM+o{Ke{p^OEsOq{S#xiO;936wi*`YdLCXuDJ+q#r^~u*l8zsTP!HjV8fnyPm?U?ND z+uO=bM*WPQpufFKEQ9@ZLzoTP8dEe#ez@icB07-{utHMCe)iR73EVqd%>o^Gwr|-+ zvnZW|!`*^Ruh}ZwXZW87D_6AmLHF683}7+|`r7OgAv_qnfIKdfG3(hsbYm<!bwfzK04oeCa+9&uGEasz9NUrq&WuxS<)=$&_p~41%zwf z{*%JM&}A`W_92fEIFQ9qA$17eNFXYufv^ejB9g;|5h)tn&bVhkXVNL3zohXUQ}j4% zdN*uxppgn#!J&adgTI+bf$Rtr8BLHJF#PR>bcK_CYlBWl97we*+VBmVbU?t_#TLP{ z068y0+7CugmV1D!IvR9!xgIb(!c>Cu0iGC&+)hC8Z{!k0cidJzh&kl*eG?HUh^<^0 zGT`4huJU6(2hGcd!VIES;tdjf?GMUyr}h>K>MT#JUR22qv>E;li5#d96^%Duc(tYc zP+Ai3pM)smt6km`fV$2ATQ$m_BPpri9{A``5xhyxoUu98Q0IOAL~_vVNLva10zeAr z#R5B3XdH01913Ep>1VtsP`Eo>1B%!VF6l`@VEoZ^lNq?JbJIA zPe1in=xzB~Ob%iV`7EEkvsy8R8{h+3Ks&IW)h5s+paK!bIl9OB)n_$Q$Dp!41fYuICB+Rca!!7>7R|U|FtR1_2srHQ*yoA^~K(AE*a} z0sGX0Na{jI^)o8q-IaVl3jeC8u72{?t04~z&QMk74Q-^v$3I8}BApV;)FO!=qcKw@ zdgSl_tVs3Fpo)sNBypJy2&lq&Qff+bE&ULZP0F>*1ZyHF7iS-c>}sKB=Zg3$yzxa) z(zhCW$W2(pXo|h&@M)wM%l?ajmKOn2C zsuDL8@qYy2%ZXZdAjY`gL40{i-B735ApV#)ZeGC34B4v6_X8ezBcYfopvg@ba_9nW z%VYnFe}qQEY<^ORZc{wPErVuP>Z+eF!Rw)NwEiQ5k|LH8#GxKBtHc2$)&^dsLUz($ zjNxO_>Y$Du3G_Ih){ZM@Y?^?Gt=T(jo$^eQIB~5l_3EI%WI#suM97MP)85QE)?KZsDOWb8!#rRK2bchnt3H^bHKP!ZU{z~>S=&}Vs%0Ug%12h7D$0)#JF6G)>G$e68GHG?9y;3U)taduTlfxOOgW3&2g1JxWP7%@3i$ofSmBH zV0)Uub;u&Mde*2M8?2T)*cBTh%iWKkQ4K+`N6(`)XIrl22^j8S$r-lab<%(|(AMR6 zb#wC!+GaQs7!*`0s1G=ypkGot>xia z{uF4cmX=lZoKaL_D%u?=MzEjC_z={;AH)o6HU1|cJa~-A3UNU`2-#Fj;Z}kn(`v~E z2GD*Ad6te3GM80ypoY0u-zuozpTcDoIlDtpQzi$K#H^cT2-!PsWwZZD<`rOpm2-qT8c{-6r^H^eaMd1bJEmM{|=Q< zp0lYo2fCCy*KtPB>g`eXsDQXCQCRZOo;wgft^+l~F5z00q-Cg8>S+oPc2Rtzl6yz< zV3L)Uq~9vOmq$hQa}7ihs4B_9+SHx_(&)RPUBgsM)+DOF^*E{DHPf(^V85BEyW0jjgXPFZE?P@J#uy!a7& zsWIKq#mYMMEdhlXUjo8!_k-(KObMu%$brp9<;kaySP8;P;Kp)oTXD}6%z8gFzIk{O zFaPcMneqZMVt`<8*vC$zF&pmpuC5e@CMM&mObPWE$cSW>iYz4XBvC;zmC67@Y+XSk z*yA`@x3^978Y_o`s*IU6E2?ZZ9jgq#rLLc0KgnQ=l_NQsf#+R-#3{W>x}NX#F9gq0 z_|}F-Ii^?Cuc}c0xffF@F)lx4Y`j1wDgH+)6ODWzY+4+90#U8I8>7`hLWEj)s)fYR zVYW3pu+0+5jYBv?gSC|lc9CKbp8|jRr7S~?T7ZIrg7x_9>?~ndmzE$_+9k|gVD||= z`Yn+1x8D4KVPRl+nA+N=Yhnn9q=ZwvPH+F=`~!S|u4y6)n9514Zzl(T{8&p=V{%QB zrG0^MDjWC2Exs2@SBKvR)n~#-&nx@-^6KX540d(4@27H}B}>~!Nlrf3+0$cz>#tg2 z6mi{n;dWdQ+mIurdkC9yvB@xDIT+aIMP>Qjy7Lu>n@tp}YInrL4TifbnedZ2?P}U!cf%zc3{M7u53%t&db1f-&p4(qNlCJJMC(d zM$qBv3<=>=4#mXtcTw76NvyA^#6%%Vt{(9=_FL8ns4%$UFt4@uNXy*=o5cl^bfKFL z$}x`Y%McEM;umujDPRaAbb}Nr^#hzH_9HDh17Tg77R!RX@G$69mtC8XJ=D+U@{*&SJW%ub@lbLGLn)%Uie<0rztuMeH*a+@=8mS8Xp=K6~(%~vqS#L zkP^lYt~f3>cBCw(azlOnBo`M~Jw646-t6My-IFM1N5^~{8ym$G_!TXI98mmIiqI1D znr%NN!fZl8Y!fcmQhb$e4FtzL+h0q->Vpzy)!{{wX=d5+#Zor#~LeJe{__y zVi5?(@fw#MW}MNL(^^`~?Y9hpzs~KC_*uuStR9+qDUPc)--*Zfhi7WKdp!Q> z`TKDvh9n~eC^iUI-`jl~c(E^eXZCBPyl{7ho8INcvlIk@`Dj+wmqPP=k*M#x^~uRN zoVXM$IQO-$gg z-!c&%hebv{CdJ3cFQJ7>r*N4%B_}7pde?ypEMbHgwfnOK`6+o?0>pXbJ}(5V%va7r zw|^!f8;CvN8}?Ypfxh72@JyXT+{LeQZomR?LVSO8btRr29bGMNZ_nye<3}RB(xt}# zfK*FDNXVT^D`}xmN}6=o)zx(e?BzOmEMhBf3Ucy>g{djG2cqn^!l|apuo|iOjF>jd z+xHt-FlNo-2Yh~eMKzt_BvDH(6o-n`(1uX#V$Tm*sWXDp;hQxE^{1Y z(-dB|7Og$KEMLCW!Y&zI&YT z(uhvvU~L67EDnKmTxm5UOrIb)xcIHLj;msK-@kur;QhXM-o8~ZVU2dSJ$fS35pu$< zc6$7WkbalXcE;>xaUJXZ?3q!YupvabMkJ?wpJ@KYN6NkECcdgo9@b6~%h=bp1Yb^- zGklpVjcTrK^U*pj8X$Qn{sbW|&E?5!`!r3VfVPDC)%$`NGcixSkb_M(D~D%kFl|4X zZx?YW-7AFMz_-1t3vqAng2VE)Qf=M3`a_tFL89QG=)pAh0Ah&Y-@~E`cM#Gy7EBVO z{zXnfp;SRhD_PIM$5$PjnYqa53wxJs3fzYdcX{g)kDu^SFr3$F;$l2UE_+c=$o2Y% zAO9tH$E2;W6Q!u*?Al=`H*S5iHR_VfoPnZJzE*DP8x)Bh6q)&iyGFlXKFU^llW=KGJS z#qEv3G*xqz%%0L6G_${3`b-u!Cp|i{H*GB;5u$ALh_&;^sBaFbwYPuEYjwrV1EvASqk+hH^0>>ZXMiuc5WnbMV&B_orPqM>NV*v+3B z?`Ux1Qtd^W4a)ZxyY4Tbp$GS?mgw4f_^DrV2@J9yOk0>CNR&f@;MdRdEd>VcYiz12 z?zd1|;m-~*MViGr#6YI^qrq)oARi}in3!4PM~+&8_=jx#OKVDeO?pnN_zIAGE~H{hD=fa3BVvX-?-2#kwLH z&|tf^PS|aah5tiR5^2VBkM=>I|~B&F&QbSD>j;r6Deh!-=jW0rV`ZDB_H^yleXH`&^Xhn3~x9hUiO z;YHf8r*G)qAfqUq)5Bp->l3veM>x&iDcHgd1M+8s8S@0-Twy)uOVw_D#R6`Ms0!GM zVc&Y8)HcgO_YihyiFPGjWMm`RqIJ{16a9`WcRYzSlOSLB7${ME{9)LLnWv)9K-q+`< z&jduwhaQ*QC36~o;Ni@#HQDtA>y_4>(@unxOer}X!b+l_bg~d_KVF?V0?qa zo!vsCptq0DXoH)*B2*wYXjRnry0yZz|6p^N3XDY;oL@SQ`Gmh3jFlvSLpFVT zTl(DgJu3^(tZ=HRpWAc%fPZpwk`r5*92)W6iJDbhs2Hj~MPllp<3$PXd%QQrH!^a` zC}gm>ou!m*mT`u^@vT?Mfrie&Mhibj0s6Rkr_G8yoZk zIV6IJktX!#c&z_vZ#;cM2>dgn(t#J~c409uRHDx)Zi+a_s#7JlHTJD;v%z(zE5J!R z`?pP)WS~SSt|NY$;qgSF<~u8^KG%!WU2>3vwnnLx4p^r03!I1cHlkpqZ;zLpd^d~Q zev%r7I9TNLXN7nUD~Ww3id^LIdsLJXb}>jY%xvs`6SFbOHnLhxLK_>imu&OgTMyTAs@w3daGAK4Swn~0o{t3_%hm9!mh?+q^%@7Ri=>R4Jj0E8n|^dz=t znS#5k5-D))guS<45c|Q|dw+lSmj9l;=Knr>ik_`oe73U={#uh@a7%}{X-tkRSk)buFLaXsi1R7mU`hBgRVfs>{%hqK?l>} zdlz;tCw|Xxf+s3$tIPm_D4TrgJYCo4?*bMB6Uh~oK98N8O19h)8g^%)teICv;I@ZM zBjAo{W6PaCo@Dv|SjXbV8%df`-+VRC*EF#$Qa~qKla2G79`2voN#oh`2 z)J|H_IWi(>brm$SJ$QF%UsTa9VWA1ns3SyJz$K3`m7kr}PnX6c#%W!{!E>CH?RbS! z^BX&e0uW=O%t$zhK%hD}9FMKcY%dxsd;FRyVF)~@N7^IL;bVU|7_Xo)60culN0G$q zb8%>@rKNQpFQ~+~JDyLNbkPWGNnKdJsHuEBA1|>|j?E63#lc{q3_luIL4}d?ShNQG z{@^*9!)j}1H`Hd?HwNr09~fZNd87KYRk1ZSM?%)_Lk1P6(Ffi5)JxDhCtX1{OXP+7 zfj_x~6s4&W>h~BbQDp)ut6+EqFYtNRdz<@7>kBub8bJD=`%OL(omsuW#N8L>tt#kb z0rOu0VTY1Ii-+;;!8@_UP=uIbo66a1M>ch)0rg)58=v|2_s8``v6W$FPfi=T?)T#n zb3RPP$-(o-M?$T}bI$??A+Ez1<<=eJZp4wQEj|##+d!eHWkjuyP9)>ro0(F7%A7yJ zSBBd@R)r}3*GX@)G~et*M?a5rTrKEWSRm*KQ5S#pilHyzZS=?p12&bi`iAq;dcPry zwiA-7>S(QR6II`5$EBh?c>`d6Q7G@tFT-E+OMe1UPWveNl@U@8Qb}FN!WgM{m}I-E zAjmI*KI4KUzv)9FK4!4mgLw^_ShcV0s`&$|FRAg7L4KtHS_w+5L`+;0pd)*A8gc5` zMiGZex(MeM1q0k^ZtR=FCNDp~0Z2+Mq2JY*d{7L-Kn~nJ%zQ0VIbeCqr)Cxc_FRqj zlbAgi?e*t$_pNeaN<~I~9`*MhDe&Wmz0R*%+Jex6!kJJ}P#kZZHwG{Q=f=@>2@UC} zl~4%46^rf&#aji4j+21WquI}Gim9V&-m#Z&sFpdDO&e63REYk1#C@B zavlhzk7TL|sIojT_qbh=+L$U`Gz||A=NU?$cpi&_wH8xW{ynU^KXErEJzbAS z{QZk4T4gXq$Lw(TZJDKoMc$u?q*AUHud|`RifmRE79&iOp1VTBw!jDLk|pn|tE+Xt zNSKlb!TWT=PZWAVc3{o^A}$cFU7^?poNB4kBXaU5LY^cVrKfHF2r>fs13_q1h9Cm3 ze^30bGd%Yv!u#FB)ywC;*TLlbYbFtita2~&g(^%qH3in@YD76K$F!j$SJ+>^#4>1c zkb538gg%jA>KH#RjYRK_P|Wm2pjUa()g7~3R$eZ)-lv=_P>$M{G~7QplQ&ATckuyC z`tr?t{Y><1334xQ@;L3$5<_8lz zb7IhXHPifm2fy1wK+_=E4><;4%U`Gl9XU`3pi31hsB*M%CnY5%K~a&BB#31oi+*B) z6Dw=-G(lce;oF!h08skhq)9Lkk&vJx4@1rYP!P=tkT9kMd20lLXZYx|;hiftAaxkD zH8LUqCmc;iT6zx?9UYwnGnf=$uTqMN0}fB0X79hwABO{gQP4lcsQmn~=p(~Jb_tr!{tkHQBkceEedSwPqs{qlh6=oM9~xX468u1G#ZTN z>FXZV1uTFL5J%Sym@@gwY7ZHAMJ_MBKm9#ZSI%uVuq4J=ETatvmG{Rzzq)%pCkyR$RcE5k&Z&t}>m@GO>grb-`A=QiOB3_}IEjf{*0#FSP={cf=p6clh1 z;YZ+iXr^scRlLaY1@S`{$P_Bvk4}p_&w#~8L|T0N;X??4B42qQ7z{HzNhg$MJ1OcC z+&BJ1%gW4*#2Un*H~b6I(tfws55U{a{Zetk4y_FG^XA97d0<39LTP7YYfE8kYkzaUcV5&sY)Uk|H+^Sm8FFa;_|oJi5!Eb;4QUf>Du!?VxFVwz|hQ&Y2Zc0Q6toM0S`g(#~$i0IVEnDk&vkjDdeg%ccynzG8u z2!Phjn^sW1{KBC{jnAUYllxLlZF~oCnY>pvANgkg4dzW{K=fp{*xaPcB{AcQlb`8t zZslZ^3iq}>VHKFB6##!&u3?TQk{|x;i~1q^`QAk%jr!d>SWa-gvb8d!IeT8c$EbIi z0X0(QpAGzxNKF-d4oeSYX~hM+s?myyS=VA}tiA{JS2X+iJ(N$%O&h-Lvv|EIT`7>JRs-1P|pjYQKj?{m8WG^x8e*ZuIx@14yx_Wf4Fk~$DGJSZ?Diu|4sjIaaHw*tszjZ*joPvrr}dV3^Bc)4oqS7e-74cDJ{65-O67jf|{7?L#j%U5$b0JrO#xu?f)R}{3J$429=~*H!cUycrj`V zJVSLGo8S3)d3pCeu=2Nm93CY*fnC)YQug-Z6d0Te90>!i8#Xe84SZDhUPyHTX3HDw z-CsJQF-#7g-M9uWdyS+%m$mP9XGs|MMCj-ek(w*b^xDSrHyy9tHF>Pm0?Ff9=UlY3 zQ&tDb>xJ*^y)F*P7aA`R%r|u(pI29=wFNk6+va`nX>gqzZaZQ(pmX+#4}>>2?>`}8 zlbNeFEi+d^3;ynVbBXhIZi_*OM;J_P#8tl>lLR5UsX3JhnSY_?m6P^d9}iBa$h?%y zBlu>*OnmdnJK$})j~^>1!FCiOKhL$F`25XVLF9Nbqrxs-c(B~PRHg6!+4gnPU+BdC z7Z(&5^C)D*HphH5`Bu%63l@CzUki$F^3`-evhdu=)peI1ADsj==``mDAA@nv`pqFX zKaBopm~KE0LYG_sKyPbcu!zMKff@WV5bg^WTJyC7nSXg<;SK~ihiKp&lmIG?phZU# z0qZs=I&j8~83kLahTDpNnoZLZ%Q`xL?b=2H0fT2;~PxpyshDlaq2*r)dn=Ty%{u$(I%_wvTwI=Da+ z3UGd`wBchq(__Hg_D=zT;KgAqZL64}C~p~FY}n?Z+mzqalk(~t`(WHd<#-L(-C1%_ z1L{vNe!okT_XhUy`P=9DK^D||bBGqob4nARJZA%dnTm!x12aX1orMmGD;W*zGK$M2 z2bhVuXw$>u_D}#PcrL3}%js3zV}gxeRvl&~sPV7SKx3P$FcmTag2QcKWK@AuK9!c1 zrZO@%W=vqH1m%&9PoF+PK}d#2j2WCi^bS-2`J)_knxDnWeiq^5OI(xOfINIg5+TR@ z);bEnT*(>i(8&QdS1)3KpzcwDFLuIwhovZL=jrVOi9;l^SWx|zW)#np%d{d{UKA!x z{SHgfcuHPk@v52{Wa8I3U&EL++$B(9nWA^$G*Tph_(LG@zR0=)7JCB9Uq61&xW?~l zmK(j8o;8yvP`00TAaC-bYHtt50f|MosI!1DJ1S$=&Bc+Z%?yo3eQ8+OA5n)?I=}04 z?nIWlHq%#xA7B~_wY z=EaAX%Tf^gX9RL?w#~|*NEUf=(P}yPd*nb{~udl9aaUi?u#@?2uPO- zl9GZfKw3a*fpmi)E!|xb(gKP!N-RLSyF*%7bT=#->Au6a_rB+xd#-<>kIKWWdEc4& z)k{c}ybXtOuJ)dY#IvUoo$cc*jwQ+Tc;CBIh~x$jZNXKOW^23(%TSlYMo!%Uy>8pxfO zW_Xk5`F~;kKI?re-Cb-U+i--9vfl3uu%;ZbObpCVz6Qkhc>5jBAX66FJj^{ za#H;K#^LR$uB9Ur3T)*}e2U}hZQTkSrdSM~FBjmsOA{3tsb>i&R0{#|Jk>fGmaljx zCns|qLoctTtgxZgJEMe2kh)}!#N7% zJ9EEs`4x^#2Lw{#)u$)a$e`8!WNt-#q7<@Q6xObu|LlIWWqiD8iEXB2JgbN*`qx3V zVJ3sJ)3(@SFfYyie=sZlEf#-qWW1anD1BZftXyLuiMxKG$khWb#FSgt=ETC+V2ioi zmf>zC-Ba8f1bQLxcr>7K$U(}uQl!pOX7*kZAtWc~X9p4Kx-K4OW*Y?nNlD*4?QxTd z&PDwuV~Fj|RUp{LARLg|3IbOD#qo(TAQb~1WdcYp*q1kmZ!;^gV1dF7-SZOl z!@sNyG)+pCA^m@OlVjxY{%eBt2z1-cSXSI-J7jc=YsWkzY6-xR-@P>GR{TJ`v+fz zMcQ|PF%@ABe+0M5x1Zuc4G@Pb0^fP^a%8}A zc@J@wPmUz}jq|*V{_%P3r054BLW&<$e#uCixPc$YdFKHY_L4vDWbuEsbU%T`<8%>w zQZEGsg|EUaaVJXCss)+oFESJ$jgAX0^52Egg-JW@ey=f!?1pO$y(|BM@vUDgYCV#F zjJVMjEbc-OK=1KV7&yNPd78R;D0@Gjv&}lZT5Od@yD@Oy1^k7xmU{gW0|pEOU%1yo zl1K@NTHc)PJ-dI`rV8#$8bNN3Hf$fWzou1v{6*BZ$*T%T@6p)xz5FkZwlfuy^>Ve! zA0?>GWy#3kk%YhLJ6w^b_c&pRzP>15-Wp2)@;I(KCjz5wb(W(CUbj?Hf7dhs-GnOS z5ijwT<)Rij*lK*X4W_sRaWA6;)2RDTgxn5JkGA`Kvs9Adrrod(YJPTFDMQaoM>durPIA&iux$v&E# z9LsKho)aRV%?i;8TG;4C@8R*26BxzX)idE6fEh@k`8!sni2c$Qe?0h$i8wQ#4fheW zPu`BWg&oOCtrBbD_65U5H$8xfDT4%r^}(9}9p*fn@X@o*>_L;=^p%M1u_c^R@5)&+ zQeceBIE8e+!7XsNyXr>)6MNq(A`_-rZqBynu^{Q@265PMep7gvw#lE1QBbhLEuj(s zPZ-kgs;ZoMWOql9KpoqxGnKe!DFru|!1(vD_J{fBpOY?5tltK;!{p33=+1RGcgkjdKr^SwcuXI? zDA&x{{b-l! zyin;WZILdbJvDBfQE1C?Bh6l^-mvxK=6oYnFisxo%a=s8Y`GbZB3{70O~gs;g( z@@5is))t|vmK@zRlE3of?#}H{ovy!79E{2)s!Pywe7sWjtSpK;qPU~T%b)y8qoaG zcwooMug7QIVj&=xYRY@dKQf5x$z`tU>vcy^a4?(EB*EqJ8&a`5jx6ljaJV?GqFdud zLRnSV4Vsc6J!gO%`O~iG@0c6P_M~AS*f^OU9gz&R@$UaRCnoU!85C|LTKqIuv+0>G zOG1DZ`O~N!;hy$}UR;wzc<c&5)_OEL} zPMx`cYs~Kcq?#`eb!}Ly#oCTsisNIyVI*j`#1=*`u0qv>lrp0c7gjDSgIWOmb!tzr zRS&Xk*xXA<;q$u^lamQ#uce9wJrSpmqgYx6Wf{PTxhYcCJWB?&M&_Ee1oMqPA#5S9 zGE)R)EIKQh>2ekqizIaK#4<4$uwV;KJ|SH+kzWSbDNoZEy8W#!<8kMHyq9LD^Mto5 z}!8&6+N$ASFkUg_M;t1hcX=NZS0)vI;eZB zKhBpv7*~IFzTdAfIo)9*e1mxr<-zv)aLM>lZ*AR=uzHNQ8<(4TbY!ERm?TBtL$KFa zj26b*EnV3I;g)<{Y@#COZ<}Lm@Ut~F{6_Oz5CF1UpDHz$9voeC0ywfL?P4WfE8;Cu z){$bO^4)A#GKHT`$)ZREjkoO6?;o@)_#Fq|d?w@v;}1}PZ46(vViyjR`JFZw8%OzF z=!zTo>%#D9+YGI(2Z=S4xwAp(1DhRA#q}~;Uzc%nwhl&N^u57N`^14&<%FFO;VF;K(_w`TX~()>U$ zc|U!fy>6PlB5?*n;mPBcCrDy-_W4c=owzKgxQo6>rVMF9g4rvh$04 z<3*HX8a9P;BZ$}HOM18Rgs0V9E9ccf<;|oE=A16EZmGqZ>5F6S-!lI4=d_0@S%4y# zj#}g?=6J?S#zH3ZcN1xI>l2l-6$+G;RlIr3Z(8Bk3gU?I?ze}08vlbC7u#Fu@l3h& z(;ANzYzM*BuEh2PL+cX_(z1mTeTerhJ;}B0J!aWAAmTekRiIh_7go$nM$h(H~_Ovg%}oBG!<%BZn2%zyX+>d0oAetxJR{c z)6;i!3=Zx^D>31u11kGUJP7*+>Q)96CrN;uA2yEA+$a&moSK-+ilE>p@oS2b^h!=x}9h0RnerCVHRK0g)AMhTtSw=Uwo3*#LVguYE<&@oj`CVqd1EH2` zeB`ks29BNd;qoaa-ffWcw#~}!3@wm~@a1c8F!8NbSdemhU!p<7GGyWisYLbbPhYuS z-JNXTtonKE&9aj5?cp$ni+VmS@mgwg+?n&lKiMK)b8=zsyXyU#kn+veA6bjb)y5mB zJv-*lM=2HGCR`$uS7YcsJ;XTRq%kCncxRs1_=>v-G3xu5 zr%Ooh1cC0yErls-pn3XK01`7kqNP5_v<;_Ke0y>g2(XRJUe)Z&6nKqVCi8s z?GNKdY^InQyug|9j*Ug7_12JOkpHa&m7Ek-et^}NxtTNXM(m(9?Z z;=;TUkjm(C4R>yhK$~o^d>9->8z3xk^?QkDZu*6fGwC|XI<|3|fB_S#gy z!#NV(9$$H)GhwveU_mx&hAD*~S^rzPSdt9{A^T-|LR&kv4uAHCVoBH?Z2Ew2Ff%-z z9$m!qXBR&DER+qL@?V^{`8>+3y2p$2tPlVEkaz`VsM`T3MrIuh18V9AR)LRw-`FJ7 zf#1=4BufU`Lqmb|A1y#6CExA({=ThNv3}z|P%2%?47q!Hn%NBhl(e_9+TH{e>ecg= zbs`%Ar5r$K6N!n9%{^1=Xck2);`4oHvUDX61~YTB-1xEK zj0uIi_#pqLYPRjQNf6s&v)QBhQmx#Bm%SXYxA%+FtczwY2F$)jvS60ELOewh=@4pc!OS9v$vLZCn`S!B5t6fC zEK$C`Jl2czv3v0|yaOykGaMPV;Ef~IB(?J1(kQ}_HRNYq?)PiA8`Is6;LHhot3F7m zETo4P#+5w{mF9w_)RbEzpPeTKY7G0Hvaj|e5)a|IGye`yMeyVET^lTpmEJvVHg>@i zcTI01mYA97i2Y*UgE!jdBh{82NE*--yx5-TUQ*c`5q~P3II*HZWm-mqAc|RC?8Umx zrQq(Ql&Kxo!&-O{!|>!r<5c=CXJ@-3@`*DFpKEmS3kLWeRh?nmqSN%QnK>PK$}67e zvZLHNWCR*4E}$m7f#m&4uL7B{JsC_aRT)@1s(&q{!C~{x4zPwABL~Odi%uugVVCN^aN7O`-jIkP=FK;~S8KxFH5{=0q zWyM{KPI(TJ1TH74@P7kQam7b}KnR=O`?OlOTRye89WHmCzBC)`=d&2ess^fujj-$E zohdj1{N<@?o4LyZaNHedhFK{j@i2R>bm1n4lX3_<+1r2KnW?sI0to*UsHy9BK;5vW zH3F0quTBmQn08lJAG_aNo=Eqe^8u-15nyY-m<6)Flxp|h^eUg76*A2s1~!t{v>f_g z5=wtiA&~3FU(XKtnc|YTSF)6!IIj0F>5M;c-N#$6BT!|iX>fP6a@v;SOTD%R|7r!h z1}mucUJHOjO)(K&mPPa`V7}7Iwj)DqPqV3k`Ak*WuFe8p2yxjVpb?_*U+#2d>gTdw z*6L4kCcip!ee+9wP$}Ei2(r6DimEYTGAkTSz1@qjgH?7))K%amMAqXx;qWs<+I)G+ z<)`Mw$m@6beC2((^|cme!JmXzy>4#57b{L*ryxOz!g~@oqnk8(GI&hzR0zU}oT#~P z*=amlhf}S}M4WGRQXS#9D#_`Dw3u%hy-;!@CNw~4Ny3qlQAE6@=Yv<2MwuDYs8W7B zLUpN>YI$0Z%U%$FQ*nOfRE^NFAHRCqq^lXaQ>C?PC%|QwL%ZVI zQ$A-d0Vs#&T!JC7tril;EP`>`Y%%(FbxCGw1=Byy1!d7;Aqr$+^Aa8~x2X6<9usjD zDJNM4bePrnug_~b-)`V)3{! z-Cm2wISR>Tku*YeqCjxdRAkV6t02qxGn@`p42TO-vaM&TI_q3^FD<|+gUT8s;_E{i zy8+@?ezb860HIY-{3p;eh`b}>gd&$B7=1^90wzF~z?15_Kdb_x!;i)5w za=))9FFu9z6w}2n5Z(@_(w2#kw>%G(BjrFu?|uJr(_D8~*i#uR@UW+=5^88txA``` z$9ry8$mj0^f81Y?l@3B>>CaZQO~EatG+)`@)_!)C|5V~8%%7sqUnPWIQB=ffel|6; z$!Sm5aLL!2m4^GSVC``O&UFCO{@1%EzVu_Mi98)nPbJ5QZFNOF7}0(-$y-H8s+fro z;pOM7XhKt{3Pa@!$0R~RLQ{G8-Cd~fi@BFD6H$yP=nFR3MB;YB>5EIuLhenc#O~rN)(^- zWDTi7*b>T$0+VPLU(zilD=4(KTSz86dYpXcEy81=k=|<29_F05&SPQ=T0^IRG;#b` zN=}oE3AAtVIQLy9a(6VXVu{Q=rWDwrvuR~8gGLXNFG}S}0?s>=hev=mng0@8QC{w- z#m86u2ar4}>*leMSt7mP*pl-f9RL|Oaan#`vSP?0&pX57bMM}aV~VM!uRVAQ(D6V3 z39QnhqIb=8u~`B6mDEa?&KJI7TnvxAMZ+9<`$`JHOb!sgi*H3hQ%?;ypdz82fwee@ z)uaMiVuP%<02yAE4$UGe?*e*U*wJcY5D@--3Wna9owo*_4d;(R|kC8dBARYM#9qo#6sEv7mb#G506?hx{75&EyX`!V0SL zZ>&Edj-o277MvtMMCb@S)Ld3J77+OQ@fl;2&E9b{w2?qu?)qYc8jEc?+hOyD^T&Dx zx5cXEaEd7x`Gy8?9|<<$S|X#vaC=jCIFm~J1ePjZT-AJX#G-;I=0EbCf#IifzW@CO zLfjw1>mPV*|hr`X* zDE2e<^lD@)l0q3Zjv2oto*Shsj@Ma4V%4-1+HoDEs9%W1RexjisY0j$jM~P2A*#Kt z_`LYNkvNuu?+oGy_QzHe$P#c_rxm*;kO_wpBrK)~;18jm?(U7`oQ8e@E+=4fI@khl zga#17wF3*yZK6}wz`#KE8Bl8T0DI>(H{|C0(D(=#*Aq?;K-#jyDy9qt{nUq>u*b}V zT<_aZ*;fSe)U##3ri1@srJ_K^QUDdkoSf?OK{=;_O1AH`2oIvycqyRUcu5HOSqa35 zukG;d5o2(lxr@u-iQ+o28+gB~WO;7+eD3m0B!bt13cf64- zh@VczbNZ?3fz05&;-8(b^K%DDwvzFQLi16s9n+1yLgGYl{=>4{UMOH?Pur;jUBaf$iRTwGvvZ8tz2tKg;Cc;v2@HDc zhB@Lt>CKMW_5Xh6IY+dG|nREOX~IF#Ax(^t-fe(*IwO^I@PIhS5Ky*v$+3-nW|B=KZ`?yU8OWD&F*$I zXZmDX9of_{)`mEHj^8Jf0-5U&<9LnF=G`Of?Mf7coB@DL6S>V|i=}UVjpv7bozeJh ztMc$6u0%P-z~SMI^hXg8_Kn@c_=21>c^3ItqsGexitWd4tNnH(0tu^sRQ8750s?zVim}d zV3z9@ad0YjiHj>&Nk4nUh~sE}r9V978)&&aFpUE9Fn<){^6e_ygeL+5By;r%?P0`x zTy6(k5j1+lN9(*w5IMkt0KwS1nEto2WQLImU} z$ccY#%4@Zl5}>zMuG&#<@F4Ctv4saUj3&j#uvc0rd#05|$@H2^T2ec2UI-pKGsjLy z$$`0rD@zacp1=ejuG8-o^;=1V?7UafkujcykFn(&aC6)iHTa$cPvgk+I%xL$f^rc zs}XXaWEkmE7&Rde6dMXZANcjkxHTfEq~GW>$TV-8ZA0cOp6$4D-5)NnetB(cp^F?T zKOQK00+$|A%Kyk5qknv6+X`vez-()8;~KQ00$H*hCkcgSX0{>AfEPNSaaAo=p&psk zOnL1UhO*Uz&|o}{c+hS!fSM6i^iu&cm#d&R>+6OO!`Bz>SQ2i?%(!kJ-gDR>a za)-T~-y}dRMjuoAwDw1D!z)z-^&7hJf&SPaUVN)%wV>xi0osIJ(+qJ0GNjB7>8u6^ zDmXo}+&a(v+miY$jr!yY|5NI12&1j=(oJ6NZws@?RG94#_^JZgND;%gC`;CKz8y1q z*{a0gKL?nosfieU^6P*WyOyzwFH)+v6@xa43q#~8BBvSdE<4va9^r{gh<_0>a~UnrAqtej|D>RP znfkS2y`o>9RMDX0^hEHH9S738ckk?27C(KX*3K|4j&jgKCQm7X*WgJ(Y5XPi!|kuu zt*>$JdQMe*U`E{ zGI$|fPEAeO8*1k8r)rJ^t(W+{0rNe0O!>|=xW{o<*ShS_3x%KV&X8W5A7*O(QZH;O z(5pXX6PnMI#)sV_^ac%Xhkamdv(gexk@M!CA1zbmX632;jtm(9(I)^nL0`4+ozK++ z6m(Q~cX#iY6FSb_rKNWxQ&Sfkfa-c|=;k2INe{UJ!f7h1TMSQ6xd^f){{Xb|A8M>- zcr1+B{EgJVOU1qCnpZybXs`(qW@ z1#E03E5~fQXP!~Fh57HtYVdp)Y%$n7vjwAv3rhuG&&e)IYod-*Hw9k}Ef}|F4Q>v{ zTOK`?gs{P3F05Z^tt}G*L*(Aqe1+<>vplz@W<3&#tLQgX1yf2eE!>)VwYIbYjIq75xMX(YmNvY+1-|0b)DN?0V6UTK z;Puyoc24EIJ&p^u>2Wcb-|i*oycK`4Ih^^BKAV3IIBVO0UAz1#=I-7e&FyLrQMmWj z=@fXqU7LW3$KfA<1=Iro%l?3ax+I{Y`lt)aAod=n2G-j1dzd;`r`kqq_*^QI!h5F9 znN{QMHUQfg($dnN3;W)F90v~dV&GKAxdSDH0IuepX5jIu16;q^$<`Ph=Qqoj^gsfe z3dq{^fh&BFdT_j@MgyebiX>2J>2AZWi15j(0n&8gAbawDi4b+EVtpH6N5`sjo{0_( z6`8F3B}DP+#o&}fd+-cZ3qy&OwY5Js@n56$egP&GsY8-|K-BtYi87%GzETeZ%B7#) zo}|#d_Sx&=!JDaa#bKZ=^17pGC6>u5u(Yh$OX1gmWGImLlaMex`ux{!WqX1nXHmoC ziUBYiSDDU52ELK^;SAH$_cA5vW*_3=(#&w>SelANrvRtCE>@&`FR40~#&|?Qr!XB8 zmp)Nl8xST8^&zOv9&-TSR+HzY)xK(yo)-0!80f*F6{hJ&$Y-L7y``0ECFp#ncpfs@ zLL*Hs+0TNW#bdl;8ceL{mNKD)1C~w7vKdpcgkWN>Oar3tNq^WPTKCFb z57s3(U-ZjAVOjb#oVuOivo`YAhne`zH4$~-DbcIN;{lA>rf*Rn14(${>ic6zOFVk+ zCr>+j&g(>yaNqJiM#NJ;q3g^Vu}kv#XgS;dvDK;6FIGe!us@_$W#!->8PBo(fBx>*INrgV6pRE9io8t zCa-3FcV_?KWSe8P*8~ke`ugB+e!IzKpEeBYS>gzz^||@G%mc5sjJVGAVH$cR0gk+D;DeII(IIZF9Ht3Ygj z54Qrbs*j1ouxLsus)B>-3%&yV-9X@sdi01>7thl3^tGQt^4?GPBW2(NTnr<{Mr|q3 z(tue1jil7+<^7|U$Y(FsK_i4`2=vDHmQofCbuYPRyXLVqKajJ7uuUZLl*14A^e|xv z{e~JL4SJ^ucHhv>{Zdz3&k7s8;Fq385Cy|Vs|jyA*P#%X-ChTeQ4qw{k;GfARG{f{ zeu?M*h2W5DEh%ZmN8~FHlIWpLNhGip6!AWSG{!dtbT4qV3_U?`-dm9A{>ioQ;L;AF zEe3~Hkn|LT^Sx~n=$GUUb6GvPK0p+v$5K5iI}7WDnY3%jEL97GLPHH8z86%&UO3|I zb&;i(1an^tZ*$r<>M!}?#54e2)QZ5NxI_RhQKGKn3I|;Y)33qYypEdQo8jlLR2b4I zG##Ow_MFWwDa^`d>e+f(%rCX8U(NMKoeDTKUJRxTg!K(c{(ou;_dIF3#^HeP+9x6|V zI?x1t@1ms2O=sQ#r-6K;a`=qmf1E{Uz{d%PU~*X1yIj~K`J8N->ONI5Nk(73rSmI8 z5@xPv^xnRA5k!*%7XdTAhscCSS4BV3y*@NcHt9ZeYq9znWuZOLy03g~wTSc#VaweI z&TL2_n+RFSdPS9dKG8M>H*g@_U7rvo194m_T>3zm=@D0HDU)gjr#6pG&|a!X+vK_J z11e{MH$g+L&Ng%sL%`P<2q(Wpi@^(-K+2M<=_^LcWm&CunyeGZDG9~cNF3#IU*-pV zCD9N8C1oG+UW5G#ZoY;=$QL>xAbFA~N(Q@GVC*K{C?%0wK^*A%Ya&*%v}KQgX^y8! zHBS-~2dA|=IxdD;WtLh2h&M$0z6qANSUVmgR37;Fh}k*o1$&%?El-vfaq=qMmJ4vD z*o=RqjH1D9`3I}Ad@#Q^EIJ#9$!+pA7QI;Pm35$~H(!2Qy9FOoUtUfT`-MN)S+*tp z7Cxu&@L`r~HxMAg@w)d_p4>lHX+9h>sNe&)_91~w!RbFs6-91R;78Y+Dr?;Z?{$FJ zvFGx7Jpsu=pBOLYsfb!gacNbi)-Yv>AVUQ^NWwQG$S^F5xcJWX0V7mYuQs4SeOx6f zFaomD)@kBe5h3^?nIB{%^K5lyEPlszqvO-yY+UAZ1Jul8_@@;a|6h8S9rN%gYQ0+i znaY_U<8GS!l!KH4%*w9F>cx)F-6?y{D_x!MeyP9T8|v-VU84HDbPW8u@9Iy{-$-}2 z!OJ-nVPfSmR|;szoVQ2s;u_nF;L#r8ilImuXY1I@OSbA3DDbuspmv>t_wrN z{PH-kbRo*1wjko?9E9x_YU>KvP~V$NqFTqH$w73UO;Fxt#4QCb3P!q1rZxHKC1He!#{(8kttV} z9d0-)g8GL-)K8XjG;r`foFkT|9YKjCg;LWqgp3fm?>5P0|FtIu{%}fir1ZSXbNpvh z$o*q*`geRuCg>%mui_tQy#J?{kewntJ^=gbwCf`z0zZ6&N9b{KLaX4ASBvLD&=#ki3fm`c)~%@t3-w z{jHaxn+J)^2qs{$?1IQOikmubs^v(ZR@qp`y-4|{@a(Is{rCL4VSg z`7y5UK8fnWz1?r=m=)<-66+#S!zvRTV-X0obFYd1VD3eh`?j05&}*MCDm~^6aFHupn?@Flg#l2?*cl24Wr&E1(w2JyraEjVIu=m2|TMI-m2D^koSj zu0-7g5>um^#zPV~zGm-M)%d4<)vqTRLcA7b#NE*%%TJstEzu4RmKY0kTq)~aDkTEZ zbz)wckpQ87G~9#c)eh<_n})#A#fto+y~(BU+nZ>RH&eAa%3O5*qhR2>J%I`=ZR0l4 zO)p@Rn5E#&dVkL5xWXrZFZj0{^~5Pcw4(p5v6-FhNP+`XUPmylE6BRxDk6J^P;GWQ zjP&gP{npR(EVy;}oqM$fWRDqs%;*OZvqrJFFZ?W;HVYOKIZ~~Fi~kChX+@-7RT;M( za~;$&1xv6?`+OT-zISAqdsTrno-nX(+LD3Kw`^MMre#8Wum1uX6zm=Kwzr5sL9GZU z&Syi+PPkAEG_=G5?MjwzAXN;Eh|G&=yrcl}LFLv`Nm}hOd(Zu}k=}a9kx~vTfOQ-0 zSO;fCvlrGz2C(4|)%*+umSi{gvEUHt2mLATSdJU|{$IcHCuj*-jPPeKRj?e<@c-r1 zg0RJ59v=LTzPsH%izdIh5iuN0VNGE;N#GCxrpc(ElI58O&0(99!$EP!8Q%baxYY4n zuE-c%(i*(TBXV=i@ua}pnasFbT^hLI)f^IoSJFWY<_2fT0NUPM1Dp{Ess;))Bzw$};RHiXd>p|S%?tNC6d9^7C#Xv=UB135J zUv^8|YjN{(9fv-H6=WU%eVeZdW!&PH0be$;^Xw|{7cw*7RH`JU=+`;r8H3n3J@7)a zAD*7pZootA{zw_8oPNVw;{SZk8)*#bwGz{Zr`er(dmn;B6)E|xLu*$1OHBt%D$GmO z1$qEX=EE<6s4VtBYt)qELVAhxcw)N^2Lh4Ics(h_0JBAY#OrL+qf_bQ>8RMdlKjNs za&#(Av&4y=-JlWE*Vh-qpDl`5Hu+O-W&5G`eC;;(Rci9eZ!AT5Dk0*5S?vxjL_qct zr^{ca(Ol(+ciY4GYTFv;!5u(ut5o+!3$b!bd&A}X8N+3N=Cc_`T5H=ZmDWo$36<(~ z^YwA=K}oDQGib}s#mj^J9TT_1Ei}`CbUZMgZnp6p^VzBC?%aWN^5Eu3DF(y!OLXaI z&*i{{;O2J@z0`^bV-w*KC)1f>i<8Zv#Cl(Gks#x8+8Dd%U(Z7eS@ zcFm`Si@NZZme@UZKkc8(fqUv1@Gqa@Nnmv=t~eTfk48@`m$oTEp_<9U(rxFqP#!+K zY4Us{x1-F5vVXOyB=jJZD0i6}Rq9R&wO8&3L65~@(j2a+wL9y$ukD_Udju{!Y@)#6 zb89Ag%k(sbbN+1(a+W+GD>aINnu?Nq$fIzWgW3*v{eF z%ijOoEnC1Oo9on8=-HS%A!E+Qtsus{uzqX-i7}QvTi4mik>tv&6Z?&M>+3YWX8MA_ z0F=`GMH(5^`Z22r->!j(r~Fp)PV$Mo1bTv}Eq}-4lxoG*CN*aaW3NPN>@HqYR29%g zdas;1$G=dgcpmocjiD$K37di675@GY*Rv*NoZ+D#nHa-)W`ZEiC__6t>20zATUw)A z*xZ%tv)8Yw9-6XCjfJIe>wFGz(4NmRwI$@F2h$1ME7V@VI`I<>d}dhi?xv3Y!Q?$t^VRP!m6ORvretz+Zo3NJ5jP<8bg+TlJ(F?@p91E^~i zB%k@c&L7;n?t&gldRx)%Opnow<(o_x(YHHu9W+JjPkJD2BYotYl|A7j0(Dg-MGupd zNm4*^`K?oWdtX<^AC>rTmd6}bbG0abqR)?4*2f50MSb6N-JS8bx!b1iS+U-B>Gtwk z89&*4xmpZCu9Yjsn{+hfTUWRv<;@?Bu+YiYcb{$a-AFE@@vX;i3#;t=Gg^qo5RpRV zD0`{W!dS60iJDNP-w|8O`mVHqNesPT3qll^6CKi+Dnv4%A8ZuV+;FwF{Pm&vpXDPC z>tI~6AdzX8s6>O`w)O#n-qXjB(mUP$ZmT-AFKqlt4hiyZp9gOo_K-~L^{#TA^` zkGz1aRWv9J%+njby>D9PzcitJD8{Re%rM+I(O!#oyW6Q3)4d4oN=p+#@5>5rka+6_ za_&xB`}+F4#`4ve_4M=t2h&AtNp+x#>B4hUb8|w*AombuYc%f&8oCA|j2P!?9bqa< zZ9z8x*kpwU8o_fE@Kkc-Wjr?qQ|Un#jGMW!G11cc`ua9d@@kiT=y?s|^htm|@DRj0 zdM<(t?170wosH}D0m?prPt5_`Dc{%2LK)hfKsMtW?dShIb!35p9V#ClOBWS9$!5vV zKi7Q64h|sXqM|4=!77&7*}vq-=>_~a4f~nK)JUQ!r<6>rZb42tnDGgibg}Saq|jtV zgTDXv!BTratCb7cBO7s@4faQK-($xTZ=gOwvafhWd2DXU801;r{Lfx^gNHRs;O?JczhM12KDx6mC35o zMO3w=X7E;9^UvBN7hxNrj??_wP*?LgEIRbaC^(}wl$1pYHCf%}%CzApG4^8Qgq5zK zx3qx!%?S||VMI#{(wjG4w^KjmE0<&YNgM>~puGR9km}#)S<>Ujd^x@Eh|B-!h;%Rz z(60h&MQ9Gp7ofd6?54Ffj^1Bi|JDhIznq#d5i+VKc)rx}(sDGH2OzLA^&sZ(3YYTL zF){5`TFR}!EwHa3uKpYx*u{Z68YzfD)mi*Z#JKF;^XR{=HL<81(!{^lnm*|1a%Rda z)V2Mg_lw@N)SqIAmfxh*xWPAROML~$u6Gl*HEXt6cr4EP{8h(A?f5;nzJG2@7-QH< zV74Zvfjy=<%W8P>S%~>nR?Waw0;S3xe)37u*u8Ddhy2iQK5#e_ZeTxcJynak^tm3gnIf%*K>Gz!#~k^?h^IlbaevD{aPsRlyR+prl|zVA*{v^WrSuEz zu)sOZGPohFKo-@>Dx5HP{!S}qzsF)|C1kit?%{{G2@h;elCI;w)%;d!sN~j$;_vcN zrOt$hi#5MK{0d)IbvgQ%(PCr|MLFMAVrL(ST?n*Lgq^xQXr@hTu|u>uPVOv#v-XVN79F z&5b#_JlU4n2K~MYL{094&Q1=Z4oJYnK3N#xA9Ak0rp!0EmrH=RSy>JUrp%H{U@txb zj2F|Edbm3XLyUoUc0LaUb8XL*jUw+aXV3hikbJzgS>6+Z6=mX&9eD&-fl>ziJ=@>} zeS*4!1?i^^V(XKRkQu{+NUYF__AaF5n}<%3W`+`y1e{o^BRdP#KD)JiQ7MYKi)rOXLt23a(y&AMZeJp4LzFb zNoUi?TT2-qX^~|NymyY;qn+zL7Lm&BQuG;+`-4*XrxE`Rrr)pE0$nr74%3{qpuTW6 z(g#Lrw0^;l*84f573oC;frs98|Cm+1;4Lv5>}+?&Y@)&aXa`(KeVV~iL7aa8VMvM# zkRVz3JO{b$MJX#FimQlv;ghYl)YQC;u2>ob)Q<^*TRo*CchyM z`ju3E?**&X0NHr#OsE)celj2ApuHdZmCN7%%zH=D72`>-r@Rt6mXsK>2>lcGa3T@K z&*4TFAe|mP4(>=Y*pY=;8LpDVh@cTTrEF+wqBXSLe!#fy&Z zM$mezVzSX*DJYF*2)_rhLQb`t1omRtEogc<|D7xz-l1 zxs$_cX!9<&>F-Ac7CeB?Ot6&nEnas5TE^o6t>-G9?&(nT z1{t=v#KX})6?Uqke{(W>5GwFxqXKj6kzU7Vi+A{fd-w$&Nr?uO9>~91OVH=fO6dq~ z9}Z!NzO@vl&-j2``EwpIqSPbC{c4U7>^YyqE&l(**H?!{*?nsdI4IpE-JJ@;kfU@s zq%=rNN_P#?AuTy{DuN(gf=DPxBPB{mgCIzW0^c6>eb4!wbFS~YQ2%(}i)Us(d#}CL zz3%&7Jd=C`WI8%Kr!ImoZQfDVkqYjK+0DEpG`D0i^`_>}jY_1CwW*}CS~2&jcR7lh z44(RRJ@bYK=3K*0w3b|7PrO!}il|AO8%3KK1AG_dXDM^h^pgpQ9r5qdh`d=5o>(3w z>kiy{t}@;mbtgMcDZ|}=^I3?n<@|!(Tn&t)<&x~?$@h$ru~){tPp>vKr|pmLZ@a2r z{IIk&i>~-cFg&IV&xeMirq)j#7~3{(2&OR}oCs!sxgYq?TxJdi+em_8#I)4m$fSu` zJhr*8FIO%2I9dWWNm@0WU%$W$Bf0c0D&seLVgI4XurP%^_NP5fU+9%?XyJXzQ^(k_s=C0)<)nM&#_qH>L7-}KWzai1ej>y%Z(9N45>_J33ncbkk5 z@_-}sKG_BV+(hWI^S+o3UIQ_B)s$U&)y9O(aj7$Gw?AbQl#q=I-tX+G4w3}I!niTH z{=&Q8y-7dnJkTiei&EtJW_;Vpq=jH?p*?P5^p5;Oiw|w(r75FMe(Ok5XN}voKPU*P zBJe1I_oyz}U)vz+V?5(Q#tJkjW4`X~9 z*c3B+p;haB{b{vlvH#s9el>5Yz+c3Y$4vlkA zvo&q=4tgRJbe3e*pD-IU@geLQQSj$V{TJ_n;nVTne9L!Q;6%0nh!NJrUKQw)LI5P6 z81xdJzHLB}TdtDIQ7Q;7mk?kh83g81z6Y6V)=O{$e+JIZYToB(ULQLzFMiqsHp995 z%G<&*oNq_8w_tno4L(!HRkUSxt-Ik4{dlpYvF&T$X})P!r$WwR8E=Xv4j1r8q){H# zOi)|uF_#kv6Rn@hgw~ZOu=faNL}XHympk4RWGisREQUnif0?M~i^A84g5vX(E6j6_ zpt`zkzPoM?CYmc(ID8)pg%&u3;Q~)H3h#$AQFOEJeTFZa4YW}8 zhzt(;V<#Et$C5_hvtQi)1UsR$VlQ4#O;NtN_E_=UD1QNqN!925{pC>UpFS#I`Q8sD z-?}TIf_pjEh_~}qezSBWQ2@NFeS!OJ;W3x-y^lYN5tEQ4pk_Ua)uJ9&XcyA-V8wM@ zyWq|(cxcch%n_fh4y$@IG*qYzUqF`xBzmGLE#86W+>1k!9qdD+3zuysZ`Pu1h5_1;dBf8#yYb(44 zs8-G(_@ef~0abZFG{g#QVRnIH>+}H_9EIMe1OjLf4{u_91~96N4x>w+?;|&2Ske`bJMt z1~3w102o%vCKW1i^hrRSPOMMr-m|nq9LC2NtYG?C>1xeVaag018PFluxm_h49rjK#@7^w_jg6ctLcw+^*q!5u{;&B znG}5`l;~&Pcxnmbf0$uAX5;rU4AgL3*t*pw9Y(dJy=%vt=hKqK*ao&qI%NnCsemQz z^{@aRh9nqyTPm^;2h5+u@6wXfc)k?4+*9BDTsSxK>ufx9S&fMmvad#?6`VkX!<7Z* zTzX*a=(;Dx-)#bW!D~>*tyl}eE5MGgtbpDd>^i+5@1s8Ez#tXk!6f*Uy}LL4!e@?d zw(c6uy~Ta}M8-}l!DwjKKFcym&bq}b6nM2ZrgmXkjEfxy3`8aGHY!7CyY zY4Zz8SF|htBXE|IkyKLvqcp=pTL8wI5br)0om#H4kv5U7X-P{ung9}b@A;wtEyUoL ze)M)6U`i6azqz8Iwjz1c{ui~ZjeJQy*Hr=rhmhT!%_1P&y(q}PF3y9q@ucfE#0rCM ze4B5MNT3A$rNfTpYB+Izr66Z6DMDsr36z;EaONSS)Lld21YvcwDd17e_MBZNV3;x_ zSBHbn{#tZju zLToqi)F|M&GgNA)(nW(jW$%2Pem*;-j03)~{jvx_j=PbLwv!U(J|`STA7Wb@07|vE zrjE9O;y37*-KSar54|xgP;I}qGL$MAlDPZn7eD_{ZyR^~8V(MQaMoAhh26fR?F_S5 zzH{e0vvtq-?pcc9SQNCf)R1-2LE1b;3ljQC*k6Z>zc2aX2BX92;i$prqJhxHL_o<^ znfQ?&kRJBhKvFQJ-2MqC_%y3HYX_uhU?)iZ;z^%4=&BLJNkZ~~gQi!R9?>%U-rLzY zN{{RQZfaImRuQ|GfkEcGr8i0`e5S9)S@@*dr$aj=Bi?_J!*pP-q3;TWNRqcQF_#j3 z&-jQtl;Gc;jkk!4^xFbcON(w``V|LV#3;I%uZ{XCgYmtYFTI z48d@U(-(XrO1al8fz4F6RJNiXlZ2E+nnSEem*!fmzc6W1B4^51<5^7k{H_U5gkh`u?0zB&Ts z6k!S-f}~^2Sa!j_+A^E_PNsGIj6qn0e}Ljr31m$RM_2{X(r#z#>FL=Y ztPVP6OZrqN1^T&P6NkYfwye76GSB|u0_+0~KjpN`XI1wvYy5+b`Y#lK_h~0SF5&Fa z=k-tN9_xtt(S8(NDwJFi{_DVo0(loVj#q+iz&?UQ(Z)jbswOVnF&aXDX!*RO3`|8pyeB+Z}mir~mjeIxlg;Q40WhC&{|>8P09bjZTGF@KqLojoQgsyLuqWb^%WMUPx#_+e z8XK2mvgma8^a$LL8t34XnrGqTo75J%A=ZQ~EOrx5RQM*2ymd(koB9Iu8kWD`&-ON3 zQj!a{Ns;Bv{wA0F&p<7HdmxH!O3M9HEE`i#y}0ywK1=aWzEYnnZ_7qcsnh+j=P^ei zUCu{*F}zwNp|ubh4C?YCQ8#WH^hV zKuK!YP5rPN%p6Y7xB`mRU+ANO{QU#B!Yuk+pVV0?x@$2Lc}LadTGE@E3HL^MY~lvLkCVoit$l`}nK?QfGMK++W%pO- z4fN=)cHzRCYoYJOz2rc&5u^JcgnN0dG?LGq;3_-li4ir$u8Q2(_;b~uhmnqg`|yzH zHUAY?;x2dov8^`R)%sUB9=~Rw@AE|_aVFi?;h@jPXM4<^c+k0I`~4tIuAD{#ai z;*QTnhvU+@iVc6TXss%L8IX-}ltoEpzsQi7|YM2g56PM>Fi~t0T0d(1mlsi%m2tiC&Tx8OuYG8Pp z84*(=X_%GzGd7{Ca3*AJU!w$b`N(^RqrsZEBNLpvbLZ|%Peh4L$a%`oAthH9U))$R zNw^Bti2Sjgn%5wDt!W&<_n35^#h?M)2`QK zEy@hCNQaDwRh`K&2Ve0T(~CP_tPHl;h%uSCk(yRU3;=(1;?_m119(Z0BB@E@_?8~# zv*ZadA?xSR)aOQIYO2m`&9~?U{`W(46Qy@)vsofi4F}SODH9S9h1@7QIeNO3C_{s6 z1tVia1p^}^Mc|~bU;zGr!Zrtl>72;$@JuKc_%|{#`!x8Q=*jVZEtqT85s{JMQ;|6G zv1VP+%s?Sr=`=Gd%XHuGQ0^zis&Cs+hS8Q;^lXJf_vw*<{z9d>wqPxrHC^KL&l z{_MK{K4wC(^*UGiV-Yue$t7$q6~su+Eyg;I;XC~d^fmtPXml%#7=WjqYyO%5hS72@ zR7X)m!M%KiOTUHgJ^y>RgSRT}fybl-IbzZFO0cTb^PXv)T=NyCKT&6&ooVGT9EZ$x zu?qvAS_lFv(JlZHxo(Uy1LY8<{X|(W5MGpq05KgknB3C`U}>S?U%nzvGsKra^Ih*H zSvQ>adI5z6dj8qz>FHvk?8WZ^eRiWvhkFZ*W@csvjZTK@(LjQy1j^!4KhVSmp2M_( zXNNd)k@%r?bvLJ8+)o4!U>3lI2;7;x46?y|F*^Y6RSj8xn|uYBq1*NXqILiaNXWEte)TVwhFT3(Fe)CqRgw3=EU_5F;eF)BY%vvoOOgnW02 zL2dU1aMxbKc>)EzkGi@Cf-|{N9umvDUnQ4Fk~szg7Xr{$z-bjr)_g=Zv9;E*Zak65 zl$FEoEIi?$dHk8#j~2%-4Y^E;T=C1x6Y~oZSrV?E?mcJcm&_3!xSJlK7@>ArmF&Bp zTjP3ZsfrDr7D>UXaz6D=>wI!u;rjb}*cSKp7`YJ?00O51La=oIIIdPdnIQ(IegNqAO?UU5lnDU=flM(CI`NBN*f2hXB#<(gNc8fp9D{jD zNjGd%H@_FrMO9Gn%O8LSSjog3I7E+O-1HuV?W zjbAU+*iLVW7px(2<7QLW7e_9nN2^?##PcQn7r79=dGH_4R<(+pa0cu@In^pbOuTNA zEBzV8&V(_9W76&`{8FbJF&?uf<@c(?7yxY^8&g%Z0KQ>TS>E6@x)nEw4M-P!?>3)- zadoH?%CF&F$6#b4=pqu6le0aUI^BNJIa;DZ7Ol;4$3HH0>g&g*esHPO+KsWOXe(vl zl2`#u<|>e;W+3#H2JPL(jpHfK1NqB+c4nAk9L5xXaU0ch?R@=Oy0+g;>{eF6hH0L@ zCPFZ$t-MJAk(oAIlEaK-XF_~UOgO_zuy`9e;$G}GYxogtzhaI3ySg{4+WG>cFV zKRugxaN7(!SQugmOr@!#$6mbfOTo7tq~vSrwyN; zk+>V8u6P1CdK6^bnaq}h_WQTp+|NKv1#7!;Q6$sAMb9!9 zdqBTT?!Cha=rM$ZgyZkF?SK}4n2wxRkFRWY+TAGdP8vQ5XB$xP;t4AP+_dy1BaqHy z=b`clLE+&WS;j{&kM4)FDwyE*ML|g)AsLaLkY8k$2dD2jM&t$Mlsav_5!#yP=30lXIq2TC~><0~OMF7xdT*8PolzfiPWaFtV_=pxJ1 zF;&whI<8(u40lNMV@y3)^e}1jB&hVM?%sHS>(qFYur zNe)~cL+hA}F$l%wzjp^4F%f2PaBwoXpOXay$wPWr9i;Ir_yun9nYPyJR?DRw6LY2& z=L5(Ro;E^E#T|QtF8l2!;7mlfgilg(mMXv!%kK6D>2-nmqdhhe(E?q13UgMTLv1TT z9vFid(zc{^Jz?f_*D>X_IlQQ^Z8e_w|e_ z(+>9%Osi6qp1C%4%1a#TI8=hbwy@Q{r*8F+(y}in8`_9%>yiBZyI4Qfa^w?^XXl6nKm=9)oZQ#OVr4~$q*R2{?qSdH`lYsC~XN0 z--5S#ZjRPi$kp48-ElZBe#ubOLA<_9!eZJZ>pUm&^mF}-7cbblfbSu1?)%1uh7Vw; zK)x|__4u-g>UuDjQemDpQpOdsEJ~rTD5d=ykb-2=LQTZrVC*K<)RaYN6Z^$!ky1ky3BL=ePvG%WCn)wK-nP$wLqcTMow>GiF& z>MM@4j?X{VQD(igPFakEMin@Rc{ls-^H4rFMQX3Afz4$5F$OQ=e_TG;uqr>tFD~|^ z&J!UWX>M9n9o$ER04-a;!u4yrv<3?Y^cI^75GG7USjfcNwv(=;1NH>B&kM3JS3Kn) z{20yejBx@gW01=$p1Y*%bRG{pJH!{P(u>R>URj3-(*SYlcAvJc)xiwe4R@0)P*M*< z-|ogFB5U8;CugxUs0rB|>asQ5ja3!p=^mJ);gr@`?yaM$Sg4oj8>VJuPXabj3o>i5 zf9ktQP&A)KwU94tKx5y`;0`q=jeB5_Yk}?ouNx_`OVbQd0Tt54MeHsUD5Va%IBQVD zbPeS%-x^~DR6a(3#6rtbRehfO4}WxF1l`jgXZ8QCo+0qvsq zHIW2c-dppvVHwYq`;Fc|Qc%-=IQKGWtVKtuM@&W45A+^VaQZAnplNL7kFOd%hv%RF z5E~%+@iU_^Ab~b)i?-3uNarBq%k_d#JS6AU%qSf+Hi3pG=s-;_J5RiP$AAC(FjvIG z>u#3*gvcV?$B7ona7oBAJ@zU@N?Dl>EY${Q0ZIl^AON+`Xzww z>s>!sOgxR~V}`&m=B-qf7XzSaoaJ$8JLxcwvUfMj?zULj*p#+XlhCZ4CWlw>%5cwB?UGNKP0Kh8|()<@y z|Fc9AY(h}DHbl-#yi6d9RNJ2hN!m)6W|fT0!6L620GS=VsJ&^{C^8X=k$M>mv3qXy#B}T@vyYXhRILR)R(g5&l027X)V` z8`y0VYO&m%w%WD?Z`)LJg&IepKzDLFz1hd+2J#IgZ<9B(hpYVlk5d-sBa9j8I?iVq z?|Jd6FjhQIDtsPAPmEucz9)!>FUiS;(K}$@6nPYsClh2V>e#3h30fPcw;oQ8O5Rp^ zm-(ynh&FfRe)HmJoze+tOqLLRZnjqgXwP-{>=P*Y9e|gav4BEq-^%6hnPUP>B7Ddq z)V!ci8vmmvDl-qapv0nl)rqY@2eUi7@#-jD*EPs8+mQf2)aEtU?5ER!u}y6tmx$_~ z8@N+W>iEpFT3qzcNR=_A6VK?<-CP;aJj4BY4)jUOjrlOD;*G@2o+%kfYtSK z#s+XKD9aV|-u~&P{PW&NiQqht^S|%i2qjLzsre%bNrSy|MH3Hx7xJT6z9H$u^2pEo zd_s6gM@aY!2Tb#Tont`kHBK~R_W6=bJ=Su|L|fA08*0cEVH@YTEwhk%HrG#8Ou5@N z{AK#vSrsFlle6a52_N-bAxG@WJ94t__YF~_jsp@ZOd6@F^gpos7RP=Ujk%CMbzs}srb{su- zIobI%Jw`=1fQ{Sb0mxVv+4-MQCI~=vqx#cVw(X>tOF1#Qs*3l;@o~6fkfv!BlrN2b zwcvKCoz7IqiWOfFKBlOzsa@+1r#-#7=5d#BlLf3Y#?D5EE#7nH+C3ExLNY)J*3(?s1 zL3~Fwk3)OI>w4*w2900H_4Z)Ak2@XIm7Y5L`a*d;&#(0he3IMF?$s(a5b*6d=^y{f z>305FO?_vU_{yAK>f8m_E0&g%0+Mns?s|G$z`amE+Qfp7ryrE_d0@NF?uj~-C7%5% z;%=)L49>K1>h?Oyq^;)_HX9$>S;|hFX>L|umNTumEG1;fyz*^$K$Oh578o$HByZ0>}``9Q9Pd|SgcJrxf-Qb0*%*3gydFUBVsg?4L+RN`Vp5g z<4;jGh&Fl8| z77W)(X>5UaB^XOeX-h*&<3M_y1P9QeJOH%gahZ5w%XluEeeEh%mT$mMPcU7o z4x^a;;6Mv_!t1$BZhr}NR(i2G6{+<$i`xqYi}H7R-Q3$&8*KSNlwtWc>&^6eA)axQT;}ErdrvAc~V1EkqLXk>f7S#r_26O+X1&zNs^zyzi4zqVlH4 zWpZa{r+eq?&YQ3FJ8$TA=(~aY0%1dKZSp-u(BqBE9S~qEfTP-dtH;&{bL?J3Txf;JZ>H^?H|Z)y z5aCciLOKAd#G<|AwblB@m6=3nngaTYl=)v*Lg#16jqtLCeXE zVMCTlSRjdnK$syHSVFR`;o*%o(nT5^P0zK+c|XZchf|K6KQMbcWlnvt{ua3}y>*!s zUm?st;3A)KWN_;l{oEuEN%?u19M#e-^H-iR%bB}JNw3!6r$M-n7Lurr`<%~-9iz2`yWvAN}Awmqcr+gglaAE)7nrloO(D8TiVE_`qW-|6S- z%Hi|@%Ka>Z+u{lZ$QuzzHf;na#1o-{>5op`h@Qo+da^BB_17rFg`uAO<-Oe~-jj$BII-Do9#ko6#-cq{ipP-s%|TRqMoiZ6gIAYI;vA4He#ROpDl>Tx#5Y`^lQ^ zm(11W)jSnt2dg6;n6%#y8T`x^k{k{ng)rRZ6Q?;@zU@M3$>T{zP%xa=o-e)qL-R>N zGGOyu&glKa1pujN7+@3pVQT}y;NMj*ki#tMdd@}oGm5Z(a#a)ErhQkddl$~=KDV9A z7+ZfmaouchtneXs+HgLFV27;v=e}a!@54lr<(Dz43LYvZ#Tp2Gz7!pYOQnwS8V!fX zPufNnPgj3#OjXcHU2RC3QPI!> z3!edajQ5jd*NGLAZMAf`lHdZ1!VTm4r}yZJ+omESS`5{Hb`=n-8#G>XJkEQQs=sIM zY@cwa#bmV8>)s^S6S1;SBP*VE2IAR7hT)$$U#PhaZG40h@KR3l^ruZ2Sy*vOgGTz) z&BZ+ejsHBOAXxrp!~FdYeb70@4;~N8-H6`YBG>j8LJmacrq?AS_enN2Y%MQ6kTZ(D9CW*N|IBp7NuKcu-E>9fHIaoG6K#p5r)VK9YAB`Zb!)5}Fd ztx1Kh5mSmPIzsM2>XTt*uUhfArG1x-!ZLl59~(J?1wth}+F9uEVVi*QMSp!)OnZ2lpa+ z-UunfYkxl=@}CFX8`uOH)*R69a83Zqj}u_9k}Pg+`bj!YJ@5QDI~xJetj$O`%wtV` z9r)$jprrf`iV5i@+9!xU?ybkkIo~4lZQwXbde&t#(6F} zu;5l$`()a!f=CD4*qFj3Bnx1B465OQSQ)%i#fbSVZ33VwBYt1!8cINOGAI>j5xNk$ z5*^NCMGAsr|MY%(W=O5y+mh83y&NKQRzy?|1uT-h9rtmTL>kFGL0kL&7n24nqzcKe7WcF z5~BNu=b;NO1|u^E?%y@uIk9Fb%G=vpAPsym4W&ee4$v~#?^^o6Ub-WhWbf-5v_BF>g{S~l;U7K#68cJR5er$b#YiPu7KhnfETnx$^(6LL zTvg2|H6adH96F^91nUZDjc3dSJTTzwmgf(6JDZlp1E5ixRB^M)eh5q&(%{Sj2I4fgMH$ggSmOY+1kSo9-(Yt4vCX z)wjbQrao3dv_X!Cg9HphyU(mglFvCv}M7BCpa7fq@bO`f<$NLS+wy2-}? z&5aUqo|^(f|Qhj(&#*q$ZfwI$T@6#Qnjq;nPcb@WbOz1{1cy(gdC zB>FFT#`Er?Fp?ai3TZCee(fb>b{8TInM9K%A3=5RqTiMOzwhb^DnaqE<0S*Y*&kuy zt>F+7-jen^SRuG}Eh>6r|KjIfr!`;>53&dt{94Zs$s4?jwOViTXh#Fwqv$P3^uI!j z{A@f2M8Xb@(*R-XU{2k2Vf1ReEB?D0NO%8(6(uzH+y}tiIiNGP_HeWybObbw6--}d za&e|(~PDWU&5 zk>3bHS$fr`K{@;hFpQs^w0NwlC&TJ^Us~Vt7p(FsW0VSv25O|`soXXhfaa@FGBB9! z{mLS1t7k}}SLs3%S_jq0{|Ojr6I$+bKm^tcdH^O4)79rwLqlIbow(*?XBT;Yom-B4 zU<@>}tSh!38aKCbuAm}>~9(Y|l+1o62fS8yR0lF!_ z3*JAc4{%S}fl0GLa=QZEPg6B4f?|)-r zL2$4!tLD6CvN?UKRZS(l)OjwXJ<_k4TR!r%pMazChSNpyoSdD>2>3!S6PrUWWf-Ia z!`Dadcg@e!g&c42RE6yRipYNmT5%7KVoM*B5)ccBjFF)6L-*f-+E^AGkm8j?5OAw_ z0ll2lXLlY05JTFIM0Wuop95ra66#d;;L^lWNVtuOqk%pfgt~m?tQgUkod^G(_oUnK zw1c-fVk1RQQ~Sz+h*2(X>g#Bu7w_aV?p?7JR&1w*7Cc`4s@Gc-YRrfymoN6zKan+sdZSuh|aXvJuqz!;!pmxsg1XTN>w*5xnY7=*VV+`sWTG*felA zVggV0OaY>^a`eUJY;InV1^7>Po8zTHQTW#n26}rH8Z#+9G!femZhGjF3W=cOP7laW zRzofR3wlg@s_EyISZ$gu0pk#pcH6?gIIE+5`s-0wd{&)Sqx$vs{e#%dro{zOC89k? z1v|EaTj*NzhU(v-faF=N57yj#2)6d8+7)HCq(55l^54pabr{&#n;myJL;^Ll!OXm#*OZ`bRP1=&Dzja#|+?{6!^Z=>a6TqqzoKG2m} zAQcbTqJHga#T5&}5N1gjNKFeoR7pp#pud#n|4O=;+{h~SrdF1gBfgtlBe)(}c9*6Q zez8C%Mogd=vOjKveOo$s$IkP#c>4=~&V^N$FhO%I&YyNeHz~TKVNjww*m<$DWmfJz z77pI-1OmtE+`09VK9+@zrCz1oa zANDflwppCXrdj~Dtv(Nsq5zY42vC)kPx~FhP64rJta1eMtF7zG2geUrG?cbdZ}tD- z9gb37Gr1`_t61yjBM@n89;{l1xtTtVc(qV4;rui-Ro@b zn0*}OK>HXA%o{9#4<}AGY+w`GJM!+&j;LoU5Qp(kElxH6XmqnuY$;J*B7fGKP5x>1 zaYjb(HF!1r zI2Pgq=ol`j^dC1xMHccE0C#Ke+pbUdhyir zW$3~E)srLUV*cPk6rjBnhg@E8X%&Tshk&*%wM?KdN*5%VP+&`tD${83<|?0AJ2mh? zkb}b^H>}?xK^9X0NNoO3i-%Gt94?+M&Y|-@crKKjyBuqaW5_68K<~NTwzsoU=RLf$ zUbXa6@qpd=<)iJXc)i7JK)1*wk1TOQpUZ<{OW0SyF_4n@_xg>=LCUOvY`>gc*vZ8O zh#uPHCbMJ$Plejs+rgN7zh5A!5q38+5ikJi>307kTzX0GG%#WGWDiWGx*-*EK?i#1 zw?S0d|F$FtY=N(UfxT&c564SzK;;k$%!Dn0eKv^CNVbko^Yegx6b7hJ79d1&88?Hjd7`UIhL04!IasXaT8`yT_Zi7KAm7la>0; zPFWKZlVuc&@`mAL_(iKgz4$o_fXOSvxj(^=fMEFO{E(Jf+Rb%$yub=U20i#NYgSqoo;Y^9}_Q0+b|wvNt35 z+iL<(7Ym2JaB5WL%Z6rLHn-Dr5yksEBUI(iR9l3tP5KMamnSV5SuoTDq^34iQq;JL@LRzM5$OmJG7s; zDk%ZWF7-s%FKuK>O>!&5j;;_AT7V@;2Kpiry(#b~J$*dn8X%-!jRJ)9Ygjq4mxQ2I z;J3H!crn%Azx=7~gc3ND74Ch0MHFzc96^B;vn{jLZx8xRzkhysaqz@r{b7Zav zDaPcH1rD_;!pG^?H3XyNV_E-;(5g#kg{;`pr4)9ui_wk@mpn8 zwnS>-=J2N{{US2U+y|;e-b80bIT=q z?8+y%m1msVCF;yU58oFE8`OF7Pwkq81!5i8W0?Rru>ErS9xvC9{6C036Uk^4it-Ck z>s$v6=qCtyU{{j z$!*%*9Q1R2uitYY6nT$W`u~Kq-_Ce)<9f#?X%hp(M8!Hx7;=M~S!%Wg+K*M;l;wf% zQG#6BYV>)%;|xO){>3yVOq`1v>n24C!f;QrNq_5x#S9d%#cq^UHSd(mC!}b%B!O{U z#lb(WX5I+7;V}6#@TJmZ&hh^7>wVgOa|Z`dB7?Bnu>2bFx4!|$ypO%1hN#RHUag#MF#;Fu6pR11ktxL|Z!=W}pyqJH5i4{wJT8-KjYZsjJak(^wb)3)KvK~%{ zt$B>OOE^c?&xAb8Kip@%mQWB-$q>!3zMK_jXZnJ`mOnQJ_XAIX?(TSn)(eTqyVO^; zT#Nwa`7-Z@?5_RSQ>Uu~o2R3e#(ygUWfM?CHw=O?~8{=5yUZ|T4BuC@Q|6+q zHb$nbstyb!gLlLy01(2z8@B5u!`v=F5}e=FGX6mU?tmAB;5rz{$#6IFgIUPqau(cz z@w;BW&|%#9_=;%O-S%ghQ~z_7I^n&1KVT4=zNKw!X#8$~_%HPM=NCWY=t`ZKD+Rwp z^5Krc@24fXf`ubX=oq&xL+KeQQYS8>FK1qc@N^8o2m*Lu5j*8S$sPvjVnnpj9{6BY zW3{Y*J{TtYgE4)>MS;pSRK-Gh;CCxT78K!u(og;y=54;iS)QAlt5pEU0Mm^HKhK)H zw8l9*{u&3QTZO>kWPeKoMlWdM^k)qUAYegpl^@-?Q=qP;%t9Tx|C@Hm`x~PBM}s=4 zj&#p^A0X2uOV}ae9FM(o-rl=mQ9lXCx5)Kf>1;>dHuDdxRVoml3uhv~B4?jQf zlRg<(N{!l6U{Zo&vwBz;W^rI*Hw(hWbF;aZJRO2f9z!s(nUL^Xcp}#8hb!+=ZGaQu z!LRQlgXQ_bJVermNxHhaZw1eGl2{f_ZVG0y@9Hx&pi1d7cFFWs3<8V z7HNzagHM+Z1_e9cMo^h?fgyA$pnQVeZVE1YeG>fh>pJQufE)&E`x&;wr>X7-)^4Z~ zH&g+g;D8ci5E~G=ya1D!8*X@RXl4PPEXsS%{)X!!yu1U593<91yASfa|5(kC{7Q;g zKkgXWA%R0eO~{x~!wnPeYT-M1 zfd?vMrZc_0y&rfB3y%w<7DR3Iqxy@ z4vWg9biv*2A1=V+&dVub#YEr^KA5b;u(@-1v68A`-S)MS6}5Jug#M6kxxs5e89n5P zgJ3?yB}SB&seoO_sLzT-Z@Hu)OoCY$JwdrB-Ty1?OTeM--oINUlAUakCQD_HvWpNc zCZ)(&OV+Wk*_&j`mNwg1QW?can1m1tMRp_0*!Q)vWq*sv#bBOO{z1{)fRhKm+S+AfoT{KfNUVnVA($C(2MD8Y3rK*QCXn_&*Zytg} zP+!sIKV`G}6iKi2Q@P}4Kh0RflK>r2wVgALGVeZKQtOPM#nmgV*m{Cg%^{DjLr#1h zfW>(L4FsQ`MkyVw;`Z3z2Ws^7ml~N0Z7;XB-$Pa?%#J(Fw0ANJg~KYw)DcaJzpK$D zYTU;6D1RA##ndXOr4t(#|J)b2TwnEzF_7{*%-jbRgpEwFzmKcsSa zBD!-?DVHooXRTX~a&5ZUCB&^;Xc*s%ixy5YiJW`?lHx7pv*wD^#f!$W6PdYh_TUJ4 zRaf+kSf#O%L9KmW?*lgBNRJWNK0!V0}n z6KC7pvR&j7W^9Lp$l9Q-bIUQ_dk0yyQ{cOH_PrFX>31y52=Pgbr~6xDI(I}cA~W7j z8{5NP`t0rUQ5x2#LQWqTH8c;iFp;j2-q;xct{299sV!4>tuOe1oS1AlUKamcb#7O9 zp$n=rRMBtsyM}dJR-%+cch^#^qg?)suSFDm{~+1SvhXsq>f5%rQBdJ@p4Rp|cHE^Z zElqRxcHEq@awLtEu8gAdpk|zcXU_R}sWXwX!?EL6e*PSY8v0g2?=gN6+KgxGMo?9# z3H_MIk3T~rP)2<#n=lfJjxa|Q`YM`xa&*42wj@EML*jVGn=DETTG2}Ssk`q zCcEKC>Tkg#`wbk^z-FeY!DcMB*h~Z~lH9rpy)k^K_<__g(ff)EUsd;s84EKDA|FCW z=-D%8LMIDGlIYgB9NrzoC3(FZ92)wRygnyr$uQ>Tg{eHPj+)jd#E#0mjy-LQN@!9lXgwy^MGhm*+uhx4$q3`zOz z%bFY+tT7*gq|@AIL)IBkSA&$-<eamUfR^JAR$C%?Vlc???I^z*Eu^Xy3-)-$(h zMDIO7%Dq@tC?D%8S&UO8yAZNL6ujxLW!p|c_L<0tV_>;0rf)gPz8^;O>|mdiEkc9! zfY_^&AE~qT^xfVGCudxA$O=q#W}E*VkcaQ%8M$45O-VbveX74$IL z@@Ti+)k>``2J(2LSZw|pYmh`)2d($d7ez-Rf#o_V&+cmqYlj0W( z-8-*Dima>JKW&j%VKZKSC2XR5kd3xfd)mLZ%uQ@CvZ8g&n)H5uFu~YoI&K)w-n*xB;iN(3`n>yCcjAmcx|=82 z|FyP#ky+mPxYcwx4pRlGU_M&8Xi?gJx07m9pD<~>una7^p%RE&%BS~O$s|VaL?Z&m z7qld;dxT$gH)g#s6tawneLtf&f7WToUw)E5yMBE)>tZKFQ2ztcX{yj7gLPW)bgs0< zeSTe)9UxcORA{yw_oDvOK-AhfAEjhNzoFJ1|2Ms}l1evcrrL5Q>`hPna=Ay}A6UqB zGmm26<3DKGB_=e0dE3Dq^Od8IXL2*)8DSK;gI#PPM%FO zil^w)jQh+HASTtM9chz|IgTb)v(c13420hfF~ZSy9kv4xe>4nWb{{}(3>)MMmVECJ z(i_}M#k~1^s~=!&T7J}VWOsc_If!~R(#y~POSbwona$B@>Gggq)95L!5ly_n<1sQC zDPr*Ep>}%})1JT~$er%bz@>|DQsoKKCw|!h?R>ajsX{|KSv@ZS-@x_U_|v9xzZ+M>=j->JEB;I>P*Z!u%A zTHEI6siZV-ITph4l6QVh&k&=IDDRAatFq}w7&HTvO_O&9ZtzQSHY$;w0!?F?m)zvXq#bZe$ft=WD7;)&w5H0EDw`s;a{N!(vA zn5*DCrg#5O|Gm8)rmHB3QzgFvBg{5>6k%eyv_FpLmwx>kJ=xNZ(16mP*WCH*Uu+M) zr(rBOxb^EamBC83^C4A!sSGukCSSG;>#vdiJp^74_(~U#sW{n9342lO3)NhllhVrg z=gWTmbR!Dvc_EWu^4H@wpZUj2d^o(}f&Nj-yPIPD_sjp~6B;NeA{nDkhE>1TGR@q} z_~)>w5;Qo7Ve-F=)jTh^l_>gilpLV{Qa#^j8 zHJVk{_I=B*4EvuI(ge+rJ1BrW_4h}&%G42Zmkuqhj?FhzU%}8Ja^&;`>)&mCkW~l> zL$&2C<>s(48)A<4L$HDf|82Xr%wszR6O0bobyxDQZ2t&CMD2zV>qjBPu?uQh0lyyb z`-kq6qhDQEF1#OO%P@KbAsAN8jQF9|dS_i{9&vK5UR8bY%gcJpD{IopVOJU3g%KNq zho#L88)hg9V%FJk5@S|jk(lY-+}ZO#;j@PxGp zi7$A9i9R~H3m8;A!}ZCf7whL&)`}w}X7Pmlug~ zikY2H3K3?Dj)D6SJXS1|eHV(8n5ih{Mix=%sD06=%xcBaQ=*lzGkC&Yg1~pJ za&jBM@dE}!LqkSWvr9)HL-^wHwlmjVsZRCTx{=H5EuB{A$o7m)fyD*Nycx|28P23o2t-i5N}N`m=tJc2vg~0E)#QVP z;6pHH5@xu}hz97H6P30M(JpF(u8eU^dnxNfvW$5dVviyO_0hP{>dcqDt7>MoDhTIu z;_Ulb729SOdo02W2rs8%G6{AO68^CJL+sf3bh{f|vwdpzONo34M}ct4d~`AkW3jaC zRsn$GhBH9H5n^6lqQb|FTv=NO`3*@ z1C#6JL(O=?h&m!V4Bk+3_~=p2>DeV7mS}!J|JSBp^Q*jc_dlSmuisvrnQ7|;^;`!5 z&QvaVNosG!5T?`YdrH>yDq|m)nQEJ0(~8~{E&G&+;R!Q$PCZe%B6jrw+?G8_zL%I@ zs*5i0lpw!k&ty?RY;@R;HT6LrM%mhrC#?7UTL(1Bsh#;L&U7u_PmasZX0<2L)1q1J z_UGdwPQq5tdh6HZd^pT3*!8q8kFe0Kec07A;zSm6wEUsy>h?azo6gu1*c^Vp(v9P0wSA@Q%jj;Pezd`- zX&Yx=6W3q7?9!MY0z4qVSE+}-%vAhgtxo|BW4fwoh@W+;xwH0v@q@?Cz{nry9tx|x ze_n>0io!jc=w}r^W`SR;W}mg;V~XRU3+{=SKAN@1^FUK!y_HG>ug@ovZg@nSm*q7JV?~Ej<=hNx@ zw;)x`2zIw$-|7`E?z{}%Y@!)g?+yqNk&Pkgdia>pabvuS;t7^L)@OE*FspARPM@`Bz0?Na7V5j)tz-C2dcXE^U-H~ZPjI@(HxJ5;TX zI=JG&_0DfAYl7@%X)t%rJ%RQw$7jqKtlz`xurIo!V>=eS3!=LvgSSjpBxA1<+ODn9zKIGtanyA|b~7qa@1J-3L6 z0S(-srr3en@Vp7Sab!PT+tT&?~o##0*iHryM~62 ziOe$Yr3_p1+u*N^UBMIl=>t!-eR%UijK>z(AvM6T$!x5DK!wXlICAu;+^3OQEdtS) zc~9WF@r5sA@@j(?=&1%6qAM@M>w?k!pyY<$c-HDejR_BOiJNbo`nK3A?9#uHj#F zRo(=3SH=!=Rtie?2p8DJ2CeKM%>||+obRt_H6#8l@q3#CGJx#^-AMs#$uX8a zYmx$3V>sG9tppxofFD6Kbc5XPNmxX|jV7*S^iB8Y+PYI^EE*AA{T-C^`Ahc*Vg%8& zfxWq}&BR|M_N2exM?hK&A@jF=@>oD0@R@D^)OylKR@VGPEPsS9Qv{S9{8Ssm#fXvF zv3#t7P5l|$sjW#LB>!oEOjvf@z47VhOB+ppyYR-|`6f-ioN9Jv@k&D*e50uTd zUDnS@*5Prs_(UNDrHX9h3?4RJ21iOY5`+Rz8t9`t49%vbCPD~`Itgkf-3sVCHm&ho1JGv zPaQ&}x;-NV5lSw92Y;2$&+KaG&0(g*5dBL1MmXU_|Ljtp(gLXXF|*nTV#oK&*edXt zSY=-EvugHC(b{}Wjfq2@oMv@w(Qi=6a_oES&RLY`J9moHF7A@M8`AyCqo7Ah1o5{v z|09nVWPoP4s@08(g_U*6GQ5%dV;~}Rv11ZIQIkfX!5F9y&b>@*e$=7H%fNmeU#zCK z9I9C&VeveKLP$tx!x;P((pDPG=>{W*HGaw={JTDy%>bQjm}~K+=c)Xw3E+eYLr~5# z%O*}+gj@3?YSeCcnVS#2&B-}NO2lJk9U+{j5OgbM?bHX4q3t{v_07W@y_)l3A+;J` zFRiWXL`W0{7z9kuWD+i{0jw`QGBo7&W67t`z%XE;Xl~ctD=x%ah80uY%Rkf@3tfb5v3D|!A>3vjtS)#qwZ}bSq(&+q? zk^fyd36pX1oL%N}WTdRf^31si0moY*;Tc{S%cr!rBe&+?kYaQ|Emj}~xd&#F^{bXz zBun(}T#vi8d;b-TSL+5vipz zTe2HxZHSM%*+@^1^avpGy;|5vn{SuW!gRuCOMACWty+Z~lnh;?(rW9hqf*8wF>(~{ zY|+K)H};&Rx{!RtVDw`J-Aoy*`ZX7t}