From 22f1b784525622ac39c9db50675c3937c7aeecf0 Mon Sep 17 00:00:00 2001 From: Denis Yeldandi Date: Fri, 17 Oct 2014 21:07:34 +0400 Subject: [PATCH 01/73] Adding vertical (Z) velocity to inav estimator --- .../position_estimator_inav_main.c | 3 +++ .../position_estimator_inav_params.c | 12 ++++++++++++ .../position_estimator_inav_params.h | 2 ++ 3 files changed, 17 insertions(+) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index 81bbaa6587..a1bfa2dfc1 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -846,6 +846,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) float w_xy_gps_p = params.w_xy_gps_p * w_gps_xy; float w_xy_gps_v = params.w_xy_gps_v * w_gps_xy; float w_z_gps_p = params.w_z_gps_p * w_gps_z; + float w_z_gps_v = params.w_z_gps_v * w_gps_z; float w_xy_vision_p = params.w_xy_vision_p; float w_xy_vision_v = params.w_xy_vision_v; @@ -876,6 +877,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) if (use_gps_z) { accel_bias_corr[2] -= corr_gps[2][0] * w_z_gps_p * w_z_gps_p; + accel_bias_corr[2] -= corr_gps[2][1] * w_z_gps_v; } /* transform error vector from NED frame to body frame */ @@ -960,6 +962,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) epv = fminf(epv, gps.epv); inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p); + inertial_filter_correct(corr_gps[2][1], dt, z_est, 1, w_z_gps_v); } if (use_vision_z) { diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index cc0fb4155e..1a1b3d3102 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -63,6 +63,17 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f); */ PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f); +/** + * Z velocity weight for GPS + * + * Weight (cutoff frequency) for GPS altitude velocity measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ +PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_V, 1.0f); + /** * Z axis weight for vision * @@ -281,6 +292,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) { h->w_z_baro = param_find("INAV_W_Z_BARO"); h->w_z_gps_p = param_find("INAV_W_Z_GPS_P"); + h->w_z_gps_v = param_find("INAV_W_Z_GPS_V"); h->w_z_vision_p = param_find("INAV_W_Z_VIS_P"); h->w_z_sonar = param_find("INAV_W_Z_SONAR"); h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P"); diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h index d0a65e42ea..51bbda412a 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.h +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h @@ -44,6 +44,7 @@ struct position_estimator_inav_params { float w_z_baro; float w_z_gps_p; + float w_z_gps_v; float w_z_vision_p; float w_z_sonar; float w_xy_gps_p; @@ -68,6 +69,7 @@ struct position_estimator_inav_params { struct position_estimator_inav_param_handles { param_t w_z_baro; param_t w_z_gps_p; + param_t w_z_gps_v; param_t w_z_vision_p; param_t w_z_sonar; param_t w_xy_gps_p; From 275a9df928590fbe590fcfed9eb30d794fb3fa6b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 01:09:20 -0500 Subject: [PATCH 02/73] fixes #1621 - travis after_script upload all Images to s3 with build status and index --- .travis.yml | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/.travis.yml b/.travis.yml index fd2a6b6d1c..fcc273437e 100644 --- a/.travis.yml +++ b/.travis.yml @@ -52,6 +52,16 @@ script: - echo -en 'travis_fold:end:script.3\\r' - zip Firmware.zip Images/*.px4 +after_script: + - git clone git://github.com/PX4/CI-Tools.git + - ./CI-Tools/s3cmd-configure +# upload newest build for this branch with s3 index + - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html $TRAVIS_BRANCH/ +# archive newest build by date with s3 index + - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html $TRAVIS_BRANCH/archives/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ +# upload top level index.html and timestamp.html + - ./CI-Tools/s3cmd-put CI-Tools/index.html timestamp.html / + # We use an encrypted env variable to ensure this only executes when artifacts are uploaded. #after_script: # - echo "Branch $TRAVIS_BRANCH (pull request: $TRAVIS_PULL_REQUEST) ready for flight testing." >> $PX4_REPORT From 0da66c33ad217ae78a52f134067a1c3bfa400dfb Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 01:10:46 -0500 Subject: [PATCH 03/73] travis delete commented after_script PX4_REPORT template --- .travis.yml | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/.travis.yml b/.travis.yml index fcc273437e..69efadfd2b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -62,21 +62,6 @@ after_script: # upload top level index.html and timestamp.html - ./CI-Tools/s3cmd-put CI-Tools/index.html timestamp.html / -# We use an encrypted env variable to ensure this only executes when artifacts are uploaded. -#after_script: -# - echo "Branch $TRAVIS_BRANCH (pull request: $TRAVIS_PULL_REQUEST) ready for flight testing." >> $PX4_REPORT -# - git log -n1 > $PX4_REPORT -# - echo " " >> $PX4_REPORT -# - echo "Files available at:" >> $PX4_REPORT -# - echo "https://px4-travis.s3.amazonaws.com/PX4/Firmware/$TRAVIS_BUILD_NUMBER/$TRAVIS_BUILD_NUMBER.1/Firmware.zip" >> $PX4_REPORT -# - echo "Description of desired tests is available at:" >> $PX4_REPORT -# - echo "https://github.com/PX4/Firmware/pull/$TRAVIS_PULL_REQUEST" >> $PX4_REPORT -# - echo " " >> $PX4_REPORT -# - echo "Thanks for testing!" >> $PX4_REPORT -# - echo " " >> $PX4_REPORT -# - /usr/bin/mail -s "$SUBJECT ($TRAVIS_COMMIT)" "$PX4_EMAIL" < "$PX4_REPORT" -# - s3cmd put --acl-public --guess-mime-type --config=.s3cfg Firmware.zip s3://s3-website-us-east-1.amazonaws.com/#$TRAVIS_JOB_ID/ - deploy: provider: releases api_key: From 12e54d1adb437b71bd63973357a647c65a8d77a7 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 01:11:26 -0500 Subject: [PATCH 04/73] travis delete redundant addons artifacts s3 upload --- .travis.yml | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/.travis.yml b/.travis.yml index 69efadfd2b..9f71b4e3a0 100644 --- a/.travis.yml +++ b/.travis.yml @@ -73,18 +73,6 @@ deploy: all_branches: true repo: PX4/Firmware -addons: - artifacts: - paths: - - "Firmware.zip" - key: - secure: j4y9x9KXUiarGrnpFBLPIkEKIH8X6oSRUO61TwxTOamsE0eEKnIaCz1Xq83q7DoqzomHBD3qXAFPV9dhLr1zdKEPJDIyV45GVD4ClIQIzh/P3Uc7kDNxKzdmxY12SH6D0orMpC4tCf1sNK7ETepltWfcnjaDk1Rjs9+TVY7LuzM= - secret: - secure: CJC7VPGtEhJu8Pix85iPF8xUvMPZvTgnHyd9MrSlPKCFFMrlgz9eMT0WWW/TPQ+s4LPwJIfEQx2Q0BRT5tOXuvsTLuOG68mplVddhTWbHb0m0qTQErXFHEppvW4ayuSdeLJ4TjTWphBVainL0mcLLRwQfuAJJDDs/sGan3WrG+Y= - bucket: px4-travis - region: us-east-1 - endpoint: s3-website-us-east-1.amazonaws.com - notifications: webhooks: urls: From 287e802bb5f4f747477b5b69b006d3e6f5295b4b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 01:54:13 -0500 Subject: [PATCH 05/73] travis s3 move archive location and store Firmware.zip instead of individual images --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 9f71b4e3a0..f0008b3b45 100644 --- a/.travis.yml +++ b/.travis.yml @@ -58,7 +58,7 @@ after_script: # upload newest build for this branch with s3 index - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html $TRAVIS_BRANCH/ # archive newest build by date with s3 index - - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html $TRAVIS_BRANCH/archives/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ + - ./CI-Tools/s3cmd-put Firmware.zip CI-Tools/directory/index.html archives/$TRAVIS_BRANCH/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ # upload top level index.html and timestamp.html - ./CI-Tools/s3cmd-put CI-Tools/index.html timestamp.html / From b84e50a3c601d8afebacad40d17d2db0e5644ce1 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 09:34:03 -0500 Subject: [PATCH 06/73] travis upload s3 artifacts to Firmware subdirectory --- .travis.yml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index f0008b3b45..52ced6b4fc 100644 --- a/.travis.yml +++ b/.travis.yml @@ -56,9 +56,10 @@ after_script: - git clone git://github.com/PX4/CI-Tools.git - ./CI-Tools/s3cmd-configure # upload newest build for this branch with s3 index - - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html $TRAVIS_BRANCH/ + - ./CI-Tools/s3cmd-put Images/px4*.px4 CI-Tools/directory/index.html Firmware/$TRAVIS_BRANCH/ # archive newest build by date with s3 index - - ./CI-Tools/s3cmd-put Firmware.zip CI-Tools/directory/index.html archives/$TRAVIS_BRANCH/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ + - ./CI-Tools/s3cmd-put Firmware.zip archives/Firmware/$TRAVIS_BRANCH/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ + - ./CI-Tools/s3cmd-put CI-Tools/directory/index.html archives/Firmware/$TRAVIS_BRANCH/ # upload top level index.html and timestamp.html - ./CI-Tools/s3cmd-put CI-Tools/index.html timestamp.html / From 0632d882bb734ac52ff5f7f5d1dc7930046e4600 Mon Sep 17 00:00:00 2001 From: Denis Yeldandi Date: Wed, 21 Jan 2015 12:22:07 +0300 Subject: [PATCH 07/73] INAV_W_Z_GPS_V defaults to 0 --- .../position_estimator_inav/position_estimator_inav_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index 1a1b3d3102..b2771f1a62 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -72,7 +72,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f); * @max 10.0 * @group Position Estimator INAV */ -PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_V, 1.0f); +PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_V, 0.0f); /** * Z axis weight for vision From eea3c801f4be7efa306af01a8153e8bbee4d43ce Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 10 Jan 2015 22:26:49 +0300 Subject: [PATCH 08/73] UAVCAN perf counters --- src/modules/uavcan/uavcan_main.cpp | 30 ++++++++++++++++++++++++++++++ src/modules/uavcan/uavcan_main.hpp | 9 +++++++-- 2 files changed, 37 insertions(+), 2 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 60901e0c75..af5f2ec96f 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -81,6 +81,22 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys if (res < 0) { std::abort(); } + + if (_perfcnt_node_spin_elapsed == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_node_spin_elapsed"); + } + + if (_perfcnt_esc_mixer_output_elapsed == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_esc_mixer_output_elapsed"); + } + + if (_perfcnt_esc_mixer_total_elapsed == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_esc_mixer_total_elapsed"); + } + + if (_perfcnt_esc_mixer_subscriptions == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_esc_mixer_subscriptions"); + } } UavcanNode::~UavcanNode() @@ -118,6 +134,11 @@ UavcanNode::~UavcanNode() } _instance = nullptr; + + perf_free(_perfcnt_node_spin_elapsed); + perf_free(_perfcnt_esc_mixer_output_elapsed); + perf_free(_perfcnt_esc_mixer_total_elapsed); + perf_free(_perfcnt_esc_mixer_subscriptions); } int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) @@ -265,10 +286,12 @@ int UavcanNode::init(uavcan::NodeID node_id) void UavcanNode::node_spin_once() { + perf_begin(_perfcnt_node_spin_elapsed); const int spin_res = _node.spin(uavcan::MonotonicTime()); if (spin_res < 0) { warnx("node spin error %i", spin_res); } + perf_end(_perfcnt_node_spin_elapsed); } /* @@ -344,8 +367,12 @@ int UavcanNode::run() // Mutex is unlocked while the thread is blocked on IO multiplexing (void)pthread_mutex_unlock(&_node_mutex); + perf_end(_perfcnt_esc_mixer_total_elapsed); // end goes first, it's not a mistake + const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs); + perf_begin(_perfcnt_esc_mixer_total_elapsed); + (void)pthread_mutex_lock(&_node_mutex); node_spin_once(); // Non-blocking @@ -430,7 +457,9 @@ int UavcanNode::run() } // Output to the bus _outputs.timestamp = hrt_absolute_time(); + perf_begin(_perfcnt_esc_mixer_output_elapsed); _esc_controller.update_outputs(_outputs.output, _outputs.noutputs); + perf_end(_perfcnt_esc_mixer_output_elapsed); } @@ -498,6 +527,7 @@ UavcanNode::arm_actuators(bool arm) void UavcanNode::subscribe() { + perf_count(_perfcnt_esc_mixer_subscriptions); // Subscribe/unsubscribe to required actuator control groups uint32_t sub_groups = _groups_required & ~_groups_subscribed; uint32_t unsub_groups = _groups_subscribed & ~_groups_required; diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 98f2e5ad4b..8a0993f15d 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -34,9 +34,9 @@ #pragma once #include - #include #include +#include #include #include @@ -66,7 +66,7 @@ */ class UavcanNode : public device::CDev { - static constexpr unsigned MemPoolSize = 10752; + static constexpr unsigned MemPoolSize = 10752; ///< Refer to the libuavcan manual to learn why static constexpr unsigned RxQueueLenPerIface = 64; static constexpr unsigned StackSize = 3000; @@ -142,4 +142,9 @@ private: // index into _poll_fds for each _control_subs handle uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; + + perf_counter_t _perfcnt_node_spin_elapsed = perf_alloc(PC_ELAPSED, "uavcan_node_spin_elapsed"); + perf_counter_t _perfcnt_esc_mixer_output_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_output_elapsed"); + perf_counter_t _perfcnt_esc_mixer_total_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_total_elapsed"); + perf_counter_t _perfcnt_esc_mixer_subscriptions = perf_alloc(PC_COUNT, "uavcan_esc_mixer_subscriptions"); }; From 7f0f4b3072008239f4481c79769ab1b00f92e707 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 11 Jan 2015 00:11:48 +0300 Subject: [PATCH 09/73] UavcanEscController broadcasting percounter --- src/modules/uavcan/actuators/esc.cpp | 14 ++++++++++++++ src/modules/uavcan/actuators/esc.hpp | 1 + 2 files changed, 15 insertions(+) diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index 9f682c7e16..995c8987c0 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -49,12 +49,24 @@ UavcanEscController::UavcanEscController(uavcan::INode &node) : _uavcan_sub_status(node), _orb_timer(node) { + if (_perfcnt_invalid_input == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_invalid_input"); + } + + if (_perfcnt_scaling_error == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_scaling_error"); + } + + if (_perfcnt_broadcast_elapsed == nullptr) { + errx(1, "uavcan: couldn't allocate _perfcnt_broadcast_elapsed"); + } } UavcanEscController::~UavcanEscController() { perf_free(_perfcnt_invalid_input); perf_free(_perfcnt_scaling_error); + perf_free(_perfcnt_broadcast_elapsed); } int UavcanEscController::init() @@ -129,7 +141,9 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) * Publish the command message to the bus * Note that for a quadrotor it takes one CAN frame */ + perf_begin(_perfcnt_broadcast_elapsed); (void)_uavcan_pub_raw_cmd.broadcast(msg); + perf_end(_perfcnt_broadcast_elapsed); } void UavcanEscController::arm_all_escs(bool arm) diff --git a/src/modules/uavcan/actuators/esc.hpp b/src/modules/uavcan/actuators/esc.hpp index 12c0355422..498fb9dd8b 100644 --- a/src/modules/uavcan/actuators/esc.hpp +++ b/src/modules/uavcan/actuators/esc.hpp @@ -109,4 +109,5 @@ private: */ perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input"); perf_counter_t _perfcnt_scaling_error = perf_alloc(PC_COUNT, "uavcan_esc_scaling_error"); + perf_counter_t _perfcnt_broadcast_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_broadcast_elapsed"); }; From 0901d999924012b482a5379854c24eb9f2c6f345 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 11 Jan 2015 04:38:20 +0300 Subject: [PATCH 10/73] UAVCAN update (speed optimizations) --- src/lib/uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/uavcan b/src/lib/uavcan index c4c45b995f..20439bb397 160000 --- a/src/lib/uavcan +++ b/src/lib/uavcan @@ -1 +1 @@ -Subproject commit c4c45b995f5c8192c7a36c4293c201711ceac74d +Subproject commit 20439bb3975c34a24c3c337a1f231fbf973a41e8 From 9215a8d8dafb3807852e10a3dab150c1fc6fc6f4 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 15 Jan 2015 00:11:55 +0300 Subject: [PATCH 11/73] Nuttx.py fixes: Python 2.7 support (required for gcc-arm-toolchain from Terry Guo), fixed int parsing, show mybt by name --- Debug/Nuttx.py | 51 ++++++++++++++++++++++++++++++-------------------- 1 file changed, 31 insertions(+), 20 deletions(-) diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py index cf86dd668f..f915d3bcbb 100644 --- a/Debug/Nuttx.py +++ b/Debug/Nuttx.py @@ -1,7 +1,10 @@ # GDB/Python functions for dealing with NuttX +from __future__ import print_function import gdb, gdb.types +parse_int = lambda x: int(str(x), 0) + class NX_register_set(object): """Copy of the registers for a given context""" @@ -155,7 +158,7 @@ class NX_task(object): result = [] for i in range(pidhash_type.range()[0],pidhash_type.range()[1]): entry = pidhash_value[i] - pid = int(entry['pid']) + pid = parse_int(entry['pid']) if pid is not -1: result.append(pid) return result @@ -184,7 +187,7 @@ class NX_task(object): self.__dict__['stack_used'] = 0 else: stack_limit = self._tcb['adj_stack_size'] - for offset in range(0, int(stack_limit)): + for offset in range(0, parse_int(stack_limit)): if stack_base[offset] != 0xff: break self.__dict__['stack_used'] = stack_limit - offset @@ -244,7 +247,7 @@ class NX_task(object): filearray = filelist['fl_files'] result = dict() for i in range(filearray.type.range()[0],filearray.type.range()[1]): - inode = int(filearray[i]['f_inode']) + inode = parse_int(filearray[i]['f_inode']) if inode != 0: result[i] = inode return result @@ -299,7 +302,7 @@ class NX_show_task (gdb.Command): super(NX_show_task, self).__init__("show task", gdb.COMMAND_USER) def invoke(self, arg, from_tty): - t = NX_task.for_pid(int(arg)) + t = NX_task.for_pid(parse_int(arg)) if t is not None: my_fmt = 'PID:{pid} name:{name} state:{state}\n' my_fmt += ' stack used {stack_used} of {stack_limit}\n' @@ -435,12 +438,12 @@ class NX_tcb(object): first_tcb = tcb_ptr.dereference() tcb_list.append(first_tcb); next_tcb = first_tcb['flink'].dereference() - while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): tcb_list.append(next_tcb); old_tcb = next_tcb; next_tcb = old_tcb['flink'].dereference() - return [t for t in tcb_list if int(t['pid'])<2000] + return [t for t in tcb_list if parse_int(t['pid'])<2000] def getTCB(self): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] @@ -469,12 +472,12 @@ class NX_check_stack_order(gdb.Command): first_tcb = tcb_ptr.dereference() tcb_list.append(first_tcb); next_tcb = first_tcb['flink'].dereference() - while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): tcb_list.append(next_tcb); old_tcb = next_tcb; next_tcb = old_tcb['flink'].dereference() - return [t for t in tcb_list if int(t['pid'])<2000] + return [t for t in tcb_list if parse_int(t['pid'])<2000] def getTCB(self): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] @@ -488,7 +491,7 @@ class NX_check_stack_order(gdb.Command): def getSPfromTask(self,tcb): regmap = NX_register_set.v7em_regmap a =tcb['xcp']['regs'] - return int(a[regmap['SP']]) + return parse_int(a[regmap['SP']]) def find_closest(self,list,val): tmp_list = [abs(i-val) for i in list] @@ -525,8 +528,8 @@ class NX_check_stack_order(gdb.Command): for t in tcb: p = []; #print(t.name,t._tcb['stack_alloc_ptr']) - p.append(int(t['stack_alloc_ptr'])) - p.append(int(t['adj_stack_ptr'])) + p.append(parse_int(t['stack_alloc_ptr'])) + p.append(parse_int(t['adj_stack_ptr'])) p.append(self.getSPfromTask(t)) stackadresses[str(t['name'])] = p; address = int("0x30000000",0) @@ -594,12 +597,12 @@ class NX_search_tcb(gdb.Command): first_tcb = tcb_ptr.dereference() tcb_list.append(first_tcb); next_tcb = first_tcb['flink'].dereference() - while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + while not self.is_in(parse_int(next_tcb['pid']),[parse_int(t['pid']) for t in tcb_list]): tcb_list.append(next_tcb); old_tcb = next_tcb; next_tcb = old_tcb['flink'].dereference() - return [t for t in tcb_list if int(t['pid'])<2000] + return [t for t in tcb_list if parse_int(t['pid'])<2000] def invoke(self,args,sth): list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] @@ -612,7 +615,7 @@ class NX_search_tcb(gdb.Command): # filter for tasks that are listed twice tasks_filt = {} for t in tasks: - pid = int(t['pid']); + pid = parse_int(t['pid']); if not pid in tasks_filt.keys(): tasks_filt[pid] = t['name']; print('{num_t} Tasks found:'.format(num_t = len(tasks_filt))) @@ -687,13 +690,21 @@ class NX_my_bt(gdb.Command): def invoke(self,args,sth): - addr_dec = int(args[2:],16) - _tcb = self.get_tcb_from_address(addr_dec) + try: + addr_dec = parse_int(args) # Trying to interpret the input as TCB address + except ValueError: + for task in NX_task.tasks(): # Interpreting as a task name + if task.name == args: + _tcb = task._tcb + break + else: + _tcb = self.get_tcb_from_address(addr_dec) + print("found task with PID: ",_tcb["pid"]) - up_stack = int(_tcb['adj_stack_ptr']) - curr_sp = int(_tcb['xcp']['regs'][0]) #curr stack pointer - other_sp = int(_tcb['xcp']['regs'][8]) # other stack pointer - stacksize = int(_tcb['adj_stack_size']) # other stack pointer + up_stack = parse_int(_tcb['adj_stack_ptr']) + curr_sp = parse_int(_tcb['xcp']['regs'][0]) #curr stack pointer + other_sp = parse_int(_tcb['xcp']['regs'][8]) # other stack pointer + stacksize = parse_int(_tcb['adj_stack_size']) # other stack pointer print("tasks current SP = ",hex(curr_sp),"stack max ptr is at ",hex(up_stack)) From e41bf13ac57081342a94f48a468e3f6f24404f8b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 15 Jan 2015 00:49:32 +0300 Subject: [PATCH 12/73] Nuttx.py: 'show mybt' outputs in GDB-like format for ease of parsing --- Debug/Nuttx.py | 37 ++++++++----------------------------- 1 file changed, 8 insertions(+), 29 deletions(-) diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py index f915d3bcbb..826e12c97c 100644 --- a/Debug/Nuttx.py +++ b/Debug/Nuttx.py @@ -656,38 +656,20 @@ class NX_my_bt(gdb.Command): tcb_ptr = addr_value.cast(gdb.lookup_type('struct tcb_s').pointer()) return tcb_ptr.dereference() - def print_instruction_at(self,addr,stack_percentage): + def resolve_file_line_func(self,addr,stack_percentage): gdb.write(str(round(stack_percentage,2))+":") str_to_eval = "info line *"+hex(addr) #gdb.execute(str_to_eval) res = gdb.execute(str_to_eval,to_string = True) # get information from results string: words = res.split() - valid = False - if words[0] == 'No': - #no line info... - pass - else: - valid = True + if words[0] != 'No': line = int(words[1]) - idx = words[3].rfind("/"); #find first backslash - if idx>0: - name = words[3][idx+1:]; - path = words[3][:idx]; - else: - name = words[3]; - path = ""; block = gdb.block_for_pc(addr) func = block.function if str(func) == "None": func = block.superblock.function - - if valid: - print("Line: ",line," in ",path,"/",name,"in ",func) - return name,path,line,func - - - + return words[3].strip('"'), line, func def invoke(self,args,sth): try: @@ -708,18 +690,15 @@ class NX_my_bt(gdb.Command): print("tasks current SP = ",hex(curr_sp),"stack max ptr is at ",hex(up_stack)) - if curr_sp == up_stack: - sp = other_sp - else: - sp = curr_sp; - - while(sp < up_stack): + item = 0 + for sp in range(other_sp if curr_sp == up_stack else curr_sp, up_stack, 4): mem = self.readmem(sp) #print(hex(sp)," : ",hex(mem)) if self.is_in_bounds(mem): # this is a potential instruction ptr stack_percentage = (up_stack-sp)/stacksize - name,path,line,func = self.print_instruction_at(mem,stack_percentage) - sp = sp + 4; # jump up one word + filename,line,func = self.resolve_file_line_func(mem, stack_percentage) + print('#%-2d ' % item, '0x%08x in ' % mem, func, ' at ', filename, ':', line, sep='') + item += 1 NX_my_bt() From dd3fa2532e63118bfd076e1027d74af2d06b9e05 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 15 Jan 2015 02:44:54 +0300 Subject: [PATCH 13/73] Poor man's sampling profiler for NuttX --- Debug/poor-mans-profiler.sh | 66 +++++++++++++++++++++++++++++++++++++ 1 file changed, 66 insertions(+) create mode 100755 Debug/poor-mans-profiler.sh diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh new file mode 100755 index 0000000000..f706fad853 --- /dev/null +++ b/Debug/poor-mans-profiler.sh @@ -0,0 +1,66 @@ +#!/bin/bash +# +# Poor man's sampling profiler for NuttX. +# +# The stack folding script was inspired by stackcollapse-gdb.pl from the FlameGraph project. +# +# Usage: Install flamegraph.pl in your PATH, define the variables below, configure your .gdbinit, run the script and go +# have a coffee. When you're back, you'll see the flamegraph. Note that frequent calls to GDB significantly +# interfere with normal operation of the target, which means that you can't profile real-time tasks with it. +# +# Requirements: ARM GDB with Python support +# + +root=$(dirname $0)/.. + +nsamples=100 +sleeptime=0.01 # Doctors recommend 7-8 hours a day +taskname=uavcan +exe=$root/Build/px4fmu-v2_default.build/firmware.elf + +set -e + +stacksfile=/tmp/$taskname-stacks.log + +cd $root +rm -f $stacksfile +echo "Sampling..." + +for x in $(seq 1 $nsamples) +do + arm-none-eabi-gdb $exe --batch -ex "set print asm-demangle on" \ + -ex "source $root/Debug/Nuttx.py" \ + -ex "show mybt $taskname" \ + 2> /dev/null \ + | sed -n 's/0\.0:\(#.*\)/\1/p' \ + >> $stacksfile + echo -e '\n\n' >> $stacksfile + echo -ne "\r$x/$nsamples" + sleep $sleeptime +done + +echo +echo "Stacks saved to $stacksfile" + +cat $stacksfile | perl -e 'my $current = ""; +my %stacks; +while(<>) { + if(m/^#[0-9]*\s*0x[a-zA-Z0-9]*\s*in (.*) at/) { + if ($1 ne "None") { + if ($current eq "") { $current = $1; } + else { $current = $1 . ";" . $current; } + } + } elsif(!($current eq "")) { + $stacks{$current} += 1; + $current = ""; + } +} +foreach my $k (sort { $a cmp $b } keys %stacks) { + print "$k $stacks{$k}\n"; +}' > /tmp/$taskname-folded.txt + +echo "Folded stacks saved to /tmp/$taskname-folded.txt" + +cat /tmp/$taskname-folded.txt | flamegraph.pl --fontsize=8 --width=1800 > /tmp/$taskname-flamegraph.svg + +xdg-open /tmp/$taskname-flamegraph.svg From 9293950cdb17af28e344f710f9121e606710a006 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 16 Jan 2015 20:47:29 +0300 Subject: [PATCH 14/73] NuttX profiler improvements --- Debug/poor-mans-profiler.sh | 136 +++++++++++++++++++++++++++--------- 1 file changed, 102 insertions(+), 34 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index f706fad853..1d76eaa445 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -11,45 +11,111 @@ # Requirements: ARM GDB with Python support # +set -e root=$(dirname $0)/.. -nsamples=100 -sleeptime=0.01 # Doctors recommend 7-8 hours a day -taskname=uavcan -exe=$root/Build/px4fmu-v2_default.build/firmware.elf +# +# Parsing the arguments. Read this section for usage info. +# +nsamples=0 +sleeptime=0.1 # Doctors recommend 7-8 hours a day +taskname= +elf=$root/Build/px4fmu-v2_default.build/firmware.elf +append=0 +fgfontsize=5 +fgwidth=1900 -set -e +function usage() +{ + echo "Invalid usage. Supported options:" + cat $0 | sed -n 's/^\s*--\([^)\*]*\).*/\1/p' # Don't try this at home. + exit 1 +} -stacksfile=/tmp/$taskname-stacks.log - -cd $root -rm -f $stacksfile -echo "Sampling..." - -for x in $(seq 1 $nsamples) +for i in "$@" do - arm-none-eabi-gdb $exe --batch -ex "set print asm-demangle on" \ - -ex "source $root/Debug/Nuttx.py" \ - -ex "show mybt $taskname" \ - 2> /dev/null \ - | sed -n 's/0\.0:\(#.*\)/\1/p' \ - >> $stacksfile - echo -e '\n\n' >> $stacksfile - echo -ne "\r$x/$nsamples" - sleep $sleeptime + case $i in + --nsamples=*) + nsamples="${i#*=}" + ;; + --sleeptime=*) + sleeptime="${i#*=}" + ;; + --taskname=*) + taskname="${i#*=}" + ;; + --elf=*) + elf="${i#*=}" + ;; + --append) + append=1 + ;; + --fgfontsize=*) + fgfontsize="${i#*=}" + ;; + --fgwidth=*) + fgwidth="${i#*=}" + ;; + *) + usage + ;; + esac + shift done -echo -echo "Stacks saved to $stacksfile" +# +# Temporary files +# +stacksfile=/tmp/pmpn-stacks.log +foldfile=/tmp/pmpn-folded.txt +graphfile=/tmp/pmpn-flamegraph.svg -cat $stacksfile | perl -e 'my $current = ""; +# +# Sampling if requested. Note that if $append is true, the stack file will not be rewritten. +# +cd $root + +if [[ $nsamples > 0 && "$taskname" != "" ]] +then + [[ $append = 0 ]] && (rm -f $stacksfile; echo "Old stacks removed") + + echo "Sampling..." + + for x in $(seq 1 $nsamples) + do + arm-none-eabi-gdb $exe --batch -ex "set print asm-demangle on" \ + -ex "source $root/Debug/Nuttx.py" \ + -ex "show mybt $taskname" \ + 2> /dev/null \ + | sed -n 's/0\.0:\(#.*\)/\1/p' \ + >> $stacksfile + echo -e '\n\n' >> $stacksfile + echo -ne "\r$x/$nsamples" + sleep $sleeptime + done + + echo + echo "Stacks saved to $stacksfile" +else + echo "Sampling skipped - set 'nsamples' and 'taskname' to re-sample." +fi + +# +# Folding the stacks. +# +if [ ! -f $stacksfile ]; then + echo "Where are the stack samples?" + exit 1 +fi + +cat $stacksfile | perl -e 'use File::Basename; +my $current = ""; my %stacks; while(<>) { - if(m/^#[0-9]*\s*0x[a-zA-Z0-9]*\s*in (.*) at/) { - if ($1 ne "None") { - if ($current eq "") { $current = $1; } - else { $current = $1 . ";" . $current; } - } + if(m/^#[0-9]*\s*0x[a-zA-Z0-9]*\s*in (.*) at (.*)/) { + my $x = $1 eq "None" ? basename($2) : $1; + if ($current eq "") { $current = $x; } + else { $current = $x . ";" . $current; } } elsif(!($current eq "")) { $stacks{$current} += 1; $current = ""; @@ -57,10 +123,12 @@ while(<>) { } foreach my $k (sort { $a cmp $b } keys %stacks) { print "$k $stacks{$k}\n"; -}' > /tmp/$taskname-folded.txt +}' > $foldfile -echo "Folded stacks saved to /tmp/$taskname-folded.txt" +echo "Folded stacks saved to $foldfile" -cat /tmp/$taskname-folded.txt | flamegraph.pl --fontsize=8 --width=1800 > /tmp/$taskname-flamegraph.svg - -xdg-open /tmp/$taskname-flamegraph.svg +# +# Graphing. +# +cat $foldfile | flamegraph.pl --fontsize=$fgfontsize --width=$fgwidth > $graphfile +xdg-open $graphfile From c0937ec8cac523d4c8fad028584e2b87956f3019 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 16 Jan 2015 21:00:48 +0300 Subject: [PATCH 15/73] Profiler fixes --- Debug/poor-mans-profiler.sh | 27 ++++++++++++++++----------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 1d76eaa445..d2393b296e 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -14,6 +14,21 @@ set -e root=$(dirname $0)/.. +function die() +{ + echo "$@" + exit 1 +} + +function usage() +{ + echo "Invalid usage. Supported options:" + cat $0 | sed -n 's/^\s*--\([^)\*]*\).*/\1/p' # Don't try this at home. + exit 1 +} + +which flamegraph.pl > /dev/null || die "Install flamegraph.pl first" + # # Parsing the arguments. Read this section for usage info. # @@ -25,13 +40,6 @@ append=0 fgfontsize=5 fgwidth=1900 -function usage() -{ - echo "Invalid usage. Supported options:" - cat $0 | sed -n 's/^\s*--\([^)\*]*\).*/\1/p' # Don't try this at home. - exit 1 -} - for i in "$@" do case $i in @@ -103,10 +111,7 @@ fi # # Folding the stacks. # -if [ ! -f $stacksfile ]; then - echo "Where are the stack samples?" - exit 1 -fi +[ -f $stacksfile ] || die "Where are the stack samples?" cat $stacksfile | perl -e 'use File::Basename; my $current = ""; From c0d71529bce816596dc3574e876e0f4c69bc9b9f Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 16 Jan 2015 21:13:10 +0300 Subject: [PATCH 16/73] Profiler fixes --- Debug/poor-mans-profiler.sh | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index d2393b296e..eede0072d7 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -77,6 +77,7 @@ done stacksfile=/tmp/pmpn-stacks.log foldfile=/tmp/pmpn-folded.txt graphfile=/tmp/pmpn-flamegraph.svg +gdberrfile=/tmp/pmpn-gdberr.log # # Sampling if requested. Note that if $append is true, the stack file will not be rewritten. @@ -87,14 +88,14 @@ if [[ $nsamples > 0 && "$taskname" != "" ]] then [[ $append = 0 ]] && (rm -f $stacksfile; echo "Old stacks removed") - echo "Sampling..." + echo "Sampling the task '$taskname'..." for x in $(seq 1 $nsamples) do - arm-none-eabi-gdb $exe --batch -ex "set print asm-demangle on" \ - -ex "source $root/Debug/Nuttx.py" \ - -ex "show mybt $taskname" \ - 2> /dev/null \ + arm-none-eabi-gdb $elf --batch -ex "set print asm-demangle on" \ + -ex "source $root/Debug/Nuttx.py" \ + -ex "show mybt $taskname" \ + 2> $gdberrfile \ | sed -n 's/0\.0:\(#.*\)/\1/p' \ >> $stacksfile echo -e '\n\n' >> $stacksfile From ff7c33a4b04e0545dc78a324cbc8f9a945f97519 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 16 Jan 2015 21:40:14 +0300 Subject: [PATCH 17/73] Profiler: xdg-open work-around --- Debug/poor-mans-profiler.sh | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index eede0072d7..2b25337565 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -37,7 +37,7 @@ sleeptime=0.1 # Doctors recommend 7-8 hours a day taskname= elf=$root/Build/px4fmu-v2_default.build/firmware.elf append=0 -fgfontsize=5 +fgfontsize=10 fgwidth=1900 for i in "$@" @@ -137,4 +137,12 @@ echo "Folded stacks saved to $foldfile" # Graphing. # cat $foldfile | flamegraph.pl --fontsize=$fgfontsize --width=$fgwidth > $graphfile -xdg-open $graphfile +echo "FlameGraph saved to $graphfile" + +# On KDE, xdg-open prefers Gwenview by default, which doesn't handle interactive SVGs, so we need a browser. +# The current implementation is hackish and stupid. Somebody, please do something about it. +opener=xdg-open +which firefox > /dev/null && opener=firefox +which google-chrome > /dev/null && opener=google-chrome + +$opener $graphfile From 1898b51c740dba2b3dd979980775f25c982dea1e Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 16 Jan 2015 22:08:46 +0300 Subject: [PATCH 18/73] Profiler: reporting function position in flame graphs --- Debug/poor-mans-profiler.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 2b25337565..460b28d0ad 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -119,7 +119,7 @@ my $current = ""; my %stacks; while(<>) { if(m/^#[0-9]*\s*0x[a-zA-Z0-9]*\s*in (.*) at (.*)/) { - my $x = $1 eq "None" ? basename($2) : $1; + my $x = $1 eq "None" ? basename($2) : ("$1 at " . basename($2)); if ($current eq "") { $current = $x; } else { $current = $x . ";" . $current; } } elsif(!($current eq "")) { From d1abf9c133bfe865f9648a88610d92a78f787f21 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 02:25:26 +0300 Subject: [PATCH 19/73] Poor man's profiler - proper stack folder that handles generic C++ types --- Debug/poor-mans-profiler.sh | 137 +++++++++++++++++++++++++++++------- 1 file changed, 113 insertions(+), 24 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 460b28d0ad..7657e4dc7d 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -84,7 +84,7 @@ gdberrfile=/tmp/pmpn-gdberr.log # cd $root -if [[ $nsamples > 0 && "$taskname" != "" ]] +if [[ $nsamples > 0 ]] then [[ $append = 0 ]] && (rm -f $stacksfile; echo "Old stacks removed") @@ -92,12 +92,20 @@ then for x in $(seq 1 $nsamples) do - arm-none-eabi-gdb $elf --batch -ex "set print asm-demangle on" \ - -ex "source $root/Debug/Nuttx.py" \ - -ex "show mybt $taskname" \ - 2> $gdberrfile \ - | sed -n 's/0\.0:\(#.*\)/\1/p' \ - >> $stacksfile + if [[ "$taskname" = "" ]] + then + arm-none-eabi-gdb $elf --batch -ex "set print asm-demangle on" -ex bt \ + 2> $gdberrfile \ + | sed -n 's/\(#.*\)/\1/p' \ + >> $stacksfile + else + arm-none-eabi-gdb $elf --batch -ex "set print asm-demangle on" \ + -ex "source $root/Debug/Nuttx.py" \ + -ex "show mybt $taskname" \ + 2> $gdberrfile \ + | sed -n 's/0\.0:\(#.*\)/\1/p' \ + >> $stacksfile + fi echo -e '\n\n' >> $stacksfile echo -ne "\r$x/$nsamples" sleep $sleeptime @@ -106,7 +114,7 @@ then echo echo "Stacks saved to $stacksfile" else - echo "Sampling skipped - set 'nsamples' and 'taskname' to re-sample." + echo "Sampling skipped - set 'nsamples' to re-sample." fi # @@ -114,22 +122,103 @@ fi # [ -f $stacksfile ] || die "Where are the stack samples?" -cat $stacksfile | perl -e 'use File::Basename; -my $current = ""; -my %stacks; -while(<>) { - if(m/^#[0-9]*\s*0x[a-zA-Z0-9]*\s*in (.*) at (.*)/) { - my $x = $1 eq "None" ? basename($2) : ("$1 at " . basename($2)); - if ($current eq "") { $current = $x; } - else { $current = $x . ";" . $current; } - } elsif(!($current eq "")) { - $stacks{$current} += 1; - $current = ""; - } -} -foreach my $k (sort { $a cmp $b } keys %stacks) { - print "$k $stacks{$k}\n"; -}' > $foldfile +cat $stacksfile | python -c " +# +# This stack folder correctly handles C++ types. +# + +from __future__ import print_function, division +import fileinput, collections, os + +def enforce(x, msg='Invalid input'): + if not x: + raise Exception(msg) + +def split_first_part_with_parens(line): + LBRACES = {'(':'()', '<':'<>', '[':'[]', '{':'{}'} + RBRACES = {')':'()', '>':'<>', ']':'[]', '}':'{}'} + braces = collections.defaultdict(int) + out = '' + for ch in line: + out += ch + # special cases + if out.endswith('operator>') or out.endswith('operator->'): # gotta love c++ + braces['<>'] += 1 + if out.endswith('operator<'): + braces['<>'] -= 1 + # counting parens + if ch in LBRACES.keys(): + braces[LBRACES[ch]] += 1 + if ch in RBRACES.keys(): + braces[RBRACES[ch]] -= 1 + # sanity check + for v in braces.values(): + enforce(v >= 0, 'Unaligned braces: ' + str(dict(braces))) + # termination condition + if ch == ' ' and sum(braces.values()) == 0: + break + out = out.strip() + return out, line[len(out):] + +def parse(line): + def take_path(line, output): + line = line.strip() + if line.startswith('at '): + line = line[3:].strip() + if line: + output['file_full_path'] = line.rsplit(':', 1)[0].strip() + output['file_base_name'] = os.path.basename(output['file_full_path']) + output['line'] = int(line.rsplit(':', 1)[1]) + return output + + def take_args(line, output): + line = line.lstrip() + if line[0] == '(': + output['args'], line = split_first_part_with_parens(line) + return take_path(line.lstrip(), output) + + def take_function(line, output): + output['function'], line = split_first_part_with_parens(line.lstrip()) + return take_args(line.lstrip(), output) + + def take_mem_loc(line, output): + line = line.lstrip() + if line.startswith('0x'): + end = line.find(' ') + num = line[:end] + output['memloc'] = int(num, 16) + line = line[end:].lstrip() + end = line.find(' ') + enforce(line[:end] == 'in') + line = line[end:].lstrip() + return take_function(line, output) + + def take_frame_num(line, output): + line = line.lstrip() + enforce(line[0] == '#') + end = line.find(' ') + num = line[1:end] + output['frame_num'] = int(num) + return take_mem_loc(line[end:], output) + + return take_frame_num(line, {}) + +stacks = collections.defaultdict(int) +current = '' + +for line in fileinput.input(): + line = line.strip() + if line: + inf = parse(line) + fun = inf['function'] + current = (fun + ';' + current) if current else fun + elif current: + stacks[current] += 1 + current = '' + +for s, f in sorted(stacks.items(), key=lambda (s, f): s): + print(s, f) +" > $foldfile echo "Folded stacks saved to $foldfile" From f158c8270b7572b3f3384a52cb6f6c51ecd7ec57 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 02:58:07 +0300 Subject: [PATCH 20/73] Rich man's profiler - handling quotes --- Debug/poor-mans-profiler.sh | 49 +++++++++++++++++++++++-------------- 1 file changed, 31 insertions(+), 18 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 7657e4dc7d..89ff4f424b 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -122,13 +122,12 @@ fi # [ -f $stacksfile ] || die "Where are the stack samples?" -cat $stacksfile | python -c " +cat << 'EOF' > /tmp/pmpn-folder.py # # This stack folder correctly handles C++ types. # - from __future__ import print_function, division -import fileinput, collections, os +import fileinput, collections, os, sys def enforce(x, msg='Invalid input'): if not x: @@ -137,20 +136,29 @@ def enforce(x, msg='Invalid input'): def split_first_part_with_parens(line): LBRACES = {'(':'()', '<':'<>', '[':'[]', '{':'{}'} RBRACES = {')':'()', '>':'<>', ']':'[]', '}':'{}'} + QUOTES = set(['"', "'"]) + quotes = collections.defaultdict(bool) braces = collections.defaultdict(int) out = '' for ch in line: out += ch + # escape character cancels further processing + if ch == '\\': + continue # special cases if out.endswith('operator>') or out.endswith('operator->'): # gotta love c++ braces['<>'] += 1 if out.endswith('operator<'): braces['<>'] -= 1 - # counting parens - if ch in LBRACES.keys(): - braces[LBRACES[ch]] += 1 - if ch in RBRACES.keys(): - braces[RBRACES[ch]] -= 1 + # switching quotes + if ch in QUOTES: + quotes[ch] = not quotes[ch] + # counting parens only when outside quotes + if sum(quotes.values()) == 0: + if ch in LBRACES.keys(): + braces[LBRACES[ch]] += 1 + if ch in RBRACES.keys(): + braces[RBRACES[ch]] -= 1 # sanity check for v in braces.values(): enforce(v >= 0, 'Unaligned braces: ' + str(dict(braces))) @@ -206,19 +214,24 @@ def parse(line): stacks = collections.defaultdict(int) current = '' -for line in fileinput.input(): - line = line.strip() - if line: - inf = parse(line) - fun = inf['function'] - current = (fun + ';' + current) if current else fun - elif current: - stacks[current] += 1 - current = '' +for idx,line in enumerate(fileinput.input()): + try: + line = line.strip() + if line: + inf = parse(line) + fun = inf['function'] + current = (fun + ';' + current) if current else fun + elif current: + stacks[current] += 1 + current = '' + except Exception, ex: + print('ERROR (line %d):' % (idx + 1), ex, file=sys.stderr) for s, f in sorted(stacks.items(), key=lambda (s, f): s): print(s, f) -" > $foldfile +EOF + +cat $stacksfile | python /tmp/pmpn-folder.py > $foldfile echo "Folded stacks saved to $foldfile" From 647163d6fa4761b0799e073bae8ea368a986b4fe Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 03:06:41 +0300 Subject: [PATCH 21/73] Profiler - header comment fix --- Debug/poor-mans-profiler.sh | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 89ff4f424b..63dba562a8 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -2,9 +2,7 @@ # # Poor man's sampling profiler for NuttX. # -# The stack folding script was inspired by stackcollapse-gdb.pl from the FlameGraph project. -# -# Usage: Install flamegraph.pl in your PATH, define the variables below, configure your .gdbinit, run the script and go +# Usage: Install flamegraph.pl in your PATH, configure your .gdbinit, run the script with proper arguments and go # have a coffee. When you're back, you'll see the flamegraph. Note that frequent calls to GDB significantly # interfere with normal operation of the target, which means that you can't profile real-time tasks with it. # From 543cb231282fdb899557f42003f53ac2f7a7dcc7 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 03:57:46 +0300 Subject: [PATCH 22/73] Profiler: computing stack top distribution --- Debug/poor-mans-profiler.sh | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index 63dba562a8..d907d8749b 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -212,6 +212,9 @@ def parse(line): stacks = collections.defaultdict(int) current = '' +stack_tops = collections.defaultdict(int) +num_stack_frames = 0 + for idx,line in enumerate(fileinput.input()): try: line = line.strip() @@ -219,6 +222,10 @@ for idx,line in enumerate(fileinput.input()): inf = parse(line) fun = inf['function'] current = (fun + ';' + current) if current else fun + + if inf['frame_num'] == 0: + num_stack_frames += 1 + stack_tops[fun] += 1 elif current: stacks[current] += 1 current = '' @@ -227,6 +234,11 @@ for idx,line in enumerate(fileinput.input()): for s, f in sorted(stacks.items(), key=lambda (s, f): s): print(s, f) + +print('Total stack frames:', num_stack_frames, file=sys.stderr) +print('Top consumers (distribution of the stack tops):', file=sys.stderr) +for name,num in sorted(stack_tops.items(), key=lambda (name, num): num, reverse=True)[:10]: + print('% 5.1f%% ' % (100 * num / num_stack_frames), name, file=sys.stderr) EOF cat $stacksfile | python /tmp/pmpn-folder.py > $foldfile From 6bbacc4271680cc262094af7f9a34807ff5c34ed Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 04:04:31 +0300 Subject: [PATCH 23/73] Intrusive changes made for UAVCAN profiling. Will be reverted in the next commit (this one is needed to keep the changes in history) --- ROMFS/px4fmu_common/init.d/rcS | 5 ++++- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- src/modules/uavcan/actuators/esc.cpp | 10 +++++----- src/modules/uavcan/uavcan_main.cpp | 10 ++++++++++ 4 files changed, 20 insertions(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 2c9387ff06..02f4649d5f 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -8,7 +8,7 @@ # # Default to auto-start mode. # -set MODE autostart +set MODE none set FRC /fs/microsd/etc/rc.txt set FCONFIG /fs/microsd/etc/config.txt @@ -656,6 +656,9 @@ then # End of autostart fi +param set UAVCAN_ENABLE 1 +sh /etc/init.d/rc.uavcan + # There is no further processing, so we can free some RAM # XXX potentially unset all script variables. unset TUNE_ERR diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index fbe378f509..1bbc5437d5 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -105,7 +105,7 @@ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) # optimisation flags # ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -g \ + -g3 \ -fno-strict-aliasing \ -fno-strength-reduce \ -fomit-frame-pointer \ diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index 995c8987c0..f7adbed760 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -98,11 +98,11 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) /* * Rate limiting - we don't want to congest the bus */ - const auto timestamp = _node.getMonotonicTime(); - if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) { - return; - } - _prev_cmd_pub = timestamp; +// const auto timestamp = _node.getMonotonicTime(); +// if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) { +// return; +// } +// _prev_cmd_pub = timestamp; /* * Fill the command message diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index af5f2ec96f..c29cd83230 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -357,6 +357,16 @@ int UavcanNode::run() _actuator_direct_poll_fd_num = add_poll_fd(_actuator_direct_sub); } + _esc_controller.arm_all_escs(true); + while (true) { + for (int i = 0; i < 1000; i++) { + node_spin_once(); + _outputs.noutputs = 8; + _esc_controller.update_outputs(_outputs.output, _outputs.noutputs); + } + ::usleep(1000); + } + while (!_task_should_exit) { // update actuator controls subscriptions if needed if (_groups_subscribed != _groups_required) { From d87bb4dfcb59601bc51d46332bbe0db78d11294a Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 04:04:48 +0300 Subject: [PATCH 24/73] Revert "Intrusive changes made for UAVCAN profiling. Will be reverted in the next commit (this one is needed to keep the changes in history)" This reverts commit 4c301d9dcf180e39186fa6753c7a3d3215b3cfa7. --- ROMFS/px4fmu_common/init.d/rcS | 5 +---- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- src/modules/uavcan/actuators/esc.cpp | 10 +++++----- src/modules/uavcan/uavcan_main.cpp | 10 ---------- 4 files changed, 7 insertions(+), 20 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 02f4649d5f..2c9387ff06 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -8,7 +8,7 @@ # # Default to auto-start mode. # -set MODE none +set MODE autostart set FRC /fs/microsd/etc/rc.txt set FCONFIG /fs/microsd/etc/config.txt @@ -656,9 +656,6 @@ then # End of autostart fi -param set UAVCAN_ENABLE 1 -sh /etc/init.d/rc.uavcan - # There is no further processing, so we can free some RAM # XXX potentially unset all script variables. unset TUNE_ERR diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 1bbc5437d5..fbe378f509 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -105,7 +105,7 @@ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) # optimisation flags # ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -g3 \ + -g \ -fno-strict-aliasing \ -fno-strength-reduce \ -fomit-frame-pointer \ diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index f7adbed760..995c8987c0 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -98,11 +98,11 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) /* * Rate limiting - we don't want to congest the bus */ -// const auto timestamp = _node.getMonotonicTime(); -// if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) { -// return; -// } -// _prev_cmd_pub = timestamp; + const auto timestamp = _node.getMonotonicTime(); + if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) { + return; + } + _prev_cmd_pub = timestamp; /* * Fill the command message diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index c29cd83230..af5f2ec96f 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -357,16 +357,6 @@ int UavcanNode::run() _actuator_direct_poll_fd_num = add_poll_fd(_actuator_direct_sub); } - _esc_controller.arm_all_escs(true); - while (true) { - for (int i = 0; i < 1000; i++) { - node_spin_once(); - _outputs.noutputs = 8; - _esc_controller.update_outputs(_outputs.output, _outputs.noutputs); - } - ::usleep(1000); - } - while (!_task_should_exit) { // update actuator controls subscriptions if needed if (_groups_subscribed != _groups_required) { From 569c3b7d37f4be5c9a635fe3e4633ecebbe8f9b5 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 05:10:43 +0300 Subject: [PATCH 25/73] Using -g3 flag instead of -g --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index fbe378f509..1bbc5437d5 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -105,7 +105,7 @@ ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) # optimisation flags # ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -g \ + -g3 \ -fno-strict-aliasing \ -fno-strength-reduce \ -fomit-frame-pointer \ From 885077a1c3cfa9980001e8dce76615e1f7552788 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 18:32:29 +0300 Subject: [PATCH 26/73] Profiler: folder fix - more special cases for operator<< and operator>> --- Debug/poor-mans-profiler.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Debug/poor-mans-profiler.sh b/Debug/poor-mans-profiler.sh index d907d8749b..ab06a1b66a 100755 --- a/Debug/poor-mans-profiler.sh +++ b/Debug/poor-mans-profiler.sh @@ -144,9 +144,9 @@ def split_first_part_with_parens(line): if ch == '\\': continue # special cases - if out.endswith('operator>') or out.endswith('operator->'): # gotta love c++ + if out.endswith('operator>') or out.endswith('operator>>') or out.endswith('operator->'): # gotta love c++ braces['<>'] += 1 - if out.endswith('operator<'): + if out.endswith('operator<') or out.endswith('operator<<'): braces['<>'] -= 1 # switching quotes if ch in QUOTES: From c2bc298409585aadce4b60dff5e6fada87c6c436 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 20:40:09 +0300 Subject: [PATCH 27/73] Disable instrumentation for the uavcan module --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- src/modules/uavcan/module.mk | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 1bbc5437d5..5a7f8390ff 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -116,7 +116,7 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ # enable precise stack overflow tracking # note - requires corresponding support in NuttX -INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) +INSTRUMENTATIONDEFINES ?= $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) # Language-specific flags # diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index e5d30f6c47..64e60bd186 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -40,6 +40,8 @@ MODULE_COMMAND = uavcan MAXOPTIMIZATION = -Os +INSTRUMENTATIONDEFINES = -fno-instrument-functions + # Main SRCS += uavcan_main.cpp \ uavcan_clock.cpp \ From f49f183f74be7d602fee6a1192538273d3d11cac Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 22:25:33 +0300 Subject: [PATCH 28/73] UAVCAN module: -O3 instead of -Os; fixed instrumentation defines --- src/modules/uavcan/module.mk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 64e60bd186..4d1b7156b8 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -38,9 +38,9 @@ MODULE_COMMAND = uavcan -MAXOPTIMIZATION = -Os +MAXOPTIMIZATION = -O3 -INSTRUMENTATIONDEFINES = -fno-instrument-functions +INSTRUMENTATIONDEFINES = -fno-instrument-functions -ffixed-r10 # Main SRCS += uavcan_main.cpp \ From 1d13edcf9221cfeabfe23eeff046dd7324f532b8 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 22:35:59 +0300 Subject: [PATCH 29/73] Stack checks made optional: ENABLE_STACK_CHECKS --- makefiles/toolchain_gnu-arm-eabi.mk | 16 ++++++++++++---- src/modules/uavcan/module.mk | 3 ++- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 5a7f8390ff..b38f40eb4c 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -80,14 +80,22 @@ ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \ -march=armv7-m \ -mfloat-abi=soft -ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions \ - -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -ffixed-r10 -ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions \ - -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -ffixed-r10 ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = +# Enabling stack checks if requested +# +ENABLE_STACK_CHECKS ?= 0 +ifneq ($(ENABLE_STACK_CHECKS),0) +$(info Stack checks enabled) +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F += -finstrument-functions +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 += -finstrument-functions +ARCHINSTRUMENTATIONDEFINES_CORTEXM3 += +endif + # Pick the right set of flags for the architecture. # ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH)) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 4d1b7156b8..a3c6e46a0a 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -40,7 +40,8 @@ MODULE_COMMAND = uavcan MAXOPTIMIZATION = -O3 -INSTRUMENTATIONDEFINES = -fno-instrument-functions -ffixed-r10 +# Instrumentation makes the CPU load about 3 times higher, see https://github.com/PX4/Firmware/issues/1417 +INSTRUMENTATIONDEFINES += -fno-instrument-functions # Main SRCS += uavcan_main.cpp \ From 4b1782174c334a9846096145a7156a015df3edae Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 17 Jan 2015 22:40:03 +0300 Subject: [PATCH 30/73] INSTRUMENTATIONDEFINES assignment made non-optional --- makefiles/toolchain_gnu-arm-eabi.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index b38f40eb4c..7e1f510e6d 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -124,7 +124,7 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ # enable precise stack overflow tracking # note - requires corresponding support in NuttX -INSTRUMENTATIONDEFINES ?= $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) +INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) # Language-specific flags # From ed27e583e01bee74a5bf46561b9aea7bd630846b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 18 Jan 2015 01:30:46 +0300 Subject: [PATCH 31/73] UAVCAN update --- src/lib/uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/uavcan b/src/lib/uavcan index 20439bb397..c9227cf6d2 160000 --- a/src/lib/uavcan +++ b/src/lib/uavcan @@ -1 +1 @@ -Subproject commit 20439bb3975c34a24c3c337a1f231fbf973a41e8 +Subproject commit c9227cf6d24e0bafee3ada499dea183446aa35b1 From c9eae96cf67ebdf6d202dc7ecac55a5b4a670a50 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 18 Jan 2015 04:05:50 +0300 Subject: [PATCH 32/73] Frame size fix fix per Lorenz's suggestion --- src/modules/attitude_estimator_ekf/module.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk index 1158536e1d..d158d7a49c 100644 --- a/src/modules/attitude_estimator_ekf/module.mk +++ b/src/modules/attitude_estimator_ekf/module.mk @@ -43,6 +43,6 @@ SRCS = attitude_estimator_ekf_main.cpp \ MODULE_STACKSIZE = 1200 -EXTRACFLAGS = -Wno-float-equal -Wframe-larger-than=3600 +EXTRACFLAGS = -Wno-float-equal -Wframe-larger-than=3700 EXTRACXXFLAGS = -Wframe-larger-than=2400 From 2ebd7099de83c603b01bedd278c38a4eb6b77b2b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 18 Jan 2015 16:09:46 +0300 Subject: [PATCH 33/73] Globally configurable stack checks, R10 is always fixed --- makefiles/toolchain_gnu-arm-eabi.mk | 16 +++++++--------- nuttx-configs/px4fmu-v2/nsh/Make.defs | 6 ++++++ src/modules/uavcan/module.mk | 3 --- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 7e1f510e6d..7055137ca5 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -80,20 +80,18 @@ ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \ -march=armv7-m \ -mfloat-abi=soft -ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -ffixed-r10 - -ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -ffixed-r10 - -ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = - # Enabling stack checks if requested # ENABLE_STACK_CHECKS ?= 0 ifneq ($(ENABLE_STACK_CHECKS),0) $(info Stack checks enabled) -ARCHINSTRUMENTATIONDEFINES_CORTEXM4F += -finstrument-functions -ARCHINSTRUMENTATIONDEFINES_CORTEXM4 += -finstrument-functions -ARCHINSTRUMENTATIONDEFINES_CORTEXM3 += +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = +else +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = endif # Pick the right set of flags for the architecture. diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs index 99f3b3140d..798d58572d 100644 --- a/nuttx-configs/px4fmu-v2/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs @@ -62,8 +62,14 @@ ARCHCPUFLAGS = -mcpu=cortex-m4 \ # enable precise stack overflow tracking +ENABLE_STACK_CHECKS ?= 0 +ifneq ($(ENABLE_STACK_CHECKS),0) +$(info Stack checks enabled) INSTRUMENTATIONDEFINES = -finstrument-functions \ -ffixed-r10 +else +INSTRUMENTATIONDEFINES = -ffixed-r10 +endif # pull in *just* libm from the toolchain ... this is grody LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index a3c6e46a0a..924b730a23 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -40,9 +40,6 @@ MODULE_COMMAND = uavcan MAXOPTIMIZATION = -O3 -# Instrumentation makes the CPU load about 3 times higher, see https://github.com/PX4/Firmware/issues/1417 -INSTRUMENTATIONDEFINES += -fno-instrument-functions - # Main SRCS += uavcan_main.cpp \ uavcan_clock.cpp \ From f6786d0be91659bfe6cca393d512edd5aa7a407e Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sun, 18 Jan 2015 22:40:22 +0300 Subject: [PATCH 34/73] Removing -ffixed-r10 when stack checks aren't enabled --- makefiles/toolchain_gnu-arm-eabi.mk | 4 ++-- nuttx-configs/px4fmu-v2/nsh/Make.defs | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 7055137ca5..0d681cacc8 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -89,8 +89,8 @@ ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions -ffixed-r10 ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions -ffixed-r10 ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = else -ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -ffixed-r10 -ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -ffixed-r10 +ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = +ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = endif diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs index 798d58572d..b2f05293d1 100644 --- a/nuttx-configs/px4fmu-v2/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs @@ -68,7 +68,7 @@ $(info Stack checks enabled) INSTRUMENTATIONDEFINES = -finstrument-functions \ -ffixed-r10 else -INSTRUMENTATIONDEFINES = -ffixed-r10 +INSTRUMENTATIONDEFINES = endif # pull in *just* libm from the toolchain ... this is grody From 91362223ea5dc5badc34870210c356eb47ebd59d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 19 Jan 2015 15:49:18 +0300 Subject: [PATCH 35/73] Fixed uninitialized fields of UavcanNode --- src/modules/uavcan/uavcan_main.hpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 8a0993f15d..583c621eb2 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -107,11 +107,11 @@ private: int _task = -1; ///< handle to the OS task bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver int _armed_sub = -1; ///< uORB subscription of the arming status - actuator_armed_s _armed; ///< the arming request of the system + actuator_armed_s _armed = {}; ///< the arming request of the system bool _is_armed = false; ///< the arming status of the actuators on the bus int _test_motor_sub = -1; ///< uORB subscription of the test_motor status - test_motor_s _test_motor; + test_motor_s _test_motor = {}; bool _test_in_progress = false; unsigned _output_count = 0; ///< number of actuators currently available @@ -135,10 +135,10 @@ private: unsigned _poll_fds_num = 0; int _actuator_direct_sub = -1; ///< uORB subscription of the actuator_direct topic - uint8_t _actuator_direct_poll_fd_num; - actuator_direct_s _actuator_direct; + uint8_t _actuator_direct_poll_fd_num = 0; + actuator_direct_s _actuator_direct = {}; - actuator_outputs_s _outputs; + actuator_outputs_s _outputs = {}; // index into _poll_fds for each _control_subs handle uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; From 4baf4a032fa87a01863ae475d4ad27496c90db86 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 19 Jan 2015 15:54:14 +0300 Subject: [PATCH 36/73] Fixed: Passing this->_armed_sub to close, which cannot accept a negative number. --- src/modules/uavcan/uavcan_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index af5f2ec96f..5b961e2efc 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -513,7 +513,7 @@ UavcanNode::teardown() _control_subs[i] = -1; } } - return ::close(_armed_sub); + return (_armed_sub >= 0) ? ::close(_armed_sub) : 0; } int From f6dc2af3986ba823822525d9865c101d91aa67c3 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 19 Jan 2015 16:24:07 +0300 Subject: [PATCH 37/73] UAVCAN update --- src/lib/uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/uavcan b/src/lib/uavcan index c9227cf6d2..8966f97013 160000 --- a/src/lib/uavcan +++ b/src/lib/uavcan @@ -1 +1 @@ -Subproject commit c9227cf6d24e0bafee3ada499dea183446aa35b1 +Subproject commit 8966f970135fb421db31886d6f99ac918594a780 From 4b8feb03cfca89b18ca88a19079e796b44f6d216 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Tue, 20 Jan 2015 17:36:55 -1000 Subject: [PATCH 38/73] Match the OS build's CONFIG_ARMV7M_STACKCHECK setting by using actual setting in the exported nuttx config.h file to control each board build setting of ENABLE_STACK_CHECKS in toolchain_gnu-arm-eabi.mk --- makefiles/setup.mk | 1 + makefiles/toolchain_gnu-arm-eabi.mk | 9 +++++---- nuttx-configs/aerocore/nsh/Make.defs | 5 +++-- nuttx-configs/px4fmu-v1/nsh/Make.defs | 5 +++-- nuttx-configs/px4fmu-v2/nsh/Make.defs | 9 ++------- nuttx-configs/px4fmu-v2/nsh/defconfig | 2 +- nuttx-configs/px4io-v1/nsh/Make.defs | 5 +++++ nuttx-configs/px4io-v2/nsh/Make.defs | 5 +++++ 8 files changed, 25 insertions(+), 16 deletions(-) mode change 100644 => 100755 makefiles/setup.mk mode change 100644 => 100755 makefiles/toolchain_gnu-arm-eabi.mk mode change 100644 => 100755 nuttx-configs/aerocore/nsh/Make.defs mode change 100644 => 100755 nuttx-configs/px4fmu-v1/nsh/Make.defs mode change 100644 => 100755 nuttx-configs/px4fmu-v2/nsh/Make.defs mode change 100644 => 100755 nuttx-configs/px4fmu-v2/nsh/defconfig mode change 100644 => 100755 nuttx-configs/px4io-v1/nsh/Make.defs mode change 100644 => 100755 nuttx-configs/px4io-v2/nsh/Make.defs diff --git a/makefiles/setup.mk b/makefiles/setup.mk old mode 100644 new mode 100755 index 4bfa7a0876..c932a67586 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -80,6 +80,7 @@ export ECHO = echo export UNZIP_CMD = unzip export PYTHON = python export OPENOCD = openocd +export GREP = grep # # Host-specific paths, hacks and fixups diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk old mode 100644 new mode 100755 index 0d681cacc8..d4d73fb843 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -80,11 +80,12 @@ ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \ -march=armv7-m \ -mfloat-abi=soft -# Enabling stack checks if requested +# Enabling stack checks if OS was build with them # -ENABLE_STACK_CHECKS ?= 0 -ifneq ($(ENABLE_STACK_CHECKS),0) -$(info Stack checks enabled) +TEST_FILE_STACKCHECK=$(WORK_DIR)nuttx-export/include/nuttx/config.h +TEST_VALUE_STACKCHECK=CONFIG_ARMV7M_STACKCHECK\ 1 +ENABLE_STACK_CHECKS=$(shell $(GREP) -q "$(TEST_VALUE_STACKCHECK)" $(TEST_FILE_STACKCHECK); echo $$?;) +ifeq ("$(ENABLE_STACK_CHECKS)","0") ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions -ffixed-r10 ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions -ffixed-r10 ARCHINSTRUMENTATIONDEFINES_CORTEXM3 = diff --git a/nuttx-configs/aerocore/nsh/Make.defs b/nuttx-configs/aerocore/nsh/Make.defs old mode 100644 new mode 100755 index c1f5a8ac42..3808fc1cfd --- a/nuttx-configs/aerocore/nsh/Make.defs +++ b/nuttx-configs/aerocore/nsh/Make.defs @@ -62,8 +62,9 @@ ARCHCPUFLAGS = -mcpu=cortex-m4 \ # enable precise stack overflow tracking -INSTRUMENTATIONDEFINES = -finstrument-functions \ - -ffixed-r10 +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10 +endif # pull in *just* libm from the toolchain ... this is grody LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs old mode 100644 new mode 100755 index 5e28f2473d..4e08d28a29 --- a/nuttx-configs/px4fmu-v1/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs @@ -62,8 +62,9 @@ ARCHCPUFLAGS = -mcpu=cortex-m4 \ # enable precise stack overflow tracking -INSTRUMENTATIONDEFINES = -finstrument-functions \ - -ffixed-r10 +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10 +endif # pull in *just* libm from the toolchain ... this is grody LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs old mode 100644 new mode 100755 index b2f05293d1..5a1d5af2c4 --- a/nuttx-configs/px4fmu-v2/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs @@ -62,13 +62,8 @@ ARCHCPUFLAGS = -mcpu=cortex-m4 \ # enable precise stack overflow tracking -ENABLE_STACK_CHECKS ?= 0 -ifneq ($(ENABLE_STACK_CHECKS),0) -$(info Stack checks enabled) -INSTRUMENTATIONDEFINES = -finstrument-functions \ - -ffixed-r10 -else -INSTRUMENTATIONDEFINES = +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10 endif # pull in *just* libm from the toolchain ... this is grody diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig old mode 100644 new mode 100755 index 9030a1f022..dedebdfa03 --- a/nuttx-configs/px4fmu-v2/nsh/defconfig +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig @@ -117,7 +117,7 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARMV7M_STACKCHECK=n CONFIG_SERIAL_TERMIOS=y CONFIG_SDIO_DMA=y CONFIG_SDIO_DMAPRIO=0x00010000 diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs old mode 100644 new mode 100755 index b4f5577aed..74f38c0cb4 --- a/nuttx-configs/px4io-v1/nsh/Make.defs +++ b/nuttx-configs/px4io-v1/nsh/Make.defs @@ -58,6 +58,11 @@ ARCHCPUFLAGS = -mcpu=cortex-m3 \ -mthumb \ -march=armv7-m +# enable precise stack overflow tracking +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10 +endif + # use our linker script LDSCRIPT = ld.script diff --git a/nuttx-configs/px4io-v2/nsh/Make.defs b/nuttx-configs/px4io-v2/nsh/Make.defs old mode 100644 new mode 100755 index 51420eb23d..287466db60 --- a/nuttx-configs/px4io-v2/nsh/Make.defs +++ b/nuttx-configs/px4io-v2/nsh/Make.defs @@ -58,6 +58,11 @@ ARCHCPUFLAGS = -mcpu=cortex-m3 \ -mthumb \ -march=armv7-m +# enable precise stack overflow tracking +ifeq ($(CONFIG_ARMV7M_STACKCHECK),y) +INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10 +endif + # use our linker script LDSCRIPT = ld.script From ae0e2d720926702f5dc1f97aeaa893d30c61fe29 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 21 Jan 2015 10:39:14 +0300 Subject: [PATCH 39/73] Removing extra UAVCAN perfcounters --- src/modules/uavcan/actuators/esc.cpp | 7 ------- src/modules/uavcan/actuators/esc.hpp | 1 - src/modules/uavcan/uavcan_main.cpp | 6 ------ src/modules/uavcan/uavcan_main.hpp | 1 - 4 files changed, 15 deletions(-) diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index 995c8987c0..51589e43eb 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -56,17 +56,12 @@ UavcanEscController::UavcanEscController(uavcan::INode &node) : if (_perfcnt_scaling_error == nullptr) { errx(1, "uavcan: couldn't allocate _perfcnt_scaling_error"); } - - if (_perfcnt_broadcast_elapsed == nullptr) { - errx(1, "uavcan: couldn't allocate _perfcnt_broadcast_elapsed"); - } } UavcanEscController::~UavcanEscController() { perf_free(_perfcnt_invalid_input); perf_free(_perfcnt_scaling_error); - perf_free(_perfcnt_broadcast_elapsed); } int UavcanEscController::init() @@ -141,9 +136,7 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) * Publish the command message to the bus * Note that for a quadrotor it takes one CAN frame */ - perf_begin(_perfcnt_broadcast_elapsed); (void)_uavcan_pub_raw_cmd.broadcast(msg); - perf_end(_perfcnt_broadcast_elapsed); } void UavcanEscController::arm_all_escs(bool arm) diff --git a/src/modules/uavcan/actuators/esc.hpp b/src/modules/uavcan/actuators/esc.hpp index 498fb9dd8b..12c0355422 100644 --- a/src/modules/uavcan/actuators/esc.hpp +++ b/src/modules/uavcan/actuators/esc.hpp @@ -109,5 +109,4 @@ private: */ perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input"); perf_counter_t _perfcnt_scaling_error = perf_alloc(PC_COUNT, "uavcan_esc_scaling_error"); - perf_counter_t _perfcnt_broadcast_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_broadcast_elapsed"); }; diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 5b961e2efc..4dc03b61b7 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -93,10 +93,6 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys if (_perfcnt_esc_mixer_total_elapsed == nullptr) { errx(1, "uavcan: couldn't allocate _perfcnt_esc_mixer_total_elapsed"); } - - if (_perfcnt_esc_mixer_subscriptions == nullptr) { - errx(1, "uavcan: couldn't allocate _perfcnt_esc_mixer_subscriptions"); - } } UavcanNode::~UavcanNode() @@ -138,7 +134,6 @@ UavcanNode::~UavcanNode() perf_free(_perfcnt_node_spin_elapsed); perf_free(_perfcnt_esc_mixer_output_elapsed); perf_free(_perfcnt_esc_mixer_total_elapsed); - perf_free(_perfcnt_esc_mixer_subscriptions); } int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) @@ -527,7 +522,6 @@ UavcanNode::arm_actuators(bool arm) void UavcanNode::subscribe() { - perf_count(_perfcnt_esc_mixer_subscriptions); // Subscribe/unsubscribe to required actuator control groups uint32_t sub_groups = _groups_required & ~_groups_subscribed; uint32_t unsub_groups = _groups_subscribed & ~_groups_required; diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 583c621eb2..19b9b4b484 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -146,5 +146,4 @@ private: perf_counter_t _perfcnt_node_spin_elapsed = perf_alloc(PC_ELAPSED, "uavcan_node_spin_elapsed"); perf_counter_t _perfcnt_esc_mixer_output_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_output_elapsed"); perf_counter_t _perfcnt_esc_mixer_total_elapsed = perf_alloc(PC_ELAPSED, "uavcan_esc_mixer_total_elapsed"); - perf_counter_t _perfcnt_esc_mixer_subscriptions = perf_alloc(PC_COUNT, "uavcan_esc_mixer_subscriptions"); }; From e62c8d73678f87b9f6cab1ad3a33c8911277a8a8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 21 Jan 2015 09:29:47 +0100 Subject: [PATCH 40/73] FMUv1: Disable stack checking --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index a467fa605e..539634e3da 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -92,7 +92,7 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARMV7M_STACKCHECK=n CONFIG_SERIAL_TERMIOS=y # From 517e1e8d4879c7a2d359b92e2eff89eddb944a16 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 21 Jan 2015 03:07:15 -1000 Subject: [PATCH 41/73] Fixed permissions --- makefiles/setup.mk | 0 makefiles/toolchain_gnu-arm-eabi.mk | 0 nuttx-configs/aerocore/nsh/Make.defs | 0 nuttx-configs/px4fmu-v1/nsh/Make.defs | 0 nuttx-configs/px4fmu-v2/nsh/Make.defs | 0 nuttx-configs/px4fmu-v2/nsh/defconfig | 0 nuttx-configs/px4io-v1/nsh/Make.defs | 0 nuttx-configs/px4io-v2/nsh/Make.defs | 0 8 files changed, 0 insertions(+), 0 deletions(-) mode change 100755 => 100644 makefiles/setup.mk mode change 100755 => 100644 makefiles/toolchain_gnu-arm-eabi.mk mode change 100755 => 100644 nuttx-configs/aerocore/nsh/Make.defs mode change 100755 => 100644 nuttx-configs/px4fmu-v1/nsh/Make.defs mode change 100755 => 100644 nuttx-configs/px4fmu-v2/nsh/Make.defs mode change 100755 => 100644 nuttx-configs/px4fmu-v2/nsh/defconfig mode change 100755 => 100644 nuttx-configs/px4io-v1/nsh/Make.defs mode change 100755 => 100644 nuttx-configs/px4io-v2/nsh/Make.defs diff --git a/makefiles/setup.mk b/makefiles/setup.mk old mode 100755 new mode 100644 diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk old mode 100755 new mode 100644 diff --git a/nuttx-configs/aerocore/nsh/Make.defs b/nuttx-configs/aerocore/nsh/Make.defs old mode 100755 new mode 100644 diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs old mode 100755 new mode 100644 diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs old mode 100755 new mode 100644 diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig old mode 100755 new mode 100644 diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs old mode 100755 new mode 100644 diff --git a/nuttx-configs/px4io-v2/nsh/Make.defs b/nuttx-configs/px4io-v2/nsh/Make.defs old mode 100755 new mode 100644 From 4b27e4029d15e5ae4936252f224ee4275f83cab0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 21 Jan 2015 15:32:38 +0100 Subject: [PATCH 42/73] Disabled stack checking on aerocore --- nuttx-configs/aerocore/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/aerocore/nsh/defconfig b/nuttx-configs/aerocore/nsh/defconfig index 317194f685..c44b074f31 100644 --- a/nuttx-configs/aerocore/nsh/defconfig +++ b/nuttx-configs/aerocore/nsh/defconfig @@ -94,7 +94,7 @@ CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set # CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARMV7M_STACKCHECK=n CONFIG_SERIAL_TERMIOS=y # From b3b5a2de0329aa42ab842bd568244aaa9fd8d40d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 21 Jan 2015 15:59:15 +0100 Subject: [PATCH 43/73] Set NuttX version to one which always colors the stack --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 574bac488f..e4c914e261 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 574bac488f384ddaa344378e25653c27124a2b69 +Subproject commit e4c914e261d2647e44d05222afa7aa3cc90d3c67 From 0943bd9a31896996db7a030715eb9d0e8626b0b4 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 21 Jan 2015 09:54:49 -1000 Subject: [PATCH 44/73] Added Prefix to message to identify it as PX4IO related --- src/drivers/px4io/px4io.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 1c9a5adc9a..8aecbb4693 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2856,7 +2856,7 @@ checkcrc(int argc, char *argv[]) } if (ret != OK) { - printf("check CRC failed - %d\n", ret); + printf("[PX4IO::checkcrc] check CRC failed - %d\n", ret); exit(1); } printf("CRCs match\n"); From e037b7ae9b361812e99c5985a9c543c2ba503de0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 21 Jan 2015 10:02:22 -1000 Subject: [PATCH 45/73] Added delay to ensure the the px4io is in loop waiting for a characterit loop. --- src/drivers/px4io/px4io_uploader.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index fb16f891f6..02e527695c 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -621,6 +621,7 @@ int PX4IO_Uploader::reboot() { send(PROTO_REBOOT); + up_udelay(100*1000); // Ensure the farend is in wait for char. send(PROTO_EOC); return OK; From 2a00948c7ad71f849223337d566c41b56f7e1e08 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Wed, 21 Jan 2015 10:19:24 -1000 Subject: [PATCH 46/73] Added prefix to Match Message also --- src/drivers/px4io/px4io.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 8aecbb4693..556eebab6d 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2859,7 +2859,7 @@ checkcrc(int argc, char *argv[]) printf("[PX4IO::checkcrc] check CRC failed - %d\n", ret); exit(1); } - printf("CRCs match\n"); + printf("[PX4IO::checkcrc] CRCs match\n"); exit(0); } From d80a00fad105a2dc98ab6ec415e28fa86f1ceed6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 21 Jan 2015 16:46:04 +0900 Subject: [PATCH 47/73] batt_smbus: disable if no batt 10seconds after startup --- src/drivers/batt_smbus/batt_smbus.cpp | 24 ++++++++++++++++++++++-- 1 file changed, 22 insertions(+), 2 deletions(-) diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 2b5fef4d77..92b752a282 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -91,6 +91,7 @@ #define BATT_SMBUS_MANUFACTURE_INFO 0x25 ///< cell voltage register #define BATT_SMBUS_CURRENT 0x2a ///< current register #define BATT_SMBUS_MEASUREMENT_INTERVAL_MS (1000000 / 10) ///< time in microseconds, measure at 10hz +#define BATT_SMBUS_TIMEOUT_MS 10000000 ///< timeout looking for battery 10seconds after startup #define BATT_SMBUS_PEC_POLYNOMIAL 0x07 ///< Polynomial for calculating PEC @@ -171,11 +172,13 @@ private: uint8_t get_PEC(uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const; // internal variables + bool _enabled; ///< true if we have successfully connected to battery work_s _work; ///< work queue for scheduling reads RingBuffer *_reports; ///< buffer of recorded voltages, currents struct battery_status_s _last_report; ///< last published report, used for test() orb_advert_t _batt_topic; ///< uORB battery topic orb_id_t _batt_orb_id; ///< uORB battery topic ID + uint64_t _start_time; ///< system time we first attempt to communicate with battery }; namespace @@ -189,13 +192,18 @@ extern "C" __EXPORT int batt_smbus_main(int argc, char *argv[]); BATT_SMBUS::BATT_SMBUS(int bus, uint16_t batt_smbus_addr) : I2C("batt_smbus", BATT_SMBUS_DEVICE_PATH, bus, batt_smbus_addr, 400000), + _enabled(false), _work{}, _reports(nullptr), _batt_topic(-1), - _batt_orb_id(nullptr) + _batt_orb_id(nullptr), + _start_time(0) { // work_cancel in the dtor will explode if we don't do this... memset(&_work, 0, sizeof(_work)); + + // capture startup time + _start_time = hrt_absolute_time(); } BATT_SMBUS::~BATT_SMBUS() @@ -330,11 +338,20 @@ BATT_SMBUS::cycle_trampoline(void *arg) void BATT_SMBUS::cycle() { + // get current time + uint64_t now = hrt_absolute_time(); + + // exit without rescheduling if we have failed to find a battery after 10 seconds + if (!_enabled && (now - _start_time > BATT_SMBUS_TIMEOUT_MS)) { + warnx("did not find smart battery"); + return; + } + // read data from sensor struct battery_status_s new_report; // set time of reading - new_report.timestamp = hrt_absolute_time(); + new_report.timestamp = now; // read voltage uint16_t tmp; @@ -375,6 +392,9 @@ BATT_SMBUS::cycle() // notify anyone waiting for data poll_notify(POLLIN); + + // record we are working + _enabled = true; } // schedule a fresh cycle call when the measurement is done From 30e32b004d6e9d0a4b13abf6ef5f93bfe7bb4754 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 21 Jan 2015 17:18:55 -0500 Subject: [PATCH 48/73] travis fix s3 index.html and timestamp.html upload these files were being uploaded as "/index.html" and "/timestamp.html" --- .travis.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 52ced6b4fc..8677bf91bf 100644 --- a/.travis.yml +++ b/.travis.yml @@ -61,7 +61,8 @@ after_script: - ./CI-Tools/s3cmd-put Firmware.zip archives/Firmware/$TRAVIS_BRANCH/`date "+%Y-%m-%d"`-$TRAVIS_BUILD_ID/ - ./CI-Tools/s3cmd-put CI-Tools/directory/index.html archives/Firmware/$TRAVIS_BRANCH/ # upload top level index.html and timestamp.html - - ./CI-Tools/s3cmd-put CI-Tools/index.html timestamp.html / + - ./CI-Tools/s3cmd-put CI-Tools/index.html index.html + - ./CI-Tools/s3cmd-put CI-Tools/timestamp.html timestamp.html deploy: provider: releases From 38ae6bcc5fd5e9ab1a7304140ec6b36ff027625f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 22 Jan 2015 07:24:22 +0100 Subject: [PATCH 49/73] Added block diagram --- Documentation/px4_block_diagram.odg | Bin 0 -> 42200 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 Documentation/px4_block_diagram.odg diff --git a/Documentation/px4_block_diagram.odg b/Documentation/px4_block_diagram.odg new file mode 100644 index 0000000000000000000000000000000000000000..95b6f600b87aedcb06535d5b330afbdb76d91c41 GIT binary patch literal 42200 zcmb5V1yo#3v#<-n-QC^Y-Q5Z9?(R--cXtm2hd^+54-6U{f(LiMgg5!l`=4{~zs}`Z zGi!Etbyam$?VjCxHi|MJpr}AVkU&6~Uzo)6K1oeUi;ERCHN{||+SmGd12pg=&s zU+)S{T@2|xY;AZ2-rfk^Or4zHRPqrs(K8Ygn%WuLn^@YJ^AW46h|_Tr3-Ckp+MAhK z8k=(ewL-~HjXGqg2z=5{gW{+t5Mk&WrUjT+in+Wv3V{FZ&6>Aw}2JDHfgIr2Y~^5!!O zgE@nVp^G7%o298c$zRX^naBTqwp{;hwkA%7?*G>jOpFY_Wrzv?(a!y^LS-iA|67&6 z)5p*Io(VVMs{|SKc@f7%0E{B zbACJjE`DbhOJlIE*8Ns&u68bb#GD)~#0>nrf0D`lPx${H{YS-n^FON)BqZef zvi7!;{pSz%?US>q%kNk^|6Yl9wAP)s*b)6s^%Kso3VaDepR9U8?I43;oP)muE$FQW zcYMOuypVK)eDx(WR-Rnk7%l^3jP;S3%d9tPRk;gP`92=d5mMB2gPApK&dOIzLMg`G zr%&Qcnyggm@Z@C*tky5VdMn;$V1NmlihWA93g=V;d?~B3=g1BRaEpA1;uZrAZ@oIC z1#QhxTgTUp8<|&MgZ#_@XHI0Q;l8@#a(7~8F)Tz$NopJvg=9Ci z^!XYyXVX(D`Fj8OKDy4m=sNhi*Qjr*d=AF_`E|kq$v`<-Ca%hZ7BXex<3&yl;((A6 zCZC)6oOQ*`vR_jD>Yhc5yLi>%A=9K(eTz1c>nl)}(#Qk(`Df%Ne zHe4|c|AAVcICcu_wOi*-qXNA7txtorF6I0N^~gh^d$Lz_|p9#t2k z4KO>X0@wxP1ePe`P9i!?iY=&3(FIqE6;`2{s3W5#8 z$W^qVHSoIE5@AL6l6+SEqcuo4xV51gOMMsB#sX2LzX&NK=h zIu%6|)Q#TY8TqMiwsy$a_kPf0utH}Kv!kMrkaS$6UqP53{LRLG$u%>Mca73{L5M4( zq4fg_Q1*2Co>v7C(pRYPhPvlWF8r@ZQ) z`7DnWxTknbxO;2<^r?^$vL3+3dEO(0{zNj;EEWr|h+a`+lZxzkIeC68pfSY3bF?3! zac-6AT@I#wl29#+q_mG7e61f1robwKk6OpIz2#<2c?x&><;yj|NHGR&AQ7G zjTnxp{*I#9U8!opkCfhHgulGCl(F*`$Oj5+{ZJ)oPwW zJ;+7NW_y$sqSFC!0mCfg(~6)OQt75eOPry7U0OIYL!rR1<}FKj8hdgh_!$1$>p?;@ zOydu3&#Z%LzZS4m$dtETjHJinUtx#MlZ#;hOlsGVlA^feE~T33l6rk<)sBQ>J*dqy zR=}gY<2c{ULZvSzxS%nLC?Rdg7C00A;t+e7k8hZ(+A+~R6jbG(rvu9)d>eioAJ`T~ z)S8OnNn=J_G0P~K@y-o^i3T!#z$#IFme4ne{!Zhg>rZknx*QCJGj%vD0{V-U-e|wW z7ei!2YQN&4nA(6bl#tZhO4ToQ$`-zvXT6}=Q=gsf62ndG^2rMTz+2*zAdZ2IxO9Aq*Cecy3{wrYAO^4D_qhhL|j5HDABlbpjFF7B7N=; z74ShJ6UzvJ`GJay7e!xx+0Gu2%_@75`POiO697Z32yy0D1O#UxFm{>U__{NH^}k=; z3wzx6WX*~zO**ai=&dfCHsS2RSFr19dpOu8Fm}IgTX{0Bi#KEb7C< z03#p#Bphx{UTnQ?+A2zyel8yv@aOvTVDU!puG5FE%M(Z>&FQY2)x5C#sB1Cn`?T2m zcsFx;-x^(cPG6a|v%8;e?Cq}O(oe4W^5OVcd9moh2v4l}vDkWD?%n(Puz-CL;Dtxu z7N+B0kE7`Fad&Of;PrbvoGVqxOH^Ran6%S(JbkWkaMRt~d}tjiUGi-{^t!Wh5$I*e z>e_beFl!|fX_(pL@PwH*5S#t(dw-Qw^ z9cOCWe^y93YQR$lj^!7KH8bXAYes1D&GHtGRT?aML>sT{>N;dn1l$?IcfgA;T%9kE zuX+Y%^7+`^aN;Tfj__*>whphQp`?V&U#xT) zJ+x%&_Taa>i7yvk6YHh!uuAgkX4Z9e1uiN~dnSOyCom|bJ-PgFS7NL6=GMJq9(23iuTXNG(q3imoFedU#?q)~(z>rrnt-hqT&Snm9gHq2M5`W~)-`BNA|Irm3 zFD#xC_w(+Ksh2X;2@$q8d{AbdH-rlx&g|&gN_LyJvsz>Fp#lu!CYBQ?;0rxUa81$V-cY|l z-Dai0zQx(d8$4%6eV$aX9EgT}Ij(s-9;`Gq?#*KXDL~O6wGMcuJ-7Gg0Wi@;&6HUQ zKle?O2J_;K7!s&o$&}qmMC)^M;a2XrU)_Nj55k5q@J@PTc5z@RxMUD+i ziL7nf*vvFSxWGFWPigi^GK?8m`a9daSU@ywvAmd__0^-7hR!dX#ErxrcLc2;JuD;b zC2s95M31Sq(rVe3A2^(`C#hKb(-^szp$~RHYZ{GA2VWu2n`;xX;gw0C%*beDOQ_&D z9yvB3BA~2Feu;8ZXi{IV?6kZWIUhlBzGj_E?!DiC3ers!-r z8{6hlco(Ky85`0uv=B^PVmx(6pmxbCtJsc99Lmq;K(Bs@Ns(QRX#H5gb3F#d_^{;A z!p-7~3p)f;mT2}m>zeN&KwxB)QUiTRbGqpbp=Bmd+T;RedOZXv>}N)Bx~0R6K`i1(VTX*I~QF)$2 zc|5n$H0K{FJRl70X4Ng8Mop}4H#Sp%0GFQyey_|N4jJYA3 z)ZKn|Xuip)N&?%9nkLb?VC|t#@x59#U}}#N$=V@PR=qY|s#h=}VDZCTiLKY$n`y~T z<35)9I=yWHBzACmLHBi9?g^4ut3PkE)BlHCPZ}NuYS{H1zQWeRARsI29+KupVcIIb zt5!(;IBPt&9g6`-Z|nYUL1_nSg~0 zXV+bnPcYG$E(EC~tb^O+O2ywp3$jSFh%yE4OD;^vhEa__9w0(4-&fvNX~fL7XU3d=q>5PR z->s42@2$2R|40h^yvtU~{BAAq;5~rCT>x~{%B_bs zl=sYpixcHHXW&3Rdt!TiJA!%g8Sa7kgGb4z#Q8&q_Qq*dIXH%N&>T(5;And0)>spl z0fY8*?wrC4lX8`As)F*y$X`^9tV6O!g8F7W%_< zI3s0KG-S{pijWKyFEEk7{~-P*pTsL3Jk8QesFlw}-H+XmEnyzR{-v}Zo6k4~R~;7X zg^Zu*9Zw>D#|DW}uyd$7@OK8MHG|xQTL|aN@^r-hE2ITEihnZ{uF$%HlBweN#YdP% z1UV1!jdt3+?>?6@J1F&kvZ$A;V8Q)Rav{|TKzWxy%)`x6u=w`Y1hw=hrwn5htQk3X z!G9=*;V)=8NgJbR81@#p`&o}6Q6RR~#XXb%c zAcH>Fp%^0mft46GvsC`yfwCZe07C+w{!k)=WQ}Nzo5N<&dJk479!q19;J$_OMpD`i zN~WFPTm4iDz2oRIpD(q8(T~jv760zs&tMq0I>Z->?Ag;>r8^-1v) zB~$g^Ds1LAqIXmE5p7WeiAHC}5r|RWNX8&V&Ghzb2^N+iz6nyK_ogPIi@3Y41D6x* zQkl<>v3=~tHVKW#x|ly?KL*=UM?FePhU4rIt5N>GFgxK2eW|B~~j-HSq)=nn^hikxy`|2hs55hWUlV;`5N0gS*h#De3$$sI&KX!a*fDvR&*=i3CuYYwNLR=O90Z`cNHu?v1+rt&LAckOdY@Nu zcB8a`f!CV@PFm{aE96$kl?yk=f27K-A1I9VZ74b56^-%35&sYkW+)R{>w5Nmx-_^O zvz^a#Oa!+?QEJHtABjQq9|gDEPT&P;8&WoR)`IhwN7?!fVRrTS{PoXOG>+5gIU!b2A)SeTeoUeME zF3@Q*Xeacs8j7`RG1BHAxMPu^%?I|yDdjqV@9P^$3^b#An%G22*PgA;tD}aJj;2Wo zI;9yPdh-O}L(ej|kEU6DLwcUKR}HFGc;!N)N@qdhHetWZ4pI)vRiYhUuvnmX<*^Dtcw(Vh{*G?{u}c#v`D#)=hy$VmIZnEtcc1D7E* zpIiW8V=XU@Kc5=AgMbdb%+vVJ%qi+Ri*F-s^Gnaq8%u{M`MRqYM3fw%kj__;UC)YJ zt#u4NYqS9B4u(aZBF%VNd15hfeZHED$%X``c#d3NxxC$ba8ElY)oRl z?c9wvU2_>W0GmuFXZB?vG_Q{XU}Fo~BI`pvcrN3%$Qt@uG(p#B*UDwHbMsCbc~$ZK z4>~cl%zH=0O3qUICPfh4-(0#=277SF3#XwKS>keHPKJuIB5~%QTj8bVF=(f$dFg%N z`;Jb=wpT5fHKO5bze?L>iCc-H+uwY|9*fAOm`R*in-8@#wwYb=DXUVFx93j4Y+CxF zi;c5$=8d55(Wcv(r>O@ods?zlvqc!vL;cONEro&uk@lv-pXbsc<)>@w14k`_l&<~f zYI7X0qbp8mG#S;##=uM`b%}Cctp`?#v@1|RI(v4;!p)@SoO|)1eth|<W1n9B-(oMF&{}^y&#OR3(FnSg}gzHp#_g)XXT8=XSkhff#P6WPs!*q*}~Di&B#7 z6_U3No8>qZZDu0D&FqbA3ZmXdU6cL3F=Lj@_BBUUHfHu;#H*&E=Dm2ehk+5Y6v7EScAFgjNSfvb&s$?yrOZT}3 z#TCglp(}|qlGw`R*v>E=oTZmLvo~$dU*B#t-J+>jav~F#LE{yj1@y)yA5R9j$|hAy z#IV9@MKq#Ho$6?=laF+Xu>@r9YpNAFh0XK@%f>|yy~dT(}hG|t;0j(k%>8Z ze1-<2xuL`eK*Ntxy~;!52=1);r`Za8Us^{aKxUp-M0p$;J8whNY?kDgi!{IWu-+4v z6!zICfCvAS?)31py5E+v(Qt~^X`FRo7Yj`II)x&%3qqfd+sThtMLAjh;Hz~GL zO|s+s$K1Ju^>l9e8g6;2BVYBQ5jKm$CL{Cf16kERFz+(&64+5UtzONV#ml<(GbJ9& z_V2ws1Y7?28sZ$JgC1gTt`Gixtq`#Cw-~THiUB)r zK?h$vJUD<3p8Q{@UOQ3^cZqPMPGC(dGeLeOErl^4oS|1Vt+e)PcCsbEl%5?f>zT!= zqd|07c_}~+4hh8Beg2AM$BgEd2W{@4UHsTHvNHI^;%?2Qy%~kP$o^vej^^D4Z4n$aWG9F}7h|1-sI&8w;B*51K&+BNVACVTEm=Sy0x>mo_|zyZ0@mxt%Qo?j0D1NO+Z z@lf}-+da)5nKARr&3>8^Q`H3bUJ@-_tzu_F1H(Tac!a(qP*yI9d`{$eyMxC2)tM>R z$EW=jSwC)fdwFCA;p?Oqv_80d_wl}*7j6oTE6;X@FTiPZcUy5KbL&lP%=*U8^>Cg)#FeJqj*wVj|pdMti1#vY})9CZ1%{L z_u=Z1%1)Y~PST+-RUqy3l~W`C(ve*Y_7uN#TWYZ@m!)YZkl`L?X0~X_0x0IT4F~J_ zM7+lz?scI}*WVMj0Oi8c32%GwDrn@`tA^WR?tH?7H7E;>g2&?Tp$#?6s@SaT;N>DelFbQbGR=;%;2s{_%FlzI{LJ+8o1fgEHAa?&a8utoJpA zoX9+^d&0|GWIs{i76do_2wuYzgkkNh>+62k)KJp;(+N2L)2`!FB+tzR$1(wNBtpOs z@mF0Z5`9gQiJL6bbF*={*S+=CaEnLZa*uVRhs6zc-F7;YoS`;*)&U#<=@q#9k5LX# zA^WZg)sBtHHXk`Q_qAaeUy2mj8}a?sg7YCx*GirCY7pRWBqNA0Qp)qF` zOzomOXV`u=KaXCUm(0tcse^kLQj!T3tj~^HO=4E<(OH6yKl5=TlAg`g`@Q!$}T(aF2 zA;D*C^4`WWLFgLqChwlgyp&oG2CrjvNg%@A^X4(m2vpZ!(x5q} zfI02A9@q3=;e~|O^gv!;6p8~-0{@`~DSHPg+ckK@6EFKw9`R}7mH;sqvIpv&Dcl}= zm@b9XY@Kv|V#=Z5`b;QwDD^2+b%oryXphV>D|DzM`Y-pwiYds2P^wU>3=pbuxrlIO zR!&gUAEI?f!|)aPSqrEO4nqnLr!NbDRc+}Bv`7nsT=ttzshl&I)1dO8@}|)9teMju zw;S1p&X#T)y*x%&7mUI=xbG?F6tRJiqjLI}Im_qzdK>7~`E(|?{Nh~J zoe9p$S%GE{6b@dqI4(%apU0nZEN+mXn-8IYnaVkklA;DJ1J66dEqSzGI$xI~>+w8E zZ^rTEN56AhlB%ElnQ&Zq)hSevM!iU_WkqiP8(LO(X0@xPVi3qZ*Dk z)+JW(eUUo+y~|QAw&o)g4o4OfOods6-f-m3ER&HLaMX&3v#qa{E%c$HNFigk;m|yK zi8Sp+ThPO#YrJGX1#*VE9h91k-V`?Sp>vAZmc_PZ9Tww?ldofr#NII_O_5U&65+)p zvhB~nw8DqF%O`;l@a?xPwl$IaDc6sdOoal~v!P>RbU=d9m!w0xAwz;r)8kTUViU|! z$5h9z2w7@`;pc=xh0lXm0&(V2Wdyu#VMJhw;#?UR*Am?vR)HH=+{DgIJF`a3Ipja# zG+5zk%|_PDj&kf`q&X6*47L9K$6h=R@kI-I?GK2=~5KthT(0#2X9x<;xM# z*GW6@qT(5prA@>|&OgnFRmk4x&`_z;mvrJNuNQ5L^k|7+V&(3J*<&fQLat&^S{FS6 zrzNs%`HmhQ5})u!UDvS2k+3C;E{HBATExKoF0+9kmMWKMLsnL#JmQtTM#p)e#V!eZ zbP9qU3?3Dp^9cz;7iknLOOJLBR$844`_|h|9u5tvc~ne(OQEMFT(vm(d%_Kpg$pw? z{|t8L>?3CG#&?3=%_Zjf-a%ogCvGGekoAhHm`z}<0r4Sx{>!VhB=~Z&7}YbGK6Q!8 z5}soIu{I<=RWXs`pIlz`I(r8r?(D9i`w{Pak@2$H-du=aL&Nv8_n3t1wShGf zBScNxu*R&x0nH31EmxO@UrTlO4~D$=A&QyrJOnCg?J2g7jI!YsHORFeKz?qjRura` zduKIHbDmF|ERxKsMI4o92V1Fe3;8-=n>;E?bq6=tv<@B>1EJT7q|BdS{l$-!TZ^_O zX1UTi^mG*Z5%7p0di)Q3`8Su)x_9s*82&i=ai57CnA$!U5cQ9qB_}89Ko9J9v$D*6Ll$3&gRW;PxxT1 zU(@N2#SFQHwcl8l5n7%Aol>P3CUAx7U)f>r<8!bqKj;$)lo}{Hcb;g+3^aUa^J}nS zN|2!|C?|s1h1~e@egWSMnlFAG4>}pW0vD_6r#MI^n;E@OCX`c&s()E2}QIwg&|S6E#j43>CP!Z@_x4)>Uj6*Z%Z@Qy1e;MUE*4@H;%y;~nm8cjb^Gp&a9o@0XtlX0< z#<**Q1J>ZuE}k2=nzTGWenx@D5QMeU?i;(_bxNQb*Q4cVbK!!!>j`oCC2uj9$MvMP zmPS|J=)uhnr)JFKKbv7m*tSuXxAt_GkRJKY;gKPA#$A;x*?8h;dAhXPd4kob#7xaS zq@SC(R3#P}RNi*+^`;&V7rG=>7lsi;K|wqTS_grwcrumPtmqrFFjj}qftvV%nhS_4 zV!5+n0|w`;6tLv)baKM(da|XvSAoOK2N>^)T=jW$N-}X0Ba*+v4}oZx$z^;=*v`XZ zserhvD~pM_p*KIh4kQN^_zw(_fnxlkRBl6*x4{NW*q{6{6~z16dTfNwWZqeZxZ{&g zPHdC?AQ%3zTqk~pTzKcg^2y0I!<5cRNjisSGL-b|7nY+jxzDxnK3^mCol0?|nvJ6Q ztjQO3$3u+ZjMARt=jYQ;a%ak;ZssLv6lcE3E*f41?#l-vCd=7$Ss5lTwMUwjw81%MeS)mNnPz@Vy?DSO^VIVl!4kokl5 z2kkkq#ZJ!$-1%pq{v4EftgY2&&KfZ*+>K~Az8ts_!F3x%j9G*SF z-THGGfW>@_u#%F@KY0v%$OFIA*8yMlb@{A@$m8Sky}i9wGJ5i1KUh9`gR7K$1u4)b z#g03RX6@j!b4D*VM~))yvkSg?wMJiF3KBAZgPS$JstH#>gy@%Q(A`_qbhD{mnh1hP z2?N?T4PPG5Dk>9%0Ly{a_%uEZJ@WH;bFy!#!&)ZvBXH6#ISY|CbU~k)x8Y38@*@)r z_E{D}`GyFEpZceytePQ;s`KzWYZkF(5g8&UoYxgCcxb~?oK44Pwn2|6iYP$_cZ0G-K&K`s+`JZ@84{-3A?t_KyTI;X zHm-ySW%PjRW6kSJG#W889LeZ=LZ-609K$C~NY_#vxvnEM1Is0k50sZ<`v7}%? z7;rJF0z!(>Y)sSYXmX;;|DW>+7%cfvc7U3iG$$6rRSX z9%h%%#*euaab&6Gf$7E{XM1@s3EA#kF8qc<5tLvbSPv%>q#GEQ_?vZ$y%qaAiEX8k ztRuE~ZST-7zr!d9VwC{XeKf2t@y0x_HdzBZAN{Nh*I(f%-URP7H+3E{=q6RpJN?Tb z-Q+uIPLD}YM}*!k=~#Vp%^_l~A&5meJ# z9d1_T-PJEgj3rJ4$Hw5QieExy8>y(pcQX~hm|^=bMNBTgmV;Rk%gcCtW1qAWhrQPy zd6j-yc)8biCoHN|_+T9vJwC?FY6hM5ecu-!r{%k@;Wly;bhv6SNxLT)ZOf2o);iT_ zJ2#J|^uUx{=6%fCqv*CYatz8JFv2Cc3eQQTlPuarurUHHvj5O7$lHq?L!gu?x{Wu} z3=rM^3)t3qw8c~S3@P?${2)gL?%#INZ5j(!(QS!j@@WrsR`?Zi+G)-|G>?lEq5kO# zW1WQkPlrc<2PXx#Kp|_yAWyO5PWWKNA7J{6$foa*N~BoVh+;5E(ErOwgz9fayIcT| z+^M+6z}ULS>inR?M1GI4?Q%93{ zW=Z(d?fT2q`iu7|Y0+wDVnUUg-b0_kx8^8(@TR0`Bi?AigVrwoL<^JW`7dp^yC@NA zC1mGOg*~ceE_PdCGPB==T)VaIDZfs=U7|5J$E_)tM+G%utq1(NwstIE!PlnQsdQ+z z<#Ds5`DT2JlXkS%i#>IK>`WhZ4*@Cvwv&E-bRR#c=D_lJ-{kvnuEdN@dELPcpEJ6xKK32ivgllZ8f!;`3K1>UO-y z&?EUQ58NDH`#*QZ)VQhFth*%|cOLp3^{p*U58yf{SeT8(lZ#}+S~3@R*@?6!qroli zPflDM)iG9a?2%7&di6z7?e=f|WvAG}=v+QTiq@|I*7?5z;3Usl=TX{AiY}lP$W_Pr z2M;c?OpW%BhR9I_G+o(}e`(J~k|SOF!Z?-Dk8`5`og5I)fFZZe08sok&iZsP5l6r? z0;yAQ`cUhhslY^{n0P2sj_`%Q_#yuAqqI>{@q-K1xU-tC*U;8|wBWy7K*ss&f;i#7 zT!@JI;{qK?yhipP+Ozw`Y2RFk7>G+jk|dS?gPyz*3G%5*`kw3-Ln0Do@+uFBV&gcZ z&!sPi3~2S5z3(E=KxsN+ndBwWL>McK=J+WIL-U~j#Kcz;{^YoIQ{?f zH3jisaeDLhPn|ZpMO1RmB}gKhQSp#ph_bSbn7FhuScM~*!TS8=-m@K7CE|o!QTAz$=A(`<@Ieo8E_9k}Vk}LIZLHBR%Gzk7JXKxR+Kl)H z+ggY^=(W=o(aUywz!kO?+boC4f1lL{pk05uJO9o*mP2jyyn)7J`kDD2l_ud_WPr>Q zF%4nr$!ry7lsF)^OV`BVC9bGv%ku4a0Ju+aZ~JPibKPLO@^nXoZOQ6QkSFrhWS5UK za#QLYY>l5_S8bA5yQ~tQrrG_Hva*BOG$@2KDho?cNSu0HGxno1U4byiDi-|xZq<0m z+6Fhm&TZIp2HXKlcMAt5OwD1rEX{dw7o~X;Z;w1`@Gg-&?aG%2m>8~~0`L!jRG(~wa=+Kh?c$nyk5u>ab?4X)40 z%b5i~Ht=Z|>E+4o3=|Dm31K^nYSs$Q{9t5g=#k<4+Je6`r~eaO(cFPLoRmbQ*8Gxf zUy!cl*!Y%Ms0OD(^LR_7SZ|R2%Z$!IZ*4zSb!CIHhJuCs8*4JGZ;Nd&UA9BQJ9R_N z!`6mMCLO3=a{!pI>vSp&Wv9N&;4idhnf*JAD9|SI8NB0`Pkqbo)B5E3$rAtVrwa?8 z3nCQm-{b*vM^&A*g9OkNdC7pv6SSHeD3Bp_kZV`vyIMcwmI!zVsVEj9pf-*sM`lWwKRF zP1!%D7nZAYhm{LM3eVw|YmpLG5f-+ zk{#J(&V}TcH^`I!kld_P5l*U>E|V_v8Z0ZfR#IgbRHf4i*;Z}-Q0|o`p}Op(7SinX zeDkcpT2zQ#kdg}3r0iAQPV7Ve#t9k!f^7I{+^HG?zqSigT#cCfSQPeXnTinTWE~xct?corwADV_3xY6>cQpJ=&EfO1(`*6imxhrBDR;` zPX*d3hG@CWpst{Pnv zGuP@wV}~;pdON3=%npS?i&XzpXA(`=SGQ2p4I`ORs!vUov&s~qyb>iP&wKTi8l&VF ziuNjv*T?O`c=!3c+Gk)B-(TLhtV+2Wx|vl1^p;T!f&M5mF^XLHiB|SizbS;zBbcIznW+`OR-O_%YVGm!=;1W4VgRp$fD^%7qC3MVU1Ps ztzFG9C^d}ie5v*~yd``TU>Ssdt6T+__j=;7;^?Iap#cx8_*)kh@Pau<0vo>2`t zhKCoX{HLuq?FmP%{PV>Zb>wqn8Ym|girKi|j|`IHBWOI8)f@N0Fw$1cAGDOeGnUjWPxd~VfuGUJ0+o2TEDj|hco%oT;k;`+b%5MPov$Si$ zK;u(y8>_bu_PY!WYpAFv&aoUwJ1Bq1BVTigjb5i*105f}8W_mhs0u#RZ;wzvu1t$t zO>Tm8q=4mcR8rcMH7s)y&ylLAJf4RXO7Z|ehs=lZMRPdjm0d=12rXapdVGuwzUmq+ zp)%p0Hb=Mrp}WHp!EqjWANoH$HEM^t3(8giQz6?!`CY^J`Bnls3UJ$UK;3)0zE+s_ zfe^ZHG6297_nK(3!XNxIJpfqDeqTLMp!YAfAU_@<&hdJpdE1hpPAR ze&%vuD&q8?|gYbyCi(-zxyIp?E^i>(C{8g1+N;6wO-QGL}0p^lQ z?UB5#;3}UnFP~9=gu8^1K(o{&CpXTu6-Ct(MupD;OGJua;Nt#05lnB1*jsSG67lqt z?+P8m9F2m#?6G#m+WmO_xbN0~S7Hhqaq$<0uhE;oXK4z%Ll%0!QAJNOPBFerRG$B8hK&bD~1Dwhq#NP8+>2LMX6P!rojBG>xIP&?Mtv20zw%0bL={#FuGam zJw3KiBl2q4fCYP|cz{(`C;PB$oXs3~eH6Q3)vqf##h)Mzq||Ud?3=bJ7E@y}JAiPl zgxB4-ivf618 zmLz4eSTm8|PpB?^3T_ka->jH%&X?d1CcaBG{6%bMY)AaXh=^pun85MvYlBv$c&WZy zT)AIZVsywr)Gz|!mXr2;lgRGlr?f>4MxRKNJJiW@a$2Oip9xNv8sQFv8wSnX2x7dc z(2+*;!V$1!X9H(&%v;#jA!OtqKQx-w1>3XVBNIrg^cUzE&^%}au&Pi_YkX`L?^!tF z!r!ojDh;dP@gdcrM0T!Z&JANoanK72MULEPk3m(KTD}5WhZN}Bentd?SSKSxxAd?N ztsiJB=L1=&FZEL`~!GJfDzL6 z9Xb#w0ML@WN9RWyRNtF6tiTvPVFYhGtc4nXYuD>`$85K7_1;w6F38!Ih#FHeAmT~9NHGj2xy0Tydq#|z37EYghZ#VE<<1Mjy_YGw7iRYD zVX)J{NmOpUT((WxWD6hME14K~D-ReJ1c>j;8&c@iLkzuk5NuZ-98LEhaM{mHFxBo( zvZl_UX?;S4s2!R&qr9G~5KGSdED(dM2(d!I_)!-X4Qi1U5v?e7DIuHERRadNAJ1sx z7_!m31@7!nzreB$>l6xu2?N8ZpE-y%L(23P1dDGks-77|Y+&bF^?jUpaPdMU4e$G) z1r%&uH>oH?E7U%QR%Q=!P}P>Mt>!2!N?oLXXja>fp1I^CK4+c>5Gj}&<3$6#@qAt42lV3 zauP&gAE^2cikc>r5)s#e-yks?=P5j$7dHI3x5(5>;YOo72=OBpv)n$3Mm+pMx32Vr zXFk!d6RUm9a4@AMV}jrZsj#Xc;_b~ZjEp5=nc9M^yL^d1YfQBv(ISlx(G8YyKWkb* zWPYk0wX}`Q1XC9e_y#0!5g8(l+Fq`zWrWdWD8&olkZ$ErLjlM)ACsHPfG~@V+I#66 zL$A=$p=av}O`%bsQ)M@M&qHBsICq7{fSQGBIgmDxeP-{F^g$AM`Mv?)A-l|{ zFi9WqN$T-Iw`%82J|GeS>W)IXDWD*+Bx;qx6(3W876ALT5I_csPa-o24rLN?(?|Bu z=X|yZF<3hclWiN`3-(I_4IE1dLPImKS;}zL)_~6d{H+kWMFLhg+9A6Uz5{zS_j_VE zteHqZA>WyPiUkT&-1u;Iq)4bNDbc+k(;bFDFIWjzR+9=wk1DCc8w0Ei;N(RD=dw!2 z*Necx{DOPMw||yj*liw*P3A;*)!P?pHx?~~X@zFTMCT5xS0%KKq09nD?rM0Z#gLq; z(*rT2Yk1YGjYH9*#CYiVwPu)9){Blc9Bdp4QzfMcqZ2Nfy%DQT0|*bIK?MRbf}5|< ztr@Z>yFd-EK})FQzEj`VcaxR4@9LLFv#7d^Bt zWxZsLGuj{#C4P4p=DE<@|H#BGN@*!wBsxM=X&fw%6EnI8(wKvCd@2(IWlv>7*voLM z-oFI}k%y@$+4_!@k7Qd|0OH+k5DmP9y(}M?0(#tKDH`>IgP_--y8wuqei$E$y&HFM z*rBqZ0GwH3P;5@=Ep&q@>5lN)AlJxv^b$Bsn7+)crWQsvWO$nRl{8@nHbI-9c!EbQ zKYMPNJ=mj-BewO5N$_m*3`B|twQ$9qt-QgC6tEjQl<`O?JKQueGRoJ^;Ccu@Xd_+A zg*~Ifee?iGiog*UBNBRhAaA%9Z#q)9Lkum5!|8$Yptufp3uz!D;(Y>7*AKuZ1Ccl| z$SHWiclqW31D*ekLhZ4@+BN8*y2U&9i)?a@q?B8v{Xv#PE*D7I7trqDruq%7T4_!} z%$-Wd#RWkSL~!Wr6lp958@XGMkPliyHV=8I0f;^9624rjglLJZtaw`J-%Dw)c!IR> z4_Afw!oNcgiH8U?nu85>(+4r{iy@zK7(^3qgHYy!BdiV@c6G189FHiXNceuR1&!bX z<$-d_5e^(mq9sf=0M8#1!PpL$$t5WJ(P+t^a8}+ClDszOqlR-Jysc>sjS5s{0_4W2 z{HaeAF@^IJ&h{r@-cJ%aABK=9k|!Go@=+R~P(+Yc_=G5cD#r4|gO~_0VQyeVs0D8Z z#o>Nnu|mhHz>PLvK(c=l!!Tv;%pG4Yw9*vEY$UX}aoA2)+NO*N6y8kGY z13d!j@(nT*8WBsYt)#{T62y05{2yK%Ykb_om{BHc|ZoR@rnm6-3t3h(8a)?z98Bl z9dWh-&N$I~RMFavdK^;)M9Cw92u2Ez=x{U1ip^p{#wZn&j}LLn!nr+Q0rt?}KZXBo8`>Sa>+o z2u5pwKezFaBZWZsN#J&st=|ZNl~-cjeY+U+aZ`Hx`eJSW7?uy683W@d5R2O4$PJ#C zwk1oJGRSE+9^4v9K*ABjyAsw>R`?rl;O17OJ0!V6B9CxvB&4e-inkB!EzA zdPv*QgJcnyrck95MB9v@=|E5)O%V@vOQfxr)cT=7v^m?Jv6*LqqacWp(j~OOG)(ST zsIAYf9=-}8LL{fa7-}t;=}H^(SKB@{r=pZSTd-*_wazVhv4w4kq9JFr?y(YpKH5N# z!NWRV#`1oK#~ut)7-zdjPpWCBB3}_*XMNm+Gr8^>GPMFJ`T_Tfi#K^VWRq4q)(Wje zgfJQ%m%xaxej4)w9>ml><9<*QJ8sqlryRtPS$G&zcI*tJn&NqoHDC&Q%9bB~+rape z(W?3Xq3RugEQhwR?Y3?AwC$d@ZEIT7wr$(CF>TwnZQHiKp1Jq_|M%5X=Ts`$*-6em zl}grH@4KP5k};cg*TIM|7)UNG3FrHR*Jfj}_$Xl(bc~A~Vi<7*B#L%?bq4nUgdQPw zd>up8A`LLxYfL{11EUKf4i+jd^BT`}fCr5fy40XqAU(A~I z42UvBhe)EhDv~Qblq{>!P43lcGCxxN8m=}2cFGRRfXmVA31DOcdl2Q~^yE-?sN|}U zd<$o^MYFjZlSPXSj`O*unHCr6k!wfWE60&mVYGbkjYu%Gb$+L}-y9%=CY&*ou0lkz z(};D#ZHv1>kEY2v4x&F|U9bS7mn_4#z@{-oNSa6)j5){^I^E%Dph@G_hvpg+)^sO= zDN*+uqjSiH7>sOp^Gk>A5PY)<-jiGn)IUG8x1{c&>#kEq@Zlg9gBHtObhjLH>>sDb6FmBFz|;6a=u!wo ziALJu=~+W4oTwr7jKC1hm^n}kGY6qa{i=sSAfP8jT9*(3S5>-ZFVsf}UN&v5Wkl6V zwX|o{Q3YFAW-=|H-$eN(MrD-9Z{8g=9x+Tht`|jfZ$$rNc4E5>hFu6f+ZHUB$Ttvx z^cB&UKww;?+^>h4ue?{l!ouQ;nOKinASYaLCpd@XUK{@%VjVnF*hfakKQ5X>G9V0& z1rbaY(FlhnO*CA$q}LAqhWJ;hVNxpbm0PbCY6dgWAssmRaWfM` zlTN)`AHX@F2vd5D-VE(-wm&3?@M;u2adr#1eZA8^Dd!lNw|xQi0(K!ZAnu@ZJc*-> z!fCm)N?(tQMfC)-k+I%=G>RGY_Ms9Djv=5P!~!SJwqLZc;-}G>;r0+TpeHc`!najn zKKbXJxPAOY$@#d`{0U5n`rsCb*6LAY?~UNMr6f(e$_n`;gESfd+~txqeS7uyL9qfc zu_IiGzKc4f48c3rZel; z+dG)?K~lo^u%Q&E=Rpk#miq5YrppZwa81oI0I%YArwb1Yr1VY0ck|?^Lu7<7(_-(c zvk?v`u=61UN&C#_1|@_iz>tas#L8mi%khuD>f{MO*J){_LLG6!-1&27=!7%CHb<>y zz(ZDI>@kC_F0fTG?>Xj=<~02>OyF{`UfC{@A@bx>LoHr>?pEy~1%~D9&eN(xkLcNM z4N@Q$lp0ZhI|sxDBITd?&7S6;g#LcOS4_H{*QZM&x5tRV1p~=U{Rk%wuC(m8R^D0S zv@gk;$)?O}UFy4Jv8GP1Knie}S|FmesmI0jWu8ShKr%#*#G3Q!Yt=MLm-C{){5$MW z(s1(8uycNL!AN7`!p0DpK=nJur|=!)18P7KSb!;22Q$M_o9OL^C*t}SU^;!tGsBL? z0kf6FYthsVD^-8SDfP>gDNYkqHpLAY5%Yy4{$Gr5vRIwhTAjs5S*sz;`i~7{+2(=n zf>E**#S}V-&=ya&oMy-8^$z^ccuC0o|1Z`TK>E!kiNKPJwX>V~8G2*DW#=zk%}NgM z9UIBl`6$N#b~>7o%XaJF1DnsjN?|lOkMlhpwlJRc=-{95ycra30gv?-3_ILAAHTLe zn~rJkjypB9wn8rlGO=6vpLnAWzx7PB+?`)Lt~S|^cz(|Rc#`yUP7HQlz}x(g-~Ono zyD_O<2I{lK`vfcAbGoH3U9$=Ok@b&HE&}Z%0_~Q9g+7=Hl(at!Xs!V$-W`&1(9UkH|llI1Y+Kf2~XRtUzTAH>40SEnt#TDZA# zEu(u}vK61UllLu0oY#Ihl3fyn8|@+vDlM8udDu0#{{5}Na%~ESsyfPS=k&$}M24T=67?OreRI+?pK{<@INCK1 zlSJxT;7(`cbs3Weeb686hKqZY@rz}>DglIsvk*^T^WT|cc;Nk~vF{v+3|aWf z{il}_vM#X&>3^vlFv{#PS^;F~O3%Z5N*>W;Zo|~PM-lHe{N~`U=U_E+(e*>1u+9FA zy4z@=_S~p04i6|nyjGI$CBW73814M^^dWu6284qS;MwthrwIQGViFU-yk?`={&h@kL z%rNY)wb%sfnOKzj)G*5nC|t-VsqNG#kT|{CiDCC>ZgTYjJrS&qY;Q^RD%AiM$lJ=oUhV=L|hyb_DvfK2#*HP7MBaf2dQYpO*xEkdoO zT5J*=A+@fj^c4;WxLu+a;hXE<6>xh48-gGToq`%3&yv&P4yvUZs!Wi|UNi`f0S$bM zVG^80{!xAw(e#QQ3u@@+Lpi1a{bBuKM}1+LJ?>sKF%P=IuDG~8Z?P)3Z+#vNUd{LI z)&kDoJTVD8p{Ju2A@w*(him+y#E`H2FD@v0MSG;cMNJmpeQ*%{cck;bpr;+)Y zjn)+1-TEs?XX7=n4{izYQp^)VX6PWtDbK;#B@YY+x);lIFA)oK}Oc&7tCp!I!e*vdm+Cwf1SIOUstE@XR<1V#w`&p)0 z5zN$+l~`TG)F4T?HvYQ;eI;(yECG5kc36ntz>j}GA$Eu56jyDHE_;0sX@a69_&NET zC#2q#mjgNFw*$E`FR|nlxIaZ*EqGkCgHxg*243yyk%!K6Z)ecXq6*aU-?z5UGymsz zDB@CoR56LrkPW`~uLtJlEYSN?y!|gWZEA=u$bZnmY~76wl)@#2(-;yu`Com3RfODi zh%9aFy{)Y{@I-%)Y2A#c0J-cxw!jm-Ya)cQi!-4gs;YjekX}7i{SIwhy|QL1Tw_A& z;CN`gL&Xd=^i5XRASsq({H5DM@TO`=Tz_Nq#(HEBDj<(TTMskVXkYB50xkecb*C^1C2LVVI|@r z{ztnM54HQqs7J_Bvzug%*Ilj|Px;zvVSjK*vJ}%N^>XIz=W=fY% zf$I~8H->b|L1)*&CP;f%#1+fB_$8Rm;1EhoULp?Nq=+jyhh{;%IXY9YBUStP3srmS z^q!6Kr5m`QRTmd7s%O6jFh)Od^B)yEWlLC;5!l6z@T*{`zC~2b^RXA7r-{y3!##xn~2C8)Z z(R`q7g?&W&O$)7`W9D3g(#yL?+Nv;28s6KkItcH-=D&YqHd4?; zwX!`#El1sy6}1_SFPhTgrku3)uotF+$A^kBq31DpyAGZ+f7Wx3rET*s?F_UzPW1kA zu?-1E%Qr{gnc7RPP3M~Yf9d1IVKlkaGqrQ)E?Nh}+e!x$N*fuRiw1o-=p?-OlOQb1 z?rFylKiu!Jli2Dn%MDgd|3p%is}!@<$(Yl$Ps54u86aPE*T!wykq<;}cD7KKi6|69 zSS_2B;U&Hkh-wM;Qmo61_M<`V1j9H#vpehX2>0M&Kw*}M?Iel}6@5oy3E^aq5IuOUSck7U zb0tX8?A!4=)dzZEcHr>%3BtE?t?>4Ul&Dd?d?>5cT;HvVgTiV`oiHYcdWTq4kgkF_ zx-X!v!l8ZdeI*xvnygQ`$! zRMcF3t9(I8+XK_>+cWo)dlzi9`=JW4H4sqX^N?$Nul(KUA@gFdiCxe%v9Ud{W2n4> zvUhMBUK=c=b-pZ3#Ol?B%IeV*WNL?r*AK6uvmDTyozP(F`!OdY0jN?97jemivrt?W z_T7tyw~T<@sSqpRp~C>8-X!J|Xyg>Fo%6!(3DYe;?>6=FkC2ME%^*?AT*z8e`1G9v+tG4Y>%R|T3 zPQBP9fd&zhiT1c{0l8-3pL&J0h;L^4d5Z{*71|LkP@M>a4Q}5yx9EV{aw?swgI1Sw z8aMr}Q|;AQUS_1wbR_guK-ys%9S0S+PV*-t+H}(9dhY+_O}~a)HeiXXI6Vr*ot0@7UqlGovw} zBloPkkH#A%`~=dBo9iS(nwH-AfwmE4S?&d0FWQ@`~(-NN@y%GG;@@_t9%!Czaz zlIx@ynX1csFr}JtwK5KlO~=xSk_wx@4wxY6dcq6t;zzjhAdpi<4e&DaT^-zt6bX9! zl`e|rN`8ev0;Z@A>A9UbnW5?Tvfh1W;K)YiNnNX#4$8XV>5}Go z{FnE+{?y6X8*I=t8@r0lB%hhKB{L*bzouEUbS(QcHDo$)W|z3{#IFF>V8g9e6ZHR+ z`#ra)D?!xQm8SAj!+&JhBt~-Az9CI4&H}fVh>iJF{Z3PB9=(q5N^_QZ(B6>7x`eT! zjuVHm#-<7x&Az0F7d`Qy?n&oh#NL(ol+6ZHEMSUT^=K1HLv&#;}eH z<-T%3mgo5|pQgLg#>3AOyV8sd=zq7ig}B6vy|)ac8}!15u`bZsPo-aY;+*z&}TzG`YGYe5FjMjWP4fa6oS-2a zBY*9M8h&V_SEHn!dVi0AQCZLW5>|3Rd)Z*H@E3ELC*qb5G+fAM&1_!8?~VzH9^Tqt zBSzf#>5gQ@i`MZC*h=tFpEdmq>N_TUS$zNMMuZo<+<>sbzHEjvm^Ai^b+4mI&@o>7 zJjvQLX5^NxjOGxxk_Ehlp8rP?FA?Ms0qc{%zY zSG6luRGQANn$8=$Zs;l#!P#E#`cEmJ!BgQY0HJYwng8ej&(S_>IDB~dX+)+|CS;xA zoL-$LztW7#8aj2h2QKPyzi{^bfW?vbLZ{RU`ylb|NFQh8E(kbji z&x`~qb9)e^;UdkrfK7t9(^H<6F3~Mp6aM?z_NT5*K+G}z&{H^~D}2b? zUtYUCTN1@@cUog8kfY9!k{!!X#T%o(jwB!cMXo374c z$j$9OdTi#-u#QMz9yWfhc_#lTalZWN3Q8vl&3*tir)sm3prj2MgW<|;~-X}0VSa@wEVHd9_&ydhook4dy7%@vH z_M00I-I~l%bEyu(?}lQcssrrPe1Up4DTTPG4cqc448hfklSb;Yq~4!~Bo?fjtLFNAO|Rb8;7S@^Q%pwy}D(K0rd;^_01afH@B0tKV!EBOEy)%l0@kn)hjwyO1VVUJBAOE z>zxZHv}y%rPX^pai|qt)^34nqv}QJU!XDw89778Y&S@Vfl5RNT%Fi3&2BgVwOWj_) z*Z9<&Hgd6Ozr2Yl4xFLYY2KUB;@9*IhiTS`m8{SVgd#H-sRVbm`KfoMC?CrMTl%z+ zZQ4lcH1rzGt4CEdf_-ZVB|d?&T(TzgkwfbVj}{k#X?strw7(4f{=9DUxPhN8&RN{k zr`4~$ofVBVZvgZ8zj~?HB|V)u!7>$gRNa=fS=y;NRoRVl62@BmW^t=))Hog*eNNWg zwJfYgh0{n;EY;UPb$Qc{r4epKSy3>M^h9l(kIJlKtnQF}NOYgo*%(ayrD0Zgr%W{A ze4s3JU7DcyQ6B&no~yhEu^TaH@_DRnEQU<})ce@}w@BSsMjMu0n~sQP2L_K=qnbmx zQ9ZdPqRQ>F`iOwA9sKBq0W%DLvK=V+Ci*?S6J_dLyqd@NB|8nhblkcZp4jjL!ie5?aP++ zG^j95kI~14dilAxAzs0sV*M|HRrzHR26U zvuY+cHq^&P(bR)TrsJvuf>Akup92CxVPm|EKcVHwIJ7{9Dk0h)+ao+ zsY~!%>uW=sLd#Krs+o-Tkuy(IN(CqBfxQ+AkSJ;d?35<$VhLGF8TG+d=KO9WfWQ|T z#T`Wo76`!o{bL;xfX9Rb_yT-Z2@wXT8DKCNAXl&q3Iher2ZaO02NObT5KvYZgJ0tm z16!q^(t~eXaXAdkyYIIP5{$(&l1o@HT<*4l2hzNFMnQ?@f+i=0Q!N$@73c(LUw`R) z4$xhcAo^p3_z>c6B540nELfjooV^ry`4y!};JDCo+=vu^WQpoJ!J?p=e4%q9Vw?oF z3{Y2pX4GB+0c{K>xU|3?6MoVF0a)QhNgXouy=Q-0FaYR1CfrycY&bk%eepDmRh|J} z5V0sCh*!W}a(_YaWX>OAx-xSre+VVzsNAc82zO#IDYRwXF&C=Z>S$wH2yFGo; z%2uLV<{w_{-Cj6dY&o^dhv-wekF-5)X6e6ycsEWG$twTK*CYEDcQMJIQefLH;kj3 z%1PG`dlC`w{x5pW;WwdU_V_*_mEd*e#cTJ6MqD_7@*L6EM@{}@$Cvau!8a2qub*zO z!fv-WH=mLo+-cF)WDNAnCXTPlf|;V$sW5eG=<-m31}qB`S)WL&nMrYzrkFu@{rUb< zkOvd16hi7?rkDkW_wr-QpoNXF2}v2Pv`t*#=r1&Rm^~E#I63G&;Rh41FfuzuQJg`I zdW3*x7X?Q{R^Xtco(l;4%f~?P+f4x$aFZ1G%4Gt@xaG1`GBh4$X7(TC$)tBewGu6R z{lKYJ=@fDip?`R#9lCQgHWCrhgJkqz6!? zgw_w&qtFx$f(1kgnpAWL3x^yCO&LaJM~A<~7U9f)MytgNF{LtkT){xmkWKVPQhWE& zn&Iax^#gfvNc+hVcSHk212uIzVM(ca*dsBSHha-s$3Z|YgQ^}RL`SV zUODRB7bF5Cf*Wj5J$NLEW+9DTN+NX_=3Xpuj>!=Y9#;eVSU5R2EMp;cr7TU<0s}g* z5(*JAV;_5mSO*m{1DD#Mfb0E{x|YonylBlf@Xp&tqBNXM5$8ylF*u%x2vRH(`3gh; zX+7FL-7umqN}Ae6g8HfEkS%p=5baa2L|8S{PWQGZoSO+z2IpIVCaHEwxHt<~YX}}C z;$T2&RB4xg>#?sS^I5Ve8zA(Lc}{`VIG)wv8+qT5(NP?H%w#g+Au335wgSYmTKjg- zAH=CL_n@s1cNZiwi;uoZJ}g`|D5}lnpp)EDLTd29UT*g_f{vIS?po6 z*(=s-$(j|3-H?CKZFh}RDD-^?rs>LLGZ+xSeq=46d0E&x_+4Tv5hE&*AxfyY%^b#S zdb&Pq@l5rxH-3)Tf5FR@$w}^xyM38SOSm7a6>D6S$XC=SXt5^Mmoy~VK{9t@t>wSH z-R!lyso{f+n_~|p6Je^QNEGc^r7Nwe9PorpKou&F`OsrbtupSgTP5jju+DJM0m*PsMaYYoT+y)p ziNVaBPKQd9FU|I}7eWw``sF$4V+|LjI&6?{S)H~SoC2n@jC4{Cfv;4FN3j}pH23mX zy*U)V(oEaHc;|@fG6uA1bk_Xp2_bT6?cRw5o|5*p4iF&O9fClsJ;EI+W#Q{RNV+^X z3d3mOvqeIMyn);npukA4x@DxU^SRla^*H2d%Uxx~s=Rrg6dztdHqsOo$OMQyi7!+3;&HQUGL`Z!-mp*pSBgzb4@u?)UCQ@9)1q9!mK+js#s2irYH2I*Tp2DoP{$VO* z8pW)NVA5pFZyx(z)*!c?WefPBtYmzykZvm+L9yKNb9BRnrJXnGM%%Z+b&ne#uab3R zjstJau8PsuKB-N*par5&iyUxo5UVc$Rg;-@ogXOb+)0mFuilG6Jvyf&gk$1RqD4rT zoC>Kju1`A%fKsa|Z$a_|Aen`s79yE$3Prg}bpl2Dq#F=7BO)WLC+?IGdb*f+6*R5!QLiAmMkl(#x1?n?gFC- zrQ|1&fYvt~k}B6ysLM)jCyYr2@dECaEwkE&G~$}%kf@xx^$+94gww}{E}H3=y#yf4 zf4T7e!_sSuav@{2m6`@=Ssx1}k`cGQ+|H6uL(YuF%n6Dm3289T2r7#1dHk|1njQDz z>~fg`6pyvF3go9wTDxMsXnKOnibQRuOkYgXeZvS)!CvAN&>Yb0DX_lDFI`>QQwg?) z>A*Hp7{|VqIUnR+$hD^}rggueYiH(zwWW0(mlO2OpP^ALL&mR0>JTlgaC9n+o(hPx zW9x-5O-uE$Bu83jYud~eOpCgNaE28_TIgSIT(K$Z&D_5V8(q(ngpZw;l1SE7L2MWU zbwdHD3>pXZTCi>(>vL%wH)|a<>Nr$sHV*H~5=~Ug>xvWX<~Xc>X_RoXk9iEqRhYFK zZa2o%u96xS+YL*tX&-e+m(ql=aHMSPIjz2 z2nEbPX4JhCt;Nhg9!!+2+DO`(5m~HMwkLInrp~AaQ@L0;Xz38JX^=zb!XSZpBd!A? z|8f)_X*C8CNV;r7c}p$j_33D&kwU^qIfu%qJ<3DBI3k2i@m=+4GRyYY?`sNExk)O* z4pvUtT{TGg0y-SG%rAO;WwH^k9Ys@FopfCy6w*EH+n*~@t|7Tt9XWV8v`!jomhB8|4?M=#u$g z9}A@Fsa%z%mwDm=W&gpmZ-FM2Jkmy4g?fNIVr-}Mh&H-xJgzIz<}VL=whcTQGS#Hb z>Zm)ibM=g`r4)y@j*SiIJ(T}2+tP8A6tE_8R92FTNTTg(!eR=%2bdU!@uzB_|#Z9bc2aWvTg>d?uhYv z^w-0mi^xN=*4GzEShEo%t1_e9m2+z5Y>0`vhr}^ILF37n*Y=&tQy8Si);W$P;{#mj zNsAXG@TC@>z5^3GE0rTpWAfM66gz*`9Z0I71pB}qQ8Ejb#~#;R2UQN)?0dAd95FZO z6Plx(CT9P^*J>Lk69W=nY_wAxW{F&=>0{11aQA>nX8zdf*y!3@cd~y;W zJpL9Gzoqq`pziC|%yZ`K;7C-!H0??ZLmI;q4x>YVV_=YH;g!#h=wMm7d{bU*isCtF zBwu1${F@c$heqY?WRgXd;wBbey7g-ydTnCHINro>E36y8m>R>{P(##~;G_e4cxfv$ zR;*7yyH@ahITB40%?>%u1J{t{t$ef6MM6eb{dJT`+pW}5SBh#0JUJj`poLF=vlZah zEi~qghS5XR(Bf66p|bbYfytv=aZD47M0aO{yLM+J;j)Cyv@prehFuT#i`&_DWIIJF zAlGkRzPdW>FD%!V7q5R4yqkh!7Z@+DLo@TG0dWtQR@=ulF0*anh}t@qs`>8U7koUp z2eqaMMv18x;7WMvs-Y_&1&7bpEtaoILEnn!IRn=gD)2c0&DO;rnPbN8$y)&_Hl%?| z!!LsbKn1DtJvm(vJCeRQXhD-`=Df`F?5s`#Ml ze7yNI6iVgdt0}_9n^yu*^(fn*YJ#eM@n~97;9!jC{0xk!>jwDS5>!nVrTpYRz-qQp ziI7W$o{HI<;RlTv^sHZfk?3lcjwOYGOSul(e~%V8=?$AtgSN!wDa}VS7(ND>c z%+iU)%(5@0G5@XlHdqR_%Ftm0iytjXLE5Ug6w&OA*OD{Ha!48PapQK(>KvEba$w*N zU!v8Bj{8$}O!)D!@}2h2+Pd~)l&vdWcu}j_`={w?>&?BHS|Zg_#k@us0C#1lho%S9 zQ&-N5dxxOF#mUZ@27B^{9cCicn4yDdi5q2T(m;Eeeod>(=f>&XYtw*5$EMbHplXW# z6Ma@3NlqbEbKELBZQ@}yhz?{oQc3~IHS?>VMO*Lkr8icju37=Zqpav0#*JQ#=xKy1 zo!5t{*PHtx1LvE=GKNp*e@ID@tZaI?Bt*N)jvCa%lG$BaGmq0UqPx62bk5$Ia&qEI zfg$xD(YY0;Zz+5ewZOj%8Tr#jp+)31D_}4gg#40x_1k!>;_%Aa2!I{{1^~EQ5#ajv zaq%lHxs2Hpz6s*QrqD()WjPh8MPYZNCs|?Eg)^vZVZ$gU*4m@)!{~;6c#-K`o0e&+ z;BBdGbn&#z)Sj8{HhLZ7U?vYk-+O=GI$b8CLnlj9Zl1Q-5`~C@@`+v^b5TP{DNG{r zM@ioVVk>cBz7AY?e?b`|W3X_26ZC6Xh+D|8IZ={r;|t3}{EUlN&jxGNqeFR1G0q&# zvs**EhPJgp;8Ir~j2|Wl6NJ$;%6QI=OSwMYS*$CyNJ>bhaoPFMTHDHL-@*g+8$|>R zHQ2Y)Vf8by+WHz9xgMHxmC5`ia=pGg$nW+SOj`bH^mkD2qQ0%65m~fAqtL*$y>|nd z1@h;Z`TehzebOe8_BO>hd{Gpo>-kz&nmii~vhmp7=cS9bgN4(N8U+knJE0nZKfX}x zSy(3wn#x@sUs$ae|8N0nbrHHB#pvK>cDibrX4`&xzNN~7p%D`48 z6}zq?XXH-mK1KvlAr)VTJ}0=vnj&ZiHorJg>tVMVstwpi3*rayhX9)y!4TRb;Tu(H zAkmml;wf%C<~Ivpn8P=u59zFAS4vh`;E^B;t3?w}1(!IL%QF#FDAc+Kze-l%l&f+s zwpz(;%_m(UQd;lmNU!*wc5NZ?t7X#KI;S=FA7nYL@Iegh*1r_WIPGJhDv>v|%zdS_ zlspF-a{#4_?s<|u?qe?XhyBpk2lzM4P(127mv3UV=pwSUJ0+lZLkrkRP-zEK+{?<9 zGFN2B&dLVftCE6@ruY8?ayU3IuC-|BYp2WIoi}i!4~-7=GEif18LSB3#aUU~_b9Wt zGqq`Nu1^ALbfZ;+S^%zrS%}^cyR3gEb!cmDY!YGsOas*e(C}%1Uy#!Vcz3+<$`+j; zEi61-@zKaZ&jU5^S#D@>0-1p7>F3axK(G2WY6V?DoCNSvCtX#d{r7;#eisL5u&kWd zLBR`5@KerPVU&xT-m4#MJlYjkMrB;>Hf>iG;C*jp3+`X~nqJTJU0I0=8pb=1>19)& z*V^4nFTsWQV@+)h0j!+7p6c(ZUD*{!tW7OsqZUo>WP3xuRcGsIseWnLzJx9UUo04i zpbOlTZZi7UGJW5d&_5MC)98|%=geC2p*B}M$RUViCUBa$PR9<0WV1h>xZWH);cQ&q zioO=TJ=&Ed-N&C?seWt@YgKqevZj{B+B`pqjfM1q`N9HWgRl%EB6p?(KkYcD5%2G4 zvvaFJQ-+Y3;j*-P-<5o>FY-?U{&ZG#t~l)CM)O892s<5djKpv!cRXT}UHpq+ z*1L79$e@zR_}y1?F!OQzF4$4QaQ0)N-mN$Bq-+vScCn2P4K-=(bs*1gqblaJ&;xHl zPtNn_Qk|Tcz_0-HtcrR?{`++-^iQ#GYY6kCYzblf;-kT20 zK9_DEFU@MQ$5oxb7&Km1ygbQ@p-TNqb58Z;9*VuJG)imzkg`~`ZK0Fqz%41|5(7~l zVJ4)J3_dbMF=R%?$^b-s5Op$WG2mY%;8+EZkEl!?;Ee)*)}G4KM$921Ca&^Uy>S{C z2{!%7?D9vMT6UCSe5N2L8ciH47-<+6Yt4usF1UM&G88%8?%l>rPOVSf-$`Qneplx) zqF|#AFm@z;cL$Dte-k%U*dO(7oD{FiuurD4vbU15dhgmY^UD@m)l9WHOL-*PNxIvX zW>`0}$a&Haq1!qm+Ni$m5SV3D5o1{t9p%I4|A(|ZKJ3kgqAoI5f{4)RaH<;aiF+B( zVJ55uF*E9BQ)hgol4$ST@6vH9=r77x_sHHrs>C=|tVwfnTKk*c{@u~p3+fz}6%0zFWmb#XE(d#$mY2kuf1`z1*r*d7o~~5h%6Ff zT{4`M0bRorB3VScuF_gIff%8^(?!$QM$>DZ%uQ3+2kItxU%U}h6_?5m+%m-?bjH1x zxSt{zKmQD@om_0q%H_@aO{2NlgkD*|Q|_Jp z@zqu5{mja6L5;pn|JBDNGF@kpjfTiG8?&eoZ#QXEk>3xY+Puv*@!pai)AV$Xh=>zX z>#oUf4YG%uEVT%>F!2U7^DbpE#x8gOj2WrlxBBAN(wRkLboOrblQ$t&gtZCsvAdJv1XM|IsA+Gm!PoVW zzYZK1hjq?C7nkYhK+L$ew7iG z+G?R+v>Qy--<0#}KHmuUp?42f@mEPtQAr0|j~{gC@}u~^o2{?A^sNy8Tv>YD#q-o7 z5Wtm*2*gm@?axxsDu@eKU--6o{QVpcUsMS#xi{g96$p|j2Eh#ZkC8zU!?;QL_+bIo zh^tVOxW}_aS&eTs#?2wx^goQzeoD38I=0RE6TdJqt1~h7Q;AU1HODB7=^S#N5%Lr7SHgUomJn&_T_Nv}ke21sq>oS-vi3Y6X>qqiucHio^aY1aaQq%T={>?Ebkqge zaEvz#FfABEM$Ocx&nc{-MU)?BEGE)dTrI&k`zaC+jL9z&bK@|=HvT9r%-Rsvto94v zXiS(>z3SNh7s8;LJUPuU7J+!rDu`mwJhGA57^Q}1PHBdvf-*b0zH;fZx#FPtlbWT| z#sk;Y@#q+BR+r1&XhHf7(5ynJA2xx2Up7ddugMR$xDXzM(c^POFO1cB;8g+Aq?wi{cU#g$frm6=07~(D<^?lh)tKFdozjb- zDrKD&ZUegC`7-9iuoQETIDa_zgA(3gUns`ZTzk@PK1}paqKJ_PB87C#i)`B)m`K7w zmCLKubZRpE24*~>Su&eLIGug)EMxe@pDoufx2H*J&-{+K~hK3c74#t(nE!3E;ck>0cxP0C|&_U?s zgrNq2<;o^bN* zHw2J^tAdA7_WZJW6k_KDtPI+e2l|d4{0kynj4cR#t7*%K*_xp${mQl}n^%*|N@y2; z^7iB$L2YKVTQ9|QFc?BB=y3rIgFN=?iD zn(qI^CVCcZ_td_-``7Dfu`RU@sv4+@udhzla(TDBKcC!fSR{UM{0_$7U*lbJu8S7cY#FNnYKM$Y#^)KYGTsW1zFSLwgS|?+ z`YJ!y*7p8nyOX$GrPA~MdguK+Lvhq^m>g3V0Dy5wsQ=DT3;+S}Z{~NGTuUo01OR}) zAB^uAij_&VY!`0fO&*jsDlZlh*ZDR6? zYWrgH^8C5uD*feieB8^{&TbY#sKR5$85kl@RtzwtlmPTcX%LD}F_r>Ap4s0OHI&__ zr<5K?mzR}xu$;(6@*uI$WkAhh_PI#ba~d!0??p9tufL%j5GqiST^d=|QiU$$I~H+(ZgaUmO7Xh7xRB#lR#k!jmQC>E2aJi3W~4}~ zZ*FEwm3lsc$LAq0T&mPkr1iQ#l(c2b{ABz3BIJF)v*ta&xDd7`hy|=ej*te=V-0oO ztoq&6>HXDt;a8?wMQPmm^~u^8UNqweZ47&d<7Eg)1OEojWj z^0LeOvu#4@=grXXuM@+Bw2*bBQh@S4Baz9wqp8F@AIa-?I=cIK-U+&|&^*2Yg%Y6i z^K%z1?}Jg)XTR-gq!~I#3IL>`@NPj&C`Javy zKGpduDk>~2Ec=8n2;>956H)^wMn0@XZd0wh%;)>6ObBqQN}Lp72H3@oSrrr`Qse?1QOL9a3-EHIt;mB9 zV#}X=ElCtaKr?fD8xi1cxq^fIi{uAmRs*3OTWl@)uc!ngMkQE#<3 ztD&I*)yCQ=Pm;IX0zjZDZ%eez06nMHhozInJP)}BzL$Cj1Gm>yjG_hF# zv!nOeMci94519)l;i_Ygr=SrLpxLXttr)wotD)F=71d{rH-Kok?No>!(U`kKe%hB1 zX8tD-dAF9GjWw=LO~6n6?mcl9dP+VP-sbQSVBu)-0&N zIIfTg$mh29yhG0n&5hwl;K^lTmguscJ9Kyud4R(OOa%m5-9DEjIW(wg() zV|%o)ERY$WT)g^4-k}kYQ_teU4*pnw%~8P7Yd{5ya6L}_^hl9j4X`uG-9tD$0W zE+DW}zK&r2{GuP%9#@I}Me&w5fNtYWMK1Nvn-9t3q3!7mA4{+Qr?TsSYGPa0p?5-) zBE2IZO+=d1fI#T|C@qEnq4%oNB3%$d2~E0yQk9M%0R;sFq*nnc5|mz~`@*@;$0?rs z?)|f7WhRsF+k5^!v)BLqd+j~GvIio#SJ!kmIfB(rS?_Rd*fD=U2$(wFnQJDl8L-GT zT6}c}H8KVrd`x`ajb=2_0iqYw=JLo1axXzZTpR=|vi9S24r2uZfQPyf1^3HHaScP_ zy&@iYSQK5B4`sk(a?G|UB#?-(=gpW3-F$F!$!N-vO`L7#x z`@kQ)hx^a3Mb_nFqD09FMK}}$wPWNsFUr0d-r8cY#G7FV7#Dn`y6-u4vB@83OoD{n&j1 zj%Q1BSxa^*Md*OE8V{CkFtdc1b*vg+{}LyIF2pOED+E~VHV*XIzX_OnUps)f%}H$Xi${`|8{$Ul8iNFy!|S%xEKe44V$~YqBN0{lha)v)Jdc0I~)OG z4IETr$4TRyhQmY8wvmLaxiAOu&^dOR_emRhZIk#&Oz)Hj)MyB6Dze zYwe2Y_))TFpEucX#Kz?T8jC>9Yf+}%Vxcw~lTkLf*oK#vx%JBV=o4#5gmJYJt{Gyf z8;5 z&u^y&v69v%KvhMc+9#ueeteHMixU(|%!N|o_g{DY9E014gk%yzA65HiGj>K$Yh*RK z^EXUC2CuqY4)HfmZeb&=f`G>D1h16z;O9Hggjb>x{AMpIUQ^ z^9cH-zZC;SuFWU+nhnX2rBW_*4tKu~sb3)}TBC8U)l^(KIPmxI5O1&}pQ~1r(~e|w z!7=M**0k*jt8JAz*pd30_Eurdt~^x_SJtK{(w)^|gr%#r_QjR*Y4uhh_}lsDX*Dp*Ui(MoZj|)cm%1DmA8!*b(9Ya&beoat6v!CD z?4BI%^tniKD^j}SNtY*C=C62lN8xfZi4+XU;*NuMW}5w2*&o@;IBnnyDlLP|y^-Qt zfZ|#j%XUCD@>X~xkbN5%$P)4VO|f2%Zo-WsWoIY7R`o8%5e)BeIQBX73+vHAcnlJV zceFAcHm7vtYG+(xg7FP}p$;KCwKKaTa*aR^t(K6f`PzHg%)Kb4K_c|~Qec9WDnbF+ zp^0d;5SC?Ij21&Buq(2$vNDm5OScgsKBOQYC5lDjYsaqK%#wxiwC7h6_aKRfJlGZ8 zKE0agg;|O=-9O$hzf({C-92x1GV>85G@MyUv}h!nonWxwY=#!1siS^#XM_g{yv4kY z4kwC?jI1-PU>3Zcrq@8_rG{#aZMw%MqaxB6*ByDt{PN|?1?<3E@UnjZu_VJgpp6>J zgTd!yh07{DK;K)8n+sb73xS)$nM@OmJK3b1+pTpwT8W-FpVfFU3AGzaqw^lE8k0PG zU`FnZHsS;rNYUrf+}HirsTO>3BVNPhk9w7Ipli2_g2&0b@SkN2N}&CTjY9;Y3rz=a z=C6QI?ats;>xZ*eswG4m`Z#xalPuVhOD3&oAQE0)4w65_$TB`Cs)B``d!=};y5K8G zP?wPShT&MG{x*-UI}@_uMCI<)$_{$*4<5e%1nlL>xxc)@MwI`?{xZ>8RiHaLAjr3A^3ze z>Y@2ODbg5i^_$k5ebA_>K>cBC8I(%2PXQuHXacZpYoK1}#GDK5Rq~g5bjMvENg@iA zK4}QGZ;EaUj*u)@&BEo08q^Pc5~CEd=HvI0*QfH!%FDNayPxNW$@!_5Yp=#=+bzjA zvzJIPtr z#;B6ucS7y-!Z~OlKCiu(@rFO*^Y&$zU8yqy8 ze!5Z^gdcGUl31VwqRP&i3l9%BU#pt0z_SWvz&<1~xG-*aHAW;jb5~SUG`8P4_c8F0 zsh_?{>Wc7zfc@7DVQS7p4{Ru}5q7FZ^@1zzw7I2a%}@^cKxFHrV>_$UnqqKChptkx zW50Sk=H*1NLB5h&QK$iR0~fj2gShq&dJ#T9N-;8;47{W~MWLBAqxcID>1eSqV(cwB zP7G+kIY7VWD&sDDX=bY88~vyqE;^?*1=HZey^huuySCIw$>T6+pESyTBZRvv8MhuW zFjviC7J2Y32{6^1((bMYm9dHrl*ocENG#&yBfo%&J{wH>YAy> zj1hi_(r~4)My17XP1nvl>5sIK`Bgd(5vqB;TwJ;}9HHdev;{Gx&j3lwIyE@27UekE zLTsjO>)AR6b3N_1$oqEqVrTGj$AKeIJFz1_qf%5Dln=$7gx1lzzL`P9Ii+ZcU7S_u zb;wK}Ttr_A_ZEQR_*SA1IoyVvHNpHLxrM4{&Las4^v5EpofxT5S?ZE2P_^+862Gv8 zI=ly3yHDi0W9pja9)X$9ytTD@_Bb_6!0&vI-B zxpN|cE}+svGMwNHZYII^hrGoHMG_~itp_?0Mlo|8g(>*Z=Zad_B#e`Gz`9#t2s7fV zL@2RJ=pXg=-vs!demDb`P>TkCds@bOo;}c1(*;$i*o5hW@$l&YKT{ItXMP$xc1P9C z)edg&;|cMGySaKvh{9bU_AoC|6}Yzx#NA8upTU=Z0d{wD_i=ZDx%&Kd3i&;eZ1~MJpT=j3e{Q5-RmRTQ z4dM;^>9Su{<~$GO_mxav^+aisQ#*}f09PL7^^ zK3d}v4qSIcenYrh-4*?Qy02Mx=fxv(DHI~hR^^!?%%^8{!|3_c3@SlUo^LuJSHhmF zW%ck>xjzpsz?CXe5tyTR+LOKepy6z}APP!9_#02ViHgzEvSSB)y=_r4hiTr#jdv)W zL#D_6il&2t(Y&^;F;&THvb-Ek|KKG_v1YZEaF&nl1x^-^iQ&6Q=?<3ygX*kcCi z+TyPKuZvw-&DHLziMF6>Rv|VS@J3}IxadXtm-4Z%XMy7kp7V!8nBk$p?zyVL9@8YJ za)Die;s*2e!~3&BKD5s?%#QWPq^?-}`86x$u*?q@}xhigLKNjW4QK(T(5^E4pcaw;1)wqkn0-7nXn6Cw^HZMw?AX4SH z-&$+0l6kkHC(F?gvv;e8eua-ZyomMw zLqf~F2ST0eVd!k2las-l?KtG4J7yk&0f|POM@C%F#iO+58ZDHZ&wNW19}=@XrRj}4 zFw5*PR2#xhxfxeryjR6{9jwvRHgbw-sIeEZMO?u#epO+9%58qyXU-`d$In1v&foF) z%@%W;tbCY{c~{H=f&n_eVB%&mLF@YMxhxQgb9Q}`YPJ8Rzdz~fd+K2%tuLb@#k;3R zUh%Ayg#8n980wOtKK*crSX?_{2^CMVz31|mgY6|qVOsy}ka@7xm*KODHMK0}?nd)j zf~^^g7@x_gNe4Ogk(Yb%9k=2bbd;TBTN)Uj@G2$j4d^*!wjb4L`!@E;V`%4H zTs0bhsjMdF_w81tcPyII5k$VFj32Vidq>4qV|s^=O5L{tgMP$mU{}+A8AqH`Y5BsC ztDktXlS?p8aDF0bm$cS7CBm_YeS5E^GEfFAA$-JoO{LiroI(;_&MBG z`{5kWT?$p&)?MVePrx3lo<4|OV0$b^*hWA?ixXtRi%zwE;BuQL#xyB4;*9vlm%cB_ z58GuV~kdAku{Ij<1* z@?BvGmrBKNg$uw=Hm8QI(t$#ivBgQxyTRrU%QNH=Mlq$sEFUs(`4;yvvRyZ{Edp26_zm>4eQH^u@uA4 zKm9m6&go7l%XGGU??i@b{?P|tb+~4`VH#4VxAf$oy>Bp>KO({&`fh`0BPs7A6H~@3a73p)RA43H6R#?RJ=Ebq z}Z2ZQ-?9ZrvNT@}=4oZK6AzRZ_!O$nc#> zALeTb5cY88DL9fQ9+{hj({(iERTtW|Vhq|#?BX%0kp?bHHF$2LplZVg8xzQHTrN?! zwW@Cm&*U$_NH=F(hFlOk`!`NBKhBClmsTav549A!pY^zsIiN|SlAc~0w*B5@Q~%0( ze#=<79HW9sU$sj5VB$oyv^;vKBe0oSIVLMUJg%}fXA=9S(-wU*cXQG*nI2?XSx8|N z8{>f^JttWA-l_r!G%6H^C zt$~(P(Bwne=$8aM{57d>Glw7Gkm!AI>LlA64@TEnu^{H4 zfu+ZpCcfbI)>%V3)3Auso8=;9ZbzGiwl4~K+9N-WB?#Xt5glhCaPcO5;1{ne$H;rD zlIEFJLSbN@mFcJ#x?rd@D6eYUu9W%ut~4r4l}#b-BO>V@@9WNhTI6D>+TE%h0@^~p*>PqRyjMRNj z$W*RW{t^;gyBL-YLBdWtg^l7@_eehr=8S~H!o^V;hAmZk5*%t8b*I#fM8WS=lO_mK z2nuEh-1418=|1z#3(@(9$Iu12_kXApjiC>Med_(DzaCJ2Y(h+vB(#RiToY9W&{0AP z{DWLxOFQVBRWhucI7KqI45% zO?%c~%WsWMTDtXYQ>I((=$TbwXN_S4z7h^U?QjwR;7Imo!1t@r?GiS0(@`^4zN)FK zF6shth16nbG_|6lqMl%P2&^(bHk5@k5CnjYDWb3r2@fvT+ zt;9WplMhH-3cG&W08Y#Q?LZhM>a)%H%w1AeyjndH&+t{5e`MO6_FchBTpcCjdm4H~ zqipcWy@`fMsIPTNoKBbsCs2BtQ(TvVNCJn7Y%l-^%LH?Q*m(V02fLr2T$aU z5Z0aN+wb8v_WQzI;4U!l0C(75QLAO6EjIW7!1?xPlmQlu#X!zu>Yu2eO*m_VN61D1 z05D^f8~H^c*u60 Date: Thu, 22 Jan 2015 09:24:13 +0100 Subject: [PATCH 50/73] Fix UAVCAN dependency generation issue --- src/lib/uavcan | 2 +- src/modules/uavcan/module.mk | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/lib/uavcan b/src/lib/uavcan index 8966f97013..7719f7692a 160000 --- a/src/lib/uavcan +++ b/src/lib/uavcan @@ -1 +1 @@ -Subproject commit 8966f970135fb421db31886d6f99ac918594a780 +Subproject commit 7719f7692aba67f01b6321773bb7be13f23d2f68 diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 924b730a23..600cb47f39 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -57,7 +57,7 @@ SRCS += sensors/sensor_bridge.cpp \ # # libuavcan # -include $(PX4_LIB_DIR)/uavcan/libuavcan/include.mk +include $(PX4_LIB_DIR)uavcan/libuavcan/include.mk SRCS += $(LIBUAVCAN_SRC) INCLUDE_DIRS += $(LIBUAVCAN_INC) # Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile @@ -67,7 +67,7 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAV # # libuavcan drivers for STM32 # -include $(PX4_LIB_DIR)/uavcan/libuavcan_drivers/stm32/driver/include.mk +include $(PX4_LIB_DIR)uavcan/libuavcan_drivers/stm32/driver/include.mk SRCS += $(LIBUAVCAN_STM32_SRC) INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC) override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2 From 20a8b26ac8c34ccf906b7775804a59afa1311f19 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 20:40:57 -0500 Subject: [PATCH 51/73] Fixed coverity CID #12538 --- src/modules/navigator/geofence.cpp | 32 +++++++++++++++--------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 4482fb36b7..4fa5806781 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -257,6 +257,7 @@ Geofence::loadFromFile(const char *filename) int pointCounter = 0; bool gotVertical = false; const char commentChar = '#'; + int rc = ERROR; /* Make sure no data is left in the datamanager */ clearDm(); @@ -269,10 +270,10 @@ Geofence::loadFromFile(const char *filename) /* create geofence points from valid lines and store in DM */ for (;;) { - /* get a line, bail on error/EOF */ - if (fgets(line, sizeof(line), fp) == NULL) + if (fgets(line, sizeof(line), fp) == NULL) { break; + } /* Trim leading whitespace */ size_t textStart = 0; @@ -299,7 +300,7 @@ Geofence::loadFromFile(const char *filename) if (sscanf(line, "DMS %f %f %f %f %f %f", &lat_d, &lat_m, &lat_s, &lon_d, &lon_m, &lon_s) != 6) { warnx("Scanf to parse DMS geofence vertex failed."); - return ERROR; + goto error; } // warnx("Geofence DMS: %.5f %.5f %.5f ; %.5f %.5f %.5f", (double)lat_d, (double)lat_m, (double)lat_s, (double)lon_d, (double)lon_m, (double)lon_s); @@ -311,43 +312,42 @@ Geofence::loadFromFile(const char *filename) /* Handle decimal degree format */ if (sscanf(line, "%f %f", &(vertex.lat), &(vertex.lon)) != 2) { warnx("Scanf to parse geofence vertex failed."); - return ERROR; + goto error; } } - if (dm_write(DM_KEY_FENCE_POINTS, pointCounter, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) != sizeof(vertex)) - return ERROR; + if (dm_write(DM_KEY_FENCE_POINTS, pointCounter, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) != sizeof(vertex)) { + goto error; + } warnx("Geofence: point: %d, lat %.5f: lon: %.5f", pointCounter, (double)vertex.lat, (double)vertex.lon); pointCounter++; } else { /* Parse the line as the vertical limits */ - if (sscanf(line, "%f %f", &_altitude_min, &_altitude_max) != 2) - return ERROR; - + if (sscanf(line, "%f %f", &_altitude_min, &_altitude_max) != 2) { + goto error; + } warnx("Geofence: alt min: %.4f, alt_max: %.4f", (double)_altitude_min, (double)_altitude_max); gotVertical = true; } - - } - fclose(fp); - /* Check if import was successful */ - if(gotVertical && pointCounter > 0) - { + if (gotVertical && pointCounter > 0) { _verticesCount = pointCounter; warnx("Geofence: imported successfully"); mavlink_log_info(_mavlinkFd, "Geofence imported"); + rc = OK; } else { warnx("Geofence: import error"); mavlink_log_critical(_mavlinkFd, "#audio: Geofence import error"); } - return ERROR; +error: + fclose(fp); + return rc; } int Geofence::clearDm() From ce11cc9f32c1d86e0ebdab3d114517995add2595 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 20:42:01 -0500 Subject: [PATCH 52/73] geofence.cpp format --- src/modules/navigator/geofence.cpp | 84 +++++++++++++++++++----------- 1 file changed, 54 insertions(+), 30 deletions(-) diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp index 4fa5806781..9bc9be245c 100644 --- a/src/modules/navigator/geofence.cpp +++ b/src/modules/navigator/geofence.cpp @@ -58,17 +58,17 @@ static const int ERROR = -1; Geofence::Geofence() : - SuperBlock(NULL, "GF"), - _fence_pub(-1), - _altitude_min(0), - _altitude_max(0), - _verticesCount(0), - _param_geofence_on(this, "ON"), - _param_altitude_mode(this, "ALTMODE"), - _param_source(this, "SOURCE"), - _param_counter_threshold(this, "COUNT"), - _outside_counter(0), - _mavlinkFd(-1) + SuperBlock(NULL, "GF"), + _fence_pub(-1), + _altitude_min(0), + _altitude_max(0), + _verticesCount(0), + _param_geofence_on(this, "ON"), + _param_altitude_mode(this, "ALTMODE"), + _param_source(this, "SOURCE"), + _param_counter_threshold(this, "COUNT"), + _outside_counter(0), + _mavlinkFd(-1) { /* Load initial params */ updateParams(); @@ -92,22 +92,26 @@ bool Geofence::inside(const struct vehicle_global_position_s &global_position, f bool Geofence::inside(const struct vehicle_global_position_s &global_position, - const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl) { + const struct vehicle_gps_position_s &gps_position, float baro_altitude_amsl) +{ updateParams(); if (getAltitudeMode() == Geofence::GF_ALT_MODE_WGS84) { if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) { return inside(global_position); + } else { return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7, - (double)gps_position.alt * 1.0e-3); + (double)gps_position.alt * 1.0e-3); } + } else { if (getSource() == Geofence::GF_SOURCE_GLOBALPOS) { return inside(global_position, baro_altitude_amsl); + } else { return inside((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7, - baro_altitude_amsl); + baro_altitude_amsl); } } } @@ -120,9 +124,12 @@ bool Geofence::inside(double lat, double lon, float altitude) _outside_counter = 0; return inside_fence; } { + _outside_counter++; - if(_outside_counter > _param_counter_threshold.get()) { + + if (_outside_counter > _param_counter_threshold.get()) { return inside_fence; + } else { return true; } @@ -133,8 +140,9 @@ bool Geofence::inside(double lat, double lon, float altitude) bool Geofence::inside_polygon(double lat, double lon, float altitude) { /* Return true if geofence is disabled */ - if (_param_geofence_on.get() != 1) + if (_param_geofence_on.get() != 1) { return true; + } if (valid()) { @@ -159,20 +167,22 @@ bool Geofence::inside_polygon(double lat, double lon, float altitude) if (dm_read(DM_KEY_FENCE_POINTS, i, &temp_vertex_i, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) { break; } + if (dm_read(DM_KEY_FENCE_POINTS, j, &temp_vertex_j, sizeof(struct fence_vertex_s)) != sizeof(struct fence_vertex_s)) { break; } // skip vertex 0 (return point) if (((double)temp_vertex_i.lon >= lon) != ((double)temp_vertex_j.lon >= lon) && - (lat <= (double)(temp_vertex_j.lat - temp_vertex_i.lat) * (lon - (double)temp_vertex_i.lon) / - (double)(temp_vertex_j.lon - temp_vertex_i.lon) + (double)temp_vertex_i.lat)) { - c = !c; + (lat <= (double)(temp_vertex_j.lat - temp_vertex_i.lat) * (lon - (double)temp_vertex_i.lon) / + (double)(temp_vertex_j.lon - temp_vertex_i.lon) + (double)temp_vertex_i.lat)) { + c = !c; } } return c; + } else { /* Empty fence --> accept all points */ return true; @@ -188,8 +198,9 @@ bool Geofence::valid() { // NULL fence is valid - if (isEmpty()) + if (isEmpty()) { return true; + } // Otherwise if ((_verticesCount < 4) || (_verticesCount > GEOFENCE_MAX_VERTICES)) { @@ -214,26 +225,33 @@ Geofence::addPoint(int argc, char *argv[]) return; } - if (argc < 3) + if (argc < 3) { errx(1, "Specify: -clear | sequence latitude longitude [-publish]"); + } ix = atoi(argv[0]); - if (ix >= DM_KEY_FENCE_POINTS_MAX) + + if (ix >= DM_KEY_FENCE_POINTS_MAX) { errx(1, "Sequence must be less than %d", DM_KEY_FENCE_POINTS_MAX); + } lat = strtod(argv[1], &end); lon = strtod(argv[2], &end); last = 0; - if ((argc > 3) && (strcmp(argv[3], "-publish") == 0)) + + if ((argc > 3) && (strcmp(argv[3], "-publish") == 0)) { last = 1; + } vertex.lat = (float)lat; vertex.lon = (float)lon; if (dm_write(DM_KEY_FENCE_POINTS, ix, DM_PERSIST_POWER_ON_RESET, &vertex, sizeof(vertex)) == sizeof(vertex)) { - if (last) + if (last) { publishFence((unsigned)ix + 1); + } + return; } @@ -243,10 +261,12 @@ Geofence::addPoint(int argc, char *argv[]) void Geofence::publishFence(unsigned vertices) { - if (_fence_pub == -1) + if (_fence_pub == -1) { _fence_pub = orb_advertise(ORB_ID(fence), &vertices); - else + + } else { orb_publish(ORB_ID(fence), _fence_pub, &vertices); + } } int @@ -264,6 +284,7 @@ Geofence::loadFromFile(const char *filename) /* open the mixer definition file */ fp = fopen(GEOFENCE_FILENAME, "r"); + if (fp == NULL) { return ERROR; } @@ -277,7 +298,8 @@ Geofence::loadFromFile(const char *filename) /* Trim leading whitespace */ size_t textStart = 0; - while((textStart < sizeof(line)/sizeof(char)) && isspace(line[textStart])) textStart++; + + while ((textStart < sizeof(line) / sizeof(char)) && isspace(line[textStart])) { textStart++; } /* if the line starts with #, skip */ if (line[textStart] == commentChar) { @@ -305,8 +327,8 @@ Geofence::loadFromFile(const char *filename) // warnx("Geofence DMS: %.5f %.5f %.5f ; %.5f %.5f %.5f", (double)lat_d, (double)lat_m, (double)lat_s, (double)lon_d, (double)lon_m, (double)lon_s); - vertex.lat = lat_d + lat_m/60.0f + lat_s/3600.0f; - vertex.lon = lon_d + lon_m/60.0f + lon_s/3600.0f; + vertex.lat = lat_d + lat_m / 60.0f + lat_s / 3600.0f; + vertex.lon = lon_d + lon_m / 60.0f + lon_s / 3600.0f; } else { /* Handle decimal degree format */ @@ -320,9 +342,10 @@ Geofence::loadFromFile(const char *filename) goto error; } - warnx("Geofence: point: %d, lat %.5f: lon: %.5f", pointCounter, (double)vertex.lat, (double)vertex.lon); + warnx("Geofence: point: %d, lat %.5f: lon: %.5f", pointCounter, (double)vertex.lat, (double)vertex.lon); pointCounter++; + } else { /* Parse the line as the vertical limits */ if (sscanf(line, "%f %f", &_altitude_min, &_altitude_max) != 2) { @@ -340,6 +363,7 @@ Geofence::loadFromFile(const char *filename) warnx("Geofence: imported successfully"); mavlink_log_info(_mavlinkFd, "Geofence imported"); rc = OK; + } else { warnx("Geofence: import error"); mavlink_log_critical(_mavlinkFd, "#audio: Geofence import error"); From 9f32a85409034b2601e42959706a6e0c1a144ce0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 20:46:56 -0500 Subject: [PATCH 53/73] Fixed coverity CID #12530 --- src/drivers/hmc5883/hmc5883.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 95fbed0ba3..a06be72d9a 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1351,13 +1351,15 @@ start_bus(struct hmc5883_bus_option &bus, enum Rotation rotation) } int fd = open(bus.devpath, O_RDONLY); - if (fd < 0) + if (fd < 0) { return false; + } if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { close(fd); errx(1,"Failed to setup poll rate"); } + close(fd); return true; } From e10d6bf603e8728061465271957486b727387d1f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 20 Jan 2015 20:56:18 -0500 Subject: [PATCH 54/73] Fixed coverity CID #12521 --- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index dfbf00b664..e5a21651d2 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -435,7 +435,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) /* Use distance value for range finder report */ struct range_finder_report r; - memset(&r, 0, sizeof(f)); + memset(&r, 0, sizeof(r)); r.timestamp = hrt_absolute_time(); r.error_count = 0; From 193a210b517c958ebce3aaae8cc9b5709ff9b52b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 23 Jan 2015 14:32:29 +0100 Subject: [PATCH 55/73] Multi sonar support by jverbeke --- src/drivers/drv_range_finder.h | 3 + src/drivers/mb12xx/mb12xx.cpp | 189 ++++++++++++++++++++++++++------- 2 files changed, 152 insertions(+), 40 deletions(-) diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h index 0f8362f588..12d51aeaad 100644 --- a/src/drivers/drv_range_finder.h +++ b/src/drivers/drv_range_finder.h @@ -45,6 +45,7 @@ #include "drv_orb_dev.h" #define RANGE_FINDER_DEVICE_PATH "/dev/range_finder" +#define MB12XX_MAX_RANGEFINDERS 12 //Maximum number of RangeFinders that can be connected enum RANGE_FINDER_TYPE { RANGE_FINDER_TYPE_LASER = 0, @@ -67,6 +68,8 @@ struct range_finder_report { float minimum_distance; /**< minimum distance the sensor can measure */ float maximum_distance; /**< maximum distance the sensor can measure */ uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */ + float distance_vector[MB12XX_MAX_RANGEFINDERS]; /** in meters */ + uint8_t just_updated; /** number of the most recent measurement sensor */ }; /** diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index 9cf5686583..90f1791bd5 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -54,6 +54,7 @@ #include #include #include +#include #include #include @@ -72,7 +73,7 @@ #include /* Configuration Constants */ -#define MB12XX_BUS PX4_I2C_BUS_EXPANSION +#define MB12XX_BUS PX4_I2C_BUS_EXPANSION #define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */ #define MB12XX_DEVICE_PATH "/dev/mb12xx" @@ -83,10 +84,12 @@ #define MB12XX_SET_ADDRESS_2 0xA5 /* Change address 2 Register */ /* Device limits */ -#define MB12XX_MIN_DISTANCE (0.20f) -#define MB12XX_MAX_DISTANCE (7.65f) +#define MB12XX_MIN_DISTANCE (0.20f) +#define MB12XX_MAX_DISTANCE (7.65f) + +#define MB12XX_CONVERSION_INTERVAL 100000 /* 60ms for one sonar */ +#define TICKS_BETWEEN_SUCCESIVE_FIRES 100000 /* 30ms between each sonar measurement (watch out for interference!) */ -#define MB12XX_CONVERSION_INTERVAL 60000 /* 60ms */ /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -133,6 +136,14 @@ private: perf_counter_t _comms_errors; perf_counter_t _buffer_overflows; + uint8_t _cycle_counter; /* counter in cycle to change i2c adresses */ + int _cycling_rate; /* */ + uint8_t _index_counter; /* temporary sonar i2c address */ + std::vector addr_ind; /* temp sonar i2c address vector */ + std::vector + _latest_sonar_measurements; /* vector to store latest sonar measurements in before writing to report */ + + /** * Test whether the device supported by the driver is present at a * specific address. @@ -140,7 +151,7 @@ private: * @param address The I2C bus address to probe. * @return True if the device is present. */ - int probe_address(uint8_t address); + int probe_address(uint8_t address); /** * Initialise the automatic measurement state machine and start it. @@ -170,15 +181,15 @@ private: * and start a new one. */ void cycle(); - int measure(); - int collect(); + int measure(); + int collect(); /** * Static trampoline from the workq context; because we don't have a * generic workq wrapper yet. * * @param arg Instance pointer for the driver that is polling. */ - static void cycle_trampoline(void *arg); + static void cycle_trampoline(void *arg); }; @@ -200,12 +211,16 @@ MB12XX::MB12XX(int bus, int address) : _range_finder_topic(-1), _sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")), _comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows")) + _buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows")), + _cycle_counter(0), /* initialising counter for cycling function to zero */ + _cycling_rate(0), /* initialising cycling rate (which can differ depending on one sonar or multiple) */ + _index_counter(0) /* initialising temp sonar i2c address to zero */ + { - // enable debug() calls + /* enable debug() calls */ _debug_enabled = false; - // work_cancel in the dtor will explode if we don't do this... + /* work_cancel in the dtor will explode if we don't do this... */ memset(&_work, 0, sizeof(_work)); } @@ -223,7 +238,7 @@ MB12XX::~MB12XX() unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance); } - // free perf counters + /* free perf counters */ perf_free(_sample_perf); perf_free(_comms_errors); perf_free(_buffer_overflows); @@ -242,6 +257,9 @@ MB12XX::init() /* allocate basic report buffers */ _reports = new RingBuffer(2, sizeof(range_finder_report)); + _index_counter = MB12XX_BASEADDR; /* set temp sonar i2c address to base adress */ + set_address(_index_counter); /* set I2c port to temp sonar i2c adress */ + if (_reports == nullptr) { goto out; } @@ -250,16 +268,53 @@ MB12XX::init() if (_class_instance == CLASS_DEVICE_PRIMARY) { /* get a publish handle on the range finder topic */ - struct range_finder_report rf_report; - measure(); - _reports->get(&rf_report); + struct range_finder_report rf_report = {}; + _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report); if (_range_finder_topic < 0) { - debug("failed to create sensor_range_finder object. Did you start uOrb?"); + log("failed advert - uORB started?"); } } + /* + * check for connected rangefinders on each i2c port: + * We start from i2c base address (0x70 = 112) and count downwards. + * So second iteration it uses i2c address 111, third iteration 110 and so on + */ + for (int counter = 0; counter <= MB12XX_MAX_RANGEFINDERS; counter++) { + /* set temp sonar i2c address to base adress - counter */ + _index_counter = MB12XX_BASEADDR - counter; + /* set I2c port to temp sonar i2c adress */ + set_address(_index_counter); + int ret2 = measure(); + + if (ret2 == 0) { /* sonar is present -> store address_index in array */ + addr_ind.push_back(_index_counter); + debug("sonar added"); + _latest_sonar_measurements.push_back(200); + } + } + + _index_counter = MB12XX_BASEADDR; + /* set i2c port back to base adress for rest of driver */ + set_address(_index_counter); + + /* if only one sonar detected, no special timing is required between firing, so use default */ + if (addr_ind.size() == 1) { + _cycling_rate = MB12XX_CONVERSION_INTERVAL; + + } else { + _cycling_rate = TICKS_BETWEEN_SUCCESIVE_FIRES; + } + + /* show the connected sonars in terminal */ + for (int i = 0; i < addr_ind.size(); i++) { + log("sonar %d with address %d added", (i + 1), addr_ind[i]); + } + + debug("Number of sonars connected: %d", addr_ind.size()); + ret = OK; /* sensor is ok, but we don't really know if it is within range */ _sensor_ok = true; @@ -325,11 +380,12 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) bool want_start = (_measure_ticks == 0); /* set interval for next measurement to minimum legal value */ - _measure_ticks = USEC2TICK(MB12XX_CONVERSION_INTERVAL); + _measure_ticks = USEC2TICK(_cycling_rate); /* if we need to start the poll state machine, do it */ if (want_start) { start(); + } return OK; @@ -344,7 +400,7 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) unsigned ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ - if (ticks < USEC2TICK(MB12XX_CONVERSION_INTERVAL)) { + if (ticks < USEC2TICK(_cycling_rate)) { return -EINVAL; } @@ -414,6 +470,7 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) ssize_t MB12XX::read(struct file *filp, char *buffer, size_t buflen) { + unsigned count = buflen / sizeof(struct range_finder_report); struct range_finder_report *rbuf = reinterpret_cast(buffer); int ret = 0; @@ -453,7 +510,7 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(MB12XX_CONVERSION_INTERVAL); + usleep(_cycling_rate * 2); /* run the collection phase */ if (OK != collect()) { @@ -474,17 +531,19 @@ MB12XX::read(struct file *filp, char *buffer, size_t buflen) int MB12XX::measure() { + int ret; /* * Send the command to begin a measurement. */ + uint8_t cmd = MB12XX_TAKE_RANGE_REG; ret = transfer(&cmd, 1, nullptr, 0); if (OK != ret) { perf_count(_comms_errors); - log("i2c::transfer returned %d", ret); + debug("i2c::transfer returned %d", ret); return ret; } @@ -506,7 +565,7 @@ MB12XX::collect() ret = transfer(nullptr, 0, &val[0], 2); if (ret < 0) { - log("error reading from sensor: %d", ret); + debug("error reading from sensor: %d", ret); perf_count(_comms_errors); perf_end(_sample_perf); return ret; @@ -519,10 +578,35 @@ MB12XX::collect() /* this should be fairly close to the end of the measurement, so the best approximation of the time */ report.timestamp = hrt_absolute_time(); report.error_count = perf_event_count(_comms_errors); - report.distance = si_units; + + /* assign the first measurement to the plain distance field */ + report.distance = _latest_sonar_measurements[0]; report.minimum_distance = get_minimum_distance(); report.maximum_distance = get_maximum_distance(); - report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; + report.valid = ((_latest_sonar_measurements[0] > get_minimum_distance()) + && (_latest_sonar_measurements[0] < get_maximum_distance())) ? 1 : 0; + + /* intermediate vector _latest_sonar_measurements is used to store the measurements as every cycle the other sonar values + * of the report are thrown away and/or filled in with garbage. We don't want this. We want the report to give the latest + * value for each connected sonar + */ + _latest_sonar_measurements[_cycle_counter] = si_units; + + for (unsigned i = 0; i < (_latest_sonar_measurements.size()); i++) { + if (i < addr_ind.size()) { + /* set data of connected sensor */ + report.distance_vector[i] = _latest_sonar_measurements[i]; + + } else { + /* set unconnected slots to zero */ + report.distance_vector[i] = 0; + } + } + + /* a just_updated variable is added to indicate to higher level software which sonar has most recently been + * collected as this could be of use for Kalman filters + */ + report.just_updated = _index_counter; /* publish it, if we are the primary */ if (_range_finder_topic >= 0) { @@ -545,12 +629,13 @@ MB12XX::collect() void MB12XX::start() { + /* reset the report ring and state machine */ _collect_phase = false; _reports->flush(); /* schedule a cycle to start things */ - work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 1); + work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, 5); /* notify about state change */ struct subsystem_info_s info = { @@ -564,8 +649,10 @@ MB12XX::start() if (pub > 0) { orb_publish(ORB_ID(subsystem_info), pub, &info); + } else { pub = orb_advertise(ORB_ID(subsystem_info), &info); + } } @@ -578,21 +665,25 @@ MB12XX::stop() void MB12XX::cycle_trampoline(void *arg) { + MB12XX *dev = (MB12XX *)arg; dev->cycle(); + } void MB12XX::cycle() { - /* collection phase? */ if (_collect_phase) { + /*sonar from previous iteration collect is now read out */ + _index_counter = addr_ind[_cycle_counter]; + set_address(_index_counter); /* perform collection */ if (OK != collect()) { - log("collection error"); - /* restart the measurement state machine */ + debug("collection error"); + /* if error restart the measurement state machine */ start(); return; } @@ -600,25 +691,37 @@ MB12XX::cycle() /* next phase is measurement */ _collect_phase = false; - /* - * Is there a collect->measure gap? - */ - if (_measure_ticks > USEC2TICK(MB12XX_CONVERSION_INTERVAL)) { + /* change i2c adress to next sonar */ + _cycle_counter = _cycle_counter + 1; + + if (_cycle_counter >= addr_ind.size()) { + _cycle_counter = 0; + } + + /* Is there a collect->measure gap? Yes, and the timing is set equal to the cycling_rate + Otherwise the next sonar would fire without the first one having received its reflected sonar pulse */ + + if (_measure_ticks > USEC2TICK(_cycling_rate)) { /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, (worker_t)&MB12XX::cycle_trampoline, this, - _measure_ticks - USEC2TICK(MB12XX_CONVERSION_INTERVAL)); - + _measure_ticks - USEC2TICK(_cycling_rate)); return; } } - /* measurement phase */ + /* Measurement (firing) phase */ + + /* ensure sonar i2c adress is still correct */ + _index_counter = addr_ind[_cycle_counter]; + set_address(_index_counter); + + /* Perform measurement */ if (OK != measure()) { - log("measure error"); + debug("ERR ADDR: %d", _index_counter); } /* next phase is collection */ @@ -629,7 +732,8 @@ MB12XX::cycle() &_work, (worker_t)&MB12XX::cycle_trampoline, this, - USEC2TICK(MB12XX_CONVERSION_INTERVAL)); + USEC2TICK(_cycling_rate)); + } void @@ -750,7 +854,7 @@ test() } warnx("single read"); - warnx("measurement: %0.2f m", (double)report.distance); + warnx("measurement: %0.2f of sonar %d", (double)report.distance_vector[report.just_updated], report.just_updated); warnx("time: %lld", report.timestamp); /* start the sensor polling at 2Hz */ @@ -779,7 +883,12 @@ test() } warnx("periodic read %u", i); - warnx("measurement: %0.3f", (double)report.distance); + + /* Print the sonar rangefinder report sonar distance vector */ + for (uint8_t count = 0; count < MB12XX_MAX_RANGEFINDERS; count++) { + warnx("measurement: %0.3f of sonar %u", (double)report.distance_vector[count], count + 1); + } + warnx("time: %lld", report.timestamp); } @@ -830,7 +939,7 @@ info() exit(0); } -} // namespace +} /* namespace */ int mb12xx_main(int argc, char *argv[]) From a23c39eec414ffb9d6808e3402d21f322e14930f Mon Sep 17 00:00:00 2001 From: Jon Verbeke Date: Tue, 20 Jan 2015 16:38:59 +0100 Subject: [PATCH 56/73] Sonar driver by jverbeke --- src/drivers/mb12xx/mb12xx.cpp | 99 +++++++++++++++++------------------ 1 file changed, 49 insertions(+), 50 deletions(-) diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index 90f1791bd5..0ef81e4319 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -34,6 +34,7 @@ /** * @file mb12xx.cpp * @author Greg Hulands + * @author Jon Verbeke * * Driver for the Maxbotix sonar range finders connected via I2C. */ @@ -136,12 +137,11 @@ private: perf_counter_t _comms_errors; perf_counter_t _buffer_overflows; - uint8_t _cycle_counter; /* counter in cycle to change i2c adresses */ - int _cycling_rate; /* */ - uint8_t _index_counter; /* temporary sonar i2c address */ + uint8_t _cycle_counter; /* counter in cycle to change i2c adresses */ + int _cycling_rate; /* */ + uint8_t _index_counter; /* temporary sonar i2c address */ std::vector addr_ind; /* temp sonar i2c address vector */ - std::vector - _latest_sonar_measurements; /* vector to store latest sonar measurements in before writing to report */ + std::vector _latest_sonar_measurements; /* vector to store latest sonar measurements in before writing to report */ /** @@ -149,9 +149,9 @@ private: * specific address. * * @param address The I2C bus address to probe. - * @return True if the device is present. + * @return True if the device is present. */ - int probe_address(uint8_t address); + int probe_address(uint8_t address); /** * Initialise the automatic measurement state machine and start it. @@ -181,8 +181,8 @@ private: * and start a new one. */ void cycle(); - int measure(); - int collect(); + int measure(); + int collect(); /** * Static trampoline from the workq context; because we don't have a * generic workq wrapper yet. @@ -273,20 +273,16 @@ MB12XX::init() _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report); if (_range_finder_topic < 0) { - log("failed advert - uORB started?"); + log("failed to create sensor_range_finder object. Did you start uOrb?"); } } - /* - * check for connected rangefinders on each i2c port: - * We start from i2c base address (0x70 = 112) and count downwards. - * So second iteration it uses i2c address 111, third iteration 110 and so on - */ - for (int counter = 0; counter <= MB12XX_MAX_RANGEFINDERS; counter++) { - /* set temp sonar i2c address to base adress - counter */ - _index_counter = MB12XX_BASEADDR - counter; - /* set I2c port to temp sonar i2c adress */ - set_address(_index_counter); + /* check for connected rangefinders on each i2c port: + We start from i2c base address (0x70 = 112) and count downwards + So second iteration it uses i2c address 111, third iteration 110 and so on*/ + for (unsigned counter = 0; counter <= MB12XX_MAX_RANGEFINDERS; counter++) { + _index_counter = MB12XX_BASEADDR - counter; /* set temp sonar i2c address to base adress - counter */ + set_address(_index_counter); /* set I2c port to temp sonar i2c adress */ int ret2 = measure(); if (ret2 == 0) { /* sonar is present -> store address_index in array */ @@ -297,8 +293,7 @@ MB12XX::init() } _index_counter = MB12XX_BASEADDR; - /* set i2c port back to base adress for rest of driver */ - set_address(_index_counter); + set_address(_index_counter); /* set i2c port back to base adress for rest of driver */ /* if only one sonar detected, no special timing is required between firing, so use default */ if (addr_ind.size() == 1) { @@ -309,7 +304,7 @@ MB12XX::init() } /* show the connected sonars in terminal */ - for (int i = 0; i < addr_ind.size(); i++) { + for (unsigned i = 0; i < addr_ind.size(); i++) { log("sonar %d with address %d added", (i + 1), addr_ind[i]); } @@ -397,7 +392,7 @@ MB12XX::ioctl(struct file *filp, int cmd, unsigned long arg) bool want_start = (_measure_ticks == 0); /* convert hz to tick interval via microseconds */ - unsigned ticks = USEC2TICK(1000000 / arg); + int ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ if (ticks < USEC2TICK(_cycling_rate)) { @@ -579,34 +574,39 @@ MB12XX::collect() report.timestamp = hrt_absolute_time(); report.error_count = perf_event_count(_comms_errors); - /* assign the first measurement to the plain distance field */ - report.distance = _latest_sonar_measurements[0]; - report.minimum_distance = get_minimum_distance(); - report.maximum_distance = get_maximum_distance(); - report.valid = ((_latest_sonar_measurements[0] > get_minimum_distance()) - && (_latest_sonar_measurements[0] < get_maximum_distance())) ? 1 : 0; + /* if only one sonar, write it to the original distance parameter so that it's still used as altitude sonar */ + if (addr_ind.size() == 1) { + report.distance = si_units; - /* intermediate vector _latest_sonar_measurements is used to store the measurements as every cycle the other sonar values - * of the report are thrown away and/or filled in with garbage. We don't want this. We want the report to give the latest - * value for each connected sonar - */ - _latest_sonar_measurements[_cycle_counter] = si_units; - - for (unsigned i = 0; i < (_latest_sonar_measurements.size()); i++) { - if (i < addr_ind.size()) { - /* set data of connected sensor */ - report.distance_vector[i] = _latest_sonar_measurements[i]; - - } else { - /* set unconnected slots to zero */ + for (unsigned i = 0; i < (MB12XX_MAX_RANGEFINDERS); i++) { report.distance_vector[i] = 0; } + + report.just_updated = 0; + + } else { + /* for multiple sonars connected */ + + /* don't use the orginial single sonar variable */ + report.distance = 0; + + /* intermediate vector _latest_sonar_measurements is used to store the measurements as every cycle the other sonar values of the report are thrown away and/or filled in with garbage. We don't want this. We want the report to give the latest value for each connected sonar */ + _latest_sonar_measurements[_cycle_counter] = si_units; + + for (unsigned i = 0; i < (_latest_sonar_measurements.size()); i++) { + report.distance_vector[i] = _latest_sonar_measurements[i]; + } + + /* a just_updated variable is added to indicate to autopilot (ardupilot or whatever) which sonar has most recently been collected as this could be of use for Kalman filters */ + report.just_updated = _index_counter; + + /* Make sure all elements of the distance vector for which no sonar is connected are zero to prevent strange numbers */ + for (unsigned i = 0; i < (MB12XX_MAX_RANGEFINDERS - addr_ind.size()); i++) { + report.distance_vector[addr_ind.size() + i] = 0; + } } - /* a just_updated variable is added to indicate to higher level software which sonar has most recently been - * collected as this could be of use for Kalman filters - */ - report.just_updated = _index_counter; + report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; /* publish it, if we are the primary */ if (_range_finder_topic >= 0) { @@ -676,8 +676,7 @@ void MB12XX::cycle() { if (_collect_phase) { - /*sonar from previous iteration collect is now read out */ - _index_counter = addr_ind[_cycle_counter]; + _index_counter = addr_ind[_cycle_counter]; /*sonar from previous iteration collect is now read out */ set_address(_index_counter); /* perform collection */ @@ -721,7 +720,7 @@ MB12XX::cycle() /* Perform measurement */ if (OK != measure()) { - debug("ERR ADDR: %d", _index_counter); + debug("measure error sonar adress %d", _index_counter); } /* next phase is collection */ From b14e849fc4bcf81bbffd47064e2850a929652f6d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 23 Jan 2015 16:33:24 +0100 Subject: [PATCH 57/73] Sonar: Set min/max distance properly, add usleep for detection --- src/drivers/mb12xx/mb12xx.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index 0ef81e4319..a4fb7bcc20 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -277,6 +277,9 @@ MB12XX::init() } } + // XXX we should find out why we need to wait 200 ms here + usleep(200000); + /* check for connected rangefinders on each i2c port: We start from i2c base address (0x70 = 112) and count downwards So second iteration it uses i2c address 111, third iteration 110 and so on*/ @@ -606,6 +609,8 @@ MB12XX::collect() } } + report.minimum_distance = get_minimum_distance(); + report.maximum_distance = get_maximum_distance(); report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; /* publish it, if we are the primary */ From f5a1680fd6eb17c4fd1b7663cb16ffe126289cc0 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 24 Jan 2015 14:18:28 +0100 Subject: [PATCH 58/73] Add landing detector for V1 boards as well. --- makefiles/config_px4fmu-v1_default.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 18be47065d..852edb788c 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -62,6 +62,7 @@ MODULES += modules/commander MODULES += modules/navigator MODULES += modules/mavlink MODULES += modules/gpio_led +MODULES += modules/land_detector # # Estimation modules (EKF / other filters) From cbf4a5af1611ee0969ea0b8d265441308e2dbc91 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 23 Jan 2015 22:25:48 -0500 Subject: [PATCH 59/73] Simplified i2c handling for flow. --- src/drivers/px4flow/i2c_frame.h | 82 ++++++++++++++++++++++++++++++ src/drivers/px4flow/px4flow.cpp | 88 +++++---------------------------- 2 files changed, 95 insertions(+), 75 deletions(-) create mode 100644 src/drivers/px4flow/i2c_frame.h diff --git a/src/drivers/px4flow/i2c_frame.h b/src/drivers/px4flow/i2c_frame.h new file mode 100644 index 0000000000..b391b1f6a8 --- /dev/null +++ b/src/drivers/px4flow/i2c_frame.h @@ -0,0 +1,82 @@ +/**************************************************************************** + * + * Copyright (c) 2013-2015 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file i2c_frame.h + * Definition of i2c frames. + * @author Thomas Boehm + * @author James Goppert + */ + +#ifndef I2C_FRAME_H_ +#define I2C_FRAME_H_ +#include + + +typedef struct i2c_frame +{ + uint16_t frame_count; + int16_t pixel_flow_x_sum; + int16_t pixel_flow_y_sum; + int16_t flow_comp_m_x; + int16_t flow_comp_m_y; + int16_t qual; + int16_t gyro_x_rate; + int16_t gyro_y_rate; + int16_t gyro_z_rate; + uint8_t gyro_range; + uint8_t sonar_timestamp; + int16_t ground_distance; +} i2c_frame; + +#define I2C_FRAME_SIZE (sizeof(i2c_frame)) + + +typedef struct i2c_integral_frame +{ + uint16_t frame_count_since_last_readout; + int16_t pixel_flow_x_integral; + int16_t pixel_flow_y_integral; + int16_t gyro_x_rate_integral; + int16_t gyro_y_rate_integral; + int16_t gyro_z_rate_integral; + uint32_t integration_timespan; + uint32_t sonar_timestamp; + uint16_t ground_distance; + int16_t gyro_temperature; + uint8_t qual; +} i2c_integral_frame; + +#define I2C_INTEGRAL_FRAME_SIZE (sizeof(i2c_integral_frame)) + +#endif /* I2C_FRAME_H_ */ diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 9c9c1b0f81..bb0cdbbb6e 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -93,38 +93,11 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -struct i2c_frame { - uint16_t frame_count; - int16_t pixel_flow_x_sum; - int16_t pixel_flow_y_sum; - int16_t flow_comp_m_x; - int16_t flow_comp_m_y; - int16_t qual; - int16_t gyro_x_rate; - int16_t gyro_y_rate; - int16_t gyro_z_rate; - uint8_t gyro_range; - uint8_t sonar_timestamp; - int16_t ground_distance; -}; +#include "i2c_frame.h" + struct i2c_frame f; - -struct i2c_integral_frame { - uint16_t frame_count_since_last_readout; - int16_t pixel_flow_x_integral; - int16_t pixel_flow_y_integral; - int16_t gyro_x_rate_integral; - int16_t gyro_y_rate_integral; - int16_t gyro_z_rate_integral; - uint32_t integration_timespan; - uint32_t time_since_last_sonar_update; - uint16_t ground_distance; - int16_t gyro_temperature; - uint8_t qual; -} __attribute__((packed)); struct i2c_integral_frame f_integral; - class PX4FLOW: public device::I2C { public: @@ -150,8 +123,7 @@ private: RingBuffer *_reports; bool _sensor_ok; int _measure_ticks; - bool _collect_phase; - + bool _collect_phase; orb_advert_t _px4flow_topic; perf_counter_t _sample_perf; @@ -261,10 +233,10 @@ out: int PX4FLOW::probe() { - uint8_t val[22]; + uint8_t val[I2C_FRAME_SIZE]; // to be sure this is not a ll40ls Lidar (which can also be on - // 0x42) we check if a 22 byte transfer works from address + // 0x42) we check if a I2C_FRAME_SIZE byte transfer works from address // 0. The ll40ls gives an error for that, whereas the flow // happily returns some data if (transfer(nullptr, 0, &val[0], 22) != OK) { @@ -469,16 +441,16 @@ PX4FLOW::collect() int ret = -EIO; /* read from the sensor */ - uint8_t val[47] = { 0 }; + uint8_t val[I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE] = { 0 }; perf_begin(_sample_perf); if (PX4FLOW_REG == 0x00) { - ret = transfer(nullptr, 0, &val[0], 47); // read 47 bytes (22+25 : frame1 + frame2) + ret = transfer(nullptr, 0, &val[0], I2C_FRAME_SIZE + I2C_INTEGRAL_FRAME_SIZE); } if (PX4FLOW_REG == 0x16) { - ret = transfer(nullptr, 0, &val[0], 25); // read 25 bytes (only frame2) + ret = transfer(nullptr, 0, &val[0], I2C_INTEGRAL_FRAME_SIZE); } if (ret < 0) { @@ -489,46 +461,12 @@ PX4FLOW::collect() } if (PX4FLOW_REG == 0) { - f.frame_count = val[1] << 8 | val[0]; - f.pixel_flow_x_sum = val[3] << 8 | val[2]; - f.pixel_flow_y_sum = val[5] << 8 | val[4]; - f.flow_comp_m_x = val[7] << 8 | val[6]; - f.flow_comp_m_y = val[9] << 8 | val[8]; - f.qual = val[11] << 8 | val[10]; - f.gyro_x_rate = val[13] << 8 | val[12]; - f.gyro_y_rate = val[15] << 8 | val[14]; - f.gyro_z_rate = val[17] << 8 | val[16]; - f.gyro_range = val[18]; - f.sonar_timestamp = val[19]; - f.ground_distance = val[21] << 8 | val[20]; - - f_integral.frame_count_since_last_readout = val[23] << 8 | val[22]; - f_integral.pixel_flow_x_integral = val[25] << 8 | val[24]; - f_integral.pixel_flow_y_integral = val[27] << 8 | val[26]; - f_integral.gyro_x_rate_integral = val[29] << 8 | val[28]; - f_integral.gyro_y_rate_integral = val[31] << 8 | val[30]; - f_integral.gyro_z_rate_integral = val[33] << 8 | val[32]; - f_integral.integration_timespan = val[37] << 24 | val[36] << 16 - | val[35] << 8 | val[34]; - f_integral.time_since_last_sonar_update = val[41] << 24 | val[40] << 16 - | val[39] << 8 | val[38]; - f_integral.ground_distance = val[43] << 8 | val[42]; - f_integral.gyro_temperature = val[45] << 8 | val[44]; - f_integral.qual = val[46]; + memcpy(&f, val, I2C_FRAME_SIZE); + memcpy(&f_integral, &(val[I2C_FRAME_SIZE]), I2C_INTEGRAL_FRAME_SIZE); } if (PX4FLOW_REG == 0x16) { - f_integral.frame_count_since_last_readout = val[1] << 8 | val[0]; - f_integral.pixel_flow_x_integral = val[3] << 8 | val[2]; - f_integral.pixel_flow_y_integral = val[5] << 8 | val[4]; - f_integral.gyro_x_rate_integral = val[7] << 8 | val[6]; - f_integral.gyro_y_rate_integral = val[9] << 8 | val[8]; - f_integral.gyro_z_rate_integral = val[11] << 8 | val[10]; - f_integral.integration_timespan = val[15] << 24 | val[14] << 16 | val[13] << 8 | val[12]; - f_integral.time_since_last_sonar_update = val[19] << 24 | val[18] << 16 | val[17] << 8 | val[16]; - f_integral.ground_distance = val[21] << 8 | val[20]; - f_integral.gyro_temperature = val[23] << 8 | val[22]; - f_integral.qual = val[24]; + memcpy(&f_integral, val, I2C_INTEGRAL_FRAME_SIZE); } @@ -544,7 +482,7 @@ PX4FLOW::collect() report.gyro_y_rate_integral = static_cast(f_integral.gyro_y_rate_integral) / 10000.0f; //convert to radians report.gyro_z_rate_integral = static_cast(f_integral.gyro_z_rate_integral) / 10000.0f; //convert to radians report.integration_timespan = f_integral.integration_timespan; //microseconds - report.time_since_last_sonar_update = f_integral.time_since_last_sonar_update;//microseconds + report.time_since_last_sonar_update = f_integral.sonar_timestamp;//microseconds report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius report.sensor_id = 0; @@ -828,7 +766,7 @@ test() warnx("ground_distance: %0.2f m", (double) f_integral.ground_distance / 1000); warnx("time since last sonar update [us]: %i", - f_integral.time_since_last_sonar_update); + f_integral.sonar_timestamp); warnx("quality integration average : %i", f_integral.qual); warnx("quality : %i", f.qual); From 2c0029235a08864039cf1239f86a0af80039548c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 25 Jan 2015 16:17:03 +0100 Subject: [PATCH 60/73] Documentation: WIP on better block diagrams --- Documentation/px4_block_diagram.odg | Bin 42200 -> 91712 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/Documentation/px4_block_diagram.odg b/Documentation/px4_block_diagram.odg index 95b6f600b87aedcb06535d5b330afbdb76d91c41..e66e1b1cdd704ebe713a2127004488aed7fb2218 100644 GIT binary patch literal 91712 zcmZ^~RZtvE6E3_sAtAWCySuvtx5b^{?(XjJ26uNBcP9|s-5r9vFYL+pSN#{~;#^GE z)YR0})O7cBKTpr7$iu*50sx2r0E-2mbUqC85CZ@J_+R@s1hBWZH+S=PGBcb zakF-GVDWJH$?Rz2YVFGG=w$Bj)6vY`-rT{B+0wpL&-)Ra#f`$Q7Z>ScAV()fc-@Gc3K?mvJS;9EbmBs_Oy=GK^ZnQLcdl_7BJDsNjd zs7Zbr_4!kD+GD5Jz~Axtx%#cQuD5{ok7yLCSa{<$4l4PO4>_f1lqkjjQ_#X1$B7}n z8qt%~JRiXlfg?px-}*-1J_*Ihf*?%yeY`23@j-v;>aTvOsvz#pZ~`Nl)93>GSAwfK zf=SH4BCjkkm;l)9$a56k8GRz7&r%I=<9=X)aFh&`^gdMTZ*pysih@5cF0_z?Wj)*g zf6^2x#Z}^gJ)|4k5S9e}x4s8X${ra$=jbs#w)pd5(M?T;YT z2v_$Wj}Q(JuFnYG3l_`Z?pH%o!U}tFnPXfdH4hm^w@M5RM;GY+k|sB)zN_-h>st!b z4Y--N!fSVk{cn75D*fN6pj4zNyaEj~*g>IOKjY=xAS4Xvk4;QoRzxIV8Y?NJOFNwB zF(_o1Hkb>VpMq2!D&o5-t^y8R-E=Kr`o|yL^b8)R7pA)oc%GGIcd2?rz|h0*7thZ_ zTHZ#uZ!N+9!O#;E$b}rCZ!Qe~hsN6r?XzE?ju6XL*nm1{=}=Z}td7KrW1L!vdUbBz zfxo#tz+Zeb{6mF2Zsv*}w#j>z0O1Gn=HkS>Y80Z^A)!zs3^GH_en<%vQ92opAB53s zgjrVbnEfy6pAJjYTVCGSeyX#BPI4z$RDPPEXFF5Si1b&0X;MPJK33e%)oq82>V_xU z?)rWWq9>_=uNXCw1HDSKzk-_ZRLCyM9C&k&2I;BoKtxiUs6gX6GyTvrCGiF54*CfV zF-uH^ny94@f1Y3un4BCK5KI|igHJnVuRnql;jRkml9(hGbr5PKX>{LE#I9&PV!!)0 ztl)+F$$meiy6SglWK25;j8GCBymZ+aGa!!WkTjS5^!)G4lkYGOa>PZ^2dRO4vsftdA2&6pYoYbrGuPU8F&tH zp-Q37Jy9DdZarB00CH{En?2OOY?$$gD6oOLX8oMQekEci>*R{Km7@4vs`l=A^JG!b ztZ5hs^}p}F;p0yLD?`G&^9?c4jXW|!UUnbbZYUVA93GY*4FZY|qKh}NPs;h2Ay#GN z4wN^Kun`29=OM;uK~TcQ#kx~MLTO~Z{bPOUot!N9PKI|mKia~b%zfM{SQ;vM9J(;Y zq7F-DN;CTsbceL9z4Sh~1_DEzJ~CoZF}|-EZ4pI!5y8d*6l4$m#y+piPV^^2)im(( z&!Vqy($(Zj>%R&~3mYRtk5cIW@z1APc@yy2hk#MOkGM^?;J0@+xsK5cG7#7FF0N+V z`s44f#2KUYKff_lWrT1Q?f?>JHOTKiH#TOJQl_Ui^beFrTB5#}r`xOB9CaovpmnRc zbogKZ_YRRn%9$&NLsA)Z?S`b<;f@WAyNm9o-67h1tjm@swU)x1pn5IdEhD zKSw@T^u5)+c}K~|s7my~{>QXstE}bSH#0LZn%{3>H^v_35GerjcaTh%da@^EdHQs% zsEE`^dKOD<5Jj69OHU)tex1(n#PLwA6K;jV>r3IghldBHn-U;w_Hi`JiI8j$zULFs z1kHkxrHoCMHG}~K14R)8o)~@w>Ak0HAY>ICNB;a#ZuQY{J!R(;lr=r|W(drMjcac{ zMwJ>CcOrP#zNvySJkL6m)qqtO9l@H2E;3$jq|$uO7~d5X!Jp}a^Jz&gbleavBbBt~ zh4cyk+pq9M6_PMpBltxfN0nmq7vyB7D^1=Viw^NEIDd+C)`!*Ae@E0u5^Yy*F>UIS zB=8wTA}Hi>3~mJNmyvS+a;*9u|93Uf58LWyZyZ&Y`R&?&WcrEwpc>+p#h_Ii!mz~P z-0wm6N2O7eQKss~+`zo!MsR+M2(sGs6h-jGyN4{(!nI%RS&7=*S0_7yNelGOt^^gKLgL}U9WYwtEhlm%-k(-5?}3vH_b8SnJwuw zRXwx$^D8wEi8qh3z2eMWmrA>MP&{Sqc^+nZze7s{zA%TY42UmSDS)_Q?RIirVxJ$t z7paqy!GxQ{1i6*pJ@EN|T3XhAY?vwcw%-kUO)WZCw^UbYCqxv)l=20i9Z0CO{*Ao4 zWD~qjvvo#Z?a;pc^3+sMp}?uJhajnbjD)y_5|Y%)M!#Dw`)LpduN3^-iBTXj2y__u4; zBv&LfN+o_J3@)Itf1tU!9mChk!30{JO)biTp!pI;@^3?3I2FQ;mLRYd5ixS!~#Zg-j%pV8+d&4Olr@ipQSrmVilp)rK0?O{cy z`ORh`DE^z710{!3$Mrl3(pLd-?Tx^Py$>)_w#3qmiI!Fp=olWW_>}%IAFESr2l1bi zk`717;|3PAD&;#$D(Oz6IZBe3tB#UDt*#X5(wKP-`)1R>m$JM{-1dPO@|+uvCg8fV zlARuF!{kxkR(APNW4uJ@!M(`Wm;3;3Y>BYaKW%9D{?IZ2He0#iU-Sa{uBf3952K~z z(8aAv+fK?e8S$vU{K$3QdODj~oOt^3UODY@=$HudJ0Bp!5VnIIoV z+HS+gf?JPFQ@@_RnvDB~DohKO$?gYMP08k5V>+QtlW000$Q3rEZ;{>Y99l@aK^ts8e|uxGExwljh0We{=~$P@M@MaWuc)DSj*V)^ zHrg?t+7|kfmLzFGk$7C@iP)HNKp0wb-B@^9ew;?FgYgYV!=RvE3d+q`Fjl`J38=&x z-_@q5Ih~|L^&~?Z0ZQ|QHzdAQh*ePV-4~^1miv=i#BI55P*U$cei>zeJSap|M&s}R z1i=ZUYZoug?2oTdNt9`h`h6oK^03<^;-7QcAmGr`qM^_4>>+51udV6}56{|US%xFH zqUioysvf--eVcWeRmRQ3Gox%QTZ^UDSrjz$(V8Wh%zdm&yT103_S}{EBZ5VUKBfP}ZK!>9N#rU0zdJz?V4V2_q{}?UjUUNbK}Yui&Y8w|!#@wDX<9tLOz2qO?nn3_#XcVxkH~`J7?FcfY^b$(8SpL zj?h~&^#nJD*UER_Kp43q4hsv|jL(*>vM7n>cpGSZnv8a!9}DB>qM?wKJDdegSjABC zmJa!ZY`2_Pz^#tZ4-c6iel@Jal3bzZSkm0!Fd=EB#E}_>jfr3FQ;MzAyLr;(8RlusrW)4sPf2 zU3bqc8_9Ly_MQ+LUQycJ{&-CfkR;S>vE?Oh!M1#GW9d`2N&Nj|Wo*iPMi^Nswf0D= z*wOcM6@%8a>Q>#4c3-WeQhY+v^cp;-+6-GTUJrKpn2)*`xNH_^{p2DG6$g;amxQvx zY;zz6_@KE_n)Hqrbw(KwDExk{kxih{n0(OB;-MK(!_$UcBrK=`aIk8@w>d&P!|7|I zaS6SmXdNMS4Ss{u1yy{c&6(ysK&DR#pZRvY2oyQ1T^Fi4e2 zD-#7qqd0?G(!+?xmOS8uAoET7-kMygxn4j#%Oz;BYxzv>Avxtg3*GX}LQbNqW9H0~EPkSqD!naDm`<2Q;?tuvN)CoF{@@?Jk08+GL$H=VpGSUt~_sugL^}_Yxsup6ikw9 zHbJZo;@T1$rCD!PY$JZX>C+|@sQe4BJ!J(I@5iS3Ji)oW(1}G|T+{I?M;^Tx{0up_ z!OH2m-?>~okfWLavoqc_+9Sf_+Z3!WO0;wNiTfyb=qPB^)CAyK8Agf#;Dqf7;8P)i zJDSh-rjj+`Th}v%+~GdyRWXG)Rzm%OdT95Wie1CE8PEI@{%yelZj1p6nnuMP}D=Gt@ z_+y}{hQ`dW_)=#l?GgnYZBx5i;;inuNLAk&JD~Dn zcrGw-4!YG3Hbw)Cm$0S}wg;!h*!2RiV3j6gQwim8q#86633gpuDAe}OWnR>kJHrrb zQ3mrW zPX*>&B|zk+eFdO}y36ys-<*DtLfwCcAtABWHAJIEd)x&Np#^Aw#TLEfnu;p&K7$KN z6YK8R$6b6Zn;-Yj|4E^oV*N&}gd=}!)prFV#{%F#&*~ka*~; zWX*%ep`%lP21U+IS#MBP@oF(l4T4i~<35AV^7E{Ae^32L4aCwef1uZZXi!_vUeo=V zw2p0JyhTe|f1JB3?&00wC-R{F53Xd=;U>me68rkZd6A2XYI0#ZSSM5eX`hxbqkf7) zoY9XzPPugr2-Xwf)7D%h*K2DId@0OT?h*9&_}O8&ua6CLRP0QlGEl$=ZyVN2A6diQV^s9LsCXl5s1b58FXf}zrQ6V}na3NF^YeZw&d)dA z*kI^jJ| z!Ne7!Qad=`0}+ZZKhQ*bzBXwNq3T>EjO1hq2xs=38#`K*=IAgpkgutYy3P+t#aK{>vbgt@cAub<75hd~Oz`=74A{rgwJMa|N@dnbX%6RQFfdzIPc(T8m9^n*dX&>! z#>UuiDRT_{r{%6wx{t?S6s8Jie>H!CGZAYZ;zl^9+Oc2ypUrkzp1e{{Rv#q6L}WOi zC$NtoF$hgmeDVsnvPzux2h~)hgZ0LG<;O*fogVvtas6#u>)Q)u`WbDAYCij34aV7> zS?mCwESAX)8kV$ambD1_6kHLS4CUYbaBW*T0V};3p#I22=B>tBe`OxQUMnVxsLGgc z*&1pXAhm4gmczr8mO%LuwPKPkBjvN3>i}L)VTp$Ea#uF|{CBKm6UOE2M#XD^q^pDj z4UO|31zI!=p#}|;KlfZk^!-LQeBlpPXMbIO8Kyj}>*b&k|6w9Dj29JWd7HD4U~**S z@0P*BznQSJZYJ!{xUoax|LN5_bYrkV9-YC?2YegQIiC@k58M}DtIG<0J#^f)nR*4A zO;nY=w7pvV55bK}{fvm9wx~WPI(;2JlS}>U43BpqXQK*pwT*d1&LyO|-9yz{shDp7 zQmExcxlqoETIE+of&;Nog>Eqa)_ z!miHnWG`S=%5EQf@Jdz9Q<`W|btpHX&0DjY$@jjy_kt7H>bH_WJNF`aWse_&jDmGf z!u!GeBO%z`=ulxPXZNm=#Q*6}tsvTq(} z*Ip>XrIr7evnR?BwINXoI~s0lm`91?Tc;@vQRGr#G!ywISL<-NC}|o^J5*?z%@-2<0XeQDub; zG>zIT1#BcgRJ0_n;08(zZHXo&)u z9K6>bJN=37`ei-hs0$klC;~+Pj(FeTw!f~?H0b01Vry4_7w8(+QVLY&e&mYp92;TM zMUJA4*24MGN%OtbRpl7g)8)vxpwHe1R6#F`pKe;Nqa3Ae%BV+4hcDQ)Ya$if{6&tE zoOD>xaPAjYRaKPlv1RK>ArZw!Ysssn-P(V|B#~Lm6@BDBUsettnZye#V_drNFD`?1 z(oGk3t1_sKuA)|mxWMe4zUbNSuip~?l)LoaUU<@7DIhIy6GdXpRpK_6erzDXw>5R} zEtcIatpD`;9=OFR8t3|(48ie~M`P47-u-PZpal^hN>b^jEbnhQWK4`qJ6V( z(r7@s6Fr8nB*t6c-*XKpw|tS&rJ--`q4y>YHOz$WkozLnC^d(DcCfvgW+DQ~82Ou^ z^@EW829@EVxp+oQT{(~v#JF8pq%VLry)50xE%{xjj;V^T%w zdRLhvQq;V(+7p>BrLD--rK% zT1{yv#>X1w^N8%T|3lIm2~W1~G74ZWmzH7|G)f3-6E1QgC@`ISca*=rQek1#m5MFd z2V-fvYqN)xYuQOiWJSmU8y#)^OnP-aw3qG-iRx}*_d@j03E+zUV{UUQF8f1rPgSb_ zc-7l-e<@Hj!jfV?N}Zl7^Z}oKdc-~loUDbM)=XVn@tNi3)SiaGxX|bwEx^JvNf~Yb z{FfL~f}KbVpdx}jzf10T$Vb8%%>2$p`Z$-t=`d&AB=J8PSlm|&w^OQN?0}JJ4p8Ug z(7a^b2Zqk%{%y#wAtYgG`wPR0v{y}0y0x*s?cRpB_lEIkk-m9N?B4b3ZJC+Nv8gw# z(U-QfTm~Y(WF32;KhWdtNsbkHa3cSO2&<~3@Jga@2$rg#&R`-X*OORIs+c$53@ul$ zOxL^N3FOPqO>?tgiFB!|uDX}7u`aa#`R=IHMQmv%w1Umeh$3S5176k%)Sxl`Qrsr> z>cZA)MOB<+YDK;10B4lbghafG4ivecVoM}guF2z^Ipe!`R60d~q6~5hjZt7_?fU6| zX(`Vj)y7bXHO@R#v@McfLNr*#b$w#_RX@L8zg6vqe|@Pvn4YVOwcyN(?L?dT2&0~+ zNkTG}jEG1mcPw>_=@(GgV{nKn_NKB^VO1+X2Lg|opdq}$0S7sMeq_Slvb4N^wu|-q z7>UiZYrvdy?%hXS^ZHX)H(EM1yIag+@!dWeyoC|#SDHD~*-4MS#(*`yR5+r++hJ@S zF^@NrHc}zO!n{$GR(An2F`PDfgFwmvh4D()nLuqh9{BipCt3~?Yt?tNC4T>Cd+aPe zBFSe`A1s2OPTz{gT1naPE7-P%9~D;l*877Gl@N>1_Jv%0zMp9`?G`_>xq(b+%z1gv zXc6U&dZ6nzk2HyQnLZDF`>0E>t1Kh)p%xIU>#TE-?8`;g`)ZD0eDs7>XOhK>xofaS zIGm6if%ljn>gbuOkACTCl!XgdfOyA#P=v@xRdlS5c1_H^d384ArG>2lMqGy?21^W! zTPfWTY9sc61{g>CWvig?br-4ez@?|-BT?Ad$)ux(uKkqnR)W{MSgbxNBtpIZbji)gIvZY-C$NHKD`15*Ow}!X9VQY@j4v9btfS*v{BLlm<|M4Ia zHNJ7E*@p9v$s`PFR9sCM7`jrlx4l1qwdWe*Wj>G?R(!nr5OOSOSplloXj4QFJL9fI z`D{=~Y|U95gcyCUgFns5JJkpN_D^$mdgNzluAD42Vrn`rP+;~Z3xJU&cM$T= zUCtBKb3h+Af<3H2cqv+-zY6Pxk}=jmn*LyQ#qs$^arYRM6pDp$6}y33Pkc-PYCj~) zT^}z&Bo+{?f|eWhB64%*7^H$i(b6HUF1_QIw(}OENBi9weLVmWQ8MEd&-cy)D@GR7 zm#W^{C^Hk#I%QYQC#9%Jx{FnlDs58k6Mq!8rrMg8DI0N8lnAU@@n=8x|LTZO8b%BUqE)xsy3rPJ(Q@lprjGFJw#A?A-?6(|X5(brs;&1|>B^!x zr50O5mNcgGYFxu%$Ov`$HPQzIN=%aWcSd0KIV2Z877)yi@97-X-m&nNKbiS2FL+8 zNXUg+fBFiIw?--EE|U{^98umf(RttLi-G>*I>PB|3T7SM_7u#Xfh5aY~+Le8f)cBoNQ40b@b1QAGPdkA4b)=d5(nD^z>S_BmqZ! z4A-wzq4>9mLpx3?nDJ_fDpmAVCmrne=}ySFgYsTf@;@680-sg*x1Ls4@>!Ucor<5G ziZRoF)3`6pY8M-#^)*+SyZ)BOpfaooaXt?Moou}qW_w(1|J1vZo)6;2{zvLVffmh} zgNtaF2r4|i9}R+i;5)xb9lQ3W-d`|^$#F!)Nfy~RZqSW0{d8AX#%(wX_oH8ujwawx z4_BBjl?19R#E9Z9$z45!mpwhQvhCk=7nOQT5<#B0iZH}>z1e*l-#vo_W!Run7hW&u4^rar(-$O@4 zS~C%$mPb4l!Ti$iGsBB>j(DvrkRdR9=0pF@A6hib7Vi2+Z~HZ2PAy zGw@vof?R2E-&Bm!dy-%Mv?=0u;98m$f1YX^&K(LwOZ;Zur%^HspPO{T+mr3Fl7c5O9mB9!@=vEmwCz5% z=dvR)QmfaW(<0$59r-<8Ze9~p_-;69$Cb9JHcP<+xkP2${Cwga<`WOlMLe0j5)d5BC9{cPt)Ri z=T%k5cX(I~c@kOlNtQ5jutbC##fDoss9JF;lbbIG%EC1!mp_$f#$4-8JFPc>iT%Ob z19l#trCNDVaoKm|cm;g;Jg!mlER{9r|DP402bhumIT~JV`k0-+Xn-8d^cpYZ$UKIr zkGIzd2mw@~bdO52Y^ft?5(3YcI4022HvG@GB2ftG&C~OQJp_s8{CVP_Qy-2cJsRV< z4m~r{)MO>`zk~v9#J(8-G(wf1mi@d5ZC6eE|IXqc1(q~Q>G-CzwfD$}pOwLEEzoG` z#v3E!VR<&}4;+orF%`Dg)Zm&1I`j&bNlIDT<83zZ<0B|l{39jLcy17#kzrE-kAf_5 znZ6IN*Vd!C28J%1NHDq<9$^`$2HCBta`KoeC1<5--VPQ+Pd9rXZAQHJ^Yfc8llvi> z$~i}A05;Cc-2C>1)?8q^QgIi*?J7EebLupW5rj=7waBQ31y>nY-_`?BIU?eko!_YF zpi!xFfHtn)+Q)(FvEu}to>pD)Z?lX>e?b$49@YI)0eaJQfHMFABG%+3yl{# zicn{q<0>$ec&+6$$4 zW{2&ilN2G}VKcO8Hf%OCSxlosRSsRI^o|n8vn_L=Ci`n+8NEVtV{^wQ#{Te>l>?Q8 z`8rIWcAIn>4bsE-lM!|p0B$K|aJO)t0rU)0gIi<)d6#s_W77jF4y+nZ=LV{bc(nAVAYgvRK+9$^!b;6KP zBzfZPCMN82?M(02*d55WP+RZE;qZO_rzPZUt-SAc^j9LO)Pdx0`Xn;ZB8zB3c}aOGu{rJ>9FvGk3)_a`FaGXfynXV5&tE0Fi@=7uu(rCEA!{tgXmrKe-te7BC3i76G= zS_z668+!25qd(Q=imCv~l%bD_pW1G+j$+Xx{TV7#vU<|8Ub~n46Xcjt%aePF9iSjSa2J!{bKR=j~6;jcJ1%Ub+xAG%GqxhVddN`%*Jo zaslQiD9Lte*I>JfIczOKHFgSKTg8~IniNJ>DFZB%SVo{h1gEMt5BgHjCW5Rd!S61g zZv0C^2L?vXpDV1BxFYW2KPv4}y-Nra&!{}pY>h5M`ETWXBqO5c@5HHQ;w?a6Nr9s$ zXr9&L8c$z=zSShyKEOX%nPf00R`G|+yv{Hys4-vgiAmT}fEdHRj?5olh`F0tmMkw8 zi`CgVi~$#XZaS%sX$;igQFxLha4WD~7ZCOn;Bhr+vK_{1FR@cuC`$_jBU*N#6yR4K zuWuWmY&Ju#?32WHd|h?M3jchE>9X^Kh`DkGklJMAN%)g2B7b7T;n~1)*If?k znqzW%{;H$MYvMDe{pbS(Qvfi-`-h*fe}67;CAyAnNZ|P%B(WV^g$~&u!~#;#CdSad z@r<@X7{s(kVocTv^w~)|VKe{}ZZ5 zZolu_n`oN4y|O(Vpr-a>7+F#UQ3WNrJQ;M>13tM6T`F1bJ-feERHA<`K~Jvl((R~R ziw{AHOp4;PAaHRB4-j*eI=5A333#-P+ph0Sczhy=>uAY>{Fr={lmfsCZKx`!4?TNJ z#!J5N(DsUsX!63SN&sstEyfe%iOE2g0i#e`0JXITmk(4-=$HL7-j>^BtxkcBudg|H z@xT}<?T)3a5a;>iu-4@Icd@~2J`ldEVHk4@>SJx6Lns=EY zKq}a8-yGwu04DmAmhDMjYCR9of_^{)rlF{zDFGdYuSw)eU-&z6GS3*}a+a9Xi1OLH z_^agQM`!O(W+*+bVjn$#`W7cmyqUzEr`Q}=T*oJ0acFvCmi!L~yo|=_bcW4Dp5Nmg zVgE6bE@tT#>}#OBZ8hfX2F97V1X=%stR-E}dUd|5PLR)-7Y|}V@T^b~R zwso2IX2=fduP|fFkG4T^3raG=b%Q!ZYYHLJBZI5%mib=Yg4yTo)-v8M-GbcWDSwwy zx-BoxjbguDi<+Id;#jK8`yPpW0_`>o1&kzdv1!VpE>#kbWu!6m+S*@pei?|xG>Vn| zD`)|tcBd+%V*`BA@yua3))W?W257wctH7x)-rZN5=`^pE5wWrR28iTJ0Fk!p7Sm1l zKVpmdQBeLXQ|njC-9+qvcSx}zHA2`*c6j6Rx9W34fu(-88W9@`UquX(N+VM?n?%M0 zKVUT$2P<7&gPcnd52c|bTTW@Rg-JwW!UzBz=|&bv(pldd2AA8-1493$ZZ}55tO~UB z#k5RRx#z;u%bnWsQH{sCOebnPaDRDB$`{=Y9FQm6WV*TY%@*=UB|*jIqD6F%;vKfL zhTwLp5_Pz*EDpdG4G!`e=)Ueba|W@6HaJa*d}blBZI;^yxt2fIJlH^~OXj}S$_(tN zYgz{#Gr{$jaqt14xr*P9vqf__th1V=dm0fN>Srx%cRg$1!(R@452=Lfmca1pxB4TB z+l{r>9?$FT4Tr8;6PF27YL5aA@z>4(ZWa z`>|(j;sOG32-LrTRaI47Ts$N6oKt2^obPfpbNv-R9i7o#o$ogXP}N|ivh5a5WkG|v ztk>^v)-mt&{QUetD1w%zCNGri@4eNibIO*iQX72C!WH8E15?T!=10-jwBL+h?GNJDICws^Ry(*q+hk9U z{J!PWxst6Dk^zYhK!(=yw^E|>LAom~MauOG%ac1PgOyivU*bLdyps<6K#;B9e@0ar za-rE7C(|=CGE(jo#hP?{#9YY5y0tM#`jUdJj1#QirhS0}OY}JI%KBv?(KNky0V|y* zF585WHv_Gl=meJMw20OJ6d9DWhe;NQzw&)vNaDI3GCG=hfYJ07d=f47pwEqhI{y-j zILTyA48DBMq=bxDCg*KGG-xT6%wK{IDv@+`4U^Fsk=Sk!{KyXn=fQ~ke76aO6rO}R zxE=K=23Kc9^gk`I8;_=++-h~V8yuBA9FF&2I6K{F2Ap4wH6}lX))(st5Z8&%tyf~q z%XfpeLeY-@tBfl)si3ddc*368*1NW0Ij+$vzsRG-H)uvib|#l}(*W^taQ%)c;q1?p zgm1ls(2xW?&shd&R(YXGG+p51xWYH!vEkrgI|NR^wCih69xZ%1dexf#{{0)K{BYj( z_E_x6bfQvB5mwP>nBBQ}j$+r$icD#{};6kg(t`y$&Mw(bMX5Pm*DJI z<4XpkxBZ6)#uG#lKnbeO$&d@W9Io2U$aJ}=gOl~^gT=zcB^T*Yzpz3i~m@qC`j z7MM|*Y8@7UJoSBAf*Noeo;EyDBtjhd-Ac+WE7(0-EhwvbF2Qa2uQgTFSzK)|nYXfb z4-cm>o*&ChJSYi?huZ-&mw3lig0{k1p9>-%=}kB@u8Oh?6xZI@*F*nBOHMLk%jrc% z%2>*{@@>}g(a12{HKYC~iY`jumMr_Q$S||xxg#{e@hkCzRe)RAVEhE$^O6$^SBQtb zgI$1~ZH=wK7kIb$bp{uWql#|Ms|(a#M=VlJ5OFwm;cE156v)9jo3Au{ za)MnPjp<&+99CASs4(^5)|}l?anvx8;&P1RrM|c7cQl(zG)e`z^lcJAAYZsoMIU~? zmKVGoY$R5H`IbAcIz`PDyN2~X7R{c&a^M`+^nGlt+`_gz zi8&iX{d2QB(+(0KdGghuB_%&6D|X0;Ow+`}d2LbgEZK|wNQVlg3LF3g;^>ITO3I`C z(W0@pxmfM^H9Q?`rYur+gtVm17^0yd#FIT$zHq4?yB6hsc5ak=O|mH{!lmXKwl&pK zZ0AsFp&sttS;T943q=qK^AFA$VTWhegPl9nKHsz;V$?-9p-4OjhJHs>s^;oP*LpV~Sq*#q$p5TtvO^>0G>g>aQ#)EBZ2+z5$r#CG7D5ckE6!l5T;| zO%56_uaPH1;jhrcKz}LNS27Ty_abQRi$x2~20L)0=;|wtaum8j9DR%&jsL;|D zva>iej?@NKbp*C^IC?lNp+SF-rfs1lLXpK5CZDqk6m;Nqz_L$qC)I}CrOvWnYuomz zw^-v?Sm-6*@oQP4wExRpuNv#>p72~6sptOwe0_q@0S``2^gCRvR8RK~*8NYHS!_YB zck?SJXO7MFy2FWMS5tOpUOvHc4uiiDs)Msdqjb}CS$a4ZXlCH8t8FfLCLdC=ou(YS zE;^5_+je5Y5x9CCyO4md1((Hhu`+h=dmxDyi-p9)FmCLdt_2xlxRz%&4A_!(_I&&{ zpOy{6k+^KOJ6;9Yr&KZhduj|goIl?7UonU&(x<-F66xWSXuBCGM@aWt!6LpC@_pL$ zyPv8J)jz)l&efAwe7y~DdJ7h+Q!NRR-#&^>kDJtsC&5lonLDg(*w91iDT&J-+Zsza zH6S9&tLEI;Rq2x`QwXs|>;l{Avee1yy{o;YQ|e)O*?HryC)g55Ryuk%y9vP{BfSym z)nA$0WJx3MG%#i(n-CXI$Nz-?Uy+&M;YiEK`|Py*;~0_H*yEqJn}T_~tj*y80kLpH#m>KVOS0j5#>~(xm&IFa{U= zrzklQJV4Wi^=Fp@A{!LL-1Hr6{Il0-m1}NB;z3qC=p45y7;`5arPA`<-LwBZ^Zz*eK4fLOv#EN!4g=~mO;eF9 zLo9IhuTP8!AXSGwsB085v`S%KOI7C5?G?9R%WiA;KG8K~PgNRHnDB@)n_^;YwQzKD zaB4Xzj3nM~6yV`$tAdPnBu^;HXeB1#K}aX|*6Zs%!=ZwbRs}VI>KSu2z|2uljng@H zrS5RikN|6VYtxN?KU>He!+O|FK#9J@h>*W~zd$C{$h4B;w5djjaJWeu&c z{#syBP+hTX0w+-*oV*XlbmO?6o24tL_|m~7dNpBN2(ddWcZwWnzZD$O7{^^qwWXkw z!9SssTa@i-MN4ia=e&HItKvN_myn{g8cP9W%j{~ijm`H zmIoV-G^ub%oJlS0llX1)4{% z&e{du+l$j4p35^UTcc?vJ&lHAmb{#?a?{KFw}rq$x~q9L!#Q<-qU6#^IrgQ;)IP{& z!@asSNb)1(&qSXGY%-vBPgsDBiG=0(^I_i~MObt?QRx0+=9yS{ z$kMrxy{ExD7Sf9p@hV=Hqq5G=k8vto*I42Colwwe!gLt_j6hgQK2iAdKsx8R)Jpez zx&yXqV)Lc{*D(b#A>C}gOcCL7YM)8dWy3s}2E*Miv0Uy*6+XrXxT@-TfLN_C`YAC{=Y$Equ(NWqF&6~Yxl&!d5DIMhjKr64Nu&xS#u-*E>j-C8>Fv%q_5??Zlj5evai zyKG`}PNm8Un=7BCc|?qX@fz;0xg*N}QilGOYS0qvVp93mdGM z|Hvy^vMi9R`l{z{P{ioCG?ra}gLLaU7F&1heUm{#b@Cxe}ps4SRcS3D8JT5aP^Z8y0iQ|H64fu3?J$ft5*rZN@7E%@=$iUxIbm(hh{ z>CG3(T-GvGZ@WP?(|LDBHwGdFTox_EcJ2S7K9T@dZFM!(S<`K+wD#ZB?+gJZx|~@( z#@D2FGLA--YNtut9Ia=*RR}%7X}8Q@;_NHAjeWPLf2w(2=(eNOGw<4b%Wp*?#S4yyJ37L*1K@p1uFD#kFK+v#C<; z+!2G7tW0ga)}S)?}3xBqSuXgkOhZQ@5jo z*^Ch0-rknE@vUSjSBmME=mP^&mnOVHOxdc3Fzt*>4ve{(1w&oaofHb#S;t6uwEMrt zNL!z5{tFTas5YI?e=rV5j;bpgxp1|z&Vg0(1HcP6~2W8+HuvN=@0(lVxn50Ko;r#v2zqMBF2 z5iKm>K_FXu62cJzPfitg_0K7ET=y9_9sUa`F+yL*pXy0VZU*ifg~4Ow#$gKjbv*5F4IlUayg1cOWeFLV3WTf944- zaH2?9%q!tvrV*MG^oaryVrV>TxW4y0;m6p>*+yCt)rytR0a2u#fMm@Ijn($X@h!OU zpK9fx$eTJJLd^;0ywJGHI|GDll)X!?t;pDAvmdfQ?)0GJsJj%`IJBvKgvc#2Qc^2X zfl1(yc7!mConn`Q$i3KZk2zeRbg`|-g~W{-+)ol*I!2-xMTTocp}bE%f-k@%??z&p z;#3hN^d)VOaWOB-NEbPTRq-BOp^INO8)LpwQ#-QX*J6R!3C7b;%elA{TvlRfO^C8#k0Fx*qZXAcdIe#+N}{ETiw^ zKodU-i`$RriAqm$c%vf4xA4vis0ZoLCx-_YhDQ)hvj^)npK_RI1TPN!O>XjYGs{DK zJM#_QeXM*rWJ9^B=r#ag}Px+BEuvS_YsiXcr{ea$n;p zTQIJck-^s*g}_dy+?NNUhL;94vIjl3h2@Tx^&&sJQk~{8(C^CoTT)Z?Z$BOpWF;UV z0csliOYh5h2!Vru{GaOs?0dzqH*|0?wKBH^mJ|A?Dt)W z5v4pz^Z#-*QmGH_!CcBu8Yz=Qg=i|SQJ=G9Mepicq_L*J14>i00w^*jyN@vE>UMOW-y%_;7rB8%fuZD_wY zVKC-V{x=&ZId)oDZwLpD(Yg+`Ql*K@twet0pX3M|XueW3NygTS3?d?_D%;hccUN_K zC5!zd!75F2a?JKZCVf9?CO_(fd4&)8*i;q^!U}D0f<6?4t#^_6i%DEp;MgF;O;_Qp z-=eu?N^WKZQ|!#(hCHn1;yB6UbW246dApTyvuQbu4|2T%SEvdm^;|_H#Oh?=0WJOuT+?N;97A0(sj!9tr3_Y=HXx1nrUya67-LGj3 zksYNu24p^Ytdu_H@1k5Z@$j5kxF>_yM60li_KhXUGYlxqC)5pNR_pvl+vediq zxI<+`golX~o7Z;0T`P-cM17pD_OSZYV_*e zoLGu^4M;oIxMAq_bevK#0mdV2h8!REw6}x^qaBlk0`WfZGb7 zvU@dm7Kp#EyrZXk{cCyp?*5`s1^e7yTsFb;kTm z6v@2$n-LGr8Eiu1`LrJ-WRjv|@dda=7W8s+BmjBP0DVXfm$Iv)(_2l5{-jSI&KnoW z*T#-ai*bz8NM<4+sWOvU1_Hey4#&&$ZwY*3%WpM9Q-Eo1a0(+*=A&4f2@vjk_@X(| zchF5??O1THh3<}38@O98jmt0>X$=7+hCoBwSF%a8GZZhulPfK0S0Ie#s zb9K`dNST;T2iuh>8Ypi7pV zjYCDj9=bf(l}A(2^hIliBI&&OgT4fGv2$?ZZxbvqv-C=i2!aEk!XBkC$%m$+yJEQ@tfROJpH0M`;FDs-*4pQZ2?5t5V8Ug^WM+!@hu;^}k7rw{7#~4EzLEU@ zT~J}(FR1#~Rt~=xXL`S$9=8MRh{O^|?s>Fzdopl__r)0xD+=h*GPX9W4aC_Q+tTm= zfSXuQhzMfJZ$4l?4tLKXu4%8~39hGwhj*{R53$Y4aAD;>AB?`BcUJq*)qgZoR-9~3 zEqT4d=jDa<+cRLm4HsG0JP+0cA1>nUzzjd_XuZGbmC^OM7*u{+=8dwphIrXtPPKhI zAix~&d39m(>-@07o#K_6@p8Il%JAs4k_un29_fZKe7&stwtS(_ptf>jd3$L6Vx3Pi z3rN%jF2D2xT8)SIRA*B!mR8!^qsF}f+G*`iMl(;pu8rEz{ZrasoK~)PCuenCI6oEh zzJDslkDr9Ivyz?fLpZ;aW@>IJ`>YJfZnmI|_Z5xWLUL75G|``fA7^ zc|KT>$hDOiW{w}LT50-nzGU%JSOx((&P@NLEg)@!~}#D)wW~bf1=f{j899V7q%LV@~_VggF)~wtM-yH2T!8>rHWSA@Fl* zgTo6-*?*YP>0##!KcA$z6=LGS!A}2d>XOLY$>E9P8;|RLISrmg2OCa!LG79eN%BFj z&SDeV#!`y(GBzBR^T)OZCI`|*Of!-STC!oF3xhh#l%+kgk2aD7=ISI~;0gbyP~+_`JC$D<4eyOY{Fy=Jz)ThY2hSSR`DM|10qW8_NJ9w>)7G+U|D zgcUbVFRazPlW1tVhvy{8Pc9{_*NvX3?)(k)fk0e5_C4SjiXAbtXdukCT8I3O{s8b? z7aAAy)A9Yq^4O~DL@Jku)h!!N9x!!z3kAk!E>n7^tc2IY#XDq=KhNV!{R6GxcU;>G zv+RXDHkNh`^c7z(l(pMOF_*aOpjqX&w9DBVHqof+wRO$53|Kb-S0oT;stO;Z2Scwd z!l9MrR!kY;4D-%bm&_GzIQO`fhwF)R8q6QWAV&q6pJosG4gJk+0@ z3%j*rWxAgpa!X2;nodbdcHcYC-`5BTGI?6oJG!ue19zECT{&*FQ(owv1Oi^Nv`NzH z3=)bxD|LyBT;;s z)X=oXd$=6jtxv<=+0;LyxhmOFKO@b5|7sts!?@oXTmye0eElM6okDYNak271y-8%k zIBdWIBHabubtW~?*$tO_0r^Wz+kx{l{EPJp>_&BRkBuD5TTJF&kT=HhnUfc;8JBFj zmJ4qN>?^&nBjqt1gmc!-^V6&YOVf*d+c{?GthVMY9SDiL97a6d^YOicOD62;DIcKa z1g_BL*6I1ASEr6@Cnn?xVRTEz51UEdHIF!6Pr@j#Rr=Q!VopY6kY8$9+7oco<#M&( z`;hVZZYp-JMZ88GS}Efj{w@SYy=(!MIXb&>LtFz#iPhLMZ%_ht;?J50AhltsOg7n- zfJAF)hDBr<*;jXWcN2iqT-=G=Fw28UQyV)5V1V|^avAw-&3OT9z~d`Nnv`3kpPaAC zIT$JlYjFx!r`dzrn1cK6SPs3F^^@n`?xfegl$Qjl?82HsLyNMCxBYFXfrEmlS6s#{ ztMEuK3wKy}k%`-BjthVU&z<#i8muu;r0vHM|HI&gMPSBTs6y|yQ$mdR?wG;F(?K!y zV-n{H5BjK=HB^E7nSMCt>=}Mbl&SKm9s|cbd?54%#U0(=n`<#1=?ibrsqRm5Qli|b z`lxn)XTQhAu4@A z*bxN98k&)uj@|%Nj>m=dJ!w)IBe5AUwA{*A3Nwn$0E@h)Rrwj(z31X+2ly;$(6Kg; zuutm=guF_bQ|dnHYv4cjBp7fad0#YFUSEhH4IOl{8x!yOp7|A#D+A6PU)c%ZSC6Ps ze!j9(H&_INvBgA=RIg-{YxfvCba*tw*iM_yM?IaU(8J`u)85wo7{m$dR%0JB2-7 z47Tly8>2I2C*v!lQOXe z@$9c`9x1#?Sh>77J|`R>kY4bxfCzl2z|;p^zo0cuQxb%&YL&gjQNG6kjj2x&?X<^<5XmjF%XblPdp=uiL)X4WwmGI??cUaQ>_f*s z^ACsaD1#qn?qmoG2tm#o!;6PIFT1VY~^lK1%HQn3A{i1}O6yq8c&+-6U z$(`YVW%w@7&}l1V36(XqGl+c+Q|gce)*uD;969boU$r!w9O@e{0#0oVj~b3U6axI_ zqQpiL*YDpK(AniWwhlTE`&J#aAr$b`3)w|)M@`F>=6OOCaSbYlRo|ByvsI0N>f zQ<&2ld1^3zizM6tXca*Wy)Qcm*%&ikU7(3G8*7Q{(5*kZ#rCXbi3@p?Rr?^r9HuFp zW}VzuVcOC~Gy9Ryv=QxkbR3=SE1!Aw34cDVZb*7RPM)Rzqg~(v=8YDbShFFtKaUT+ zlS-6>TJ6(X#CjsMm6))4dAvJF?O_(^vM`GQ?%e1u$o#a~w6@?V(}Q z_+|O2!m2uF>2Y=+9xKy}6I?f^4#q_wl?9+yppJtt*tdb$HmHM zn*P~GJKBrPN-eQQ+C+C(Ux_zsBGJ&xlkKi8r)6r$;j)!+g(BbyIButg!+AJ3HDN(R z-^P7b!g?`uiqMGF0Y!*u_HjD+$#nyFO4(pKxaC{|Cu@KFQFCh6c!Pmxb4Dwa+cIk3 zJxSRjcixwIYkAL=2g(Z=nU36{wF6E#y&A{8_ChOwKsIG!@0!wtrR3@ZNpClkcelE9 z@9hyzLq!Ci%xXxBLN;f;t-7pp&gu7k>FqRCW8JxZRKhI_3ECvi3bDpvk=~uHF*|Lp z_7%O#Wopny6&Vf1vbJ8rofSJBjM%l>0Nqom2Gev5=^$SG{gsNdG{ThA>IGbb=_h8> zg$Zhc1iJ3_b1PG_2q^kqZzzW^#e`mTm#EdR|urkv_ zQGwlAW7D7nK>=mJ?MSI!t$PE1rN~aCZwDb(I%I+QWBa)a3b{V+i1Noc?S~b#7EkAD z^h*P%%NZDX)KS`xKhu{xKaq|`_00xA7-{Jq41mYIIlB_TLF8_)4}$Hh#$C+r7szRk zyVewld54$ZlZ;tw?LWR4dTY`2aix<)*$mG@K55-f-?gj0@mxnFC5kG}?HOK4$9j%! zWIHDstcK;=vpX9s)sqhE&-mqBTR$X-*Yn6lxx7m;@bb?dQsW*TnxanBs3(IFpgkYkjwMT-ez z7S!TsB))vC>e?D3`-c6QxwhNIzxPWYkaQDtJ+LEHu#_N$_aXn%fMf{O5Agu8OX;jUNV!ew3a1yx+N4 zUDK>iUiO~5*cJNd{$)H$XQ>C#M@QCA$3C0(Iq(moH`rNHBXL-JdDu7@R-|6UKaMkX zm$pL@d(%*Rw;QMk0{;Qv?X455Bno7w2pm4S5QG)@qt-jnG%iN+_YnkQy!1Z5OTsWp zVo{(D)|C#`wOg)5?!}4LRV$~pheoZ5aupIJ5D_O}3NjB$79yMxw)%R&J-*4YvN8aN zqL|vS*s-9&am^%l5!+hZvBKuo6!A+nFPbxh}&Xr+~X(L{C zu0;42RkdT#_yJlRvqvvrym& z68uY>IRM8c)io!&T^8zZ z`p45A(h~9eW_ez(81%4zjJ;w8vWR{8o81I~0EFHt!TZWUU6UVj|7Psx6r#5|I#|Hp zVx=9UV+wdJ)lGV)`*%M8XYUm3)B9dSe-GrU8<-7s|8F(uqkGc*oRay5Mh{Ev>Wu?y zzb4T(6?>y8l>hG*o9|md)1w)h5<>rzlQ0ah;|Xt} zp92%TxZnfX&x#}Ku7L|8L`?dxrP)YJU++~+{9(};zIR}~=go~aT(7Jf{og$qVWsN- zN$&4z|GNynyZ_1kKUMpM4pyq?zr(~H{~ezEk1$N{=adYYzb_R5*joI+?2xDbE{dlA z4zs`fXE=$){xNk%lyVIEdQx}I&86+;%>u8@wD(u|FkrjbNwi=uG?!F9AyFhUG%vXE zr$cIUxjM2F_eX1?V#jM0v*JY1Sq#w9@|5~<{~CRZ`Lc;b>>nZB-o^b=sZe<4Y95p2 z%K$Z(!9`+AhMZJ*{yL8mi)`(nTCp>9Ca*eg`CgMVftxbyTB*xT<fpmd0wY2j3GCnUC zeB9)XGcE1;9V>>x@TRLQ9}AjlfMiOi-7qL^=Vi)aDbK5V36Hw+%Sc@5VQqPdHiJ3B zFTINt)(Wmhk4=}-J8FP?M9L8e8g(*-`b}v+axI$UI!HN0LiJiNwCP&tMf2=7bUZ z-$$KQxjwHF=Xwk=wBx`g9OzdfoUu2F4IF&E4ve~M&o91ZI-JayDS`>C0!fA-A5`qZ zJ-kF3D_BRYCG&fgzsw}{!+aFR8~FT;Dcu7YRK!2?yspkZD8VcdYzlCTZ?<`6>QyVx zSu9oPXsCS}zCSqSVdhN?G#D4ErHxWt;EF8tV`3Tb!pM_~KCm{Obmhj>0cjX8!X&N5 zT0RtLwBQ1tTUp}ROs zaKFg$s&&!YNjFv33wNS(!{U{?vh%jGQ~=E^W! zfiag#3b4W0d%bwL+WMt27RIOwRYBark@{01ph4O8N97H25YP4LAVRz2H$}yh9YAO( z?d05dZu^dkOXkG;0tq~j&ofpUhnllq)=5-TG%XslH36039?T6Fk_uePtP zXLWblcxQ2P)(tp&>R;SA^>sIOC}AzCBV#CKDzMZn21Vh%KQZ5Evw0#YzoD~$(wk+- z)kgR_x=DKU%O`2ZN^tOV=&jdXn}&90AQ>f=2^--R%lJg->j4vuf%i;+rjn(;fpUOK zoy{O3HclEGC2DT2@S8s0BZ}}fx9=^73JqB8T)x>!Xg37vb?oqPOJk?dN=av27CY@Y)NY2!ESwb^4W zvEpO3WRekN*!dE0liTfH>HRG_o`=DaD8EX{`8PDJe_>9r$+XE_`CbTqjw-~4;c{vs zZ|(Qs9F&ap1xpf61ggK5Le_xkZ96ZnST;uP!)HVoUa&Ef%0_iXS8_9 zdxPKfRe}V!jB%3{!y%ulajI85E;Oa1H+uo{K~{^r02i^%V9r_T4qd+TlwA+V`O_`V zJ+M*v&Gif+xMWv{NT+>9kA+$1U3jVJF`_av?ao zXgY))jl%4D$0A2q{oBZV%EON=Yh%ZUe2-w2fH5z{=EEn=QY8%7xIF{5GaLNOK)UEz zI5`h?F7FOraW~52^}7x3*Uq=SH?0oKU4l~Qwf$#J$WyoZR1I%epS4z(!FqG=?VW<_ zv**%E_hf1<#pCOe18$yM3@=Hm!8mYb-P^FHC&nh|tExMsQ&k#XUhTn`Yhq%~IK-$v zRdG>A^6Yyml0441=-^+f;zJIk1g;5})vLpMlC~VDlKh8~woC7uT=khwaG=ESP-jh~ zWt7e)0+*NhcrV;-HfVmlT=!ki@lMKk;H-P7;%zwL>VS7X8h2U`5~=(+fX9Qu5P0*V zlX$Ex6suVQKNz*Ej7=5kSZOi|C1qaY<#ldf8Z>xS__7WWKfO($(70^-W|{)HgOTCk zf$#KZ9d@u`O<6u4y^eN(`PHNC0?Gx?jS?l+9P5md0azq%To`HXPu4wyIlYDU9*{BV z;#&9Qw7%GZZwMP}HT*+^KD}zE&T3NIeexw)lD@82wNKwF zF9!ZKUAr0;YJR&l?5j)FNBU>D*EgUgPTP&Q=DD_~D`i^ac{(leP2+=h+y2R=`?2)~ z`II-zt6eqX+uKi42BW8&6FYUBeH)oxyvPQ_yOOpa7}odes^^)7e$!`fE->0&Z){E5 z^iR8~HwZ}mLEkL>-l+IE648n4UX4`SFs~%u4x$CUtgn(wH+Qk6 zE(Vxl>buh$F5&p5j;zB2BG$5JVhSJl$ zu)0(vt?XLK$0wz9EJ!x@5Eo6(&#$YNPMTdh?%26ABMr7A&7M`$hPI3Z$kC{?P{Rd_ zLv2#NrU{r)!DJo6Kq@I$nI#A7l_$}i>-rO^ki6s8RQXx1Gxu2`a86Pey0n^NzhoW* zv8+Nz5%flINfb%F*q_w$r_N8E8-HEJxt1S|Y-y%%;pfOwK7O7MhFnC<-p2naC}%JmY_P(2Rho9~ba$ z@)GeJ$+{bU%RuZ73HzM7`s^W`<$UL z$sw5`@4TUP$URM%G-af(LOWaqg);sNNjaiOibn0K$j^9nPNQXDt!pZUE37{{jrJ#h ze430#0^Q4el#(EA`eY+L(5;A|rc2jCBuM(#8fc7bNv^a15HAV022$jg@j`Dt6pQy@{I{E-PtxloA0%D*Gcr%L6pa~u2&Z$s|F zdK@7&VoxajvJdS_A7Jg95S1@kOnGY~b@)sq; zXh`nKq1DpVH1B1nPFHS6^rlkmiwNX>jr#>9PbQkqrt6sFW2L+~+z7X-ATy!-&f!YJdSn3bWihp(-!!~+3{=Ru}u>d#+QaF+3ZKJd)b_%3OVSxX6V z<8pBk*5@0}K3$L@zV!}n8_E6h6A|$2X#E_u7U|9kz;kadk*+P_(|pD!UH3S9vorU9 zcrC;)Gn@t%z4w7Crc_=wWj7xs!Zt{ya8`UiT{><{Y7LWIT4X>^9-yJgQ`LP-fxD$m zdmD}F1iw%`3SeN}GJYw^O~n}8qokC2rLfw-5+M!Cf(BokVAY}3dZ~P?9+xibY(+VdS5}!vk|K>upcW_w1M?acgugcT67+ z7HAIM-rE|FD=#UpkfA?g%QE+ylH(1M<7(jXf8O1l7ty(2+o{%m^n)jT(RK7&*z0Gy zl>F)JH-^S(&qA^hAEKu&Yppk%-0n$QW%fRfuqkdcobCu-`kM%BsWY~t6@W(Q+hM5Z z&2GSf{-|6pVg+Kgjj$L2CQyC{G>AoSJ_z15bZFh8itLa|7eM+vUZM$2$n5Oo#W)tz zg<)TC+0IaKMcFh|X_83wh#hs@7`WY6wWCZQ$>8NpDZQjg6RmFFnN+?>xb71+t zE-dO^T}6-C!p|Arl+Uq4gRFW}D^Z-pxrDZAXf(r%yYt>09ncuWZP_g%SOTCxGJJs= zA4-EKS=bN@{2EW`U$^XS5>R!?9MtHfzYd=-7?W`E299Vp79>XL>E=!ro# z6s{;N-D(%}X`R$)^5N)-69%HUL^D)ihw1qIW&ZN6`WzdofhEAf*Rg)DXZxtPRR`&9 z2`l!4C2M9uo(xl9>*M-C^lL37Cp_--KK+>j`XiJ^l(S3 z%?r@aamKM5@$aq$HylP!*0gPw)7i{A=Qu4xh3TZ;d0x`3N*ipC9^;zZ$y?Hdn`RbuW(q7If|{V*e9y?lnLvo}hc6ZQtw0b)|v~f%>CS zP%qiaegO&@7-;fEV&?C&GN2*s=0SaE6c!eH+#&(OpW!w71l^flcYqG_y%e0h#Ef0F zA5P@NswCfeAXj;CLDz(CO`vYywWoHo-ABWs(Bk*#{{ckl0s`gZB4pg{Pd=!=;AniZ z=6x1TlKjJiD#?RAD6sV-4{+f)RXfVsI1>cbcOmZe1?1$Za5$$#HM-SR12!RO%^^XO z-(%`|g&Cw@%GwUh&)&nGbDvBrbQXlS^Msqv@!Q7Bxf86T`b4?tf3#1aKj_BxAB+|p zdcHiPH^xZ2^n+qEG>UR20-$I{WQa5bP%l2^1ltBgOwaCZXvYqdV>(G8+27NEI71~| z?0)Rn#X~83EzofX44ju}H>X-_jgx3G3pkEK;`Xc8!-bzmL|nc0(k^HVE&r;780sHr zK=P<>=+3caNU$?qtXi4>)C!*(6}M&(Ejihu`733okHZ?H*0e>-&&U<-o_oL0;SuF@ z{?(N0AtI%yHXHa*tcmhMhZz;SaQ2GxO z+dsMz{%T0V=$7hR>OH}}XE_*G{5P@hKOJzBCc1BFhb{13U%_ktL6)?adNUtNZWU3* zO9oUuJGFYh<&7r!Yn%gaOG+WMakU^k)&t7)HyJQf?Jl9O(54+HWR=tjLxgE0e@WRU zVE81|uLz}QCH!&Qm!;$kSMQpp$nKfoypgNv3h&zpmO>#cEAfZA|I%%w-vfHHf6c$v zWOQJl%grKcm3`>IYyMFPT0@)0vn+&j?8cIDeTvMl`Ue2z8^Dv)2@L~vx#=q(nE%Vo zjrMxmD~!}9qCW}Z#!d57P5iM~*DQ*X*nQO5fgA2cRQX|(>L28Fgj<@u#~Rrr@&6Kv zH%y1<@^Y0Fwtf{yl=#CP6!FQI(P}yO=w^1C{egdU0=exsubcA}09+G_i|6|Xj3S^k z{?Tb?gT}>R+cO=kExZN_a z*m<1+;oRiRrc3o#*%1dgOQx86y5y&Jg1={ftZRE~2M^~AGuB@TV0}}tw!4D*M&QDI zu#R9vx1UKGR$}zwbk~+%1zF4@5+7w1eNt1=X2UWJuUKSpY9(l&!9@cK+l32 z^^35FT3FM1X!FSM@q@H`QVlqoumgPPhPSQ_1wv&DK8ip#h;NjyuMwmIj|k_y&Q=?( zD|~sQ=;XHkY081%ev!%LTfdVag#ROwNOtPXcM_r38bUUzdpw67T_j8*1+>2Wqge-L zQ5ZROO^SzZePCPT_N8Q2oWukn9vIu_17be1cYE{#d%|4d>Kg=6dc`9t<^?v9VbxS$ z^rNBl+>9&r=7PP%9kPNA<~K-Vv&6>`nlp`(ovYQ_iJNkKngwR zwb_~Nzb%z7>F-|13EGi-t{&f~&~<6TcWQ#&(~t>n$L-bt5c%r@PmWkCNyrvS|KM?7 zv?_DH!m+v{)jB)5vBF2NXja5FTjPC}Okw3?`{N$EM-{I}RRpo(sui); zJq+p~wRVZ*YBkRD+#mw}bK9Myinxjks>V>U@L!NS64FhAME*Z^SFCUO^nZ->sm+ttzTV4}4S zVUfIVJK8jr+HapbI+W&uJyl)qcf?__g>sgI!L=r=P@#-fU4tKHFgZu`VULlXF}@w1 zlE`(^d4q`s2ZzMY)yE4yYV6-A;QSEft6igl@;L&v30k6qOP*Ksg-!ZK zpF8v1&0N8fR0*5iij~0}9^N@$@#Cl6*X};ojNU)hBk25WC=a6XA9ao}!+NJ4NIPc0@n}oA`$pa_0h^ zDDhdB(Iqfz&)n+-=&~L7aC+jlWV@n1 zQGNG4kR6_aH0Iamx6DG64ybiQ+U z{)g@lC#7!o*C;Au4I1@Qg6`zU2ZB^=S&@XF7UXCbXyu-_s)U4@%zAz74C(Qd{Dl^< zn$)`qD04{faB1f(1qU9ProiPY`uK-L-?_96sqFF7-_Wlc(Zq+s>YLkR(q)C0;1Dj& zNePibKC+f+x$-gDe>e&nacvBMkB4V>{^7?P`!NOctb8MURCa)6Bc)Ip4h^!25?(JP z)7KuU0gB!U~mwA^ymfEt2Var=bs})-dN5PA(#BCjRZPX)VTn&^Jx4V zE8fSmxYv6tR3uWAKQg&UD{p-@uCJe`Tk?@O0?j+&RDDLN>pmW7d%Iw?{l2A%C;fwm zD1M$jex5dJhQ+RcC`qf8A1a&akL#GR8lHxL9F@G?QNe0I8Wcr*POUiSDTA2mk~XkT zmib6fpq56t;ElCk>sg$E^@kmnj@k*+j;{*Gd(I1eXa5lCIx9r$w80&qedTx`)a7xb zZ_XaW>oNFa`-GnT6gEb?^X;7W4b>y*`mvJ)B@dbKe>!TBV}yQ9YrHr&z0S1iS~KOC;APXlyLia04jsfNq zE8s8IKfKXwqy^he_s6+dPt{2G`7VjI^Hh){#-mMW@4|4AQN8-VY4o!Y;=~E3Ar8T`&eC#wX?VBpbC#ca(__Z$e z*_tT88Y4K~#wmRUe#~wTJKVPscmag3UAhVza_(>D8f=DRF{P!A*3Qz1V|I7J@Q^qP zLs~|DhljL$IyY%O3R!xE9dBrfwO6=Zr^(t!^vfZE1(5}&5bk^#zs8k@dQja!HbT}mF*}fo>{=xGR(JIAR|LTiH>nGi{ zet$nat66ChFOP*h@erlz+HC(TTr4bC1L9rv2lLzU$13KWPOm z&h}CP)`Ivu4d&o@t^IEOPyn4{1sitdSiu?(=e_CiXBetLJt=31ZX_^v@PEs$-U$7ZB#Cql4|x zg=8zc0sqrh1aByTsq%ce2GELw26O(~@Z<(9E7#r?nD?bx53lhlDp)q;0SO?Xxg;R8 zS~)HCpp$i9e{l`E;f5zGXaD+R;tZPQTMGaArJl-Jzrsz<`*%Om-2g`mhxsrv2LtfQ z2cb=P{J~O(ZGgswu!vR~MVak3RR46`p3QDJ^Rp@@!6r=UInb6`5M)nLy>OqWKRMHp zDHCMr2l;A3j={4k!@VA*W{w6uUf09?>rVUaSQ@#i6WXg&jmC_Og09(Z+0Qq10QGeH z%1~>YQoNh7T*?qY<6fVlET0KT&N?!!uFcz+YDpoz_ATvG$!EwwD>utU`=M%kv))qh z5#6*ac#b^@an!rKUloioEJ<|QsKr35^l#}pCqVp>U!hEy$BC0nrr#Fr^b5qikdmy> zms;Fj78<=@M?0f$MCXZAqYSw5e%v%c{jgL3kGz7!agORrr&6|ic^o{ysV4*{{e$NN zxE0qCUFYz?Wt9N9QaTmO(<8_I4zLr+oCVWB!6({um^F9tS(f(rNcDQ zPELG{jxx4l&n@NiSE=23T>p$+0j>Xt_FaZdpKp@2x(Ior0TTvJDVN%a>T?5+VK-AM zQez<`XP5?GQcp@6n-GOzHcMjQg3MwWYN6#9sogfFY^A$TiMbeuTFQGfkcb6{kNt+p z32?$bYMmsR9j%Z;#Mkmhqo(r zGf%3)@NzfskIbv>S8v&HJH0q8K5MA7!*c+sgS`BjmnfVb0aadh)fguAIQ3Ot_xNp% zHLn7QzDiL`?pcJ?k_~$miMQy2_2qS`$aC_GpoO+ad(ryqF7TV5d1Xu2hO@fb=x{bI;v+sV=KW&; zxoaap4yzwvTG!etI!KLV&&AW)Nn|?Ju+Qmiyk>N5#Rsf3&tk#ZXt{`XLAs0n=5%#D z6&Xx^DF51QZ@tN+*dR{=u&i0QUKFNWDdH^CyGHCH9SD5Yxg~LN=3R8;n9yX2(x0A9 z2nq{Jc^p1M5oT%aQLRhKtc}ebF)_~Q3Lk++h8(|}kOWRXEttAj*Mmfm&m(7)OIaxU zg|sbh_mk4zUbt4Xej!>P#;z3<-Zj9)Vhpf1aiEEc(Acl2vW-;#*hjgEwAKcau%hof zw~lH^BO{$6f1wb!YZ%!P6*BOX_&-PHLPG}b$fa^F;7v6kb8P>*0KI^eVCoPtMUHS5 z1y+;(=MMVsLwWJcuQkVZgGD!F;9rJ#SovT6332Ax z8U_FF08C#m`}93tz8KRQK}2cN{~rBo`^Ke)9C0R>A_&BtaiQ1aW0L+0PgUr5sxlZN z_8!{2V2+xUs-%>r=$)3)9Aq_TIIVRx>jNi(o($%n1kSBmuH-oeYdfM5V@wEA-=`yi z<{aES4bvs(1wS|PJ}>Y-tKX?-wmQX5Uo^zVlq+dHR0^oaY>Noz7P1YW{f$lv3P;inQMKe zNnb9tn688ly2;s&(HQ4e3z;cTtH^|r&?}Uf?N|M^&S&?yHFtMbp;FemR<@~2mmE&E z`QpNGKj^}A1jjdg2v;cfdTr0}gGP(XRj>d)DnGPo`h3tkwpgG5KAB_C{18Wpdjth{ z!yfzN!P8n_CruH^8R@XYBa>K*inrXhGecl+?p5xE=r#-SRty0zRt(I$(S=hHFq1KA zX7G;*&nCFyv*}g%C;KL8Q2$xzbpIB5(j2n={{;B)ge`*qR+Dnu{QoGy+g!W9)gjSd zGPpnFFPPoj>Gy%!_+5%xmy8L{HR$Eh@InchqvwPL8nt}LP*Bgp)-d%0F>kGy=Ya(d z>+zyI98Ual~yE~}Jtf`Jidm0kYlewwMSKynaS96=oO+lQ;UB8bi z9$vbX_Lwt9j8Q_k8^hsn5n1l*5zCN|Gvv;!3^M2oZ?|-*{ zXHF(_x~r^cDSDu13zk=+4QLrQ51xiX47S zJ(nZ<5A4yL?BE`!+ zQ&T`l&HG8dl3av06V3ZcdD z*9WThQh5qyvE(h`R%8N+TA<`DWqy^7T0j@}E+sX;*!adrj`+V+7aRK@)&2iS{5k1QVEz$H6}cBNwN5y(oAIq#6EUMC(a(~4xLB4ioU zp22DnP>UzW&JlT~Du*rmS&hp9||SX9-~hed%U z|CdFvN&d&80>AvPMakik{cBN^{r{ynN(9t@Ey~p3zZ91Y8TpSzJ?XJBVLhjAh{+wZ z(&;u&K%qlCU{=%0`^OM%&Gwn)~e zK090`>r<)~)tso8$%lJl7o!t%HCoOlAGq=?p%3<>32l_?um|;@X5zy#)&}1YhtGeL zjV7B~xf1x97208Gk?jTH)HJI?@xzFOwYR#P?D5v=J#(9mS6GwcDowMUoh4ZBm-2iz zpKQ`j6_gD-_NHp|6&;)UunatA!U1k?zy7?=7iaS6dlz=~X=@Z5o++Agzd4HMVpn)d zb!s^2=C}|RO+Fb3@dKkPmU$d{8z{DAtonDLXUV9P8^SlF;Bk}BFju3=0|Fz(n)cAT z<(xSb&mWuC94A=vgurcKjj9Md1phZm5H28|6hWU3@o_IP4dV2h?B7=g&`odbt}}Mf zJ4*Rlz71xN4l{Y4$eNFn4M|LW*98*=o(*#{(T%pX1^ewCaw1&c{n$cN0TZmuF(Aflgaj)2yT+ zVIc>EUy6laPCs;;!#AW% zkv3VH%Sj_02zEf(=Ub4jdi?*0Tq7b=|LcwwkogzS=mDO#-^9$uYeGHX!tX0|rM`kn zs(H!>({&njDP;K*Y{Kv4QkIaQA%B1f2HBoBRk$TnN>M4ji9s*&PNr!R^)zB~MyLBY z34(+>+5;Y7M79bIUjG3J_U@vQq@TfyJ#8{bi;nqm4Y0A_v2d$nTVVM_?T9qPav;6CSK?z@-we;=m zCw>_%`h`qWy{?HI@9O*NGn@i5oS?pI#inyM_UeE00TrkYJoMyG*RLo zwW|exZ_$J={2HLLpwr2KX|sfOf1;YLa-@fdg2cB9@L2HJW3X7SX)7UuXGMf(#qoHl z2C0S@_JOLJP@v;qg&CvYV*dGCg)QOB;61O?Op>+oPIxjegHl>(^y!-E1D5mkIaY}~ zCp}AnJ-lj!84srpJbgn`0_fT(RpB*M;nk*io>qgYo^7$Il)ikRjae2?UvG!{4TBVO zhKicZSf^?Ol+tlXp$h>yAa$zFUddK*QFBOI*=sabZ4Y(?7!mp2Oef>lbhAUMeOhBd z{AmxD7WRMKTj&FSOz&9ZR4;d{8GcF+X6=nL!a+Oy53Z7L9qr)}(2D|}bZlJX1ZBYY zk416(_oFMhcSm1Rp!EZoZES3e1brxFPg{sY0#FqpBh-zpK>jh5^aQ&v^X!vOSfn-#t#dQI2mw(t1nFwVsm6)(!?_>#^8T~7AIGaQLS#(df+o*R}-JU|RJ93JQC0TA%hNt_n z65Ag1o%mQ8M0NaG^h3Qo6<#?r@l1J!86QTA*ZL51pkku;5dE2ia@yd z-B1v(IY)37{`obuC#!JiQSPyD0e+@hX*-N(O;ezRAzen3t{bV9vhppPcTFAjh3mb$ z;xWurc4@ep^V)SD?x_<)nNvV4Tu<8S5qTEreZNm#VDIa-TRN?!y4VZmV$0{xBa-=C zjgmy_5=0!d!v%4D6Xev<3(>!9Yi{Ebd)Z%$vmpEXL@MMJD(X!Nl`7)tRK6<6j|y*s zSKGzd<#c3L`P?mO78)=&=9 zFJ>uVhdjqQ+hO|1+VDmtjIyJ z%YfqWRQU`4Bt^X!+OL#o1f-3GGf<^4A@HaWuKfmr1)XNrM$Z6@TDTDGP?)KrVd&Z0 zh|ckyOXTp;y#cb{7{ypuXHApqxDClJU|ZFv2%6 z!zlIU^IJv89d0v*KKQY1frr;t8Pt>b69M7X3l-NBJ$0kxpf_s@{T2c_#Ue2h=kN*| z&*Js%vcLL!*FgHvmDi1K2(BKXH8g5C(brzd;*?|ZM#e~K^4{lyp=Z!Ah->~?{G37s zaHJLyM`%J1YDX+wsxURBStdt|YtvT`k)P5vjB^V=K_*bOruxrCFm}Hz=c^V5x~F>7 z-=~*A*yttbku<$nzh*O6U^%kc$IGM+j>s6gdodveR94= zKhbt*3Bu}!dutT1|IM7O&$z=0uh-n(<4|!kD|b^pRNonoggR*)8jg?T+e5x};*ImT zBnc6AHQ5+Oq62dQI$D@P6omZ-{LY6>hF9fD!bZ{h8DAPp*xiu?k+~g`A;hYYX{3p% zh%PU7K_oI95@{Dh$jrfJhrjlBqkqP*F*fD(9rFgvr~@pcf^s*u9~@8em5aynQxjbQi(m?C$2q5uC$nf3l&*ZdZNpAT84$0?5k#-7v

w4joZ?AtCduB04lJm?*7wrAP!dB2&9}=2*34nflVrVXD&%PM zr#GgD9%Nkj?*{SN`qW3GtK+)~pAwAnM?_983EfcSujzb5rb3&PzoV@O)A|KZMDfFd zLuK7%kd;IBky1SJ8I8WrvGh=S)9naFRKjPDJfhG^hBqHGl$LEQAiKFQ#p6UkD6Sb2 zg}jVoYsW*33@95KNI|i;1z1dRla2eQT#%|zJydE3WHx1+6&lZihp09#msMywn4(+2 zT_>v3sg&%f)_zrjqo#X|3PlN8Th#<>?O|Su3RQ@~LXU19i$bq6M)JW7RG^B_oaGN_ z{kBiO*DJiCo@bAMoC7u7-$t_63-jiXHRu<0i-`dUR*6wx?O0CO`sNdug;gSB=rfQ* zZRFp*2YMdgvBCndL;fiXXb0D4_ZwajB$JP?h4KS;9h_}XF)6F54SR44?RS?uc{_kNB4*)5Nm?iSRXwkU${ zp%^werhugJf)rcS{jLf5V4T> zp}*cYP?CfIME^SoQST6;QLTh8J7a`zpy==dHZgnbAev!9aoFijYI|VfgwS>{A`%U( z&vAt!>54GphV4nK3~@-I+AisW)8Nh$E}I_-`+|Wc7G%Avu;n<0Po$>~cF*-PMcM`x z_I>+rbpuk0Tuj^{&?9j8s);$cK1iu-tyo>UfH*KMD|qNg9=@X1KInm*LbZz)F%_-G zV(k(#3lw{VA&=O5rs!!zW1N=oes@^x65st;(0WKxV`dfq{eJhte$pPfRHE<#4*-$T zFDPbwzt09xmSW@5BLvMxrTMJU{hu*)hQ%HBZN^(!)0m--GvoG)kkH||=xfrVL?i;l zn-jwje*%J;2~DhRcwy8~oBvdy&|7VHBL#zmgI2T?dy{D(Ib$;pHim`aj^X2AsY-zG zfMUxVj0~^hR-{|_bFW8ioh0{C`=S}sp7uN0>kdPYEaS<|f;8tzUD`4RoB!rYg?X%qTbWdC|-XH?;KUBCuJ&9j!uf$uZSME$iZT&&-j%5Xj=g zkX61*tzCgt*U?dCIg3&qsR*~4kL-5H9UVtNmJ~pSix#d9qFNLly4c9t=%;l72s9W( zW2zJmrH$+(SSYBLP|Zs|dLHrshlDS;DltY98ykTZ=4?6LFWz7+!m~|1KImE4QSne= zCUb~UV#Z*W6EV~)PJA5to7tVintf>b!b#?XgAaYo>1_3O5hFh z0eHdqV1^Ntbo_0_7V8Bc(mmBK1nQp3=Nb-{hgkDkY6U=Z63FVVBnY!vXayByJ2Nv= z0N8bf@($Nt$b9Alm`f0cVG(0@*XTL8fh!JrBPS%d@s^*VB*fU(YK0zeu=qe?l@N|P z;s9jBSYf0I8}81sHrO?|OAGD&8@45pwm2q+1a zPYN5KE*q8 z8$L!>`1ncFrRQ0MHGFZZ(HsXN>Z@)J7>1&Eyy1)VR%$w?hdnW-0iN?!xAdmUDMp1O z16-NKuW=REw!Fck?N?{}Pn>XA2MSDe3!oISU}E=vix!e{cA>H zcN(X;bpdrZ*OFRK>xxbWxH_1Fdo28QDbmwE2}aakxLA?@y1?R!sdWX-wl!IfStoR~ z89vp8q&b2%*8Q3=UH?TlP=RzW$9}epH=VOEc$U^Btk5)E_Cm00(CsU;77=PVkH{!$ zH;nN~8`G-$oN7aH(v}tUWQ1z_Wvu*)mUQ7a2kfr(!ZKa#fdIYhWx@3M+Ya|FSmY3n zk-(lLyG3=O!l|y_%y9=Q<4F`ctWVhY+$YW+REcoEH93fuXe7e}i0HZahn!4`nZbDw z^XB|!y(w!2II1195aX7RAC0*PO8sgI_MleEwlVUweJ{edMvnXzuUG%*neDtdp2r#t zr8Kv}=%XD2gAr6gQ46T_q6y2YW>hQFd z5>;aA4S2I)r z^tgHu|0Y(mgeDl?hi zqNTml>-$lTayO>B(tEmwU$uh7un`g5t}Mio!vEMt;lul*Re=*2My*JHwZX>taT;iYt$t>(DPfyO z(Uo8{O%$*j_y&m^d@^I+#`I#vMm~MGRt>{1ik{>Oo=xoc0igYk=tt%^`-C}Qa0HAx zL&Cw)>W+)bj7h?TsJ#1HK>kbb_&4;1XRcU)oIy`gJdboh6e0%-q&kY3kquio=Acd} z1nW0;q};9J>=Ab#Yo1@Uq`>6>ep385s#}4&{yO(6#-1AsMO95)0t*UKd%@U( zc{O8&#lDCY`VO&)ABvon`C{89rqtS70_kGnwkMc$;_ywl>)5#U89WC44FF}_DF}f+ zEaW)L$TcuEsfOacGdn}W9o*DYOx)Ri0KKqdz(w#H#4Hc$=vT3DLU{~dmxWLCg`+Uj zzJm0NSj={zG%PM)p;{%vD=m+&GqPV!U~r)t<7+(C;e$dSX}qq8&pHu_2S|_$FsBD% zngb2HtP*Xtq9nXpC>_d5n|~}S6?_`3)e2yzl8zJHWx527{T6dy)}4q5$xhJ{ysUXV zy+mwftYHRD%aq;Y%|GkhMyRz8-J|1yfEt!3^4XOOTs3OeLecOzTurPzC)5#|09FOM z{?{t^pawjx(ID(qT{_8&Dtc>CJa`GB0d^qQo9D?a?5{bQXxDZ2g5|nOBlT1ZIu4#` z1C2l_dxH#gHb0c%#vqj8jF=8gQrB*41dh+m22(q>)&y4;iDoixaSRAlLQ4bLVW8~F zDm(4+E(tz%C{?pi$DTZ9f{)Jdfp9hOR73qp0sIA7NZAo=H0Q-yT%^M~?1EsR2my<^ zVIk2W@Q{)Lj`G;W3PMxQ21R1mO}g5duq(Xqce%f_4I-Hl+T%KN?kelBciAAJOiGb7RlzN8Jz7Ru)v7DmrG2)a)5PM>94i5$5saH~|sepSBJ zFke|nU;$ji>RIzx})aS8XbXN5TfgFGmuWSTJ`qvurOUuwSc7R=blJ zl(6B}x8)pkv{RmzsSm3iZW;`LNlyBFi)%Y{5-eAA5ylGNMr zTFD9}c^>iy-bIo1YNvz06L*h)dOM=0<{<6n;|}RN6Us&ucR!A~iuxfr+Snj9>@@x- zJ*VU85EBwoO{Mn%<9vsJLDXHmQR1H--4UgSh{7!P4})@iPi7+jTgdex8|hclt%hfMy#q zUpi9BSm7XGJCaOR)l#zY3GT;(J=r}-?!Os^7fPY~LU~=kmLUCdqV%btksSBjKpNnDv9xVX|{G|DP-BG?u*0eU>3m;{N z=5Sglj@a}vsX zXswMLb$1&Er!wMdBCo>t-|Y_+DDOh1&{*VWetfn}MQsA=!tX(J8-|_fZd9bX!^MPW%aEhWcoj7S*>ARrQ_{Cs%FOZ z@F$#38n?Zwp$tN0Km#HlkzvK2M!#=y=}1!$)1b-d-m^)I2^nNUbS<<_XDDagwaL@< z=FGJ(KVSw9;D@I3=jFY82Y7QPk7E26Qak2N{yT_&5a*R2!pr^_1c3e4Ymb`N=lBxs zXlZr&WqnljoJS;(&}po%o3chLf)e9g9vR+F?*Z2E-rS8l=E#fAXK6mT2xbeq5Uq^c z-BjejA*+s zL-bS{8TSce4eEaKD2on+&$MBs+BV#V#Z8l>`L zr7k-`(KB@wvHfDt!;7446m^%DB1+_-jM;uw)U+&ZX!fC|b}pI9En*qXv=|_8B-^j5 zm6SS*{OWnhRJ({q&@18qr-yVkl05M9odm$VU7Wl1XS$lUleVRxN4XU8hf zutViwv$Nz$|D+p|^C4EO>j*z$mgJXa$z~6p=2e{TV|5Y5>`dqLocOpMUwLbscdlFn z!Wlm5+}RKO4w?NuT=u6@vO#v?Puj{9ZL%|S6@B@i%A0F8||7Iv$s1r|>+SyhMm8e<`_t9k+GK9*5*?{3qugL8~?J7s5Peub1y& zig4Cf?0NK3Pn_z8<21VQDh(%Y%et|oHHGqY5{ULb0;SB718|;^# zQ*z%KEz3C=EmvGY*L1RB1n*DD+8!^mt9KCaWxWRS^Z4iESW~>jMWuk~+<%cUHC_+} z?CR3{mz*6XHBB7GJJ=NiXgZKuX1^eS*QJKa!9f5QZf_fRBJSG@UJW6pFm5~F&4-sVfO{%5p zw^WO%yE%R)BE?c)?!YcjJakiX;F$U6g_yt3F6zu+Ges%N zgcJEsy?jr0q(uFt(0loSjrfz?U-+3l<>{Ncd#;+snQ%V6V_AshM5S%G#9!G{?4Ppv zu;$4m8H!TL|Ajw1)gPmdBnBnCHYp7~)_NI!CWXELdsl;gGpUthDIV8mxHt6!sWfs; zME%-ylix2rOG!1_eQi0ko-~T-h+o#*z3V%;@9B~Up36eirq}YZxcv`#ysPE?S8BvZbL%xe{U+P^meKZKj>%81 znycpnu0Nh!b)$3@S1sSx;dou}N-l7}bbW%8XWVLcSltb4B&hXyo0PCfdFOv~7a(g2 zX^kfT5og2u^!hEuG#)I&@OHO#%2QnbIh*?HOT z;e+{8Z`Y`P$%Xm>_>>uyqx~y`!{+q**2+8Qv2^jGt*$?&s03O~#7V?SuUApB%^lD& zSZ!GCiQ$K<8k(+IXS_+ZEq5*E(HgWa?UuCLX1lQw75QbP}JuAJ3HIs?!IzaGui z@*BSjsj*YzmDu>)Pl$)A>S}$i`BtSzM69m;)il_2^+@d=g>g`=&^?7*bD4MQGrD%I zyG;kYcJ0=Hlvj8<*%?7lmsU$KXIATPBe(}T)eY4!#hPe>g<8e^vlXbCEs2hSvirMx zFZjiu{3*g*3I}Wq9K=FF-wP1b$CleOjLn36L~~p4UDuaKG{h6v-PH7c*4$N~N$h{p zG56gekDZQBzOAYpj*{ri#)$VjlQmzl*VoT&43oZOn|Js!$VY(C#*w_dSpPb2V$9Iv zS^XJa%cKX5&ZxFkt>erylA&$v+()1r3k#+Ss+J`hYdol&3XXv^@q)18bIU2=T`A;; zhga@_Be(f{SE$XkH6~TvXj_wff8oISmp^_19VxSL!TNd0F!PUMno*qba7mtkVdBh? zr=jN#YvR@Htpi9s_rG^{34O~z{QQ1+2N}W(E&-3unaa|mvC97Y?7V;K@7Xy)46Evo zR)jPknrZ`%m8wh**ThS!+;UdU%Q=U*CU$IPVeaJdYKr^FMM|aoI62?-n9@#!v|G}& z5ye1KSG{1;&*Xo>r~lcu1>f=uC%bD^CD$N?B)3Fx5)8F5CEWse*at@8!niKlaKSGa zh$Bd-k`=LktL*9&sF=@0J+CQALRq(r^MW(#>JLs=??*;dNA+aZ?%=d@BrblAUZq2I zGlxQ1!K&925K_m6A7$r-Zo5tczNUZJ=*dn^;J7J>zkKLJ8@0wU@4@Ql;gdz4yi*@c zjo5Y0xS*-j1a@mSx3TmlHdC2`ZGMmHj7LuKX+UZOEm}!k~0j%jFv?%$h1dk>Up z%*S+>7N()GuSkJ$HO>rXS(c_D!vI4~@`RwsfFCkGsw~xD(=WnMpJz!G0@VWHMDZo@ zsPHs!G}=Rl0})NAGzx@GcY;~Dz8CZhQzMa^)1;7wylPZlpxI^A6TTbmk2Hd8fkKsBz}M7lDSxG_Ke*lRFlsES0iU z#srg9xMh`(0nBF7cs(Z%3PLun6ty~c0rw(>v$`apB*GV+p(BoF0ptNSQf8s&|n9JXLKt(@tv$i;QokI zin&KdiP+vOFoUu0G9RC)G=4_Z(54*AGVuQ-%t9_kggsvI`O`4X3ZQaNK1K8|TzpcR zDGav9o)tkNCnoSeWpc@XVXiMBL-~}bk(wz{mQzj!17F|*2mw(aN7e|HK8}Qm7zB}a z#E>E`07wdF2*SL%oLGjVdQd4uG-$o{O)#1gkUCQn7byTBs8Mhcwnb0&6b2akJ!5^y zTuv%!V;U()IA^?{*j38%V&<=+p<#n8S`Jo3VX`H+(iXmRMfC2tv2M$3sn&@Z0gaiu%E3$TyKD&6@=yhyN@j=B3$cc|BW4uSDd~*5W@mdI3NQw( z2AY7ClD&2+3<*uS*ggfAKb#*D=Rm@88VuAMMQUsxOqwRD154{SY|{|887E^{PgGcf z>H?BduXRrEA;XZ=;YaxQBV7HZL%Z@khSQ#5z&^_q9t2uub0pZfC5mXEehiS_ct^ERqXf~F1UN{^9 z*GV0beo?Z*)S6k*`mFQ@{?-=quludDc`KcGv<^nHDWxzkCp2I)r|c(aUQZ}V*1>pT z76FMEZw-=gmAW0f`d2$l`=@FKJ24lcBD|ujFeaq2E>s@fm!S+jdoTb#tXc%PcVP6(SAxKLi!XH zq4_<|AzjMQ{1CKIRmJz!4jwct<}!oVYC86P<*6H8&w8ei z$5ZZjhwe7Ky63u7AR?oxap;gOpg9Z5 z1ICO)AgK&Gb7!^9P%?Npn&4Al31UmHs>x!?;t_!;GB06UjXzMxQ_K)dgb78lK4310 zRR-2MtN3$jPBH9f0EE02mQy`jY^04c&i4*!kdf&Rb(k2h|4vt9V4jhy zJ5WG({wR(LrwZS*cba$E<_$X$st}~0H{((+WHp$w%FsxraiSPEiaHDS3&4k^fEP1n zvrw{jf*c|e3FlB#paOe_0R=Ocf-_2N+rcCREoy=R3Ijp_ssXnAD}vpe4)In}-qYJP z0cIeSRE@<}Q#WV_6xXVxFv&`cYe`7ZxWh9<#)ooEjo_!ghk8~p)gyv(lA}m1$s$(% z*ANO33^kQ|CBFnVfLoxhf%`0p-hl#&VR2>Wy4kz~MeU-BB<)%DxKo%C&N?%B3%OKC zNup|@PL+=;N&;jFh@~8*ta0H!-Hqo@H*qS8@2h+_~= zuOS=njb=?vZr;{y{%(r+Cg;>6YP`PSrWY$YAN01gH=h9|N4F}BuR4pe*IN}6Y1li|izey`qM)X163AH{*9o5u03LQEbU|J8S3)(k{R zPI^37q-HN|U*=g-GFUSp17bD%MyS@|VA^Qk&S3-Tv~D2rMKPLXBD}cJC%|Db1VbG5 zTgq#pn;nz`I6lZ|bcpdCW-A)Ls;E=pTiws~HD(Ol(23BILVV0(1jdrRDGP=S(J7c3 z&}yvMr6YdoWpZ|^TJD3Y<^eVnl!J+w88_iwg?<_`#)_kE^eY$x3=If1@5rUFAW>e6 z?DOs}y(M%D&z~peN4enEu&4QMW3UuoP5Gff*PZO_g;HJmI0OQ<3NR}!$gOyT*cDGN zK!J`|n#v64C^ZZv3j7*ky-BG3unnL!0PCy%tl1J5P}=wy3zG>CgO^s&{DG*LmwGN_uiZ)i5nnjz$E0Vk-p6 zh+$Yj0JK2Th*&j|kRf(0)e({b%;zh0RCfbbg}tB}AZh{kr~|n6>Nd982a)eob5iTU zGtC95btCFhd*)s4*6Qeya-k2VNkL~C5?OWbC2K)nwDg(k8Spp7DN$kfWTM?TmRYWf z&|bQoHM3Om_nyQkn;DM3y0nQ2bQmg8wbpF)cI5^9w!xEyRkD0=F{zdI2 z)JIx`CCZqN+~ZP=ig{GLb7Vy#i$g0UH1$he z8?UU;-J_CKKs}xt3}hvYxPGasT6G{jv>#P%CumzUnkh8E_@W?)p>QFff|Oh!|2bDY zujI@WB06`>I8tXxA|-UU&|}#N*!Vh>^8us zkC=$ui@vUJs2T#o% zcED0$X|ch|G`p=w*UwkSchW@rdGF;I!9b!u2TFtfxOjUx+kf<_;YaljU){s9M=PGh zBa(4j+z8TW)n>QbXx@psBk|MA=-X@NE9Ug28$s~E;1QnAD_xf}t5sVX?A6xS7l}w2 zhBDjW==iLAKd?i=9k- zNLI^uMZP~W3?k1A#lE5oXu4tkTnCAA`_q$u`ts=cWAV+)^Rov*xZwXHChzc&r%B_5 zF0DgzN{;eI)>U3yy*T~+-sbnA-3#_u@VEg>20Vp6crse<8Gmxi_k)L=H6avoArmP% z%G=j`J8^+JGxtYj05$+J0AzP&R#*5RKTOXun*DofbZh&vY`3Q~-w>9xc$y`J$MUzCm5itMCxx;yzL3FkQRlO)Jg+4_Hs^)lKV-ZY)VN4<6INIJ@H5EJ$iS{z(mu$<0mN)77Pu51yLme zt@8P7#viX~MtBFWy&isQ^=o_BtMi2^Pe!7CGBt46fLQ|`Qy)B<*Bq;MbZ>LexG9># z-R|b_hr1+0P~Q&Y(+{F|ip7~}yD>5%-BB(ej`6@hWjHOTZT1iQoMT z@11zoqq2zbt<6FF*TT;`u6U#gSO*ZELRUbc)z$_#O%&FYf2_ImbV zvZi*lcc~rUOTR+HS41_-iE(5*m?r@Ta9!C76H6h(i_xo!G`tRo*fk|-t*qB=w(<#+ zsZBG6a%Rr2(LK!0Yb@Gno}AcZ9vRhp60&u(upMTi8W9c1hPpB#sq$geNer@Ndtl2a z^Q*}^xG-WFMKKLC)B{uIJzm`y>5WMt5YG#At5n8(4LcMwFUcI#f%%lk7B}}r!zM!bcBZqRo^_HYCMR5)S(jerXPhCgOB z;}&O7!CP)h002Hd^uU0P3YNw$u1==TjLb~H#KQFV4->11@W;PQz*hrVIE2MTIXRga z9PG>^733rkU~yrA|;BHIcs#>e{ zxD`}Ebs31J6A?rVI)R8hMm#Psy7g}VLmOkv!ztMXVRBHZGp?BPAeM|O`r4w1Jr9?GP=o2eyRhu?h8zD2ZlrmPs zjtUW;pcEHY(Hvj⪙-Xr(sctL-lNXF^mYAeRPpyTF!C@k1@Fxv0w#yy2dgNlbESzW zS{Y*f2`i*zYL#AYQ;T_ix75_-+|`jaRsGZ(s@=<+u0Bm3x~q4~R__x>Z>u_X{T&MS!7iZDPy;e}K{9$X zwQV1Y`f9k10T?Bv{?|Aw(qS^XwyPY4e*IvBB6TFsF@}C2pCo?cieJC9H@H=N@47J| z3Fx=`8=BU-L+!C@?N6y#Dz6NEiGQf=dd^0#X%VAb|(bZFODwOh~GlFv>-B$bx8Xqzwq4PCX>eOrq6kc0g_g~^` zvZ2JZIFW$ojI9i1x*s8!0f0ZDhB!1b#d8j+ZA1v_d9gTjeLkF$p2vmRG@n!j9f;m| zsUmL2(Gnjj#1ZkU%YF+YT>yF}*89X!`o0KexmsMi3LPiJ>JZh_HcS6)dpevjQ!3V2 zDbw0+LQXwGPj(qcehNXy=ia6;bSDe<#(cK`zqc_p??s9q56jDb2Ft7Tts`@GLtgSKq_4tRLU=I#DcVKN6&v1cnS6&5>K`fdUxhm@Gx zt0S8_uwf71T*pmG}pRUc>Y=i4+k!r?S_T}x9jwaWz z#rvp&QCE|isJyeEF*{v*exb~$wT z{pzQa%_D92nUBH%j9|mHAPW=N@Fc!OfixT5b#+4D9#lw^yJG5@HX441nyiN>VO}nO zvxPR1qUn%#Ylw@ix`NG*fdSA@0puL;HgzvAy?mLe=5(Ngp<`sry#+thg}A&(I9aR1 zmmU%3*2kE|{|m0B2H~U3wI6ocbjq2Sc!bOSmMJ-J9Jp~JgMk|GE^JGs;@sJE`7;72 zdC^TUsm;hk-T=y)$%5VAe!wIKEEgeOygPv;!I)6D!7t}`Q-#-rjNZR(!6xd+xh%xY z=T>3z5=6o==>54Rm(`4cvEqS$-SUGepbUKQD~`h9!3v#T>u=6ednn-y`Y?+}054Pe z!5?$OhMu>A{@5ZU3H%0}O>5ln(d4;*xE3G`vP7p+l(^8m?5-@4^U5#IBTsQEI7Y2< zc@Kxkk7D?|ELhz9+QqUpkHsBtY?CeC1cuWE>I5##6jMp3o3+PbtF!)45o^=2lKmu^ zhcj9GY4FxfOu$AGL-yz6?8EsNv<_9i`h`o-k77(5@RM{mM}7yJiIdT3ZyZ`ESmyFw zP*d4qlHBvLyl2v!mmL&8=Wa?b+=+aK?RD(&E*L(_0gMM4Z1#X=_-${=+YOz5b5S|< z9kp63I58Df)5FB{qA_*5`3AP@nH39;C-hCS>tmz`^v^QUWm6r=IE~l8wqd?ExD}jX zwEBU*pfk7SIPt{me6wFZaDF8+_aC$;=+1IO`zRAoXrRF%G^`zGNA>2mB&li@mEZ=~ zFF$m}PG#JbJ-0+Z3k z^anVBE!r$hju_@ zSJ!PndW#<(*M)(-0~=7ItNmaNtHQqV62W*)={RBqj!3rMEDy;U%6o7>`4}iMzVb|I@@Cz+nfn zKG!J z4@X_%Dt#;51T*MVDY3Xe+DQ^I*W-Qfy~YzNPav|y`a80{VT76TQO8PSCkX7_O-H>x zURbsP8bWFKR1+3V7f}^8`o`E#0oJK}TCtkwxROUX_R9CQ-jel5|Jf1-uDJ5%BP z(gj>j0RVJpVTVrhDPy_hXuUmp-RB0fKr|95o(1p>9S$LCyY?`7Ye>nLsL8uXXyIgIgyvfw*WB6aY*5d=UOVVcqxz zkrxxv@##%?UF<_@gI*@OzR4is zrB=(v{%P~@R~R6!#}@Y=Nel#{iPB6*XTDFKv+mO(P!9;}0qDxw9T%usEd+zkpXqZu z`1RC*6TwI7()`sxr`xz6aIpUj2CXh;-GT@MmvW|II0f$w_COBBiL;7msSPTiyc{ zH^9(B5@wu$>$h@veqR;!yNQYaznS?l+3Bo-lktWe8rorceJ4=c01;)B@fxC+O7hU- zpS}4}wWS{d6zI^IX)FU*h0g17(drwW7m`5b#gt!%A6~GD4X<4I=Me}4e*vb|LDDeO z*pdn>x05lb2`HqW7C-@RFzB_nWj@hIx<0wuAz%C*KnLe4thA=tBH(}4vGg1H#xFU{@xlMu3 zNj>p!$YlJdHcWhG>~yTvddIE!j#!UWV1klGbt7 zitVhI>91M=D7ekrdRsgH6m|cp?vEq$Z;it>;U{rJzcG|=wu2A(bQ0Dh`7J&x9?%{=gmDnrH>{6o&A(My9NqvIfr?(z0!UHzl6P+Jf%K`!`aOHZB*AJBBY~k0F+MB)k5u z*G>!$8|VZaZ?wl_uAmk!0f4&_60w}05Bu&Nd|VqL=exKP|FmyRyzAiCy~|{hjvg}~ z>4+#dSU?7|>kO@*-491~ovX{o-BoBO%fG!Qz_HOvL#@;t^4JZ(O+=&wA2?DPyr;+$ z{y2Kbd06GPD#i*Q9N=~N5EC**)z=6jTrdrRzmOx=UIFk&uw?t|g_G4n;sgK)ZdlE`6SJ&diy)=e}ni!Owrc%tEVgOZf03H?4#e923GCaa2on?2f^A`qdJ* zRp(z^LHvoR)oDS%rmw3{3Xa|lfC z=1I`Y^5B^?*3MF%Sb?4YqoVq(935Zx7~b@-<$c-+wHGWpub};(V^Ky?#nNXrH+R}j zzXt1{Ps_Hc<$YXrUx%J@c1aSP5%?LAz7S-U*F??gHlBhH(BMJ*Yr81++j(o#rz|~= zZ74JTbAk&?Ct!@erHn|j!*Wp^NIdT&riJCB#G1;Xr6q%ZGxWcg;s}u)WWFl4(uhHG z-BBcj12NiE>ypj&z8d_4tRb{?0^8!+hm@E#l(J zIdgD85hF#5fJM{okE`=DN?i&R?TgQ?w29C1PZ(cpUfs!*^UJw*%&C&ZIFi$kwuupU zhgBg0*__nfSard!%uEy*qsupA{B>2y4N5AX|^D#79V6+LPV=e5R?_LR# z$AtV`RQ<9zCYkxAL3%mPohj2?P9e~~`*JmgZ}WKp@=@>OX(e2Hag z#MhN4eoW|MHyJ^qe8~BqVFwZSl94xT^J4* z3Ez>7k4L;@y-mJ)qNcSU zq*?wms|3Y*Byl*&p}ypbY!;xPb;kN0O}9oSR&`F*1<+EzC4R2q+8GM!mr zykA=*ZNf;;d`MD^UrjbyiQPZPkqpB@8$t~?##lQhl}vB1tHPHzm14Gks)gNAs5xk_ zKr=VxV71vI$rmLvJ3lD}+hj#i`g5y%zamK6b!lqq{{j0--__NXpAdi4C^`Hh%nt-b zWrB#MrOS!?c680nVr&22?i^!5zavcoa+T~k3PTBwHq+oIm&b+#;njSo=-bZnTKc{p zErc5px?h$nbEYB~p$r&}af^NW*c%~K*ljdnq%!dKnU&?`v6rqFJ)h!}YA;3#xBSRj zxyuy1yU?Ql@e2*z)zZ-6}E9G#S;D|#@JL|b2~Q%nq? z7Gvq>&v~MMl%)H-Zba(;z42#;(p0g0k(mYOsx4_2J!_vU=AW!li4!jDQCCUM$`3S+ zCV3?|3xzWzE_zQ1LU!BqB%YHUx_&;~ctl;L+aqgl-#nK;Y`NMw(>Q6Eqhc(BH74tR zQROAomhU0kpN2gQaDaa;&t@5G!j)u|PNb;#`I1!f%V73nCc^EV$?)s6O7`9i_V)aBUf7j_P8T>U9SO{SvlU;Hi_Gd`f>Q=Nfi0N%dg;>0?R+R zewH~%y0wvx+eY*4#bSi?K;KVJkjmPONA;eae_%&F^>BS3O%L|4v;(;^XNCkL8+S6U>JbRIypv*~=#c3`%`U z?iWRZ=%6x?@;i9t4~J%o+M4Nm4poyDGpvOR_rbmaif}C{O5f}7<&y*%@Zc0P0?Wqb zHHY4(Rd$V$uu!H!ye1;&Z5dM_hzXU|?WsUVn0m+ws(K zhFlJzBzKvjlbqbv-WOGzG!c)XNOY7~Pm>5<`2@u|;f$mHv{7bw&A0I3Wfc$ZA77+^ zl*Ur#i7xXL6T~6sTSP6JL8V)qmCgj`6kC;5uvrAp`!(M>r{k#)==Cx&ap(lTm16(q zcR&}7elThH?;!K@Ns3A{hW_~e>ShannwjtSh2nR0o;PmBd@XYzc_vIK@$ZtG^{6d) za>qL<%h&l(#HNvQIXij%Qr92OyQ>LEBR_^2G|Jd@;dX)Oql@-FNGs1onci7f#2o2n zd4|ch@7Z_Qr{9zPm&(GdZ>?K$a)D=PY<{9F{IlyTYTI%YMO>x(?IT%azf{WQ&OuD! z^QRB*!K5K$;LO?nJXd1#zFOzvp-Wm@(FQk19G9CF5iZ4{+}1uxu?QYtH>>_N{VmHB z8CGYZVZdGzFI`AdEi@0(7y#Ya?1t1~v}6;EY;46)cd6w?Y|=;!2y5bOu=(VyDguDBrS>1P<Ywj!66*bKKHJq%hl0a4*rIwO0ohm={z{6-{@jqrN>^I zg~U`gfI>GEo+(PRH{8w}dwrq>advUTM~nT+y4}o2{Ka}lLqnQ2s_;szrx|fYEFtB4 zjD^0~L*EG%2geKXUlv^oeSw9t%gMOI&SijesxemW8$qj*A1b?Q#GPXm_A!$~a~C#or7t?gW}ZV8N!9*+Fb59O^*=tNqBZ@IU=3f=1{#cL)TdBEOd@DFI>xTLTHjc%YFC7R3K_ zV7g4N&PX!8nHuLPShDT&mikv%(4b>c@q=+>%1?v5VMPo^OhKj#-)rLFu(`23{R4++ zxg5sL?fPAC!fla}gy6;rX=`h{Mg+fQ4+{%J6%1N&(qTegC9InRtS45h9FzRHvirps zO*l8|uC@DUp^+BW7~>7fNdGd;(!+V%ZrG~!N>xY4b2#cpo+SX>KYz-{mHN8u&Nl6U zngimmf5gp7!ZyYEh9&~@!cx5}26l%}&rM+J0mS^o!hAce)~@!_*V^lUI5gN;+wt(X zReSGrxTh5c=KO^A&I7;jlz7;kSM@TQyS8@1Zjs+xmyDx6pkYb33w3O0v!S>l4XqKW zMop|Rr_KSzJv77p&b}-6`PQ2#Y!l0W8Ix`o@>q2a?$>4u?_<4GSt<7Fs&Lj9He4wj zAz9yV8qNO+GDkn~!X@!V2(j(VE1CReonMfV!1k&qKL?*`?UYhY$e;5{&_&c8Ri}Hg z=vAZnwO8*0gUuB(Mk?J~X`^OV@7~Biub%n%UR6y>7$f~Pc+S=RR^V0;h&~Z@Yz_%xpC<m2G6Yl0SG)fJ^OWQ#ns3thZ>aQ?nOApwd$JX69vZy3tw!l z@<{ceCgiBQ{tsDZ$qhPvk>h=o6cXt23jE~NGK{qwyr+XN@Gvk3t-c)Ci!9XI%D~%x z%BAHIJYvd7!B93PSNY2{>*8MQe(|05KX}jjzCPG|bSv4jLX|}15dmfpt+?yxVvzZp zWg=ivAr^yLcrZ*WHwAs@MnAemSxHKf@Q2fH%0m~oU0?ggOAELDd}>)Ts0bNII2e3B zJyiD@qw$vx_J0+gR^kCZVmh3kN9sOl_@XuIAmh`|t!u-IT;!AOx>ZjgN3R<^Pu=h+ zn%m3JVv>>B3VAG%=B|PY;A3!!FoS;2z;!DwpAv-ayb*3^d`e>f1eB*!WDw8y6~dV% z*A1n`f@l%~4Qc)9nZ`l%@I0lI4D>gSu@y7pYIWMb@Ik*t8dM_m;*YDPNXJ&5{O6dl z***W3@LCn(1r4;OzdkIJls-}Se6irEo|$5zoJc4*cq5pTf|0J-o`nDCf6LP|r;c3- z?(ZFsCjNj+h8d(L7t*Z%mXhCBUbrniTik(uN<6QM2XZ6_y9f!+Ro?6>e`1N|c7P7` z6#UarKXLAn@3cnl?JZPvHK7)dOA4Q$o(2ps#$;QaYk+NG{lh>%t#n0~NY0-OLs!54 zIgG<)MNI6DF>mz_xLt5bi7N**2lH6Iwyy31caYj2vXe?lk`>1M^^Y8ka<_mg7HSFp z8AR(FHwaJg=W$kFdIs2x?hdheed#^o{DXgzmy)SjpgEa6UpNX@iYx7limha3Xn8T- zzR&bOM^er;)~-1W89tn$|1?4K-2!RS80u>5~_ok-V=;~~Ji z!H@NiSFri{Z=S;hFa6(*PuX?k&rpek5_ylOn1q;oPCm&<_W~0bJv}I_)#JVQW|q=x zn)g5Rt?o1d>+bw*mR^Tsss3pENJB6V$G+cR%8iPDIEeR%u5`;RlU4=b6X{GkdM_o8 z#|qoxLI0g;z1Lb<(V$h`!Oudid(-doahzln3xBj7_hI~Tb<0RmWhW2(wCoc9D*9`` zRUU*iX8VI01FGzuFgil~+HP{z(ntaS$*h*+wZJl$HfuOhftJUxzQ+_OMEJPyr=@A(p`6H%DmoHD* zCw?W1@~k^!lqIk(I@$cc>1?mJ%8Kf)t?G0VgW0m?AFUd!e%keY5g5u(IQV_1&7#}r zj{|Y~_!^^vw`|BbiXNzz1fyFnO=A51f+~8=8*kufU;mYSeOcyxa3EtE?7v}3JRWI} zJY1c>P<#I8gzZbZm;AH!p-&&S+g7|-13xilIuM+9A*6gy$lr^3fANaM=$2sXDrfeI zoC(vMKBfEL*&LOEkbl*SCA|ZQeV-%3FvQkVu6ilTzToNk*r2-Lv*vK{2NAsoPz=GYyMW7EYXdgWIz_Tc+ zT++W+4HPaXtKSWqq=m75nf&cX+A`melH5UWiS*AcE+Pj%^|<}I8<3kyjwpNjsYmE1 ztZw=RnR|>J6Y#zUsmXgpu=ETt!bT;UIl@)CtT8J2Pghn~FIHAp)Z>VW;6!mx;ml7T zIzsb9N(X-y7uD&}M<8N!b#)PeuZ^3vSi1>B+qF+%cpNFolqxSN!$VF=F(5Z2haSmM zQK~G$!nLv4uT->k^tM%4V;VSbHU1Jki;-&|_f6F;9LX7@#MA6uaU`1Rccs_#0#w7n z83a53bJ2wze03zR8_SM4I_3=dyfr*5g~F#m+PRrBh_6 zJ-vedH7uYPtsM`ywXrKLronttuSAyHL)C7FhE#rVr6!#x_anOUdnoa##jH=)I#DPT zPoer@(~@TK)XK&26+XPaUX)uJAJRBC2M}}Bgnmr2Z8QfdWHo56=)rO}z9j zJJnO6a$A@g8Gk;dpcs!4#G?@un(OW5Yj06ZahCXqacML1le%l+Ls{*rpG=O*X;SU( zw=84^z9JqT$EQzs+=g}-@mG6uSu{(1GRLfXOneH7X?rye&#(TtUB|aPLWG36F+9%X zwX zCfUA9vi!Pwi;Jg3uSrOZhX)Y{>o?@GoBG{^<7|b!W_Sm4D-AkYvGR~6tso9sixFP{ zEOB# zG7~ACq{Zs%b9)motCS{&lYz`+S=~kTi>Dm_9UeYpN5xizi1``slrJqfL*3RT1F#-F zo2s#|UiT5-aVUKeBd|EJFGmA`%np1f%=FwV65vQ*H3no0U5p&EPueivYo&YiJv}|W zw0NkVLC-wp6K5NUvs%91igD5y+c>ZF(?)_gDCQNdxcJ=ZpLUkY(z!2W&tiz{2X+Qy zq@FoOi1|4ZI;$P$laC8ktu)LBJ>oxf7rBSx*9m&`fTG^2YY6@@@J}o#0^|LydBXRl1uej`l_|b(4wJhrhqu?42Px*3IQ&u(*1`8GA484a!*7}`KIKd}r~D!l(OvSPNpG1-&kQ>+_!Guy16cZo}JlBx2?nFWvnV)Tv}n_yn|deT{pGTozubjkC-n& zWj>RIylccLC@9DmK`Fd1Z)>YZVnQoZ*?W?7?M(ijfg$|j-3 zU?qWMt2C>2!*)=)29Lng)kpo6gKI5YL-|WUY?uwI*V8k_3iW&t_*!;i{$m#6(D}ws zOJmlH`}^Y}d`!qM{+#{(-o*+=Nn`dd5h_=hFF1>ciK@R!Z|GmV;Jew+GanarwQb3j zUsFue?GCjp!|h>v%J97Z%6)$*XE1i}T#vZN6X$J2%Gpl$sLhj$qn&Fq3igdrY&W-4 zZ2bn83wn{O<+UnZ7uVIEN&F-Mn}&|rS+Ot}LLAxP<0eumjETbYS)Z#t)x*XP9yz#5 zzNLwk-xaezEujIe0=crFfXD$OME{W`?IX*8n4V}h9iPo!>kj|~PZaFSW2sc3Ls{FI zYXej1Fv@S0Jw|vt;@-UObIk!P^pW29Q*62Gy`%I=wcEHL?#;|gV0J)*Kao@=;TD@- z!kl-JVOvSDsT#rPtJ2;bPAOh)J+fzf4XwRGr&%gd*r(&uARg=S0!KEw?8$uP^k1iL-55t*l8W%ZNE4#)kXXYzb?Z#DYWKa7+@X6s)SIzt@AdB$C07XP+1Xhx)O79iW1{0# z8?hv9s+TTiy+sk0@okyrJ^Z#HVkqT;bkO7pGo0Vvj#vAUb~$H!&a~r!2{B?>xz6K* z3dG+De9eAgcetCkJLfm>0~VTJ@45w>>lxSPih2=_vIseC$GD1-%c&59iI}J#ogY4_ zo-@Dx^SVmJ^QaE>r(GOLBj~hVCsb{nl8!WGM8aXIAW&aZml|4LfQ$MDBsHU+UR@eq zyP-49DYoDUO2gj9NjbQr=IHg6eXTuFLw2V4Z7--sd?i%O8!e7=KqVXdF6Qh{3@m`j zJ#r5>Z+vdy&1R^7ny-O}^VEoJN<45*O$YxHA?CkVKytT9f z*;{UglYk&}R>1~lCBFiZdx=HCmnjzs+5XPab*k6w)Z5M!#c;%*5D#F{7IWf)L&$>8<408EMxxCl^Neqb3IJ>w=c0d-a?4n7(x9~S4_wEs%4qIjt zpKK5Mya-#fv^N*}u>O~$4cFdubG8@}QBqQ}-yqVF1avp!XBvO7AVyrPoBvpZ(%}UM zh(Z>cLPB#C3&)Ct1&;%|e1Oc+5A*?}nI;lp&&zOqo5^N}5+*p{(b#xcwoXRyU$}C1 zPIGx4Z*x80S;*@15Uh`Z)~+w=9R)tquO(VH_{}4L{%&3N0yVkdL0jkPydT_j7F9XMB zoo<(p6Bl=1|9hv#@HGN!V}q>PPiJ4gr>ZMT7!HSvW+StdddLnJj042Anoh=-KDS#+ zCkTAQqY`YeUpy;M`F7sOozSx&C3U7}Dwaq4pA}geTB2XOFwujb2eZ(K&Ou_vZk&DHQwKVMLLSms_Q3hDF}76C723W0 zz{lIWz#tPWq1t*B7auz2GIvbDWeh^$Z&tPQGe>VjzgwZV-;R?(G-YLCj%*;^I>*fc zakj*S!!*gTynE-G4n9uyq5>QwKkTYnK@EO^aF z47%iv1dl_%$yHJKH^pDe*6vKWe(27AUea2?GbE|c<)SPAU%EN zRN72Wv^3V%Ou0ZmPb`aqm$?!gV*<6G)oIr!m69@-ZyH>Rer1S=tHlHMCVnMm;REKWy%e<`xw-9n3t#5E?Xy5Nmk&V?I697y0zAm zzaJaMaTqoWZH*R=^BrB+b+p+g37SlN=L)K;P0I63Ao{tB4Ys>9Y_^626@Xmkk6Pc< zP{C_`kIyOn#L^7G?do|ua~&*sLiMsN8iw7N0x+jxrTz7!l33zkTSv!>I9P-jul2}> zLloRCSloTDOcX^-^#PAs%U`T($3IfABjP%> zr4!_C1e!wFU4OKN)F+2{1joQ|%5)9vOHMOdJAJ7L`9Hiw5p&{$3;lb#W_RMRcNk~| z+3hGYEQ2C;8FJsHj_9P}&<{T4xB3-t*-yC3Q+PXUpZ_xs%CThtLQB@0Pz#ph<9G(3 zB>j*JO+G$$=dEjKXkH(!ynH7qDy9_kBTO_F1Jd&;0pgJs6qeHt8MH3a-2~SWWXxd;1FX4b5}f1t>mv z<;wbe^lYg^DKyBJI`u`Vf3=?$1Tw$ND@drvcGr{0mEY4E)L6c*FqmRC^3FCP03BOL z36;Z8@WOmG=7rq3TGX|7AH&DhviZ2s(8J19Q8k&OgMl#l5Bj0fe$ZPZm%rMh4MxD@i04OC8}m zitu|AS?TG&Y^KAhbgSm7fM+!rvuDgTJD=XjKIw2x2X?j731n~ZTANK@>*{)BRjZ~3 z;AP)eSy`efxy{W{3L0~>Mw8<^{k@6&f?9cs#Y-LT?5R2`Uy7w6ke<&kH2-X>v;F2p zhK6k=f+|5JM=oZoO4pz2WLvnb>8H#l=vX=mn1sm+oAr*Y$@Nrm>T*1y5OQCR%t6?5 zT0)_xYLC|jGE7+#inF^9qs+Jye9pT5mf{kbi@ z!c$)ED+FL+z}rmrZKl{74gm2qSuP1bMr-^M@SMy{fD3T!2EA9{H(qoMc~wnbyVQjw zP|BBObCjr3F2qDXV)!YOV23ZrcAU6;vygkOi^*cnJ4xlH(kIzecfdD0tD^np=Z(iW zZtm`Cs;DfwpZzVb2HiJQuYh)p&L#}}I}-ilrG}S-_WAeg_3Ztgi8w(g<}tEnPfYQs z#k#%iD`2ZQ_kYri{xl9?<4sL^E62r(35mxE)BBx;gsh?rY;DJ9W(<7$`od+=Hk3+h z*|XEosKH0!afYKCfC6i52gk<8*F;dn`upx8?Ry!;|g->?wC(;UI!UBNg9s%EyVe3z1*Cp|B5pn_C<_S(r-&6Lzi8zkvA1M4dbxo$|_`ua3i)YdBH9bbw3+n(edU7&Sd^0EvOMj;S< zv<_q_i;tj(@|EFoK2N9_HyQD91!sR6gTS{iFHTm*vK#g(wu=F{W(1idK8wJwzTrkB;!uv2rH z?PaUmj0HZ4ot^VKnCTII6uBp=Cu8rUOO9X$NI7obfHM| zGV28ubMW)?M|Q_F(P*BOQ0nGK>NX}7B2K$KSO0SrA4!;y_3ni;GdnxX z=Xlfgm5!&hQAgpo22fRuspqR%G;yC-+X%cc(h5?|>%aN6in3yU&G=OA?j7T=%8ZPw zhv)6q)rl-|i1w-0-0W;ATiF&GK;$+HI3QCes$`c80lt&$P2^ML$A2*Cg}OKfLMQVx zdO>oi{nkI z0+pNtb-ds#kMRi5_$uDg+xYk5aJq*+|CC0AoRWe>VDEQ8u-!yM@EROc&Qog4F%3zr zCtS*0_wL;@5HK<6F?q9GTV7e&U$A9(`FgZK-K0@ObQiFCv*qRGT|Uzh=(LfXJd?OV zR{Cjpn1@`%>!ixnWau!6IY!Q^$KF)vi7QMosv~TyWp|5S_h@T+E8uMeO>LA69cZ;@ zUIh5uTT^rVF6tMJG`Qr}fDe5_KDEd&MTLth>zSDissu8?s(Egb7y8^j@ z81Ym^dkC|7qr>_VR|1cc0y(yWS@_J1cgs)bwdN+r=N9QI`MgOyir|#}4o^}X?R0B( zq~Q0~UwZBQ5mVbN$fg^9xb4yVo4co%Dj z4Ej%qg) z)}_Xh*b%(dUUMFwEsJS$=(R+NAipU0+>7R#Ta~RxiyZBaeiC5fdUUyJgJI&8&7uf# z+hz-7(9iAd?Sd*V7suP*Sq5MzQ6Ak2+SAixT_x<&?yW#7ZvU>|jcvl*icL3&wN!6% zYbigqRTjmP*2h(Nz@h-h;CjI6@736)>UhZ7wbzxJ*UMQu*neAo%#_ z3}fTtC%$X{`clsk1DF+*rb@86pR7rZ=`s- z_D_$UmPKFm>DI8#PKoHHZwAsNyiTvgyKS#*F!#vf#Bjgp?&}y?a7$m+J8rjePd&>0 zbRO!~wr8vwj{>D&V`ynaf4cJs z=-X_n?x8$|^K>NW!z+3E^r>1VQk9^m=1mt9Q*lD6O_lD^S8bcclN4deG*JHl-f6~V zd%!*=E^eG{iprt&`7;dS01PlYL8)6Vq3L8!z(;{@YUOC#=|Ix#oei35q?UV~Y-`H{ z7)}Y21-S&c#Z|3VtDpBx8-QjJ<)b>--hMs_vN^UD_A29Qg~gO8k>mA6uk0#6D^Cy} zkTX8)4|%PYMSaZQJ34Zos+M0pvR2Odnoj$NyiE7Jh0Rv_d!q#wpWj^aS$8t0=4hD)pUdF`SdF z5@s%NEsPbHPHW**fA*se$U&u`!pQ)mzq)#Qdg4=$h<@w&BGK@tO1RrbW@3I2hxpn( zBJA|bTxb}DNq8%_a}A(3%ihb!-aKvXxMk1%)7#6IV;NyjGrYryL*3a$9k-1EiGL6d zM*w^C3JMG6CT)f!n*W}WpR9IXqxU-9H3TWMQNN)!R_qut+Vo&7JON2wFWCc6Lt6bjSNx!qdK-fz~4mF1Q*lD4QCY zN~!iVMOa8Wz5lmsw>Yz@N9jr5zrQF{Ocgp7oYrVnke4saP{}V+xW3`}8UOjSrD)Zy zk9O_68lT~umqH@%>??RyX1raziG2qyJ9A`(HOEO~@=Uk3_T-JdeMtmR8eVtep<3#_ z1WI-hRdKF>xK}{Lvejsw9tz9Dvx?j`s7tiI0X^m22NC@xD*=D|s#XiAOl2-yDeY^b zEIdafUY^jf`JGJ%t0KthN4t(!QTA07%$b(`_J$x@1u8SLu1{pNa@gu2<{iDgX#{GO zD=A}dClWbrk0Qj`T6)IR5zr4#j=qz%Zv9YToq*0`C;40|&_-}!^rlFU@`;tE|ITY& zenZC>o7*m+_c8~mLY<$_Aql2~^YZ#r1BdJxOAEx*m#oKr637B3e5w>1p_C$a=m?0V z=cw3&FMg2&`L2Zn?N!3Kfs+(9eS--F=-C0P z&JM-i)l1if7D_6rsI9Z{`koq}xZxq5J5T}t8+0LyfsblTT@ksVZrn+S#l??!u&GDarn8AUXs?s5)^6@21 z+M$T+GQ%SyDajnTf_44Ti5U33$CDccrm>5^L}bf+_e7c zkm&0Xbf?}cYz>1FC*V)w7#PQ=Iw)kzyJC$)Xl*oTB29P+HwlVNW2i;H96-ETdALLx zNR1kFUpZdI$YlAV$J<_~z=`+Oj*Ubh``cv^LcMnznOrNRtMh z#Bkn@Gj>IGh3|@HRdT2@92AoHkv$E@g7o!otgLXr%^5GWj7R_t2%Cv1DXO6U&xbyx z^e!?$Hef^D)SgD12cO*2D2Hj)*Uk%yrFcPgkWfsFp=zUk@%AuojC) z{Q^qEXg2aaHDHulP(a&}f=kYAjvvl(5PsF?UH1oQ0~ktl zn%G}o>f@oPRgGMMc{>U_pMM_SbSX$IL<>7uc6vQ^O6z1TQO3r~x2>9+v1- zcN0yqbqoN)3!hpv+=1c8ve$rp1{)*iyjno|FDkIr<4*GlJ|C5;+k?CrK)wmhj}`lV z1P4q~NfdwbX0DJ^gSym32ud-K0H8uFzhm8tFR?U~rw`}(ciNaa$5sv~r?wYx^G z`D`@Web2d@%5!iL0MQ!BO!xydZ_7O`VB7tgj&SV}HLnpafU;*xJrym6MJI;(Oke`+ zRiO5hlC)EgDWY^g-%;<KKlExSnnMi z1GjY=5uolBO-w{2#B<8T9rqo~A|S19g`Ex#4wwgb7$dBk#Vq`ULzG4f#;a~Y9L_3o zI&@;&v3>$JBY}zCGj(uTGY6vk6KArEfij6K(8&SxxP(cYgslZy%_ce1-fJ*}zGtY{ z!dzrvM>yLDxXuTaY+qIK&DulSdeT{cJXM3axX6H6!iFwHl$vV3+UqGQ^LAU+rS3(?s=Md3-F-5O5{r4t|Cd-2@_ z2&`(4OMl!-fL*;*R1D9rqUe@nW^>FzLK;}UKdrDJHLa_!*XbeRw`XUUjd%c+1jYhb zjdiDaMI42RsBvb#LkqON>+Me|JQExwaGRK2>WRo_2W5d|=6ax8qpGDY`Z@hib z#DGrc+1r{&i1s&H1k<=rpAx$d0MC=NFHr)QIJ7WnOLgke3N4e_I0eTAKdw3>5-JcKtY+=u6`Gj! z=g+e-TtrVO%vm?^RDVWq(v`R=J$)brhG~bc6#;`i`zt$pt!VQ3rB8z^s&S^b7exT< zuy}neJcd#2RNY$f#_$CO==vC={a7>=Ow!#yIJh8)Uh9u8N^nJYdn;X2#L^_ zURYRIqe(WT^no9#7_aR}CcQY)OyfQ%lnR;E3q$~3xvm9Z0kzxe^r7jlb{iSG`;qkz zzMXqK43jigi?uHkgt3S9pN={1N(j&YT`4->Wh4$gfC`XCDKka`xs^=!&Yq_j72LB!UeB+6sU4Aq;oO;JEj~2!XeZRr5 zNn=mmln+f!HE89lRhYOB!lnl7AxI{(ZI59|R^l}fWB7l_=xJ$b{R%hME_n?8e2+XV z=yKiB8&EYDk10+;4_mDph?bI;OgTu5Acm(8 zb8N|CR~`aJnCG83gckTFZdI!jI||G6NvIv&lyL$POFzQgNf%UM^V{|7y9UkP+HtU8 zvE;8IiL+%AzZ8{}`r#liZ8!jH&+>=qRu{ZGewM&zND1bK5?lisH~?mHoS3+u69_!X z-MC1Nc~9um3NQJiV1-llhxhJ;P7}TQ=cydqO!2u|%GSjtL zRHbDvF83Ou+~fAjKmGmncsoa=k5wBuuyd_iJEuTkkzi$`)PuPv;NGX=$5be$`!!=q{+kEm2WJyYU~I9 ziKP_#2&O;%@7+z2^aU((hjH&(7kYKlfg~Nac^ZZH!1ZpON<<{~(4(ka%9|S_N2fnoe+AKOu+gHjhXa%Zu!p0x7 zcGe)uJVZ*`A0b4jy=MPW&X;35v5pe;I<<>ItXMR;Y78B&{RZP-=SBYlW!)o`A;;JG z;Jd4TIrJ>rpFINtvfMyHxpwKR2Y#JPI_2OS5>_895>Q1&MOv;we+h4Upd;J$$lsLx zFJs%o;*(U-#90o~7#Fm=`Kg00vTMMweFYWwhGDR|#B}ayb*qz?X(uq^Iqo2$!(wWsOEVNcD*1Ji4Cf()-V!^=ETk!Dc?|Vh(qgw(NRX~r#0Se*y zI0*T4MmWKiEfT6azqnwa7r2o|ylS5X#C<*TM_xOaV|XVP@U`3=Fk4zwPZOJAGN`TL z!=zrmHf{?9)AyFKyU0)~A`-V29uyvVIHll;r0A_sFcl@G3J46XEqI8Yj-gMmFm7`& zf*VG47XsO3SRW$1WYHz%3nkY3lVE;w*`Hu;@yob9iB~RW1%)d9&SGZ;e3K}mvw(%j z<-MNXcE#?m1@kIls~?~;@H(ZM5P~kcSJug$7ki~XX!vX}jEC?En*eymoNjw~%;ff2 zjam*sUMEb|6%~#0?7aja$yw}30w_$}-X7~(&ypp>>qNSw-x}bxssO$tU$+4-h`@b($L6%f1 z*Ked)Qi<4G`7vK-dIgoDpUgovvkqAIg=^)|&XlJD z)jIsjQnrdf2mjBnB^)I%P$3me7HE?wGd_g@ZRHujGxU$|_xNhXcA1@colt5?!dum3 za^CcLozhH+*!TPeBi1haeJ$>R`mdkl=)%VNG;krL*quee<}9nevQq?D^pq3EXt`M| zL604T91U+9-v=nHffRp^Xn+R`GoR&SfX;I?$0&uE`w3KQ=Z-yf3X_VL@D|Xz|sqU9gG*cSGC6BoA~g z<7FX@LqLOEU8Y9w<_{pO)T257lv3tuj=#Q(kEdyPv;Q_K4MWxg5=Cp*wY3lLds!ob zC3`LjZ6)$@6DX)=hoG1J}P~r^L^xx+SJ^!i3JjPnbL>$_45h*Wk z?BEawSU!=8iV4>mbrNmu1U|H30|NBP!F%2JpH-V5o#Q-#x|RLj5xpGuJ#SBT298dT zz`9vzYOPSvS}Q&1^ed){UFlfIFk-8Y6a{H>(0g2>+=+Y6kfKHV1NHdi0vXUJn`dUw zwAIQ-<4KX1f}@XheE`N4zM5YyJbBDp$0fpyj_uob=wx-{(+1!s}Hd=@|1*`2!k2 zLl?wld36PRm8FJg+F}skjrxX$HjtGfz z1xj-cNbM%&c6e$10)@p{+}zycsQ`>9!UF<}V5rH@DC%48dsl`=$oNrzm1cIXO>iIj~^8BsEh>q(e$VX$k4>6e;N(YCt-N z?tJ(7yZ>uFU*7p3Yq=(_*w?wwIN}+@)%gxb7^rO$EH&17r(1EV?bGQ*+<;$dAkws~ z@<2LAf3wzllLcj2EerfnVELVfJXjzc z0s@MOST|C6isYYk!xZbGPN$ab>K7RP3PCGZ19`d+PMSSWQ$ajVOicW>uy98W#~Q)L zRyd~xP^)4@8*q6g!)14(q7#bfp*7s_{424Wck1<1@cqspX%2>9&B2WYp>HIC#<}rI93vYg( z5@H(tg{5K(x+HP9^kUsh_Q_kcLY*^=eq!b%2N*1DyG9cxDPF82hz`X#|AHR__wolZ z=orzi`L-A3?CRRBY09y@w&w8-+zAU2^`OJU$1TXnJNtPsBlL<2Y|l}|aoF#F1JkV~ zFn*|dj!?7MW2IFz&!I((&6Tgsse&Q>a|s?AX47(*+Bqa&{Ww)HkiJ!H4X_8Qw|xad zRX38w4NBz$ylQ8J9e;cVhU1mB5Q!p>y1EXEp(OpcgNW(61~(DAFMJ?<_^QaF zq+f33#b_4GYi=$z<@cd?IO&2|2(nBxOR_FmqV^QBJKyAbR-EzxAV?A*!)<`!%DDNm zGGRy6BOUM#trwP1S@ENSbekwN(4dq@RU4M(n~AQ{IPga;Rj+0*>3U{o8Cht9DrMwk zt;E3c2T>{mgo;}*lkRtLaPX#%U9B=B`dmMKorW7Yu&=ah4YijC50#!Oz1O#{yFZA% zfF`MbaDR;J#TNihr`^^$X=YC2_Z4kgTTHM9*8*eTIp1O{bv-x~gbY=AVR(?!Qplq* z`4Iup9-P_7p0rmMzu(PbzExj7-Y9O|EsOg$M+s_q{Z?UBBjXhi%o%W>%r%`GN%2_E znlORHP4TBnvv%G7Nj^+bPq?+UxQTr!!)~FOYs=AFu&DIF@EZU+44^+jpNB6g(nSOO zexjEKz5@334~wlv>!1S6QRH^5?P|f<$7@C~8jWiO1|#N-el;UnBa+!KkYGJc=uhPV zps2|J$I1+8IALL-tz!r6Jiyd4niMKM06pj>YWwas#IQ`S#SGROnx0NNEKZ?_1&e|& z?fzF@y1Kg0fyls5z;w^lZz?O+5fV`|H!okoCG?Lih#Q~bVm!B$3RknuPRrtm?u|u9 zb<0c3Qs)kAq5>mEFcR`lUtTtXf(`>FXwQb!CDHDwbBpOPt82oB_p#>o<|4twYdv=Hn4yZu4h-Rl$`a&6u8;)CV(bPxw3f=(zkvct-Qyy4z1Ef<; zkbM~2O6SiHfO`Rskv*hSF^m=~l1`_ZUS&}f$wn>p%ezNuGgWtKnPMD9YuhptGrQ@1 z;*_5M#Emdop8E(Jf|@*&VSNfN15gyI_OjP1r)&}L^_Khq`fZ1CF4z>FY3aIqahUjm zHgX3*9rz4ztz?#Kwf$f%v6iiL(*s96-DdbNddKydHL405|wVLn~;i$77XI3v_-GSjk< z87S`Dso>}>%REoM9)L1b0_>q#|#Z*nL|dwR|ro;f=sfs1Q}N7&fVn6Ws+Ut_Hw z?RONENXs2VD#BLhd)tVH7|(#Aqr1j>Bd>7Hs|AiM_l*Z?t#c>_=(%A(!Lfee^eKR7 z+(nhUs@fRFLN1uLW2q z@R;iXewy8REAjyScCilIM0dC3SnY>RiuE}_3cFPjV5~Y)ayL`h(e*mB|8~_OzO7yb zPQh$?C{3`+eIqO0#wQjt)4p&u330L2TiBmLY!ysmZJM=0-tYRQiwV2~%Uf_YAWL_q ze*344^m~OO=acEMNuTSJ)OX-K6cx?e5K|k~A{F1ru9g99gWJY@05B7bhDdpsnwedu zhw?UL14<5nEF?^hn-4eYHTeofLZl>6P*90MU+Wnt+3({rzJZQwPPSIv6Br}z6Y7CF zA28%8)Go6-$q9*>9o;Joy|}ngV`JmV=d_(QAsNI<3pUlWU6d9LnJQZ|AFi@n;Q*j1s8Mz=^U@lh9 zKU4Jbx^~gRUzk*eURQ|*PjFg7nV|ZmryII^Au~&7 zYPPm4N<8H&As|-9`&*tVoy&?7j>XYFQ)9m9B;eKLa?kG?Jr+$@W-Qg2G-6i}I$L8^ zweb{PMcP%Q?Txl})AxTBG%&y^aZuDAIP%+2kXAy}IGuqJ4l(pPza z10p^r;jK3P1tO^h*QOxj(^+mkOWn3R!L>j%$Q9T;1lCG=iiy6y0zw(&NA&8UK*bgE z=h~6?x8=3buZkDr%%cp4)t}s|+wyEc=I|C|4!(0I*QEdkf?cQzn2~BGQNn(QMF?Cv zV8yZk@ZRQ%^5?|!ZqXSw^%hPG9QWm;HHKnuWfuLo{RYF8_3`mMc`U%kqG@;sA2p_( z681f*$An|)a$?#2ZbYH)q?Et?ty8Li7*^wz&(+y-+%Mj>EeJIY0`TNc`%R0*F0)T) zMAPEsUd!|-V%U&-c*Bp~k8zm40$Gi@3Yt6*d9WFAG(<_U+uu4T26Xs;Th2X<6WA4- zrQ0_>pOmB6oQi`4ryqu0?8p>*Kd>rHz9od(PgncRCoARvHUUWRhOe7F6JNRCi1Y63 zshVA=o;P)_IlZ@Z^Izfuiq`72SpAV;Wl3t+!Fk#3b~o+vApQLfn@<A7m>0`G##ltCH+sp}zd(2qo6LA{6pR zJM7ohvnG#X&79l;aYLavaKbSbZplPu1`B{kHS`Jj>N2R-=8yxPUT3IgaO*Qyd;72D z!Gx#SR_ezKdKS^3)va@W;Gh5iX*Fa377`xSv}n2k>ei58Oj09y`yUalg0RJ0pgY@N*olxAk+c zj{B$rKbGb4aTl~pr|}yPrNH+#8wwfXHC>TxECC35-*^PU&kv~Bgsj~Y%xxxm#kTV& z*L^1^7yyz|@ED_@Ed=uDr2>!AX4NU8)|68@@rFYeX2EE4v`KxKWwA~-8*G!3A!oLJLa#hLYr$E;0bHmh zkcf+z_+#0gu(5EN9;mP^xVY!F3`(;rt14(iGOxn{wM34J_ZP(6vQHADo(BzgK9;06f5YHYuMYSG z0(7W&_k8nY2Eh3PG==U;PsUf>o%x@g+e4s!=v#A2>~_~P>&Qk%!)BSp8nEkj7dA%6 zv~BnVn*VI(CvJNSbsut-9)pAd7vx{qn~Ub2nt<%2;0z#<8~d{@Zi(bg7-6qYu*vw& zcFMC1#Q=lN6NE@^G7MtfdIujrRZsdoUDOB~5$7m$O<_iki>U4A(0p3y(eoXd(Hs3J zudgYcLTru;G1VGt4SmCA zCWcVSBN1@3H$C1iy3ev4b}$nf-*V7mC~nvjlPs-4l9x!bJmlEmI*cNC;W`g^*Xt*^KrMQKI`+J^4adcd}8hvJzzq*TEN~*_1OqkZ0n@^D9Xah)qMH-#?aIHGO5}Tw~ zC94NT3COs*d*=Uq1X(wCRU;=T-VE`X<{Eu^@($u@+wAA^PPZjHF#VuCz8wQ_d~8xd zV(-JF#I1F1s{5ZF(&Ikf!i!&6uuf=bY4g{^4nkQFh(r(PY_~Gfwbr2Tnh$*6-V1Z6 zmufk8h#~MoTxRhJ^_m#jPnsBhx1*()EA~vS2 zc}MCh3v~%!yVGr7MIbpDTT$VtdkQmU^k`^U0Eu83A#dg)ub4;@kN{k-#B1^(v+HW@ zH<(co_vK7Qmpb`DlI=!Z5gJN^;qGi9yDILug%z6-K@J2ALiwqq5@=dz2v3{z-aCXP zT2uczKBZ_*6%JY~ef7-6TC_ehL%)vVRF#Jij(u=) zaSi2D0+<&m7X8ZexFNSu3(k22nlL5s=I~T&1(3Lw)cV#wmz3B>e|*ijdQ|TerPZnW zmEI=&N7oR_CCc6m-%O$@`ztT?OU8UafFP{~vR>El`3Rr@`Ut8 zqy6iaStCBN^#I_{y&w5AP+vkjI+(Sop07pN*iZ?k*Zc}M&;3ZJ>J5)D7HD|K3_vjF z14*kM>@lJhi+>+(Lu1VFJ+omCTwJ&2Ej#iCwIN{q@I3m=c`ky_A|&|f(KSRMqH*^Rfcq_!NYl-C3qOYVCG$p}fTJ1I5x+r|_Qrkve z7sS~M9v*Feb5pzfzT#GJssxo)>Xx)0JD<(ql%Bm#2a=|0>1PIA5l=4!)`iX2Ghv2L zv;dpweba-@r%#I8iewY%^?&5$O#ykkZfK>%v2L*5j;Q|Gp1^^?-0%goOr58(w5?6g z&S!J}=ZZS$q&(?QTCF;pB&?D)11z$P>yvH1!H>g+<%XIFJ?a4bLE64DJ!iHFXQX8I z8mf>t%nRfWgvrYE7xnb*W*U7WT1n%BH#eWYAVfuh7i-mo ziw-Hhve7W(ExtE+6S&fREoDqW#oObc6 zYVbA;3|TJnTYWqSz2m+(=wAO)1zb#w;l8fR+|mfSSN(U$Av_hgXRp-NlakW-A*{XG znSrQS->WZra@lO|<_CM-RgWjOsv;WQb_BH-V{E|>8#WoqpDznN3nTRSq*?Ot$w&O{ zW=0AT*F^Nj>ddrXOY6(UAq_BXkCqyHD zG(@df^KJL6yF;)hArQf>4DNkVuW!!|fGQwXMw5AVb{=S;mX8Cino?mh=-*Cu&@P_2 z3)!Nj&R{aRB~$Sa|57>&ETmpK!41n%-XKMG09J3C?ws0F#C_f#ZJFDhb2GZeMKs{* z{Ffe~qJA&chTh}AqtEF8nrOc1{;%vTNh5przFS?X?t1yHvpUEd5S>#W&^Z+yQ0u<( z)CmN&$0!Kq;ZyKFb!u8e2D)Y^8hz+fkapj8O_j{? z5M4E3(4CrEwN!0nx9v=4wJb1e^85jrm{VeOQJY@exbyruNO+LOvtLseo#TLva~$h| zXL4ehW`)t4_PJ2;<>p#j2enrVC5C~SC2j!^Ljcv;73geV@nq^}lz|zv-pHPN20}5a z6zK7Q-9{bO2)XRjXj_aTbi01R?P>*0b`;RKpD2 zv-(POx@6pBrjKK~mxNJ%v@lKlX7bT`6y+@4TeM>=b791_aDmTS(m9`ff}kb0k^@SD zjGUaeh6+{JS(aJQ%nA?HkCeW$pt6r|ehZxMYM0&8Ahb)Gn+0EhcxyYs^QIFO^Lsgf z%+LK}Gi^-f0|lf}#H?ZXJ6j1`NayG#ppYY~+HZcFH0Q033OURMr(}BmM@r`AU*c?O zLoIB`X6X#Pq18S708-sppz?F&nnpewSYpRCxEa>YVoj_eSZKS(Oj0#943MjX*jSkS%=tWSae&DGy$nE!qtZ{ z2diHP8_FA^FAR%E-FPv{|U1p_c)~1(aq<+DX9R;|K>h;YQQ0j*niT*erwO6xlnd&yFJ>RG5rP=`hw}h`e|57CZ$h5F z3+@D>P5P5X+UKCts!ZexdU$!CF&P#hKZ<~-M0`aCkw48^Jgs;wZ5(>YUvB27mEvBT zClZAIwf_EBil^I?LSPOyZT{E4btPUojtDW>1J)h%rN%v2*3;!zu9lW`e$djEZvehi zR99p=6|yDBiM!h}IL6+bp#o@H=gpjZ;DP$0x|FUp8-K5B!GP)E4EI;Hu?*B`{vr55y= zy4gM@;?N4>yw1&z5jE9VpFH9-=5dpCS!%|ETL_9EF@gF-sre4+*#}Y}lZ_GKLHnfv zW1!%i@WG~b3@Hp>fS>;dIHWTtH#aX{ql*!`Z*?}X!dvE|;R{VdDf9djM`OuT_A{R< zyx6Z_r#QE5ICttu4i68*tY;`pP~ceI?RP%3LLPBA`6~39EvNgjls&!$8~PjNfq`OH z628KTAZA{}(R59`D31~!KQ6w*M*66Sl5s0;Bk4j*%yzf=ts-i6g$D85On^uuIX6{; zKL(D+8V9#N$2y4_lR_aa72Kac!3~A0fsa?bW@ctu5REbV#PB)*oGP)Z(E?mrf`M<( z!IEW75h_kgOM4;Uws-L!(4&VDsueWxe7g&720Lgkdek==`Dy?_)N97DC+_FW2eeyx z^eK!7{aIgEzXb60hjq@DS>*d0Qd!6FRZ}9lkb|Zmr4$AcpnMNVo!h0En>YU{2)RxA zkO8q!jsex{_ap=!fXUPm2o#@NZdtm5P+q8N(GN$c>{JWf{f{x->|rf!X7&|$ujmST z{y%UMZ4WH;j#8@wE!>!)N{d$TtWnDh?~ z1armNO}HI>ydxdlCqyts{d}iL)h)pToh@;^El1{g<1iXA~WJoB7+D><@b4KNeo&MEzx{m)}OF&eYM5jp&>v8M!PGr{ifFD3LlH* zI?vZ@^j@p_rw{<{8R)~ZAt;?cV28}eSEngAfQKms0#-VR%|IRqD#Ts7RG!&>)%54e zxd7~nr7=*v5T-@j0WtyW=Rl9rm|p9S=$Q)!dB7g4-N*w5)c498_xP7zUuCnk&@x1) z?`U~b5$khy1Qf{VP1`J=t@0xDc}bA*dUi!qCI zRU?M*iqDWo{#X-~A=qilJ1fqy5OfWEvqfci`@GTVtUe1E)inMR3g z*KtW{;wf(#0hEP(4!C0)f1qYB<4^_acmv%ST( zNYMB~XhSmc@>-Y=5^_;2o*BzIft{5^XNtATF2iIp!USO|VjNcrd&f%**S9EQV^tU5 z>ZJNrq8-)nd*F*grww2E>=y+jgEs?fNr9**_mNCqKLbp+Mq74hRSQ+ZW?GFmJZtTh zjjg}{uSLLjcQbt;cOTGD-UB8&39rL6V`%`QK+!_zk0RQn*%DQFP$RoYkJuxMFOZ1n zV#xkX-62q5n(&>YKBN&~bpD+UWq!7UW z#2=>HKgIiM)!u|l<`|wnRW)ln2l!gGlYQuhejO|K4A^ptHr(bdH{vE6I?cU-Ia>R4 zI5sh5VeQQC%in~*91U*w&{1hc{32E%X>y!SfeY^jcKe{(UIt`ZFV{nR)lk%FH{#R^_HcEgO z5(4<(6P*CYve4?94=M(qm!SP3=RDKjDvP&I#H3w2?QwaOs0d(*xwnKI!o2kz(SCDy zzkY<620Lify;^24)|P?VS%O-weR?&iEN-B&CA7cqG>9OS2fCPdac)fIw@dK59l(bF z4p89G1$#dqiE1gaJxd;?^a6?|=J&8BjW?SLU@3U8TK<|Q1^iARqk@!x$Dx9;x#;#z z_nw~?fUM4ofM`-a>^BWSgbDC)+Kf2-kAq4dt~p>m+=^`GIH&yaqrnfqG=3>C$yWx+ zo7n;oN69HD_%dmJ%k}>tgzo)XQw)y)`@;8>AS$tL&z#Q4uEKMY%Rl^MZX1=RD00{> zi$2a_h?wO@GH#Tt#FIQGs%*3r zkLKu%bgOpT@6J`Xem(>yHr;vT)Z*+bL=*zV62xxz()D}AzQ_tJvM==GZXR%iQE(5v zRB-#~^ICW9HvL?*kby%LlR&K3}lcQca;zP1v7Nlu!S*(q7HxQ4`Gk? z-vmg+N$FFikfw#+#&CpMoLPvKUD#Cq=&y?pQ25&F@uCCW&I0@Um^q!<$D5<$nL8kl zbIAnu7o=IC?)G8`EZgHa4Qx*r9|a7gfx_VC3ulF;d}rZOf)~!te-00N?HLcF%KbWb z=jO`X_Fs{bCPp4%Rc6s8%8o`0U324b)T_e~+8IDvbgGW!KX8J z&J8B%Eh2#3XDKYK$^tBCS%2gKSrkwZbs(e&ua1Dq1D%9~QbhCWA0VC#2Z@Nca*^2} zI#5n#tY4NZswRdw8@bK7&W48>!S}d`K4lPa<=-py~hWvYZ z8B3rNllvGv99fR>l2V20=MjLOfB|cAP4U?nY7quPL<%4W3y&1MRs8t&R%qZG5@OPv z9ov#u_(Fe*`NCHdVdYT`9`x8#Udg~{Xl$?W4GYU~5Egv)j+l7fp{gOH z0m+?c{kTzgZt56F#x-0lwA3pmmFlFVCY&@sgERZA9A8RA1q8;_S(04EpE=(H3a1#b zyjepGfg<=Am(7fgDPN7$4dWt62Dis_BqMFZ-#=*A?g0fYhIQADA=q`T&(UZIrUtN` zv}yY`mUUt&`|hwbkPBpV$q&u4isqL%LMKD^#5pT@o_!#D=gw6)Hbl<@*Z(5!%bO~# z4u5@gtRDJonCd>vbTt3X;50P;N;VZSCQEp4 zUqKtj=&RRQ2IxDgy%3uC!2oNE$-^P#=_z>t8pHXp1|nz#QwB&q4-ZentjFHC^HhC_ zYbX)0d|F(iosYz^vb=l)lv*ADJY&M=h@#{1qZ@Ys!8ifW z&CvE(!}x~Ves}Z~){t^sx`_Q-Ifo`XaC>Q^0*FY_fz)Ias0u*x%l+7H+CZI}r|uB| z@hc8O&mY23o!h^Am@eS#ES9ls^o{2W?aj9e9F4AA)Pj=)ZhRnq!ve-g=1Cdvp# ze>mnu&6afxTkyP!sHy@o$~Qj8%xZ$A*&bDSMHX%&2rVK-FkvE;20G1;-em<%0@zl+ zDu2epM~3{%aw-X%?+DY{`0P;}fT^&L{&mTK4lSa8R&6JDp{v!Zi5q!#rd+rym>t>t z&ZLJ0M{`0o4Q;h8?sG=r$Z*xI``8C~rl7Jtxmm!gf&Xdac790~3MJyfx{KmFIzINX zUu+PNzfSTw2X)w~Wyzi;=&|hX?7UDfvxCJWfG$@0;>)%EPsZ+q)6KC!S?4|5p{$&* zR`Oz?!&`)lt7IlH1RGV@Cv|#V!m6+hFluvQy$&u80|jb>=h1C`@Lo^XTWpKAJwPrJ z7XyU;BEZzLL)6cMTU^LRA*QH+y|?4!Xx*}#*SVaiK>F=BfgqCd4_QCa@N?FlES|+W zr&96az-^qJzl}laZ8S?LQ&dx@MK7>2?EN=}sB+KKan=Sy?A5B(7CfX?Ec0q$neNM> zA!q&ToQN?Eo8PFL#o`{(`WL`dd93iFiJC^(I_djOwxy?}q$`m7GWX9{ZE9@%;pO2e zT&mM>1WV;A%oxRTBSsf1%jfEq_EV+h z;1~~?sqOuOIV;NB-`Odoczt{)*%p8D2(f2YN>*P6i z>0)-i(M^rkia2nw0eXLsmk;(UVX~C25tis<10nZbeIMSEt~LGqFRWP2BX1K`Vt~^S=s%?d(2!2#uK7xxTwSBU>SjWEn=yj{dJ7@e-*;-# zY^ws$^gnJikKNb&Kr&E!1fMhEC(&K%Y32o*hd^`-DX*(I*c7#{aKjZ^B;aYrgBhXn z-bv1mOBsn3GhlttDNUjDbmedQN5p$C2+VjGIoxZ!hwAkf*j@{`{1(L+Ksr#kp@};B zp2I!0d~m7sKZ_WHR4}_UJJ^QuE)!POSwkY8(K^U*Bi+c1@N@QGPFxWZlaocz{j>DY zP62vZ21Be(uo);#)8)aj#>rEpAQ*qH0LgVOKf=cIpNS9BxY<-E`^uouK;1bPXfZ&6 z@#?hNllFIEsAuw!>2qaF#&y6O1avLKGsOGoXX?(ldof8o5Dwb!f#+`IdqGd>X5gA~ z^FLP;BrlEM|K)Nm6;1N;JEJkU6^>_MyJ+XNF_)`1Zab<%82y5mzbx8kdMl-aZQt;IVqLV^)3*m~t%w)GYkL4E zYD*|(XXo@y-Oj2h7&qa8NL=vJ*T5i4dBUC?h{H(z_tm$I;Q2-e;I}P&uLBu*po*xn z#exE^My7X=5WhJuiPqlm(lHQLKzwz(pn=96HUh*5ofiA#0n3~J_|G334e3ueWc~Nt z8H2EG_AL!Q5W)kmmX7ip0v+}IM@c&Z40v+-F7K~)rrv@}asVMV5+nA#_HD87ZUgBZ z;?4e-;N92*vNKpatyqKY! z!ldly4XW$Vs>`iG9sMoJo-r!xvtP_4dVKJEzGP$Cq5rIk*PnJC2^>7MA}u|+usEH+ zBU}8MA+#^wgw|f^7%a^J~E38{Xlq->GL{ z#^LqfC3G^-U`7)SF%xN`O`p%;xrtz?Jm>|JVx$40r0Jo{zs<0?6gVF-R_*71YbEDb zxsE(B+8n_Ut(q#`g8Qah-;aGsOXtLg2A~O|ebdWHeE$J~{EMEB^m{bC59l`ImuS$#rfSuPFP?c;cUp zFpAj^NH&zavurTK>tE5}ruY2sbdg@Z{CXO+D0sjF4SFFE-m2-9=P-Kp5v<;LB)Rm& zX&Ku#vpuWPO+COlL0o*K8@ymsq2&X2c3@+rH50izL+N*sFMx+I-{pCbOs{yaCj%jB zwH$VJl>5)b`2YykVft_E6YP0z_~*FHoQa`S`R)~wD-|bW9*`j(kd-_SXB3z=(|=Cl z2i)KT(l>p*cfUH)QdeVAymWlengzfU(s=P3vcCBZ5+SnP{_N-|E@3Osjy;h3(kn$Lso78DIyLTJeEANx=shGwup~>#DDoUO8noDU9ZIN z3-f~a4~M<7G_D^wNoIjFRfVh6ZaR0DEWZq4!v7u9M^f;KP)($PvmF^-Tj7@~MGot6 zFS?qdCw?ys7)0~_mNdSe{83fAD7QVhbo?G+-3VR@1i_|H>PzJxM+*=@pAV7>{P-KV zKSgh3$2V&Ca0Huyf^h!&C+yF#r?ZgG%7160f*Wiaet~Jd@7Pk|6=S2Y>eRQ zBfte#NyxMLL^{QAM)K^hu^VyJ7DWW!%waWKc#sj~G`;}M2N zAQ^75ecf_I8Hz1Y*?+erlLdU@5dys)`8Mh4}Z@(*s1EQOq(i|pHqkP=e_v)m>-BY zh*!0t1~)QdqkG?-vjO9P>@NlZ)aU2K@A`pzS6P z*s7%d?xTwk{O6!p>Edi*_fEt@m)pO=a zGlKQ!)`oT5ecYX%yQ^;2d>NfUtjWiZkmZj&CVnM7V{A0oOWfAGzc0FnM6B@+R#3(o*)(=T6mn+ewX zb#6?&XD_ytLVQ~5yoTdaZBcN7g9VQk1#oLmEO%W=y0I%6dVEy_Jab;XZ9@1I0#`Ic zjbOLs%j?e^As79J;yFs149u{!LS7%&%;k5HZOhxp=9sZY?%YTW8?yAiRhiHLEONF0 zVO!|2l}gkP7@*ICeN+Z`8>FyZ^CAH7eZ&Ljz|l?JW2NII@bG$YROE)7=tkC9IHv!^ z!mToftD;o1WV%u2En%DOxOD*YAdgd#r(T}!zc69Y2fpbuoA$Fqv4`AjAr~TK%4@4o z6}@^6Jx9t?*DaWo?;o_s(S_<;58);sY9?LKLtUc^yQWU9O*KOv36*2n;#k6}@9?8* zY7!u?5XXje1LE5VLutf{vfcez#?$M%`}-KnC%Nf=1P;M*k=8J^+*iw6ddGzv$y5gN z^F+K4O*JYZe~b==HYKaKSY_3;Exy+iyZ5@GIi+ZDy^S`kvHJJD;~|ExFrqqFBa?p1bZu+`gVy!Rx`JLvyWs1(X3E|xOVSD_h}vN@ zELTlcD573?VFvgI_RVVvS4@f4$UFKpmyR(1yQ==-o#hx44#g!A9uK&%IeOY|@9l%P zl2W23wo*vHuun)ONw#AAt*qJA@*Ze#VBbl1$9rKp4pm( zzRlY1$6iNB?}nOFU-?n#$$VkBmmsv~7z;YN#TIYTy!bDJLSoIkN0vBxU_`9A1MF;& zkYps}#Y^8A1blpt{0J8b9UUEs#f(q#-v#^cAH?TAS{l2!I+;4Nu(7hTvH@~2_`}M@ z$;*TI%g)Nn%Ok{ zJ8-M1yUU(3U5js>jupDh+)cJ3)^$y1usQXlHWyuv#q$W`Hk-Yvo^R`Q@Se`e>oJ^AAPAJcI4@#DN5hob}2(?Uza0vIVXk{P`3lR#Q6J>42E@Gd;ocY`^9 zqTQS7Ul}Yu9eQjp-OcGS4)Aq7nnl@oRCFIxby>`rR^J$_UgN(=>c6{cf9etTY)Ve6 zb9>Uv=lXitJ>G3q$W^|p^69mm!Wkzfw~s}_<97|LyjEL*`j(Lv~k zcFo;=IXt;Z*)(1eUv+lu>wM;kaeo;oU7SEhHJ@}CG)MnP9#eqa^mFa1JT-obRz~m5 zUS7ytaMK|1Jw)-*t8ZB6R)4uXmP+jY?E7zg$Zsx}j}oZHQ=47#{=`@vopV5rfi}*^ zCC%)h$3?){PnQf`sPmL2xi(mGxTzIA)Gy=t76FBB4HKcl_8^Wm!oE$J80Q&0w-Wcc zi+f-Dc|ulv&nw!d19*bv24?C#7ovWL%5eq}#ZoAt$G}4UrlKr95!vyFetT(%_pT)9 zI134@%%Sub^DR(rPeGonZF)Hk6#Qtf->sHZN#!lKYdrPBGJbX z4$C&%EDUj`Pt3-!Hc1IqtI*7jJDv?Tm#!iUxGMD)^o)T+TY1TT- z;m;FG$xj6eR4%1@NHGaRYO56kUhc`R&=)!f^fZ?9*qN}4cPt-KPW9%jP&gi@BX#`_ zh~se78Av}A9qWTrCH9-?i9M8CO%cLzSdrp>c>G6B;-#xjq?|-IHT%QQnZhz&G&!#u z-loik{(KiND~@I)0ZlR}v@((G%j&IGQcH6%35k~@u)^(6F!r8&jGI`vj!SjSO=^_B zPm{rh^Rnn|uQFY-CQ*W>KBnl7dZAWIM|0yBLkKh3A76D3J}OPsXw}**@q?e)$1H`L zk)rZhRX6?#%g54m^@2uM+~{G0Bo9i+RY}iTkRrad6LIK!wa=koQkk-`cOJzdpCfB@ zC9Vh3lf3BYahXw;g;b$6jwoTqI|AcUxp!S9UQH;74$papb~Bb>%Z!53*BNKA42nlZ z?>L4XA&s{dH^zAuwqhfV`-$o`jfT8++G`O_4Rs7k&R^FicHM!W>)nT9LX!0r*?IEV zKVd(3swT#-MI-Vf$;c=$?M97()s*Rwqq?+HW{>rIfiF6edgN2u2fsWMXw*wghnQc` zRRtP(um&!+f3Z&VP}FC)P$l`qI6|uEPG|NiH~2}AeQ2+EK**bF9Gz&CiU!$>iN$03 z1%Aa%8&At0JTn@6Lt&O;Q z`!#rxAJWJ7Xy}^tlD>B!KcE1$_5c6I@&s%w&MqD{rq0anwl*+gUFW&_!4FJ*ixlfrq5|O zdSA0#ed5o{QigHhsnT~N`z0<>ov+WrBX^lWaip2N(W#>BM9EBCfjdEmvS}h*xG?K? z=v+2+)e?iXNfLjo317lXN6~y{5BlKeB46hfK9fZhzYe!`IPBHDTl1{`SXlogV9m*+ z^80smKI~sxE`$~Zro6T864VXdvdjKX;Sq_V?$1#%?IiJD{UKX!WL#6_&T%TY3Z>9i zW1?bufbv_SjhH+3{rFK?$fd!)XYzRgpB@h1^f0H>oGMM9gL(=Tv#sPrc28?k2NTk% zNFCXfFLhOxHM!k;)e4g?12)Xs_bfr>#T1_&Lk8_QNi$H_XFBxu#PwzK3S353(l*(a zDkkfD8xv674Ut|7`@Bu6b25*_{z~ZJ^*w0SrhNOETfZtbeVh8Ps<&hBq)qYSuoN20 zWlfa3-Gzy#(b`Q;UyZz?H&syd6@A8F_*D}|nmu5qOr8roq!s(^9sm}JkH@#ec#rs8iu`_Xx5BLm8 z|6XC~gz*EGhQ`y;eBS-c$-q{U22vi^lR+=R!gkFFDvZjo{0xkUHmLFW=!I~QasVoI zF(a?$r7iC8ubluwS&?u77a>&Y$HdwV{=atf!|o6>_{E}E5JKr2rgoFG=G1>#_m-N>4Qd17)#UEdN*G+fp_2dhaN%cjmlt1g`x9ksJ zseiFmadGJBVs;s(zNf5>on(BoH6m6lGCbD#;zu-K9cy23GUTa#L>eYLC{ED6znqgdE;8{>2VgXUy#aq*1+|N1j zrRiedPgpeYLgjKeJbNFbCcOX0bbRaba`lbJwM+k9zPVQy%T_urUX7B#~9^XvA!?nRVx;j?Z%&NCWgj`Vgq`XIKw5Z?OGZhd%AZrt+I z-NPR`^;LIIhB-y=>tmSr$wpN3&eK{ASzFqWhV*$jWsN7lpsNPI{&v0ToH|^g@KT;- zp(H;z`;ox0q08Z(jNCTdk|kg7f>W=DcIC|w@yChoNKe)hoznx-K4E8SnJ1#3$6mGy zNL0G(J>7E18v50t)KE~W;Wk_*3;bEH^-HDojU2Wxfv|8{3VkS*XT_8fVbBNq3>Db~6wyx_?>>uCH)~7> zx+<EE4F6^*rxnve*^Z+~Zxv z({MLcPka;cMa$eEu}UkGk0z+HcoJder@j@8{C{ewZB>>09y5gJmJyV3{WOu#mOHK1 zeLG61Q(1--E&nvPhj(=)e8BKcmgj4H)lw>r8>pYnhn@Ji*ybtWnAw_nYR)Z6 z$k$gF)Bf9BMAFPhwy`cO-^Y7~DrL$npYf~Lj6}OK$(1#8D>1w#+^HWmbkVirHVyv& z8oLs3D7QC08d6CjTNrIZ$-dKOSES(%BP9)uY5Zq1W+-k6DG}xpB_=W5LDv7Rkx`^n zl;xVtKSPU)EMx1RC9>pxQ_VA$(Y^0H-}8OX_k6$KIq!SUdEay1Z=UnjTuFwWPx7V_+prq z%)^QCEvkfQJ&S5%l`3b==$4({dM>|2Q?$>Y9E}F+hk8?NeP&BUt?wE4*&vU(b?+;U z#(?3}s(9<(o{GxhZi>e&q^Ki1aB4r(>N85N7j|Z4OqWI6fCG5sQ|iaiu}5=XYo>lP ze9@K?SvklOtsFXY9{jfOkF*l+=hU>{siyrlUL{V~!M5=?)$U}m4zy>oV2%}OR9cpi znjiDe7i&)yY|4Bv{WkG-)(e)A>`hy|n@x@byQw>!-P8))pk`Dakfd%pWRq-~ml@Z^ z?Tzo@*3r;?W5Ag!Z9HZ&YV^K9<$xV(pGS6Z6}eDuEXCP!dPRu|dqTnaUhV_6!MB~&yJK8Kn#DuI$QET6S}tU}mE9^VQK9(TYTwT7k$5z` zkvTqMlH?_KFNa==SH|3!Q7kUNm|34b5~5P?SpQpD(vV^h8h^EgwPHsE|aJEoQQk1?T_X=+zsX8cGJ=gv10n`m~zrdMEmA-y&I&w zD_f$W;$s$NRR32u)swEzTKO?fu1Tt7Liz@`8}B)^bx305t4DqZbBLb&|G}n&!S^4itJyD$Bb=VU&!d*quC?bRaXybk_O;`fw~9^@Rz&{q29 z+OFOJBiikP5BFo>A<4V%c_x^|AvG^ra=q+`?6&n@^4ba%Mt(+K`770cm|U%nnhSOJwAY%kaXO}ID42VQP~r+Dgk}+>TIsQ zS)S~#;`R{k^}WU(B|9#;9@O5|UpC9gik~PyCgnX{JUT`H=-KkctMQ^i)bLzSXU`mO z7Tb+g4o(0jsp>ZTSu6w^&0o7J&lNLDpyz z7C{L5QK+!&k%ka3!p{$hK?2so6LtN_L?RML;;jI{-_{Pm^Pq3(df>dg^%RBB`eX12 z67pvj5QgH}{O5KPhT=7@03}RuIiQAz>|j>f2VCrRu?QU69~tyb%|cimE=q6x!(J^) zv7AYh8dO$h2RdkY%Pgp6*VCj;wTYTvrdPPDx~JskPWl#y>@jR(h5py#ptMSrXOVk^ zuSyn3ws||89I-d}jh;<@_sK1JopPSnGNr7hU0R(yH{)SNdEF*(SY!jFjtsuTu6Kg! z%pJ*`aK6@OzdtfH`LCDoKoP|B`;4Ohr6_F03kaBWHb zEox_=u3~%tQ$|+9O~bg_^^gY@*D_;?h|89n0%`r07G<}MDLVUN>>_Dp*bfkxxPwFa z*k-6iBLnw_6_MsqG|`@9ea3WA}pgZ`Ag{Z4LWOb<;<;wWHqiL zs(II}M-r0zhE&<;ugg(Y{pJ3boDL6W^7&8kZKvEnwWXia!B}hhZN4SR*ix@N%6U2$ zI2#Bpgi}Qa&HeAMf_#abnWCop@WyL^oU?{IkZ0!r*;uHP$O>5yutWHd5t|9td8!4p z2=4%HEfOpmizJ;PAQz(&S!Y5xRsbV#@OptjT!Bm2DKgdY69Rd!;XW{pX zR5h4g~6Fx&{R7!ah%`fNzES;c=uN1C9^m8%YPI{Q52h1mYdvv&DRD-~+&< z^K-yJ(wCPC*3&bzvHo_}H#IRZv9`B0HPsVlgZUYOh17Uwk%iR%lwRi7ns46uZkm@; z5J;_?$h-stAIH~L@Ei!lbBzK?@D^F(@aDVpgxZ2+w>MzdR4m$qVGG5FWw; zm%lvILe0#MFV$>*2w0xy`@cK*bs`AiSrQVylkuC02j%;9UQiH7p%AiVLd4J7aNz(I z^;xQ^AV4gy=Ry_>AuNJ`@o!lOLRbU=WTBbnJ274e5eOY%5gJgSPGT#0kI4YPLBPlC JMF7qQ^f%&EpRWJ_ literal 42200 zcmb5V1yo#3v#<-n-QC^Y-Q5Z9?(R--cXtm2hd^+54-6U{f(LiMgg5!l`=4{~zs}`Z zGi!Etbyam$?VjCxHi|MJpr}AVkU&6~Uzo)6K1oeUi;ERCHN{||+SmGd12pg=&s zU+)S{T@2|xY;AZ2-rfk^Or4zHRPqrs(K8Ygn%WuLn^@YJ^AW46h|_Tr3-Ckp+MAhK z8k=(ewL-~HjXGqg2z=5{gW{+t5Mk&WrUjT+in+Wv3V{FZ&6>Aw}2JDHfgIr2Y~^5!!O zgE@nVp^G7%o298c$zRX^naBTqwp{;hwkA%7?*G>jOpFY_Wrzv?(a!y^LS-iA|67&6 z)5p*Io(VVMs{|SKc@f7%0E{B zbACJjE`DbhOJlIE*8Ns&u68bb#GD)~#0>nrf0D`lPx${H{YS-n^FON)BqZef zvi7!;{pSz%?US>q%kNk^|6Yl9wAP)s*b)6s^%Kso3VaDepR9U8?I43;oP)muE$FQW zcYMOuypVK)eDx(WR-Rnk7%l^3jP;S3%d9tPRk;gP`92=d5mMB2gPApK&dOIzLMg`G zr%&Qcnyggm@Z@C*tky5VdMn;$V1NmlihWA93g=V;d?~B3=g1BRaEpA1;uZrAZ@oIC z1#QhxTgTUp8<|&MgZ#_@XHI0Q;l8@#a(7~8F)Tz$NopJvg=9Ci z^!XYyXVX(D`Fj8OKDy4m=sNhi*Qjr*d=AF_`E|kq$v`<-Ca%hZ7BXex<3&yl;((A6 zCZC)6oOQ*`vR_jD>Yhc5yLi>%A=9K(eTz1c>nl)}(#Qk(`Df%Ne zHe4|c|AAVcICcu_wOi*-qXNA7txtorF6I0N^~gh^d$Lz_|p9#t2k z4KO>X0@wxP1ePe`P9i!?iY=&3(FIqE6;`2{s3W5#8 z$W^qVHSoIE5@AL6l6+SEqcuo4xV51gOMMsB#sX2LzX&NK=h zIu%6|)Q#TY8TqMiwsy$a_kPf0utH}Kv!kMrkaS$6UqP53{LRLG$u%>Mca73{L5M4( zq4fg_Q1*2Co>v7C(pRYPhPvlWF8r@ZQ) z`7DnWxTknbxO;2<^r?^$vL3+3dEO(0{zNj;EEWr|h+a`+lZxzkIeC68pfSY3bF?3! zac-6AT@I#wl29#+q_mG7e61f1robwKk6OpIz2#<2c?x&><;yj|NHGR&AQ7G zjTnxp{*I#9U8!opkCfhHgulGCl(F*`$Oj5+{ZJ)oPwW zJ;+7NW_y$sqSFC!0mCfg(~6)OQt75eOPry7U0OIYL!rR1<}FKj8hdgh_!$1$>p?;@ zOydu3&#Z%LzZS4m$dtETjHJinUtx#MlZ#;hOlsGVlA^feE~T33l6rk<)sBQ>J*dqy zR=}gY<2c{ULZvSzxS%nLC?Rdg7C00A;t+e7k8hZ(+A+~R6jbG(rvu9)d>eioAJ`T~ z)S8OnNn=J_G0P~K@y-o^i3T!#z$#IFme4ne{!Zhg>rZknx*QCJGj%vD0{V-U-e|wW z7ei!2YQN&4nA(6bl#tZhO4ToQ$`-zvXT6}=Q=gsf62ndG^2rMTz+2*zAdZ2IxO9Aq*Cecy3{wrYAO^4D_qhhL|j5HDABlbpjFF7B7N=; z74ShJ6UzvJ`GJay7e!xx+0Gu2%_@75`POiO697Z32yy0D1O#UxFm{>U__{NH^}k=; z3wzx6WX*~zO**ai=&dfCHsS2RSFr19dpOu8Fm}IgTX{0Bi#KEb7C< z03#p#Bphx{UTnQ?+A2zyel8yv@aOvTVDU!puG5FE%M(Z>&FQY2)x5C#sB1Cn`?T2m zcsFx;-x^(cPG6a|v%8;e?Cq}O(oe4W^5OVcd9moh2v4l}vDkWD?%n(Puz-CL;Dtxu z7N+B0kE7`Fad&Of;PrbvoGVqxOH^Ran6%S(JbkWkaMRt~d}tjiUGi-{^t!Wh5$I*e z>e_beFl!|fX_(pL@PwH*5S#t(dw-Qw^ z9cOCWe^y93YQR$lj^!7KH8bXAYes1D&GHtGRT?aML>sT{>N;dn1l$?IcfgA;T%9kE zuX+Y%^7+`^aN;Tfj__*>whphQp`?V&U#xT) zJ+x%&_Taa>i7yvk6YHh!uuAgkX4Z9e1uiN~dnSOyCom|bJ-PgFS7NL6=GMJq9(23iuTXNG(q3imoFedU#?q)~(z>rrnt-hqT&Snm9gHq2M5`W~)-`BNA|Irm3 zFD#xC_w(+Ksh2X;2@$q8d{AbdH-rlx&g|&gN_LyJvsz>Fp#lu!CYBQ?;0rxUa81$V-cY|l z-Dai0zQx(d8$4%6eV$aX9EgT}Ij(s-9;`Gq?#*KXDL~O6wGMcuJ-7Gg0Wi@;&6HUQ zKle?O2J_;K7!s&o$&}qmMC)^M;a2XrU)_Nj55k5q@J@PTc5z@RxMUD+i ziL7nf*vvFSxWGFWPigi^GK?8m`a9daSU@ywvAmd__0^-7hR!dX#ErxrcLc2;JuD;b zC2s95M31Sq(rVe3A2^(`C#hKb(-^szp$~RHYZ{GA2VWu2n`;xX;gw0C%*beDOQ_&D z9yvB3BA~2Feu;8ZXi{IV?6kZWIUhlBzGj_E?!DiC3ers!-r z8{6hlco(Ky85`0uv=B^PVmx(6pmxbCtJsc99Lmq;K(Bs@Ns(QRX#H5gb3F#d_^{;A z!p-7~3p)f;mT2}m>zeN&KwxB)QUiTRbGqpbp=Bmd+T;RedOZXv>}N)Bx~0R6K`i1(VTX*I~QF)$2 zc|5n$H0K{FJRl70X4Ng8Mop}4H#Sp%0GFQyey_|N4jJYA3 z)ZKn|Xuip)N&?%9nkLb?VC|t#@x59#U}}#N$=V@PR=qY|s#h=}VDZCTiLKY$n`y~T z<35)9I=yWHBzACmLHBi9?g^4ut3PkE)BlHCPZ}NuYS{H1zQWeRARsI29+KupVcIIb zt5!(;IBPt&9g6`-Z|nYUL1_nSg~0 zXV+bnPcYG$E(EC~tb^O+O2ywp3$jSFh%yE4OD;^vhEa__9w0(4-&fvNX~fL7XU3d=q>5PR z->s42@2$2R|40h^yvtU~{BAAq;5~rCT>x~{%B_bs zl=sYpixcHHXW&3Rdt!TiJA!%g8Sa7kgGb4z#Q8&q_Qq*dIXH%N&>T(5;And0)>spl z0fY8*?wrC4lX8`As)F*y$X`^9tV6O!g8F7W%_< zI3s0KG-S{pijWKyFEEk7{~-P*pTsL3Jk8QesFlw}-H+XmEnyzR{-v}Zo6k4~R~;7X zg^Zu*9Zw>D#|DW}uyd$7@OK8MHG|xQTL|aN@^r-hE2ITEihnZ{uF$%HlBweN#YdP% z1UV1!jdt3+?>?6@J1F&kvZ$A;V8Q)Rav{|TKzWxy%)`x6u=w`Y1hw=hrwn5htQk3X z!G9=*;V)=8NgJbR81@#p`&o}6Q6RR~#XXb%c zAcH>Fp%^0mft46GvsC`yfwCZe07C+w{!k)=WQ}Nzo5N<&dJk479!q19;J$_OMpD`i zN~WFPTm4iDz2oRIpD(q8(T~jv760zs&tMq0I>Z->?Ag;>r8^-1v) zB~$g^Ds1LAqIXmE5p7WeiAHC}5r|RWNX8&V&Ghzb2^N+iz6nyK_ogPIi@3Y41D6x* zQkl<>v3=~tHVKW#x|ly?KL*=UM?FePhU4rIt5N>GFgxK2eW|B~~j-HSq)=nn^hikxy`|2hs55hWUlV;`5N0gS*h#De3$$sI&KX!a*fDvR&*=i3CuYYwNLR=O90Z`cNHu?v1+rt&LAckOdY@Nu zcB8a`f!CV@PFm{aE96$kl?yk=f27K-A1I9VZ74b56^-%35&sYkW+)R{>w5Nmx-_^O zvz^a#Oa!+?QEJHtABjQq9|gDEPT&P;8&WoR)`IhwN7?!fVRrTS{PoXOG>+5gIU!b2A)SeTeoUeME zF3@Q*Xeacs8j7`RG1BHAxMPu^%?I|yDdjqV@9P^$3^b#An%G22*PgA;tD}aJj;2Wo zI;9yPdh-O}L(ej|kEU6DLwcUKR}HFGc;!N)N@qdhHetWZ4pI)vRiYhUuvnmX<*^Dtcw(Vh{*G?{u}c#v`D#)=hy$VmIZnEtcc1D7E* zpIiW8V=XU@Kc5=AgMbdb%+vVJ%qi+Ri*F-s^Gnaq8%u{M`MRqYM3fw%kj__;UC)YJ zt#u4NYqS9B4u(aZBF%VNd15hfeZHED$%X``c#d3NxxC$ba8ElY)oRl z?c9wvU2_>W0GmuFXZB?vG_Q{XU}Fo~BI`pvcrN3%$Qt@uG(p#B*UDwHbMsCbc~$ZK z4>~cl%zH=0O3qUICPfh4-(0#=277SF3#XwKS>keHPKJuIB5~%QTj8bVF=(f$dFg%N z`;Jb=wpT5fHKO5bze?L>iCc-H+uwY|9*fAOm`R*in-8@#wwYb=DXUVFx93j4Y+CxF zi;c5$=8d55(Wcv(r>O@ods?zlvqc!vL;cONEro&uk@lv-pXbsc<)>@w14k`_l&<~f zYI7X0qbp8mG#S;##=uM`b%}Cctp`?#v@1|RI(v4;!p)@SoO|)1eth|<W1n9B-(oMF&{}^y&#OR3(FnSg}gzHp#_g)XXT8=XSkhff#P6WPs!*q*}~Di&B#7 z6_U3No8>qZZDu0D&FqbA3ZmXdU6cL3F=Lj@_BBUUHfHu;#H*&E=Dm2ehk+5Y6v7EScAFgjNSfvb&s$?yrOZT}3 z#TCglp(}|qlGw`R*v>E=oTZmLvo~$dU*B#t-J+>jav~F#LE{yj1@y)yA5R9j$|hAy z#IV9@MKq#Ho$6?=laF+Xu>@r9YpNAFh0XK@%f>|yy~dT(}hG|t;0j(k%>8Z ze1-<2xuL`eK*Ntxy~;!52=1);r`Za8Us^{aKxUp-M0p$;J8whNY?kDgi!{IWu-+4v z6!zICfCvAS?)31py5E+v(Qt~^X`FRo7Yj`II)x&%3qqfd+sThtMLAjh;Hz~GL zO|s+s$K1Ju^>l9e8g6;2BVYBQ5jKm$CL{Cf16kERFz+(&64+5UtzONV#ml<(GbJ9& z_V2ws1Y7?28sZ$JgC1gTt`Gixtq`#Cw-~THiUB)r zK?h$vJUD<3p8Q{@UOQ3^cZqPMPGC(dGeLeOErl^4oS|1Vt+e)PcCsbEl%5?f>zT!= zqd|07c_}~+4hh8Beg2AM$BgEd2W{@4UHsTHvNHI^;%?2Qy%~kP$o^vej^^D4Z4n$aWG9F}7h|1-sI&8w;B*51K&+BNVACVTEm=Sy0x>mo_|zyZ0@mxt%Qo?j0D1NO+Z z@lf}-+da)5nKARr&3>8^Q`H3bUJ@-_tzu_F1H(Tac!a(qP*yI9d`{$eyMxC2)tM>R z$EW=jSwC)fdwFCA;p?Oqv_80d_wl}*7j6oTE6;X@FTiPZcUy5KbL&lP%=*U8^>Cg)#FeJqj*wVj|pdMti1#vY})9CZ1%{L z_u=Z1%1)Y~PST+-RUqy3l~W`C(ve*Y_7uN#TWYZ@m!)YZkl`L?X0~X_0x0IT4F~J_ zM7+lz?scI}*WVMj0Oi8c32%GwDrn@`tA^WR?tH?7H7E;>g2&?Tp$#?6s@SaT;N>DelFbQbGR=;%;2s{_%FlzI{LJ+8o1fgEHAa?&a8utoJpA zoX9+^d&0|GWIs{i76do_2wuYzgkkNh>+62k)KJp;(+N2L)2`!FB+tzR$1(wNBtpOs z@mF0Z5`9gQiJL6bbF*={*S+=CaEnLZa*uVRhs6zc-F7;YoS`;*)&U#<=@q#9k5LX# zA^WZg)sBtHHXk`Q_qAaeUy2mj8}a?sg7YCx*GirCY7pRWBqNA0Qp)qF` zOzomOXV`u=KaXCUm(0tcse^kLQj!T3tj~^HO=4E<(OH6yKl5=TlAg`g`@Q!$}T(aF2 zA;D*C^4`WWLFgLqChwlgyp&oG2CrjvNg%@A^X4(m2vpZ!(x5q} zfI02A9@q3=;e~|O^gv!;6p8~-0{@`~DSHPg+ckK@6EFKw9`R}7mH;sqvIpv&Dcl}= zm@b9XY@Kv|V#=Z5`b;QwDD^2+b%oryXphV>D|DzM`Y-pwiYds2P^wU>3=pbuxrlIO zR!&gUAEI?f!|)aPSqrEO4nqnLr!NbDRc+}Bv`7nsT=ttzshl&I)1dO8@}|)9teMju zw;S1p&X#T)y*x%&7mUI=xbG?F6tRJiqjLI}Im_qzdK>7~`E(|?{Nh~J zoe9p$S%GE{6b@dqI4(%apU0nZEN+mXn-8IYnaVkklA;DJ1J66dEqSzGI$xI~>+w8E zZ^rTEN56AhlB%ElnQ&Zq)hSevM!iU_WkqiP8(LO(X0@xPVi3qZ*Dk z)+JW(eUUo+y~|QAw&o)g4o4OfOods6-f-m3ER&HLaMX&3v#qa{E%c$HNFigk;m|yK zi8Sp+ThPO#YrJGX1#*VE9h91k-V`?Sp>vAZmc_PZ9Tww?ldofr#NII_O_5U&65+)p zvhB~nw8DqF%O`;l@a?xPwl$IaDc6sdOoal~v!P>RbU=d9m!w0xAwz;r)8kTUViU|! z$5h9z2w7@`;pc=xh0lXm0&(V2Wdyu#VMJhw;#?UR*Am?vR)HH=+{DgIJF`a3Ipja# zG+5zk%|_PDj&kf`q&X6*47L9K$6h=R@kI-I?GK2=~5KthT(0#2X9x<;xM# z*GW6@qT(5prA@>|&OgnFRmk4x&`_z;mvrJNuNQ5L^k|7+V&(3J*<&fQLat&^S{FS6 zrzNs%`HmhQ5})u!UDvS2k+3C;E{HBATExKoF0+9kmMWKMLsnL#JmQtTM#p)e#V!eZ zbP9qU3?3Dp^9cz;7iknLOOJLBR$844`_|h|9u5tvc~ne(OQEMFT(vm(d%_Kpg$pw? z{|t8L>?3CG#&?3=%_Zjf-a%ogCvGGekoAhHm`z}<0r4Sx{>!VhB=~Z&7}YbGK6Q!8 z5}soIu{I<=RWXs`pIlz`I(r8r?(D9i`w{Pak@2$H-du=aL&Nv8_n3t1wShGf zBScNxu*R&x0nH31EmxO@UrTlO4~D$=A&QyrJOnCg?J2g7jI!YsHORFeKz?qjRura` zduKIHbDmF|ERxKsMI4o92V1Fe3;8-=n>;E?bq6=tv<@B>1EJT7q|BdS{l$-!TZ^_O zX1UTi^mG*Z5%7p0di)Q3`8Su)x_9s*82&i=ai57CnA$!U5cQ9qB_}89Ko9J9v$D*6Ll$3&gRW;PxxT1 zU(@N2#SFQHwcl8l5n7%Aol>P3CUAx7U)f>r<8!bqKj;$)lo}{Hcb;g+3^aUa^J}nS zN|2!|C?|s1h1~e@egWSMnlFAG4>}pW0vD_6r#MI^n;E@OCX`c&s()E2}QIwg&|S6E#j43>CP!Z@_x4)>Uj6*Z%Z@Qy1e;MUE*4@H;%y;~nm8cjb^Gp&a9o@0XtlX0< z#<**Q1J>ZuE}k2=nzTGWenx@D5QMeU?i;(_bxNQb*Q4cVbK!!!>j`oCC2uj9$MvMP zmPS|J=)uhnr)JFKKbv7m*tSuXxAt_GkRJKY;gKPA#$A;x*?8h;dAhXPd4kob#7xaS zq@SC(R3#P}RNi*+^`;&V7rG=>7lsi;K|wqTS_grwcrumPtmqrFFjj}qftvV%nhS_4 zV!5+n0|w`;6tLv)baKM(da|XvSAoOK2N>^)T=jW$N-}X0Ba*+v4}oZx$z^;=*v`XZ zserhvD~pM_p*KIh4kQN^_zw(_fnxlkRBl6*x4{NW*q{6{6~z16dTfNwWZqeZxZ{&g zPHdC?AQ%3zTqk~pTzKcg^2y0I!<5cRNjisSGL-b|7nY+jxzDxnK3^mCol0?|nvJ6Q ztjQO3$3u+ZjMARt=jYQ;a%ak;ZssLv6lcE3E*f41?#l-vCd=7$Ss5lTwMUwjw81%MeS)mNnPz@Vy?DSO^VIVl!4kokl5 z2kkkq#ZJ!$-1%pq{v4EftgY2&&KfZ*+>K~Az8ts_!F3x%j9G*SF z-THGGfW>@_u#%F@KY0v%$OFIA*8yMlb@{A@$m8Sky}i9wGJ5i1KUh9`gR7K$1u4)b z#g03RX6@j!b4D*VM~))yvkSg?wMJiF3KBAZgPS$JstH#>gy@%Q(A`_qbhD{mnh1hP z2?N?T4PPG5Dk>9%0Ly{a_%uEZJ@WH;bFy!#!&)ZvBXH6#ISY|CbU~k)x8Y38@*@)r z_E{D}`GyFEpZceytePQ;s`KzWYZkF(5g8&UoYxgCcxb~?oK44Pwn2|6iYP$_cZ0G-K&K`s+`JZ@84{-3A?t_KyTI;X zHm-ySW%PjRW6kSJG#W889LeZ=LZ-609K$C~NY_#vxvnEM1Is0k50sZ<`v7}%? z7;rJF0z!(>Y)sSYXmX;;|DW>+7%cfvc7U3iG$$6rRSX z9%h%%#*euaab&6Gf$7E{XM1@s3EA#kF8qc<5tLvbSPv%>q#GEQ_?vZ$y%qaAiEX8k ztRuE~ZST-7zr!d9VwC{XeKf2t@y0x_HdzBZAN{Nh*I(f%-URP7H+3E{=q6RpJN?Tb z-Q+uIPLD}YM}*!k=~#Vp%^_l~A&5meJ# z9d1_T-PJEgj3rJ4$Hw5QieExy8>y(pcQX~hm|^=bMNBTgmV;Rk%gcCtW1qAWhrQPy zd6j-yc)8biCoHN|_+T9vJwC?FY6hM5ecu-!r{%k@;Wly;bhv6SNxLT)ZOf2o);iT_ zJ2#J|^uUx{=6%fCqv*CYatz8JFv2Cc3eQQTlPuarurUHHvj5O7$lHq?L!gu?x{Wu} z3=rM^3)t3qw8c~S3@P?${2)gL?%#INZ5j(!(QS!j@@WrsR`?Zi+G)-|G>?lEq5kO# zW1WQkPlrc<2PXx#Kp|_yAWyO5PWWKNA7J{6$foa*N~BoVh+;5E(ErOwgz9fayIcT| z+^M+6z}ULS>inR?M1GI4?Q%93{ zW=Z(d?fT2q`iu7|Y0+wDVnUUg-b0_kx8^8(@TR0`Bi?AigVrwoL<^JW`7dp^yC@NA zC1mGOg*~ceE_PdCGPB==T)VaIDZfs=U7|5J$E_)tM+G%utq1(NwstIE!PlnQsdQ+z z<#Ds5`DT2JlXkS%i#>IK>`WhZ4*@Cvwv&E-bRR#c=D_lJ-{kvnuEdN@dELPcpEJ6xKK32ivgllZ8f!;`3K1>UO-y z&?EUQ58NDH`#*QZ)VQhFth*%|cOLp3^{p*U58yf{SeT8(lZ#}+S~3@R*@?6!qroli zPflDM)iG9a?2%7&di6z7?e=f|WvAG}=v+QTiq@|I*7?5z;3Usl=TX{AiY}lP$W_Pr z2M;c?OpW%BhR9I_G+o(}e`(J~k|SOF!Z?-Dk8`5`og5I)fFZZe08sok&iZsP5l6r? z0;yAQ`cUhhslY^{n0P2sj_`%Q_#yuAqqI>{@q-K1xU-tC*U;8|wBWy7K*ss&f;i#7 zT!@JI;{qK?yhipP+Ozw`Y2RFk7>G+jk|dS?gPyz*3G%5*`kw3-Ln0Do@+uFBV&gcZ z&!sPi3~2S5z3(E=KxsN+ndBwWL>McK=J+WIL-U~j#Kcz;{^YoIQ{?f zH3jisaeDLhPn|ZpMO1RmB}gKhQSp#ph_bSbn7FhuScM~*!TS8=-m@K7CE|o!QTAz$=A(`<@Ieo8E_9k}Vk}LIZLHBR%Gzk7JXKxR+Kl)H z+ggY^=(W=o(aUywz!kO?+boC4f1lL{pk05uJO9o*mP2jyyn)7J`kDD2l_ud_WPr>Q zF%4nr$!ry7lsF)^OV`BVC9bGv%ku4a0Ju+aZ~JPibKPLO@^nXoZOQ6QkSFrhWS5UK za#QLYY>l5_S8bA5yQ~tQrrG_Hva*BOG$@2KDho?cNSu0HGxno1U4byiDi-|xZq<0m z+6Fhm&TZIp2HXKlcMAt5OwD1rEX{dw7o~X;Z;w1`@Gg-&?aG%2m>8~~0`L!jRG(~wa=+Kh?c$nyk5u>ab?4X)40 z%b5i~Ht=Z|>E+4o3=|Dm31K^nYSs$Q{9t5g=#k<4+Je6`r~eaO(cFPLoRmbQ*8Gxf zUy!cl*!Y%Ms0OD(^LR_7SZ|R2%Z$!IZ*4zSb!CIHhJuCs8*4JGZ;Nd&UA9BQJ9R_N z!`6mMCLO3=a{!pI>vSp&Wv9N&;4idhnf*JAD9|SI8NB0`Pkqbo)B5E3$rAtVrwa?8 z3nCQm-{b*vM^&A*g9OkNdC7pv6SSHeD3Bp_kZV`vyIMcwmI!zVsVEj9pf-*sM`lWwKRF zP1!%D7nZAYhm{LM3eVw|YmpLG5f-+ zk{#J(&V}TcH^`I!kld_P5l*U>E|V_v8Z0ZfR#IgbRHf4i*;Z}-Q0|o`p}Op(7SinX zeDkcpT2zQ#kdg}3r0iAQPV7Ve#t9k!f^7I{+^HG?zqSigT#cCfSQPeXnTinTWE~xct?corwADV_3xY6>cQpJ=&EfO1(`*6imxhrBDR;` zPX*d3hG@CWpst{Pnv zGuP@wV}~;pdON3=%npS?i&XzpXA(`=SGQ2p4I`ORs!vUov&s~qyb>iP&wKTi8l&VF ziuNjv*T?O`c=!3c+Gk)B-(TLhtV+2Wx|vl1^p;T!f&M5mF^XLHiB|SizbS;zBbcIznW+`OR-O_%YVGm!=;1W4VgRp$fD^%7qC3MVU1Ps ztzFG9C^d}ie5v*~yd``TU>Ssdt6T+__j=;7;^?Iap#cx8_*)kh@Pau<0vo>2`t zhKCoX{HLuq?FmP%{PV>Zb>wqn8Ym|girKi|j|`IHBWOI8)f@N0Fw$1cAGDOeGnUjWPxd~VfuGUJ0+o2TEDj|hco%oT;k;`+b%5MPov$Si$ zK;u(y8>_bu_PY!WYpAFv&aoUwJ1Bq1BVTigjb5i*105f}8W_mhs0u#RZ;wzvu1t$t zO>Tm8q=4mcR8rcMH7s)y&ylLAJf4RXO7Z|ehs=lZMRPdjm0d=12rXapdVGuwzUmq+ zp)%p0Hb=Mrp}WHp!EqjWANoH$HEM^t3(8giQz6?!`CY^J`Bnls3UJ$UK;3)0zE+s_ zfe^ZHG6297_nK(3!XNxIJpfqDeqTLMp!YAfAU_@<&hdJpdE1hpPAR ze&%vuD&q8?|gYbyCi(-zxyIp?E^i>(C{8g1+N;6wO-QGL}0p^lQ z?UB5#;3}UnFP~9=gu8^1K(o{&CpXTu6-Ct(MupD;OGJua;Nt#05lnB1*jsSG67lqt z?+P8m9F2m#?6G#m+WmO_xbN0~S7Hhqaq$<0uhE;oXK4z%Ll%0!QAJNOPBFerRG$B8hK&bD~1Dwhq#NP8+>2LMX6P!rojBG>xIP&?Mtv20zw%0bL={#FuGam zJw3KiBl2q4fCYP|cz{(`C;PB$oXs3~eH6Q3)vqf##h)Mzq||Ud?3=bJ7E@y}JAiPl zgxB4-ivf618 zmLz4eSTm8|PpB?^3T_ka->jH%&X?d1CcaBG{6%bMY)AaXh=^pun85MvYlBv$c&WZy zT)AIZVsywr)Gz|!mXr2;lgRGlr?f>4MxRKNJJiW@a$2Oip9xNv8sQFv8wSnX2x7dc z(2+*;!V$1!X9H(&%v;#jA!OtqKQx-w1>3XVBNIrg^cUzE&^%}au&Pi_YkX`L?^!tF z!r!ojDh;dP@gdcrM0T!Z&JANoanK72MULEPk3m(KTD}5WhZN}Bentd?SSKSxxAd?N ztsiJB=L1=&FZEL`~!GJfDzL6 z9Xb#w0ML@WN9RWyRNtF6tiTvPVFYhGtc4nXYuD>`$85K7_1;w6F38!Ih#FHeAmT~9NHGj2xy0Tydq#|z37EYghZ#VE<<1Mjy_YGw7iRYD zVX)J{NmOpUT((WxWD6hME14K~D-ReJ1c>j;8&c@iLkzuk5NuZ-98LEhaM{mHFxBo( zvZl_UX?;S4s2!R&qr9G~5KGSdED(dM2(d!I_)!-X4Qi1U5v?e7DIuHERRadNAJ1sx z7_!m31@7!nzreB$>l6xu2?N8ZpE-y%L(23P1dDGks-77|Y+&bF^?jUpaPdMU4e$G) z1r%&uH>oH?E7U%QR%Q=!P}P>Mt>!2!N?oLXXja>fp1I^CK4+c>5Gj}&<3$6#@qAt42lV3 zauP&gAE^2cikc>r5)s#e-yks?=P5j$7dHI3x5(5>;YOo72=OBpv)n$3Mm+pMx32Vr zXFk!d6RUm9a4@AMV}jrZsj#Xc;_b~ZjEp5=nc9M^yL^d1YfQBv(ISlx(G8YyKWkb* zWPYk0wX}`Q1XC9e_y#0!5g8(l+Fq`zWrWdWD8&olkZ$ErLjlM)ACsHPfG~@V+I#66 zL$A=$p=av}O`%bsQ)M@M&qHBsICq7{fSQGBIgmDxeP-{F^g$AM`Mv?)A-l|{ zFi9WqN$T-Iw`%82J|GeS>W)IXDWD*+Bx;qx6(3W876ALT5I_csPa-o24rLN?(?|Bu z=X|yZF<3hclWiN`3-(I_4IE1dLPImKS;}zL)_~6d{H+kWMFLhg+9A6Uz5{zS_j_VE zteHqZA>WyPiUkT&-1u;Iq)4bNDbc+k(;bFDFIWjzR+9=wk1DCc8w0Ei;N(RD=dw!2 z*Necx{DOPMw||yj*liw*P3A;*)!P?pHx?~~X@zFTMCT5xS0%KKq09nD?rM0Z#gLq; z(*rT2Yk1YGjYH9*#CYiVwPu)9){Blc9Bdp4QzfMcqZ2Nfy%DQT0|*bIK?MRbf}5|< ztr@Z>yFd-EK})FQzEj`VcaxR4@9LLFv#7d^Bt zWxZsLGuj{#C4P4p=DE<@|H#BGN@*!wBsxM=X&fw%6EnI8(wKvCd@2(IWlv>7*voLM z-oFI}k%y@$+4_!@k7Qd|0OH+k5DmP9y(}M?0(#tKDH`>IgP_--y8wuqei$E$y&HFM z*rBqZ0GwH3P;5@=Ep&q@>5lN)AlJxv^b$Bsn7+)crWQsvWO$nRl{8@nHbI-9c!EbQ zKYMPNJ=mj-BewO5N$_m*3`B|twQ$9qt-QgC6tEjQl<`O?JKQueGRoJ^;Ccu@Xd_+A zg*~Ifee?iGiog*UBNBRhAaA%9Z#q)9Lkum5!|8$Yptufp3uz!D;(Y>7*AKuZ1Ccl| z$SHWiclqW31D*ekLhZ4@+BN8*y2U&9i)?a@q?B8v{Xv#PE*D7I7trqDruq%7T4_!} z%$-Wd#RWkSL~!Wr6lp958@XGMkPliyHV=8I0f;^9624rjglLJZtaw`J-%Dw)c!IR> z4_Afw!oNcgiH8U?nu85>(+4r{iy@zK7(^3qgHYy!BdiV@c6G189FHiXNceuR1&!bX z<$-d_5e^(mq9sf=0M8#1!PpL$$t5WJ(P+t^a8}+ClDszOqlR-Jysc>sjS5s{0_4W2 z{HaeAF@^IJ&h{r@-cJ%aABK=9k|!Go@=+R~P(+Yc_=G5cD#r4|gO~_0VQyeVs0D8Z z#o>Nnu|mhHz>PLvK(c=l!!Tv;%pG4Yw9*vEY$UX}aoA2)+NO*N6y8kGY z13d!j@(nT*8WBsYt)#{T62y05{2yK%Ykb_om{BHc|ZoR@rnm6-3t3h(8a)?z98Bl z9dWh-&N$I~RMFavdK^;)M9Cw92u2Ez=x{U1ip^p{#wZn&j}LLn!nr+Q0rt?}KZXBo8`>Sa>+o z2u5pwKezFaBZWZsN#J&st=|ZNl~-cjeY+U+aZ`Hx`eJSW7?uy683W@d5R2O4$PJ#C zwk1oJGRSE+9^4v9K*ABjyAsw>R`?rl;O17OJ0!V6B9CxvB&4e-inkB!EzA zdPv*QgJcnyrck95MB9v@=|E5)O%V@vOQfxr)cT=7v^m?Jv6*LqqacWp(j~OOG)(ST zsIAYf9=-}8LL{fa7-}t;=}H^(SKB@{r=pZSTd-*_wazVhv4w4kq9JFr?y(YpKH5N# z!NWRV#`1oK#~ut)7-zdjPpWCBB3}_*XMNm+Gr8^>GPMFJ`T_Tfi#K^VWRq4q)(Wje zgfJQ%m%xaxej4)w9>ml><9<*QJ8sqlryRtPS$G&zcI*tJn&NqoHDC&Q%9bB~+rape z(W?3Xq3RugEQhwR?Y3?AwC$d@ZEIT7wr$(CF>TwnZQHiKp1Jq_|M%5X=Ts`$*-6em zl}grH@4KP5k};cg*TIM|7)UNG3FrHR*Jfj}_$Xl(bc~A~Vi<7*B#L%?bq4nUgdQPw zd>up8A`LLxYfL{11EUKf4i+jd^BT`}fCr5fy40XqAU(A~I z42UvBhe)EhDv~Qblq{>!P43lcGCxxN8m=}2cFGRRfXmVA31DOcdl2Q~^yE-?sN|}U zd<$o^MYFjZlSPXSj`O*unHCr6k!wfWE60&mVYGbkjYu%Gb$+L}-y9%=CY&*ou0lkz z(};D#ZHv1>kEY2v4x&F|U9bS7mn_4#z@{-oNSa6)j5){^I^E%Dph@G_hvpg+)^sO= zDN*+uqjSiH7>sOp^Gk>A5PY)<-jiGn)IUG8x1{c&>#kEq@Zlg9gBHtObhjLH>>sDb6FmBFz|;6a=u!wo ziALJu=~+W4oTwr7jKC1hm^n}kGY6qa{i=sSAfP8jT9*(3S5>-ZFVsf}UN&v5Wkl6V zwX|o{Q3YFAW-=|H-$eN(MrD-9Z{8g=9x+Tht`|jfZ$$rNc4E5>hFu6f+ZHUB$Ttvx z^cB&UKww;?+^>h4ue?{l!ouQ;nOKinASYaLCpd@XUK{@%VjVnF*hfakKQ5X>G9V0& z1rbaY(FlhnO*CA$q}LAqhWJ;hVNxpbm0PbCY6dgWAssmRaWfM` zlTN)`AHX@F2vd5D-VE(-wm&3?@M;u2adr#1eZA8^Dd!lNw|xQi0(K!ZAnu@ZJc*-> z!fCm)N?(tQMfC)-k+I%=G>RGY_Ms9Djv=5P!~!SJwqLZc;-}G>;r0+TpeHc`!najn zKKbXJxPAOY$@#d`{0U5n`rsCb*6LAY?~UNMr6f(e$_n`;gESfd+~txqeS7uyL9qfc zu_IiGzKc4f48c3rZel; z+dG)?K~lo^u%Q&E=Rpk#miq5YrppZwa81oI0I%YArwb1Yr1VY0ck|?^Lu7<7(_-(c zvk?v`u=61UN&C#_1|@_iz>tas#L8mi%khuD>f{MO*J){_LLG6!-1&27=!7%CHb<>y zz(ZDI>@kC_F0fTG?>Xj=<~02>OyF{`UfC{@A@bx>LoHr>?pEy~1%~D9&eN(xkLcNM z4N@Q$lp0ZhI|sxDBITd?&7S6;g#LcOS4_H{*QZM&x5tRV1p~=U{Rk%wuC(m8R^D0S zv@gk;$)?O}UFy4Jv8GP1Knie}S|FmesmI0jWu8ShKr%#*#G3Q!Yt=MLm-C{){5$MW z(s1(8uycNL!AN7`!p0DpK=nJur|=!)18P7KSb!;22Q$M_o9OL^C*t}SU^;!tGsBL? z0kf6FYthsVD^-8SDfP>gDNYkqHpLAY5%Yy4{$Gr5vRIwhTAjs5S*sz;`i~7{+2(=n zf>E**#S}V-&=ya&oMy-8^$z^ccuC0o|1Z`TK>E!kiNKPJwX>V~8G2*DW#=zk%}NgM z9UIBl`6$N#b~>7o%XaJF1DnsjN?|lOkMlhpwlJRc=-{95ycra30gv?-3_ILAAHTLe zn~rJkjypB9wn8rlGO=6vpLnAWzx7PB+?`)Lt~S|^cz(|Rc#`yUP7HQlz}x(g-~Ono zyD_O<2I{lK`vfcAbGoH3U9$=Ok@b&HE&}Z%0_~Q9g+7=Hl(at!Xs!V$-W`&1(9UkH|llI1Y+Kf2~XRtUzTAH>40SEnt#TDZA# zEu(u}vK61UllLu0oY#Ihl3fyn8|@+vDlM8udDu0#{{5}Na%~ESsyfPS=k&$}M24T=67?OreRI+?pK{<@INCK1 zlSJxT;7(`cbs3Weeb686hKqZY@rz}>DglIsvk*^T^WT|cc;Nk~vF{v+3|aWf z{il}_vM#X&>3^vlFv{#PS^;F~O3%Z5N*>W;Zo|~PM-lHe{N~`U=U_E+(e*>1u+9FA zy4z@=_S~p04i6|nyjGI$CBW73814M^^dWu6284qS;MwthrwIQGViFU-yk?`={&h@kL z%rNY)wb%sfnOKzj)G*5nC|t-VsqNG#kT|{CiDCC>ZgTYjJrS&qY;Q^RD%AiM$lJ=oUhV=L|hyb_DvfK2#*HP7MBaf2dQYpO*xEkdoO zT5J*=A+@fj^c4;WxLu+a;hXE<6>xh48-gGToq`%3&yv&P4yvUZs!Wi|UNi`f0S$bM zVG^80{!xAw(e#QQ3u@@+Lpi1a{bBuKM}1+LJ?>sKF%P=IuDG~8Z?P)3Z+#vNUd{LI z)&kDoJTVD8p{Ju2A@w*(him+y#E`H2FD@v0MSG;cMNJmpeQ*%{cck;bpr;+)Y zjn)+1-TEs?XX7=n4{izYQp^)VX6PWtDbK;#B@YY+x);lIFA)oK}Oc&7tCp!I!e*vdm+Cwf1SIOUstE@XR<1V#w`&p)0 z5zN$+l~`TG)F4T?HvYQ;eI;(yECG5kc36ntz>j}GA$Eu56jyDHE_;0sX@a69_&NET zC#2q#mjgNFw*$E`FR|nlxIaZ*EqGkCgHxg*243yyk%!K6Z)ecXq6*aU-?z5UGymsz zDB@CoR56LrkPW`~uLtJlEYSN?y!|gWZEA=u$bZnmY~76wl)@#2(-;yu`Com3RfODi zh%9aFy{)Y{@I-%)Y2A#c0J-cxw!jm-Ya)cQi!-4gs;YjekX}7i{SIwhy|QL1Tw_A& z;CN`gL&Xd=^i5XRASsq({H5DM@TO`=Tz_Nq#(HEBDj<(TTMskVXkYB50xkecb*C^1C2LVVI|@r z{ztnM54HQqs7J_Bvzug%*Ilj|Px;zvVSjK*vJ}%N^>XIz=W=fY% zf$I~8H->b|L1)*&CP;f%#1+fB_$8Rm;1EhoULp?Nq=+jyhh{;%IXY9YBUStP3srmS z^q!6Kr5m`QRTmd7s%O6jFh)Od^B)yEWlLC;5!l6z@T*{`zC~2b^RXA7r-{y3!##xn~2C8)Z z(R`q7g?&W&O$)7`W9D3g(#yL?+Nv;28s6KkItcH-=D&YqHd4?; zwX!`#El1sy6}1_SFPhTgrku3)uotF+$A^kBq31DpyAGZ+f7Wx3rET*s?F_UzPW1kA zu?-1E%Qr{gnc7RPP3M~Yf9d1IVKlkaGqrQ)E?Nh}+e!x$N*fuRiw1o-=p?-OlOQb1 z?rFylKiu!Jli2Dn%MDgd|3p%is}!@<$(Yl$Ps54u86aPE*T!wykq<;}cD7KKi6|69 zSS_2B;U&Hkh-wM;Qmo61_M<`V1j9H#vpehX2>0M&Kw*}M?Iel}6@5oy3E^aq5IuOUSck7U zb0tX8?A!4=)dzZEcHr>%3BtE?t?>4Ul&Dd?d?>5cT;HvVgTiV`oiHYcdWTq4kgkF_ zx-X!v!l8ZdeI*xvnygQ`$! zRMcF3t9(I8+XK_>+cWo)dlzi9`=JW4H4sqX^N?$Nul(KUA@gFdiCxe%v9Ud{W2n4> zvUhMBUK=c=b-pZ3#Ol?B%IeV*WNL?r*AK6uvmDTyozP(F`!OdY0jN?97jemivrt?W z_T7tyw~T<@sSqpRp~C>8-X!J|Xyg>Fo%6!(3DYe;?>6=FkC2ME%^*?AT*z8e`1G9v+tG4Y>%R|T3 zPQBP9fd&zhiT1c{0l8-3pL&J0h;L^4d5Z{*71|LkP@M>a4Q}5yx9EV{aw?swgI1Sw z8aMr}Q|;AQUS_1wbR_guK-ys%9S0S+PV*-t+H}(9dhY+_O}~a)HeiXXI6Vr*ot0@7UqlGovw} zBloPkkH#A%`~=dBo9iS(nwH-AfwmE4S?&d0FWQ@`~(-NN@y%GG;@@_t9%!Czaz zlIx@ynX1csFr}JtwK5KlO~=xSk_wx@4wxY6dcq6t;zzjhAdpi<4e&DaT^-zt6bX9! zl`e|rN`8ev0;Z@A>A9UbnW5?Tvfh1W;K)YiNnNX#4$8XV>5}Go z{FnE+{?y6X8*I=t8@r0lB%hhKB{L*bzouEUbS(QcHDo$)W|z3{#IFF>V8g9e6ZHR+ z`#ra)D?!xQm8SAj!+&JhBt~-Az9CI4&H}fVh>iJF{Z3PB9=(q5N^_QZ(B6>7x`eT! zjuVHm#-<7x&Az0F7d`Qy?n&oh#NL(ol+6ZHEMSUT^=K1HLv&#;}eH z<-T%3mgo5|pQgLg#>3AOyV8sd=zq7ig}B6vy|)ac8}!15u`bZsPo-aY;+*z&}TzG`YGYe5FjMjWP4fa6oS-2a zBY*9M8h&V_SEHn!dVi0AQCZLW5>|3Rd)Z*H@E3ELC*qb5G+fAM&1_!8?~VzH9^Tqt zBSzf#>5gQ@i`MZC*h=tFpEdmq>N_TUS$zNMMuZo<+<>sbzHEjvm^Ai^b+4mI&@o>7 zJjvQLX5^NxjOGxxk_Ehlp8rP?FA?Ms0qc{%zY zSG6luRGQANn$8=$Zs;l#!P#E#`cEmJ!BgQY0HJYwng8ej&(S_>IDB~dX+)+|CS;xA zoL-$LztW7#8aj2h2QKPyzi{^bfW?vbLZ{RU`ylb|NFQh8E(kbji z&x`~qb9)e^;UdkrfK7t9(^H<6F3~Mp6aM?z_NT5*K+G}z&{H^~D}2b? zUtYUCTN1@@cUog8kfY9!k{!!X#T%o(jwB!cMXo374c z$j$9OdTi#-u#QMz9yWfhc_#lTalZWN3Q8vl&3*tir)sm3prj2MgW<|;~-X}0VSa@wEVHd9_&ydhook4dy7%@vH z_M00I-I~l%bEyu(?}lQcssrrPe1Up4DTTPG4cqc448hfklSb;Yq~4!~Bo?fjtLFNAO|Rb8;7S@^Q%pwy}D(K0rd;^_01afH@B0tKV!EBOEy)%l0@kn)hjwyO1VVUJBAOE z>zxZHv}y%rPX^pai|qt)^34nqv}QJU!XDw89778Y&S@Vfl5RNT%Fi3&2BgVwOWj_) z*Z9<&Hgd6Ozr2Yl4xFLYY2KUB;@9*IhiTS`m8{SVgd#H-sRVbm`KfoMC?CrMTl%z+ zZQ4lcH1rzGt4CEdf_-ZVB|d?&T(TzgkwfbVj}{k#X?strw7(4f{=9DUxPhN8&RN{k zr`4~$ofVBVZvgZ8zj~?HB|V)u!7>$gRNa=fS=y;NRoRVl62@BmW^t=))Hog*eNNWg zwJfYgh0{n;EY;UPb$Qc{r4epKSy3>M^h9l(kIJlKtnQF}NOYgo*%(ayrD0Zgr%W{A ze4s3JU7DcyQ6B&no~yhEu^TaH@_DRnEQU<})ce@}w@BSsMjMu0n~sQP2L_K=qnbmx zQ9ZdPqRQ>F`iOwA9sKBq0W%DLvK=V+Ci*?S6J_dLyqd@NB|8nhblkcZp4jjL!ie5?aP++ zG^j95kI~14dilAxAzs0sV*M|HRrzHR26U zvuY+cHq^&P(bR)TrsJvuf>Akup92CxVPm|EKcVHwIJ7{9Dk0h)+ao+ zsY~!%>uW=sLd#Krs+o-Tkuy(IN(CqBfxQ+AkSJ;d?35<$VhLGF8TG+d=KO9WfWQ|T z#T`Wo76`!o{bL;xfX9Rb_yT-Z2@wXT8DKCNAXl&q3Iher2ZaO02NObT5KvYZgJ0tm z16!q^(t~eXaXAdkyYIIP5{$(&l1o@HT<*4l2hzNFMnQ?@f+i=0Q!N$@73c(LUw`R) z4$xhcAo^p3_z>c6B540nELfjooV^ry`4y!};JDCo+=vu^WQpoJ!J?p=e4%q9Vw?oF z3{Y2pX4GB+0c{K>xU|3?6MoVF0a)QhNgXouy=Q-0FaYR1CfrycY&bk%eepDmRh|J} z5V0sCh*!W}a(_YaWX>OAx-xSre+VVzsNAc82zO#IDYRwXF&C=Z>S$wH2yFGo; z%2uLV<{w_{-Cj6dY&o^dhv-wekF-5)X6e6ycsEWG$twTK*CYEDcQMJIQefLH;kj3 z%1PG`dlC`w{x5pW;WwdU_V_*_mEd*e#cTJ6MqD_7@*L6EM@{}@$Cvau!8a2qub*zO z!fv-WH=mLo+-cF)WDNAnCXTPlf|;V$sW5eG=<-m31}qB`S)WL&nMrYzrkFu@{rUb< zkOvd16hi7?rkDkW_wr-QpoNXF2}v2Pv`t*#=r1&Rm^~E#I63G&;Rh41FfuzuQJg`I zdW3*x7X?Q{R^Xtco(l;4%f~?P+f4x$aFZ1G%4Gt@xaG1`GBh4$X7(TC$)tBewGu6R z{lKYJ=@fDip?`R#9lCQgHWCrhgJkqz6!? zgw_w&qtFx$f(1kgnpAWL3x^yCO&LaJM~A<~7U9f)MytgNF{LtkT){xmkWKVPQhWE& zn&Iax^#gfvNc+hVcSHk212uIzVM(ca*dsBSHha-s$3Z|YgQ^}RL`SV zUODRB7bF5Cf*Wj5J$NLEW+9DTN+NX_=3Xpuj>!=Y9#;eVSU5R2EMp;cr7TU<0s}g* z5(*JAV;_5mSO*m{1DD#Mfb0E{x|YonylBlf@Xp&tqBNXM5$8ylF*u%x2vRH(`3gh; zX+7FL-7umqN}Ae6g8HfEkS%p=5baa2L|8S{PWQGZoSO+z2IpIVCaHEwxHt<~YX}}C z;$T2&RB4xg>#?sS^I5Ve8zA(Lc}{`VIG)wv8+qT5(NP?H%w#g+Au335wgSYmTKjg- zAH=CL_n@s1cNZiwi;uoZJ}g`|D5}lnpp)EDLTd29UT*g_f{vIS?po6 z*(=s-$(j|3-H?CKZFh}RDD-^?rs>LLGZ+xSeq=46d0E&x_+4Tv5hE&*AxfyY%^b#S zdb&Pq@l5rxH-3)Tf5FR@$w}^xyM38SOSm7a6>D6S$XC=SXt5^Mmoy~VK{9t@t>wSH z-R!lyso{f+n_~|p6Je^QNEGc^r7Nwe9PorpKou&F`OsrbtupSgTP5jju+DJM0m*PsMaYYoT+y)p ziNVaBPKQd9FU|I}7eWw``sF$4V+|LjI&6?{S)H~SoC2n@jC4{Cfv;4FN3j}pH23mX zy*U)V(oEaHc;|@fG6uA1bk_Xp2_bT6?cRw5o|5*p4iF&O9fClsJ;EI+W#Q{RNV+^X z3d3mOvqeIMyn);npukA4x@DxU^SRla^*H2d%Uxx~s=Rrg6dztdHqsOo$OMQyi7!+3;&HQUGL`Z!-mp*pSBgzb4@u?)UCQ@9)1q9!mK+js#s2irYH2I*Tp2DoP{$VO* z8pW)NVA5pFZyx(z)*!c?WefPBtYmzykZvm+L9yKNb9BRnrJXnGM%%Z+b&ne#uab3R zjstJau8PsuKB-N*par5&iyUxo5UVc$Rg;-@ogXOb+)0mFuilG6Jvyf&gk$1RqD4rT zoC>Kju1`A%fKsa|Z$a_|Aen`s79yE$3Prg}bpl2Dq#F=7BO)WLC+?IGdb*f+6*R5!QLiAmMkl(#x1?n?gFC- zrQ|1&fYvt~k}B6ysLM)jCyYr2@dECaEwkE&G~$}%kf@xx^$+94gww}{E}H3=y#yf4 zf4T7e!_sSuav@{2m6`@=Ssx1}k`cGQ+|H6uL(YuF%n6Dm3289T2r7#1dHk|1njQDz z>~fg`6pyvF3go9wTDxMsXnKOnibQRuOkYgXeZvS)!CvAN&>Yb0DX_lDFI`>QQwg?) z>A*Hp7{|VqIUnR+$hD^}rggueYiH(zwWW0(mlO2OpP^ALL&mR0>JTlgaC9n+o(hPx zW9x-5O-uE$Bu83jYud~eOpCgNaE28_TIgSIT(K$Z&D_5V8(q(ngpZw;l1SE7L2MWU zbwdHD3>pXZTCi>(>vL%wH)|a<>Nr$sHV*H~5=~Ug>xvWX<~Xc>X_RoXk9iEqRhYFK zZa2o%u96xS+YL*tX&-e+m(ql=aHMSPIjz2 z2nEbPX4JhCt;Nhg9!!+2+DO`(5m~HMwkLInrp~AaQ@L0;Xz38JX^=zb!XSZpBd!A? z|8f)_X*C8CNV;r7c}p$j_33D&kwU^qIfu%qJ<3DBI3k2i@m=+4GRyYY?`sNExk)O* z4pvUtT{TGg0y-SG%rAO;WwH^k9Ys@FopfCy6w*EH+n*~@t|7Tt9XWV8v`!jomhB8|4?M=#u$g z9}A@Fsa%z%mwDm=W&gpmZ-FM2Jkmy4g?fNIVr-}Mh&H-xJgzIz<}VL=whcTQGS#Hb z>Zm)ibM=g`r4)y@j*SiIJ(T}2+tP8A6tE_8R92FTNTTg(!eR=%2bdU!@uzB_|#Z9bc2aWvTg>d?uhYv z^w-0mi^xN=*4GzEShEo%t1_e9m2+z5Y>0`vhr}^ILF37n*Y=&tQy8Si);W$P;{#mj zNsAXG@TC@>z5^3GE0rTpWAfM66gz*`9Z0I71pB}qQ8Ejb#~#;R2UQN)?0dAd95FZO z6Plx(CT9P^*J>Lk69W=nY_wAxW{F&=>0{11aQA>nX8zdf*y!3@cd~y;W zJpL9Gzoqq`pziC|%yZ`K;7C-!H0??ZLmI;q4x>YVV_=YH;g!#h=wMm7d{bU*isCtF zBwu1${F@c$heqY?WRgXd;wBbey7g-ydTnCHINro>E36y8m>R>{P(##~;G_e4cxfv$ zR;*7yyH@ahITB40%?>%u1J{t{t$ef6MM6eb{dJT`+pW}5SBh#0JUJj`poLF=vlZah zEi~qghS5XR(Bf66p|bbYfytv=aZD47M0aO{yLM+J;j)Cyv@prehFuT#i`&_DWIIJF zAlGkRzPdW>FD%!V7q5R4yqkh!7Z@+DLo@TG0dWtQR@=ulF0*anh}t@qs`>8U7koUp z2eqaMMv18x;7WMvs-Y_&1&7bpEtaoILEnn!IRn=gD)2c0&DO;rnPbN8$y)&_Hl%?| z!!LsbKn1DtJvm(vJCeRQXhD-`=Df`F?5s`#Ml ze7yNI6iVgdt0}_9n^yu*^(fn*YJ#eM@n~97;9!jC{0xk!>jwDS5>!nVrTpYRz-qQp ziI7W$o{HI<;RlTv^sHZfk?3lcjwOYGOSul(e~%V8=?$AtgSN!wDa}VS7(ND>c z%+iU)%(5@0G5@XlHdqR_%Ftm0iytjXLE5Ug6w&OA*OD{Ha!48PapQK(>KvEba$w*N zU!v8Bj{8$}O!)D!@}2h2+Pd~)l&vdWcu}j_`={w?>&?BHS|Zg_#k@us0C#1lho%S9 zQ&-N5dxxOF#mUZ@27B^{9cCicn4yDdi5q2T(m;Eeeod>(=f>&XYtw*5$EMbHplXW# z6Ma@3NlqbEbKELBZQ@}yhz?{oQc3~IHS?>VMO*Lkr8icju37=Zqpav0#*JQ#=xKy1 zo!5t{*PHtx1LvE=GKNp*e@ID@tZaI?Bt*N)jvCa%lG$BaGmq0UqPx62bk5$Ia&qEI zfg$xD(YY0;Zz+5ewZOj%8Tr#jp+)31D_}4gg#40x_1k!>;_%Aa2!I{{1^~EQ5#ajv zaq%lHxs2Hpz6s*QrqD()WjPh8MPYZNCs|?Eg)^vZVZ$gU*4m@)!{~;6c#-K`o0e&+ z;BBdGbn&#z)Sj8{HhLZ7U?vYk-+O=GI$b8CLnlj9Zl1Q-5`~C@@`+v^b5TP{DNG{r zM@ioVVk>cBz7AY?e?b`|W3X_26ZC6Xh+D|8IZ={r;|t3}{EUlN&jxGNqeFR1G0q&# zvs**EhPJgp;8Ir~j2|Wl6NJ$;%6QI=OSwMYS*$CyNJ>bhaoPFMTHDHL-@*g+8$|>R zHQ2Y)Vf8by+WHz9xgMHxmC5`ia=pGg$nW+SOj`bH^mkD2qQ0%65m~fAqtL*$y>|nd z1@h;Z`TehzebOe8_BO>hd{Gpo>-kz&nmii~vhmp7=cS9bgN4(N8U+knJE0nZKfX}x zSy(3wn#x@sUs$ae|8N0nbrHHB#pvK>cDibrX4`&xzNN~7p%D`48 z6}zq?XXH-mK1KvlAr)VTJ}0=vnj&ZiHorJg>tVMVstwpi3*rayhX9)y!4TRb;Tu(H zAkmml;wf%C<~Ivpn8P=u59zFAS4vh`;E^B;t3?w}1(!IL%QF#FDAc+Kze-l%l&f+s zwpz(;%_m(UQd;lmNU!*wc5NZ?t7X#KI;S=FA7nYL@Iegh*1r_WIPGJhDv>v|%zdS_ zlspF-a{#4_?s<|u?qe?XhyBpk2lzM4P(127mv3UV=pwSUJ0+lZLkrkRP-zEK+{?<9 zGFN2B&dLVftCE6@ruY8?ayU3IuC-|BYp2WIoi}i!4~-7=GEif18LSB3#aUU~_b9Wt zGqq`Nu1^ALbfZ;+S^%zrS%}^cyR3gEb!cmDY!YGsOas*e(C}%1Uy#!Vcz3+<$`+j; zEi61-@zKaZ&jU5^S#D@>0-1p7>F3axK(G2WY6V?DoCNSvCtX#d{r7;#eisL5u&kWd zLBR`5@KerPVU&xT-m4#MJlYjkMrB;>Hf>iG;C*jp3+`X~nqJTJU0I0=8pb=1>19)& z*V^4nFTsWQV@+)h0j!+7p6c(ZUD*{!tW7OsqZUo>WP3xuRcGsIseWnLzJx9UUo04i zpbOlTZZi7UGJW5d&_5MC)98|%=geC2p*B}M$RUViCUBa$PR9<0WV1h>xZWH);cQ&q zioO=TJ=&Ed-N&C?seWt@YgKqevZj{B+B`pqjfM1q`N9HWgRl%EB6p?(KkYcD5%2G4 zvvaFJQ-+Y3;j*-P-<5o>FY-?U{&ZG#t~l)CM)O892s<5djKpv!cRXT}UHpq+ z*1L79$e@zR_}y1?F!OQzF4$4QaQ0)N-mN$Bq-+vScCn2P4K-=(bs*1gqblaJ&;xHl zPtNn_Qk|Tcz_0-HtcrR?{`++-^iQ#GYY6kCYzblf;-kT20 zK9_DEFU@MQ$5oxb7&Km1ygbQ@p-TNqb58Z;9*VuJG)imzkg`~`ZK0Fqz%41|5(7~l zVJ4)J3_dbMF=R%?$^b-s5Op$WG2mY%;8+EZkEl!?;Ee)*)}G4KM$921Ca&^Uy>S{C z2{!%7?D9vMT6UCSe5N2L8ciH47-<+6Yt4usF1UM&G88%8?%l>rPOVSf-$`Qneplx) zqF|#AFm@z;cL$Dte-k%U*dO(7oD{FiuurD4vbU15dhgmY^UD@m)l9WHOL-*PNxIvX zW>`0}$a&Haq1!qm+Ni$m5SV3D5o1{t9p%I4|A(|ZKJ3kgqAoI5f{4)RaH<;aiF+B( zVJ55uF*E9BQ)hgol4$ST@6vH9=r77x_sHHrs>C=|tVwfnTKk*c{@u~p3+fz}6%0zFWmb#XE(d#$mY2kuf1`z1*r*d7o~~5h%6Ff zT{4`M0bRorB3VScuF_gIff%8^(?!$QM$>DZ%uQ3+2kItxU%U}h6_?5m+%m-?bjH1x zxSt{zKmQD@om_0q%H_@aO{2NlgkD*|Q|_Jp z@zqu5{mja6L5;pn|JBDNGF@kpjfTiG8?&eoZ#QXEk>3xY+Puv*@!pai)AV$Xh=>zX z>#oUf4YG%uEVT%>F!2U7^DbpE#x8gOj2WrlxBBAN(wRkLboOrblQ$t&gtZCsvAdJv1XM|IsA+Gm!PoVW zzYZK1hjq?C7nkYhK+L$ew7iG z+G?R+v>Qy--<0#}KHmuUp?42f@mEPtQAr0|j~{gC@}u~^o2{?A^sNy8Tv>YD#q-o7 z5Wtm*2*gm@?axxsDu@eKU--6o{QVpcUsMS#xi{g96$p|j2Eh#ZkC8zU!?;QL_+bIo zh^tVOxW}_aS&eTs#?2wx^goQzeoD38I=0RE6TdJqt1~h7Q;AU1HODB7=^S#N5%Lr7SHgUomJn&_T_Nv}ke21sq>oS-vi3Y6X>qqiucHio^aY1aaQq%T={>?Ebkqge zaEvz#FfABEM$Ocx&nc{-MU)?BEGE)dTrI&k`zaC+jL9z&bK@|=HvT9r%-Rsvto94v zXiS(>z3SNh7s8;LJUPuU7J+!rDu`mwJhGA57^Q}1PHBdvf-*b0zH;fZx#FPtlbWT| z#sk;Y@#q+BR+r1&XhHf7(5ynJA2xx2Up7ddugMR$xDXzM(c^POFO1cB;8g+Aq?wi{cU#g$frm6=07~(D<^?lh)tKFdozjb- zDrKD&ZUegC`7-9iuoQETIDa_zgA(3gUns`ZTzk@PK1}paqKJ_PB87C#i)`B)m`K7w zmCLKubZRpE24*~>Su&eLIGug)EMxe@pDoufx2H*J&-{+K~hK3c74#t(nE!3E;ck>0cxP0C|&_U?s zgrNq2<;o^bN* zHw2J^tAdA7_WZJW6k_KDtPI+e2l|d4{0kynj4cR#t7*%K*_xp${mQl}n^%*|N@y2; z^7iB$L2YKVTQ9|QFc?BB=y3rIgFN=?iD zn(qI^CVCcZ_td_-``7Dfu`RU@sv4+@udhzla(TDBKcC!fSR{UM{0_$7U*lbJu8S7cY#FNnYKM$Y#^)KYGTsW1zFSLwgS|?+ z`YJ!y*7p8nyOX$GrPA~MdguK+Lvhq^m>g3V0Dy5wsQ=DT3;+S}Z{~NGTuUo01OR}) zAB^uAij_&VY!`0fO&*jsDlZlh*ZDR6? zYWrgH^8C5uD*feieB8^{&TbY#sKR5$85kl@RtzwtlmPTcX%LD}F_r>Ap4s0OHI&__ zr<5K?mzR}xu$;(6@*uI$WkAhh_PI#ba~d!0??p9tufL%j5GqiST^d=|QiU$$I~H+(ZgaUmO7Xh7xRB#lR#k!jmQC>E2aJi3W~4}~ zZ*FEwm3lsc$LAq0T&mPkr1iQ#l(c2b{ABz3BIJF)v*ta&xDd7`hy|=ej*te=V-0oO ztoq&6>HXDt;a8?wMQPmm^~u^8UNqweZ47&d<7Eg)1OEojWj z^0LeOvu#4@=grXXuM@+Bw2*bBQh@S4Baz9wqp8F@AIa-?I=cIK-U+&|&^*2Yg%Y6i z^K%z1?}Jg)XTR-gq!~I#3IL>`@NPj&C`Javy zKGpduDk>~2Ec=8n2;>956H)^wMn0@XZd0wh%;)>6ObBqQN}Lp72H3@oSrrr`Qse?1QOL9a3-EHIt;mB9 zV#}X=ElCtaKr?fD8xi1cxq^fIi{uAmRs*3OTWl@)uc!ngMkQE#<3 ztD&I*)yCQ=Pm;IX0zjZDZ%eez06nMHhozInJP)}BzL$Cj1Gm>yjG_hF# zv!nOeMci94519)l;i_Ygr=SrLpxLXttr)wotD)F=71d{rH-Kok?No>!(U`kKe%hB1 zX8tD-dAF9GjWw=LO~6n6?mcl9dP+VP-sbQSVBu)-0&N zIIfTg$mh29yhG0n&5hwl;K^lTmguscJ9Kyud4R(OOa%m5-9DEjIW(wg() zV|%o)ERY$WT)g^4-k}kYQ_teU4*pnw%~8P7Yd{5ya6L}_^hl9j4X`uG-9tD$0W zE+DW}zK&r2{GuP%9#@I}Me&w5fNtYWMK1Nvn-9t3q3!7mA4{+Qr?TsSYGPa0p?5-) zBE2IZO+=d1fI#T|C@qEnq4%oNB3%$d2~E0yQk9M%0R;sFq*nnc5|mz~`@*@;$0?rs z?)|f7WhRsF+k5^!v)BLqd+j~GvIio#SJ!kmIfB(rS?_Rd*fD=U2$(wFnQJDl8L-GT zT6}c}H8KVrd`x`ajb=2_0iqYw=JLo1axXzZTpR=|vi9S24r2uZfQPyf1^3HHaScP_ zy&@iYSQK5B4`sk(a?G|UB#?-(=gpW3-F$F!$!N-vO`L7#x z`@kQ)hx^a3Mb_nFqD09FMK}}$wPWNsFUr0d-r8cY#G7FV7#Dn`y6-u4vB@83OoD{n&j1 zj%Q1BSxa^*Md*OE8V{CkFtdc1b*vg+{}LyIF2pOED+E~VHV*XIzX_OnUps)f%}H$Xi${`|8{$Ul8iNFy!|S%xEKe44V$~YqBN0{lha)v)Jdc0I~)OG z4IETr$4TRyhQmY8wvmLaxiAOu&^dOR_emRhZIk#&Oz)Hj)MyB6Dze zYwe2Y_))TFpEucX#Kz?T8jC>9Yf+}%Vxcw~lTkLf*oK#vx%JBV=o4#5gmJYJt{Gyf z8;5 z&u^y&v69v%KvhMc+9#ueeteHMixU(|%!N|o_g{DY9E014gk%yzA65HiGj>K$Yh*RK z^EXUC2CuqY4)HfmZeb&=f`G>D1h16z;O9Hggjb>x{AMpIUQ^ z^9cH-zZC;SuFWU+nhnX2rBW_*4tKu~sb3)}TBC8U)l^(KIPmxI5O1&}pQ~1r(~e|w z!7=M**0k*jt8JAz*pd30_Eurdt~^x_SJtK{(w)^|gr%#r_QjR*Y4uhh_}lsDX*Dp*Ui(MoZj|)cm%1DmA8!*b(9Ya&beoat6v!CD z?4BI%^tniKD^j}SNtY*C=C62lN8xfZi4+XU;*NuMW}5w2*&o@;IBnnyDlLP|y^-Qt zfZ|#j%XUCD@>X~xkbN5%$P)4VO|f2%Zo-WsWoIY7R`o8%5e)BeIQBX73+vHAcnlJV zceFAcHm7vtYG+(xg7FP}p$;KCwKKaTa*aR^t(K6f`PzHg%)Kb4K_c|~Qec9WDnbF+ zp^0d;5SC?Ij21&Buq(2$vNDm5OScgsKBOQYC5lDjYsaqK%#wxiwC7h6_aKRfJlGZ8 zKE0agg;|O=-9O$hzf({C-92x1GV>85G@MyUv}h!nonWxwY=#!1siS^#XM_g{yv4kY z4kwC?jI1-PU>3Zcrq@8_rG{#aZMw%MqaxB6*ByDt{PN|?1?<3E@UnjZu_VJgpp6>J zgTd!yh07{DK;K)8n+sb73xS)$nM@OmJK3b1+pTpwT8W-FpVfFU3AGzaqw^lE8k0PG zU`FnZHsS;rNYUrf+}HirsTO>3BVNPhk9w7Ipli2_g2&0b@SkN2N}&CTjY9;Y3rz=a z=C6QI?ats;>xZ*eswG4m`Z#xalPuVhOD3&oAQE0)4w65_$TB`Cs)B``d!=};y5K8G zP?wPShT&MG{x*-UI}@_uMCI<)$_{$*4<5e%1nlL>xxc)@MwI`?{xZ>8RiHaLAjr3A^3ze z>Y@2ODbg5i^_$k5ebA_>K>cBC8I(%2PXQuHXacZpYoK1}#GDK5Rq~g5bjMvENg@iA zK4}QGZ;EaUj*u)@&BEo08q^Pc5~CEd=HvI0*QfH!%FDNayPxNW$@!_5Yp=#=+bzjA zvzJIPtr z#;B6ucS7y-!Z~OlKCiu(@rFO*^Y&$zU8yqy8 ze!5Z^gdcGUl31VwqRP&i3l9%BU#pt0z_SWvz&<1~xG-*aHAW;jb5~SUG`8P4_c8F0 zsh_?{>Wc7zfc@7DVQS7p4{Ru}5q7FZ^@1zzw7I2a%}@^cKxFHrV>_$UnqqKChptkx zW50Sk=H*1NLB5h&QK$iR0~fj2gShq&dJ#T9N-;8;47{W~MWLBAqxcID>1eSqV(cwB zP7G+kIY7VWD&sDDX=bY88~vyqE;^?*1=HZey^huuySCIw$>T6+pESyTBZRvv8MhuW zFjviC7J2Y32{6^1((bMYm9dHrl*ocENG#&yBfo%&J{wH>YAy> zj1hi_(r~4)My17XP1nvl>5sIK`Bgd(5vqB;TwJ;}9HHdev;{Gx&j3lwIyE@27UekE zLTsjO>)AR6b3N_1$oqEqVrTGj$AKeIJFz1_qf%5Dln=$7gx1lzzL`P9Ii+ZcU7S_u zb;wK}Ttr_A_ZEQR_*SA1IoyVvHNpHLxrM4{&Las4^v5EpofxT5S?ZE2P_^+862Gv8 zI=ly3yHDi0W9pja9)X$9ytTD@_Bb_6!0&vI-B zxpN|cE}+svGMwNHZYII^hrGoHMG_~itp_?0Mlo|8g(>*Z=Zad_B#e`Gz`9#t2s7fV zL@2RJ=pXg=-vs!demDb`P>TkCds@bOo;}c1(*;$i*o5hW@$l&YKT{ItXMP$xc1P9C z)edg&;|cMGySaKvh{9bU_AoC|6}Yzx#NA8upTU=Z0d{wD_i=ZDx%&Kd3i&;eZ1~MJpT=j3e{Q5-RmRTQ z4dM;^>9Su{<~$GO_mxav^+aisQ#*}f09PL7^^ zK3d}v4qSIcenYrh-4*?Qy02Mx=fxv(DHI~hR^^!?%%^8{!|3_c3@SlUo^LuJSHhmF zW%ck>xjzpsz?CXe5tyTR+LOKepy6z}APP!9_#02ViHgzEvSSB)y=_r4hiTr#jdv)W zL#D_6il&2t(Y&^;F;&THvb-Ek|KKG_v1YZEaF&nl1x^-^iQ&6Q=?<3ygX*kcCi z+TyPKuZvw-&DHLziMF6>Rv|VS@J3}IxadXtm-4Z%XMy7kp7V!8nBk$p?zyVL9@8YJ za)Die;s*2e!~3&BKD5s?%#QWPq^?-}`86x$u*?q@}xhigLKNjW4QK(T(5^E4pcaw;1)wqkn0-7nXn6Cw^HZMw?AX4SH z-&$+0l6kkHC(F?gvv;e8eua-ZyomMw zLqf~F2ST0eVd!k2las-l?KtG4J7yk&0f|POM@C%F#iO+58ZDHZ&wNW19}=@XrRj}4 zFw5*PR2#xhxfxeryjR6{9jwvRHgbw-sIeEZMO?u#epO+9%58qyXU-`d$In1v&foF) z%@%W;tbCY{c~{H=f&n_eVB%&mLF@YMxhxQgb9Q}`YPJ8Rzdz~fd+K2%tuLb@#k;3R zUh%Ayg#8n980wOtKK*crSX?_{2^CMVz31|mgY6|qVOsy}ka@7xm*KODHMK0}?nd)j zf~^^g7@x_gNe4Ogk(Yb%9k=2bbd;TBTN)Uj@G2$j4d^*!wjb4L`!@E;V`%4H zTs0bhsjMdF_w81tcPyII5k$VFj32Vidq>4qV|s^=O5L{tgMP$mU{}+A8AqH`Y5BsC ztDktXlS?p8aDF0bm$cS7CBm_YeS5E^GEfFAA$-JoO{LiroI(;_&MBG z`{5kWT?$p&)?MVePrx3lo<4|OV0$b^*hWA?ixXtRi%zwE;BuQL#xyB4;*9vlm%cB_ z58GuV~kdAku{Ij<1* z@?BvGmrBKNg$uw=Hm8QI(t$#ivBgQxyTRrU%QNH=Mlq$sEFUs(`4;yvvRyZ{Edp26_zm>4eQH^u@uA4 zKm9m6&go7l%XGGU??i@b{?P|tb+~4`VH#4VxAf$oy>Bp>KO({&`fh`0BPs7A6H~@3a73p)RA43H6R#?RJ=Ebq z}Z2ZQ-?9ZrvNT@}=4oZK6AzRZ_!O$nc#> zALeTb5cY88DL9fQ9+{hj({(iERTtW|Vhq|#?BX%0kp?bHHF$2LplZVg8xzQHTrN?! zwW@Cm&*U$_NH=F(hFlOk`!`NBKhBClmsTav549A!pY^zsIiN|SlAc~0w*B5@Q~%0( ze#=<79HW9sU$sj5VB$oyv^;vKBe0oSIVLMUJg%}fXA=9S(-wU*cXQG*nI2?XSx8|N z8{>f^JttWA-l_r!G%6H^C zt$~(P(Bwne=$8aM{57d>Glw7Gkm!AI>LlA64@TEnu^{H4 zfu+ZpCcfbI)>%V3)3Auso8=;9ZbzGiwl4~K+9N-WB?#Xt5glhCaPcO5;1{ne$H;rD zlIEFJLSbN@mFcJ#x?rd@D6eYUu9W%ut~4r4l}#b-BO>V@@9WNhTI6D>+TE%h0@^~p*>PqRyjMRNj z$W*RW{t^;gyBL-YLBdWtg^l7@_eehr=8S~H!o^V;hAmZk5*%t8b*I#fM8WS=lO_mK z2nuEh-1418=|1z#3(@(9$Iu12_kXApjiC>Med_(DzaCJ2Y(h+vB(#RiToY9W&{0AP z{DWLxOFQVBRWhucI7KqI45% zO?%c~%WsWMTDtXYQ>I((=$TbwXN_S4z7h^U?QjwR;7Imo!1t@r?GiS0(@`^4zN)FK zF6shth16nbG_|6lqMl%P2&^(bHk5@k5CnjYDWb3r2@fvT+ zt;9WplMhH-3cG&W08Y#Q?LZhM>a)%H%w1AeyjndH&+t{5e`MO6_FchBTpcCjdm4H~ zqipcWy@`fMsIPTNoKBbsCs2BtQ(TvVNCJn7Y%l-^%LH?Q*m(V02fLr2T$aU z5Z0aN+wb8v_WQzI;4U!l0C(75QLAO6EjIW7!1?xPlmQlu#X!zu>Yu2eO*m_VN61D1 z05D^f8~H^c*u60 Date: Sun, 25 Jan 2015 22:31:11 +0100 Subject: [PATCH 61/73] Revert "FMUv1: Disable stack checking" This reverts commit e62c8d73678f87b9f6cab1ad3a33c8911277a8a8. --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index 539634e3da..a467fa605e 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -92,7 +92,7 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y -CONFIG_ARMV7M_STACKCHECK=n +CONFIG_ARMV7M_STACKCHECK=y CONFIG_SERIAL_TERMIOS=y # From 18d756dd599f93abcd5dc89f323a5df77384ceac Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 26 Jan 2015 08:59:19 +0100 Subject: [PATCH 62/73] USB startup: Ensure that we are not talking to the peripheral too soon. Startup does not take longer due to smart rearrangement of launch calls --- ROMFS/px4fmu_common/init.d/rcS | 26 +++++--------------------- src/systemcmds/nshterm/module.mk | 2 +- src/systemcmds/nshterm/nshterm.c | 6 ++++++ 3 files changed, 12 insertions(+), 22 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 2c9387ff06..4d337171a9 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -5,6 +5,11 @@ # NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS. # +# +# Start CDC/ACM serial driver +# +sercon + # # Default to auto-start mode. # @@ -43,29 +48,8 @@ else fi unset FRC -# if this is an APM build then there will be a rc.APM script -# from an EXTERNAL_SCRIPTS build option -if [ -f /etc/init.d/rc.APM ] -then - if sercon - then - echo "[i] USB interface connected" - fi - - echo "[i] Running rc.APM" - # if APM startup is successful then nsh will exit - sh /etc/init.d/rc.APM -fi - if [ $MODE == autostart ] then - echo "[i] AUTOSTART mode" - - # - # Start CDC/ACM serial driver - # - sercon - # Try to get an USB console nshterm /dev/ttyACM0 & diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk index a12bc369e8..4e27105723 100644 --- a/src/systemcmds/nshterm/module.mk +++ b/src/systemcmds/nshterm/module.mk @@ -38,7 +38,7 @@ MODULE_COMMAND = nshterm SRCS = nshterm.c -MODULE_STACKSIZE = 1600 +MODULE_STACKSIZE = 1500 MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index ceaea35b63..50547a5626 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -50,6 +50,7 @@ #include #include #include +#include #include @@ -67,6 +68,11 @@ nshterm_main(int argc, char *argv[]) int armed_fd = orb_subscribe(ORB_ID(actuator_armed)); struct actuator_armed_s armed; + /* back off 800 ms to avoid running into the USB setup timing */ + while (hrt_absolute_time() < 800U * 1000U) { + usleep(50000); + } + /* try to bring up the console - stop doing so if the system gets armed */ while (true) { From 9cc94fcb2dde1a591c20e008ca59d1f876c2070a Mon Sep 17 00:00:00 2001 From: Johan Jansen Date: Mon, 26 Jan 2015 13:51:34 +0100 Subject: [PATCH 63/73] mc_pos_control: Protect against NaN and Inf setpoints --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 3b631e2cea..962dc6d4a0 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -726,11 +726,18 @@ MulticopterPositionControl::control_auto(float dt) reset_alt_sp(); } + //Poll position setpoint bool updated; orb_check(_pos_sp_triplet_sub, &updated); - if (updated) { orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet); + + //Make sure that the position setpoint is valid + if (!isfinite(_pos_sp_triplet.current.lat) || + !isfinite(_pos_sp_triplet.current.lon) || + !isfinite(_pos_sp_triplet.current.alt)) { + _pos_sp_triplet.current.valid = false; + } } if (_pos_sp_triplet.current.valid) { From 9c627255ccc980270fe56b6c4ddeb494e1ce0f50 Mon Sep 17 00:00:00 2001 From: Johan Jansen Date: Mon, 26 Jan 2015 14:22:36 +0100 Subject: [PATCH 64/73] MPU6000: Increase gyro offset tolerance to 7 dps --- src/drivers/mpu6000/mpu6000.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 168b34ea91..81d156af1d 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -921,18 +921,18 @@ MPU6000::gyro_self_test() if (self_test()) return 1; - /* evaluate gyro offsets, complain if offset -> zero or larger than 6 dps */ - if (fabsf(_gyro_scale.x_offset) > 0.1f || fabsf(_gyro_scale.x_offset) < 0.000001f) + /* evaluate gyro offsets, complain if offset -> zero or larger than 7 dps */ + if (fabsf(_gyro_scale.x_offset) > 0.12f || fabsf(_gyro_scale.x_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f) return 1; - if (fabsf(_gyro_scale.y_offset) > 0.1f || fabsf(_gyro_scale.y_offset) < 0.000001f) + if (fabsf(_gyro_scale.y_offset) > 0.12f || fabsf(_gyro_scale.y_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f) return 1; - if (fabsf(_gyro_scale.z_offset) > 0.1f || fabsf(_gyro_scale.z_offset) < 0.000001f) + if (fabsf(_gyro_scale.z_offset) > 0.12f || fabsf(_gyro_scale.z_offset) < 0.000001f) return 1; if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f) return 1; @@ -941,6 +941,7 @@ MPU6000::gyro_self_test() } + /* perform a self-test comparison to factory trim values. This takes about 200ms and will return OK if the current values are within 14% From b8fade7dcfa98d0963c7f23529168baa64f7fc1a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 26 Jan 2015 20:04:56 +0100 Subject: [PATCH 65/73] MPU6K: Improve gyro self test to allow more realistic deviations from nominal state --- src/drivers/mpu6000/mpu6000.cpp | 31 ++++++++++++++++++++++--------- 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 81d156af1d..1c35bae2d2 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -921,22 +921,35 @@ MPU6000::gyro_self_test() if (self_test()) return 1; - /* evaluate gyro offsets, complain if offset -> zero or larger than 7 dps */ - if (fabsf(_gyro_scale.x_offset) > 0.12f || fabsf(_gyro_scale.x_offset) < 0.000001f) - return 1; - if (fabsf(_gyro_scale.x_scale - 1.0f) > 0.3f) + const float max_offset = 0.34f; + const float max_scale = 0.3f; + + /* evaluate gyro offsets, complain if offset -> zero or larger than 20 dps. */ + if (fabsf(_gyro_scale.x_offset) > max_offset) return 1; - if (fabsf(_gyro_scale.y_offset) > 0.12f || fabsf(_gyro_scale.y_offset) < 0.000001f) - return 1; - if (fabsf(_gyro_scale.y_scale - 1.0f) > 0.3f) + /* evaluate gyro scale, complain if off by more than 30% */ + if (fabsf(_gyro_scale.x_scale - 1.0f) > max_scale) return 1; - if (fabsf(_gyro_scale.z_offset) > 0.12f || fabsf(_gyro_scale.z_offset) < 0.000001f) + if (fabsf(_gyro_scale.y_offset) > max_offset) return 1; - if (fabsf(_gyro_scale.z_scale - 1.0f) > 0.3f) + if (fabsf(_gyro_scale.y_scale - 1.0f) > max_scale) return 1; + if (fabsf(_gyro_scale.z_offset) > max_offset) + return 1; + if (fabsf(_gyro_scale.z_scale - 1.0f) > max_scale) + return 1; + + /* check if all scales are zero */ + if ((fabsf(_gyro_scale.x_offset) < 0.000001f) && + (fabsf(_gyro_scale.y_offset) < 0.000001f) && + (fabsf(_gyro_scale.z_offset) < 0.000001f)) { + /* if all are zero, this device is not calibrated */ + return 1; + } + return 0; } From 52f3fe1d9af53e5f1dd40714aa177fcc4c5e0047 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 26 Jan 2015 20:23:42 +0100 Subject: [PATCH 66/73] Added more docs to offset as suggested by @velocoderaptor, thanks! --- src/drivers/mpu6000/mpu6000.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 1c35bae2d2..2be7582442 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -921,7 +921,17 @@ MPU6000::gyro_self_test() if (self_test()) return 1; + /* + * Maximum deviation of 20 degrees, according to + * http://www.invensense.com/mems/gyro/documents/PS-MPU-6000A-00v3.4.pdf + * Section 6.1, initial ZRO tolerance + */ const float max_offset = 0.34f; + /* 30% scale error is chosen to catch completely faulty units but + * to let some slight scale error pass. Requires a rate table or correlation + * with mag rotations + data fit to + * calibrate properly and is not done by default. + */ const float max_scale = 0.3f; /* evaluate gyro offsets, complain if offset -> zero or larger than 20 dps. */ From e95e09628484875cf65686561eef8434195df96b Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 28 Jan 2015 09:31:42 +0100 Subject: [PATCH 67/73] added references --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 962dc6d4a0..cad6cf3aea 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -35,6 +35,12 @@ * @file mc_pos_control_main.cpp * Multicopter position controller. * + * Original publication for the desired attitude generation: + * Daniel Mellinger and Vijay Kumar. Minimum Snap Trajectory Generation and Control for Quadrotors. + * Int. Conf. on Robotics and Automation, Shanghai, China, May 2011 + * + * Also inspired by https://pixhawk.org/firmware/apps/fw_pos_control_l1 + * * The controller has two loops: P loop for position error and PID loop for velocity error. * Output of velocity controller is thrust vector that splitted to thrust direction * (i.e. rotation matrix for multicopter orientation) and thrust module (i.e. multicopter thrust itself). From 97471bf0aae5c069fe37f063f2a8b5eae08755c9 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Wed, 28 Jan 2015 09:31:42 +0100 Subject: [PATCH 68/73] added references --- src/modules/mc_att_control/mc_att_control_main.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index a094ed2c60..c828f1f942 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -35,6 +35,10 @@ * @file mc_att_control_main.cpp * Multicopter attitude controller. * + * Publication for the desired attitude tracking: + * Daniel Mellinger and Vijay Kumar. Minimum Snap Trajectory Generation and Control for Quadrotors. + * Int. Conf. on Robotics and Automation, Shanghai, China, May 2011. + * * @author Tobias Naegeli * @author Lorenz Meier * @author Anton Babushkin From 5444972347606333dd61206011263e4a2e5d83e8 Mon Sep 17 00:00:00 2001 From: hauptmech Date: Mon, 19 Jan 2015 16:50:52 +1300 Subject: [PATCH 69/73] Add call to access the mcu unique id. Expose via the 'ver' command. This is prep for verifying calibration parameters against the hardware they were gathered on. --- src/modules/systemlib/mcu_version.c | 11 +++++++++-- src/modules/systemlib/mcu_version.h | 11 +++++++++++ src/systemcmds/ver/ver.c | 14 +++++++++++++- 3 files changed, 33 insertions(+), 3 deletions(-) diff --git a/src/modules/systemlib/mcu_version.c b/src/modules/systemlib/mcu_version.c index 4bcf957848..24f4e42076 100644 --- a/src/modules/systemlib/mcu_version.c +++ b/src/modules/systemlib/mcu_version.c @@ -47,7 +47,8 @@ #ifdef CONFIG_ARCH_CHIP_STM32 #include -#define DBGMCU_IDCODE 0xE0042000 +#define DBGMCU_IDCODE 0xE0042000 //STM DocID018909 Rev 8 Sect 38.18 (MCU device ID code) +#define UNIQUE_ID 0x1FFF7A10 //STM DocID018909 Rev 8 Sect 39.1 (Unique device ID Register) #define STM32F40x_41x 0x413 #define STM32F42x_43x 0x419 @@ -57,7 +58,13 @@ #endif - +/** Copy the 96bit MCU Unique ID into the provided pointer */ +void mcu_unique_id(uint32_t *uid_96_bit) +{ + uid_96_bit[0] = getreg32(UNIQUE_ID); + uid_96_bit[1] = getreg32(UNIQUE_ID+4); + uid_96_bit[2] = getreg32(UNIQUE_ID+8); +} int mcu_version(char* rev, char** revstr) { diff --git a/src/modules/systemlib/mcu_version.h b/src/modules/systemlib/mcu_version.h index 1b3d0aba9b..c8a0bf5cda 100644 --- a/src/modules/systemlib/mcu_version.h +++ b/src/modules/systemlib/mcu_version.h @@ -33,6 +33,8 @@ #pragma once +#include + /* magic numbers from reference manual */ enum MCU_REV { MCU_REV_STM32F4_REV_A = 0x1000, @@ -42,6 +44,15 @@ enum MCU_REV { MCU_REV_STM32F4_REV_3 = 0x2001 }; + +/** + * Reports the microcontroller unique id. + * + * This ID is guaranteed to be unique for every mcu. + * @param uid_96_bit A uint32_t[3] array to copy the data to. + */ +__EXPORT void mcu_unique_id(uint32_t *uid_96_bit); + /** * Reports the microcontroller version of the main CPU. * diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 2ead3e6323..087eb52e3d 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -54,6 +54,7 @@ static const char sz_ver_bdate_str[] = "bdate"; static const char sz_ver_gcc_str[] = "gcc"; static const char sz_ver_all_str[] = "all"; static const char mcu_ver_str[] = "mcu"; +static const char mcu_uid_str[] = "uid"; static void usage(const char *reason) { @@ -61,7 +62,7 @@ static void usage(const char *reason) printf("%s\n", reason); } - printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu}\n\n"); + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu|uid}\n\n"); } __EXPORT int ver_main(int argc, char *argv[]); @@ -141,6 +142,17 @@ int ver_main(int argc, char *argv[]) ret = 0; } + if (show_all || !strncmp(argv[1], mcu_uid_str, sizeof(mcu_uid_str))) { + uint32_t uid[3]; + + mcu_unique_id(uid); + + printf("UID: %X:%X:%X \n",uid[0],uid[1],uid[2]); + + ret = 0; + } + + if (ret == 1) { errx(1, "unknown command.\n"); } From 21d3dcb1905432e349f70012ac0a4f79e5e7935a Mon Sep 17 00:00:00 2001 From: hauptmech Date: Wed, 28 Jan 2015 15:40:44 +1300 Subject: [PATCH 70/73] Fix config utility to work with all devices of each type, not just the primary one. --- src/systemcmds/config/config.c | 70 +++++++++++++++++----------------- 1 file changed, 35 insertions(+), 35 deletions(-) diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c index 077bc47c90..9f13edb184 100644 --- a/src/systemcmds/config/config.c +++ b/src/systemcmds/config/config.c @@ -36,7 +36,7 @@ * @author Lorenz Meier * @author Julian Oes * - * config tool. + * config tool. Takes the device name as the first parameter. */ #include @@ -71,18 +71,18 @@ int config_main(int argc, char *argv[]) { if (argc >= 2) { - if (!strcmp(argv[1], "gyro")) { - do_gyro(argc - 2, argv + 2); - } else if (!strcmp(argv[1], "accel")) { - do_accel(argc - 2, argv + 2); - } else if (!strcmp(argv[1], "mag")) { - do_mag(argc - 2, argv + 2); + if (!strncmp(argv[1], "/dev/gyro",9)) { + do_gyro(argc - 1, argv + 1); + } else if (!strncmp(argv[1], "/dev/accel",10)) { + do_accel(argc - 1, argv + 1); + } else if (!strncmp(argv[1], "/dev/mag",8)) { + do_mag(argc - 1, argv + 1); } else { do_device(argc - 1, argv + 1); } } - errx(1, "expected a command, try 'gyro', 'accel', 'mag'"); + errx(1, "expected a device, try '/dev/gyro', '/dev/accel', '/dev/mag'"); } static void @@ -133,41 +133,41 @@ do_gyro(int argc, char *argv[]) { int fd; - fd = open(GYRO_DEVICE_PATH, 0); + fd = open(argv[0], 0); if (fd < 0) { - warn("%s", GYRO_DEVICE_PATH); + warn("%s", argv[0]); errx(1, "FATAL: no gyro found"); } else { int ret; - if (argc == 2 && !strcmp(argv[0], "sampling")) { + if (argc == 3 && !strcmp(argv[1], "sampling")) { /* set the gyro internal sampling rate up to at least i Hz */ - ret = ioctl(fd, GYROIOCSSAMPLERATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, GYROIOCSSAMPLERATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"sampling rate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "rate")) { + } else if (argc == 3 && !strcmp(argv[1], "rate")) { /* set the driver to poll at i Hz */ - ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"pollrate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "range")) { + } else if (argc == 3 && !strcmp(argv[1], "range")) { /* set the range to i dps */ - ret = ioctl(fd, GYROIOCSRANGE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, GYROIOCSRANGE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"range could not be set"); - } else if (argc == 1 && !strcmp(argv[0], "check")) { + } else if (argc == 2 && !strcmp(argv[1], "check")) { ret = ioctl(fd, GYROIOCSELFTEST, 0); if (ret) { @@ -206,41 +206,41 @@ do_mag(int argc, char *argv[]) { int fd; - fd = open(MAG_DEVICE_PATH, 0); + fd = open(argv[0], 0); if (fd < 0) { - warn("%s", MAG_DEVICE_PATH); + warn("%s", argv[0]); errx(1, "FATAL: no magnetometer found"); } else { int ret; - if (argc == 2 && !strcmp(argv[0], "sampling")) { + if (argc == 3 && !strcmp(argv[1], "sampling")) { /* set the mag internal sampling rate up to at least i Hz */ - ret = ioctl(fd, MAGIOCSSAMPLERATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, MAGIOCSSAMPLERATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"sampling rate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "rate")) { + } else if (argc == 3 && !strcmp(argv[1], "rate")) { /* set the driver to poll at i Hz */ - ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"pollrate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "range")) { + } else if (argc == 3 && !strcmp(argv[1], "range")) { /* set the range to i G */ - ret = ioctl(fd, MAGIOCSRANGE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, MAGIOCSRANGE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"range could not be set"); - } else if(argc == 1 && !strcmp(argv[0], "check")) { + } else if(argc == 2 && !strcmp(argv[1], "check")) { ret = ioctl(fd, MAGIOCSELFTEST, 0); if (ret) { @@ -282,41 +282,41 @@ do_accel(int argc, char *argv[]) { int fd; - fd = open(ACCEL_DEVICE_PATH, 0); + fd = open(argv[0], 0); if (fd < 0) { - warn("%s", ACCEL_DEVICE_PATH); + warn("%s", argv[0]); errx(1, "FATAL: no accelerometer found"); } else { int ret; - if (argc == 2 && !strcmp(argv[0], "sampling")) { + if (argc == 3 && !strcmp(argv[1], "sampling")) { /* set the accel internal sampling rate up to at least i Hz */ - ret = ioctl(fd, ACCELIOCSSAMPLERATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, ACCELIOCSSAMPLERATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"sampling rate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "rate")) { + } else if (argc == 3 && !strcmp(argv[1], "rate")) { /* set the driver to poll at i Hz */ - ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, SENSORIOCSPOLLRATE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"pollrate could not be set"); - } else if (argc == 2 && !strcmp(argv[0], "range")) { + } else if (argc == 3 && !strcmp(argv[1], "range")) { /* set the range to i G */ - ret = ioctl(fd, ACCELIOCSRANGE, strtoul(argv[1], NULL, 0)); + ret = ioctl(fd, ACCELIOCSRANGE, strtoul(argv[2], NULL, 0)); if (ret) errx(ret,"range could not be set"); - } else if(argc == 1 && !strcmp(argv[0], "check")) { + } else if(argc == 2 && !strcmp(argv[1], "check")) { ret = ioctl(fd, ACCELIOCSELFTEST, 0); if (ret) { From a3b2c99801a2cdc780cce77e04dd2d924c2c0560 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 27 Jan 2015 12:37:35 -0500 Subject: [PATCH 71/73] A huge developer time saver, J="" make archives This gives warnings about -j1 being forced some places, but it still successfully builds all archvies in parallel. The resulting archives have been tested on the board. It is disabled by default so no functional change unless someone adds J="" or J=8 in front of the make archvies. --- Makefile | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/Makefile b/Makefile index 64c468d31b..b178597056 100644 --- a/Makefile +++ b/Makefile @@ -169,16 +169,18 @@ ifneq ($(filter archives,$(MAKECMDGOALS)),) .NOTPARALLEL: endif +J?=1 + $(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@)) $(ARCHIVE_DIR)%.export: configuration = nsh $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) @$(ECHO) %% Configuring NuttX for $(board) $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) - $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) @$(ECHO) %% Exporting NuttX for $(board) - $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export + $(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export $(Q) $(MKDIR) -p $(dir $@) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) @@ -195,11 +197,11 @@ BOARD = $(BOARDS) menuconfig: $(NUTTX_SRC) @$(ECHO) %% Configuring NuttX for $(BOARD) $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export) - $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean + $(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh) @$(ECHO) %% Running menuconfig for $(BOARD) - $(Q) $(MAKE) -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig + $(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) menuconfig @$(ECHO) %% Saving configuration file $(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig else From 27b2701340648e2fde1992b175abfa591e0eee01 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 28 Jan 2015 09:48:53 +0100 Subject: [PATCH 72/73] temporarily re-enable stack checking, disable some modules to make firmware fit --- makefiles/config_px4fmu-v2_default.mk | 10 +++++----- nuttx-configs/px4fmu-v2/nsh/defconfig | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 3abebd82fa..76457216bd 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -37,11 +37,11 @@ MODULES += drivers/hil # MODULES += drivers/hott/hott_sensors # MODULES += drivers/blinkm MODULES += drivers/airspeed -MODULES += drivers/ets_airspeed +# MODULES += drivers/ets_airspeed MODULES += drivers/meas_airspeed -MODULES += drivers/frsky_telemetry +# MODULES += drivers/frsky_telemetry MODULES += modules/sensors -MODULES += drivers/mkblctrl +# MODULES += drivers/mkblctrl MODULES += drivers/px4flow # @@ -70,7 +70,7 @@ MODULES += modules/commander MODULES += modules/navigator MODULES += modules/mavlink MODULES += modules/gpio_led -MODULES += modules/uavcan +# MODULES += modules/uavcan MODULES += modules/land_detector # @@ -120,7 +120,7 @@ MODULES += lib/launchdetection # # OBC challenge # -MODULES += modules/bottle_drop +# MODULES += modules/bottle_drop # # Demo apps diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig index dedebdfa03..9030a1f022 100644 --- a/nuttx-configs/px4fmu-v2/nsh/defconfig +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig @@ -117,7 +117,7 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y -CONFIG_ARMV7M_STACKCHECK=n +CONFIG_ARMV7M_STACKCHECK=y CONFIG_SERIAL_TERMIOS=y CONFIG_SDIO_DMA=y CONFIG_SDIO_DMAPRIO=0x00010000 From a25dbb3c8e795b90869c480ae5c62c84b8424b3c Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Wed, 28 Jan 2015 11:19:52 +0100 Subject: [PATCH 73/73] Add a compiler coloring tool to highlight warning and errors in the output. --- Tools/make_color.sh | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100755 Tools/make_color.sh diff --git a/Tools/make_color.sh b/Tools/make_color.sh new file mode 100755 index 0000000000..81316a9328 --- /dev/null +++ b/Tools/make_color.sh @@ -0,0 +1,36 @@ +#!/bin/sh +# make_color.sh +# +# Author: Simon Wilks (simon@uaventure.com) +# +# A compiler color coder. +# +# To invoke this script everytime you run make simply create the alias: +# +# alias make='/Tools/make_color.sh' +# +# Color codes: +# +# white "\033[1,37m" +# yellow "\033[1,33m" +# green "\033[1,32m" +# blue "\033[1,34m" +# cyan "\033[1,36m" +# red "\033[1,31m" +# magenta "\033[1,35m" +# black "\033[1,30m" +# darkwhite "\033[0,37m" +# darkyellow "\033[0,33m" +# darkgreen "\033[0,32m" +# darkblue "\033[0,34m" +# darkcyan "\033[0,36m" +# darkred "\033[0,31m" +# darkmagenta "\033[0,35m" +# off "\033[0,0m" +# +OFF="\o033[0m" +WARN="\o033[1;33m" +ERROR="\o033[1;31m" +INFO="\o033[0;37m" + +make ${@} 2>&1 | sed "s/make\[[0-9]\].*/$INFO & $OFF/;s/.*: warning: .*/$WARN & $OFF/;s/.*: error: .*/$ERROR & $OFF/"