From dc600e7d65df3d91fc1dabac33b6e264ef9185df Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 20:58:47 +0200 Subject: [PATCH 01/88] First stab at IOCTL driven offset handling (in PA) for all airspeed sensors. Untested --- src/drivers/drv_airspeed.h | 9 ++++ src/drivers/ets_airspeed/ets_airspeed.cpp | 17 ++++-- src/modules/sensors/sensor_params.c | 2 +- src/modules/sensors/sensors.cpp | 64 ++++++++++------------- 4 files changed, 53 insertions(+), 39 deletions(-) diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h index bffc35c62c..7bb9ee2af1 100644 --- a/src/drivers/drv_airspeed.h +++ b/src/drivers/drv_airspeed.h @@ -57,5 +57,14 @@ #define _AIRSPEEDIOCBASE (0x7700) #define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n)) +#define AIRSPEEDIOCSSCALE __AIRSPEEDIOC(0) +#define AIRSPEEDIOCGSCALE __AIRSPEEDIOC(1) + + +/** airspeed scaling factors; out = (in * Vscale) + offset */ +struct airspeed_scale { + float offset_pa; + float scale; +}; #endif /* _DRV_AIRSPEED_H */ diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index b34d3fa5d9..da449c195a 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -129,7 +129,7 @@ private: bool _sensor_ok; int _measure_ticks; bool _collect_phase; - int _diff_pres_offset; + float _diff_pres_offset; orb_advert_t _airspeed_pub; @@ -358,6 +358,19 @@ ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg) /* XXX implement this */ return -EINVAL; + case AIRSPEEDIOCSSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + _diff_pres_offset = s->offset_pa; + return OK; + } + + case AIRSPEEDIOCGSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + s->offset_pa = _diff_pres_offset; + s->scale = 1.0f; + return OK; + } + default: /* give it to the superclass */ return I2C::ioctl(filp, cmd, arg); @@ -464,8 +477,6 @@ ETSAirspeed::collect() uint16_t diff_pres_pa = val[1] << 8 | val[0]; - // XXX move the parameter read out of the driver. - param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { diff_pres_pa = 0; diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index f6f4d60c76..57f1de1acf 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -68,7 +68,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); -PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667); +PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 1667); PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 1ded14a91c..29f9de883f 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -60,6 +60,7 @@ #include #include #include +#include #include #include @@ -199,7 +200,7 @@ private: float mag_scale[3]; float accel_offset[3]; float accel_scale[3]; - int diff_pres_offset_pa; + float diff_pres_offset_pa; int rc_type; @@ -230,6 +231,8 @@ private: float rc_scale_flaps; float battery_voltage_scaling; + + int airspeed_offset; } _parameters; /**< local copies of interesting parameters */ struct { @@ -278,6 +281,8 @@ private: param_t rc_scale_flaps; param_t battery_voltage_scaling; + + param_t airspeed_offset; } _parameter_handles; /**< handles for interesting parameters */ @@ -551,25 +556,11 @@ Sensors::parameters_update() /* rc values */ for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) { - if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) { - warnx("Failed getting min for chan %d", i); - } - - if (param_get(_parameter_handles.trim[i], &(_parameters.trim[i])) != OK) { - warnx("Failed getting trim for chan %d", i); - } - - if (param_get(_parameter_handles.max[i], &(_parameters.max[i])) != OK) { - warnx("Failed getting max for chan %d", i); - } - - if (param_get(_parameter_handles.rev[i], &(_parameters.rev[i])) != OK) { - warnx("Failed getting rev for chan %d", i); - } - - if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) { - warnx("Failed getting dead zone for chan %d", i); - } + param_get(_parameter_handles.min[i], &(_parameters.min[i])); + param_get(_parameter_handles.trim[i], &(_parameters.trim[i])); + param_get(_parameter_handles.max[i], &(_parameters.max[i])); + param_get(_parameter_handles.rev[i], &(_parameters.rev[i])); + param_get(_parameter_handles.dz[i], &(_parameters.dz[i])); _parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]); @@ -659,21 +650,10 @@ Sensors::parameters_update() warnx("Failed getting mode aux 5 index"); } - if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) { - warnx("Failed getting rc scaling for roll"); - } - - if (param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)) != OK) { - warnx("Failed getting rc scaling for pitch"); - } - - if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) { - warnx("Failed getting rc scaling for yaw"); - } - - if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) { - warnx("Failed getting rc scaling for flaps"); - } + param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)); + param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)); + param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)); + param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)); /* update RC function mappings */ _rc.function[THROTTLE] = _parameters.rc_map_throttle - 1; @@ -1033,6 +1013,20 @@ Sensors::parameter_update_poll(bool forced) close(fd); + fd = open(AIRSPEED_DEVICE_PATH, 0); + + /* this sensor is optional, abort without error */ + + if (fd > 0) { + struct airspeed_scale airscale = { + _parameters.diff_pres_offset_pa, + 1.0f, + }; + + if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) + warn("WARNING: failed to set scale / offsets for airspeed sensor"); + } + #if 0 printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]); printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]); From f87595a056e3688f5582d0315e161cceb16abc77 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 20:59:35 +0200 Subject: [PATCH 02/88] Minor initialization / formatting change --- src/drivers/ets_airspeed/ets_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index da449c195a..0dbbfb4c33 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -196,7 +196,7 @@ ETSAirspeed::ETSAirspeed(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), - _diff_pres_offset(0), + _diff_pres_offset(0.0f), _airspeed_pub(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")), _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")), From 290ca1f9bf973a9ef957cb413930f7aac06054e4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 21:45:59 +0200 Subject: [PATCH 03/88] Reworked airspeed driver to keep most of it abstract --- makefiles/config_px4fmu-v1_default.mk | 2 + src/drivers/airspeed/airspeed.cpp | 378 +++++++++++++++ src/drivers/airspeed/airspeed.h | 169 +++++++ src/drivers/airspeed/module.mk | 38 ++ src/drivers/ets_airspeed/ets_airspeed.cpp | 398 +--------------- src/drivers/meas_airspeed/meas_airspeed.cpp | 482 ++++++++++++++++++++ src/drivers/meas_airspeed/module.mk | 41 ++ 7 files changed, 1124 insertions(+), 384 deletions(-) create mode 100644 src/drivers/airspeed/airspeed.cpp create mode 100644 src/drivers/airspeed/airspeed.h create mode 100644 src/drivers/airspeed/module.mk create mode 100644 src/drivers/meas_airspeed/meas_airspeed.cpp create mode 100644 src/drivers/meas_airspeed/module.mk diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 213eb651b0..a769eb8f22 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -31,7 +31,9 @@ MODULES += drivers/hott_telemetry MODULES += drivers/blinkm MODULES += drivers/mkblctrl MODULES += drivers/md25 +MODULES += drivers/airspeed MODULES += drivers/ets_airspeed +MODULES += drivers/meas_airspeed MODULES += modules/sensors # diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp new file mode 100644 index 0000000000..2c719928a3 --- /dev/null +++ b/src/drivers/airspeed/airspeed.cpp @@ -0,0 +1,378 @@ +/**************************************************************************** + * + * Copyright (C) 2013 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 ets_airspeed.cpp + * @author Simon Wilks + * + * Driver for the Eagle Tree Airspeed V3 connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include + +Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) : + I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), + _num_reports(0), + _next_report(0), + _oldest_report(0), + _reports(nullptr), + _sensor_ok(false), + _measure_ticks(0), + _collect_phase(false), + _diff_pres_offset(0.0f), + _airspeed_pub(-1), + _conversion_interval(conversion_interval), + _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")), + _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")) +{ + // enable debug() calls + _debug_enabled = true; + + // work_cancel in the dtor will explode if we don't do this... + memset(&_work, 0, sizeof(_work)); +} + +Airspeed::~Airspeed() +{ + /* make sure we are truly inactive */ + stop(); + + /* free any existing reports */ + if (_reports != nullptr) + delete[] _reports; +} + +int +Airspeed::init() +{ + int ret = ERROR; + + /* do I2C init (and probe) first */ + if (I2C::init() != OK) + goto out; + + /* allocate basic report buffers */ + _num_reports = 2; + _reports = new struct differential_pressure_s[_num_reports]; + + for (unsigned i = 0; i < _num_reports; i++) + _reports[i].max_differential_pressure_pa = 0; + + if (_reports == nullptr) + goto out; + + _oldest_report = _next_report = 0; + + /* get a publish handle on the airspeed topic */ + memset(&_reports[0], 0, sizeof(_reports[0])); + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); + + if (_airspeed_pub < 0) + debug("failed to create airspeed sensor object. Did you start uOrb?"); + + ret = OK; + /* sensor is ok, but we don't really know if it is within range */ + _sensor_ok = true; +out: + return ret; +} + +int +Airspeed::probe() +{ + return measure(); +} + +int +Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + + case SENSORIOCSPOLLRATE: { + switch (arg) { + + /* switching to manual polling */ + case SENSOR_POLLRATE_MANUAL: + stop(); + _measure_ticks = 0; + return OK; + + /* external signalling (DRDY) not supported */ + case SENSOR_POLLRATE_EXTERNAL: + + /* zero would be bad */ + case 0: + return -EINVAL; + + /* set default/max polling rate */ + case SENSOR_POLLRATE_MAX: + case SENSOR_POLLRATE_DEFAULT: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* set interval for next measurement to minimum legal value */ + _measure_ticks = USEC2TICK(_conversion_interval); + + /* if we need to start the poll state machine, do it */ + if (want_start) + start(); + + return OK; + } + + /* adjust to a legal polling interval in Hz */ + default: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* convert hz to tick interval via microseconds */ + unsigned ticks = USEC2TICK(1000000 / arg); + + /* check against maximum rate */ + if (ticks < USEC2TICK(_conversion_interval)) + return -EINVAL; + + /* update interval for next measurement */ + _measure_ticks = ticks; + + /* if we need to start the poll state machine, do it */ + if (want_start) + start(); + + return OK; + } + } + } + + case SENSORIOCGPOLLRATE: + if (_measure_ticks == 0) + return SENSOR_POLLRATE_MANUAL; + + return (1000 / _measure_ticks); + + case SENSORIOCSQUEUEDEPTH: { + /* add one to account for the sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct differential_pressure_s *buf = new struct differential_pressure_s[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _reports; + _num_reports = arg; + _reports = buf; + start(); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _num_reports - 1; + + case SENSORIOCRESET: + /* XXX implement this */ + return -EINVAL; + + case AIRSPEEDIOCSSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + _diff_pres_offset = s->offset_pa; + return OK; + } + + case AIRSPEEDIOCGSCALE: { + struct airspeed_scale *s = (struct airspeed_scale*)arg; + s->offset_pa = _diff_pres_offset; + s->scale = 1.0f; + return OK; + } + + default: + /* give it to the superclass */ + return I2C::ioctl(filp, cmd, arg); + } +} + +ssize_t +Airspeed::read(struct file *filp, char *buffer, size_t buflen) +{ + unsigned count = buflen / sizeof(struct differential_pressure_s); + int ret = 0; + + /* buffer must be large enough */ + if (count < 1) + return -ENOSPC; + + /* if automatic measurement is enabled */ + if (_measure_ticks > 0) { + + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the workq thread while we are doing this; + * we are careful to avoid racing with them. + */ + while (count--) { + if (_oldest_report != _next_report) { + memcpy(buffer, _reports + _oldest_report, sizeof(*_reports)); + ret += sizeof(_reports[0]); + INCREMENT(_oldest_report, _num_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement - run one conversion */ + /* XXX really it'd be nice to lock against other readers here */ + do { + _oldest_report = _next_report = 0; + + /* trigger a measurement */ + if (OK != measure()) { + ret = -EIO; + break; + } + + /* wait for it to complete */ + usleep(_conversion_interval); + + /* run the collection phase */ + if (OK != collect()) { + ret = -EIO; + break; + } + + /* state machine will have generated a report, copy it out */ + memcpy(buffer, _reports, sizeof(*_reports)); + ret = sizeof(*_reports); + + } while (0); + + return ret; +} + +void +Airspeed::start() +{ + /* reset the report ring and state machine */ + _collect_phase = false; + _oldest_report = _next_report = 0; + + /* schedule a cycle to start things */ + work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1); + + /* notify about state change */ + struct subsystem_info_s info = { + true, + true, + true, + SUBSYSTEM_TYPE_DIFFPRESSURE + }; + static orb_advert_t pub = -1; + + if (pub > 0) { + orb_publish(ORB_ID(subsystem_info), pub, &info); + + } else { + pub = orb_advertise(ORB_ID(subsystem_info), &info); + } +} + +void +Airspeed::stop() +{ + work_cancel(HPWORK, &_work); +} + +void +Airspeed::cycle_trampoline(void *arg) +{ + Airspeed *dev = (Airspeed *)arg; + + dev->cycle(); +} + +void +Airspeed::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); + perf_print_counter(_buffer_overflows); + warnx("poll interval: %u ticks", _measure_ticks); + warnx("report queue: %u (%u/%u @ %p)", + _num_reports, _oldest_report, _next_report, _reports); +} diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h new file mode 100644 index 0000000000..3cc03ede97 --- /dev/null +++ b/src/drivers/airspeed/airspeed.h @@ -0,0 +1,169 @@ +/**************************************************************************** + * + * Copyright (C) 2013 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 airspeed.h + * @author Simon Wilks + * + * Generic driver for airspeed sensors connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +/* Default I2C bus */ +#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION + +/* Oddly, ERROR is not defined for C++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + +#ifndef CONFIG_SCHED_WORKQUEUE +# error This requires CONFIG_SCHED_WORKQUEUE. +#endif + +class Airspeed : public device::I2C +{ +public: + Airspeed(int bus, int address, unsigned conversion_interval); + virtual ~Airspeed(); + + virtual int init(); + + virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + /** + * Diagnostics - print some basic information about the driver. + */ + void print_info(); + +protected: + virtual int probe(); + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + virtual void cycle() = 0; + virtual int measure() = 0; + virtual int collect() = 0; + + work_s _work; + unsigned _num_reports; + volatile unsigned _next_report; + volatile unsigned _oldest_report; + differential_pressure_s *_reports; + bool _sensor_ok; + int _measure_ticks; + bool _collect_phase; + float _diff_pres_offset; + + orb_advert_t _airspeed_pub; + + unsigned _conversion_interval; + + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; + + + /** + * Test whether the device supported by the driver is present at a + * specific address. + * + * @param address The I2C bus address to probe. + * @return True if the device is present. + */ + int probe_address(uint8_t address); + + /** + * Initialise the automatic measurement state machine and start it. + * + * @note This function is called at open and error time. It might make sense + * to make it more aggressive about resetting the bus in case of errors. + */ + void start(); + + /** + * Stop the automatic measurement state machine. + */ + void stop(); + + /** + * 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); + +}; + +/* helper macro for handling report buffer indices */ +#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) + diff --git a/src/drivers/airspeed/module.mk b/src/drivers/airspeed/module.mk new file mode 100644 index 0000000000..4eef061610 --- /dev/null +++ b/src/drivers/airspeed/module.mk @@ -0,0 +1,38 @@ +############################################################################ +# +# Copyright (c) 2013 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. +# +############################################################################ + +# +# Makefile to build the generic airspeed driver. +# + +SRCS = airspeed.cpp diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 0dbbfb4c33..3e3930715e 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -72,9 +72,7 @@ #include #include #include - -/* Default I2C bus */ -#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION +#include /* I2C bus address */ #define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ @@ -91,349 +89,33 @@ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ -/* Oddly, ERROR is not defined for C++ */ -#ifdef ERROR -# undef ERROR -#endif -static const int ERROR = -1; - -#ifndef CONFIG_SCHED_WORKQUEUE -# error This requires CONFIG_SCHED_WORKQUEUE. -#endif - -class ETSAirspeed : public device::I2C +class ETSAirspeed : public Airspeed { public: ETSAirspeed(int bus, int address = I2C_ADDRESS); virtual ~ETSAirspeed(); - virtual int init(); - - virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); - virtual int ioctl(struct file *filp, int cmd, unsigned long arg); - - /** - * Diagnostics - print some basic information about the driver. - */ - void print_info(); - protected: - virtual int probe(); - -private: - work_s _work; - unsigned _num_reports; - volatile unsigned _next_report; - volatile unsigned _oldest_report; - differential_pressure_s *_reports; - bool _sensor_ok; - int _measure_ticks; - bool _collect_phase; - float _diff_pres_offset; - - orb_advert_t _airspeed_pub; - - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _buffer_overflows; - - - /** - * Test whether the device supported by the driver is present at a - * specific address. - * - * @param address The I2C bus address to probe. - * @return True if the device is present. - */ - int probe_address(uint8_t address); - - /** - * Initialise the automatic measurement state machine and start it. - * - * @note This function is called at open and error time. It might make sense - * to make it more aggressive about resetting the bus in case of errors. - */ - void start(); - - /** - * Stop the automatic measurement state machine. - */ - void stop(); /** * Perform a poll cycle; collect from the previous measurement * and start a new one. */ - void cycle(); - 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); - + virtual void cycle(); + virtual int measure(); + virtual int collect(); }; -/* helper macro for handling report buffer indices */ -#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) - /* * Driver 'main' command. */ extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]); -ETSAirspeed::ETSAirspeed(int bus, int address) : - I2C("ETSAirspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), - _num_reports(0), - _next_report(0), - _oldest_report(0), - _reports(nullptr), - _sensor_ok(false), - _measure_ticks(0), - _collect_phase(false), - _diff_pres_offset(0.0f), - _airspeed_pub(-1), - _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")), - _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ets_airspeed_buffer_overflows")) +ETSAirspeed::ETSAirspeed(int bus, int address) : Airspeed(bus, address, + CONVERSION_INTERVAL) { - // enable debug() calls - _debug_enabled = true; - // work_cancel in the dtor will explode if we don't do this... - memset(&_work, 0, sizeof(_work)); -} - -ETSAirspeed::~ETSAirspeed() -{ - /* make sure we are truly inactive */ - stop(); - - /* free any existing reports */ - if (_reports != nullptr) - delete[] _reports; -} - -int -ETSAirspeed::init() -{ - int ret = ERROR; - - /* do I2C init (and probe) first */ - if (I2C::init() != OK) - goto out; - - /* allocate basic report buffers */ - _num_reports = 2; - _reports = new struct differential_pressure_s[_num_reports]; - - for (unsigned i = 0; i < _num_reports; i++) - _reports[i].max_differential_pressure_pa = 0; - - if (_reports == nullptr) - goto out; - - _oldest_report = _next_report = 0; - - /* get a publish handle on the airspeed topic */ - memset(&_reports[0], 0, sizeof(_reports[0])); - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); - - if (_airspeed_pub < 0) - debug("failed to create airspeed sensor object. Did you start uOrb?"); - - ret = OK; - /* sensor is ok, but we don't really know if it is within range */ - _sensor_ok = true; -out: - return ret; -} - -int -ETSAirspeed::probe() -{ - return measure(); -} - -int -ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg) -{ - switch (cmd) { - - case SENSORIOCSPOLLRATE: { - switch (arg) { - - /* switching to manual polling */ - case SENSOR_POLLRATE_MANUAL: - stop(); - _measure_ticks = 0; - return OK; - - /* external signalling (DRDY) not supported */ - case SENSOR_POLLRATE_EXTERNAL: - - /* zero would be bad */ - case 0: - return -EINVAL; - - /* set default/max polling rate */ - case SENSOR_POLLRATE_MAX: - case SENSOR_POLLRATE_DEFAULT: { - /* do we need to start internal polling? */ - bool want_start = (_measure_ticks == 0); - - /* set interval for next measurement to minimum legal value */ - _measure_ticks = USEC2TICK(CONVERSION_INTERVAL); - - /* if we need to start the poll state machine, do it */ - if (want_start) - start(); - - return OK; - } - - /* adjust to a legal polling interval in Hz */ - default: { - /* do we need to start internal polling? */ - bool want_start = (_measure_ticks == 0); - - /* convert hz to tick interval via microseconds */ - unsigned ticks = USEC2TICK(1000000 / arg); - - /* check against maximum rate */ - if (ticks < USEC2TICK(CONVERSION_INTERVAL)) - return -EINVAL; - - /* update interval for next measurement */ - _measure_ticks = ticks; - - /* if we need to start the poll state machine, do it */ - if (want_start) - start(); - - return OK; - } - } - } - - case SENSORIOCGPOLLRATE: - if (_measure_ticks == 0) - return SENSOR_POLLRATE_MANUAL; - - return (1000 / _measure_ticks); - - case SENSORIOCSQUEUEDEPTH: { - /* add one to account for the sentinel in the ring */ - arg++; - - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) - return -EINVAL; - - /* allocate new buffer */ - struct differential_pressure_s *buf = new struct differential_pressure_s[arg]; - - if (nullptr == buf) - return -ENOMEM; - - /* reset the measurement state machine with the new buffer, free the old */ - stop(); - delete[] _reports; - _num_reports = arg; - _reports = buf; - start(); - - return OK; - } - - case SENSORIOCGQUEUEDEPTH: - return _num_reports - 1; - - case SENSORIOCRESET: - /* XXX implement this */ - return -EINVAL; - - case AIRSPEEDIOCSSCALE: { - struct airspeed_scale *s = (struct airspeed_scale*)arg; - _diff_pres_offset = s->offset_pa; - return OK; - } - - case AIRSPEEDIOCGSCALE: { - struct airspeed_scale *s = (struct airspeed_scale*)arg; - s->offset_pa = _diff_pres_offset; - s->scale = 1.0f; - return OK; - } - - default: - /* give it to the superclass */ - return I2C::ioctl(filp, cmd, arg); - } -} - -ssize_t -ETSAirspeed::read(struct file *filp, char *buffer, size_t buflen) -{ - unsigned count = buflen / sizeof(struct differential_pressure_s); - int ret = 0; - - /* buffer must be large enough */ - if (count < 1) - return -ENOSPC; - - /* if automatic measurement is enabled */ - if (_measure_ticks > 0) { - - /* - * While there is space in the caller's buffer, and reports, copy them. - * Note that we may be pre-empted by the workq thread while we are doing this; - * we are careful to avoid racing with them. - */ - while (count--) { - if (_oldest_report != _next_report) { - memcpy(buffer, _reports + _oldest_report, sizeof(*_reports)); - ret += sizeof(_reports[0]); - INCREMENT(_oldest_report, _num_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; - } - - /* manual measurement - run one conversion */ - /* XXX really it'd be nice to lock against other readers here */ - do { - _oldest_report = _next_report = 0; - - /* trigger a measurement */ - if (OK != measure()) { - ret = -EIO; - break; - } - - /* wait for it to complete */ - usleep(CONVERSION_INTERVAL); - - /* run the collection phase */ - if (OK != collect()) { - ret = -EIO; - break; - } - - /* state machine will have generated a report, copy it out */ - memcpy(buffer, _reports, sizeof(*_reports)); - ret = sizeof(*_reports); - - } while (0); - - return ret; } int @@ -516,47 +198,6 @@ ETSAirspeed::collect() return ret; } -void -ETSAirspeed::start() -{ - /* reset the report ring and state machine */ - _collect_phase = false; - _oldest_report = _next_report = 0; - - /* schedule a cycle to start things */ - work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1); - - /* notify about state change */ - struct subsystem_info_s info = { - true, - true, - true, - SUBSYSTEM_TYPE_DIFFPRESSURE - }; - static orb_advert_t pub = -1; - - if (pub > 0) { - orb_publish(ORB_ID(subsystem_info), pub, &info); - - } else { - pub = orb_advertise(ORB_ID(subsystem_info), &info); - } -} - -void -ETSAirspeed::stop() -{ - work_cancel(HPWORK, &_work); -} - -void -ETSAirspeed::cycle_trampoline(void *arg) -{ - ETSAirspeed *dev = (ETSAirspeed *)arg; - - dev->cycle(); -} - void ETSAirspeed::cycle() { @@ -582,7 +223,7 @@ ETSAirspeed::cycle() /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, - (worker_t)&ETSAirspeed::cycle_trampoline, + (worker_t)&Airspeed::cycle_trampoline, this, _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); @@ -600,22 +241,11 @@ ETSAirspeed::cycle() /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, &_work, - (worker_t)&ETSAirspeed::cycle_trampoline, + (worker_t)&Airspeed::cycle_trampoline, this, USEC2TICK(CONVERSION_INTERVAL)); } -void -ETSAirspeed::print_info() -{ - perf_print_counter(_sample_perf); - perf_print_counter(_comms_errors); - perf_print_counter(_buffer_overflows); - printf("poll interval: %u ticks\n", _measure_ticks); - printf("report queue: %u (%u/%u @ %p)\n", - _num_reports, _oldest_report, _next_report, _reports); -} - /** * Local functions in support of the shell command. */ @@ -790,11 +420,11 @@ info() static void ets_airspeed_usage() { - fprintf(stderr, "usage: ets_airspeed command [options]\n"); - fprintf(stderr, "options:\n"); - fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT); - fprintf(stderr, "command:\n"); - fprintf(stderr, "\tstart|stop|reset|test|info\n"); + warnx("usage: ets_airspeed command [options]"); + warnx("options:"); + warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT); + warnx("command:"); + warnx("\tstart|stop|reset|test|info"); } int diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp new file mode 100644 index 0000000000..4fa02a20b7 --- /dev/null +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -0,0 +1,482 @@ +/**************************************************************************** + * + * Copyright (C) 2013 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 meas_airspeed.cpp + * @author Lorenz Meier + * @author Simon Wilks + * + * Driver for the MEAS Spec series connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include + +/* Default I2C bus */ +#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION + +/* I2C bus address */ +#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ + +/* Register address */ +#define READ_CMD 0x07 /* Read the data */ + +/** + * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. + * You can set this value to 12 if you want a zero reading below 15km/h. + */ +#define MIN_ACCURATE_DIFF_PRES_PA 0 + +/* Measurement rate is 100Hz */ +#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ + +class MEASAirspeed : public Airspeed +{ +public: + MEASAirspeed(int bus, int address = I2C_ADDRESS); + virtual ~MEASAirspeed(); + +protected: + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + virtual void cycle(); + virtual int measure(); + virtual int collect(); + +}; + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); + +MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, + CONVERSION_INTERVAL) +{ + +} + +int +MEASAirspeed::measure() +{ + int ret; + + /* + * Send the command to begin a measurement. + */ + uint8_t cmd = READ_CMD; + ret = transfer(&cmd, 1, nullptr, 0); + + if (OK != ret) { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } + + ret = OK; + + return ret; +} + +int +MEASAirspeed::collect() +{ + int ret = -EIO; + + /* read from the sensor */ + uint8_t val[2] = {0, 0}; + + perf_begin(_sample_perf); + + ret = transfer(nullptr, 0, &val[0], 2); + + if (ret < 0) { + log("error reading from sensor: %d", ret); + return ret; + } + + uint16_t diff_pres_pa = val[1] << 8 | val[0]; + + if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + diff_pres_pa = 0; + + } else { + diff_pres_pa -= _diff_pres_offset; + } + + // XXX we may want to smooth out the readings to remove noise. + + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].differential_pressure_pa = diff_pres_pa; + + // Track maximum differential pressure measured (so we can work out top speed). + if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + } + + /* announce the airspeed if needed, just publish else */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + + /* post a report to the ring - note, not locked */ + INCREMENT(_next_report, _num_reports); + + /* if we are running up against the oldest report, toss it */ + if (_next_report == _oldest_report) { + perf_count(_buffer_overflows); + INCREMENT(_oldest_report, _num_reports); + } + + /* notify anyone waiting for data */ + poll_notify(POLLIN); + + ret = OK; + + perf_end(_sample_perf); + + return ret; +} + +void +MEASAirspeed::cycle() +{ + /* collection phase? */ + if (_collect_phase) { + + /* perform collection */ + if (OK != collect()) { + log("collection error"); + /* restart the measurement state machine */ + start(); + return; + } + + /* next phase is measurement */ + _collect_phase = false; + + /* + * Is there a collect->measure gap? + */ + if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { + + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&Airspeed::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); + + return; + } + } + + /* measurement phase */ + if (OK != measure()) + log("measure error"); + + /* next phase is collection */ + _collect_phase = true; + + /* schedule a fresh cycle call when the measurement is done */ + work_queue(HPWORK, + &_work, + (worker_t)&Airspeed::cycle_trampoline, + this, + USEC2TICK(CONVERSION_INTERVAL)); +} + +/** + * Local functions in support of the shell command. + */ +namespace meas_airspeed +{ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +const int ERROR = -1; + +MEASAirspeed *g_dev; + +void start(int i2c_bus); +void stop(); +void test(); +void reset(); +void info(); + +/** + * Start the driver. + */ +void +start(int i2c_bus) +{ + int fd; + + if (g_dev != nullptr) + errx(1, "already started"); + + /* create the driver */ + g_dev = new MEASAirspeed(i2c_bus); + + if (g_dev == nullptr) + goto fail; + + if (OK != g_dev->init()) + goto fail; + + /* set the poll rate to default, starts automatic data collection */ + fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + goto fail; + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + goto fail; + + exit(0); + +fail: + + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + } + + errx(1, "driver start failed"); +} + +/** + * Stop the driver + */ +void +stop() +{ + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + + } else { + errx(1, "driver not running"); + } + + exit(0); +} + +/** + * Perform some basic functional tests on the driver; + * make sure we can collect data from the sensor in polled + * and automatic modes. + */ +void +test() +{ + struct differential_pressure_s report; + ssize_t sz; + int ret; + + int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "%s open failed (try 'meas_airspeed start' if the driver is not running", AIRSPEED_DEVICE_PATH); + + /* do a simple demand read */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) + err(1, "immediate read failed"); + + warnx("single read"); + warnx("diff pressure: %d pa", report.differential_pressure_pa); + + /* start the sensor polling at 2Hz */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) + errx(1, "failed to set 2Hz poll rate"); + + /* read the sensor 5x and report each value */ + for (unsigned i = 0; i < 5; i++) { + struct pollfd fds; + + /* wait for data to be ready */ + fds.fd = fd; + fds.events = POLLIN; + ret = poll(&fds, 1, 2000); + + if (ret != 1) + errx(1, "timed out waiting for sensor data"); + + /* now go get it */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) + err(1, "periodic read failed"); + + warnx("periodic read %u", i); + warnx("diff pressure: %d pa", report.differential_pressure_pa); + } + + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "failed "); + + if (ioctl(fd, SENSORIOCRESET, 0) < 0) + err(1, "driver reset failed"); + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + err(1, "driver poll restart failed"); + + exit(0); +} + +/** + * Print a little info about the driver. + */ +void +info() +{ + if (g_dev == nullptr) + errx(1, "driver not running"); + + printf("state @ %p\n", g_dev); + g_dev->print_info(); + + exit(0); +} + +} // namespace + + +static void +meas_airspeed_usage() +{ + warnx("usage: meas_airspeed command [options]"); + warnx("options:"); + warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT); + warnx("command:"); + warnx("\tstart|stop|reset|test|info"); +} + +int +meas_airspeed_main(int argc, char *argv[]) +{ + int i2c_bus = PX4_I2C_BUS_DEFAULT; + + int i; + + for (i = 1; i < argc; i++) { + if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { + if (argc > i + 1) { + i2c_bus = atoi(argv[i + 1]); + } + } + } + + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) + meas_airspeed::start(i2c_bus); + + /* + * Stop the driver + */ + if (!strcmp(argv[1], "stop")) + meas_airspeed::stop(); + + /* + * Test the driver/device. + */ + if (!strcmp(argv[1], "test")) + meas_airspeed::test(); + + /* + * Reset the driver. + */ + if (!strcmp(argv[1], "reset")) + meas_airspeed::reset(); + + /* + * Print driver information. + */ + if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) + meas_airspeed::info(); + + meas_airspeed_usage(); + exit(0); +} diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk new file mode 100644 index 0000000000..ddcd54351f --- /dev/null +++ b/src/drivers/meas_airspeed/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# Copyright (c) 2013 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. +# +############################################################################ + +# +# Makefile to build the MEAS Spec airspeed sensor driver. +# + +MODULE_COMMAND = meas_airspeed +MODULE_STACKSIZE = 1024 + +SRCS = meas_airspeed.cpp From 7fe2aa27974f93810727b0a59658ed760c6ad591 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 14 Jul 2013 11:22:20 +0200 Subject: [PATCH 04/88] Fixed last few compile errors, ready for testing --- src/drivers/airspeed/airspeed.cpp | 2 +- src/drivers/airspeed/airspeed.h | 4 +- src/drivers/ets_airspeed/ets_airspeed.cpp | 1 - src/drivers/meas_airspeed/meas_airspeed.cpp | 189 +++++++++++--------- 4 files changed, 108 insertions(+), 88 deletions(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 2c719928a3..5a8157debc 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -134,7 +134,7 @@ Airspeed::init() _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); if (_airspeed_pub < 0) - debug("failed to create airspeed sensor object. Did you start uOrb?"); + warnx("failed to create airspeed sensor object. Did you start uOrb?"); ret = OK; /* sensor is ok, but we don't really know if it is within range */ diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h index 3cc03ede97..89dfb22d70 100644 --- a/src/drivers/airspeed/airspeed.h +++ b/src/drivers/airspeed/airspeed.h @@ -86,7 +86,7 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -class Airspeed : public device::I2C +class __EXPORT Airspeed : public device::I2C { public: Airspeed(int bus, int address, unsigned conversion_interval); @@ -100,7 +100,7 @@ public: /** * Diagnostics - print some basic information about the driver. */ - void print_info(); + virtual void print_info(); protected: virtual int probe(); diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 3e3930715e..a24bd78a5e 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -93,7 +93,6 @@ class ETSAirspeed : public Airspeed { public: ETSAirspeed(int bus, int address = I2C_ADDRESS); - virtual ~ETSAirspeed(); protected: diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 4fa02a20b7..0c9142d631 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -37,6 +37,15 @@ * @author Simon Wilks * * Driver for the MEAS Spec series connected via I2C. + * + * Supported sensors: + * + * - MS4525DO (http://www.meas-spec.com/downloads/MS4525DO.pdf) + * - untested: MS5525DSO (http://www.meas-spec.com/downloads/MS5525DSO.pdf) + * + * Interface application notes: + * + * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/application-notes.aspx#) */ #include @@ -79,8 +88,10 @@ /* Default I2C bus */ #define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION -/* I2C bus address */ -#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ +/* I2C bus address is 1010001x */ +#define I2C_ADDRESS_MS4525DO 0x51 /* 7-bit address. */ +/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ +#define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ /* Register address */ #define READ_CMD 0x07 /* Read the data */ @@ -97,8 +108,7 @@ class MEASAirspeed : public Airspeed { public: - MEASAirspeed(int bus, int address = I2C_ADDRESS); - virtual ~MEASAirspeed(); + MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO); protected: @@ -126,122 +136,122 @@ MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, int MEASAirspeed::measure() { - int ret; + // int ret; - /* - * Send the command to begin a measurement. - */ - uint8_t cmd = READ_CMD; - ret = transfer(&cmd, 1, nullptr, 0); + // /* + // * Send the command to begin a measurement. + // */ + // uint8_t cmd = READ_CMD; + // ret = transfer(&cmd, 1, nullptr, 0); - if (OK != ret) { - perf_count(_comms_errors); - log("i2c::transfer returned %d", ret); - return ret; - } + // if (OK != ret) { + // perf_count(_comms_errors); + // log("i2c::transfer returned %d", ret); + // return ret; + // } - ret = OK; + // ret = OK; - return ret; + // return ret; } int MEASAirspeed::collect() { - int ret = -EIO; + // int ret = -EIO; - /* read from the sensor */ - uint8_t val[2] = {0, 0}; + // /* read from the sensor */ + // uint8_t val[2] = {0, 0}; - perf_begin(_sample_perf); + // perf_begin(_sample_perf); - ret = transfer(nullptr, 0, &val[0], 2); + // ret = transfer(nullptr, 0, &val[0], 2); - if (ret < 0) { - log("error reading from sensor: %d", ret); - return ret; - } + // if (ret < 0) { + // log("error reading from sensor: %d", ret); + // return ret; + // } - uint16_t diff_pres_pa = val[1] << 8 | val[0]; + // uint16_t diff_pres_pa = val[1] << 8 | val[0]; - if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - diff_pres_pa = 0; + // if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + // diff_pres_pa = 0; - } else { - diff_pres_pa -= _diff_pres_offset; - } + // } else { + // diff_pres_pa -= _diff_pres_offset; + // } - // XXX we may want to smooth out the readings to remove noise. + // // XXX we may want to smooth out the readings to remove noise. - _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].differential_pressure_pa = diff_pres_pa; + // _reports[_next_report].timestamp = hrt_absolute_time(); + // _reports[_next_report].differential_pressure_pa = diff_pres_pa; - // Track maximum differential pressure measured (so we can work out top speed). - if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; - } + // // Track maximum differential pressure measured (so we can work out top speed). + // if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + // _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + // } - /* announce the airspeed if needed, just publish else */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + // /* announce the airspeed if needed, just publish else */ + // orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); - /* post a report to the ring - note, not locked */ - INCREMENT(_next_report, _num_reports); + // /* post a report to the ring - note, not locked */ + // INCREMENT(_next_report, _num_reports); - /* if we are running up against the oldest report, toss it */ - if (_next_report == _oldest_report) { - perf_count(_buffer_overflows); - INCREMENT(_oldest_report, _num_reports); - } + // /* if we are running up against the oldest report, toss it */ + // if (_next_report == _oldest_report) { + // perf_count(_buffer_overflows); + // INCREMENT(_oldest_report, _num_reports); + // } - /* notify anyone waiting for data */ - poll_notify(POLLIN); + // /* notify anyone waiting for data */ + // poll_notify(POLLIN); - ret = OK; + // ret = OK; - perf_end(_sample_perf); + // perf_end(_sample_perf); - return ret; + // return ret; } void MEASAirspeed::cycle() { - /* collection phase? */ - if (_collect_phase) { + // /* collection phase? */ + // if (_collect_phase) { - /* perform collection */ - if (OK != collect()) { - log("collection error"); - /* restart the measurement state machine */ - start(); - return; - } + // /* perform collection */ + // if (OK != collect()) { + // log("collection error"); + // /* restart the measurement state machine */ + // start(); + // return; + // } - /* next phase is measurement */ - _collect_phase = false; + // /* next phase is measurement */ + // _collect_phase = false; - /* - * Is there a collect->measure gap? - */ - if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { + // /* + // * Is there a collect->measure gap? + // */ + // if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { - /* schedule a fresh cycle call when we are ready to measure again */ - work_queue(HPWORK, - &_work, - (worker_t)&Airspeed::cycle_trampoline, - this, - _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); + // /* schedule a fresh cycle call when we are ready to measure again */ + // work_queue(HPWORK, + // &_work, + // (worker_t)&Airspeed::cycle_trampoline, + // this, + // _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); - return; - } - } + // return; + // } + // } - /* measurement phase */ - if (OK != measure()) - log("measure error"); + // /* measurement phase */ + // if (OK != measure()) + // log("measure error"); - /* next phase is collection */ - _collect_phase = true; + // /* next phase is collection */ + // _collect_phase = true; /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, @@ -282,12 +292,23 @@ start(int i2c_bus) if (g_dev != nullptr) errx(1, "already started"); - /* create the driver */ - g_dev = new MEASAirspeed(i2c_bus); + /* create the driver, try the MS4525DO first */ + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) goto fail; + /* try the MS5525DSO next if init fails */ + if (OK != g_dev->init()) + delete g_dev; + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); + + /* check if the MS5525DSO was instantiated */ + if (g_dev == nullptr) + goto fail; + + /* both versions failed if the init for the MS5525DSO fails, give up */ if (OK != g_dev->init()) goto fail; From 08ddbbc23e5ee40c95cc838c08e946c7ac063698 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 14 Jul 2013 21:12:09 +0200 Subject: [PATCH 05/88] WIP on MEAS bringup, ETS airspeed sensors should be operational --- src/drivers/meas_airspeed/meas_airspeed.cpp | 202 ++++++++++++-------- 1 file changed, 121 insertions(+), 81 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 0c9142d631..6603d3452d 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -45,7 +45,7 @@ * * Interface application notes: * - * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/application-notes.aspx#) + * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf) */ #include @@ -94,7 +94,12 @@ #define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ /* Register address */ -#define READ_CMD 0x07 /* Read the data */ +#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ +#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */ +#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */ +#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */ +#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ +#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */ /** * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. @@ -136,122 +141,122 @@ MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, int MEASAirspeed::measure() { - // int ret; + int ret; - // /* - // * Send the command to begin a measurement. - // */ - // uint8_t cmd = READ_CMD; - // ret = transfer(&cmd, 1, nullptr, 0); + /* + * Send the command to begin a measurement. + */ + uint8_t cmd = ADDR_RESET_CMD; + ret = transfer(&cmd, 1, nullptr, 0); - // if (OK != ret) { - // perf_count(_comms_errors); - // log("i2c::transfer returned %d", ret); - // return ret; - // } + if (OK != ret) { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } - // ret = OK; + ret = OK; - // return ret; + return ret; } int MEASAirspeed::collect() { - // int ret = -EIO; + int ret = -EIO; - // /* read from the sensor */ - // uint8_t val[2] = {0, 0}; + /* read from the sensor */ + uint8_t val[2] = {0, 0}; - // perf_begin(_sample_perf); + perf_begin(_sample_perf); - // ret = transfer(nullptr, 0, &val[0], 2); + ret = transfer(nullptr, 0, &val[0], 2); - // if (ret < 0) { - // log("error reading from sensor: %d", ret); - // return ret; - // } + if (ret < 0) { + log("error reading from sensor: %d", ret); + return ret; + } - // uint16_t diff_pres_pa = val[1] << 8 | val[0]; + uint16_t diff_pres_pa = val[1] << 8 | val[0]; - // if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - // diff_pres_pa = 0; + if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + diff_pres_pa = 0; - // } else { - // diff_pres_pa -= _diff_pres_offset; - // } + } else { + diff_pres_pa -= _diff_pres_offset; + } - // // XXX we may want to smooth out the readings to remove noise. + // XXX we may want to smooth out the readings to remove noise. - // _reports[_next_report].timestamp = hrt_absolute_time(); - // _reports[_next_report].differential_pressure_pa = diff_pres_pa; + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].differential_pressure_pa = diff_pres_pa; - // // Track maximum differential pressure measured (so we can work out top speed). - // if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - // _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; - // } + // Track maximum differential pressure measured (so we can work out top speed). + if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + } - // /* announce the airspeed if needed, just publish else */ - // orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); + /* announce the airspeed if needed, just publish else */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); - // /* post a report to the ring - note, not locked */ - // INCREMENT(_next_report, _num_reports); + /* post a report to the ring - note, not locked */ + INCREMENT(_next_report, _num_reports); - // /* if we are running up against the oldest report, toss it */ - // if (_next_report == _oldest_report) { - // perf_count(_buffer_overflows); - // INCREMENT(_oldest_report, _num_reports); - // } + /* if we are running up against the oldest report, toss it */ + if (_next_report == _oldest_report) { + perf_count(_buffer_overflows); + INCREMENT(_oldest_report, _num_reports); + } - // /* notify anyone waiting for data */ - // poll_notify(POLLIN); + /* notify anyone waiting for data */ + poll_notify(POLLIN); - // ret = OK; + ret = OK; - // perf_end(_sample_perf); + perf_end(_sample_perf); - // return ret; + return ret; } void MEASAirspeed::cycle() { - // /* collection phase? */ - // if (_collect_phase) { + /* collection phase? */ + if (_collect_phase) { - // /* perform collection */ - // if (OK != collect()) { - // log("collection error"); - // /* restart the measurement state machine */ - // start(); - // return; - // } + /* perform collection */ + if (OK != collect()) { + log("collection error"); + /* restart the measurement state machine */ + start(); + return; + } - // /* next phase is measurement */ - // _collect_phase = false; + /* next phase is measurement */ + _collect_phase = false; - // /* - // * Is there a collect->measure gap? - // */ - // if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { + /* + * Is there a collect->measure gap? + */ + if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { - // /* schedule a fresh cycle call when we are ready to measure again */ - // work_queue(HPWORK, - // &_work, - // (worker_t)&Airspeed::cycle_trampoline, - // this, - // _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&Airspeed::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); - // return; - // } - // } + return; + } + } - // /* measurement phase */ - // if (OK != measure()) - // log("measure error"); + /* measurement phase */ + if (OK != measure()) + log("measure error"); - // /* next phase is collection */ - // _collect_phase = true; + /* next phase is collection */ + _collect_phase = true; /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, @@ -293,7 +298,42 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver, try the MS4525DO first */ - g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + + { + int bus = PX4_I2C_BUS_EXPANSION; + //delete g_dev; + + // XXX hack scan all addresses + for (int i = 1; i < 0xFF / 2; i++) { + warnx("scanning addr (7 bit): %0x", i); + g_dev = new MEASAirspeed(bus, i); + warnx("probing"); + if (OK == g_dev->init()) { + warnx("SUCCESS!"); + exit(0); + } else { + delete g_dev; + } + + } + + // bus = PX4_I2C_BUS_ESC; + + // for (int i = 1; i < 0xFF / 2; i++) { + // warnx("scanning addr (7 bit): %0x", i); + // g_dev = new MEASAirspeed(bus, i); + // if (OK == g_dev->init()) { + // warnx("SUCCESS!"); + // exit(0); + // } else { + // delete g_dev; + // } + + // } + + exit(1); +} /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) From 0f19de53119e5d89b2520f6906ab50fc9d3a3b28 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 21 Jul 2013 11:27:52 +0200 Subject: [PATCH 06/88] Ensured correct pointer init --- src/modules/sensors/sensors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index b2a6c6a790..5722d2fdf7 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -391,7 +391,7 @@ namespace sensors #endif static const int ERROR = -1; -Sensors *g_sensors; +Sensors *g_sensors = nullptr; } Sensors::Sensors() : From dc5bcdda761e5f8f4f7f26a600f02df007ab1df6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 21 Jul 2013 11:29:10 +0200 Subject: [PATCH 07/88] Hotfix: Made accel calibration a bit more forgiving about motion threshold --- src/modules/commander/accelerometer_calibration.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c index dc653a079d..6a304896a3 100644 --- a/src/modules/commander/accelerometer_calibration.c +++ b/src/modules/commander/accelerometer_calibration.c @@ -268,8 +268,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; /* EMA time constant in seconds*/ float ema_len = 0.2f; - /* set "still" threshold to 0.1 m/s^2 */ - float still_thr2 = pow(0.1f, 2); + /* set "still" threshold to 0.25 m/s^2 */ + float still_thr2 = pow(0.25f, 2); /* set accel error threshold to 5m/s^2 */ float accel_err_thr = 5.0f; /* still time required in us */ From 97f732ccf1e05f55ae2e48ef9d21c8e9b7b57510 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 22 Jul 2013 09:19:59 +0200 Subject: [PATCH 08/88] Fixed up ets driver (not tested, WIP on meas driver) --- src/drivers/ets_airspeed/ets_airspeed.cpp | 2 +- src/drivers/meas_airspeed/meas_airspeed.cpp | 46 ++++++++++----------- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index a24bd78a5e..2e32ed3341 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -282,7 +282,7 @@ start(int i2c_bus) if (g_dev == nullptr) goto fail; - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) goto fail; /* set the poll rate to default, starts automatic data collection */ diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 6603d3452d..f31dc857de 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -278,7 +278,7 @@ namespace meas_airspeed #endif const int ERROR = -1; -MEASAirspeed *g_dev; +MEASAirspeed *g_dev = nullptr; void start(int i2c_bus); void stop(); @@ -300,16 +300,33 @@ start(int i2c_bus) /* create the driver, try the MS4525DO first */ //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); - { + int bus = PX4_I2C_BUS_EXPANSION; //delete g_dev; // XXX hack scan all addresses + for (int i = 0x20 / 2; i < 0xFE / 2; i++) { + warnx("scanning addr (7 bit): 0x%02x", i); + g_dev = new MEASAirspeed(bus, i); + warnx("probing"); + if (OK == g_dev->Airspeed::init()) { + warnx("SUCCESS!"); + usleep(200000); + exit(0); + } else { + warnx("FAIL!"); + usleep(200000); + delete g_dev; + } + + } + + bus = PX4_I2C_BUS_ESC; + for (int i = 1; i < 0xFF / 2; i++) { warnx("scanning addr (7 bit): %0x", i); g_dev = new MEASAirspeed(bus, i); - warnx("probing"); - if (OK == g_dev->init()) { + if (OK == g_dev->Airspeed::init()) { warnx("SUCCESS!"); exit(0); } else { @@ -318,29 +335,12 @@ start(int i2c_bus) } - // bus = PX4_I2C_BUS_ESC; - - // for (int i = 1; i < 0xFF / 2; i++) { - // warnx("scanning addr (7 bit): %0x", i); - // g_dev = new MEASAirspeed(bus, i); - // if (OK == g_dev->init()) { - // warnx("SUCCESS!"); - // exit(0); - // } else { - // delete g_dev; - // } - - // } - - exit(1); -} - /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) goto fail; /* try the MS5525DSO next if init fails */ - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) delete g_dev; g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); @@ -349,7 +349,7 @@ start(int i2c_bus) goto fail; /* both versions failed if the init for the MS5525DSO fails, give up */ - if (OK != g_dev->init()) + if (OK != g_dev->Airspeed::init()) goto fail; /* set the poll rate to default, starts automatic data collection */ From edcd25b5ed15502b32c9dadc1fbbbfa552f0b74f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 22 Jul 2013 10:24:35 +0200 Subject: [PATCH 09/88] Airspeed sensor driver operational, needs cleanup / testing --- src/drivers/meas_airspeed/meas_airspeed.cpp | 59 ++++----------------- 1 file changed, 11 insertions(+), 48 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index f31dc857de..5dcc97e6fa 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -85,13 +85,10 @@ #include -/* Default I2C bus */ -#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION - /* I2C bus address is 1010001x */ -#define I2C_ADDRESS_MS4525DO 0x51 /* 7-bit address. */ +#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */ /* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ -#define I2C_ADDRESS_MS5525DSO 0x77 /* 7-bit address, addr. pin pulled low */ +#define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ /* Register address */ #define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ @@ -298,59 +295,25 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver, try the MS4525DO first */ - //g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); - - - int bus = PX4_I2C_BUS_EXPANSION; - //delete g_dev; - - // XXX hack scan all addresses - for (int i = 0x20 / 2; i < 0xFE / 2; i++) { - warnx("scanning addr (7 bit): 0x%02x", i); - g_dev = new MEASAirspeed(bus, i); - warnx("probing"); - if (OK == g_dev->Airspeed::init()) { - warnx("SUCCESS!"); - usleep(200000); - exit(0); - } else { - warnx("FAIL!"); - usleep(200000); - delete g_dev; - } - - } - - bus = PX4_I2C_BUS_ESC; - - for (int i = 1; i < 0xFF / 2; i++) { - warnx("scanning addr (7 bit): %0x", i); - g_dev = new MEASAirspeed(bus, i); - if (OK == g_dev->Airspeed::init()) { - warnx("SUCCESS!"); - exit(0); - } else { - delete g_dev; - } - - } + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) goto fail; /* try the MS5525DSO next if init fails */ - if (OK != g_dev->Airspeed::init()) + if (OK != g_dev->Airspeed::init()) { delete g_dev; g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); - /* check if the MS5525DSO was instantiated */ - if (g_dev == nullptr) - goto fail; + /* check if the MS5525DSO was instantiated */ + if (g_dev == nullptr) + goto fail; - /* both versions failed if the init for the MS5525DSO fails, give up */ - if (OK != g_dev->Airspeed::init()) - goto fail; + /* both versions failed if the init for the MS5525DSO fails, give up */ + if (OK != g_dev->Airspeed::init()) + goto fail; + } /* set the poll rate to default, starts automatic data collection */ fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); From 830dff9b6a6fc7c53a0974b80b2d2582bda2df0a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 25 Jul 2013 11:16:25 +0200 Subject: [PATCH 10/88] First operational test version, provides correct readings (as far as tests were possible) --- src/drivers/meas_airspeed/meas_airspeed.cpp | 40 ++++++++++----------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 5dcc97e6fa..7a2e22c018 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -91,18 +91,10 @@ #define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ /* Register address */ -#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */ -#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */ -#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */ -#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */ -#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */ -#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */ - -/** - * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. - * You can set this value to 12 if you want a zero reading below 15km/h. - */ -#define MIN_ACCURATE_DIFF_PRES_PA 0 +#define ADDR_READ_MR 0x00 /* write to this address to start conversion */ +#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */ +#define ADDR_READ_DF3 0x01 +#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ @@ -143,7 +135,7 @@ MEASAirspeed::measure() /* * Send the command to begin a measurement. */ - uint8_t cmd = ADDR_RESET_CMD; + uint8_t cmd = 0; ret = transfer(&cmd, 1, nullptr, 0); if (OK != ret) { @@ -163,7 +155,8 @@ MEASAirspeed::collect() int ret = -EIO; /* read from the sensor */ - uint8_t val[2] = {0, 0}; + uint8_t val[4] = {0, 0, 0, 0}; + perf_begin(_sample_perf); @@ -174,18 +167,24 @@ MEASAirspeed::collect() return ret; } - uint16_t diff_pres_pa = val[1] << 8 | val[0]; + uint8_t status = val[0] & 0xC0; - if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { - diff_pres_pa = 0; - - } else { - diff_pres_pa -= _diff_pres_offset; + if (status == 2) { + log("err: stale data"); + } else if (status == 3) { + log("err: fault"); } + uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); + uint16_t temp = (val[3] & 0xE0) << 8 | val[2]; + + diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); + diff_pres_pa -= _diff_pres_offset; + // XXX we may want to smooth out the readings to remove noise. _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].temperature = temp; _reports[_next_report].differential_pressure_pa = diff_pres_pa; // Track maximum differential pressure measured (so we can work out top speed). @@ -403,6 +402,7 @@ test() warnx("periodic read %u", i); warnx("diff pressure: %d pa", report.differential_pressure_pa); + warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature); } errx(0, "PASS"); From 95dde5f1bed21d1a36a065c94c961a8f216a10b0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 26 Jul 2013 18:24:37 +0200 Subject: [PATCH 11/88] Implemented config command, fixed a number range set / get issues for some sensor drivers, fixed gyro calibration --- makefiles/config_px4fmu-v1_default.mk | 1 + src/drivers/mpu6000/mpu6000.cpp | 44 ++- src/modules/commander/commander.c | 10 +- src/systemcmds/config/config.c | 413 ++++++++++++++++++++++++++ src/systemcmds/config/module.mk | 44 +++ 5 files changed, 496 insertions(+), 16 deletions(-) create mode 100644 src/systemcmds/config/config.c create mode 100644 src/systemcmds/config/module.mk diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 74be1cd23f..1d9c0e5273 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -50,6 +50,7 @@ MODULES += systemcmds/pwm MODULES += systemcmds/reboot MODULES += systemcmds/top MODULES += systemcmds/tests +MODULES += systemcmds/config # # General system control diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 8d9054a387..1fd6cb17e7 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 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 @@ -35,6 +35,9 @@ * @file mpu6000.cpp * * Driver for the Invensense MPU6000 connected via SPI. + * + * @author Andrew Tridgell + * @author Pat Hickey */ #include @@ -191,6 +194,7 @@ private: orb_advert_t _gyro_topic; unsigned _reads; + unsigned _sample_rate; perf_counter_t _sample_perf; /** @@ -314,6 +318,7 @@ MPU6000::MPU6000(int bus, spi_dev_e device) : _gyro_range_rad_s(0.0f), _gyro_topic(-1), _reads(0), + _sample_rate(500), _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")) { // disable debug() calls @@ -366,10 +371,6 @@ MPU6000::init() return ret; } - /* advertise sensor topics */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report); - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report); - // Chip reset write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET); up_udelay(10000); @@ -384,7 +385,7 @@ MPU6000::init() // SAMPLE RATE //write_reg(MPUREG_SMPLRT_DIV, 0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz - _set_sample_rate(200); // default sample rate = 200Hz + _set_sample_rate(_sample_rate); // default sample rate = 200Hz usleep(1000); // FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter) @@ -463,10 +464,18 @@ MPU6000::init() /* do CDev init for the gyro device node, keep it optional */ int gyro_ret = _gyro->init(); + /* ensure we got real values to share */ + measure(); + if (gyro_ret != OK) { _gyro_topic = -1; + } else { + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report); } + /* advertise sensor topics */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report); + return ret; } @@ -509,6 +518,7 @@ MPU6000::_set_sample_rate(uint16_t desired_sample_rate_hz) if(div>200) div=200; if(div<1) div=1; write_reg(MPUREG_SMPLRT_DIV, div-1); + _sample_rate = 1000 / div; } /* @@ -660,8 +670,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return -EINVAL; - case ACCELIOCSSAMPLERATE: case ACCELIOCGSAMPLERATE: + return _sample_rate; + + case ACCELIOCSSAMPLERATE: _set_sample_rate(arg); return OK; @@ -689,12 +701,13 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return OK; case ACCELIOCSRANGE: - case ACCELIOCGRANGE: /* XXX not implemented */ // XXX change these two values on set: // _accel_range_scale = (9.81f / 4096.0f); - // _accel_range_rad_s = 8.0f * 9.81f; + // _accel_range_m_s2 = 8.0f * 9.81f; return -EINVAL; + case ACCELIOCGRANGE: + return _accel_range_m_s2; case ACCELIOCSELFTEST: return self_test(); @@ -718,10 +731,12 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) case SENSORIOCRESET: return ioctl(filp, cmd, arg); - case GYROIOCSSAMPLERATE: case GYROIOCGSAMPLERATE: - _set_sample_rate(arg); - return OK; + return _sample_rate; + + case GYROIOCSSAMPLERATE: + _set_sample_rate(arg); + return OK; case GYROIOCSLOWPASS: case GYROIOCGLOWPASS: @@ -739,12 +754,13 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) return OK; case GYROIOCSRANGE: - case GYROIOCGRANGE: /* XXX not implemented */ // XXX change these two values on set: // _gyro_range_scale = xx - // _gyro_range_m_s2 = xx + // _gyro_range_rad_s = xx return -EINVAL; + case GYROIOCGRANGE: + return _gyro_range_rad_s; case GYROIOCSELFTEST: return self_test(); diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index 8e5e367120..e9d1f39540 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -587,6 +587,8 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) close(fd); + int errcount = 0; + while (calibration_counter < calibration_count) { /* wait blocking for new data */ @@ -602,8 +604,12 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) calibration_counter++; } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry"); + errcount++; + } + + if (errcount > 1000) { + /* any persisting poll error is a reason to abort */ + mavlink_log_info(mavlink_fd, "permanent gyro error, aborted."); return; } } diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c new file mode 100644 index 0000000000..c4b03bbff6 --- /dev/null +++ b/src/systemcmds/config/config.c @@ -0,0 +1,413 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * 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 config.c + * @author Lorenz Meier + * + * config tool. + */ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include "systemlib/systemlib.h" +#include "systemlib/err.h" + +__EXPORT int config_main(int argc, char *argv[]); + +static void do_gyro(int argc, char *argv[]); +static void do_accel(int argc, char *argv[]); +static void do_mag(int argc, char *argv[]); + +int +config_main(int argc, char *argv[]) +{ + if (argc >= 2) { + if (!strcmp(argv[1], "gyro")) { + if (argc >= 3) { + do_gyro(argc - 2, argv + 2); + } else { + errx(1, "not enough parameters."); + } + } + + if (!strcmp(argv[1], "accel")) { + if (argc >= 3) { + do_accel(argc - 2, argv + 2); + } else { + errx(1, "not enough parameters."); + } + } + + if (!strcmp(argv[1], "mag")) { + if (argc >= 3) { + do_mag(argc - 2, argv + 2); + } else { + errx(1, "not enough parameters."); + } + } + } + + errx(1, "expected a command, try 'gyro', 'accel', 'mag'"); +} + +static void +do_gyro(int argc, char *argv[]) +{ + int fd; + + fd = open(GYRO_DEVICE_PATH, 0); + + if (fd < 0) { + warn("%s", GYRO_DEVICE_PATH); + errx(1, "FATAL: no gyro found"); + + } else { + + if (argc >= 2) { + + char* end; + int i = strtol(argv[1],&end,10); + + if (!strcmp(argv[0], "sampling")) { + + /* set the accel internal sampling rate up to at leat i Hz */ + ioctl(fd, GYROIOCSSAMPLERATE, i); + + } else if (!strcmp(argv[0], "rate")) { + + /* set the driver to poll at i Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, i); + } else if (!strcmp(argv[0], "range")) { + + /* set the range to i dps */ + ioctl(fd, GYROIOCSRANGE, i); + } + + } else if (!(argc > 0 && !strcmp(argv[0], "info"))) { + warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2000' to set measurement range to 2000 dps\n\t"); + } + + int srate = ioctl(fd, GYROIOCGSAMPLERATE, 0); + int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0); + int range = ioctl(fd, GYROIOCGRANGE, 0); + + warnx("gyro: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d dps", srate, prate, range); + + close(fd); + } + + exit(0); +} + +static void +do_mag(int argc, char *argv[]) +{ + exit(0); +} + +static void +do_accel(int argc, char *argv[]) +{ + int fd; + + fd = open(ACCEL_DEVICE_PATH, 0); + + if (fd < 0) { + warn("%s", ACCEL_DEVICE_PATH); + errx(1, "FATAL: no accelerometer found"); + + } else { + + if (argc >= 2) { + + char* end; + int i = strtol(argv[1],&end,10); + + if (!strcmp(argv[0], "sampling")) { + + /* set the accel internal sampling rate up to at leat i Hz */ + ioctl(fd, ACCELIOCSSAMPLERATE, i); + + } else if (!strcmp(argv[0], "rate")) { + + /* set the driver to poll at i Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, i); + } else if (!strcmp(argv[0], "range")) { + + /* set the range to i dps */ + ioctl(fd, ACCELIOCSRANGE, i); + } + } else if (!(argc > 0 && !strcmp(argv[0], "info"))) { + warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2' to set measurement range to 2 G\n\t"); + } + + int srate = ioctl(fd, ACCELIOCGSAMPLERATE, 0); + int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0); + int range = ioctl(fd, ACCELIOCGRANGE, 0); + + warnx("accel: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d m/s", srate, prate, range); + + close(fd); + } + + exit(0); +} + +// static void +// do_load(const char* param_file_name) +// { +// int fd = open(param_file_name, O_RDONLY); + +// if (fd < 0) +// err(1, "open '%s'", param_file_name); + +// int result = param_load(fd); +// close(fd); + +// if (result < 0) { +// errx(1, "error importing from '%s'", param_file_name); +// } + +// exit(0); +// } + +// static void +// do_import(const char* param_file_name) +// { +// int fd = open(param_file_name, O_RDONLY); + +// if (fd < 0) +// err(1, "open '%s'", param_file_name); + +// int result = param_import(fd); +// close(fd); + +// if (result < 0) +// errx(1, "error importing from '%s'", param_file_name); + +// exit(0); +// } + +// static void +// do_show(const char* search_string) +// { +// printf(" + = saved, * = unsaved\n"); +// param_foreach(do_show_print, search_string, false); + +// exit(0); +// } + +// static void +// do_show_print(void *arg, param_t param) +// { +// int32_t i; +// float f; +// const char *search_string = (const char*)arg; + +// /* print nothing if search string is invalid and not matching */ +// if (!(arg == NULL || (!strcmp(search_string, param_name(param))))) { +// /* param not found */ +// return; +// } + +// printf("%c %s: ", +// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), +// param_name(param)); + +// /* +// * This case can be expanded to handle printing common structure types. +// */ + +// switch (param_type(param)) { +// case PARAM_TYPE_INT32: +// if (!param_get(param, &i)) { +// printf("%d\n", i); +// return; +// } + +// break; + +// case PARAM_TYPE_FLOAT: +// if (!param_get(param, &f)) { +// printf("%4.4f\n", (double)f); +// return; +// } + +// break; + +// case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX: +// printf("\n", 0 + param_type(param), param_size(param)); +// return; + +// default: +// printf("\n", 0 + param_type(param)); +// return; +// } + +// printf("\n", param); +// } + +// static void +// do_set(const char* name, const char* val) +// { +// int32_t i; +// float f; +// param_t param = param_find(name); + +// /* set nothing if parameter cannot be found */ +// if (param == PARAM_INVALID) { +// param not found +// errx(1, "Error: Parameter %s not found.", name); +// } + +// printf("%c %s: ", +// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), +// param_name(param)); + +// /* +// * Set parameter if type is known and conversion from string to value turns out fine +// */ + +// switch (param_type(param)) { +// case PARAM_TYPE_INT32: +// if (!param_get(param, &i)) { +// printf("curr: %d", i); + +// /* convert string */ +// char* end; +// i = strtol(val,&end,10); +// param_set(param, &i); +// printf(" -> new: %d\n", i); + +// } + +// break; + +// case PARAM_TYPE_FLOAT: +// if (!param_get(param, &f)) { +// printf("curr: %4.4f", (double)f); + +// /* convert string */ +// char* end; +// f = strtod(val,&end); +// param_set(param, &f); +// printf(" -> new: %f\n", f); + +// } + +// break; + +// default: +// errx(1, "\n", 0 + param_type(param)); +// } + +// exit(0); +// } + +// static void +// do_compare(const char* name, const char* val) +// { +// int32_t i; +// float f; +// param_t param = param_find(name); + +// /* set nothing if parameter cannot be found */ +// if (param == PARAM_INVALID) { +// /* param not found */ +// errx(1, "Error: Parameter %s not found.", name); +// } + +// /* +// * Set parameter if type is known and conversion from string to value turns out fine +// */ + +// int ret = 1; + +// switch (param_type(param)) { +// case PARAM_TYPE_INT32: +// if (!param_get(param, &i)) { + +// /* convert string */ +// char* end; +// int j = strtol(val,&end,10); +// if (i == j) { +// printf(" %d: ", i); +// ret = 0; +// } + +// } + +// break; + +// case PARAM_TYPE_FLOAT: +// if (!param_get(param, &f)) { + +// /* convert string */ +// char* end; +// float g = strtod(val, &end); +// if (fabsf(f - g) < 1e-7f) { +// printf(" %4.4f: ", (double)f); +// ret = 0; +// } +// } + +// break; + +// default: +// errx(1, "\n", 0 + param_type(param)); +// } + +// if (ret == 0) { +// printf("%c %s: equal\n", +// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), +// param_name(param)); +// } + +// exit(ret); +// } diff --git a/src/systemcmds/config/module.mk b/src/systemcmds/config/module.mk new file mode 100644 index 0000000000..0a75810b0c --- /dev/null +++ b/src/systemcmds/config/module.mk @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 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. +# +############################################################################ + +# +# Build the config tool. +# + +MODULE_COMMAND = config +SRCS = config.c + +MODULE_STACKSIZE = 4096 + +MAXOPTIMIZATION = -Os + From f3bfbd87b1f6faef6bac75c9f94b590bb8b504b6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Fri, 7 Jun 2013 14:02:18 -0400 Subject: [PATCH 12/88] Added sine test. --- src/drivers/md25/md25.cpp | 38 ++++++++++++++++++++++++++++++++++ src/drivers/md25/md25.hpp | 3 +++ src/drivers/md25/md25_main.cpp | 18 ++++++++++++++++ 3 files changed, 59 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 71932ad65d..f9f5d70ab5 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -45,6 +45,7 @@ #include "md25.hpp" #include #include +#include #include #include @@ -550,4 +551,41 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) return 0; } +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) +{ + printf("md25 sine: starting\n"); + + // setup + MD25 md25("/dev/md25", bus, address); + + // print status + char buf[200]; + md25.status(buf, sizeof(buf)); + printf("%s\n", buf); + + // setup for test + md25.setSpeedRegulation(true); + md25.setTimeout(true); + float dt = 0.1; + float amplitude = 0.2; + float t = 0; + float omega = 0.1; + + // sine wave for motor 1 + md25.resetEncoders(); + while (true) { + float prev_revolution = md25.getRevolutions1(); + md25.setMotor1Speed(amplitude*sinf(omega*t)); + usleep(1000000 * dt); + t += dt; + float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + md25.readData(); + if (t > 2.0f) break; + } + md25.setMotor1Speed(0); + + printf("md25 sine complete\n"); + return 0; +} + // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index e77511b163..cac3ffd293 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -290,4 +290,7 @@ private: // unit testing int md25Test(const char *deviceName, uint8_t bus, uint8_t address); +// sine testing +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address); + // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index e62c46b0d7..701452f2d5 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -136,6 +136,24 @@ int md25_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "sine")) { + + if (argc < 4) { + printf("usage: md25 sine bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + md25Sine(deviceName, bus, address); + + exit(0); + } + if (!strcmp(argv[1], "probe")) { if (argc < 4) { printf("usage: md25 probe bus address\n"); From 764310620837461857d511144738a521e3840f97 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 15 Jun 2013 16:37:15 -0400 Subject: [PATCH 13/88] Added log print ability to md25 driver. --- src/drivers/md25/md25.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index f9f5d70ab5..4e7e2694a6 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -49,6 +49,7 @@ #include #include +#include // registers enum { @@ -73,6 +74,9 @@ enum { REG_COMMAND_RW, }; +// File descriptors +static int mavlink_fd; + MD25::MD25(const char *deviceName, int bus, uint16_t address, uint32_t speed) : I2C("MD25", deviceName, bus, address, speed), @@ -579,6 +583,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) usleep(1000000 * dt); t += dt; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; } From 42f09c4b547052d9fe2ef49f40a2df6910cf75b1 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 22 Jun 2013 13:41:38 -0400 Subject: [PATCH 14/88] Working on sysid. Added debug values. --- src/drivers/md25/BlockSysIdent.cpp | 8 ++++++++ src/drivers/md25/BlockSysIdent.hpp | 10 +++++++++ src/drivers/md25/md25.cpp | 33 +++++++++++++++++++++++++++--- 3 files changed, 48 insertions(+), 3 deletions(-) create mode 100644 src/drivers/md25/BlockSysIdent.cpp create mode 100644 src/drivers/md25/BlockSysIdent.hpp diff --git a/src/drivers/md25/BlockSysIdent.cpp b/src/drivers/md25/BlockSysIdent.cpp new file mode 100644 index 0000000000..23b0724d8c --- /dev/null +++ b/src/drivers/md25/BlockSysIdent.cpp @@ -0,0 +1,8 @@ +#include "BlockSysIdent.hpp" + +BlockSysIdent::BlockSysIdent() : + Block(NULL, "SYSID"), + _freq(this, "FREQ"), + _ampl(this, "AMPL") +{ +} diff --git a/src/drivers/md25/BlockSysIdent.hpp b/src/drivers/md25/BlockSysIdent.hpp new file mode 100644 index 0000000000..270635f407 --- /dev/null +++ b/src/drivers/md25/BlockSysIdent.hpp @@ -0,0 +1,10 @@ +#include +#include + +class BlockSysIdent : public control::Block { +public: + BlockSysIdent(); +private: + control::BlockParam _freq; + control::BlockParam _ampl; +}; diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 4e7e2694a6..13d5c7eeb3 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -46,11 +46,16 @@ #include #include #include +#include #include #include #include +#include +#include +#include + // registers enum { // RW: read/write @@ -572,17 +577,39 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setTimeout(true); float dt = 0.1; float amplitude = 0.2; - float t = 0; float omega = 0.1; + // input signal + control::UOrbPublication input_signal(NULL, + ORB_ID(debug_key_value)); + strncpy(input_signal.key, "md25 in ", 10); + input_signal.timestamp_ms = hrt_absolute_time(); + input_signal.value = 0; + + // output signal + control::UOrbPublication output_signal(NULL, + ORB_ID(debug_key_value)); + strncpy(output_signal.key, "md25 out ", 10); + output_signal.timestamp_ms = hrt_absolute_time(); + output_signal.value = 0; + // sine wave for motor 1 md25.resetEncoders(); while (true) { float prev_revolution = md25.getRevolutions1(); - md25.setMotor1Speed(amplitude*sinf(omega*t)); usleep(1000000 * dt); - t += dt; + + // input + uint64_t timestamp = hrt_absolute_time(); + float t = timestamp/1000; + input_signal.timestamp_ms = timestamp; + input_signal.value = amplitude*sinf(omega*t); + md25.setMotor1Speed(input_signal.value); + + // output + output_signal.timestamp_ms = timestamp; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; + output_signal.value = speed_rpm; mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; From e7cc6e71ad5d53d940a0e5c6961e5ea6c3a59e27 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 22 Jun 2013 13:45:12 -0400 Subject: [PATCH 15/88] Added pub update. --- src/drivers/md25/md25.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 13d5c7eeb3..582b871c78 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -605,11 +605,13 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) input_signal.timestamp_ms = timestamp; input_signal.value = amplitude*sinf(omega*t); md25.setMotor1Speed(input_signal.value); + input_signal.update(); // output output_signal.timestamp_ms = timestamp; float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; output_signal.value = speed_rpm; + output_signal.update(); mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); if (t > 2.0f) break; From f2a0cce958db1c97eb70d43c3151992ccaed4cab Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:21:17 -0400 Subject: [PATCH 16/88] Fixed timing issues. --- src/drivers/md25/md25.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 582b871c78..7a1e7b7f47 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -577,7 +577,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setTimeout(true); float dt = 0.1; float amplitude = 0.2; - float omega = 0.1; + float frequency = 0.3; // input signal control::UOrbPublication input_signal(NULL, @@ -601,9 +601,9 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // input uint64_t timestamp = hrt_absolute_time(); - float t = timestamp/1000; + float t = timestamp/1000000; input_signal.timestamp_ms = timestamp; - input_signal.value = amplitude*sinf(omega*t); + input_signal.value = amplitude*sinf(2*M_PI*frequency*t); md25.setMotor1Speed(input_signal.value); input_signal.update(); From 78ef6f5265d5f4e84d4e36be37fc7329587df0a3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:31:23 -0400 Subject: [PATCH 17/88] Changed final time. --- src/drivers/md25/md25.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 7a1e7b7f47..375072bb03 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -578,6 +578,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) float dt = 0.1; float amplitude = 0.2; float frequency = 0.3; + float t_final = 30.0; // input signal control::UOrbPublication input_signal(NULL, @@ -614,7 +615,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) output_signal.update(); mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); - if (t > 2.0f) break; + if (t > t_final) break; } md25.setMotor1Speed(0); From 76d086e0773bda8252b9a59b737b902ddc52b59f Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 15:58:58 -0400 Subject: [PATCH 18/88] Working with debug messages. --- src/drivers/md25/md25.cpp | 49 +++++++++++++++++++++------------------ 1 file changed, 26 insertions(+), 23 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 375072bb03..4cb005721c 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -579,43 +579,46 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) float amplitude = 0.2; float frequency = 0.3; float t_final = 30.0; + float prev_revolution = md25.getRevolutions1(); - // input signal - control::UOrbPublication input_signal(NULL, + // debug publication + control::UOrbPublication debug_msg(NULL, ORB_ID(debug_key_value)); - strncpy(input_signal.key, "md25 in ", 10); - input_signal.timestamp_ms = hrt_absolute_time(); - input_signal.value = 0; - - // output signal - control::UOrbPublication output_signal(NULL, - ORB_ID(debug_key_value)); - strncpy(output_signal.key, "md25 out ", 10); - output_signal.timestamp_ms = hrt_absolute_time(); - output_signal.value = 0; // sine wave for motor 1 md25.resetEncoders(); while (true) { - float prev_revolution = md25.getRevolutions1(); - usleep(1000000 * dt); // input uint64_t timestamp = hrt_absolute_time(); float t = timestamp/1000000; - input_signal.timestamp_ms = timestamp; - input_signal.value = amplitude*sinf(2*M_PI*frequency*t); - md25.setMotor1Speed(input_signal.value); - input_signal.update(); + + float input_value = amplitude*sinf(2*M_PI*frequency*t); + md25.setMotor1Speed(input_value); // output - output_signal.timestamp_ms = timestamp; - float speed_rpm = 60*(md25.getRevolutions1() - prev_revolution)/dt; - output_signal.value = speed_rpm; - output_signal.update(); - mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)speed_rpm); md25.readData(); + float current_revolution = md25.getRevolutions1(); + float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; + float prev_revolution = current_revolution; + mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); + + // send input message + strncpy(debug_msg.key, "md25 in ", sizeof(10)); + debug_msg.timestamp_ms = 1000*timestamp; + debug_msg.value = input_value; + debug_msg.update(); + + // send output message + strncpy(debug_msg.key, "md25 out ", sizeof(10)); + debug_msg.timestamp_ms = 1000*timestamp; + debug_msg.value = output_speed_rpm;; + debug_msg.update(); + if (t > t_final) break; + + // sleep + usleep(1000000 * dt); } md25.setMotor1Speed(0); From 77c084a4cf6d5ac1131fae493230fcea2b11700c Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 16:00:27 -0400 Subject: [PATCH 19/88] Fixed typo with strncpy. --- src/drivers/md25/md25.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 4cb005721c..f265ec4515 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -604,13 +604,13 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message - strncpy(debug_msg.key, "md25 in ", sizeof(10)); + strncpy(debug_msg.key, "md25 in ", 10); debug_msg.timestamp_ms = 1000*timestamp; debug_msg.value = input_value; debug_msg.update(); // send output message - strncpy(debug_msg.key, "md25 out ", sizeof(10)); + strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; debug_msg.value = output_speed_rpm;; debug_msg.update(); From 4cfcea176785975590d1d2952eb0b0270a6949b3 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 16:53:24 -0400 Subject: [PATCH 20/88] Working on debug output. --- src/drivers/md25/md25.cpp | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index f265ec4515..9dac5e5ea8 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -575,10 +575,10 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // setup for test md25.setSpeedRegulation(true); md25.setTimeout(true); - float dt = 0.1; - float amplitude = 0.2; - float frequency = 0.3; - float t_final = 30.0; + float dt = 0.01; + float amplitude = 0.5; + float frequency = 1.0; + float t_final = 120.0; float prev_revolution = md25.getRevolutions1(); // debug publication @@ -591,7 +591,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // input uint64_t timestamp = hrt_absolute_time(); - float t = timestamp/1000000; + float t = timestamp/1000000.0f; float input_value = amplitude*sinf(2*M_PI*frequency*t); md25.setMotor1Speed(input_value); @@ -600,23 +600,26 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.readData(); float current_revolution = md25.getRevolutions1(); float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; - float prev_revolution = current_revolution; mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message - strncpy(debug_msg.key, "md25 in ", 10); - debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = input_value; - debug_msg.update(); + //strncpy(debug_msg.key, "md25 in ", 10); + //debug_msg.timestamp_ms = 1000*timestamp; + //debug_msg.value = input_value; + //debug_msg.update(); // send output message strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = output_speed_rpm;; + debug_msg.value = current_revolution - prev_revolution; + //debug_msg.value = output_speed_rpm; debug_msg.update(); if (t > t_final) break; + // update for next step + prev_revolution = current_revolution; + // sleep usleep(1000000 * dt); } From 308f1dbfa4787e84665a3e822ddf7d1979f023ca Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 17:04:43 -0400 Subject: [PATCH 21/88] Added amplitude frequency to md25sine command. --- src/drivers/md25/md25.cpp | 11 +++-------- src/drivers/md25/md25.hpp | 2 +- src/drivers/md25/md25_main.cpp | 8 ++++++-- 3 files changed, 10 insertions(+), 11 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 9dac5e5ea8..1079005c05 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -560,7 +560,7 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) return 0; } -int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency) { printf("md25 sine: starting\n"); @@ -576,9 +576,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) md25.setSpeedRegulation(true); md25.setTimeout(true); float dt = 0.01; - float amplitude = 0.5; - float frequency = 1.0; - float t_final = 120.0; + float t_final = 60.0; float prev_revolution = md25.getRevolutions1(); // debug publication @@ -599,8 +597,6 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // output md25.readData(); float current_revolution = md25.getRevolutions1(); - float output_speed_rpm = 60*(current_revolution - prev_revolution)/dt; - mavlink_log_info(mavlink_fd, "rpm: %10.4f\n", (double)output_speed_rpm); // send input message //strncpy(debug_msg.key, "md25 in ", 10); @@ -611,8 +607,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address) // send output message strncpy(debug_msg.key, "md25 out ", 10); debug_msg.timestamp_ms = 1000*timestamp; - debug_msg.value = current_revolution - prev_revolution; - //debug_msg.value = output_speed_rpm; + debug_msg.value = current_revolution; debug_msg.update(); if (t > t_final) break; diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index cac3ffd293..2fc317f5e4 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -291,6 +291,6 @@ private: int md25Test(const char *deviceName, uint8_t bus, uint8_t address); // sine testing -int md25Sine(const char *deviceName, uint8_t bus, uint8_t address); +int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency); // vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 701452f2d5..b395088a38 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -139,7 +139,7 @@ int md25_main(int argc, char *argv[]) if (!strcmp(argv[1], "sine")) { if (argc < 4) { - printf("usage: md25 sine bus address\n"); + printf("usage: md25 sine bus address amp freq\n"); exit(0); } @@ -149,7 +149,11 @@ int md25_main(int argc, char *argv[]) uint8_t address = strtoul(argv[3], nullptr, 0); - md25Sine(deviceName, bus, address); + float amplitude = atof(argv[4]); + + float frequency = atof(argv[5]); + + md25Sine(deviceName, bus, address, amplitude, frequency); exit(0); } From 95aa82f586a8c44c53ae48517efdeb5e5673b7b5 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 29 Jun 2013 17:05:41 -0400 Subject: [PATCH 22/88] Fixed arg number. --- src/drivers/md25/md25_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index b395088a38..3260705c1c 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -138,7 +138,7 @@ int md25_main(int argc, char *argv[]) if (!strcmp(argv[1], "sine")) { - if (argc < 4) { + if (argc < 6) { printf("usage: md25 sine bus address amp freq\n"); exit(0); } From 1980d9dd63e29390f7c3ba9b31be576c07706f73 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 01:35:43 -0400 Subject: [PATCH 23/88] Working on segway controller, restructure of fixedwing. --- makefiles/config_px4fmu-v1_default.mk | 1 + src/drivers/md25/md25.cpp | 2 +- src/drivers/md25/md25.hpp | 2 +- .../att_pos_estimator_ekf/KalmanNav.hpp | 4 +- src/modules/controllib/block/Block.cpp | 4 +- src/modules/controllib/blocks.hpp | 1 + src/modules/controllib/module.mk | 8 +- .../{block => uorb}/UOrbPublication.cpp | 0 .../{block => uorb}/UOrbPublication.hpp | 4 +- .../{block => uorb}/UOrbSubscription.cpp | 0 .../{block => uorb}/UOrbSubscription.hpp | 4 +- src/modules/controllib/uorb/blocks.cpp | 64 +++++++ src/modules/controllib/uorb/blocks.hpp | 90 +++++++++ .../fixedwing.cpp | 18 -- .../fixedwing.hpp | 45 +---- .../fixedwing_backside_main.cpp | 3 +- src/modules/fixedwing_backside/module.mk | 1 + src/modules/segway/BlockSegwayController.cpp | 56 ++++++ src/modules/segway/BlockSegwayController.hpp | 18 ++ src/modules/segway/module.mk | 42 +++++ src/modules/segway/params.c | 72 ++++++++ src/modules/segway/segway_main.cpp | 173 ++++++++++++++++++ 22 files changed, 536 insertions(+), 76 deletions(-) rename src/modules/controllib/{block => uorb}/UOrbPublication.cpp (100%) rename src/modules/controllib/{block => uorb}/UOrbPublication.hpp (98%) rename src/modules/controllib/{block => uorb}/UOrbSubscription.cpp (100%) rename src/modules/controllib/{block => uorb}/UOrbSubscription.hpp (98%) create mode 100644 src/modules/controllib/uorb/blocks.cpp create mode 100644 src/modules/controllib/uorb/blocks.hpp rename src/modules/{controllib => fixedwing_backside}/fixedwing.cpp (93%) rename src/modules/{controllib => fixedwing_backside}/fixedwing.hpp (87%) create mode 100644 src/modules/segway/BlockSegwayController.cpp create mode 100644 src/modules/segway/BlockSegwayController.hpp create mode 100644 src/modules/segway/module.mk create mode 100644 src/modules/segway/params.c create mode 100644 src/modules/segway/segway_main.cpp diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 74be1cd23f..cbca4f6a69 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -71,6 +71,7 @@ MODULES += examples/flow_position_estimator # # Vehicle Control # +MODULES += modules/segway MODULES += modules/fixedwing_backside MODULES += modules/fixedwing_att_control MODULES += modules/fixedwing_pos_control diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index 1079005c05..d6dd64a094 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -52,7 +52,7 @@ #include #include -#include +#include #include #include diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index 2fc317f5e4..780978514e 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -46,7 +46,7 @@ #include #include -#include +#include #include #include diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp index 49d0d157da..f01ee03553 100644 --- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp +++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp @@ -47,8 +47,8 @@ #include #include #include -#include -#include +#include +#include #include #include diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp index 5994d23154..b964d40a31 100644 --- a/src/modules/controllib/block/Block.cpp +++ b/src/modules/controllib/block/Block.cpp @@ -43,8 +43,8 @@ #include "Block.hpp" #include "BlockParam.hpp" -#include "UOrbSubscription.hpp" -#include "UOrbPublication.hpp" +#include "../uorb/UOrbSubscription.hpp" +#include "../uorb/UOrbPublication.hpp" namespace control { diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp index 7a785d12e2..fefe99702d 100644 --- a/src/modules/controllib/blocks.hpp +++ b/src/modules/controllib/blocks.hpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include "block/Block.hpp" diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk index 13d1069c7a..d815a8feb5 100644 --- a/src/modules/controllib/module.mk +++ b/src/modules/controllib/module.mk @@ -37,7 +37,7 @@ SRCS = test_params.c \ block/Block.cpp \ block/BlockParam.cpp \ - block/UOrbPublication.cpp \ - block/UOrbSubscription.cpp \ - blocks.cpp \ - fixedwing.cpp + uorb/UOrbPublication.cpp \ + uorb/UOrbSubscription.cpp \ + uorb/blocks.cpp \ + blocks.cpp diff --git a/src/modules/controllib/block/UOrbPublication.cpp b/src/modules/controllib/uorb/UOrbPublication.cpp similarity index 100% rename from src/modules/controllib/block/UOrbPublication.cpp rename to src/modules/controllib/uorb/UOrbPublication.cpp diff --git a/src/modules/controllib/block/UOrbPublication.hpp b/src/modules/controllib/uorb/UOrbPublication.hpp similarity index 98% rename from src/modules/controllib/block/UOrbPublication.hpp rename to src/modules/controllib/uorb/UOrbPublication.hpp index 0a8ae2ff7d..6f1f3fc1c0 100644 --- a/src/modules/controllib/block/UOrbPublication.hpp +++ b/src/modules/controllib/uorb/UOrbPublication.hpp @@ -39,8 +39,8 @@ #pragma once #include -#include "Block.hpp" -#include "List.hpp" +#include "../block/Block.hpp" +#include "../block/List.hpp" namespace control diff --git a/src/modules/controllib/block/UOrbSubscription.cpp b/src/modules/controllib/uorb/UOrbSubscription.cpp similarity index 100% rename from src/modules/controllib/block/UOrbSubscription.cpp rename to src/modules/controllib/uorb/UOrbSubscription.cpp diff --git a/src/modules/controllib/block/UOrbSubscription.hpp b/src/modules/controllib/uorb/UOrbSubscription.hpp similarity index 98% rename from src/modules/controllib/block/UOrbSubscription.hpp rename to src/modules/controllib/uorb/UOrbSubscription.hpp index 22cc2e1145..d337d89a88 100644 --- a/src/modules/controllib/block/UOrbSubscription.hpp +++ b/src/modules/controllib/uorb/UOrbSubscription.hpp @@ -39,8 +39,8 @@ #pragma once #include -#include "Block.hpp" -#include "List.hpp" +#include "../block/Block.hpp" +#include "../block/List.hpp" namespace control diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp new file mode 100644 index 0000000000..6e5ade5199 --- /dev/null +++ b/src/modules/controllib/uorb/blocks.cpp @@ -0,0 +1,64 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 uorb_blocks.cpp + * + * uorb block library code + */ + +#include "blocks.hpp" + +namespace control +{ + +BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : + SuperBlock(parent, name), + // subscriptions + _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20), + _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20), + _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20), + _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20), + _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20), + _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20), + _status(&getSubscriptions(), ORB_ID(vehicle_status), 20), + _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz + // publications + _actuators(&getPublications(), ORB_ID(actuator_controls_0)) +{ +} + +BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {}; + +} // namespace control + diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp new file mode 100644 index 0000000000..54f31735ce --- /dev/null +++ b/src/modules/controllib/uorb/blocks.hpp @@ -0,0 +1,90 @@ +/**************************************************************************** + * + * Copyright (C) 2012 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 uorb_blocks.h + * + * uorb block library code + */ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "../blocks.hpp" +#include "UOrbSubscription.hpp" +#include "UOrbPublication.hpp" + +namespace control +{ + +/** + * UorbEnabledAutopilot + */ +class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock +{ +protected: + // subscriptions + UOrbSubscription _att; + UOrbSubscription _attCmd; + UOrbSubscription _ratesCmd; + UOrbSubscription _pos; + UOrbSubscription _posCmd; + UOrbSubscription _manual; + UOrbSubscription _status; + UOrbSubscription _param_update; + // publications + UOrbPublication _actuators; +public: + BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name); + virtual ~BlockUorbEnabledAutopilot(); +}; + +} // namespace control + diff --git a/src/modules/controllib/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp similarity index 93% rename from src/modules/controllib/fixedwing.cpp rename to src/modules/fixedwing_backside/fixedwing.cpp index 77b2ac8063..d5dc746e0d 100644 --- a/src/modules/controllib/fixedwing.cpp +++ b/src/modules/fixedwing_backside/fixedwing.cpp @@ -123,24 +123,6 @@ void BlockWaypointGuidance::update(vehicle_global_position_s &pos, _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); } -BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : - SuperBlock(parent, name), - // subscriptions - _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20), - _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20), - _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20), - _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20), - _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20), - _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20), - _status(&getSubscriptions(), ORB_ID(vehicle_status), 20), - _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz - // publications - _actuators(&getPublications(), ORB_ID(actuator_controls_0)) -{ -} - -BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {}; - BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) : BlockUorbEnabledAutopilot(parent, name), _stabilization(this, ""), // no name needed, already unique diff --git a/src/modules/controllib/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp similarity index 87% rename from src/modules/controllib/fixedwing.hpp rename to src/modules/fixedwing_backside/fixedwing.hpp index e4028c40d7..eb5d383810 100644 --- a/src/modules/controllib/fixedwing.hpp +++ b/src/modules/fixedwing_backside/fixedwing.hpp @@ -39,27 +39,8 @@ #pragma once -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include "blocks.hpp" -#include "block/UOrbSubscription.hpp" -#include "block/UOrbPublication.hpp" +#include +#include extern "C" { #include @@ -269,28 +250,6 @@ public: float getPsiCmd() { return _psiCmd; } }; -/** - * UorbEnabledAutopilot - */ -class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock -{ -protected: - // subscriptions - UOrbSubscription _att; - UOrbSubscription _attCmd; - UOrbSubscription _ratesCmd; - UOrbSubscription _pos; - UOrbSubscription _posCmd; - UOrbSubscription _manual; - UOrbSubscription _status; - UOrbSubscription _param_update; - // publications - UOrbPublication _actuators; -public: - BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name); - virtual ~BlockUorbEnabledAutopilot(); -}; - /** * Multi-mode Autopilot */ diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp index 4803a526eb..f4ea050880 100644 --- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp +++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp @@ -45,12 +45,13 @@ #include #include #include -#include #include #include #include #include +#include "fixedwing.hpp" + static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ diff --git a/src/modules/fixedwing_backside/module.mk b/src/modules/fixedwing_backside/module.mk index ec958d7cbb..133728781d 100644 --- a/src/modules/fixedwing_backside/module.mk +++ b/src/modules/fixedwing_backside/module.mk @@ -38,4 +38,5 @@ MODULE_COMMAND = fixedwing_backside SRCS = fixedwing_backside_main.cpp \ + fixedwing.cpp \ params.c diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp new file mode 100644 index 0000000000..b7a0bbbccb --- /dev/null +++ b/src/modules/segway/BlockSegwayController.cpp @@ -0,0 +1,56 @@ +#include "BlockSegwayController.hpp" + +void BlockSegwayController::update() { + // wait for a sensor update, check for exit condition every 100 ms + if (poll(&_attPoll, 1, 100) < 0) return; // poll error + + uint64_t newTimeStamp = hrt_absolute_time(); + float dt = (newTimeStamp - _timeStamp) / 1.0e6f; + _timeStamp = newTimeStamp; + + // check for sane values of dt + // to prevent large control responses + if (dt > 1.0f || dt < 0) return; + + // set dt for all child blocks + setDt(dt); + + // check for new updates + if (_param_update.updated()) updateParams(); + + // get new information from subscriptions + updateSubscriptions(); + + // default all output to zero unless handled by mode + for (unsigned i = 2; i < NUM_ACTUATOR_CONTROLS; i++) + _actuators.control[i] = 0.0f; + + // only update guidance in auto mode + if (_status.state_machine == SYSTEM_STATE_AUTO) { + // update guidance + } + + // XXX handle STABILIZED (loiter on spot) as well + // once the system switches from manual or auto to stabilized + // the setpoint should update to loitering around this position + + // handle autopilot modes + if (_status.state_machine == SYSTEM_STATE_AUTO || + _status.state_machine == SYSTEM_STATE_STABILIZED) { + + float spdCmd = phi2spd.update(_att.phi); + + // output + _actuators.control[0] = spdCmd; + _actuators.control[1] = spdCmd; + + } else if (_status.state_machine == SYSTEM_STATE_MANUAL) { + _actuators.control[0] = _manual.roll; + _actuators.control[1] = _manual.roll; + } + + // update all publications + updatePublications(); + +} + diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp new file mode 100644 index 0000000000..b16d38338b --- /dev/null +++ b/src/modules/segway/BlockSegwayController.hpp @@ -0,0 +1,18 @@ +#pragma once + +#include + +using namespace control; + +class BlockSegwayController : public control::BlockUorbEnabledAutopilot { +public: + BlockSegwayController() : + BlockUorbEnabledAutopilot(NULL,"SEG"), + phi2spd(this, "PHI2SPD") + { + } + void update(); +private: + BlockP phi2spd; +}; + diff --git a/src/modules/segway/module.mk b/src/modules/segway/module.mk new file mode 100644 index 0000000000..d5da856010 --- /dev/null +++ b/src/modules/segway/module.mk @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 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. +# +############################################################################ + +# +# segway controller +# + +MODULE_COMMAND = segway + +SRCS = segway_main.cpp \ + BlockSegwayController.cpp \ + params.c diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c new file mode 100644 index 0000000000..db30af4160 --- /dev/null +++ b/src/modules/segway/params.c @@ -0,0 +1,72 @@ +#include + +// currently tuned for easystar from arkhangar in HIL +//https://github.com/arktools/arkhangar + +// 16 is max name length + +// gyro low pass filter +PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq +PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq +PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq + +// yaw washout +PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass + +// stabilization mode +PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron +PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator +PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder + +// psi -> phi -> p +PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll +PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate +PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg + +// velocity -> theta +PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain +PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain +PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain +PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass +PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard +PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle +PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle + + +// theta -> q +PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID +PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f); + +// h -> thr +PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID +PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f); + +// crosstrack +PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg +PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain + +// speed command +PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity +PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity +PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity + +// rate of climb +// this is what rate of climb is commanded (in m/s) +// when the pitch stick is fully defelcted in simple mode +PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f); + +// climb rate -> thr +PARAM_DEFINE_FLOAT(FWB_CR2THR_P, 0.01f); // rate of climb to throttle PID +PARAM_DEFINE_FLOAT(FWB_CR2THR_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_I_MAX, 0.0f); + +PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) +PARAM_DEFINE_FLOAT(FWB_TRIM_V, 12.0f); // trim velocity, m/s diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp new file mode 100644 index 0000000000..8be1cc7aaf --- /dev/null +++ b/src/modules/segway/segway_main.cpp @@ -0,0 +1,173 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: James Goppert + * + * 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 segway_main.cpp + * @author James Goppert + * + * Segway controller using control library + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "BlockSegwayController.hpp" + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ + +/** + * Deamon management function. + */ +extern "C" __EXPORT int segway_main(int argc, char *argv[]); + +/** + * Mainloop of deamon. + */ +int control_demo_thread_main(int argc, char *argv[]); + +/** + * Test function + */ +void test(); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: segway {start|stop|status} [-p ]\n\n"); + exit(1); +} + +/** + * The deamon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int segway_main(int argc, char *argv[]) +{ + + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + warnx("already running"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + + deamon_task = task_spawn_cmd("segway", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 10, + 5120, + control_demo_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "test")) { + test(); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + warnx("is running"); + + } else { + warnx("not started"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int control_demo_thread_main(int argc, char *argv[]) +{ + + warnx("starting"); + + using namespace control; + + BlockSegwayController autopilot; + + thread_running = true; + + while (!thread_should_exit) { + autopilot.update(); + } + + warnx("exiting."); + + thread_running = false; + + return 0; +} + +void test() +{ + warnx("beginning control lib test"); + control::basicBlocksTest(); +} From f4fc3bbd571ce99b707d326a206159a6eab49547 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 14:10:37 +0200 Subject: [PATCH 24/88] Added RAMTRON device, updated diagrams --- Documentation/flight_mode_state_machine.odg | Bin 18105 -> 18452 bytes makefiles/config_px4fmu-v1_default.mk | 1 + src/systemcmds/ramtron/module.mk | 6 + src/systemcmds/ramtron/ramtron.c | 279 ++++++++++++++++++++ 4 files changed, 286 insertions(+) create mode 100644 src/systemcmds/ramtron/module.mk create mode 100644 src/systemcmds/ramtron/ramtron.c diff --git a/Documentation/flight_mode_state_machine.odg b/Documentation/flight_mode_state_machine.odg index b630ecb40242a9a52a796c30ff0dbc283a4de7e7..f9fa7a032343b3b74e3b795504a34539e442e065 100644 GIT binary patch delta 13736 zcmajG1#Df1pGjq}~Ck-<+%-AG*hndqbGc$9;%*@mF*@A-G6&v3<&@j*L|mi zK;mX(<56ej;A3UsV_{89gP?$AWtZk)QQ+W7?1x~2U}a@byoG23|2tJdvH}0m2mFtL z_?LDucXhS0w{&6hw6p!Kqo26Oh3R`$V!B9)!wrUhL4g?^Kv#gRM=2F;T2NPNUB0}cc{);MDWlQU%e`P zeRNwFxCHd`GWx^&kh{mujO;(w382%!iC60{E3G8?R+TyrFAg3FFG&^_aYxSp-cF>s zdZ8~fvcy;eIiFJA6vtM+^5ERoslBzuLc9{}+-6Io)S^#;EG9~phU-JTdzq@Q6FbX` zJSD09xJ5LL`)bliT$`Nq&0b}47e&tI z)G`Bctgfj_96t|Dp1$_}B42#lyVzWBIodlC$NbHDzl-(e%cNCYqsb-(MQfO4%F593 zk)0;yj0LZ$03-El0t4uD?lCw-^5dF)2$s}(@h}Xw6|$!vZ}ahnbEd;YUgdyo(izd< z_DSrH3_ds36I3=5Bk_4*4F8p`dZ+lY0oV&nB&x<|x5Q&>3a?L_h#S~LQ^^69CQ|8` z<9748E($Zo1k|lrQzrhl!XPw>phU#ert&*0gVtX5v4TdaT)nJ7{!G!C;sK< z%fn4Ph`T6+Euf|{-S^?F+uCAWIV&Fhonh%N^%4BzQK7B}h11Bb484~j5{j^vn&KQd zGcZ2gp&}0ga_^_^pY^|F$qu}hIsa;1;|qDUK$IY|+OfH=0QZnYhxa|S+=;0EUZ=&| zCR6*k*H>Zt`t%*UJBXU>I}<9B(ZJHTNJJB7`C1ecSf7F9lSm_4t|r|(_^2XT`mn1| zMdw5O>MLyT-UHFoR_JQQKnBI1H6a1OYoMbQkM0720siG=k#iy$(@yC<)G)^%Ae6BE ztNAezm4OnTAKtA@#bjQSi9(bg@c@}4CEj#g0aOyz=^5-e7LU*e%%7*!Nr859mCp2H zg(f3@@1hRMaN0Y>p!@Bp;47;L0iNN*q@m5Z-n!uoYjJNFu-mu3xpuNcnZplYJiMA< z#E3OHs3lHf`5QJ8!=i*f5kjKMmGsU2^0tY2?-c>Ku5H3ov=KYICY2eFs&y>4c4Pej3PFs2WLH_x&#Vk2(&{T(7!)M%Chv3PS`-zb zn4z7}=5ftBnMu1Dx03^wNSfKTCi~MsTb>7V%okTk0P#v^CPYg&RvOF~zpe{Ka zUvkd;zhzd>%-^}lF4HUmJGP!)+VpFfhh8?fn>pI=Q53yctURcvr@r%9^|)vA{q{eL z;;YJ?%~m9MpLJ!;QM~lNlzU!9Di5JLXMKU3zyG#&WtGShKUl`|fa-61nFe=vVpETI zO?mqhU0H|1l`LumPQy_khq!Be6-Jn#HufF0=z&>T4hGgna9d6u6AAzrBL@Kfo!4Pu zVgJeNiHC5+z_WyP9`}!&66Jg9vQ33}awf{&sTHQHb6a=%hlz!?4Chau7Lf`KZ0iS~^_?89Hem3d~W63&>$>qb50VooAi;Z zGrQ=IneYASUJc3T!AK-`&F5~0Yn`;k&2NFM&C0!d;8a@C8PQvo$l3h^ThHt19<{Dv z@hsP>L3M#fXV=Cg)4W0_ldk@06Z2xn?U(h<{(2V|4Q+?6$SV(h0#p40ySuj63=Q+H zdx6NycCMjzK>3zWyt|!Gk3L@{rm~@3zP{?&;5(c4=k4j9cgwn-Vu^=`$0d=={JFJk zA4_IAutOu%Qlo29p;^7@u)(S`>c)JX&S|u6=2Xs32P~zM@YgrJ({jq=}7{NXhd>`K`OX?_J5`mC!`>zD8qBCSlDv z<=F+3&Q<(sb%Obk3aA}BKYB^VQnj}oMvX??q?Y_rslhYRqQe@5y%`MX4A#WeztWTg z@+0(jm@ih?3OQ85ZyKu^S@z0ju2XiuP6m@@t--NZq7|Fm52u&PwljRU6X~Q|DqDez zJ2h}L|Mt^XzmWUPO9+`4bn{L#|4;LaKvu8ePQU1s+2zp7Y) zFgwX4IhMsM8)0h*Oq9d8=N%niIr)b32dRygiGe(o6UC7(WqgXdJ%YLTq4?XX=zImk znjTHV?Jf0~GN-CxW+&RziC5Aj^Vku#LMD_BAa;SRBT_X6(gdl&~oH$lIrx?Q&wy9G>l&JNu=^ zbDVz6FP#0DW2C}Y7vD&?3tWC@Xg$&luE8m*dVdc*h7^FtyKI&GCMbF9m~ZY3Rq)i3 zalxc5u<&Jz9JRr>Ndug{(}yqySmpAw$YaVaQ%@h_h9Unq_9fHYxJG?-wf9QFp3ds@ z-W+v$0pHpA9FlvsV~_j3OZ$3W?f3SUC>;L#M9B*&%}(wfh#>Yw+LGv~o!p3NO{?#m~W$ay{+q&a*EHB4I;0IO}ZW~7a$5UI`ytK~ksKu}$cpVZi2D|i`` z0S&T5e&+o#>5E<~?0eB)0o<}H4d3nYo4&SAE8;gLf?324KPGLzOMDRb+ogKEX-n2pG&2W9K5w_pEKM-#OZXFs{RG-`MeY@eC zO2Dh#?J(=$w6;yyM1(%(8cXnL>+%`pdgg!QAm`#Q5HfJjw?nV8<7QPg!P~}Z=?L`9 zwd^EBwIT?M=6)odOB4~9Q87RcGx#^}T>^T#0Y&dj_uyh+Pjh_{Ca!IsHNLS;Jlh8g z#V5iJoJPX}&UDB(2V)!W+{EY|V_{i z=zUquiW3W|2esDCF+&d9TDp?z_c{O_6=%zj;`mA$EGdT^DCE zg|AOK)mFMxyEo;=Z9yf;70%zO%x(sLpHAMhsb?Rxp}L zx}ead7f8i&7M8*Oy8aEv0o(T0;@55t%4azhFe4PHH_kXeJaMo=zp=YKnMm_QK%3GD zI@;>ks~WKkCun2ec(wgSo8V{412HkfPKi$d&;i@|R`DH)=CiE&Ncfs4N#@x`7z+ScnF<&5zlQ&+-66wErZpX*-Bj`*rz}3>C~Q)`N41C&?3i8l>U5gVZFM= zyTww`3t~24bZ{gDZQI?<8iN)wwIuKNA}jH+aU$4iYxiU! zG7gf;hT*6uS`IUv>*TN0rD_6KgSoi01PaZphW5*I)YZkXxi46gCis%P6n~oo!52~| z#;p&zUuoyx!;%B#qeY9EW`naUP#p69q`GQsKq`Fq_57sRFr?C*xcRbxRQau(I78^5 zUbdcLva#riK3AbfpXoS_TS4`UG$NkwhYEV~ix{P4Ut!~0#LL17OHV*FKCI)XYgLMNaDD+lW5)nV8GoR?a{E{;`mEc?>vxw97sjoMCehW!~m>Cc!H9Vb8KrwKiNJPp# zu!uN7CInesZiSH=MwBHq%{RP<8Pt>~KDLGXGJix7s)zU)uRAp;Bu=K~US5d=?KsRI zl%l2(<>Uj87BO)?d%TcaS8=^5Ug4nuu`r4QO3o0o38orx@F}v1E3MyrskhYf zz6iyxv2?v~(&!|wzj^bFfXE1f)5b|hP<^0+Xc$!#X;u6<*%VLtQ1x~&R@5r%%#czZ z^X^dmd}3F$Cz@`|k)Me(WI`!ARuUk5qu=K(h89l7a`9Sz$AR{o0k$2VU8~x zzQpbFmOY47)STsf#n5@2^?YzXcci5#NsWUglS-)5=o~h7-2t~oLc&I6k(?zLy71E*BP zXQL@J*-Iqt?F&Oivat`(y-d!n&b@CVUL(S|ZEPdf0W17AH^TZxj51m|CoJ_qZqq5mE@9VJzmrCRlPB|4^JR0K#$u zASy1NzOp3;QA_IVSsTy^@GaQuXsQt$QSfjJ@6Kjw{Y;6ynkwY7P)#I~nOv|N1&lF{ z$Zf_?C&84^SjyeF#*VsrQrKk}EnTN24a<)`V1e7m)#DAw#(b?K)~A@M;@C>DsgGO+ ze%t`xJs{>;1l$NvhzmUp$Z$E5M!6XfCtrG|1*`j(-HtL%xvZxqT75VUi%pK))S_+t z<-1Yl)pPmR$#7j2aR;>sK((|nUrvX(2`k|hWuhg)RZ@wmvL#h53fe4C5dRQ>HA#jz zZ8irYE8@D-$D%p~p>BZ99h5^F!R-HQhDh@1zlh7}-5ZAxK(Cx11f zGvr?&z<|TQlT<&*L)JNVhTxtR^K)Op-$zFZjS7B~fc?WuYV9SfiYO~KL@QxHT8NR* zU%86Ge%}7FX1OTDku>geb4r-)iaqw8l3r$W-QA0Hr>zG?N-`yz5ywgB_gv2!%*z9G zX+?xU#I*?M4ZY&+`y;4VmKzHP^IBi0F>?8h9gi;|7`_2J4|1iH zBm{W{tF*vTT`7PS4(7CNA@_@&@4HYept#tXoCIRS>NHz1d;x+y6E^LOk1=Vc2wP~t z0)RD=WH)uBwmCcdYkg>Ox22fkI8+l*O1d9IW)>SgzsgNH;)R&ZxcWLcfj=p*j|OTS zA!!awZ}B15s2?5~F`nQqrPbm(VK0&4{G?JSqtCExp-8^PEnJqB7ky_joz*yJiU!Kl z3J)U*4s$^u_9|ZhpiSWg!e(=U9r7(R`FtkSQQ;(Nv`7->B|ZdN7dAO+_pAb=>=$^} zd}C6M%vNuPNKminN?2KcS~h@hUWL1?QQ9v#+oqY_8etcV{@|}~WHo)@q+Lo%g*Wl) zQ4wtnh39@nX{~NfO22QKpZ#*JR~+gX%z|!;qUQs1N2OO0_5J3C)6!oXPTu1d?%3q= zz%)<7elHZfNyPAwYUsz0=a9_5r-t9f_(bjgEaW_`X9)d!b_%6-;rP~wdQH4<9HU?I zLK9Jc{8lbwv+f7+7-9aP^)I6L^&+3Np*mYx{XpODYIhXiru?xcaCup>k!vs65ga}b zc~?dZB)B+bJ#Qb+LC*n!3OF2j;F&Zs9cvOtZwGxoy1yu#a<*Dme{F^YTCMW-$*3%Q z_hvZ1ysmt4=!1d-jKnDh!Bmoh!i!`J#1>G+ig5B(`~Rj5bDz1g?_3CEx^KC4Apw2i za;~qa=&*Om;eGzeDayUVIq3E}iwCXRzIt#d6Fly0B7hZvtvxRoODdmE*{9JT3eB_$ z-BO|o5rs2?8;$vOYMe4aIm}wd3;A!XzB+ska2C(Gf=FsOIHl_TV@xid@n9m+M#LzZ z;H;#9f$zs6W-u?vSr)X^Dt{b>Wpn0V>tkzxp06a^pX=+f+n-PU2mQk>Bt03Oz}JhM zp3mKm(H7zE&y$N5lE-;FogclfpSokrt)^Dv)g?cg+dpT;FTJgSC{mQrSL|w@BR7P^ z%^oL7VKyn3D&A)wp}j~4PFp3vj}fn?eyk#%;F7Hfj#HDR(tRFyP6yeU{l;3kuwpS@B`rpi1Ycxw95M2MhB<7UcZ3|XN36{gIoa%Vu)razwLkL6?J z)upK(zszazLiGdFyhCgd%Yza#Z&WHcfB-Uj%}Nji57_o*S&sVO7D6C z%1+S++}*&Ates`A(NU58cFjfH!b2~oH4wdNaKt()4*i&7#cPH+wbyuuh2<4?e}hco zLZ)gW@(&h6Dw@8 zR8Tnw_lsCTtNjBW!qkOk!zPY#T{=GluiVCwoJkArw{;)1y?MAS$HAx2UN%u_*R;eC;a7(7h54#+`bHP?v?qi52HDUy8KDQq;IA@|z*fQmVR2Ydk_8otOxowk| zmVSZ!+g=*IAc} zJI)fVc=bPz+l?eM4y6pRYNKnjQhRNCZC%8HEK%=b=YUz|r&2mq5+%)1C4fp18ksDZ zsLRQzQ8dWAxc*ppF5k+4qBhv)6dNg+Nz(=rl!qw()u`DJK)J@4bh%2ao-!Z-A;)g% z`cY2)J+j{p->Px7$#lLpdNP|;!FlgXfh3z`IGHka_Tz2=nKZw`g}*B?ds_F)n)neA zE;=#XX}=%LHT%!Y*mA`k?w6vV{z{JJbOlB2b9sCru~v?9!KES#t8&3s47!J?SH#If zksvTwY}C#2fv(#A!b^-K*o}zsmx;<@N^6-`9_~oSfX9NOuT8Xz+8;2E@L=pUGO7PDlchMz=O7k*)-*)LggC$S+UofDjY`Pb0CfzY@l#Ggk#{_bt~Z2lO7rq^ z1$7FTDC+{Nt~*s8#z{FXm|W`j$1{gzCfOydfI8zXqe6-62&CNB#Y;2$Wt_kgeA2Dw zol15rpi>LkA{Q}j=6lGn^7a$eiU8LHJ&~$4wjq%1Gdzh6SYiTh=J)P~U z;EawY+(KEof@(BA3lvv}n5%QtdLreGir|VaoiNx^@w6R`llaaVCj*p*CRlbTK?0E( z2&(kg*L$41qb$iG(j=IC9(FkplG8yfOXZ;MR zD_;*7+^6(*ob-Cx8|qu#>6MAIZ41qQwh(yrhKn{&G+YBH$i~GHGF_V99X|I{!?R#A z5wjeIfJ^cF77TV@oZW%@b-V(r&1G3Jnaq#9_uC2XJE@-Y*Vy;IiA8dfb}i`k+XpT1 zILF@QDbd$aj$XB0l1@D7*WzD;=U>=H5R#(5=w#z|kaLShXjpr_E`<$Yi)6IqTQqOT z3KqtfzMFGOTkV7?@8uZl;pzYGXu}^5S)p1?x`Kc_X@Y%hK=cC|v!z0NCu6PJtS#P( zDa-X+XLLLesS?byr79#J4`V{g6LFDWrv}8dKe_mSlLJwUUf4?a%NOeeQ(qsKt%qn| zqnrihs+divHqM=CG`^LF`nd|lWZL*k+Yfq3iBgveA^`>f3MEpcIC$oVWdd?|n!ClW z_~rGZg0a)iF3v+Dj*bYw3g=P~)VJqS^q_u*2_*wkS~nun<9rS#i8O+Adu;U6m=r19 zi}+lw;uxR~rv;K4wEloJ)iL%i833*^{Dxd{XFOk`?<3R?DN_bWi4GI1SsuJ6AVp;> z^k*C!(;~Bgx=D+0G)VkrgfiUUT`Tt;B_H2Y_;~GCsKLdXs>EsRr)9Xzsn z1mfDx6{NFl7{lie|6R}4QAkJjNlykBv4_Bwlk18rq4&GXSBIV}?-vc4AMI|Bqutc( zoR97)5UCSKn^ZlWvm2IuK}^EliiEgSs^5XGYMI`48O%9CzUe;7W~|ypE>FEkVoTo= z&v+vF6|sCnldamdC>x&8nSYr+;0Trcfw^$!>(CxN%YryJg8>?T3jcG-McC#*5Q`50 zbiDr89oK()7sPg!lt|3c0f2uV+`ml+>fhb$Oze%VY+aaL|B{J(R183L1{n!abj1XyNMu2;@u=j7+U;!E70#89~uSbx^f+9L)f( zTi?`?vLm<< z#VA1|3I0I+7{U^m!q@qP0XaTuD)7T&Sn;G6MHaJ%OMwIgaR6BjNY*=k9L-1Yiu%VRFTuRZIJZ3SqmC~7@th(%67kD3OV_jz;5psv%m%K?Z6hF8aKB`| z0%Hm(a&o)w^b!KRz52k9F}C1Co7njh?K5SLic;6up}jp5lN9)4Fu}ipQeG#2*PS`6pkLJ? zWAl7_c71#Qc-cSNkA#rrc_0KD_6WCBv#7Qp;my6gG4q z5cc~tdF*+6_gf-~UA#B#WqTErttNxr{*|(VvRhSPN_*_S{4GH=7;tTQSVrP`g-5dU z`1!Q5tq6@Fh%N!Kb?e0O&`(i8J$9?v9)gGolqZ#b4|@bN{&do^!J7cjWlA>!l;p|b+8 zHw1frw+mG^Gx|hhQOKSVv ziJ|UbpS=tEMHoOA!Pdd-ll`(M7Up(tPW47t8B|4*Cd_qip(c77Sgwc0B>#ohL$<%m zCBP8r9`9ooR>~-gP*Rf-bmAZlFFP-G;snxBLWaOl@F82M7ZvQ8cLLCK!4!-F%klBk zWjrC(4OqQ>=j6n%{05#}`QH>cK{OH^=GJ8m-2AZ8P&*3vPmgy-SQ1DPuBGvHNsQ&L zKP$O{l+ZK@=;+Trgx!nLSPeMWSmzj)8;sgT1Is8n-&9~bifEA-eb853=DoN&-b%e| zwsT1IKJIbae=LC4#|{;<9J&VrL%0}On^aJ6^r<$r`>cM(5yE^m6&56Gq@%E$15D9Q1L9U7dh2dy02)-pGkhu6eb-)`@5e^t50P`@(l#UG&C}{lA7GlpqqF^7UC^a zB%Ka~9415SW=T{rXis;6a~nb5ff{uJNTn;=zD7ME^tA$=jXL-$el221t;snnrIIHG z6La|xQKfx%U*h|?#?Te@$`o1pPsaUw^Z?jPl`%%UWgfrmqR&Esp((E+9+S_W4=yY0 z&79PzfDBgu_ob!E?sn*{zuzy=@(tG>JoSf+8zFOlSBgGiTKxeZxCw)Bb#AG}>4Ar6 z%9T7HKiJc_}GlrIsJ zz{+i$)!PKNOU_S&;CSt=L)OF62D(ciN&#DG zF}KL^Q)K{2UjtTzlibQ7_+A6*VIMPm_r=0SUc8?`uWP`OBvC=cn`hi3>d;B7;fTz zdBLF0y&4-TS=gk`ajFeEZF4mdkP`i|OsysjpHN`0u^k){``cI75+-#{6=j0d@ zkxWfqy9S1SOT49RH!ol+L+Y%V0>@l}SZpr7HUT~9ZwbRK*ys-7?2ihpd({laiK^2W zFNg>wi}F$`Gp40OyVHz9I%gbINUI!}2-c;Cp4d+|-Sk~Y;U z;;hgw>Qf5E(W=*ch$lK?2H#2JiT@=?_x<|9mCe80q-e^DX+D=gzb4&bBcS_&{aPLM zcbCkVlc4~{s<{fsya?rcz~3XoJ#M$Wcn?iC7&s`t zUL#SgMuLmpP9+55L1Q&?goiIG zYx4&oyKlv3;z@BB72+eh`cfr)Q~}}1>NV`}6Vxa8%crZjKvsD zUSHdvSt6k5cTSRrp002IH1FCx?Z3VXPiq>`=yM~_tc8oxsR>Sw4k%xXzW2To>|eEB z0KGi7nScIz_IOg9)dLK@Qx^MpIU{m}+NXTvzW%xmd&~*leC#3FCvL;f1p-5_B%lSQ z0Bu;5EkH-yQ=vgzeyVFCpYV6oVb&{{o(0XO2Yw$Kwqr8DexQg5P_BJ8ct{>jh=BzD z9>Ts~^7k+g;jUeV?sHD$E%rA5*_~{m8S3}Vck#Q%FdfT>j_l&ic?y$<9ZwQ?`ftW% zUr64O4QaS(f1ni)ntr zV^RqB$14?nSlWDhZ5JteKGmVC&^%GTR!JkK zSoZ9zoIC9-YX53f1L_J-1s*4m6~u4-&pEb18}b4+6wS)`h!RH zOQ{Z^-&6|aF*a1H$pqL_-_LYl)MJS#e^i`_t10Mgi7jo}YfNTyWAUd<=(FqVFM%F$ zu7Qh8ni}EMOXn`jZ6Bgvd(idBt~X_%o3b2TC$e@-EbAKZl2FF~W}|hizhc zt6s2i8oSUx+^q1O%jLSHd|B#FcrisOs2Bch>CmKhxGIO zbu!tlKA@u^h!=7P9VrQ!AL&eW2rTG*>!YlKj}d1EXMGzxq5kuEvCCEKzG@NYdodd5 z%L-QsgjjQ2LJEa0tQl|xk1%)kWHue=#2sE3skdSimLBNalZ>^1zZ&Z_K?w+T-*v_4 zDUaJZr+Ju6R>*>-KmT+shT{M!0R-@UBc0j6TETs7y6OhR0y;1*C#cazW>=rmW-f8G zMT;C*CusmFGbuQcJdBj%A2uS9?^b#VY1pDf?e{SLbWl6p?We2L=yVb(@5P-(&JQV_ zmN`xY=|DvLG7PMr#>n6!B~KPuAT?P9MlAG=tdX`d2N*t)UBl37za!urXDO<*&N;^? zmD~L96v^Es$N?#t{oa$3Cu(d^XasZ^KgC;`?kt6gzzu@e!{kl*LXB-L)q8ko)DZmk zZh@Y?Hy9%1jpR|e8;~(@SYL{vrW5L@Nh2q3;M= zBt81*B^~3=!7K?G_jT`cXagKp1bX0{H6qn~m6;0~xt7Qg4NQbI%~50coBoaeYjhNX ziw(S|ei2YLO)K#JQ)|(Eq+U3q1(;d2UTPiN#{q6+Mxm)-T(MOuk1)+7F45Bt zsUlCIhf~w5dn<(co5B01Mf?m0xFf@GCxviSac~QuTL=K)~=25!_CKW1Yn z4xds$A6Q^L2)IvITDXBhL={Pon(09v`h_fA62NfsHKlUi?G3D7K3A1ZEW-Ut5ZKI= z3C5c!dmqnC5jWVm@R(|a>}W^Jc5?A&aJ8j4c{++qDd+}#B@b`;Jo;CoRu#hJ)(uP) z&flYxsiZI&N~N{@^jOqL$b2Z{tfLxrQMclAFq6113dUbgr+r;JS&Z}4zoer2!~XQm zTat&zSBAT6M^M@Bj{peZvMD=R0L3l(qr>hz2Wc0H`-pj8nPq%YbiuE4J#Spmes_@x zld;uKph#`5RIjudsQ@HUO+Pdwvo1Rye0#j9}gy5(lI(VWcK$Fn{Ii5OU z5B3hULsS5Y#xB86Wwd}vql{E3K!V@PUFAG2bIl6U>t7amGA**#)J0=A<9)eT9^BE= zA<_JCez2F;$JAY(8i10zov}%BQOWkL9DX~MNDZDemyV8m|6A_{I4L*@A+|A|t6NQ7vW^@V_uM{}T+82;^dd_@^JcmW%U0Gg%@WH|D=+Qtp4h)8gj-7eB&H zmMAO`yZbDU-JjI`u{5@m4Z(M@%&5P5XqDBZ-Pox9qeB#e8kxQH=HN2Q;bgM zAArukTE+js;YP5}OkJF#1w@n7uaU-pALv4@Ko>E9dvr>vLwkARCOF^?NN z5s4f2|01;KNo3|GrvG1B|1;FICKwXvt0bf7rQ^Bmm#}XA{EzivXK9(M6K_ zUtVVZT_?|*h{QvO@?U}ZFF*e=QNWvsEJe-#PYBEg)Fn;+qN=u80RZ^_<-jWM-w3;U g*_!_g4)tGV{;N~pL5cv}MJzE&iUxW_{2#sl2P{;YApigX delta 13325 zcmaL8bx=4ae&;>kx$mi4 z_02y$yL;{KHMXm3&tAz15N)v#D5?rj(AXdlJP3p@&69|tjPkdU9EzF?GK2&1 z=L}D;A^hw3V@R#B@theqPp#p(|g3OWv zAaDNk@V@WryLefn#EBO2h!psFYWzQx?*}v9I}})gyMaFlK)zoaT zbBrE8;WL^=IwGBF((76acTIq7eO!~Euh9O-co0AdJ3_?>sH}>T&?TAV3Af8!=igGo5$?7u{uPDIjK_H zg#Kl_`OlgdS*Ak+vRj14UJs=bS+FJiChj0WbV9oNaroVtfXFMJ#H^L+i?byFDB?%( zVZ{k`M=s>Kk#0;Tb74Op@#khyu#?P?b8j8@($&Dtw)c^Q(WDpB)pE?pT(A=g$8Tw_ zhj4Qt;1$$E=MZeGdkyS&6+-6`a}s_f4)hxEex}V995S-UZG@64aYe*ftuZyNDcY?r zxKukgi<8>QWR8&cxz}ywd;>NBeBvDH$Jiejn;LZ_)RK~=cg>Zy8}AU^vJa9+1_o^x zSe^Jch861tN^LfwZ>OS>;^?7;(s8z1R<^assZdUSuXuM)x^bi;)~5ziuKh}Fsor@^ zNs`j5i?LK45&9F*_^G*cq2ZYHax{D3HdjV$*EA0b>1%`6D1x1apNEu+F1!( zz|X+>LyDH0ncwztecsIPr~B{HNLMdWy=hh00nE;4LzQFr5^mq<1o1OuDy&yyx%VYb z<@NN1Y;ju?4Y34V50FU&Oe8T&xzAP2HL&O`C)FZDH1aSlb4ndLze~ehgk`sd4XcoQ z>3!;hLqOB`q?NJ`e(3W9LZ8O-vs2e;f8ZeGj%6a)5?(GC(Kw0H#KSMdzme-cfzA4F&ye#6fiv_Q>(5D@XSRKQ)%CbcMPko zjV@wRd|^tBT^&BFNR zsHy-5pCelnHTpMRV(3wTK>rg_;o;%`iKt*(L{eZqX_eojdrG~oN#4d&JvjpCBUnwD zw_w7{J^K~+-3FY+pi|i1Mim)V?$Pl`2Hqo1Czm<;o3;8V7Y?{ppPi$6~RZ#V{IpFCXBGOBL)?rAt=$`D}9L6zxyWAL090oU~y7 zWzB}H7JIVP=B%awZU2ug-wHA=N@cs+muUsCgYu%kE?-2S3C8*PciXZU?rIzIR6kjao%2ae6catbG;`!!c8U?z(2C!vGAay{VT|(MTzelV4=2BlV=X- zENE1#B74l~6Mpdfq_0;(rh*Hsm3Elf;^gHpi)OJ};_NI}B5>2o(yCG_iWZH04u%gJ z5y3es9;rb*biMrizCVm6HgN%7xKrg9G2&NT{O!;#N)E1_H9s{BY#=SjshRs#7-$|J zHi;YhBf2%+4y@F&u1V5l)dSzFZWRjry(!IiDkkY2Y(C#}rih{?U6-IsxzZK;rmSzC zsuCLob8r<6uoSr#@~XZdF5CY2iAbGkoM9sfp(ettzuIAAZ(xRY>OF%76ZkVtsX>Xu zww-%ngMV|Yn%=r$O@(XWHme&}m$1eqK@i_y`5;zv)gZs6itW4`RaS%7Xub!i=j|B3 z$v)2%yxh&BO~>1LMrKm|O|8IIP~_=LQ=IO0BkykdTsNlbVp*W`;l@)8yDIWGauhf3 z^SM_ll6!4lXZ{wHWka4)vRM&O)6Im+!QCpsj}7I zR_|TrDNa!MG^+-gdl1$9SFQHIg94^#scZIek@J9MRbmd;SSmqvSx?k>k6PfjFn5y| zg@#bLK3&&x1)5*YNWELOoQr!x8D)(RWt{*2*2elZG*NT}#4RAN?8;7q%4ImaCz^A5Ub9p9I$(jOl&w zQvX;7h&4EddL5o0Jst}JzcXaS-cf6k1WE%+ucz|LR`V*}yzeGH9IlQpRk<0g$Br5f z`M!Ak66~h?LjA&3&o{Z&pS(G3eUhT|TX)K$Ke;E?Nas5n?kCQNlMaKP1_w(!UU0uh zrgUxfrrI~){`GB`YL~$6cHYf&p<;ogLvMQqe(-H^3bTpL@M?_;IGt#oVmV0{{{95% z!?h;1Pga)2{C+5Am*jpm=az$)rm2of)8Ap1V>d@IGG&^1s2r)(o)uL6itFcjpqxt3Qo1)N(GYqkQDWCaJVyCn zHb*=3K)mc6Jn;5MEw9e2UhVg_mCY#$E*o#FDCvZ1SAXFx#}|E_RBOY^kEo<%BO|PJ zilTI5pNgLE>hx(l@<#?trYTeaLbMRYiu3~e-n~E z;ytwHo_B{%eCnpPVd|J~rZZG&I5fmy}yZ~gj49{MNkYjZ}jlH#w&qe;PV7WI~o9;!|WMqBMMubFDO&X_k(H%T?eU7M^flw6S z4`jb%+@YV5IT+@(lbCtfXS(F zn&ScMqhE7V$*CJ(#0pA8rjxXiKAVkm0Z{EuXLDe6GdD+Wzp1g(a4(o~-e3!l(=m%yjBE3w^yyq4_6E}3=5Jm{g0A0lE8)QSrQsX}s=0)O)P zliDpLR8#hNy^{4RX?WU8DyNwy51IayyLNq#B+b$_TrR1QXk* zUBr$_$OIloNFf}^R;Mb$h>pJdeisJ@G?zWVwzt2ddH{TM=u z$dKy<8<-;k`y^iu^A_GVGS!O(1a&zuZv}~c($Y$?ErNHLsJ!gu+f#U6ru$FZZnuny zfMZ=L`*}`-{fWxG=23X=<#aU4ba@K~T@1gWj8|7Ne%_)|-t$^RE24hlAEuTt zmuI|Tf8j@Atv>I# z%T(sRp<;?hG7g8R9jw}C2&InF7YT$y|MsZ66UNx~Ji*#ZbT>q}66r`QT5O3w+@a@k z`P4`A#bQxpAgl#m8ke)>tu>2x?fOGp-L(4{JuQY`h7>f%HavjEJ6k`o+@RB0o)!=To+!??$d+g8kh1QcUa=W{I3-k;wG73D?@ zWpj4G-KBSk1YWhvm%B`vUtl*Xlt(su6P)i8!#e`TkR$PY#x9|w# za${FR#~Yy-&m%PpArqs%V&rGP47^zxG>txyh?OBY1QcZK+~QD0Rc%(O$_!+hNXelR zM0etS3K|Zi57-&f;=800XEppX4pfJ3N^xx+fIBP6HzJIOmnYs8X8&I#t7a7i{u0Cp zpmdi|(D0GgPiWA1%)4VPDw9Ewbf5v*#|vc$)wlT&--0RbYwr@lT!iUfaU#A=aYh2n zk2K@GGomx2Epv&Z-A1Z5X#prvJRgz;FYMIpqv7FiStVUXOUCXTgAd-?m3=9Ff3hxA z0_7Iybm8ndvj#HlSO)S9K)PCtk7)o0G0=OMTBT@;Etx_ArRjGq`!C`;Lhe${j``J z@kl*e%f|zo<)uPt&!6Gmi;k&GVEpmJ2!O+eDg7vcA(D$0LKJ4$Sz2WSM*Pjw{QMyLyMGP&iY2YnI@>Em(9H9?G4+oDtYcLn0h8a`9_@l`?8e=Lo zGL}eRTD&(4a?0YN(X^esFU7;D1}RgeN`!q$lxvLC{va_j7N;U&9RxaI3uMTTA&|P! z-1e$K=*ngHdX=qYQ}$AZWJStn(nhpl)mp_OLEU$g!#zP;-WYea$6t2vB7h)4|0UUZ zyLH{mP`fDMY2npk@=={Uz6Tv!Hjh$Lwi;9v(Z~@4aBXUecsXJZ7(+t*f5E_Y$h_ zdVZQNt)Zk@HJ6oXh1Ct-?SLHEK5i5X21cV^P94Iv=OK3C5$W#o1?kUw07ierV2|LF zifhkP5E;4BL(c=-z7g|X!N=iJ$Yu5SbBaHgaJQV6dTzKcWKoy00ouxm=`P#?nnCkS zfBdok@Tx5K1oQ+B)bbsN49qwNxIQaby(;84|8SgP7gkI9IhUf-#R+s%9^`GXSvj?n z)-JA^XW=eLcV&8CD|&SoR)1zTbe$_KwfPeYx;wUUo5n?rjOJDTk@r<9tx1*mSe5wO_nr#(EX zwoLW-g9N5*zi!rghGd{F?j31STUqn-?M|=5bM~AJA8(Q{6MvH6`gl$`CvW$Ln3FNz zc|V7#EaYJWbmA?yge8pf%IY><5to8b*E|Yy*>_48R#PMam1P&Ly*q7xltiK>?E#lv@C+Nldna6%1VOrBT;j&-O$b^B?LSdRjdI1%V1+xA! z;tsR0Vs2~FNlBYE-@w$Hys#&#rA(D1e+s+Q8Fj+gM068;rM4ifoZ;e#XzayGxI^Uy zc~Wxx+f4V0^cH4IVUoqJJc9c$7)&vDxmyD86iOfMI`#BNbU8bncX_@U9kuy3ZMgwE z)!lkG)6Z3ycwc~(@%Ce)$JC#3($FIAU;LPJXD|$I9JDG(B~E%joc!o1iEcz`$0A>Y zugDu8b={l!%0ZtB&9d~QefNu^!E9r#%rLJa-84^4N+Nj4~2LutA2i_ z>Z~C_F`i4mm%Btbu}mf(4E*i@j#HQ+n?CHPgalb(M4unHniL<;RUx6Q%|DlmH<$H8 z&S5z?zp(%cT;Uk^ZT8EMA88QF`@-tA<&#w_b;>Icp%XFxe*7AXPfF$!`VfS%h4&n_ zudqlbo@-X5w=DXbk-XGpm@K%`NYn!R#8m7!Xxh+3c8Xp2EOhP}o=1)8p8Cy+SAr$m z_cpuYV**Eobn$rlj#4fg>ve;Xsa^NKNQetiJF@|Q^wu<_Wv6WTzmH^j%-h~RURm0B zM&W0Rb+jvdU-9)opnLh&O4!112r6_jAOW3^*rwpCQ3U0Ln2gjxHigwPVj;ZB4vB8A z^#Csbp%D|YLl=fg+1eFB)Ksi~RD^<=Mn`i;U6{t1^bB%`p0E4HZkHBUoT!RB5>XWR zQ4#3O&fN1+oJJLL*c;hXYYzpW$+wgxY8nB9&=C z-2kB&{obu@J=_-|b-u&bS`F(6&CR`MKaQX_m=up_)ggC=9EwiUi@)1Gd@vhqs1>0Rm zo4C`u1c7JAn}Mlr3SqE8N4+uuCf&GEl{+yMqYcV*FbcZFfO&>RK%243?;NLweq97 z5w57+BDEO8iNoB`T7jZkiSIxuF4*%2Q`w(R7rYw}b>G4w-}PtGgJwet>;-`~#+S;^ zz4HhkRvbC)P(R!vrcaC!P*CCZTV#BXXo^YVmNIF^mXJ$ah{ZK> z_Rh?lE)mE|4ie<^3Z_vrLP!wMxLcTt>mx4~l0uM;bRcb=>^^N8DnRq;jiWQ5(!hVD=Ny82SXSQs2eta=jn!h%;Va@^BtVhtTRA! z{snRT*emZx(hs_`61iJ0 z@Q#_G?};M0D6~jj2+rQz#x+5$ZaYz4H*81E@QWr)Hx&p~gMVQ+S~p@|0HGg?=+GZA zg7peoco!*npu=MbA!)i*9>#Ev=o_x-eSTy1NnJc@+ZKP@7LDf#ze0y1Qo3^4Zp36P z0leV9j42^bU#OK^d7g!>vE{^S`*giK1g|IP%Hd*+1TfrDEgtdxEW-VyUB)Zj5*Em) zNv-RG>9#B1YjAjV;$qB4jCv%6D5Vd&d%|-7U`jlMpZSa4u<@3Up@t)cOlvxr6XJqkoSz6`WZ_KL#dW2MzArv^76}G z?k4e=N^TQ)R5bC_c8GpgoqB17|D1?OfTLk;%>1c*uIV5p+bsHnpu)!1H#dLJ)@z0= zF`eb*Gn15RPYS;Y)VJ;z;GaKgkTL2vFN7e_M@oo)|4{pPiGpPE9|IpM3=oJ411w4- z0id7AOG{{YWuNERdhF3-hF%MFMb_xZw0Ux@S}kUtZ48}#(H~2%H1{%-rA57kmp~UM z-+9>vYkida>gz4_cKz^hfNc8tE&UY~#(~8ZSkGetGPNBC4gE@oi223=g|BA{%ic1C zY-|@x(7QzV{{VphAXEqX`}+esmR4e}&m00J&EpekU)e3ndGD94CEv%8QC6d#zimPd}&&J@i66R2wX*CgGJEg}ikS4u=YAzPXdOL?gB zlx{gPBnl9BJ#9$@rKmMDdyk$?k*RSUX$eR;5=L4 z@{^Ydb9MfqY~=+sa6L z?>4%BG~Kkk_0-6+5SQ0{Qx!A261X>wbBzPX7mELm9^+gAxn&03bzMkYlk&gaId@i} z3^4=N;gk9j(=@YatQfWVHmuOJ$)KMRy|ZX;m)FDbbFfRs2riXhJ9|F9g7kqMdsUZO z%y}Q6Dw7b45!WWa@sCl?M_^nIAs>V$aI}uR#cpu52(vHSIm+m$K z`lx%OAx}@&Y#bK{+OJ-MNI?a#5u2OeJ@2>5xU3W^C6iLf&fxsAXOuyeVH;PPE0i7q zI1y>DzHzoNyYp}*>=jFa15m(mM?(z-VJ?aW#~kQvRE2KGTlDh{=#B3fjyEO}-{*^a zImBJ3hoXZ^P~|)$Mfq%Y9DqTm(e=XUN(M>$9U^(l(xfPenZey2^0;V$P9#U3#ml4EjS7RPziDdk+TklQT#R8M$5MEep7VqN>mj$dC|c zzZBOzfkjKb6ZeKY!oN$Gj)u^edA;IO6*HjK*#Fv0pm&2iy2vQ*yQqQ~RThfLOO8u{ zel+vQ5QPjfUWZG~XWRSW=`FauANPYsVC-H?ybclzzWu?O%ql;?E@p39LLqO7k#zbC zXk^9}0MkXI7pvEhh61YtKgE-R#+1t?~M0rpi%v!Y>V= zSr+~=&N#gp?=YoLU+!Gr@y&%ew0GB59Zh8#)XENC1$}DH_W+W-H80l`%vhCf`dTUH z<>JeyRYetZ5wE)oOD3RVQ9z1o(B-c4SK)5W)XUuD}MhHluL**%oambsnkn|STn@D-;POs>PE_w zJZ*dVN0jFHcDD=i$v?ax+L00PYGLbF>g<%95zh7S-Vsau_ff`5amS3d)L7R^-7j39 z(K28}%JMgrKJu51;~KEJ1WU&hyn^7)qu4JeA|ayYqP8a5H71;_y??;FjK{ zPUksPWF9(E|E5?{`NR+j_u zk^I5l(}?f-yxq}PAZ7tcf(epMxz+}4`tSFsx3i}+5!kf?5?AQ-r%?-lbv8UgoGDGeNsQ)o?Y;P7$xxqwwD#F@M-fJ_JXIq|p8f+M6b44Dhvk;yPGNLP-)%SG{k^=Ei-i&yQDxnH3#M%}r=JFV;$5g>JI{@E4asi(oA_IdQZzfNxQ8$wB<+cBxZ} zlJAk?g9Zss^UWO@M9PBTf5*kBI*{p6UxFo{l|N^^#~nB%iEQ%RwTK5=yugy5ap=R} zG*1*%Ph<7(`V{x}Ylqw=-%K5UC`)xFP!C2p$eOiQ- z%heasg(ll^bmxT{KngPHH+1kPqW=bokr?d@_4<70^-VCb0GCyjSYClbHTM;&;o*v* zgpRXH)doa<5e?d@r>F+rZXl=($EsyNHX;SlgoQ7(1m;Zgiu-Az2a7J$?~KVt5aH-2 zWyk2%(UEZM(HP3=eqS#Aj*>uCf%Y(h5!@H)5Mv8NNAj&|(%!D;W<>(QEqq7`)#$kF@OT4AExc(7TpQ>>GE8fw0mv+6A<_Y zH`_=6Z!fW$URYavN_~-+wUP zGpwKNgo6Ir7yxbebB~W;BU(OEZ=J+TT}=#}sEsJi?0Y8Vya+{38 zo+*D@FTv&wV)&k>#vg8t0B-gbkmIA#ZlXa$G7$$0P%X|U8jrSj1rkCZ2i_j({Nye? z?=FE?QIzdE$`_N~A*bKh-e%hZ0l%h0FvXqxRi`6K$;z(V9T{JHU}ujY5=6T;F^Jjf zA<)?T`K?xHsLk!TF@`!?_pni&bk@n8AJ%^@G@;X&iGm^IKE&w}K`2^Efb&3c0 z#?RD%OT;Pv(6WMuurM0&$>F)@-UUGmbN2yOr!l(ecF&_4`!ruJ%69zLt~{*57YnxO zYJ%wQ(Kxbx%@xi%^Z+~$0oBzmq(k6^_SXX_!Uw3C{Ov7Se5pQ2*H1RI=P-TEWm4De zAH7BaleUCu^flhAQW&%hjG>vq`{dUxCL;=xl451o-& zu|Y5Si*{Q~b@N=2j>NzgP(t0&j&vRu3_p!rZeG5!gsXn7jX-$qhQ5L_+b2}2al8Py z2|S!Edl-2+0~Nfq{f~!eug*=sk&7?=NYX>Z}41}otcBuE`4s` zR2D8pp<`eCb~^TK-q{Txft1x7`lqc)-oQZJgdQYkS{drgv`QEy6Co)6h8LcS0AZfq zU=egUNrfx!JkrJsS?SljS7VgF@eTkv`4aY;3n!=p$`kTv*_Az;*#dmRmpz~?!rnyt zFM(QO=wA7Cn^<{sQ^?StPKIO4`I=~3SrfdMdsdf0sNR8P0lmKYwzWN5K1Uw+hl1Ur z!}DWyPFaE`wqNOzY|+Gr^m9d|`nVcy^Bv(H17L}AXThOct4VNH7;DFYUBIQ>lW@`+ zZpm-?;-z(v_*syNHP-u`dj6B~oYB{sDSe*LGy=+)KnVm_ubB(eYyHvipO1SC!sp6) zzZFbj)6r^R1_2RiuKdSB%S0U4uTxYJ1mZ5Cgz!~#oA@L$jfKLKs%E_?a=`c zyQrnpYVW3+Sr1i=3y!iG5){Ax`jo&|$f&<>J}uvhftSew%?`!g!82_BT%Z=L3g7vj z7BhP;wRUB#e%x+bH$-ZwTJw))&4TlU*Nz1ga-Q*AJ<4FQ7?rWq7XUNIK;g&*UxAQ( zF`Q~Pc$w!a6|NkSA~*Q}iut;icDYAy6698j|7e^_9en9)0!<3&DY(4g8mfx+4kVAy zckZvbv^-d9M`ZX0w~xkk-rRzJZ(2XG1T_jN!r;-sHk3-mEkenQ#Ou+$cw(Uhnh&I# z>A6QIA$7oR1TVQX188%mkRvWIBY(bODBMiq=HzIFw8L&Fvj(`}q~GlBsC26iU1n^; z)&)f3dz@0njb{U9yMApkn_QcqvL-s5^@CG9{$LN9{oL>kh`@>VSvXwwURrp@pP!jG zMI#)k%ir8f(8}2Z7rqV{i7m>cwa=Uo^vH%n1g?bXYG&l#0onzGA6q1ik*cbacDj`- z3>T5)$o_89Wv04bGVx;(z(fgsSd>l+k`Jt}SET3!YwmbSqWOa$P(LhX&ayV;4{^so zLGZhk{!=%4F2M25P?aC!q-AO%joG|AN4hdJ2CO6XgO!3#0XJT<+jrSd#eEq z&&U9@uS(MKz>EW^0=3YLJf@fJ0I}lt-f7`FD2%!E3B=Vq$T2v_Yz#_Nj#=9`fFhfE za`?5N(+dh?xd^aRx>Mv`B-ELc6>B7RJyH)stUfL05k^ z_O7>#HQh@XolMRKQW3y>geCojfvVcBDdJMhVuf117u46(vGRqR{P z`kPWgfoOf88gn3!q5l7K4*y9x{7p)*{qL;A8`=cN_`bs2%=JGK4EYbr(lwICU;j(t z0iNU&g!-p08Hu0g-z^2W_X9H6i68!7w(r0D8~OSEW!DM(GY$>Tm4QY2UrG`1KmA)W zh+t)b|MAli(D*l=>z}sqKp^d31C4=_8W8^)S(M`XZ*d72Pnv=3AH~T3S3dnu_4GfA zk^g%vfQ_VywEw~U?}QN2{{{R#TSfqZOdTEE%pKhRk(j6|KtN)H{v&DmU-_cH5|{sS zL;=rA)BTIuA88^;3tsR#9~D^m1LD8B5RM6db4 zRssxQ5n1H__{s5udjyCX|A*SYYt1Fi1~fi=`K#pF + * + * 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 ramtron.c + * + * ramtron service and utility app. + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include "systemlib/systemlib.h" +#include "systemlib/param/param.h" +#include "systemlib/err.h" + +__EXPORT int ramtron_main(int argc, char *argv[]); + +#ifndef CONFIG_MTD_RAMTRON + +/* create a fake command with decent message to not confuse users */ +int ramtron_main(int argc, char *argv[]) +{ + errx(1, "RAMTRON not enabled, skipping."); +} +#else + +static void ramtron_attach(void); +static void ramtron_start(void); +static void ramtron_erase(void); +static void ramtron_ioctl(unsigned operation); +static void ramtron_save(const char *name); +static void ramtron_load(const char *name); +static void ramtron_test(void); + +static bool attached = false; +static bool started = false; +static struct mtd_dev_s *ramtron_mtd; + +int ramtron_main(int argc, char *argv[]) +{ + if (argc >= 2) { + if (!strcmp(argv[1], "start")) + ramtron_start(); + + if (!strcmp(argv[1], "save_param")) + ramtron_save(argv[2]); + + if (!strcmp(argv[1], "load_param")) + ramtron_load(argv[2]); + + if (!strcmp(argv[1], "erase")) + ramtron_erase(); + + if (!strcmp(argv[1], "test")) + ramtron_test(); + + if (0) { /* these actually require a file on the filesystem... */ + + if (!strcmp(argv[1], "reformat")) + ramtron_ioctl(FIOC_REFORMAT); + + if (!strcmp(argv[1], "repack")) + ramtron_ioctl(FIOC_OPTIMIZE); + } + } + + errx(1, "expected a command, try 'start'\n\t'save_param /ramtron/parameters'\n\t'load_param /ramtron/parameters'\n\t'erase'\n"); +} + +struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev); + + +static void +ramtron_attach(void) +{ + /* find the right spi */ + struct spi_dev_s *spi = up_spiinitialize(2); + /* this resets the spi bus, set correct bus speed again */ + // xxx set in ramtron driver, leave this out +// SPI_SETFREQUENCY(spi, 4000000); + SPI_SETFREQUENCY(spi, 375000000); + SPI_SETBITS(spi, 8); + SPI_SETMODE(spi, SPIDEV_MODE3); + SPI_SELECT(spi, SPIDEV_FLASH, false); + + if (spi == NULL) + errx(1, "failed to locate spi bus"); + + /* start the MTD driver, attempt 5 times */ + for (int i = 0; i < 5; i++) { + ramtron_mtd = ramtron_initialize(spi); + if (ramtron_mtd) { + /* abort on first valid result */ + if (i > 0) { + warnx("warning: ramtron needed %d attempts to attach", i+1); + } + break; + } + } + + /* if last attempt is still unsuccessful, abort */ + if (ramtron_mtd == NULL) + errx(1, "failed to initialize ramtron driver"); + + attached = true; +} + +static void +ramtron_start(void) +{ + int ret; + + if (started) + errx(1, "ramtron already mounted"); + + if (!attached) + ramtron_attach(); + + /* start NXFFS */ + ret = nxffs_initialize(ramtron_mtd); + + if (ret < 0) + errx(1, "failed to initialize NXFFS - erase ramtron to reformat"); + + /* mount the ramtron */ + ret = mount(NULL, "/ramtron", "nxffs", 0, NULL); + + if (ret < 0) + errx(1, "failed to mount /ramtron - erase ramtron to reformat"); + + started = true; + warnx("mounted ramtron at /ramtron"); + exit(0); +} + +//extern int at24c_nuke(void); + +static void +ramtron_erase(void) +{ + if (!attached) + ramtron_attach(); + +// if (at24c_nuke()) + errx(1, "erase failed"); + + errx(0, "erase done, reboot now"); +} + +static void +ramtron_ioctl(unsigned operation) +{ + int fd; + + fd = open("/ramtron/.", 0); + + if (fd < 0) + err(1, "open /ramtron"); + + if (ioctl(fd, operation, 0) < 0) + err(1, "ioctl"); + + exit(0); +} + +static void +ramtron_save(const char *name) +{ + if (!started) + errx(1, "must be started first"); + + if (!name) + err(1, "missing argument for device name, try '/ramtron/parameters'"); + + warnx("WARNING: 'ramtron save_param' deprecated - use 'param save' instead"); + + /* delete the file in case it exists */ + unlink(name); + + /* create the file */ + int fd = open(name, O_WRONLY | O_CREAT | O_EXCL); + + if (fd < 0) + err(1, "opening '%s' failed", name); + + int result = param_export(fd, false); + close(fd); + + if (result < 0) { + unlink(name); + errx(1, "error exporting to '%s'", name); + } + + exit(0); +} + +static void +ramtron_load(const char *name) +{ + if (!started) + errx(1, "must be started first"); + + if (!name) + err(1, "missing argument for device name, try '/ramtron/parameters'"); + + warnx("WARNING: 'ramtron load_param' deprecated - use 'param load' instead"); + + int fd = open(name, O_RDONLY); + + if (fd < 0) + err(1, "open '%s'", name); + + int result = param_load(fd); + close(fd); + + if (result < 0) + errx(1, "error importing from '%s'", name); + + exit(0); +} + +//extern void at24c_test(void); + +static void +ramtron_test(void) +{ +// at24c_test(); + exit(0); +} + +#endif From 382c637fab66291a28b18f7481aad3b866de6639 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 15:41:10 +0200 Subject: [PATCH 25/88] Fixed stack sizes for airspeed drivers --- src/drivers/ets_airspeed/module.mk | 2 +- src/drivers/meas_airspeed/module.mk | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk index cb5d3b1ed0..15346c5c55 100644 --- a/src/drivers/ets_airspeed/module.mk +++ b/src/drivers/ets_airspeed/module.mk @@ -36,6 +36,6 @@ # MODULE_COMMAND = ets_airspeed -MODULE_STACKSIZE = 1024 +MODULE_STACKSIZE = 2048 SRCS = ets_airspeed.cpp diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk index ddcd54351f..fed4078b63 100644 --- a/src/drivers/meas_airspeed/module.mk +++ b/src/drivers/meas_airspeed/module.mk @@ -36,6 +36,6 @@ # MODULE_COMMAND = meas_airspeed -MODULE_STACKSIZE = 1024 +MODULE_STACKSIZE = 2048 SRCS = meas_airspeed.cpp From f4e115160766510ef135bc02449e08fd26b87cf1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 15:43:31 +0200 Subject: [PATCH 26/88] Hotfix: Cleaned up outdated docs --- Documentation/commander_app.odg | Bin 11628 -> 0 bytes Documentation/commander_app.png | Bin 25356 -> 0 bytes Documentation/position_control.odg | Bin 12559 -> 0 bytes Documentation/position_control.png | Bin 36561 -> 0 bytes Documentation/position_estimator_app.odg | Bin 12160 -> 0 bytes Documentation/position_estimator_app.pdf | Bin 14243 -> 0 bytes Documentation/position_estimator_app.png | Bin 29623 -> 0 bytes Documentation/state_machine.odg | Bin 18576 -> 0 bytes Documentation/state_machine.png | Bin 208880 -> 0 bytes 9 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 Documentation/commander_app.odg delete mode 100644 Documentation/commander_app.png delete mode 100644 Documentation/position_control.odg delete mode 100644 Documentation/position_control.png delete mode 100644 Documentation/position_estimator_app.odg delete mode 100644 Documentation/position_estimator_app.pdf delete mode 100644 Documentation/position_estimator_app.png delete mode 100644 Documentation/state_machine.odg delete mode 100644 Documentation/state_machine.png diff --git a/Documentation/commander_app.odg b/Documentation/commander_app.odg deleted file mode 100644 index 17459f7cfc9ba8ae35122c0c9ccca1ca729436e6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 11628 zcmdUVbwE_x_Wwwil+xXjLw6`Bjgrzi)DSZ;Ln9yv2+}Ft-AIXaryxj(bT=p=sr&}L zK7IGy`+oQR`Q6MJ&N+L1K6~wT_UyCPURzZO8Ra$rfB^u2&2HUGN9O8e2LJ%q2jUjM z9&B&nfm4p2AMj6p%9=8#GDIi3J1fvpbi!gb12B!-U8ypWd$>Jum*$Rs{cla zU1}Pij{*Q(AKwWroJ_gg?Cr#*5MQ(|7BD!1Qi7g`i<_R-0s?}XgCSND^jey-oWk@{ zl33zUOG_}wLiA@VoCtMHX%SEeT=Ykk1idp1BKln)QHZI%1zgk#B>KBzqQ6UvesAc< z9XC5L#8!gd+R4d56bN*6b>(v9aJQ}$ZJf2!2A?C&Z$z%1Yh!tZweryRdye&>Qhq5o3)+8#g5^<8ydZf<_y zkL#aW!|lO#|Fp$xSxykt-T|SfnVrS&jhaHh_WzXTTK0QSe&GW4 z{{10>Az&x4DZ(r;3sWa3Oj6StYHtdsm2*ZI2qq5vOPL?Y?+C3#Pk`H=hf&%YY-i5N`$rqU z=zh@uYo35#|A^pDU=Zzh(?iX!DG-C!8RCSPZG`E8lHz}i3DF-<@#odQ7{1^BF_~dt zV0@n)5fkFS3J&57ZsBxoGWhj`Hmf%cTN1|inlG1EyQt9DM@ha*Sb(XqMw|fX=wfb7 zt{{3xtHh-cZrbe4giMBpW2)R()8O9Q6+g5IsTq@_lJqiqbGk*u8-B-KesfZ93yUyW zG-!}oJzn?Ge7@vM?~D7!Mv*r|aBI9s2&2|iF+}{0`!@YaCd+BmB^e%I2`@cBGUyFy z=TgUu-mPBR+c1-_^?ubE#6hhNr)xB0zJ=1}>;PAp;>ae!3Q#_E5gP+VD&3)#em2Z7 zlUk)@t8w6Gxt>)bw?C90+e}uDk8Gbe1*fEhE2VOutb zI%h|b(f(c9D9`Hblpegja38{VB;tN{&qN(qJ{HT;d2t@@uH z+|OEv2PB7#q(?EVseP)yv@dhud4ilZB|dt&QyMQZeOZm&$WM=JAZ?Y7jW$wDG!%u| z|9D*o=UHBr6*Gx)o^(+Tp-coxuv}mY^L!@=&s&i-@M(^s-`OX^Q_*a5sZQtu5OA2V zp(07!%2#N1<~CioVaWZ=zST15(~A7q2{HYrJ6-7ho7+be)elnpo(ESs70$@?3BT`> zgaVdKdT&xb9rv8_B+w--Wkas=odF9+trnWD&?BMjs5fFQPekMSXP#yaF-eqz9cM*W z6x*}k`c=0oK5q7U(zs5M(CvkJGnJ5!*c**d#Wk-2TmgUa zt9%6xljo1`-PT*?a&?`2SF@8U+4!p7RG8`6s;43wTi4 zdbf88?SuE0zm?D6@vO9Kf$$wu8sFl6o?`|rCuPI)tCofpQ1|6dgVNx_9UjBXr;cu8 z9ul4;?@wtKdhA=d|*>Y6#0XP`_gewKo(lSJD{;SBs-B(X( zmd!7%4^-XRlgQQDKW~g5MAOrc+`>P-r8ry8C{3LLf_HYz;&xR|Cg;f=0dTv{zLp*% zrw7DcXp-VQSR`W4TZ{L^|MZHLf<%cS>U@yD#@ zq>(leS_Q>PwM7Beiv4&*-kF0DyNOg0)mW$Eg88>%ZZ!jFuocAcM?99a`-eV5j8k8+ z!YJkE;`a~cjFs5*q@)j^W~d4?H77(@1e&(^8fk#Q)_Zl(XCB=(wK!Hm1r%m>{^X7i zhgyzOJX_>%pes~-V3iCZIYYyDx%3i<(C192Wk7prJ9iw+d6`pYs6y=m>yPE)R?bUo zR8mFzLLV%)#nsbSd)meLikSI5;mwh4`Oa7}D?E%zZ2~Da&F^+PcLxvRx)nXM5*!YGnvw#?cL_py)wji zzZdFGwXaCV18PmidoroA<#3a)a2+|c)B6Juj2BQ5DPXaxc@^`_K$tsKMIO3k{@w%d^o?c)btY0xK7%i8FPE3etElYhKfB#%!yFq(5p=lvC zb2xBB@RBAwN!H7(FFgc2%#8-QaZI!Q(anT|J*N?A*xjDjhS+1Cv((?9uuV zgLkU;d(ZdDz@*&?iJni*D$xEp^D(Y!&ot7AW_%G>9`7$s7kNNt!hBouMng=$$K!6~ zR@eqZhRU)QH#KXtdOjhEHFSoHt-xktzJ73JiRj>P+gm8pohFm|+^t(oYrm;mDnbnyq0ziro)#73B883NwJ9Kshu+Sc)O_> zF%I~vD9kN=yPEl}gKHC_?%&ITo&|f&TulR~=$$Lg^&!U}_R^eEZtM^jzu=%sD_ZL6 zZJ?l0$X*Kq_Mtn?3Ws*xxKCGlDccsC+x?Xcn5B_Qu6czv(CLZpI z;D~FOQ1cZ+Tys7BC}3Ps**(pxMuMaI2tK&!OET?mnQo;x=q@>a{MItto+FG%i3;^z zh7x$&;ltKyF@2PtT0x9|P@5tZSRU%6(f(QI${#YBYZo`9z(Y}>a;94?yz`lsz~2J=Swq<8T!n;JD^~pu@v(d=lYgN&|8@YIRIJDJ zQ|%PY=zt>S)76d!w$B5@3deO09(ngg)VBgr(fsx^3fVGk!e8DWd9L!ZD{AvqtGjYX zo=8uCPFF8_4KLv$$s)aalDF+G0rXJ$Hda=a_8X+-Cg}msUWdj(V%YRdMq)o90j*`J zRhB9%Lsc-!_~Z4GG{JYhyX#UjcD?bNrwF22Fz zqSu^(d0)AkS6wKm5E-R{yvpxe8wyY}s7zM^1c<6C2imJ9ckw#T0R2 z*Q$Y}U-DE~`o<9EV57;)nQ<1v;<4)@85*~$hsoCI)za~q%-aH5k8qhD2q-cjv29Rs zr7#4#Q<%-ZKEzVn`4IU`ChSr0>3`7tT@|eT%qU()h;3RhbVObm-`&yXgDf6 zg@rO!YkR7->Ef<#2Q%v`Y4GK~hBfiQSQ_l0AihHo`9$3My0gqc6U%HB9Six#Hffp5 zi;(Nn-icUjg^3sNs8GfL^D1P%`3u^kEzdX4 zDE)*vjC5+oZe+i? zorsi|45@kx6>O8QLMjK(^jn0`@DFnv`w|Cb`zE=$t3;GN+BHIzkD(ecojwNWXWq6_ zli-ssPt0u$^f#}3y%09WWXihO^)MU=Ve>Ith~wd5W`>2GS9y=gKCXC`c4-)W5kx;}5jGAAbEcS})tPpm>uO}xK7^sS#Y&Fawe20% zGkFa<9`Se{@ucVAjp33=JfJZ?wA-iMG#E+~-4;hGP(#A}%45pWA{eZ$ce`XGMXh%I zg`p#ycZ%c-rp~Q$I^CBxR0lUJFxVjS{jeZ;FJfo0S)UftfF0_9ooUq#X0nZ;3<|zp z@*dj!9@_N*n}pmK0MDRUS}Zn2TSU{+XWvOj9yW~b?o<;ZQ~tu9F2UQ zia*+qJ7F(qghU+eg^lKwqRy>ie~Yzpa`K!>~@j*}Cb#QuiDr z&ff7S?gVoVSoNkTuer!yD;|^El)kHUnBQ)38K@ zPB9FNXWKn!3Pez4GWfwsc{?}Lrm#3Zz0WeQ;4bL^m_QUWtC%d!nfksQyonAcb=`C$ zyz3omx!FA5WRblN4~&W*X^>?rO0109y~$(6FrS+45#M0P+XbR6f`y?z#x7G1UK@Cc z15kye#0C=GWI|v|{>`*quIb3RHA>XyOeWI`H!#hW?Wi$d25)L1yZ5v=EXp3m_PwM1 zDK=So+|i>}m)PTU%w#Y259S|VR(Lrl2#{T3)4`#riOU|csEIZoeLojfB+}E-sJ-29 zx7178KbNbx$;I8czPKh8MlmL9to~NWOo)4;?DUC1C(>KqXAGSlZSEC#o-e@P4)L*N zX^Edk5b_A&+WC~eC|~FzzV#OSIGxKtnetPGk+Q*}d3{|%ulAvT{O6U1aVhVMO>fl$ z3#AuDDl-lH<(Cg)8V4smwZERXUR5nFUR^snp;H~^6^O;cqkBIcouA8-hKJ!>M2MQ} zgB0QDXj(hln?X#$c5tB6&r>c3h*hxaL%Ew+KK}hs?pO4UA=rDd`M7Vy!ka97 z=7&Rj4xBDrPnsJ%*Y^@PPA=@97InJe0fJbNp7Q_S`BYmYRZQ7Lwao5$NGxJdyjaw?l+>7p0*wf zYVJyYd~zl|{d$MBQ1@F)#P0mK+UG9^6UY}s-=eD*f_o(TkoW1%U!V;Rxc2R(#5#Ci zCFTT&v!}XuMG()&{!7ho)>;H^suV+v=e@%ueQ+G{Q%O?S}KvQRS_@A^g3&Wh2?1H+$&e;;;=`gJL>FLlk`W# zT)NX&$&)PN>~jYO$xh`?0aDb(Wo{?|6n7hOy_YW7@E?VH>KqpclmPr9kQt26ZiEu- zQ9sr8Hc<$qMtX3vVb$Urb?Y&}amKEyha0oF3}Xn@k00r-PL44uQppPdZ5ZOSeWRVK z573Rn(R?K-am35h#~sL;^gh$x01uyg6q&+Ivl|!_3FqG}!Zhahe5xaH&UsdZB>OU` z9G&z?ZTqD5f-r{4@ne~s@W}^kT-p(<4Q`wiR^YQQ^JMNoO|OIFGyfL7=}T4+OHO`n zC>Xli%c(4(J02_Iu6RCpnPMDqB`|k(D3{#gX#eD*a8m(!--=Wl^(g)LR9|V}RRnbU zvaN0CECdVYX=&(LA?Q4@GB94qb+PVwYoavW@Z>D~)*N`XSlSqq`-59Mxs{2$iiV|C z`jornmW;@8O`3)4gqD_fO>y>8s+K)^xIyFP>|VS(MfzK*N@qEctn6rdA3S~tELyQ| zCzBpRJW>8OV&h|QSt8`(Q#MU^%hAUp&SabP`P0_3XL3zL3YcNfi(+7WJDidym&p{k z>CFkBKW+KFPxo@9b5y<{f=+NedYhKicUFeV6yTHA@J{DqnaQ}jv#|b~hM^LR*LdJ+ z%tyPjOJ%u&db!$u(XB6gH^bMb&pS(!4@R5Ii_+W%cH)%akL+h*D>nTf7$;4(+vTHn zZ+O(*2-knXJ`s2tT!%Jw7}9SjVG|ZRDMi#Mz!_mtkF~esh0#G z;+tB35&O{V?Hj_yWXzq%fRT{p*3fk4-ljURw#w;iYFb5(TQNAG1Yr`4(Lrx6eD18J zFLN1!N|g7uDz@_2Ap1A_m9n^ztEA8?x<%@UO~!A=Pa#+6E~V%vJbr>yv9*Sh{cz{u z^YD<@>8N395K>P7^e_{MCumRtPOjtzvNs)m>gkE8g32pb)l98x&FmLLh37R-W`oD9 zj5yx9bV3^2V(h4^@$u&tAbyoh0I|dQYTh;S+%Er1GNxI zuGol7x*SIc&cF5~&e;==ee7g0yqH%E;>CI_-ZZ#N>84$I!H#$UE_e%0oJNPz4zT4z zL!q{g^f}~EZJO;jtZZZ}b)5B_ZPvH5U)~e5VXM=Ad||k%1T7bH8WV%K^!fFHWWJi* z_EdKvAr;}lYTaZrK7=`pdhIIM*j1EY&pAODTtSsv^iO$Zu9y;Dm=UTJ3X#!Rc8a(KGw<>$kqb zgNOIaq)q((Ju!J*^Rv((PGq1EOR&`+xequm5Rsd*vVa4n!A|z34shV#gUSB_>;QFe zc0i;Co&QIi6BKIaU<$FY`yX-F*$!v8nJMhQ;3)q}PZ-n+k#hY1Ag?{GKbz-T)BoPy zU!kr|^1q`j?VyO%*w4QGRWgR<*BR$?N-qHF1MpVTd<*rw$qKUyWJ6yr@cp-*6(cUK=Ufn5T^osq5aTLl= zCh6QeK}pcZdp*WJ_qF%%CVkv`V*F*z$qozp<+;>YT|;AWN!M3LF|;8}2TVOooG(R& z z$md_;Fi}1bXRpXXuX=68f7J-nU=7J#x38P-a}ixMTSg7(YJWfK(ymslt?36Y6+XaV z*fPx}QAR2sc^lLTTF-adWnI;(Wj5m%&{@jX;zU6#r7f_vP`WZq=Pet%CXdWH*O6t2 zC{~j0TItnqv%Pm~ELH|h3wH2Q>CCh5qxqkwC*ygx5KeutVx7g+ipuD+PLQ3hT~Ddg z&_c7U+TILomO31)$!(G-Y$nnqG%b{48D|*Gig!#qjzaVBMJErMVSNd8w2BRrz4-?D zp&wi{$s^ZurARtTD#&3EQ{911Upo5pJ(4uSS~`X}G74NW#g7G$`;;d|?M`{r{&*i6 zH^QTLT_G$KDK7q9z6=}h&Le{#zXI(mJZn9Pec0eN0AsswxID*u)EB9E6aR8+$K0ax zT@wW1ym(CRkA<1)zZkwRe17%fJnq7ZPFNh@tXG}qfW*56=GEgWJ)d}PN$Gc&xRn%Z zOo#m3*r2@Gm=*O(Sv7QEta&qnpQR<>8+6|^rL&BntD1v!F0<*y`>07Wtw?!6VuSb_ zt(8CmhBMhNVjtd<@~pw=0K;(y`M7w(b+!|sWxR~D-kes2o2+B67rtz*SEK5F@w4Mh zeWxZkG`4AtCyk3vdvUmcf8Ydw38x=RHAyU3 z8kN@!^o5i4yW!MXA@w;kC<;?LfvIm1Jsi)}o`0ZnpC3h1dI zBRZ;lhM$%2zV&TQ*#&%89o1W)WUII%>yPd@bSP6qY)6H_y zdhPCf?@v~4eY0AfS!#UZ5FKVw&(72rzW%ZIgs+x=EQbP>@AxC;)|AjIAef=hl;5xA z+l-Jv+-I`-D>mWMUD}MtAX4?>QS73)yd(U_?B~{BZh3kYBT;;eHwv7=x=(NSoF}L(>)7kt;l_MoE*9qv?w6|vBn$3Qr)rPNva1mMTNRfCGnl4^x9>u+I?%9v&fH3Ym+&}pmrL) zZ;PZw4VHKF!chTstD0P1j`Q$0(8_3+M`xaOkz%n_Y4^QL4&mYVio0xVqLeD+DK9qqftzYwaeH5z7VJC%Xa{L9B{G`YpmNYCE=|y@EpZ zHz0dob-e98dBsq#g^T%ZwYQYxUvFiL_HJU#amW}c9Jkg!th(<(&r8(!F{c2MzA8>L zE={KK*5?5_)9WI!JC-GhF}>W=Rb#hpEX#;9ur_YxosB)W)Q8W_l+U5xm!=BID0%DL z&~NEbA$JIjzG`YeYbk`wFtnwnV|XDg2LdS z^;cl&E{##$o-8pv_1)1&qXOqxEBGf``@7%_sTGPmyaLz$jl$xlBOGsN?S8gp{o3a} zCM%Eg0xgzNA^f|;vbp5tm`u+kcGhKtoEZ7`>)+TfRhcG%ChD*cLg7{?A3jia%Z=X4 zjq`6&lS_L$1T#lvb;DGC29$VmaXeU+8}hlKmvNzTfFP}faxrE-<4f$q{`{KL1g%1r zb>(U8gvlVY&?6BJAWPd_-zhAQiIYb1s)mjCRnZEH4kbe!KpI`@jAlzXG42Q%+Omi! z6vR*2Bwyem68&b?OCzFOBxE>$FSxy5NNKhtpHG^}?qH)b)Dq=ooLl%;4+AHooa&tm z$;?T}LNS`HeR3r3ji&y>lI_t-+uL8d0Q-m~v2%5=lH6w7FjWR?w>kXIPq+RtP3mABQ71nvWF?!*d36o%xt;L;wWiK(3{${ic!h9 za=#4DejCsRok=w zY-0--D?XZg!d8Pv<|#BQR(V{{{EB#TI_61h?&Ot{z+}t!q+oVjIB^uhor&f9Z;lKR z!jVyVpm~o|;h`+h97F= z5b%*AEVR!n)W|-z1YI;)Nxa_~9(v3Y)aPb5#qMKDl<_6CEz=_XdBl0xu4{5PE58I| z^veu3ctRO?0Cs;c6rL^^JO4$Gl>($ZVI9?d+Gto?H>K*Zh(8>^-5SNt#)&??x>Gto9HhRt)EmuZ?;G z={Df+cSv4)kiW{${gQu1{dpVYFN7N6^m?n&wTJl=_0z@uJ>z@5-{@DNM*a8QM}J2C zzJz+65&l(b5tqN^hkpY9ZiV$1FdboozgutpGs`a&0B{{#{VH3CFyzm%#D9cZ|8DVL zU;yAc*!opisQ#1e_t5K~@)-XG&+nnwKjnG(7d*d*W`ECf9i06t!+*hp*ai1nsP^|v z*J0PMf=T_K7Wx&s{ZkgHzhL+(!$`K>((#TY*A2d{Y3tMC4%nO zJ$Mt{PE1M|eGKF74LsBcX2vQM6fzVsApu3Fk=1c$O+|x~<}F*pS7?N~gzUnocyCZU z#(wZBXcmn{+Q_uAxY|h3mC2Jbu-V>}D`GjQDek7Xon-4nC-`YiBfD?#R;_abJ2L@6 z#`xBDYUjK`<%(_G(;@ds+j+Nz_5fq`@w

x}UG_O=4DR83dczppb}2u3Ax(A!1Cv?)-S=3^j(;Bs47S zsd0BATv;mmn=CaZt<%nYN2UErQ&ZD~&J%ii^VV>hwULrG2B(G2xYgCwwb3$eZtloG zjqFwv)o|DC?UE#pve|`&g_$aOwFYfpZ01^fZo+8dkp8wl*Iyxle6)Q2Sz^`AwUP?)IbRxgli33|&S{{eB=(Bw7nE&>T zB5T0K6EQY9&lL6L%XeAoZG!gBPHAar_Lz>0j0|VY@87=trjK%c|FupR-i0p#)Es5A zb1xbiny+8K9$^_88p0vCin5{K#tIJzBxPjE)Sl4Mtz3b_vO2tmhleXr^E4}Lb{FMJ z)EUI&m$c1ingZ`$6UZ9aF89`ph>LSy{at{Hh2Q@5sh=f0TVnc$)S1{0y@J!-J{edW zc(jV?ss+h@e&{dg2u=<*JkR!q=u~nwmnQ=se@Z69i0w%#XV5I)TpzEp7%4tFKiOD9 zLqYK(Q_PU3WMs6g_qpEpT`J|?kJogRDx~cR{GRJ$74P1?t4{jZ zapa*Wu8&U+b?4i^W~t=CYTH{L$Rd)i$XCzdc3jVfwS0bd0*lcE19|9g&f#WsZim%! z$BlUP97B48**+QmIJon=x{I$*jTYf?;UIpZW^{aiVH}_Q{QRcCdtGtdkpM-`II1WU(q*_*_2yr0K`kYb!blx|b&FoY1Gn?6$ zB61?NXZxe!;kZUdMt`r%@~G`_ssWq7+IqTvtil%dMmOx( zFUs<$u8Z$OU|<}C3kUEcRpAM-!n@HF}c1`qh$e#8Dl zAl`+9VTpxS*VL4#Td1o3>yI?5o!;o_>6MrcAY;WGFE_h4UN-_TH5KtRLhbVDS)njS0h*U(@NxsHO{7FqVgxK<1! z9dklVrb;;{jxAnG8yD1GBf=_3sPGx9s`i+SiYg5vKM4tm+d@LMW{ryyu5gX^#_X)3 z!@9kYkPjJ#Ro$6`tZcVgUJbj`rmm={=wt6QSrwAfwMCS;dvVD7B=I}bcF%|De1G%a z`Qc2k?Lw!!%Vdvf&?x`HoMFk;Eai-0w<$03kN5&O*ZSf}`BwW_pOt%@xpWoZ-`sjv zg^#dv7mJDJ#b+Si+4i>}9yDRmU79|_(peeKP&yk)%JZ=26{SAKzJ{=~9Xc7mHQ zJUEOxwfAvxiy=BdAPLXt%ES?t!@1_)Xmfsg#4+L2(AYTl)hJ%A)LiYOX0WX3P*D$2eQs&s85GxWj*i~J9FARTYPC#yaqyi-S4GDHZf5*_hii4+@=WPFt+EN% z5B3HrEv4L^1_EuwOdS`8C6;j`CFvKEF>+>khHp?Hu)U4_y)l4(akk-^r&YCYSNE#X z&9yI`qjX5~&0^bprN)Y1v8RQ&cY}ZQ_gqig{-7US2YD7Vl;gwaE>%NR*B)TzttGzX zwtdd;Iex3IJwfDsHH+q<-Nx~Ft;r;|#j*C!#`q$y2;WnIn)Y8}ughGSP7M@9y8_5b zil7U#%>C+$(V;r?S(G zQEK56vDlt%flRBAH2}e^cqc;#@-~D-f=SeWE@m;TYW9@Z_b?>;>!~ug%B*G{=kXtZ zbgl19%6aT&Q?25($#lfQ@pG{Bk$P2BvI>9uy!l4vMr%(|p526t%b%yMSvo)ylBT2gn;Gv6J3~$n)+8qhXqWlj1|GR*}E~FgxbgX9|dSI&udifTUZTL zV6^aC@^193r5I|{3gEbn-ZEi!KJ27^{XnjJ&~5AJlc|7RrfQ#p?Lz8cEvKxheGwX}4j}bbQACeO@dQv13Q>ZbdBfP7nCYuZ> zCj0|vF6t%h?UKoy%I^PeF>0;cXN!YQ_{N6n>IA6VOMb}6Bj4IBxykmG| zz~|7tPQ|G}NqU;p-L@5R*iiv zX5?7jUChqT#v)+6@qnxUmP*2~`4@@|K#CzDA@{u@V12-j|8=~#!eKGeU+}tFMaO+_ ziLXs6Sf-TAm20jREyK=+1H(&KJXj{gj*ro^#yGwA=$WCGB-?c_GOk5dOxWA+%`$0HXdB)HPt_;qg2Her&)7}?q5iFAZM&ujQj(+q&uhrEJkB( zII+Cv6U=du{#tIu`hbc6p9#zDZf;sTIFv3pCqzWpLz2(Vrq5BN%4A=yF`k4=!>OaZod+I_Ac|kYRjj_nXwL)#{LJ#kJS2 z92@0wQf5xqBgx!3iir(ZlwF8mobWtTTw2WSI4AFuH-D;`B%7{CDvWrRCu z%ECHi+^0&-hqotOHwH2k7Rn|)=wi&ol4NJKb*w#2aR>;8AVEVASIX5?%TXqfag+T- zl^IURc|OgtaCjJ_U^;$3wf&o978x}vBAhTr-{W`Zf<+->++hI~5lb9tc>4yeK)(LO zQ`4K3fBesi)h(dZsJ%FM<<_K;h-7^5)KGHW$QL%&bLli5hjJO0nu+G-=3BKE0{tAz zYW#0TTN7p^gkJAILv z7;YngFh;FPYTQrd<>i2~NccTYe}23R_ye#o%iX<#$IB@eoo8DdY1Y`c_CAhREM&@s z2B?(LpE37r=f`!8&T`e3a&1sxcpYswbrAGYBBHJB8g47ds@m6nMZ%h&=)oos;s6q9 zR5@7K*%c=wOe##0D*0;rN7_}fr5Xfg4ve;U+%I2EQMOFZ6wITPa2Y#Kv>$ibBd#vj z+?j7x%h{7T<%;f2>#J(0X1BBIPBf`{c&~cm>)^mv)$~<-(YfEJW`4`$^TAuAgH@I} z#|)w**?n2>!v^%+D{C@!>O5eDLkgGwGUE-PHC)$J7XNYPS_eag=59=1zsKu|mj_Ih zd^?ga7fkBP*6|bFe|0Wc6;>v8nt6}(8G*|NQe$yWtMUq+1`o!(jJ zp{Yd{cMm???-c3&cF#vB6l7k$1l;?fsHi9}kLfBoxwf`8AU4P|_&Lv$Y?AS@-7MBN zoG0C;#ugi-utqES8?pNooJwPuXCgTsvuAONtr`9dRK$glq zc5?_fR%7MU%ge1!zZ&7R7l5o9{IKucKqDn3y}W1@9sxn*moE+n>ssnpcs{1xC%w<( z^n{yxw5KN|E-8&h3>rjq}AxE#v!j04sgZ>Wra{P@ulM#W*$>mz}! zPr=L#c_C0_W?@0}vi?Y8+bvGb&+kK`-A+1V*@mB(UYl!Wla=M=PR`Cf zmpGLgD_-3#-|fg|!kvO!PEM{PhC_umVklQ@XLB?0A@ZuSB0MFLXAq?(O3a2L=u~W$ z-UUF-)T+<&F*#j6<8Qqc{y=7$V)OK92dY^l`2hHW2!%*YLIMi|BZ|}3@a%YRd~D44 zvVenQAMz3My6nQ-QHUjMr=kBSV<# zPFXlPzaG$E4#luyvXM8HbS#i2FQ85XIwePucBwW11}n?+;ykZ<8#9vR@<<{@n=~)w ztP()o5D|IpmvM*T0r=dxSXp9%{iT+kd~aBTzfQskDs4kM@Q$FksPu=7A9siuPb{F^0>DwSrmV~0|EjF zbljLJDGh*?fxO15#TZ1wTj{d5427Z_RPD*sy?I*eJBGvpf)h-t{?@Fb=KnNV&$ek_ustdgb7z{ZAroi~Jj?b^@g z=E?Fm4b9C|Po8W7JLI@NmZ4cun3rc|iGYErtgO_o^B6ZoEG`<0iZ;VL^E6Ip$M!lp zlW@*)olU3$p&WzCsX#4Xy~Gsw23XzBm}qEd6BV`#FsTOw+3F>kWo3?bc6RYzFgcjM zf8eGteUsq?&X~xvH#CrwkxiX@spM$~`uk@A*%9vr>*?uN$^Sa<$B!R5EXT_0bQ__R zR>{5p;6YrP?(^qw!@~OZR)(Y=E5L|CAh}pb@Pz8L@Un2FUitRNs6f@t-919w0G1PS zf32VJg0-`}5SzJemFN2`*%y14kvepwM2K0?cn$qx25i;G!d zD#wfhfzTQn8X6dYUGcHa`RzO8XB?eWAR_WYpt}T*- z@J0n{TO^a`>ThNNoU!q7vEffXetym4RgN8oPjjAMU!1Jtmx2xT{PrD6v1F|0*M9*Q zCoaxH99aBMqg39|sKsWP-BK^}>!$LGipIu9W_gsip*{Jp8t!peN`7TA*j?;F26MN2 zq_Tpn#8MSDbBnN)o?pMmX``>G*l*j#D@ym4>MtV=JS~tFQYi7UUdUtyyBM9E@A3tT zFWLWq7qZcf&CL)Oj0_EXF{i|ENRjtO-2vGQxig{8|Duc{BPe_ssKWJtb2Zb{9D}WZ zWKPPD|2_z=*Wv%f7tc)w%iqjE{20j7N%+sFfEh`={v&K=`7!{Y$bOKw-$TrI#Gv0G z{2URHI4zW?C`=iNSukf9X%7e{OE>1@4WTH*aENV_(1CqF@chGrSi@ zCDW;34JhcTVf*hY$2^EskYG2E`x-c$7lMM@xT}LXF$1P?tS0jDUJzYutgYcdt8*`4 zY!4yno}Qj=<3f(NR#p9-DB!(~t65|yrLR8=JfS&$JHsAi=LwyBAf_PbdZXQJRj}^; zCI)de(Tl@sB3q-((%gLY47H)Y{=4MYUVwjNUVlrO7!E53J3IPD{~U|aQV5z00_crW zp%el*o$;AWFRey)1n6(P@8ejO`Qp#5CxpiQ1yt@PiqiIQWh+x6? z_BJt#{!74B;(c+IjvLx9U;Y9_phU~KE3zd|8v%I?)Ck6c7Uj%&J9Be$Wo0PGAY)vd z#)OCKv&Z!H_S$#?i}jR+<(dGJWdHRGGMg8fzP|pq@81o9PBSvP7uYmAtAEM3w;S5Z z%ZCn_*3{{)TkQ}?N=PVB;{u6pWCRg7renUpzn=#c3Nsj>_V!}6C-5#%UWt&+**p>9 z;okrmCaVSEe@IkGib%-c0>8f>sm^N!4($- z!y_&uGg)G$LgVUHY}6IMGL$C~s$ZZ=sE2!yqz@nj1_Hu2Wsz`!9lc7{z%gJq!axxw zCMHi$Px$^gO!E|QAh}4u=E1?mRx_!v9DU;fE61aU0?*&9bSE`TH~7V{neCq)OpZ>k zGk~De9>r{FX$f5U{_u}6^yCE3^RE>?dTgK+jh0!}?eycuUBBQRsB|BI^1|Q_I<6YM|#X{i$=^z=iXwZWQK(ASDJ(#UF zkg3G&vP<3fk`Z(OZbwT8hkd}94<0;_aC87l+lJI10D&-_Y&M|bRd%7f*AOi&G}P3K zS$Va3-(<6)BGI7Th?LK;v$vm<^|}*fLg^MFL36bD^L29&=m^_$ZBPC5^`Yno23fN} z&sRB%VLZX*G9KAbon&Ft<4d@?xj_n6FSG2Rbl494{5i3233lk*?Cf7&{YQKYA72#Q znvjrC+ZP7F7ai8Ez7%30qh-jYG}XGFh_BlI4b{O?`&-CJF*7rRhl%={hCIQ2e>i~X zDQrU677~{*`Nw(7Gd_?QlBxL)#%w{kI)up~k|1i4x+%VTRq&GVm3i5;h1gx{1L2L^ zX>;l}xyX~xHm?d)Ehnmn0SN#;sfEX5y@q@YeSzGqcRj|Mz(7K(6c@)#p(cl#RHINI zHnkMH<=D%AsROgbq#u$A2??pidVhtG6A2Ry7rYjQeISyOgoiv48F^s6rj4zkB@h?O)7-~Yuj-#&7Gg#dtj-XltCF2kt(;X#D>K$(?J;Z>re#gt%V%vrD6 zfY=&+DPH+>z#9-%k;NZr92(Dc&PH?-6B9s3Xx>Tksp9`q3t)+ss?uLYzx54yAJoof zL%B8fE6RY(KVZM5dKhy!1wg%6l^z|N#LmHC-t0nOD3k&Mbf8FIsf7lTn|~V`2|+9@ zEG#5M0CM`n;6vSu^D`(DZEb7-b7%VdV>LV`@F!rZ1%eyMcYqxmQ&Z0`LI3mbAT7l5 zduoSL5D*aLa(@oFOC>EC`%ErFv39$aP9I8R7#lN|57?HIwP&kET|h-wYuC8M`nJA= z00^LcWlt$fIrZ-tn(dR2x?P+dz|+v{)IvqHK*T^a3{gW_d9Wu%6gCtHe>X2zmzu)w zqjQUiYEE+U7r2d~W9c+5a#^P1brOstnQAJf*}T!ZG(B1o^1;&BS#lYseb<}Cx4rc| zpyrI!@i^+>nB3jpXXMrilY@!?ii*|YqGr>Q)&uP)NB(J7^T}b9A@@AD_ZjB)IRSo;U;u$4x@61Z7WNLE&qQ z%p78JzLdnKiEk{lVC-xda{Gc8>HX+XGlve&O5Ok84UDLfs9Cp@tbtp32f2- zvo*W*_`-XEGk6q8off?UpZD);_eac-zg^{yv!9DWr30PoM4x_W=BDX~|g4PK}C+O7J+&fSHG{SFc{#blr|Rr7r2x zlKc)-jgOBH5L4n2w8O81WEVqe;@Onw=|XsmB_P!k^0}2Gbm8s>L8kMk6V-jppUPYC z)16~$+%|3@*kV<^yUnV}KVfhE*>w7aS=KF`BVP97_Af1gdh-q&EOW9p>&Db}4~DdA z%q_u|EimfKGHkNNVkVEaQVM~ybs#$>BEEaueQ$GMW!|63aA1&-?Hg+YKaD^sejbX+olX^w-wsk_U)xwWR_yp zZ4F%&ng6)8w-WF>;nDD6+hiRvm#%R8T$f8RN$pJVq4y4Y$&FmCgRd?(xdOCpnYHd* z6L_Mf)BD{pSlGX*`cyCGy?yizRTrm=`XLtwQ>8kG#Vj4IE}BK>&A^CpLBDmWmKx`- zxrE@23&9ioy%nEZA3ul(s_{DgSSa}F*UUF*+51rvVYlFieZqS4R<2In#8U=zH@C#7 zJAWX%p`)XF!eGE;(JLe2DG3y7~I@BX`%i)Uez^Eu|H-FE-IYGWM__~ z4!89Y{L-E?=~y#a^QMEC&FtEs2`|s7TQmg*cER^^&pZ76e^|!b>+lfw%RD>VI!w`( zbL5MTexQopxzJ|)GRpnf&Jq`QiU5bpTq%6(9bFGKhS%K0)q`%s4zK;z{m1{8awS@L zq*`#2-7(%)bCktkI+#A1?;L!f;y%WnzcT15Km1Hrjs8n|dO9#6_yR$)^F}rT=w71F z`scYThj|uVG zKq@cW`uM57JyK4fF+AE)8qGaC%X9cfN}|Pa7VIwtt>8L^!|7cOXwmGrxj}L+i@4)m45$CAakdDWolP^KE9l{cq$l zqhlert+^a!-n@=;gAQB9c@3Q!PE*mTg_EJuthiWT_>wr?kL|#mvud4s3O)_+hB$6a>}_ool-(D= zZN$W*<=HDa>I!upCAZOCblC8%Ghbf(`exRf{j4d^s?N2%&NInuc`_^IbEAROhgeqj z4dwUg?13(?T|4mnYRz-2N<3bk41H&PR-K+fhS4-x8yHi4zDTuxo!hT8db4FqyNwpF z`cCk{QFYUSRqb&iFRuAOfbp81Yo57P|4Se`-1i%UvWgw}Ci;S8Bh!iLWmise+kB{*?Y6}SPtjSnOxc>@jDe#)Scz=UA zrlWmUG^Ry-6#bv+BeV!xxwQB!+%RUfW#D(&EPtn=Uc zR5_)sRb6*{u3sO+G~03@pSP}7u%&#I+vPIHn=3Z#Nivzwmg{gZI5*%`-@O{q)Usg_ zM0`(iBZPmK_VMHI*SWqye|EQLDm3h01I$HO!dL0Y$SPxUy8C~Ft6iY z#Z{wu7G@vfh=zTjf@NYf#vmo39Kc(-pYD{Hm_W% ze`nH^|E}H8KH>-oabjZmeu~93(DTu2YTQPbDj|n}Wcpn_=hj&5Bwh7yhL=>I1oz^t zO3w}>qe8WA_4M>WwRIF0S*S`68&l?)tF5gMP``!-1~j;shTAC}`Woo}`1$em6W`-g zROvuv`09zqJYE0sr}&u}&lC=o0VU=9;_}LXvxArpLh83C$M_=*FE)3XI^v7iE8N$L z9~9V~MNQS!@t*0_*}Ki}bycZ2;9L{vA23(jnrNB~rQd7iKdn$(FG_j)_HC&1*M%vB zH#qj(wgb+u)Sb-)^9Mon&Wvw^C2NtxXXd+~*MGVZ{fpb%@8n*Wo2_i0vlQ=wpNDlW zh-PeCzuHy4Q`VNQ`;$a$OAh`+qO@E3<<-Ad>n=dYVsO)eMhCzG|CQR>Q&Mxa+XcpZ z?R*O7kqS9|zle%N*bZpRnU6mmkIhrZ@!l_DGEBD^*IXJmRPDq5Zh1I4dN)VI!@=p5 z@aHfx4EBrd4bi=T!*AK6bglzB2`A63Iy$YL_y%IR?<9Lmr@(W{QsZHw$BE!x6Huha z_1a778RajIsT4Dx_ZCYBI zw935lTs*JqIoo9MNO!kvjkYIL^M{9rKnJ=3M8(HR29Hun@$g=e3 zY)B>|XnkarpCw^EhF^&`!rxy4I3kF_KY#ud5*Ch_rK#*N`h4NB{K%A*xCrUV0!z|5 z=Whkgn2U?zQMZjlf~WZFhYW~hS#gu0zHfXNd_#1`QfDXYc%|j$=8dr=3Fh|ucC9&C zAg`agPbAy*bD!4?;wF>vI#EWGnqpfF(l6F7O#ZC7ff%0I&>C>ApeCJrSFb18eyL{1 za3j@haTY#VYFzLa3U3P6^#=t?$StlLk*Wo7d6Tt2vJhKec8huUze%6c&|Xk}@^d3nCj!@Qezxr1U@DW)z>6 z5lC7oU$+yIh|{epTi6?XZCi=GHkEgDaejKHfr!R)bQu4Z^k6c!#L?NvD%FgV$)Gn! z-(U7zPG`g(D5v!~Lsnu+v0l@X^Ye2V)n(ARpiVwf!Cao|E;do{Mpz$hL-9WQSSmV} z+cDRU5(8WFZRucnq2}m20n(fg)lbX2_DcNhnR2q$s4>3#dEy)KaIOU^s2xYrIzRjE zR4Ln?B3^4?Tv|tE0=|%TeU_T7rh8z+1b-?0vUA>+>v>0Tg6GcbzVW`SNtdG%nwvpP zX7toT0xTLAT*TiDF3zG;DH-@W9ub0+-%@VWPpBDQYB`~~FkxpLv-(D(^Su~9x4n+m z3x)3Y(HHLKJx7GGnGVARo|1u{q>~+uJl$NRHBtLUnUs$09VVWJTu0@2)0?0pxkDlY zzOVw!wZobcn7)q=@^@uStwEK51t}f-tl-T|Q!+Ip*f5uP7oQ%H+Ha3mMsTL5W!pOEnI zB~vAS^T?@d%gc`;Ga_!eUrV?PtLj7~&)(>!ym6LR##C1b#!dS@@=1Ilg+O8Blx=_^ zqoC({X9OMpv8X2RJ_)|d)00XN)0>r7iU!vhV5HdU8 z(18D0>q%+m-l*;?Ht8dJYIq8EJcD@}>nmoOOJ`$0T>2t~&$~8$GQa357+?!N+|6k< z)2Pd?Ngj=2*6>m}$W3%9e=SsNkX{JutB`-LpvqhVch99JEo}k#*-z||AA+1J`nans zW3CCT-Ii_Bp;D(5kX@!D{>EK5-hzM4Y`G%G_2Q5l_o=YO?^BIR3f1)o+K#^z%iJUQ z&Bryts)Odu{gT_LV{C0COGC-;9}bESn7#v1QLlP9*3VYQZ)V+^V8ilaTdQC0A?N3g zlshFT@jn*fU7@njuziMjguz+hs(fFuWL2&TqmJMe_@O{EqdvEKS2)uwEoM4dTLXqy zP@zC>tpwQ`id-4Kqi?`9$(+0SvfhXdx0*4GGnFN3(vyBZEc&QI>#4cIrs*bUE6t!@tr1jcmsQeEVQ=vJ1q!$ zDG+wtHU_gbqFfg$<>-FLKi9`>2dKrGvNXP&N2w}nhuhfLECX>5*3+WGLJ*dadLA%e zz;MjvludvD2P>>ovecf;Y4L@HeVX5@Y0`q`vAE@YRhc}4AVNdM$uWxSd($)kvizl0 z(y#bt4ubvIJAT+lBL;`*B zs5a|S>5e?MeF}cs)zvW&lR;ny!CN_7^$mouf`S6DvzSj*JAX9nc1TJTHTO00f7jKN zqf@#nR8c#g$!Gd3eLwfEY)Rj0SEc6pRN%mn4aqj)tDPf4nchzh=c5A?=A)%+Kp_CJ zm7|guFOovjJF?t5K56c0Eblk9Whke(?Cs)S{X~e0I*v<{q}If)ZqSwPI6QB%K;mX| zAHGG1u7%DG^_sk+5CHV&totc`q^yX~b3SejkRtsERQet6lA-; zd@s<7=j47fx^2MwSjxS2VpO?hS#u{<49k==@<&VRr3J<^;0P=*j<}e-9E&=WLlXT}i!i2BAPVS{XsZNipAD zSE_-m20yyWFXX>VH7eS663lL{T3ejg=o811@L9ecN?yNN>JqtQwRK$8S6O?W0B#zq z(I>Qt7(?Ngb{qEE2qU_ZGWQxMvE4;%^+6|Ijio-jpM_oO6(8kW$tPbJ9Ig9*87DmX zt7+o(7tzDQds1s0^MO1E%0ouVE{Yf~ zuXM}azA$S2K?^GD3MkbV6@ybfJO3CK=I|CflWltZdXW?SXRyJZtsq}(55v;D{HSd% z;2oZ31bZ1HhF4+^r_I^H+(MTo&$C_r14%D=ot$Bbuu`TCm99Y*UQ^S+sBuS&x~;Yo z5B}Uz<--Fb()95xwv8&gx%^C1ftMAhZ46zH5$mbv7{Bv$>ah6^6ZINDRSXe_*Hlj> zDNp{fxF<4T%$|?%MDrwlW+s=~TvhyXdcvl)@JifqZE5~i?wh^XpXip%n_=_pU#1!2 zzu~d9Sc1x5RbFn)8V!EVmo|EpM+T9J@iFJD5(a(X;;nR8tAs9%>)7AqGgeI-nUDO% zJ4?FM(dqbEoL&Zgi`y1t# zx^=(8Lx;^@zWgAawgQxtLPZ}94R&P={O!P!9Y{g#w}?nE0v3#XuH8I&*rQ%QTJm_6 zNSeTtlColHVK28 zH!M&Uk^@tL`B-^Dz&1f&&Ug|3S<#tieRZ4uXV7FOJWkd~Jr1XV)c1K~AVrjLiXwhx z<-c_!Mfh^BgY#xFQhtPs{4x78UPpVy7LO|T!Bi#NE_RQD0d?Z{Af2wxbzq_2y8lv4 zj1#O-VPOhjMlk5*of$TH;F>FKc_{7Vlx|j_?HzZw#A(XR%(Lr6$+a_(Z>%^!=R~1e zRvT9s80Z}3lcsxC`LV5coMk+!v}94lqw0&s1BmLXnG4i9WQ@W5<`26k#(_gO9C|k)6F1&7bHr3P$v%E+CrQf-xa;^?d=t-k& z&rVIg?sVjx@5TsEzWT1WYNp=%frPbpvRTT(BkbV=!lRRu7|F*+)h|CLt05_!xGe-o zebA-?u7~}7!$mRFEC#KC_c%sMEhK)YsR8W(@rx zRG-}BqRllc?Zi^$K|0aO8#*~W{41;cHAU&SgdQF`iG>ngC8}`QGlhL1nDikiX#YQr zQP>aCK^6lG2+Tyq?sJhKQhsok3CY3J|CLHwgVL<`5WZLhO~Ir(AZWmreS*Rg`t>Uj z4$c!8RHFoU<-DQ3zfK_TctN+#`53Es9_LKBk-n)+j{~*8ntu zFfrSEc_M0W@pZ*+(~^Ba?L}RD-2bvh0agcF3pAP?1E2!I`CqOr0ZNy>cNAjkIi--r zcC|#Bf*!ao_tVts-9=usweZd-Y>Pz=274&ErY*-L>W+<@{nDQL&=rJAD*Dr(jM z66bvVx&)4%#l@)4pLN+|#>dA&`2_upLJZywrJ$swgc2PaI~Xi2(9i|#Sx*R|R|k-V z9ao&6pD3&$Q`1c7l7Y(45}YZCJ;rzL-nGD&l$2D=P(<^7D1(4X5S%Jdz<44+9RQay zsAw^$H_^Ns^~A)*TNS#&R>Q!+Ktr>1?gg%z;bEjrN(RnF_DK(Jg!&WQh%@Hn$B&_# zj_Ahw6RgJ+6yMU);F=3G$eS)vhnu#*2Rk&VTyv~ z#wF@|F79<6XV9SqSiI%dC!zIw&*AQkQ9miEs}paqBbyQEXS~OrYNYf$gLXjZskw%Z z4*EK{r={Y!N`STj)$VX}8YYB^gnPjUZm+pGHO9y8BCKQjX_=Lh)Gk<8Um+A+SF2C8km}3K+aI1 zWd@3KAn47DrmCHH!0cNLiH--=^JJ|ImF%SCF<-C=7#IQd~$+1Y3fb!^2 zZpFyR2#*N36ReK9-(>&6N(!d|Wv|D$`ppcQ-<|MwOz?0}D{Z}#&&ZZd5_EB?1lj@c z5lkb*uH9WbK(4m7Pl*G;{^?Sqoz^#3`zcpGBQ`E>z_dg5nE8L36Jk&*ap(n4cHxP6X_a#|T=ki!kW&)Ey^*!Rke%6Zyn%UOBgfBEs_`QKKy{fu3=oqBMMpb9_+ zfSswUX@GQRKwSs{854E#>favD%w0|Qe8Uc62wBz6wsN>cD#*4>Fy2CIA;g!zqPK3D zxR{%6fof+g=WF&D(Evh3V(TwhGg6Pk1d{-G)BSDotWpyHgSkkE5Vb1Wemt!l^Bk(}vb*27C#K04Au&f&N`2e+StLIHXqqmhG6^ z5h1^S|At5}779(1$OH0iQy=m{riQ*p+-t93odu)^xNS8OBvXSg6z$rzZe-IiO1=>s zrCMSdA(+&?vWIM4Ob-C`397%tV)r}b9HG38qq}+OBY^}1YAc~M5i@Zhv>rlKa#Q

LKJ~T8%ps8pOy*9g%E^W7Wq{NI+BlVxu_I%Noy zkWD#c2?>n4-9!4g&4VL5WRw<8`Q_(rGll~eg!uR`jWtIYc*V$3giNE90YIxW!xhmaD<4H zpZ}!tN_gYpRA(GFoW+Z*`gl3(#P z58s2g=dV44z$Oserb`g=B|uYf2=QN>7PaUvgVPmxe<&zKa=(u0cOz7^Utt(f(9+U^ zH3a7x+AZX-W`)0~ke=G&kL2m_zn4WeT|?y_85s#(7JqjRQHa5%mETtooYC;rfz$d6 zeDy+dtG%gMe^2j>JjDIPK@Jykb^Bq z$Gax*aRqjZvVRXKBriJrp;r(KP{W)ZVpJ$1Eabm}0<66M=P2Y-hR;7>c4E0hLIN1} zKcmEOh??7HSA2B{5#WkNlM#XCWmcdH`AhU~19Ol*KIv?{FT5QS683*ah|e@&L;}oK zVUz@yHk{R;^=GPu_6~q$fLi}rmj=MmmMTAh1P)9cHH1)nz@mKd1j*C*srzTHw(Ci)hS;W-sG-&xF zS0N5*_^z6NW3kuNo!Njtwt7&~1$iE?R^c@TdunW=@> z*%&Gku;1Vd7sw>=rFt+hsOIYe=mahTlniJBpm*o2zv$Y}rkkW!b*4ugKWP(MvI>5x zfOAb^%<=9d?~wEP@21>8VeAzAJtZyww#zvEgY@3vkn;FmMm+*|dxiGxg{)GotrMNR z<+Oi08N75WD^||d1I-50)yVUuSEi>I`X~^%HH#JMyabXP%4PfhS+AwO-=nMYy)_=A zH^YSbFL%rTVOe3p^wJF)z3^PS{0Nnci>;ORufB*^N{M6TTCyxSH>GZ}u{z!m(zLuO zhD%*^IDMOMUnY;Ts;O@zY(aRi||!r;chrExfgPH6QytiPK`Q@=LMg64lziL=diZNSy=cK8U7ix%bgQ3!qQ}1V@l?r`FA2TkHJ1#ua^+m}jjcj-bOnuIx|iu(tJl zA5q^O>4ZbFN6#D@D#j*jv_9xag&k`7H=wuwwy6jjpiLE>d5w1DurX|;`*TNP^8WnY z%G|`Doq<-_6?IFVqxGrvnF;5ecbm)&=zHsIyVDW;%IAg_5&S>9CLNpm3OtVQ(T7LK zc+-XD25I%3H1ZH_u2uWYC?S!HG1}_PFglx-F+^f5P2wpDNhv?(1AA99C6|d^RjWX1 z&e-Y~B)2DS9reCKG8}0svTbt zqb+rJvW{g?gP}!Tsiih>US;sx#Jp_v*>s|s)mmKjuLXZU(&I6X>6N*wH!Em*$Vr`; ztq=SJ3|0)ADJtsX_s7d`wJzcHHA^Nqo^(39-!}{Fbvs`vmZ*u}uBnvlqj4GD9;>1{ zW%X3)#i4q=KM|ekS+y~4)YrsU;dHv7P#Ev|^kPGTZ|UH20)e^zMlJ5-bSR~{00tuH zE*jab8?B2b=Q*76hSnUYvrK)2UJPc6-&(VCHyU^!G&gFr7aV}MVId}FrcvnJq}4@f zC>^!nNn^0zaL*0jN`tfiMa#)4Vj7!o?!ev+n{L5EFTd|XnrFj=v`d5ZnP>ONTJW>) zlJ~bq%b1A9)ic?ocGLJZ?Jb_vX|2_lO3b(O6BVvc_0`OhMm7t($@d7C#+yXj;DD*(pLg%-rygNVkJ$>nX9!tKPdm~^gJjQ{2=}6jlfR)i1nXFzM8zf`(Gqn6}tAKmaNkGZ!SHXi!)-M zJn7C}i|mrpK7Ny!R8a2?s>1BT0^KK|A8d;TD*&g!=bT_YgjN*=ZV5c$3_4LTZ#sd^ zUW>{2*Xi>+w`yM<6c1sv6x3MV)0!xsDm8t`>99Jl{$(6e4QdCMs@ve4g zrLCk}J{Yacs$brw^65U5zP0k5K=9eY{ZXB={j4xNg;DJ|zIln}eLRP#k(z-(yv!iZ zb(c6Tx-tx^2!x~ciC0%G6ASv7>5OQpqOvl49!B={@iis?VRL2N#_{nuogbGo#GwYQ zNFE-wIDZ~HB-K5fWT9`}81UJxUJ8@R8M7cP%k;uoBpXv_nM=31sv>b2?V2B8F7{3 zHCPH9#XIyQl)moA>nW_wFKr{bin#s8r)|j9-d3Ld9`?RqdlPtY>U*9;yw-ZP0JSp{q%4WelK52R5*ZQfopC^z^44ci@viV1B>@2K}&(D}!sm&*J+x4mN}qqs571 zJX9@LP*W;JgibnFW11A?M_dp9z%Q2I70>*)TU=s-JJRd1oyy#*)-ZskHi`Y%I~9g#7= zea{*BH}BuU+w861oq2HJzQQ-XWy$q0yndJJ5B|!0YHIMopje|u$}!)YHU9a!<(3He z4N1|lxEU&kQ-ye=bEDzIe!(bz+d`(28 z1#jpofEZT0H>d&4X2gNtZ~yULk@obC%u)>XoHNJ$9(rmc%0v+O>_BBAx0FvRTZRXn zphjL>(ekz+e!Xgxg8s4hXr>u~&l9`^CT1+h5}f&MFHCgD2AwE$drx9kCHOciYHDNf zlq~RfgX(LMTjte1}?`D~^$g3B)50K4?S8hQkU@{=MRd?m@Q1)$Kx7$(*Z4`z? zwq)Oz5rxJY;f}IXGM2JuiDFWOvM*VNgc3qDmKH@qjC~zs%hHgYu|4Mu@AEvz@xK4S z``aAmn(O-R*Lj|w#dP4k{L8UnT;2Do-r+YxA5LHW<;JbUkG$rdZ*(|bdnkXh_!^G7U0fDEgQbLJU8gL6~|?7e2wsQz-2^}p~l^k zW1!l-9P1jZdCq^?g%$O|b2F5IXJKOS=$ZKe72FpTI|3^| z8v0HW<xjhz& z^h`;9d~#LcU$_vCsg=XSDu!X{90Q^mJ3K>7_r{m;*Bn>>xS@9x2`#e<241#bHf`NE zliQ9~y7ezDdQ((`=iMFdvi-c{68IG=EaW`4(G7)qtd}zy)Ef>wtEHtSPGw&ZgZ<$v z@PhI#Y+8->s=HV|5nM9^ST%jOa~zQ@5I=CUEY~iMIg=E+?j5DLvT%RwXLI14xVqm= zp%DYy9rr!C3p}e|EKHugFsr!ORuFR7<CP$@8WC*o{8n9D zEa3G0^rN$*5P3;Q2Le9`5bWqy?4kS#3QZxQS2RD)#D$G+hh_yo&|TeF-TIdBOSk5F zspy$ywQg$yhjX!gX#Z#$qtaR(ziHf|cbEpQ_z!p1ngiNHv5-jA4^x-c3V8g9A2 zK^0*F`<&SZ4Bd>VyEmvDB{#|iHRULSAw)jSvilkKzjx;PkQ;N z+jUk;+MKg@y`5*7mOd?OsO1Dftn!TfYJkWVno*R}ut~K$2*51jcm;WRLnz(~=NIuW zMuUMzgva!y0wM%fPuv%soP;~!`tw=Z011LE9&jl@ZJbB@Cr6ralj|4@3!ocab`pdo zk&eWzp9J%7uB35VON+a1#0FQ9B=nZmm3JEba@1>C$c^8UsA!NE|3yumWCgc$@R$RA z@BmCCgAlQ_b&tBzkam6~J#nC*agzM$5q%`#_TcFznv-(_Dm@=HTP*h7&zj)1j~A+e zK0WQ{tJ*O1Y2ma^w@Y91arpIfen+~?slb0IrrI^C-)mj#m6cNUWLoo=BhA;>yW0rv zz9f~>lB@K#g9(K?A3!zWJr`sVoKuZk9O=|PR1i7VK$Rb1BB;#9C0SqY*Mg+xNwXwP zh^6B_X~LLm`W)CF^*SM;GT`aysiSkSgrZ)3#KhLsDdGWUaEFTTH}K3bs<3zbkkcSHTu#wT;X@VA=# z5c{ny8d}Klw>&a_h0r>;^5${XTHn%Ly2dl_g0K4zpG{!>*gPOtf=<9s_UrNIbdAxC zC!xz9Ter`7;EseiC_KRx_6MqHw@4n~zWDv;7-Hd3F0%RMKx{9Q>z{j`{XfCh;f3-` z^OfN%Q#+MC!_$|#W-rk%9_i9RZ;Ib(-i+aX&B)pN(f&ir%J{dl5F^lAm&x?eD%=LS zKVJ+$j~EO_yb@-bDhTG*oTvt;MfWN8%Nsh8)7@q)j)lV;v@`d5+=^c<=YFNG9Acjm zWQcQbIlPY)-b+)bFqnUgs4G8wWF9}sXvXc4S~K#Xq0C9nKoF%isyuC>auY%%g4fq4 zgDN@s8+m4r!bZ{M-?K7(PZl_TAk<$Pl9XOooyU$HG{0nb{_J?d)=Xq6<42YH3+F;! z5{o8P+sgAykDD;1#I>3n2jD!(%lhX%T2z~NikM$wihp&hOw;`o1Aad(7yu1g=>&rSaeKn=Z*FPpEzHiW7@kJ*{Z4fA*JE4u!=6*6pF`(Vf*& zdm;0@=7|R-WE#xUijAi0jQh{XO!`r~L zPeyA1ra}NA;SKU(OeMvxJ3oN|tzTy5X)tjKAT2%Ydnk@xPM*^~ZY|PNJ&m?)d4_zY zO%tb=>aXM(y}p3eKN=Nl5^t11akaE`lXRu*rinADM4Kz!f#d})>a`n%zT5f93sv6vv&)euH zu(n|*EIWyOB3GI3%wmSq_U*fG9qv(*(8SP?C{N=8xcnvkL+%c~>5{Z;jI1DN)K#FM4J=*=MTu2aF9-C$ zXyy#=7&rVa+RMjYns`n+&;|S7@Bgyi&bBr~K&RCW;AO(b!O_$~QjXBDl}Jh+esV!l z5@2AsDIE%s_~vzW&5`<4>~%G)D5KAegHu-ajzp% zI8FX84=i9y&6W7DFYcQ9Yhww>sJd@Vx8t3PQN}4hML$-}U~_`~xmcpH8}GZ3$0>UJtFT^ix$;Rad9U4mzZhst|X2_gb}iRREMA%gq$< zB4F6`Klrs&D}Jl>v3F82{k(U0cQ@O*P(NGEO){~1bM%llo{ zJ9m*iA#l^)WF_!5b-L;Ld}*_pU(YzCbM)LmHyNLqX?#)GRE$;*Q?852SwcFH3_A$2zXnhTbU zN62&mH8?sN(qeC|eVfO1Cq+eh`T60TA0D=<6n$0a?RHhRnmO9NGf*{N>R5|VmboOKpw{S+4S42_|N6xrQs3AJ)PmBP2W%xO95QYj zSLnJh@4HHhP9}mL546_GN=iUW`1hk9zh;8^5(piDyik3U?wl@=Uzkt-ClKxeuOi@K zX-8jVb+kOdz~Jugeq8-=cz6~YrR`PH+dmi}Mgby$+9M!jtW33sUa%1b8Qc=^g=dyY zumbjW+qF^4fImPLLq)%6pMua=p3{q0P!N^XdXPiz>2BCv(!DmXs>`Zi^@$1|Vatw|nAi6kST&O~wBTngeU)QimtfK*V-Z2|S@12eu}tI1K%sRJPj+@TJR~ghYi+H;ZXdbX z&LIWPo!bJ_+DSE{9?VFl0Pw0H$2X!tiDvZ1qh4^N`rTpc8N`ktQB=D7jA zU|rJc5X*ZDJaG3O6l#6mO*S{;t9qegef>dFxLPC29(FW2E}Ulc#v6C%r#bGYb25z)$dDgZpCJAI2Aku zvUkV-<>3M(a7nW@vi37Fz9f0QfOAk%vfbwGe}?#$6N1ag*tpXJJAkvY1iNNomT=)l zz|FC{>$dNE|%c_ z8>RrIqZ4bt-gV6t7(_32+wxbh6gepe_8D+@Jg_Tgq@|7N53{jp?LNi6_?CYWIPRjN z!DTwP5+Nuo-1Osz@iC0bE@XQyo;VT=%tqM$0%1qk*|iD8dZ_t@FvFV?C}DdKk?5Um zeM}~`9|I#XZZWZ^75&d(4TGo;xRizmsP2B^Q>CK%%Ypnq0-$dWZ=JlCRbd)TUL(Y; zf_PCK1d9_9bpRqJ{%`)OZFyIn7x*6 zH`|HkO&fHzq^z!psHiB5!kpa!u;~>*=1!?WOkg8+LZAZCTjrbsca(8v+newvjVQf= zVtc4112t0OcsbAi>{{@dH{9J*-<|F(lS!Zk2G24DfGU!F@T7qiQ%h8b5>KlG(6?a2OKVaXop_r(=dx@dd^I#^3Au>s@Wn8X ze5T{#RV0rem6Q(@Z`;5@Jd#7+ZGFMM!PyeX+kFrdO;f&i_>)2j=79)1TH!(Y(`BX+ h$_YXB|NBGK4ime8OL#_Q&N{hUD0RJy1!`6g{sme06jlHL diff --git a/Documentation/position_control.odg b/Documentation/position_control.odg deleted file mode 100644 index 5fb002c5e77ce2edf979aaaf06d4df60a509b489..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12559 zcmeHubzGF&_WsZvA|(xiba#Vv2}*Yi0}L?(4Be$DEuE6mT@upL-6f!cfTRM_;BV05 z)qBr5_j~UDzs={Jx7PFQwb#4f{jRn5LPG@!nGgU#2LR5U@T4=5INq=V0DzkfehJ_J zb^y6}I)cm{9qqwDa~Cia!s!OFTBxjI8czUw0bF?RsLL|lL(zbhv4yR^vnihf-2 zum?lz#OZ8YTpUF>Io;jeIox?Upw8Bu+`_`boZs)#{ZW-A@LzI{uFm$~r7VG*AbZeF z(_x(49Ne5gWp6b6r%K(({;ravGYAGJ{BGxe%JDnqcP=Ot`Y)w#?D4}~-&N<~;^O1{ zasE?lm;>1UpVoLI%MOG(IKuU`um}BKsW}Af@K0%OWWTrccLHl?OG~&Se|{)%oq0K} zIW5gy%-P+*AosgJHUH6$|K3{R|7fkHv$^|!MR0R*-pJ6={9qUPt)ueLN&M`UH;+$3 z?E6CmL%=RzbGTWYLFO({X9+DEsDn9-M!^+sAZIbozm)lb{EmRX1nlspfh2gixOv#Q z_}ICHw7B_1c=$#5g#SSQyPTLMP~SK_qtS17e&_+Rgtq`< z&2H)H{Qap&XlQXO@^P#2a%ujd!Jj1l9SHOU+Jj&cJU z!WpFg{q^SL<>04R1w&jtO!b5WOa=I8e!FSv=nS<50bMwG`MDgp>F>LO?Je1P{!r-` z-4FVIjT5k&mk8zp2GV>tJ=Efc0^Vs|Aui%{Jp6Q=5@LV!36UR9@#opU7`|WrF_@vF zqkkVA;RE8o3O4)*26DME8SG|2TQXR5{vd?!yHcU}@S@Vt5IHRdxiEwohNT)1(1`4D zyB?9uvY(-!duX=8lBUZM3%FXgG~7iGRN1ICDBH_@63U5%X4)dtbBiGwUWE4NWxqB8rftNcSGTn*THJO^IRCe8VXP7c%^y4F79I>kr_z?Nq8mm+c zj3a`q`PEi}c7em_?i_^oU1oZ=9W(zur@H00WiiT(m}#f;A!_f41Tb?%^2pD0E6t>OrQPsomSLw7q>C5D~_bek#2R7b~QSSE|gmL#w>r2k|1Fok@*9P z@NCmp?n7%q{X&X_T3R74N4I6%GAgdBkR-DSWuypDI>bm(S_hcsUB956lDCV|du6y| zIC^VU87&{zh)6O$nL3Prl*5&r=Z;+5hPoLI`ebio(}7^ww2jJ0wYduwK!1(g=|28Ls(Ma3fVy*7vW0BYnPIYj6}Djno*+O zuo?0RfQtUH+ZTjT_mmvIAokmjr{*Q+dmZa*L1BdNRxH$l4PZ9@5algcAu)f*(6=}t zfl4_Q!b#uTxf{*VVvM8l6=AdQ!vw}^=8e?03Y!h?mDtr?3|;xE%}$)0)3AOk|0KAu zv@125S7$FIs){E=41BLCx2nGtxb$_HDNaFX?QHixnd8f<_wX9q$Tx|Jycu=~8j2}2_bbDqO2@t>kt8i9b8_4&M`FMv4OJ+cojjq<{fKso zv3NII7X%UpdGM{p>4b*rFmQ8u%^gtm1!S?wNAb|}#RMqmakO)vqs?%KSyQ@F^+Dt` zX_fh@T6E=$Xb8knT_y9UJZaHtJA?(OJsOr?2pxMZeGw81ka6;}w)@%+l%Bs%AWnMU zZFp8PLTy^%%kXp!rXjz#hC79##tQozMC<4@Bu1eUPY#W9wO?o<1{W674ng)gHLlS5JF3*SZkTAiHju^h z{K*4Gb1-wI8oIsmXNY;zo8nY_$LJ1;`E7|ZkXE0!629UK-ayqEe>95MG*9d?>Rv`9 z^Sm2rda?Q@!6;a9%L8z?YWtX}B^y9o-Bg;s73ZOUo7}8%g?>TycD~;uOye-|x*^4Q zvR-ev6xLh7|c_xEAS9Fyyk?K`qf63@4a-KE$Z7ZpCJn-lg-o41OeKVqO(Zx8HMz{|BVw3Rhkf-Ntj22D%2u6f9fb~TW5ZZKRo ze8#kfcHj6jE?Nm^=<67Qe6c8>IZgYX#rP6H4vH8hyEvqrBQ<`kYC@Of+a{reS46E+53-v% z*m2=$Ouq9x^uu^>^onrk#QN~biGHyIIw$iW)T*!2imV@)IOgNYdvSIc?Im<^eXI_h zvycYzsO!BRQRFyE{)p&j$0fqKp}jwBKYS?M#lXHHJfbK}@+F;!9x6ZFJOks`oqiM+ z>T=`=dP~XP*Fq|)w{YC^q4^6h>+0TS$m;G~#{{v|F0N^1Rq+0xmMNE%IBR8=x5?WA zzHiRFh8Pcr)L_j^WQM(FKHwatFxBZr5sFuC-KhlwEYH+p354~*bVw$Q61-T7ZqA^WR3W}_e|tNqfsN7$dt>w) zA1ISUh8a2BEB^te`6wjKCwn4v!k+xI0hdy>o^Fuoa%)kD>D5$m+sjG8nmnnRCiB3+ zcX(r3k2PA_Rd{$qLpjbm#u$3L!+O+UfsI2JQ;$t>Vi!3(#8UWA%0f3$%w!v~@}}~T zxTvj7*8qtVmNO2Mw~c}{zNKSEk?=9L&CPH^v!4ard6Up%t8%+&BhlQGX~fHzTjfs3 z@IKpDQ{O}EL(Y)k8vI8h!APdKdj{?IM3>vLnC(;2KjuMV?9lMde7l9NB9$yQgnE28eqzVC4`U*8#VNZ>3G8 zO)mP@D?`^8nJbG5+i&v@18i00VdCBHW0Mf&Ho9%F78$x^$H>J|%u-b?f|;@M*MJ49 z64pTj4rEhZ?=qy~?JNEF&Ra^ZOKh(wn5(;Qs4g)~hXZ!E08 zduX@h)EgUmoFk#x;+wlA?^$i29it85sCa0owqNY*DrBhJ#6T#urC7h`twQXPF<>Bb z=Z!{dwJN7>15K#lBZWE#^Tm=&NgXKKI$vYTI5L0t$ucO6dM#Z3w0kCpWof$(v3$`_ zb3_ot#gootLzZoXfn87+h!P&5@nULfh}G85CBrtH$V|;|4$pOVcV*Uy3TUH;&N72h zG^>bfGgDI7L3^g$dZcv3V1DP;rL-{JipgbUpnIYfSm2=S-1@3-&_(SiXxu3Nvy|JK z3a{m39iWM6$ZmU6_O+;US|Z2Mfd<0f#zIt+@jK)z{cahA(N~J|IxUM+AH5TsN_@la zw-owRObdGIj?Oh3Untg%x7Fc=t)p3{Buo09t9DT>RtDpGZw-RyG%I5VlAJ1b8t-}U zIPFw~TO^D@TWYF?x26?jnRJ!bJ%6@=pBf|Xw`(j)V z#2uzHzrVvKU%1vZ z`^lM1{~TX`{OoF+d!o8&oT^%9e*U$#y_Z@(hjRW4`5Kun=TRFsJ7?9JmR@kZoijO_P{jE$ z?}b4EZ#@~AIy>vlT(t#T`mtXT)uD0Sw)-KQj^rd z3w#Hp$7|f_52)_)xi%eZ>Qu(s|~StzkZRqD%0Nx_>dqo%AU6e_MawLxL^z- zzTa}HaeK|fhxB@3)kZ6UZ<+EsP>{^I9f?RX7fL32(SP8$Bby7f=0lGZBor~UF>=hu zeJ)Z>XJ;SblM}p#rCIe}CayxQyEu4FfCzTkCp?&6EbS-!`oczEplI~@@N)0Kdiyv3 ztz-Wi2TnWgbLdkH0H9s@rvvwMO0^ELibw$Nx!r7}a0gDy#?`?BVh*;4ak~6G)go3(?M&ytJ6cxO|#UCMVO zwF=^w=MIGfthJ|DXKLt(WRdB!vL6wyNg+DVBg+J!D+xra`K^rB&JW+4zlz>-KgrzL zZ}Y;&!#e~N9yq!n0VpsK02BBC8l3-o7pV<6^=Z{6Gk20Jt|Q}Om>Ozg8AQsOKbzYp z-qE!PHJ*fUBVE*R0Vw7#5cH}$+yl&ASF%F;;-HsBORDn`{p9O~R>8jd1OelBU!5;M z9-x-3`cPi1-n!X8OnqHpt7HGb%M!MvE{-$pp4reW`6Zod*T05YO2Vg6iBHg4KVMI% ziQq+@7fGsBdU0X7-N~RarQ1eoalx^X%;`wx==IUn`tHRfxr&Ox?b$XxL$A}~mF){> zEp6)rq~+J4muvUi{4eY3HfM|26&~QRd3|c!0=^Op4%r&HmacO&akJS*0lh1xYm82l zw!?Y<_9NL4ZhNv{xOJ9=J`HcpUWTewY>pvYV(8%-mb~QM*~_-g6jp9uSdR%MSl;}3 zjz%-ngU;15qmm5Y{ZVjgZ=u6QGUMTKzJq0cb*I{S^tZiNL%^y0;UU>``KI^98!9-N zk#zoUtFH37BxyRE!prvF-rITzM!ClvVw02`pVDLIFm=i|#j6NImss@<5AoA% ztrMG9rBpo6cHap_SKuv~REl`J`CCu=N7a*;DH_KWih0XTPakX05VqnwURaFwe0aaK zk4CH{Fn&i;C{*xT0cJuWeVx`Se zL6z~ZDVaToN-ZOgD+HMZ6iy}v?Fbh>;qK-NnO`cX?Mywm67bbNjzR*TKOXl^KC69R zChu_dvF~7~0IHXF#u)`ZPHZ^`4NdB_I zzoB_uHgaEu_ABG{^;y}eFO(&|mv#SK(o}c94wPHF-dEMrTG@%?4C>#PyhTKEW>Vom zU`bL?@25XOR#RDYlkNPEa3< z&?quhab1n^mzTC*B2gftwtMx0TH}25+QL}e>Q%w3joj=_wxTvg-;!c^-Dv%TJ@frt zJJe!PKD*DbibkGVu(!qFOL--){KvZ#HW%fs+kw^QV_p0Hl&&Z60p;-Zi^3M(8G5E| zD(qVS*;|#4Ivd&_kpwI7_r16JP8lP&I`+b^oWMaQU_a#;#u7*Y+Nh3O26ORkf4 zFKzDdCTtT|%=nqavd)Ot<<$knylKEUNv}75&DW(%KP0~nw#GqI;_`QCw1T4QNelDE z$Zv}P+J%@x>&f5SgwnpycN9#6$kQGt+s>N~@XC+8cmPzDk`qIy5^lEx` z4F?ojQSy>CTvsvVwoYeHdj@O+dW0&ES+3256a>{Nd3D8d_CQ~0_y}dNhF)+$;#;eF zY?bo3?)7vet!ZY%N4wkXEg2$0xbRAq{U;AKFb48XAdYDi`Q$e5G_BFgzyEqiAt{*w zxNn5x(qI8Na-9;zjUZ-G*f(F-1iEYlZkC-d>J09#NWH^N!fIblET;B4-zxEo1u4Hc z@p0K3B;)iSHK~}=K3M!FGIM6(0t4A;`6Sbc=Qoz-^$fZzGW3~{JUn)~=vlJ+x(W_} zlLTm_i)HqvQHvh%IlsE5$1l4`LLiP7BO-}zrS~56!$E%F)Cd41cYQ(%$Yc)0*}x5G zBtdZ0l_BkIL;|!E{4o;!*rmeI+CK|wERBlJ7+5smOHwp)ZQuf+oy)>b)^+w6qk01E zUxj=D_Bf&bv+Fqsq-VP99zFY+QB??^5yPqmXaR>8EhP8KTRb*$$_uP(~ zlyqBTe|_Rm*`Fq_e>q*qK1kWtT)bXN(KD)TKOGi#`Z8B1><);4ojhk>Vgs%d)VV)2 zjlDV|f`3nv-ADX&F9;xeN=Yy@K&Z7@{}1iCP}0qf(zcP?^GUkfwc%)NcMUsZ#I6VG zVQ{$s24sMu3?P8-|L^`VLG3rBegiez5{EpR8@E_V?tyIieY2o{&o;QZ^RrOH4`iSa zE3ow+3z{$)k)w_E#&c zjDMk_IS>d>y7<0;%n5XLcK%}~90@*Yj&_q?0=Nm5Zpzh zMLvB04Nc3T_OuU@N((ABQ3xW~Lr0|Vn6T9&EC#C#<`4P~K2C6U++B%Q?^Ld)6t03j z;B?oG8sUm`(_Ov-f3un0E2)5L3N+E?WQiGyT+hMe>9IUzYral+UM!w$cAlLd)aZ&u zffb2w;SI)H5)e5LDsm&fFV!RcFu^QW|E?jco34wQnV84ubGl{SSm(OQra}r)%e;ou zu)T_kGixX&>vAHS366iYRsGAmfr2uRi8#${!+U)SKRa}23_a|dq)=%p=w{EIzjzs^ zn8In~UNavd7{^UwH=8-SQJyb=8H!_Sf|=i#GsX~67)n$wdAyV=$UuNMt^Q?!1q5oM zv*6;>`w*--jKUm%GNkP%Y=74<|D&nkcE_@7&0e6eY9;B8b!y`-OPozZi7K6;KsV1P z;T5bC%%|u6x==SihKcOaN3Yon?@J$cSdl>tU%-|Ni;-0;?Oc&Y)0);_b+-r)wBFJp zFs}+#n3oyqM0I-M7KrN8ibe7CEmIP7=K(XhJ^$xpA&iktvrVG?z!FRpzlz7ax-sck z^8f-o^`_79SxR@Fsp|U=XiTNLvgZ`W5ly8u#7NM1jN>q*jb`ZZ3+-ePxt^2(-{$9B9Vj75>j4ub=WdZ@~uPQJQsfPL9x-8iI34r`%Q znwpiJene}xVs^iBojne**FA0O^U@>-bRDm*q}z5LG}FPMnM+5o8mlds^;|!kJ1=B+ zLLV!gkW}NHeX_-mn8scB~RZT?7 zhmh+G9UzMm8JbvSv$@)idvj(4T-Z6Gq1E(Q1yk7*d6748 zt@vIy1;m#x{OJJu7HXmU!?4XXiwJ#bvS!*x2-Gh~%n}x%I$h;EB9--Q=s~QSZv+)3 z#nvLaGVX^Fupy9swTQe-658n2g)$k5*1pfRqqDKsF}z2LPO{^XT@IWh?sW61etn2bC`b96jg`0Zx zoeE;>EUVb*mGE54K8Z%M_f@o22Fa_P?iFxMYn=htj&p~=mfkqF zLg#9>dLogwg&0eMCA3$kaW$|}9j#eEaA<>)3Ja^Op6tk{KqyFVE|ixnB}{{104LIg z>=ARHL3#T1A(r}8QFUCASQe`h4|#{vm}LdAc!-&{yVLD#cGRb9cRz$JFi>drkYS}J z$WL~oL0WoP`n&rn=p|f(l zY#MbPCw=x(z$}wyQ>2P%9Y8?wNt7{?j;MZyE{M(){~2V_ruNz5gAdEh#;p^+_k!ty zqE2Imd)|o*VDlOzMBEbQk*zDYOS}dvD%O#xY^?ZSLnuZT-W&+C$4y{!zeZGs&2a7n z)o1#iXm0bTzxyg+?6jU9o1#{qKGHh&&~0eqwj=spU@&|#P%i5uEkF7wUUvUH{y}7> zq-aRKwe02xeL6l-^7|bg=WMsUoCHGdjS^%gZFFsgrOCIQj%)U4|`SEIWN)E8G=r+=Sm)*}Dv^Q4A8NRC@aSM0_8s zrTBTSm!E~6H#cQK8bhB-5!Kugm{^IG?smtZYf$kQ{hk`>yYaM3mkO#Hm*KWS7BjXP zvSIVMFPk3nHW{EM05Z9{3OMWph}OUQX;a{1__77n3rw!EkasNK8K$Pcc=={N)5S$j zrb9sz|J$uFQ7f{GniooO1>d%l>G}5sqlU6fs4}HfDz_=6)l}uhh}7a(s0c<_NS4NeY?J(A zipCZ6a6L_jm#KP=nti&45M1-Hb&R_w?w+<_tayVPKa3wU^NagU7h`_HQp{pBe2H4Y z&CtTT(_2%%uWYpptLuHkm|NHl%Yw?H zlb4~^Z7)1)ow>!rR1v7WC^|m%-V*b`v4vnP?>Ri!#{M9Ly>Y0%jr|0<(R0AhTlmxEL)% zg{9{c+17+E9|7+BSRGph=Xxr>Yj<)|HCA8Wd-|T8&#_GN{A>Uw;t|zgqMkBmD1g$p z&nES?*v|yzEgz}3pV{p#eJd{Nw&d+3orJ_7L_VXjrQQW>ihOh@h`UiD_mzYf(MPn# z>T?KH5e}KnPB)UI(fiL=2A>Juwx`d9g)0*Eie5;+I+qU;2we#^<^N7f}ur+i=dC~%-6b#UobSHPn?C0vk<3A@9hDGt!i zTbGSDGaIRWB1Z0L2ULlWlQyo#OS~JW#ZQP6-j*DN&Qtl4e(WAkXOl z&y2JJ!M?BYmuYrDx@fRlPFU&o0?P_8_&=FXv}RoZjh^?RYdz8-c`dgr69Y=PQTkIFSI(SUEz0|?X$4(zRn?<_K#a?M4oO8sI zLjO=$F}C&yq4JA}s8p=!;m6Y2EKwwHo&B&h6Fatepf3ev9+xavnG8`&^|4u`4xdgq zuYgZ|`+kBaiS}mXgSJmgQH%BtcL=`{-Bv9xvra+<@Ppjvi^lXg!{I(WVT$`7@TGHxkEHG#MjG1|e1ZD>C(o|vP zgcX#o=OJLUf^|JSS$|m2(aCcaeELOUTm8nYq=meDgzyRSWuzOkA|Mh1{yvHM#vlAu zex@}4C+a^lm46`~!Vhn<0dM@ppQxV>>+gvhHz|R?3Khz~CkXy0^7j>ko5YS^B^G}A zTbjpD;NLAM`~qsiyV2h*FZ?IVFBAZ96Ds{GZ8U$54E_{2{kz3~fdPP<(CJsXr1>-1 z?}5}m<>90KGtcjV)j#F2{|lbq1FgU3xe2v?75FUZpTZ}2qUvvf*WWYU1W~`r@?S9h z3dH^?3nAT~_4yT;{Zkg@zhL0R24HXo4!W9635C0Q@|93(c+s)bk1NU+kqW}N^ diff --git a/Documentation/position_control.png b/Documentation/position_control.png deleted file mode 100644 index d8d1a8b0cc82c73077e7899e66892c5bbf11d9d2..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 36561 zcmd?RWmFx@_V!B@cMBd!2n2VR06~JgOMsxkZQ(?44IUu4dtl+3puyc`A;I09^%i^Y z{O>vEJ>!o1ez;%m?TkRyN{{ZY?y6ZepZR+_NKsxA9fcSL0RaL1jnr#p1cV3r2nhGB zknV$TjC@wA!LNIc%95f8CH<_2 zb%Tv4rOEj;eQ&}buElY{Yd3{vZ&okm`xAdka0LhmzKXQ>?tVWdzH1CZ#$Vt5fBM7! zSsO>6NJ8qFqPs*zMWdpkf`fzYo;ph@DMc#M3V2_;p6$*lh4DqFq|E0kq{cHFIMnK@ zKCr}WWqJJgF}qnm8Zxp7CxR1ph~X2m9d~o{^(yNbJd{V`i_^JG=@yAtY_{_aV}%-- z#LlZB%uRuzq3@pfw=Sj;E6x~y>ocXtLy5Wnig05yq%D?SqskUmqDbq0wo8VE_2EH2 z{nFA>I4Q3vlD&h2DCefKv@}Y5Pi0vdGAgPVXWHpIQ&aDYm3X>Xlx&1SB|f*Y?=>|w z)-zSi`VB1H+|54lCPmt|kE6)dHggUxE;$y{0|R^Ydre{@n^92c(aucu+}s={DbEMX zS37Q($N7GKkCOV-VH5}m$(hmBMrH#k$&ryimk+>2d_i^g(`7n4K91>nCm|sL^E^UF z0bS{XdETS7{^XG0U@BkPRG~(lY8xKkI-`T7b_)v&0rI`UbTO((q(`9dz2dl5eDvti z{QNwJT(#Ad!%BB7k9XbDbme=UDl1CghYugt)Yhgy1)Vd{UmFVtCn`C)Z^dDGX~|W9 zJUmsN_T|fi!^5bqcQ0PNAmOrlB?5NDLa$sH%~u&38p0Fz^Yi27;aOPN2T3-y7Gj7E2*(t6n*#ZIpw>}(ft1Yep)1Oz>IW) zhmRhutgaT63M_7sI*A(^rdL;2>oRe3a~nWS|EI-o-n_B5x5pD_)UJ?XAXxss5v&C@ zH8C|UNJU>cy7>E0ivdwm&%M39Ipk(0Cwr5)F*{{7t`B>dg|GJ?h%2S1r-z4!|IbMu zKbFo`7D}ZcA?Y!N+V?trQl&dNI7qjcZfP;v7|#B)Ut4D<4K;Py)OKJX5(xe*kPA52ba24}1eq}rO91$+WK zJ|(skdG+d*h{(Ov0b$qur{YRH+I*BWG-lhAWo!w()6?#YEq;H_{8~~nmCrf2b+JgN zxaJbiEJFXXpE5EyTZ7J3ACpKG8298T0MC?nTdQ; zYeLL?(i+h_F;ShDC-oGIRKOK$z~37WYT5@{CoL^KJWo=Yh@R?W&!v7s19u@EQm8t! z;J?m$tuM1P5y6}8l0!JRC4j*3+x#5d#=${FKhdFF1qxx|W=tD}xVl!eUq$SxvcYw( z@YITciL(K7FYBhxnmkFTG3H=8{LBs5m^XglE#Ibe6_*(8go9Dbir@pZZjRgC0E*bl zDMgF`sN0dL0Lf+9_H^aeUNhVU0?DN<0O5k-8@BMFPOz zWZMD=<`gQzd8!2^diBb9*`=lM&9OpETg8MEs6l;|v5^7Y{7tC0v!PG#g&8%SgbO50 z<^2GBg%z!prQBo7qvAlmKU#Qp$#kpMe#4Gm=Zvh`%JXV(&Zmb+BGS#K^<01H)a5j} z4lVI^&N@FhQus0_B5bXi-!#IWViM|zNCW>>FOK#Meigu)+}qpB&@T9b%q`y&YVEe! zp+DZrRg^5?DFshS-nn`RcWwS^_{8lJ9v9(25W)}HeFy8Y-I+pjhJ;YO9v~gg&YUdC zwC+st-Wo8&2bVN$+BQH09+?uHMbeQ!u|C&YAysH>WF(We0J1la<|#lGx!#!GXH+&_ zVR3XcAYAD4v#aaPbDWFwbIDO9Yke^tJbFX@BV!0Q8F?_Pp)7skCce#D7)6WvR-M>k` z^n+b%<*Mr!h4q&4n9mw+ZJl3BA(S7o4|jQ^fQ~Ew$gw?1)M9c)pbuA@dU$wPlYtKN0Vo^;T z(=dd8NQTe6{OpSgAw5o!Aoo7n>%dcL;vp5-@W?C;pCg`+ay!g~E5g;teDrKuGP5SU zl}iHUteAfZv-g>7UKVCT>a{{=n&^JoJD1k5LyKg*AS_9(bT!_gK8Lx+WDhUm2~SUw z$Y5*Vx0rv9gjdbDx%(L4u3khkKlWsm^rW;5v|r2)T#2vSsgF9&m%7*-?S3Sz=gBE@ zv)d%Qe4II9O`p;pV{4{?7&bRDv83d2uq58>eG?oK;wGR!kRk|T!OZ?Vf7i+(A|^Qq zk>f|+aWOG5J`-o_L(d=(2tmkLo%4H)fXw2>%x)o8;p4!KRmXq;4#tLxn!T^zzlwBT z!>&`PZuTqEo>fH>dau89C%|Pfm#$fEFP4wBkvIPQF?PZhX zbyzLNr(Rq~|7~UqtpYEL+Iz8!$8H5t=^@2Qe!ydLbfQGSbs@68f`BS#0v)=OxuP^ zU-Q3};AeVShYLwOhAmh%ylcP0mA}?xml)A4YrX6v)%1?{p=i`u_EpD^l~#+#{q*sp z$liQoSsdL5_0bUX^M#+E{ZI+%@K7)@F`1c}i!1UOe$nD^aW75$uH_~Ov15Gf5lEu) zT4@vJ%fhQ+?9IL}z?MZFfn~&LRo+v;E2%>Gup9~2G18d)MLaMidot$sLM<|QUBfjx zN*{d;Itvb{u}iAJGD!&w+L<%Y zgIdF>m2Qx4%->UMcsrK9x6Cz0uh(!yC1mp4U-)=w^0w6<9o@lqkfT_YZj5ko^I`=q zeLE3Nqo7I`Tjh^wBH(&vD;V_agPhc|{DU38PI8l>w*9^-*PZ=6iB=6KZX;-5d)}{} z&#F{j>MNKg<~I9tH*$RsSgutNejRrNN1O&mQBS&EgXuaLN+H z4}EpZ-@PGg=5#;Vj8!jT0MoViJL&A-+VGRbshJ2AtV$)H`%29F<}d z6&{?&V18O(H}^MucwYp}yd;}QZWo8ye1zjivBYB+mDkxZ5@Ez3Rwm}093OMs_BRs= z1s4^<7-62rE>%%R?8BYPrcMb^R*kW|{FFLvtHu`+zN&V~P44LGJP7#N-s!Z3UpUyj zp-PcK-U+tmcrhf3Bkqac3r9YlNn#aS?BS_7mu?PeZ^mmq)|)LJmY0iBY#M5lUpzR?4$JYY>;V8J_WsctTqMQ_`^+g6c|%P>Ft zNXhhDsHPWWFv>#S-PZ_PBHdjuQpTj9+BOlUN8)~FTa}j(ssH{gGq<_orL&}Xj7e?w8KVdUV(>N#P~2SYkmIF(-CW$((B9kjG179zH`Az;ahjVERJ2mQC)YVs8#Rs z#N)4n8eIIltFKmz=6^MEc^+0=`#v+$;L$LrNb2*xJhn(qhKr^vGR2Q@$RR9z_WF%V z3E7?1s~qIVjy%Vy9vj=!zZ@XSOB(ChUIr(@Nz?0?&}7 zip3}e=FRl%b*vBl?eCCo8oW5eY9&23%w68p{HL#}ZyfhR^L1?S)z4iL#gz(--Wb*v zJ`NrgEAt^>c^&I@u|TaYFqq?}!5r|-caPbW9yv0XEJ9$w{$x8%a$U0CE1>`KW%3K( z_p>>Teu3Eq74~uIIWE4HZVOzt^VgjeK6bUUjUH!9*6xi@y71afp?$r*V5EqMd<+We zx;)vEk(RcZtHUQH)y+giFC-Q!h}tf~@hWu5@r+~JJM*enL6OdC?`AX0d``K!O`jMk zEO@zM_N-a@Wr=5-+TcRHN@MpuDb9`G<5YsIiwZBr){k+OXv(EAvCtm`zhsZ0gJrV$ zS!5XQ6|f4&%oFxyHsO_M*=p=2=w0bMtxqHlyq_A8cc7(9a3MGE%Fjv-BfCLl4=PkA zf4?o5!Ktw9Ys^^GKVB%Deh*|s<1g`0PKw_>c<|Y_`9^)F?`T^7lGSZytsU|6mDBff ztBE;bx=t?*hb#pdCQ7T3pQ!hfD9D$`;n2vR!rYK*?1GrsIUYl9irN#Mfi;<{shOa5 z`DpK93XUSLOcYzyt)NET4Z+>yx$3OA+K3n5N!q44r;F69BAluy72vSm|kp0RclCSFhma1re-;kSx&o-m$XJmM|;Nyp+90`@jj)uw$ zHMYB5u#_;E70Cg^>{w2vGptg4xjAgz`bUA&-K|&Is?Mz|FSz#$n$mF4qmG=(R|&C8 zc5lk84oi`~I7L@`^k8#N(S7o@3Sw2ZWes}&cnw6YA2Zv(xL|XryPA04Vlj-PM`VWt zo2p{h_Tt#mCVpTVnXb4YWv<5X8fMFRWN+JE{I!;yQ>J(%9ViTb$;o8mO8)--Q&Usuw?DMBwGUkzz;b@$GJMqhfOt^kc!XlM zT|Zz96~n6yc`cJc{}~n%ZE&6E1zZ1v513~|CB!*dSw(vF>e8!5$rjAXU%>y5isKHPH3KZ3KWK(6}d!?d_R!5Ex@q(7zD4(EyR-S5EhItkTlRs z4Vs%QMqY?Yy?XT_DTyTfV~J*y=f!eoM6K@b#|MaLXlRO9cj;&=rkb+y(#i^Te2<*0 zEb-=<8HW_N?YwTaO|o?M;mHXZ%Ugs$3dYfDpU3SrZ$xKESQy9vTJH@agA90NBs#~! z*m$`wi97QtI3&;|>_9RO8j2&DBbzXsDT%3SpuwPBu?}VpppEP=w*HIO0R)Lnoi0;T z)A!>=A{)-_KmZy`rAp{>JNQ3KnY&1mIX&di5^ibI#(Lnv;bZrRSdBR#rudw6FixLxf}g5f181dg4IJ zEH>oaesQ!0@)j}-T>W3fSg%KD5Y~beVs2oE$zq5Oj6DU0i$-2 zZY|E=qRr^1-@ku@EFDM({mJibZ6kuWg1>zEQdGpi6i-4(*tvG3^v~^%O-kZ-+15ao!ky^yiTID!HpGE1(Os24Fh!kjCiH{9akfPere+ zs6fNSl>FxspR%&DQc`~GGiBDRt1#{i&#Np!LP6>7>r)dZ>0WX8b6)C5sg4K=g%PK# z(;c8#g^6wjXJuv8)bIpnfR;Qb2>E+QF-9aLq%YFho5gq5Q2w`eJzoq9Y9LCoe24uo`#dF_V76z(#rqh7tHlEB=|o zb$?-dd%K}QAm+Yhk|He!8=EK@kWLJYp;JIm0~;;Vt45=D?|ccZ5D@Z6ZODMO_x}r- z_#X}Y-=y${fXsTm_^x-9l$1c}6Biff`NEe4Bpq5ja$)ZVkF(u8iR3p53VS2D13mG~ zwYp3N_bLMnpMWVcf!)mC*Oy~q?s}&hCJ{lN92?udXlFN=ewwFBCnnZSudc3wlRYI?-|3E}pQ*Ohpv41=4h$ruA5)qCPj%x0!@X6Q z54_J5iiq}v1q@$Or#!)UCcWueM>8868$BCUnoL7``?B2JT-g`w+}!YswNyV*%6{@> zyRGr!A3t7kCGD)Oaa&EY;AMr|*Un;)@tt2>q~j@iqzHKt6BAD_lx8d8fqPKryybuI zQKhtkf-O+fodwdI4%N4}r=aX?Y_0Qy|O3JbWb6QzYle-`0wFs@#{vg0jLH9P=d zIVpHh`KsM(N5;m+2iCE5qI9vB=jR}L85)*3Z7Bb_DL_Mxj*6PJa(VsQH!KVtHb|Is-;``XRc)Uie(h{|Vs( z@gGT*!>o9{G_&Mgp%XPx6HG@U+o)ocCsR4HW6sR>xQ5gA_8{~z5yqD7d~kTUkn<*9 zK&w`@jb0L$HH-LqFv!KEvXwu+`f#U9SNOKu&O3H*3-wmEd5Gg*qvYBbmdwkX?UBVE z?OZ>waH_32o+ufcsOv??Lq%5E?<@&os^U78_i7+`Ar#$=A$JT@diIUxo9D^?kD~N& zqk8$J(IeZ4P7G9u@!tgWo4ot;o;W2sD#Zd`Q? zbV|wiTRYs*Hdh9Rc;B8i8aWpRYveW`I&Tb?RK{8l92gix(FU3;lYqudi=g+iR|* zMyn|{9UUFeKVRuQkr1aPPg1k+wVG`=dmHW1X}j7OUoE{$Cf^G=+%asUI?ill*MObz z*e#F8M$cTqqpu-vHVk6)gEhVLXZq=VuI;Y|4B{$owsJ#=7((o4G@J=F`vUn%c#DX- z{+9d79ew8NJ)RA(tag9@%JC?q?=KNkK2Ta#2y&XlG%-=yOh@fYJB+D-$~WxZ=jRcj z9Q`?#Ki4-^CJZ&@xN$zd)8@v0OS{Nml^CwZ-JLae=;Oeesw5DCoZ>P{wR8+tl0N*W z)O+>JtKWXTAm;A&nwXhODXzI_PG&=Dwp+^$BG3&Bi)qFx@WeJ~3ILL;UcpOI+Gm8# zHnl-zXVO^cTY;sewjdtAdKwrM1m=RT*iNGA>T%7@!g3=&`v2}Mc=_vmA)n8MxUhKI*;uqg|^>CmKboIROWYNH}mnK%$jioM8s z+WFm&_Q*Sqv^7NH`mIBg}mXaIwa|FLOJqS&B!Yc!_`cN#P6EEw#ysy z^1rAU1ZB!z-YfyhkEM1318&1HTV0Qx)DC@u?{+aUR^>x>-S>mtTuO$V(zDPoS`S5m zT#gaHv>V<R)l3{FZ)`u)mBfKuPAV^_@1&=xf!-l?)m~Pc z!xUGP&;&n9qQiajO(G-P5cARRh(SYp-QT;#9va~o&GfeXPMe2nK$D8OKo=h$+l#Xm za_851Q%1C5{F43B+4T1oDy=Azp%N(pB^u>xr7w|%mZQggRmX`>Ufy=~zI+pL=o0AD z^`!j|3!ns-rKbOV(xVY$**KeuCA$78R6t^MTTX#D!?Y!e|Ds|wEUuk^6SoXjp)2yt zM8(O_-=CbWha=mj)?NnJr5~zGZ885NCAk1HwEw3XR;N*_k4q!p)|*C;LCTZn&E>Q+ zU3nM9U!l?teR;s`QXg!I^#bZW=OKN%;edF9;^W82G5pLgY9f9D&uybNm<^uVZac>8 zst5Ear`52=5wBcde*K%OwR(7;lzeYWLv-`zWKbl5r}{1Pa(#cvbK}57qVmJkHG1Sl ztc+d-j~MFr!>>!7e+`WoOxqP+&`gCfFuv|X(;AL1^^y8V@v3>=xEcI?e%}4J>Y&sG zgGJWF^i3l<-7tBKWkGr>ty)=@qDWxDbN<5Du!7{5soA|(Ua;MmPdFC#;%BN_{(6n1 z&ykhP42D9lH-?ynNou+JY*gcWKYR3>(IF|lfzR?AZ^r5P$(r~as!6l*8VQ$7S*vk(!BT&M2s^FPHS6Zg&}bT%quW~~>AucQkQQ@n^*^)kxx`0@{Cf?O z-I}Xd|Jq_jjek7`ucRLHn?tQavQm>_kIvoeLC|Av9_A%Ti>W16%|Dqa6jx|)}apF9G(B^ zym=8m&*e_HGNaT7B_$G|HM@DsKXbanfBNlc(s&Ms2Ak5|h*`ru!o%#05i zf|O(@`GflyiM`sFwJa~~W~(5~B__}EYtOi6Bm__)l@``>5bL3H+h>=P?lw2$M;F81 zr!GciBU!1(i0JQOfodD6$6RmidmF2*k7NzD$Ghg|?I$t3?MCUiTTu+G=8wmXx4hh@ z;tEHQ>MwqEdz`<}$V%}Tuc+6Heq4itsA3E74ozA-Wjs#T{kJ>SOoGC-UR(WK8XaT?TPO7m09LHRj7&vjK9U)Pdy#s%Os<9(N88 zM|Ca({iQhNOy!1g3{RYhi0B3ezkwO}+?>oa^YHQpy`};+=)?+b2iyAkSaDb_qPGll z8ooHQw{XMT57}dD_2lYKMqLy(_SWo6Yu|{iGJ}QlyArOMtMn;jmEUN9XJt}%4jK8? zyyK~@O&rp`WXI!NOMn04hm1Usio7rUSq)o!trVllAmnpogZX}GAZmI}7Oa8ed#q<`?Dcj@)O>I@*M~Aq*tCGi+yuY9 z(w=%;J(g#puSK#-?wv#HqgOLaC25uLOj;mHJ)sNrk0`$>L7frhjD#K82y>6D_G+1i`v7mJ&7 zof+QLKn=$U`hB(6Oc>JM(a{0m015{(rC2Yzr7aJ6k_?SYo2?|!K~u8da)oq=UL zkHA=$d!H1WVQ9j3(OCLz#+ACTbhJl>yQYHCW2)&|%56`!#DSMX^lQ|W@I%aPIvZod z8MEoz0BT}M$fG3sdZ(!pM}B$|6JM;Hg$TW9_o->8%Zl8!48g6->MH@EExm|tC!rfH z>cV`lP+s3J(z%h>bxC5I8|anX6j|VMt8HPsV}*oCePI1O61EkXh|DLSvgK;LGw)wB z*)6GfIFVAxUEh~9ngTDer{&FDp$_p>AYiA;+mM;M0YiLJ@_mq zX@HD;xMF{JsmZv-=<&_5+pDWEr63=~Uh__BambQ<^sP=k(RY1&%|{av2MV`NMW3I- z4_lhNq03jKE;rP!(?c%&3VVC+TLgp;+dnX`1~PAd_ijAkmU&bBzZHt08X$#|lam7pjnf*+ zbK=8|7ru3s7+0s)!s<-Kf9Y%|ptRd2v3nd)x6X(+jgsfACy`n456leWU!Y z8t$u5MV@CBvoV6{GN9=Nhn|x-@PF1uADdp{BA<- zjZ{x=SAOyJXK^K(TRPGgx6gPRch*vg%V|#+=9*8QQ$66K4C6X^qTy?2Er|&wz!4>eI6#& zM?|?qluqs~D+QM*gHc&vrG_2cc`ZfN4kuqj#lr^=)8673d+iG)Qv;ogVmy$0M1NJj zpQtz~g1RqgR1^aqg#|71^MD#uF2G7i_+i)X=Q3i5p6ilm>s)gL1$wM>c6@xi>nZuhhIL*2_epxfdrw2q~j0Y?3d%ud|&u} zKan#it!*RV!v3W%r?Jaf&qKrH3s&gzhXpa%grMAN(!Qize7uX&ENP=Q z%GX*kY78uF=E}v+Uxivcj+HVcUdBp$dEEqHQjCwYBPdz}x=^D;*Nqul$n$(~e%^bv zH-YJ|4a@{3N=c$ylzMI|E;Kpl$!`x6ve0jnQgd~5{N)YxBOxrA z;`u!w?ikUe`UOQ@W-0N+WhG^*a!)+KyZE9ZPH^XWKt`0s+Q+yC>9`M;+v~z#-{@8z zY8vlh7sHx-G_uHpZ=fG23$}X@nTM7>a`hEfVyIlmBoJ#j4<~}m8Gg`70p>tZ2l?f9 zaxbaRW+P@oO^OUQfpCvRqZVNExnjN zhIssW!7ZQMv>t_Y5Bl&wbfE8$D0HtN>qJk2qv#VTjl-n5SXj5us(Sm-*-yEX>fLLIs>?=Zoj=0n5SAQVH*br&To9FdR z)OY-bF;%~B=TM9P9;NS`>x;(!*w}SR@?&)~Rkj>mqat_Qz z?_g{#b>Fh$>xfR`RX!OA0S4dSeiTiA!snEin@eM)<;7y$5ejNB7Sz~rE${g^I)7WI z5>lY;j{NK{*Mq?GNYC`TB83=hW4}$7!h9?=6GE-|Tt(g9w$fFr!>y7^1ri$_k>?FmATKSN{5o55kH!&lKs@@}3Yj?J@* z6_U3Xs*9+hRRlC~d=H?0ySlpIU22i*xxzIejTp_Uqb&timDPBOqK0N>l1ee@>4q*Y zT;o;4_;5=-vAkgAbXB;Ri&?BnJuA)OrpwWZJ%+`TEn@Zj@o~;xczdaH08uZ+3H`lMtqJ=Mi(uDo)@H?Lm2G@>%8c&#J5b;oM1nj*r^a_2($WQwM~x=E5`@3%nC zxyW%Zr5<1K4&SuP_D1!sXPoHm8KyB`LPCO8u!k()p|X~Zh~h=2?d7DacfIlHle3S4 z{1Cgt2vys{-r@A(0IOM2j)jr%Vx6g)NAUBs^Amcp)mrprkD!^EDaa<9`6Z+}o6g_x zw?z=Dq*G;CRhi99`dLwhfPC?f(z*VozdUFpr$qfx&~crcW0;B!jF&epFIM{P~$@G zMp6#Pw0wE5)0@K5CTTf2P;YcTv7&t?nB6UXDO_K|9&PY4kZny{)<|OJcHG^0>K<9L zSXxK0E&SSY@+{sK)_hxe(q6e$DveB8G=a+KXHauA@>&LcAY7VRoS}KtdM#G?w&rGy zS!Vk7WTYJ}uDxcbunx7zv@JP|biC-g2cBdS`raV3Ei4AT25ZgT1V;g_9b=V!Yo$;T!EcD@wSa5ZrfXzZJBw9K`(ElT!9MftYXQF zT3sQB-%<&(rdC!B&RgT~g;&kBqkZGl0`F(5+WW(t&2K(~#Y~ZA*&SkEU(au9bi7bFH2;K>3-;H(4EP?l{VlP_ATOT4s8PrK z%`=;5f{b1$Ynj=eDXr`kGbnQ&t*WJ@WXG`@ZQQK@30LA--JwEwxd}<7^zhQ?vk({q z13t$cci1%cy^G0@CL*Uh3~}#vXDLS{$4ZoQmt#=>>jiB{$@dvzF1@ceHeR&pcMG+% z=1BS2f1&z}H~GBH*>|t3n`Yux<(nE@&LNqLO><$B3@LY9U~`H6c*D~27Ioh3K)bIP z(geU1na5+>Jle|UKJIyQZ|3l3|rQ@ z7XLysECacJbB(^rZ%yM(ih&`<$LV$gViXwA!^-9v8MExuv$-Gs7wWD!_s!Tue4%c~ z`pro?N-RDjL-wyaCGc+!D{ZA1m5WQo?u;VQ;a}%{R9aNHHx7NEK^^ka4xEh8?4VWZ zJoAhrRN=9Bb5}qU0Bj#y^#1+(v$L}-o6hZrD?Jp#-n}ahzyR|0?b{EaV(lrrN1#1i z!GIS6D=^rv^ZvQD-b><P;bEmKC+U--&jgie-MkXy zBjZyF^J-ov@+UaI)44FI;_%802NwY3J&_bGXD_kZtgJQwFEYg^ef?@R`Td@ljs~cR zJI>WPgP}Vy0r~Oa9;ms!5=^(yqP-llfu%#erE`%NiK{JaDUI@B8)j(cdxc`6h z9bd-(3*T`U;p^#m)|3+9Y*{W@{P`2qtpC(cfhkCkpFgQ{xxKUV$W;JOj|LA9&(*_Ygkvs4JOmh??v8wi)_nQ) zjT9GGOlcHUdv|trlKVp+;BfvLvxoF%DGBHj7ZYpR2zBVbSI=rEmcaQky>+B!O3(9k&Yd;`S_kSb!R zjpKj(_;K?UZ~=w9!u;D?1r)@4_wE4?(acPMuWwpg9Tm9kFJA`rnM%HXJvlk~S5x64 z4E}}{GfQAZ$1`Y&A}!kS0D^>i9G^oDSCo{DtW>XFLJ1FL_=l^zdq-y{uIT#?z&B$L=Orip7X{0M`RtTZ#djK)0iK zMn!deast?|a7)$Hzxb7co>KARt3rReSZS(AP*Ek_-MkCRy1L(LYuy|i*b0=q+(C0Y zI-F~HDo(50OrZb+1DhSsy-oaQe{G}bm!V-{S_}k0iz_b|Q^NQonCkl!c?=GlPPC+4}-KcEJDkdYPRqg-uBF|Y0)r*HmM%cNy zQrOMHb(sdbyVJoBUo-8Z;Wi-8_QRr@i&Z-&IVEy*Z`8K%OvTAg?ln6l^^6o&@RrfY4R%;2_qC2zUm0dqNk# zaUC6xhJ}YFCYqhM;^N~8?@qx$PzYQ+dp9h?!mybclJ>iu2hl-R^71BC(ES(-#m}hh zN$kCI!j_g6O@{FqxE08J0ocj~2o}}H;4)ru_a<@{9t)a$e8u8^Y##Gy0cP*)jE~}H z3kL@WHW^$S*?y3B z_fQ~$MBfvdow?gT)Eo&REqe4U20%2sFCKW-RG-Dza}(X2SR;&x9oRw_Y}h`i`}+CW z*Xqv7mB4xGW}Fjb2|y@}iSb<-b(Z z_$QW#)6nGBO)UX7^ZNRlC5+XI zN7yr8&;m+g^_-fT$&nG27tz4B2bw#OO*rg(xeZWN5MiyjW(Ec@2NFjGnc`>C#Sn#s zg#i^eFp{ePq8S{uS_?$OvNG1kc%xO|g0hvh;&n#5bjt2n&0oJ34qSot^Os+pC{ujl zgT~0nA#RxGU$oz-SREnyKr%leKE60of{>RxFx}cAIkyA<;>hr@tH6A^Sioy4>_5{O z3JOX?W1~eP&?|rymfrr_sU1uLRaR4?NXSS?c8-q!phcBWpFe*NX3(CMj`sEgR{>Jt zWW~S1*61z}&Opb#Te;o2Ie!AIG9xqdWiSdVs-vCVkDnv>j;p0%+e~D-QJZg#auj<<+wXPS0Pzq(pxKH*IoqveI8fCjch@rY#NJS|)hcgIiie zZEbA~(AkEVzU?9#vVPCD&jQL&IOg9c zKpxY&rFeiUEe24~2BV;(J3Bf3!>Mx?Tbaa?OH2QPq_4ReI+OX&O22!I+i;>3x(i*Y} zY~sLy{qVj333zt^a72?a8#H|raAT7j0h}kOQt-&vQGxNt${Gn+R-LNe@o|EG4tL+c z00si)$5(9hw?=p<%m<4Tlc^OP9RCp+vnVI&kPVF;hV)afNIHaVZ zf4WsT8GngEbN`A1s7xE0n&#{*Xnjq@T7)%2V{5@&+k;VJOwc~tr7`x?CU!Pr#)nr& zYho-b)oO3VffD0w=PG!vP{jWgl0-D6`P z6>o0gg@VO}k73)1x~SGo{CwIllf0Yg>qP>M!k~Q;brk)I7L6;1 z4>k?ZHzPP+f-w&R(zU3V7*Kjrg}gwlshDeEa1I#wqGcwOfaiR0D{O&Tx|ce1Iqex? zuN1Lfz@9DL4wQ^ah1I`lF5*qzEN`xu)N}<;n5xiRtnB z5L-eK5QhP6**HF zcrO*^7KU9$gFNrpsh!3qeXb0Z0K-VLChx1gMhgzg?xG_S_`q0+SZ@Dm_-8XupWF|W z$II4U){QRPXe3*#dGTVBYaiy$f|1kVQ{0BSzoSPPQ*1s;8Z`3XlOZSn$~mfJHSuOv zfA;;XKkAgU==zmG{WKb^#-=+k{ee5L(=NX?{4-95y$=5Mm%l2WxO!IB+sT)%jIy3D zN>AwhZBx;mU0hN)EN~=7C42aEnJ8apD}%){Fc>!_5-Bae)VS=0B}w3l3M=Td)&(Rd zfBx)cHetWz-KUCkxtE9Ck1M~b=0r!QpM2Xrku6p~u3jbB>Erb#qsaWJIWa1ABBH2V zhp5_vMQb=G=FC}c?tj!}W1ao~ceHK3)C@n#6yDF@6 ziP|yHUqsL1(P(pmT9rs2{}n}hKF!S}SYQ729)~%oSp;xejL$I3-@wrQmM@!fvg6*a zeys~7D;6T*yg?3m_I3^K(*1O?g$%JVH!=WrUC$~W!;FEba5=wTXk6`I{VwHtU3k<- ztVYA=l_ zA^evH$=bCGfQOS$1}?kYfD3gllfZrU5J%LIIG8+tv`|GhMusQ-gA*&#r0KKUZ-Wrk}N^M9`j z&wV%)Z}2Z0yk7q=Zd+o+PaS3ZmY@9f+aoxiC01qIGcd3h?Y??j#)+YGQ$9hbjPo27 zr^Jf=moy3yi*f%@Q-CD*#AE_eA^VY7#8(?3h^y2{i%iH>IC2P)6T=6UoRs6tZmyeR ztZ|rT$TEhV3Jy^Ihhtj8$6wIVq5*1aO{KY&M@oM`94;2IS+D^eZ4r} zJF(Aal1Nkv^mI_?XJd8?<`Df$cNFPeIgu;Jr8!Q4-WHr;6tbD+U#Ivt4xZy^4UsA@ zqnK|N93Rgf>R9z(M5KtH7&TJ}xPAvOvhWiHbok=RiW*6hBEdU6{D>>0{lq6CaG1rvI*tg7l)cab0AimcF%2v|w>jEk9V^00A zD_j(DsgYQM&E;TMql`h(0Y{SM8a? zLz4;n_@5#0@#sLbNzfLc8@g^Q5y;6(Pe2dl2u;ntU3Pj-B9#TUQ;qBYyqQS$P(F2C zRTb(eWK~hyTUWK44XD}I8cSS%;;(h*(~Y+9^^46ycsr=W+o|Bb}_r2bB zfU6Uj{*K9#bmMQ!Q?QCH`ZB?6@CGUU{PO-CE{PW)F4bP`_~^fii~!^X<=~Ss9mBsY z!6*)#R`fIqDu{S@)lDg4qAjITeya?F5SYr@zdL_fDSdQ-MzNPI#uUG`y**oDF>-ab zC-XeYv@daGZS6f@7mR-;7|*2NMO;LJ{F&wHs_GITUSxKEH@k^yENg!GZTh=_nA6LV ze3O&4plEHSvn6Jg*gbo+ficXOlBQYWL3+1g537}7UJBh*Sg2n)zaPHS3xo7ubq8~Y zeUi3j^e?%dc`=ws#HYTYo2kg4%?+ex!_FsJ;jCm^iV5={d$O$7t2!pYhhiaNc(Gja z)Yo7qsDvr^5m(a9lv%2lrsi9^r@(Wo(3Xot>1(8dr_g4GEvh*RuZFB0u+CjkbT*q+ zF-UMlO&Ui~hp1NK69CZUYx737N`4Tk)qrO)|;Wn(pN!2v_Nk zo4BrTh6Gw$n+Ld--kzvB z@n+_QGPYZSL)%~Gj5x!qj8Aa$mhDW1fkF=c zS*-WF!>s>iK$!IM>ZLnix2h z3-nfrHtZWcNnO3ZMPndCxP_XK-kSwvi^pZi{epu4E zLN2unz*@a3rbN@>GO`HfvLX0#BtzAB_lIheo2k`Z1;H2rH-Ymfo zV*~dOO}G>tL1p-BCi~jS5*LK3g?+-ZqWHY>k~sT?7cIQm#tTVqwH6)%B6P`0Q>C5Z z-yF<&Y^p0v&5)mh+Hwzqnvlar~ERnAHc`27aLFIsc8cG15r4#vaRq{fzQyg z-j^0GgGQnG3;14_Z7f3vRElbB3ep$Tg%8>}or_qiXnwfvSweAkq;N5HOSmEZHmyGdkBu-3JEEEi>`cmfvPZ$@bmS+lEONtkd#U>XE9 zZw#m}NhxbdSU6AGdkvb)oJY&c{37*x4pqKU3epAT z(S)8`H#tpqIB03%VpIvq*PG98kMVh zMckG7+RHOpv4IZONkWkQJ%go1I z*bExJZ1QSjsJTs7z*-nLCjACkxApQ*oMqe3zHv5dbN7}zy6vg1x@B!HF)%OpjA9C1 zrF!0wj0&V0A(@&ab!WxJaW%(#gh*`fr)9PVUG5^aCGD)WtUaOF=fZr{6mrk+wlq7b z7Yvp#R4y1azR%XJ-J0*o1ZjlZG_K^U*h)TSp00F6PJ%&HwP&kOSo@D@W(fVrvwrq7 z?XpaJQ3>**T9{xIGYods!|U2-j4{(%+Qloc#l-7uO>wJ{7jG;r1gL?0Gj8CWSN;O$ zX+QZkp#jC*wBdEJyBaO8mIV^`KLD6r5h7x5O1R zGzM>ljqBc!6Lj9k`q7#VEWy~S?YJr;Sgq;_`ZO?b&R7+Hut(B0@bHXF}8$0P?&moX^gv2BJ_X5c5Lz*EAq2Vq&Io`qF?7 zSguXfS5#C0@T7pp&ks-g#>xt;emP7kBh}%63&NQ~LL7ivwPD^LBvQLVr4k^6r87fw zudQj7?Gha&uhmTX(LpAG&djfv31P;yALl3mZ4**Uw*gLmLKp{!Ax?}OZ+(3opf$X+ z@4@FHk*x_UsvWC+Yuj&NVm8pa+I? z25&=zj96Q`u#Jrk02q3z8BbHY!OZvM_)G%dLd_Hr6-`k}u^o2m>FEjbQ1^5>+8YMl z30!S(ECN!0d_JS^!DQ(Iset;broCCC(67-K4?Ng`(yeLP6<@r z4Rv+DX02cW>3LZwUTR%eS4UUM`5gi(0OA90;nk^dDa}tJTae==;HG z4VKu{F5?TxYYK{r=kQ2r8gmj8ryZ72SnTj7Y2e$Wq$D_Vqx+!{vBzQD`H?~0^U5tz z!n3<@k6_){aNn2%jR25RL(and{2qux!>+1(0!{~`r z5kDWFI_|5D8F^>?R*$+ICfApM!G@WYiE}VS!kq#z*-dtK3%I08u@g-OxisRwH1Zz4 zDpK*(goBB^obL9waW&w;Vh! z#n_)Uo0F5k7sJm*Yq}zarzuZ-1^f6Z68e zg9E(9KiDuV{{zp+|MwRwbic)%#*rg?|Km$&D6j33hJ?IevJwN8YoAF1;iR^)amqKk z+kT%E{4IUI(J7t4S;9sG5NSKgkAnQJzFP38<2zr&8o2Uv(4U zFd>G^4j3~_a}YguWh4UBVdc3hoYXa!@-$V!Ypu1fZwG}z$6lT!GlY}rhUJdbtH$|Y z7oIu=ylANv4y^z6e>l$v$*U#61R+4N4okv?zW-bT8HPHp;x#$m`xY-06?>s zmeU4({rZAEgp7>rJ}F)o9o73EazKeddWy0*a^He6*6%W&a^PT)>PF zC~=T_X2m;HFzh@4UYQFz*Q9RyMMXvRnb??{L;a*=K%bQGjiYObe)!%lb5+jiV6z9j z(48l$!M9~M29EuSaUUVDCp>b$L`9_bwa9Y1=C~7p3e{g-?FNOTjld2YeEMe@OINc7 z=Re_3Y@wffk1xm?A_Z{%NUp@Jm?CbXonzpB-T)wLz_4MLmV{ZY+@QrFE8c1|N z#qrKQ$}{eQWnAoGS~a8#fU+0C8HV+X!<))|5xaG?A4u|^Zsg4M551nzaJdCkx8zP30fYSqZgnsKI%`Raf{T_E<32q_@1FE39zx zXAv|O`>4GRqPtBln-S#n7zvI3;wr8s?Y?Sx_*}&G$7F@blkmB7XYjcLbT}FD``4QF znW{uUJW_FMtC6Lg@K9s0H(NLA^%Thk9p=OJs3VP1JNd*8r}btodsO5*e(E#lYsVL( zF1%E%mANY1{uHsdoN0S#7Fg~lQD=C4+hJ>04_${ID*lc^w7qJYD_{3~+^~KHHE?O* ztK(?ui}zKn)l8RWS#=c0^89Irx8lOHkfP<&rKp2_NA+#|NQ|Vyk42WkLVb&sd(!-2 zcAUoO7eCj=Rj(@!r8hHx8`NX?evAWS=2>gf?<8ewR*_$HiBP}pTm9HT3pT$CMDArt zzyE~{af{;D5i}jhTHcbPa;+08*-AHMMwL31hT7**?ysT={Y;GLO__AvzZ|I!W{b~E zH=KKjz&6r-%;N^J8t}rRu_VBS z`(>57**>Bt(qyAOVC^pv&DHwjy4ZmQyWoJ`I*WVm#REj=%*Jf8h6tPCK5w@EL1gOq zdduAnvtN59_p8kh-uiB7F7G0RKCun9n|!@9>3P(X`l8X+xtM{`gUWe4%RpM|K(J3~ z;!MKC@>xz}!L_}|u{sUCT*>+ocN<$9xdvD=`Yw(}7EGR7r4j zew|24F?4-D@`b{M!_c8(=Q?~6k8gAmKW2AYIc9R1AIbYSMQItWHSK-KY4V`f?qfst zx=NqVnT#)NJGZmHCc|NDtG;iTp~{xHOg1!Vxt-DEz@p1z=K$@Sv7uoP^kp{eSs!!V zleTNT$-{hozjYZyf<<)4EIe&>jg5@^$~j?S1F)FT*Ts^{ru1)?^Oc98l@B@g7bDY2 zd)DVEwq|96F7+IyAlq4zvLgt5-^)Hngmnl-(jPEi4A^+oR-3xv9G{*lii`AWc{Ct- zjx*|Rzjum6g-6xi;Xs!(v(jZjmfe2Z>f4R9#_BzV!y}weIfNI-hKh?vEp#%d#f9gu z{Hkh<*}fIoT@)xdJ6)F)byRF@HNWrtGd!|u`L!6X_*KqGs<&PXG*o>(n-+d7ccwxm zb3Z@e89E_%Qpp4x#8YCEE)gHf`r=(w6eX+9NSO;Sw^ z`(gB4Jgwa#+Pi!i#v4mA3f%!sh@Hk@YuX<4Q1%l(iMg%SOcqAsLW{jtq2>M}eeZHD z`)Cp03m@j)2pGiaYAXF4rrxE!n@`-K3FD2ZoN_uCr_8QZ#>1U12CAYNpw49{^H%FOBU^kNS01QCa&ma%ts@EzJj#Z(S6qg#@Nh!)n^afs)0a)3oR? zG$QgzCmAB4Zw7%21ixZ4`oQ99oEIAU%nf=0HdfYOCY-XttS>+(Bint)Iv{0b{_SLu zA5^{;O~4GvhK4@nb*Y^>eR=_n;-jN`3A3%zsq0%J{y5j#KVG>73$4lV{8#7JO$~ug zE=PxF-^aiJ1r(^@aTS(33&IR&egL$9^q9WFSGrK4E@a{{?<=$SK**ZzkDz$DHVu@$ zHO$dvgk3CuX#sMW_I7qq0GdL};COU^fl?}$tOP_iwD1WxC;jq&+$axsde4hk@?|nYLfts2r7-!^@pH-zlf{_e*7d=%7R&!iNVPO7(&Wk+@@Ogj$#betbnmiMl zTzLP_FrnPL=ZAQ70=h&05bzWGknt!4PC}TDH-$j43F%V{9nKcVJWEe|tWH$5B;@E# z{nteHW}oLqYpo{FP(sy84Jv3yrrNvqWiM8`HxxK%T^&v9FXA~MC7k?+eNnHFGoMNB z@e2s3`lX9*p}%?|x*cD&HEY|jY2hw+7A|i!wP#G!6kdzCaWlym@bKqbLd#h#)rsu3rNN zL{^mz+?(tbVY!c|$%-nF&5d5sylBd=b?wf@7ZT|8dd5R^v!mK}{w3nQ$z&6ex+A8g zUYd<{{pHfZScF6Q6w*C|JK~P(zjh`%UvK$1zG|EpF$}fiTs7$|t@=1wo9j`=KKCm~ zB!PjOvaO^!i@cson^mu6Aboizi$IvJ&xMH+o&PD(Y@SH?D0jywmwekWiwafb#yHuN9b}F7GHtZrjjYK=A z67oYzYQB?m96c|;M$UhhB_uCLD z7UV|W9WQZ|j^uw0__;5Q^WNAJ`p=VGFu(3pU-#LD~|b4 z%JkhE>^zCrreP0&n&JrTeZ{oWkv{bYof6B&(e~6OlNfN7CxW5B0qW?!97T8hyLTt4T+`DRbwf&?n!aU7PkvH>oo7b3fam~Tmg5;DdmDMHI)>TMgB?5*Y z-HPKYhz{?Z;8U69Q`uiQ!dppG)$7=FT%Jan-S1Qj{rXq`HO**^=!je2yAsj2{0^>} zZj{U64uDSI)fRzBKy)U_2Znuk#No6Q|5HPxH|REb%I1>&Cb^F^k4ned_^sV-k?RzT zO=ozDWkPOKxi%!^q)Pyl5+HhY?Cxqsu;Yp+zTl7*dv%-wqw0|!{XqjY&h+i+j}lK8 zp7!uAsHtjdn0e{%)}UYq34>f!Um9CmjKx~|1nATubdc&XEJl=ja-%|N?ZZeuAR6O~PhD$zVlmfFe3n+U|KZK+?{b&vKn9VS@HSsN}p zLt@F4)^2N~cGTW~i*bLGwy(iNU8;|uOs6dce^2_L@mJPB625_#(R2gREC_2GVlAgz zP%!2Fi9WnPi^nifvq)OrDZyn?JymF0#h>9r9FnmVywj$wIZWBnua!g-L)_f+O;P#B zW}{ae_3+!Gf2AX1Wort{C7l)Mt@pNjg8G_vogK11c=_*id{G{kbU0nm`64gkPu6ii z3d=e^(=coN1>#9?B4&2X1~RF#gR{gUhnE~w5dgRde+1XKp!*w;a4t$OcA1{&xRW`% zhOTYJQxfmVjrQ}mrtMI&3uiOXtk1Kx?ey4I=lt>^XDxM+IjtR^^HzO=3^1b5{MCz# zDWllTCprVq1?B4=d0z1FEPGK+C^8G7dw?&&I9s+o=E-iRZ85tYwaR=H-fwHNjkY8? z%Y$iXv;JcbRd%;J-GDaW-HE@6XNmg z)A3V;0&yYhioWZNJ%|Z|TOsVuN5<8w3;SvO9n6{ES-YC=c+O@u^d&w@-)_Dkt4A;F zJxq};(D!T(9f;*DZkUx)HClvmA{%7y{(K){m_)MQ#@EFqqv<45mS0%_Y~8^2WEr6! zfqUVR+j86Xhx@rDwGvw4I?9JS-UylN%ClE*>Jiq2zdeo*I3i#yTwDboSkGxz^^~FW3k}i5Swx{-sRJ{8D!1BC2AN%4)>db9 z?f*>^*D;jiS8TuXEuQLp2k(x(!|Oa}q~v7ALutlq4qHFbjGfwAB)!z;qh7cuio&$WxW3vG%;DED#U6&Z!K%Pi~JFVk=K6Pnl5Gg5|wN|)7p_$ zk8BxZa1z69IvmDnRd?ylT3=f?ki18lpV#*>!)X0fY1n;af9a5`i+z(rd0v^)!MU_g zdU@kScI^iTm|<{koPAFPI#b9KgsG<5lgJ0mz`k)GKYj#pbYN=P5V4#y6JJf`3H_~l zyI!!7*es*T2?@Ug>yUEd;vTgG4nmJT1fmNsoqYr(yGq)#hXCdXfxfwgZ<*MuMkazc zpg;o`VDm~f!0TCV-xf{nat6c-P+`KK48hG)m54{1_6Jpk*bu1uKmBGv?+ch1*Z&Pd zb?X2;1qP#E#(BVRSXf&FvX33h{M%k$!oy>xqcgX%+6RV*{$m~lkcF`8djQ`JIqBx+ ztp8|q4Vr?l+_;h2G25M?IX^S=FbfAkj$OX(S4kjAHxJuuYEwmjQTztX94Ha@^gfQ1W zIVJoYwH{e_4)ZC8Hq#!pMgEB}Jz)#dpO!=$Bo||wybp%3#SN&vc_Wsfoo<`ogo{|0 zLqpXHp(bF4O$wqk{P#zn2QOREu-t-O$I(- zyS_%I{hP$=uLj(m3Jg8=a}mRH-R+G7wW-M}dp{_brP=C<%1Al6_cfX-zg)h>Nvq{) zu~yW|*R@RMJlfCvDF@@Vxk_;$nLv;*ArMtMwmj67=w{aVCR;nQp)7Fj^C!OPOC|$p z@(1?P{dlS?jcqKZMv5}MoUy}}P|}^tnD@`M?$Op;Nvfz+*Ox|MC)Yl(J>-LSjOr(B z(!^&q^8oH8Fn9pjm)K-yz>{#;X) z5UgKzJ1bTf+656Y}fed94arf$*V6&VCG!x%NNCs0~e%nO$ib%;^%;dpo zKwZNj5oB*;R#8rFWNvO32rxwg#40!=T=rLM4RT-qihc-Kbiz&9`=t33<==H* zKGL@dYv5WMO^l=T5Y&ptFd{WMgkK`8DEhT{vv#b|sN)+@Y=otY*^Q7*(RBIruoAIl%;X`PRYqi}J)9_ZPXx zI#A-(PO^_R)7J?yJ%>$XzufalLnkhCM2AGMPHIRu`uNO@_oM;K)*LFpXRIRgP$xm2 zI5#sPjPYq63qMZEVua>Kf0(T;=U?rFwZxx5kpFVm)9A`yawq*Qq0v<@b1WjznW+2P zDu5va3<1On#a6RGu4TB+Sh3IlW7wr zeBvSJp{;_m_uN(;PG|{-G7zk zVoZ8_bn*u+c1A4Bg{{-XW_;mKkwO#6KkMQpT~fQtZJp8ygnuvQA*ABT`@2wP{{~V* z=C{%syAQC`HM|Fof{&hFJhe+yM5M33Ux6U?OHh!?_Ps~Y{e|(_-aYg1)3+F`Vx_AG zf96+_gL$uQ*C~O;rrXj(BUyhhPg=MRnQ|_#^`CoIxUsoYGe5bD{P6wrfMe2B#ZunI z)~hL4kqfCWYr0=%L6FLPPrlL;Y3Fxe8ds2&v|h)Q-R~OCbsqP&wEVynvEzuh438vY zOSP1n##!PVrS@>(!>9pQk*2wkpR>aJJTxMs=R)OV063YC57GjP2LjupI1tz226^$~ z1waidsa;?Ia-Iq?OiP*upMc3waUQ`~_5$%!2JrYS_^oFB4t|+bR9037A%?zchGJq1 zh|K`x-kuE7rlzKLB`_;pb+?`b4MH2iWDoFC3JMBV$1t5tV(gzVo!M|1z;vKyIELx| zBw#?B27-}9Aj+LEnouU7F#T7Q_(AkJU{&PK!d6OJ&O7?5fq=+h!>Hh|K}pMoQXL?{ z@uKoHn2NyZ^Y~HprO%`s47YAQO6-6fC!_oO8wps3eP+1a1zJaNWdq$O@erp%;?VNX_qi27J$bS~S zWu0{w$Y|JMkjJ`E2uqOr_!#EZ#?>~OL zRTwM)11X?l`}>X(Z$C7{tM&Dtc%iMEmn*`G_!t$>@f!iKMLd3LWm{-Y@#OzZfBv5! zg#Y{Z%(AC++W1N%&Jd6S#?+pz&)^4*x3IE;=)!nGXf<$FPD66g%5dd5H=m~rPk|V> zx98nFvGVw<>B5B*BS1HX+$U{D%62Eo1FzufdV22E$fruxM>w*)Ac=!(HxLPLg?IUK z0{8K|{UqTs)o44KvnmFl8e-_=NpNII&-$Mj*<#Zd^*h0z&5gjtDe%FPr*I{4WWV3g zZTNiql$|eI^d%f&LJ}6FlOi-}|@%WRe)T_S;DRy%|}{gip8_@C%u{07%iKr8d>m=~GS$r2%(aZJ-^ zuvS~;#G6y=hb*YP)PBU3y%vp+d=4)+dw0vF7udL|m7Vo8>xBM<_SSC&2mBM*3;o<| zFh+qrc3i3^dZ88#^Wx1~gy6z(jwr2He@3YG%tmH;r=7Z%eHvVEyPT5m^s zh1wEl@7r}V(>DYcTDDZ=HdG1(*^%&YCLgFd0{38_0nUXIf!sP8 z+xv9d+s3^kE0$~*AMt+f^?!N&H+>p&0sY^www2auser#jVms5f>X=?5^Rq}ItO`L%?lqeb8CyPCXPdOsI**t7K+s-Zs?n|UmJM5<%v|O< zoiI^}N4!_jTQeV)AJ>qWovqs5)D?A6ciBRBWU~!aN;Qhg3T@iQc#5lDyiz zHiFu?FBl9`(zFeoSLW|EUWV?f{tqG4@JcK5-qlQ7?e^Z3d-z8)+}6v<%vA#4ud8Qq zvtVzeq%5gE70bnxqTVNgwo*?|DwClx!x^T=F%~PY+j{QObMDk|=l;HNY8TkDvPH<@ z#>A0-=3gLY-;M9*r81d2gFFQ|3iVj&8U#ay{Iny-OP}}RtMU67%QWs>p+|Z`g*1@#)PrO_S5+{iYX7xY3poe3pgt@@A0A*?e3LV%-#q z(w9b0D! zHUGDDZS87)^9&}updc#B?Bdanb!Tz*p^~?r>bK7cb^OfzWEeX|F3Kbn84o6n{njyW zX<;Glt(HcC;(QDOZ7}1}@%ryH#^@FuLzL>sa^Jk)>st=C^X=$Nky^IYqZXpIosVdw z`{I+bm9DHGqtiOq-K~hT>D!q8eTqiRZAOOvJE5_RzCPU5)6ccK@w!;EZX#fvmurqB z!VzIBUGE_Hx_Y=IME2rv;0fJw{($Dzwv({XW!d=FC`Y{B7OPEmkVU>0A-~3H;8)ue z0V-I5{R8eHqNC8P1B&UHCi;OpWe4d48$&LUhx1SD24X48{va_V6nQhcK7S9p~C5?ZA9N zR%=JA%Dkq;P2y6$?%e#%8q;ka{<R|^G655;q}BdlqHy3RxA_9oBpk@!o2llFEzN&deRMhw3~FXp432E4iU0dr80 z8m5*+=BTxiC+Q&_n8|?{C%M{NCv(-;Nt1uy!P-+6`$Vf zyo*jxy>S;*6U%+-lA6*yTjOq_4^gNMU%ejg`)RqkyZM)YUtAoO@8IBnaKDOUXVqzM zi&DeY-Rim|vaGeEcA#MnG2}uVUX~|GF`s;lR7bB2h`p=CV-J45dwb#jTdRplTo#PFf6K$Y@ofJs+=! zLdB*Q85Q}WpKAA(Wf%((HK*Hh-v4WeCsN(MYWdJRLowm2_3?MmtsRLP~K| zrtVJ}#A?RgE!y7z?aRIo7Bv?{WajeL?P@-6TX`n4++%B`(SYgN!f)L~b0d&9y6t%6 z?kP5I`0ObSk;WP00)e>`sHX$G{q%5P22`EGb;+-cYWUi}|23%_tG>nIw*sZ1-KFzw z$xoBC`)gP*@xiXFKMz+c_Sd5rh%sJ^atvKE<~ z_%|1e2^(pR;~&=4>Q|=x59XZ%P+BG?wz=;a0(e+BYVFcf|Gl2rww_^nZT4F;NzYtJ znJjI(deNPFI#-_gpDEd~*C`rDJ?V~1?`7#`K~JI&KV@e}#^(pvXDq|AKB|(3$CXIO z*eq|M&3mkWFslpp=+E%>6eMhZAK=wlF-*j}uATln_&I^EY*J@_=&2eyvnsbNeVBVz zNLQxSm`f~T5hZ*u8Ss|*BvDN;Vr$3b)v~1GfxwBMoiaE$m#M@bKUA9MTH@xit!ocy z<&(gu2{xiM$#i21IGaUX_#1XSBVl4(5?mDifW|X1GfVv~nl7I92#2EG&{kx$>WLPGXsJ)iI|XU>j27pd+v z&V%hoE8Q-FWx$~8WEwe0Wk<4WDksu2?F#HI)xXIHw>x_dI_ABYuG#WGQ!!rIBZo7R z?ff9KfAT%PjgNBy(vMBJ-C-;Aps$f)A>;&fvLjd8Iqk-Sa?SjG%4Yb5r%dods=`i2 zYdC7fW97vEk7f=WoMa8X@xvCTd=PoexRJ3h5M;Oo}d?6}>TgQaA%R$Nzt{(f>LM zk7O$nR_n3LpTiDGcI{77l#*G=DfnzY8)L6o#UIU(@|xOpf$B1)pcDu8AV%uZR4GcJ z{{}VB+4pac{~9*10z1zA=VO$kJ{DS6_%*$}56B1?3yUo7*T~2WIu8&{fSOP(9i4|z zfrvHwD{t~P2b z352v(IaVv7cIz z$2NIO%$qgz(#WT3ueCQ97(xFJ_88dxD?UOlvj?Ao-ws#>3|j~2YY)N5fMI)q-EclO zc4%-=f^Sre(ut6QBJ%53`Tp~onwsE|uo>`C!_0QvVPIh3;MlxthzDDD@c=mqh|AtH z2qk#~*=obJuAma$1$hl1kw$mYAi>y|Rx;9QtFK+A5ccoGfE@-)ZaT*Qc%B6R6S8>W z&HI*c5Q#CTABb>(g#w_PbY=Da^LS^gKzY1mmH_gJriO-MpYy;4E7=i^xAVFjI)a4D z+1c6XjuPP{aMc9@JK)m!ZrnAu6kBg(WCU_%OhGV4vlrOh_{798sf2c!VA$dh@B>Oq z2u6c=G^TnTkirAeWLfQT4Ym}~D>;RI^50&Nj8~xdSnE>J4zLk+aBzUV4dDAk*GfU8 zpgH(m_JXrOS|lrU@LeXc#HYz>e|r^_hwU;m;1tf$Z#3>o39zYzSK!)%RCiVII;3Cs z!1peA8*3s01O&)SxG<`@Q;MjVT@uuofb^i9C(u6UFC!yS(Oq5)n}O!SV8)de7u{*2rStfs%>6bYxv zGsq6|M7xr{*&I`Q6kQ2_;5@5i2hb%)nh}?B zpk}ls9|#sqxVfV^;{|37i~4GWbH&X9%~1!_nu5Q`tYOES zu73d{gd$N)+DtZ5Y+;QIfq^d+^%p_l3IujJguSHRhqrmNXCQ;lbJT8r0l;adXnAI@ zGZ;Jx*4#4P@h%GyC8VMik)5UW5^@e#a<@tY|H?=8-XzK zUkc_Jy`yYLyMf!0W$D_u2dz_*?v?!de^WOt4Cn^3y_ybxiwxsP(asbvp}OcS&AcF8 znNM;MxxTfvzK$FfvO}|oyR{zX7V7%_Y7IiITli!w9)uQ<6pvX=F_Yi>dDlM1Xy)B4 z$|>|rx<_MfZyh-kMy@QLzR0octLJrQQjqGy)1;aR;&hxrmht%I$|IB2%%wa;8TVY# zIwP0X7dHYmpTA&`DVH%>W|!`KbT6LJhjT^R15byx5p8$OXlpa<*JJMqbW`xyJg@a_ zA?bUbPK#kL4u1u=hj-K75>9$V@AB+I@+k3By zSq?c~IC!Yyil-~;ALLixXVO{E9};re>WtZ0cd;#s*CkcAo*JbjPh1kno4jW2UoC2i z?_Rwj$I#wsj*r}Nydw+TZ*cH7>;avva0>49LRt6R;eBn3Ao*4md2w%~=vJL-$?b%Z zAL>ury^%sHD6z~bd-0cp`yZ?FZjc1JMUeI!(&Q)It{T9h)HngL;{AC44Cn! zvS-MH^r>hJqb}!-ahdUdjmPD2cKEra7fayVanC7ALao3;)>j_avis9hT`^|5k#Fbz z2PufaABo9*)4A0s7U@k)+Hm3c;2@Qxq2Mx|k@4?%C#8j*5^C~$gZ&obq(z4KCq~*v zOzCjmoV)s0ZHPX$z5Y)K$nnzu5e!-!G&HWfI5-mCHzrS9>jpeqPc`8(&KuwHG%C3l zU`&El{-3R?-Nbh_P~W$|EEGPUgxl+T0tY`1>e0^54y1YdpG?9z)+EbOfeuhazPIKC zPCU1b-2aYWsbIG1DJm|`&_eABs`cg}f=WtYLkK9MV8F6*8G=-Nx1}nF#yik`6_%<$&1$d?8DjS(&JGLvn8}q(YH~-cU%W ze5D*d>d)>p9w`<$30r=F(-Ks;3d!NH(={2{QtUe9wnNJT?H4dJz=o2uPO_0)oKODc#*j;{r>^vb#v92nYg7gCJ7UpmcYqNH>UpbccZO zU3?xt`qbz5eE$Erfc&YYP$bIzQju7rY01OQ+F02MBi;;AU?ZTA5H!1aZA z1#qx&0K?rOU=RdiZ(|OE+c-G_A3IvGJAq&}Fm@*h*wMnt+{FRx2xqr~f*{s5<}md? z04|))sbr%90N2-dKrkG{?&e_sKn(Fm^B4?;As|KQIN3SqXuyuUeicmUS8Ac} z4gL1U&ECe*PK3@H4u=QyW4g+$sa{_`LAh;7$RNLCg0R*Fwb3rHw`T+R1G{13v=RkY}Y>2LbMY%XQ zx!5>(*f<5WIeCP*c!hWbf9L)q-2)4Ap{E7Vc_rDQafgQmJ ze1wLSZOouxweO!dkei+NuCk4zi<_yQ0G}xz56v%?rVyx;E!Z3m9Z>Ya?{h-vw^97@^dE%p zuYX(2FfcH_ua1ZX@jnFzaR&p#uT=)SUeIO@rlFq%@V)1YT<{a;tb%0eJ>$O`Ty9}|d&}^#3XU8b%S*>e(SFAFq0J^VF_>!@JbfN>Zy_We z140YLtd$m#9~)MDm7zp1x!)r!YvGfch`AUGt){_Xf6~GL9!@r3C4mji9;ru4u&4Qj z;E0ApU;~VWD&6;!UWb-Y)eEL-o`K*3pfx=UHxrE_Xz$f{Ms?V3uF>K|fr_!(l>K6= z*$oV++EdKVZMXWe^{TCQwrOg#fDCSJ2GWRbqXH6F`mFuLeIeg58?DO{td)JXFjRPJ za*dwxP4AjP`Ie8A0nKt1;N$*t_lRe1WE|lVkJN#s4a_93>z;*l#gsk`fSxl{Vjn6k zIGnN^r{(8Gso`7(P;pKNo7^J`wKY3slpdb+*$7iyJk!1?z^-GZyXh4?z(G+W;z-0ygeH)3((g6B82*&+X5VZWV}>FB_5zC|SYem)dDIqJDoTAj zI;tBQuKvwt>=h>I9e?Ic0G~`?w%n~t2YO^Y&172T!7+a8Ftlh=Evq$+ulQL@%6R8> zm?2MS#~}a`=C@7>HTzQG{%hi*wgR!sx#pkgkWn`^>Oww^#gPV*>~GB`6cIBN3D+9g zxRn{a;M42ssSL*xsH@JCr=OtH8c4aQsg1N!Qrmusd|_B%qvd%sWl*Kt`{rm?(u*5S zisneQWs01$yqsTsPTmi8Td`o|k6%Vv=DE7Izm3u4@6Q+3v6(ZOo#V?&uF~lj{#u<& z67$MVtG?&H>)z%EZ=A{OSYSgcXvi%p;L&s=Ie4ES;_JmtnmEJzaLL_LclD+v^qzg{5X&RWH;36Kx zVC3)rq8<0$*2uHt%Y=>Epl!|fS}g0R7PbZfd8_bF|n*<(M z*C#cGCj!NqA}3yB)YIDaa<)d(-YFLnh3gT~XUG}PKgGf5(fphvAxTf*=C_PPwdC6r z=`7?^=61JEDoF^_WvMwD97RDlr1jy1P;u6(M2|gBh%=p8#}(IAN|B0q6#+TEygDs?CE7i zfW$*Zbh8{MN^yllf-)cEZ-;67*bi>HW%4#zy%$VLNZutr)svs{p8zuXWNlJyAM@TT zeX%6I|K6+H)7OF7`kP3oFY$f(Pet{2_V0*O-!$tXY{H+gIWAOJ6ByN9AbPp$M@E^Z znw)VEy$wqxWnQ4cBoS`U-lLmGZHc%t>i?wM%hVOpv7B_`Wri(QsP!;RE<7143x+ei z#^7{I+fPJoDWs;`x$OSy1nIFBxKKKQ2gzk$++*Qc~)Wi<`aLhdzBKV73TaiLideIivd>}$}Sldu|f@1@sxfby6x z>81!xhdtI&=JN!ug?_Y#jko31vWX)nNU~038~GO7IB#|0PS+b4y~DIg1hI$7ip}B5yxS7QWNymS_B-UHa1@PPl8H#D^jq zwI#2Yz10WZIq7~$C0}e!9<9#5UrI8H@GQ9lcin%q(yT;!^8Bph^cnvEUf9RD%XdZN z1zy(k1){gtN?D5f7~O{f^mt-}47ysK$7TE0FGJUPYM?$>9rmIFZ#2da-;(R$t&ARA zob^Mq&ST@o9)`|>>N%;HYXl1#`AsO=i_*S?ua_Y{PenO?tKuLo_mD{-!0Ch0W$5Qb zZO&zz&95kwj}lb17y?A+2t&~y98%@NGNYilUp!7jRs;)3Zt}51g&Rk@sn50^esxk; zLdSUis-{;T4FC{f1OWbdOTtEMN#;(D@M~)vu_J96O-C$M5qJ+i#4tgf01Q1HnN8Sk zM|-u|tIW~W2aqr!v3*uiO&^BLFu%gIpK#S1pDAywJQCwa zyY4sKu8n)KB~A=Wik!1#D2%XrUY-|<6kDp~@*XT`c~l_3Qxv)*z=rv-Z7Khgb4&-@ zCwp&9o)=P#@?R|O-JX9cJR z(a3uh3@d!)LpFxmJC-TKYeJl@gl0YJVm#7VxmL}iNL^e{l{YeDGF7ClW$e1TM46JY z%F?x8n3$4^<3mv624jb2O9P8fmfjM6w(9-_?}!%1Cw*#c((?5{OnE3fEQ9D~mG=^eW(O)A@67rXxO@ zpSSc`sPkDk=Ek~)V*I1Pd43rM(qOIT!U;JqB15g+EK4B}g?IO)swqK@k^dH{hJpA_ z0FueGDuQ)}-lqm##0Jb;t_7?zRrMcYqhy$c-uX_o=IbP}bL8ae9VWT&ee3Vt_F;0a z&R7n0P()fr+45>nn7{*)9atW7qpKH_ksBUk(4S0hFY9;uP^?Bnv~~TFShKp79fqTG z00NDf43Q)}^o^j6O4B#b?w0a5deinn8c?`d-URn~SP~6=2xb4=2!dfg_b61~@2`Gl z8>H>+x0YnN1?YYE1kG;9q}Qx9+8@j_aA#0etcf?Os{CFB8%xByq6z!b+Jq477LhR# z?A}P@N(%b(norn_){>3Qd0jodk7wWN2cKKT9Jz$%Lluu*PENn2+^9JCR!?Lsmg+2S zeQa;rQ=+68HdQH{*C5BOL-VwbwNR>QmQh6^S0^Q%dL>mSQYW5$fAiI(@72N1W4oTa zJ!s2hi`q7DbPTY=MhhGdej!3G`Ql@pVqh{R0hS4a=##<_9MVT768M>4T)z zCuD&rdq&*A;;(5eqm1{Pk~Zt^>=zl*1m^H+#*K~qYtc`~yD;2K(w0c%~77E@#;R*=nT_Ih^7 zqtTBED=%8dNSLR)$CCo~IGIChDrXhgO|^Vp3^x>Kuc>-mIM`f$ykuYVmW>MHXYB>Z zbO2wXokXD>ahpdj)R^f>*g@`+;ZHfV-p01Tu`j0*d_=%)$2jVNftr~f5RxNPTjgb-Z~DiviNUjd(p?{FN-lqjjo1AipE?>sXXMYa#1&e7uvu{gK4mJ>5`Uq z1=ItU)%&=*xY*} z+3K?Ud2gk7RN*Y{`~kDG>}_p{V1Z`oan8=&l-<$U&bfiEc$jPu^<2;}>H|u0RSrQ1 z!J+vc5v{}IK8TMEWfz{>GZ6XfC6=~boKC5fUabYeD6&qMor#9UZW;z_ z*NkOUI}R9w5v&D~mho$_aS(tEL+pIsGZ$ENQFHuyg%ko=Of zR$xJC)E>$9WGC~S6K8uVon_ifT?6*0zi@XfcKghyYP5Y7^dR+KDRzWJKCqOq%Eg4b zMMuTN=1$U-cei4aE%~GkU3Z3tVxw`c%gt<0HRN!VuLUqHTrO5&?Kl28ktpR<0l1r| zk$#L!MwidZ;$Tr9^jgx18M+%yaU(5VGiL~*Y*Z6y zv0$8I2+zGa`4Incf{8cva+)%_3HDB^-KzlWy`V5L{o1~gmxQuUvUZ&73U9aZ??sp* z6RGTPcw4Ua`dSWNtwPVmuI<6q=B$U~m;eC2><@eJ#{q8DR9u}hqUQP{L)e4b)-Dca zjvyO*7!dyBmL1|~^-Nt=4i}383qgXbATO;603ac50p%FTh<~w16;c2ICZU3~gtlAq z)~v5`%n5bV9?DnR=ccyru>=+(kX`R-YoKYO-;kl!*v#C@M>lkXTRleML2XeZ5b>!$i=Id$t4Vu2Ua-xlJR1-7eJw{LGB z__R}XI*Se-)UVDB&WfB+1t#=c;?n4ZG?D^#nUMXgQ2|33fOGX*QKP@QJ1mO>QHxz@n!|oYNg%4{FxbF`qe|EgkW@8Njk|CM-8Luh#qfq z3?vRZVl7v|+gH3yb2iVq?)8pe9Jpl^S$j)gSwGJ;t)$)P=uTR>k`dE?IqlrgV6|}k zfxfp$*Hn?s-Aw6yMIo=Fl&aCY#(3|KFZO2hhS|JZovSHt^-&!3N7ghLC%CP)OrDT_ z+kN;IcQkw3I#qAx)TegMM6Y@KaQp3aN_f4(+H5KXVJWmnk$ZYhcse$Q+NHdM?4`-2 zaB}vsv3u0F{hm(_V>|t=O1QKvH7ACF zcD*MJJj>^!6~mjF)BB7&=kJet&o=i`-`emjj}^b_Y*3pswyBkjz>CwSaY5&p(eb=E zI(riY><0bm zD9t!{hDxJnF#F7WuNd{9m3GH{q zAIo8>%rS1{CRM~g>8Q~iRzGO(c7`Ht_6~o&Xsp^HC zgT46V9$NBjxLj1VCwl_oG?+_fRNpQw9vU|i-s2)!CDgDu3uS%wiEwYyb|3BOYh*!p z2mT|uI@H7ZL`T?ISU(jC2A07Gb;Ie2;Tey&Z(;CeWSE^jshV=<6NgyI{Ql1A-e9*ylP~t8 zUK8nTERVtCiJEvj(IZn6M#u>s8)V0#d|y${8`hZ$nJTDxb!)ygvL;nYKJzB+{|x7G z6hXd8J}+`S&L2Kmd~x^kORDI2@o)#b31qnxJr=l9;X9IkpIzZ~#r$yWGqs|%#iE)M z_Ty}_mZ^p>HIz{rNq1n``OEvh=wtToWew|!pZ60ki_$hjafe>k6rARIf@f}rdM_}1Niyerux#8Oy`#TK%B2@*C59YtwTVy~53dSI1w=-c=8D?NPNxW3yF`*-pRmI6oX4 zJ}P#kx>{Vc;vJA%C3Qq!IBn+SnS1o^VmMy8{+-)qe#6M}+G!j`oP-4T&CZg?y84%e zb9_D$`_1!xBQU>N#!@H{aA))DUZOZfm}Xd7)cez@8oZ}~y1sD0%H@uZe=2L=v@o`djdwE$=C-@riXM1-3VdZC>aA&inVnR}Yjk0sa$wg2 z-loPTk`GqP3tJltP9;-OiW9ZY+X&H{;ZI6(sDT%H4y}k(7mo5Wwnm*D6xw{v-J-_4 zaWd#)Au@NFYM7{0>%^4h$}e#K0N=9x9I%cbr}s{D$b-@RqSPRX>fAiH2->)O=vhtp zu-seR>Y|cv(${}RITgL7zzDbLBv=hubio!dV@L494GZ-T+d}`AYk){u?3gsvJ7%Ur5`gkkRMacegmHDb3?KE#?yb~SI%XjfT9*)?2 zbsx}o()Dak!XrnJ9M0$uFp09N&>W74x_QdP;_PPVq!S z?d!Rj;NK+m;6}hd?}z`mQU3pmzt|4{n@Y;AP*zAe_BMoGY+oBo3NotFMUsyK{uuGT zuK7{!Aa10b94&3Eeh;d_xPXYDrxh3ml(d06fFLm7KQmMO4Ku_E;sQa$oL&A$KDd*U zJp|+kw*MdbuES_9Ff$PJzwlB0ot#i7D?}{&|G{}}p#E7s*OLDC_Wq9RS|$HGm!-WE zBIf#|Z+{o%WBMBjLFVR&!2kCkCeYjk3jO`K6$NoJi+-Kr0Jt`xuggE5)Lxt2Ft|G+ zT>3q9Xy_0*&3Eh4r?EwS=v;QAea>R5*U{OvIqgP?jOX-BS}K-7IxAz$J@pZf6fx&J zJ6A{X@Kd_P5{BYrH`ieYKf0AZb#A=Xr`(!zUaqO7-P8oc%k8nGswhs9p$SZ7dZz9> zzF$de4jXDOdnsSP~vAZdd5->&P?)yXt3e#_2kRE|6G+mTGAw#8^>j`A4L@Y z;p4K&x?Cc0{iL3A|E8i66xfM%e=dU6B;2>e@^KcSKfn1?V&J3o&}^@QUGH}F9*w?( zTS_(A?IIcNo%ey!B}QkLmZgb~mRjs%K2>_GUMdd65rz#VB+4*`_iAJsc=;C)iZfg% z)w{RzQ$M-ru&jH@v{_rfYeUaAz|us*PRPH2&d3%icQ$U1Wz=stiU45AAkL{l9@w~! zWw+bIM1~^!2rwU{A^s8<|LDqbZtFtvvw3Qko3MI&KwL&Y&rH#S)jAy=%!Ehd>#`CY zC;d*rp0F5i`kcEhpvcIQ&V+WhPY-rba8D)g2;f(1vCmJXXz@+iE>J^m8GRV~aDNWv zAu-m41UAr1LXq79TV6f@8e`wECp5ZH zMbCOnC6PTAEX@=B$}iakF$O-uFB-NZZEmvsHey76JWE4YTjtb>l`2 zN-4e2NNMH6dE&!|bMsFZcE!7Bm7aEqoqmfYRSr-fQnvKh55D^%_+5}>d7Ml$(_rPf zj^=J8DnnJzjLJMWGei-4-;n6ym?Y%x9*#(wPWLX!)}D%xazzE!tzOyZy)3A$GpQjj z%?eADIdIuq1YE5(;&~~|vSQnw*4*IPcog5gj;VkcebD%& zY?dDiaa0R6{coni{{89%%&Vt z%FkD!N+#d7sGmv};-=2rlF%xh;%vrv!^`Z4v|qd+$Sy?15X&jhMolsjXnjx+>VvGE z?#_Hf(b`_qVW&s;)Fi~+SRSdTu5rurt_80VPf`QJon7DcZZ`Hj^jQ15`3?*UJ~?($ z^ER81ds&od88t4*`QB3JF}y@}vQnq3k=}W^0nJ_CtP+QNZc>auabAs-98!#Ga@RQN zDxEFLIjz1<$#J~+i0d33r>!ghPQGp!WxhM~9i9~rr{D-<53UNFLX){mze4q@AN=NW zV$%Z3`vq&fL>EF)KAA5SNvk)yH7ac#j70Y}q$>RwGdt$}Sis|~Q6AN9J1B^mrG(Rh zBF0%lta%ZH2;LSo7mJR>X0GYVsXikdO{bM7SB&MTQST85B#zgd^*ghEo~cRsP7NQP zB1i-SkgFcDg)=_GGPEL)&@Tv)J~8I0X>$NN@5B_%e;If#K_DUL)de<(_?rij7ut4& zB$K5ZjPoj8@!ZX1|NL-n=jzII12VuEF=&&ROcJt4tUguhvrJODjz-bZHsq$+m z_fAZoeaZ60Cqrs*C#wij@E2^z2N}Xb3?9r(q{U@g9$`w!w7mn;;13tiF^n7J1K9_H z)Ok`G%JON^Hc9 zIwilUG;Lb{{u32akRe9x1RQ@>XE+N!K84oKzOg1R``n8Rb$(qZoNDxduvI8z4P%B% z!bIt)sX`4VZ$OZUX;RE>(P?!9C>yTc0Y6CPl)waTp|%(B3O%DLrB+nQu!Otd{(a(efVyM1d5VK7#e_{xcx#7%wWGoG)VKEP{kIP$TMCfVgqv zAXgNPGN2X$50b~ji9B6LdA1y+C_ijjHYY4)`?gB2toZFv^XCPnPUYcUvqv9^zFc`Q zDr`~u({tyHcUq}4ZlcMlb4L@X$qZ+Pb_NcwqzfBpY<-O6;yuIZrQOM&oL)+}eBqQJ z_$DG|C@){n1G$lZ@m$8B$gRX%RVC82+@99^2Iiqf{>TDvmIWl}8+;7cxVz7@XglH5 zg1eu0V}o};(9`M!;h1*FwMb-X1vYBRy&hD9T7WfAsrYak4l!oNxz%*pJLFz6H97aaYjh#mA^Ib2+W3vw3Lv$otcK~$-IIpgQnAra zgZ0ubGTuP6RbB}kr!@bKwPoUv z*_mycsewM*jT_cgZ)yi$kqamjFMZsqqB0NiK4fIZgJymENR^9gU_H~0B4)IBx@53R zG1HVh5gH~<+=+fJ;k!G+O4}Jb^16D~TL4owmw`8S?%QKAcOKo!JF>SwxSmBUa`yZ3 z_E9{^#~O%$OlZH^&tKU;+2VMkXHMLaqUB*H8atKsJmuAP^2ApoLc!pT9r3x=k2_cV zQC;| zZTlByWAd(nJ~q5L2goL)V&Wic@%lF2)f{%*$OQNF<87Y2elJJ`93Zg@>2@oa;Py4U z@#Z+ZxyWoMyK?_2^~P*7GY{L{sPQ*s8ysx!%mmX9SrYGR2+Bv59U{Hk6A~7WGCf!> zD0?G};;Fk6`pU$PHOAbV%5m~0MTQ~;vbOTmN8!3Wx?$XWUKLF{vF@ZgU&2)z*JdN8 z?H$O8j))1B3-%=-w4BGM3H?aSqO*<)Nq*K;T2sk-o|$WlV+R!3Lik9voo(5owRqYc zj1uE7)FwByZ$~$J*sH`Z)nVHJW5ynV0!6V>%r8vk=1=Z}ll9#AjOMW~`-dwIvYT7D zzCAhJliN_cHtfi9xVMQAXQXo|*J?#VCIb9(*6g+M_p|)Sq5U)0pHpLha%doKuhY-2 zjl&;YKdjSVQvt4X(0-QNH~yHB_Givt4~?%=1%8(Ih{s$UV} enPvWml~rBo1|o$A5wt=4_z>yvJl9F~fd2#h9iprN diff --git a/Documentation/position_estimator_app.pdf b/Documentation/position_estimator_app.pdf deleted file mode 100644 index bc07209ee1fa6470ea84f4f8972b0bf2864cea93..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 14243 zcmaib1yr2NvTjJQV1W=Mcp$jU4DRm1g1Zmy3~m8}y9D>(?(Xgc2=4B#fdFsF+2@|U z?|E;%f32SBuCA```bz#av#QDEghlB=49rO6UD;jDUA0~5NQ@*v5^H@kByMhi6xhlb zVnV_MrN{$BO)Vf`JAkN#9t125Hn27X^YS9uL+rqMmPpPiEvlbF7Ddrp4^(z7W+hbG z@Zr6W4q@Hxn1}-yUw7j?J^U=nIUWxc{p6#TFhx1_NondTlB50B^46I7J4Zc6 zMuHGgRe%sd+au`rxzTU8FHw)Jj~uw}x_v|Kihdm~iu{Yl-vpnw)^xgd*!o4i_@2J1 zudcS(Z?JU}%WcPZG=7EunEtsNY?IGM#TgMSr57bRN0xb*9XTP})z>%Z$XKJS>A##i zXo#kp(LLpLIoA~5(fgHGnl(dK$CKELJ(FwX_Wak(cW-K3J!emWoE8Pp*GRhgcXp!mw{{J~h%G%-@7oV#nV8g7i2H};2!3sa z0+b=-&J+!497>y`IAT`2vcLX=(UO2i!+(jkCp_6og%i;n6<-)Bz18D z2bXUN4Wum@y6zdT2N93>Tkk9T|LbiLt z#wBdqtgIO6@P7B>4U2LG9O_I1R>hXywu%VqET@USjC2wF(UlE@fnE7I@Rqt#XJE|T znSkr^t1G&@6t!M7Xaa`3Pc;yAky!colw>L%~^Mqq^E^U>t zg%M)RA+b)zooG~AwE73SwZYdF)$mZerFf*lg}%}?czv)xla`y)e{`-EX^|Epm8<=o zI!k<`ES6`&{qTpVnZy4W+9M5lZfRINP&0DgY78xQxX6h({6$N{00Toa%G_4&gmK1R zDPDwvfI_N9t34&Si;YI`TaAgYgr$5ytx1_s%vHdHWftJBZ1nTc{1=!Zu*-LYgeZ!o?DEL+(e9&R+k)c^hJxYr-S05m7@!m?&NrU#yN3>(t_EOsx zqB832EvyHeIwCIr*cpdNrhF-unu*qS38s>*6m{*A?TJY9#JESb&qEH!hTInYN=hL_ z%$xJH8HI4`RWAsfsJhKkti3!mDc4zKgy+@H-QyVlS|$WOVf^_9BUda z_ET}bY1D%kqxOyge@GY!kcBBn~;vb$Rg}90mWy+nyo!G;l zrX?z*VrX&>!HP?QPO@6TV4_`y;9ZZcjTaJo<6&jESKgyWy|y|rn0V5rr3O_)d9C0g z(RT7WIA&mS^I)XdY;B|?l5iQDy?T3jNtNA2<9!u{1k<-6 zEndlV?%qVQVmZboKkG^qQ=wJ%c9oOgDSGlHA9!pI9EpZ(5PQ#PGQyM~DS6*jTzfvG zO~|HN&4Ssoy|Dj1c-a1kKYib6>PWii{Vrel)5}Jtc6=nTmEm7W7212w!${BR_qhXN zVqt!s{zGK>uPn{_|H#sRWpNM*h=m!*{P&!_EtzNAWY;OUy9Khf(ds5*N!&Cl9U&2Pt#VCv|QvagL|2V=a~E zV^SzaxVY8=XF!^V$#0FXk!*z_!3sV^-F zk9f+j0xZ9pluO+CJ*JHwvosWH3NGTHfBqQ}xYpnntJ*q69?C?9fodVI$D{xId7? z6?>Z08|RyB$kLQIWB1*#uD^Ji#R|*t`9|G`jFclum=hEpG_`+edj|iV`onliY>K`_ zO>iyq`O^(~^M_`Enp1mnI?`*S^MF z7JtoIkrE5A4XSYjT^faHHNPkc8$slgGqA=GiU&LUps8a)j%DF;Ys;BOOHJ?|{F~XvWnf z=4RU}?B%$S{zMh%Wze}T`*L6znxElbdtL6*#!GQMPc6O! zA67EsB1^v$OOkcoDYJcD$7f>>F!7f?JP}5DEUI1zjbuh3X_X#yZn}(@{gupXq1!@8C_SiwC~SFm!to zcxuY@qA_0C>IV_d0eNe#=fnHkv>t-``8C&(exO9Na~T7EitlME5-IHI#q))}?h3VQ zD}~=gG79_C0|CGjSwjD+E0EDJ zRczbr2sP&**3XQTwOE@92=;d$-8}e)Ul=nKBJw0Xb%i{&{&jG<+{g!1Cx-i$z{MjF zh#41rHE_Ofd@y%>&@B>5tFAqUnMWQ}vgKK8L3wz!gn7*}vc<^a8rc+mV(8Hm1#hCN zQPb@=TD)IPh{l{2x7waGy&VrpkSA1KaQA;%a-46*ks9tW0tmvTHKYTp`WwPUVd3UY zsmcvp4ge&+h7Qy;hei%*;e6?5pL&TVJ_Co>yN7M_&ek25a)8}&jgI{Kd-%B5Oz@J0 zXY0fS-}rc^MM{Dk+3g!a-7@~8Sz4J_O2PqIhdfFj!dimYXy3OohN=LY-_pO5D(`mK z`C2;t7~f4!rz$V+TW6K|nn{;@fCsf(%Tsiqh+!vP8S&&>`WltbCUf79mqO{EX?~`E zONa5l*|oewNnTbK>S=&DLrQf_?hcq(ekU`oc-SAfAh-D#M$6l&PN2Svz@CKZ%lAE& z<%^b?1PqUfpAAxZwbb-T9(<#hY)t3s{2abUiy^z8y`dJV#9PZOazMtJ${_2c)K>(_ zw9BUp$UHBwGougqWtYH^PMt?x%AYivJw;Iz{L&{#QG2wkxEsH^=4ckgeYia9$ic@a zaigs5)LN+8vREXwkQ$=n$ zdg*#r?(~-?%qb^wZ0AM0ErE5M@{J-I&ve{_r2bs4#vohS;7IYxzWFZAr)<+E0FkNL zajw30BDhpU&hXa|ff>V+LXx7~2`fC2tG)HjhDOLFr_3^+okdI)(>#Xm#8@89?mkQ&t5v;-r zVVr8xEP|C^kURMc-Wo$Bk>@Wfnj!6b>2W9pj!!ud;EbA51|w`1qyQ#-L~9FdQ>SHR zf2^8N5oU>uvuh)7XPP;B?Wb@#u(acZ-4;DnUX$x+0}eOu;TJjjA&DTJ zdcU-oZieG59L+Ns zvC#vg8>CdFZ9MEVg+funkRd~1{-ZhJnAUcDwa|9G(RMJ{_{XWJe^*U6u$WF|Z$t9O zDmPKxvEAbY_d28($2Ih>zmi4@j+NTab?jEn;BzvcrHiDLtJL;HY<`u`?O~OdWyx%_ z-D?0rc5{bX>JZ<+p*hdI3hBHG(g2A@_M-B=5tpU(Qi^19J<+A`m6?NGs$orgEF7Jh z!TapdLIe-(X~=XB9YaU~Igzwv&RcO3G9mO=6shQes2cCWFDqNSQAY_))GKLcqaYkB zVZBqL3ADP{iq&)<;;QmKdkDaR8QNc}tzmtK^==RQF!4bl3M_s61ov6Od!pk^wHJ>jWHGbxA9 zEWQ&3kV3Qu_Ao^9!4P?M`wUd_o^Ng6-&%9JpziTFH8_1FjUJeDj7g~vMWS)0F!5oe zqwJ>q^oo}A+H9;~=pN1Kn1d-Hy|uZ)x*pQy>mfh|6^ zYUObh+sW*8YEu&T>t6>>Q{A;z*OxpD*6)HG9%&p98T3h;a<1kofaqL!Ttq|QzIOg$ zlVN8Rr$_{C#lG9RbDcHfo%AgiI+1$>X*a2#?+6XnA-pwa@-IktVLwO0YEy@j`zT`s zmWKLJ)v)re(=A(E0L8|*)BEf>KBPDBu3Nl)N8g^$H`nkGg8YlMcg66N_F%@1o zY%*g##W!7JEuY1tJJZC(sVgQWwEfUoz8@F68D%XgR;2E%uqA+degBI5eUv_XP6WDk z-_BV|u<`abkmAloJ10%0D-@5R;6rwr@}z+ou6#s6ffA}Ps>&7;3)xH__*SI==FBIK zjiH!b)24oYHY*xXn{VUbG8?Ub5H#s_xnVr!k28XzbGK)%_n@D$`bcO=?Q7u{l&$wu zO2zE=dtPe(RoukB4&yKk7x1v**`!*=hz}?<&jMH9{Utow3Irt*S4&EJSZa6*R{+aE z8Me65*%Bp$;+NeeiWnwkNM;n4@Azb{j!jegnZ<35d$Z;j6`@YX5!ioK+fXrh04o>Ut};e79-BxDx9}p|yIOuXG;( z5;uoVoko<3;NsB?!7NY(b(BW@i-UE6K&D=n9$P0-S>egJU2l`dMBkBj`%LPLCYf-K zeFUMIZ<8by?<|!EjL6)IW0cJtB7%<5ZW5B2tk^}g$rV3l^blDdsZ5g4ON*P01(QD8pe-RbMzYpc&I5VL_m)k%?A~(n&27)#nKe1~;B;fD#Smm~lY(v;IvThwUX;xeAwg&6EigBj5|X{H z80=WoVW|o>VLJpNs&{GlyS&O{7B_2I(Ut41E8+kXP!Ps<^)?D!v;MNA(`O?4u%Wy0Rk)W6fqjn4D%@^xov9b_q zsoe)6OFy*$cWa@m*#3dsl*CM8M{TqnX1mR(8c554up&jSG5x2l&DDWvl~Os}*Wxo8 z@`8o!Phv+uo5Z$x6YqBpq%3guH(L_| z8$=t~Q49J$p`Jz@=IuEazd zeizXlVbkdQjDKd-66}-A5Wc=tL-PW^-jyU-Cf|e=jz&}1Q?VtEVc6GyB^Y2NF4V{T zWx2C@m%j52GmI|lm!Q6I5oA>PFFH3=M}trDrIe_MX}Ze7iLLzCn%gM7Fx#^mS$A7-WSsg z_^H^YtI7v=qFU4E%{kxD%$t`#FEp*6jyJu*BOrG?qDL)_rVEiVsBJ1r>hio5z&5Z+ zv!v_ImqVrNH39YtcUA2EGQqPXCc8Gh7r75jO|SKxMl*0M2XrUI3a>!e`9@eF$U>en2bX|GK$8nWMs}7G|(~Q0jTB#89Ojnc*mVjCJ&z6 zB=_zreQK~0gHOb;ZU~nid&daD^FL>+_oZY#tVr|9e=gTfwpv-oY!DY(S<_pval07~ z-3}@a#w%IVNlzOoxm`}geH)FJ9ovG(bFmW7k<^}6RV=TSYHqVrC@=Rz@bEPEut%u+ z_PSZAzhNRnvAyDGzsHa8K&i8+Kh#DkBOVs<_2f$)iuOn#gwaw=Qj7Zo>jD?LsjhG(Ipv2KraP9cjF6Aha_3xT5VPtq7F$&kxp48j?CzhZveoXuVYn}0s4-$p}A2<#(jmmE1EKF&Rur${M8--GJ zRpS=(s-1|ZqMay)~IXj~GRI~Tx`$c;iNo2Sa}M`x=SqIv}N zFkSh2i|t`l$4Wnl;M_&nKmHhbxfm3jL!Rx2f^J3WL@X9k@1P0jt2tlY$&`5QAQ_lP zfE)NZDw9gl1_`dY>{eAE1~x#B#>Nchk;iXx@Vv}f*?H`n1VM@<<9(oXVy?7`w9f)8{{rgSS(84A=&JME zzDf~Uji3cgUTfPr7aLF&Ss)=wAnjQr4@%_P+uu0L!J1xk?D)nA5qNeD#i}v`bGHN5 zqstE^GbUSH)h5?2sXf_nc*(lsX*uf7?xh;D_cJ`)BidRm!svG9%En{#s5@OqT%`w$ zcQ*ixzTd;h^_DnurW4#RO~DBbeVcd7wqEPGJByJUR<;pM9Dev|cIoy{-|s!x_>TRx ztW0cuJ1y<*7gHv}IL^&M8G)dlcRkI-7oedizN=2zmJ{cv-7W3wP6KWBT|bzU{CKNV z!4{m9Wk$e5H!`vF8X*9>W0@w|%a71M@SRO7aeit$KfF50)8_m#x&u1-w4Ck=SFCLt zMmqe}K?H}ZaR_-<$k)l&DI~tm)!SIheKjYqxy+S%`s8d`uH>w9X6HS=DG`GU%v_4T zMY!u85o-dycHwD--cD$ooW(V@OPuSmS!Z7EFeBE@VNTNM8|;u#h;6xx#e%2x$H=Dc!cH)|4tgS08C z4v1|I?U!v?v<1Mb#gtoU)^kncOsDF0qqHmxk$n%*&LCW-KCwNij_+H(XkNX38MWS$ zAxVp3ctEN_;N%=ZW^FgiOX=SFlY!XwtJY9w&}8^2%WuEg12d~qtF}znjjP_)S!RM? zi}*Md=O09Z+#}EH*wk`i$8cc9!dHpR)CMevjsThqj^x;E5XmM=h5GJu{<`YBYmLb< zIysLyQH#kq^Mwjvs{PTDxe;+YOYikN``tcf!=4aH&HRtS97iZpNLg9>unx5LH*eQs zg+pPK?uj7#K1tRHGE1Y2!ne5aH%OM}-gJ$Kl#Q?Il3i?)$FYC$i~xQe>M=Z3rQ1g! zx)G<-KHa69*>2CUwTm}< z@*j@v#p18AZc>kqxa_Tkx>~D}-DFOhuH3H&2_H3liz@AvQDUw%7M*;C7rX&51~p*4(1IvB`69W89o#H1mg6nJ~y>f6k4omd&Sn< zM%YEPL-%QrF?0=x=yxqRTg0l0(iBf;>3Or)d4;O9e(o`}g1QqbySmJSVA(B&Ca$ek zLBIGyOk?*&P7P;%*h_<=k3Def;eEC)whFc?8}$SA2DW+Y_4S(|>i5~3dz&ExOatzW z_)47cW=aP%nOeB->Lu0^_*amKUrW5qd$*3IDaAEPv%k{CC=vIDeM^fFNZv8;(hNj1s>e7}q~1$+ z&W~F31Rzl$n@LU`nbjqTahAzbNy9Sw>2oN+zqdRZ;S;&sn|BbD;F5?O&0;iTTGn1e ziO(-9j2ANJ&?s`2N||lv2?9ntE)`BjZ)UhM+F=sWZo6U1IF_A$V4|_FfBB5?j>A1% z8^PGIJ)O`dTnn4|o-h>6y1*OjY^5Uw>J zG6q}+fimRj#*F?g`_EO#kB2@tTBl?YF)S}F&be@YZ@iqbZdffJcAkY>3dKXxWMN3E<-ecp zW4Lvj0cc$oBd6JQ@ZucmlN~ya(}*HbsN{y6Gu(z9kl{SkAZy#h44#)u%^l2dWg$;w zGpVm8N=+jR|>73_5KM zA#zN$`5ddqkDcK^h25~5l_2{8fs-KwkoLQbpu+{XydIUj@ECdyXf#({9{rUb}howgDthH5Fcm)&V1 z^u9?JD7E5ct$ac=Y+U@LnOIa(RdnE0u*(Np0d#wNNH2KEYZu z_Mwe7RGJ&=0@((cxuVTVrS^hdE4Wi6Us5ewL0jcB z^PZD;k~x9{rWq)#FL2=Gry2RgU44m}hu<5nOdq9Bx2vHN%(UyFhMJP(d!wNiPkqVu zekmQ6t5GG}HPo&DVAhro;|m`MPt(Oh$;@3Q5kFvfbI=|G7!wM<&aJ5+VPvky%bYYNQXD+uz+MUD1T1x3F1a_Dpk~x>aE9AK>~Xy=s@t^{s6ap!j%%l} zV+cTteihW&J|{-Z^6iQ>xJKfR+;)yAWLstN*Vul;#m%zX^yI1{RWCx7B<XB!z1jMu-SAsj$#6BvkJi5n^#B%?;*@>LB?wLHgv zS2#1Lx~~?A3>PI%Lp;?XC?2-Sq^b89^dsFCJLmlvH5Orw!@@oj zll9zs(SBs{*iD@e%v;mX2f0*v3z`1bUU=zS0H?z5jOR!(x+c5MI@(q%3QpxJ8x1Wh zXkH5K%Y0&x^YUyWRnErP@cE9xLz2($w^q_!KYp90tou0W+Ul2gzlI3^^Pr6iU4V|j z9`TI#ZC=Pw*P^dVj~`NIB|2|jZs->g9I>o0A1?kUwpJ?LyylFmij&vaGRO&O@9MRA z==MT3cyDT5t(@bXw^|!3j2fSN-QyW5d-VRx6B$484ok`AP#spBl_6=th%4-AI{K z8)wCklcN<A2c$i6D9>%VzByuqich-J}$b8bpy+gF>RKD3UCfXPFS{T zcGTF_dR+qBBp#SsEDKeFJwR4Yb#)8z5~yHlp~u#;td)IkPIfy+oE^Wsv2vG&O?A9o z+QK7ss~X8 zN_Aj{ojT@|+0WI5dp(NoG?wdZz&y^-Ok#MVx@Ay5giKv0c8zZ%R7iM+g&gxeU;^MK z7Wf%*)wvxT?tZ;EV*NVLbr%r$JC$pf&-r9U5PUR$-iB^|i+?cVb#K1X>C}E`j^;<$ z0(bu+nZdnXDzH-DioBrpTH-=lhiqXlAlsk#!~L$)0E~O7FY(wDLHdD<;Pm8MeLvzD zTRLL7*hpSILKi$Q%Rox;HUv}2@?!zf2nc3iNUy85cQY=19GkAzi#-4$AB8L;Us`$( z>!%6}J&y{{Im{uz#sx1yM96Pgsq*x@U5?Qnp8l4;l};}z*mn}QGv0{RvpFm=8$i1 zAOl7)YhkF81T8Kj7L!mf8ephOJPx-7|IrRMoTBdadkl8} z@~S8x!KZ2JYsEKcVQ6nIuMm1-^gXqg8EqY8>vm628oTd~v>MjWOEg3pT!jga-|xL& zo|;UhT~^moYI6NGf2Ty-EDis&1^y-nYw?0~uUq>spc-0B^rI|d|0s11>B zFt_XBH!e4JlRI2orZ3g9s4uK@$|w>Ob-Y4B;EHkv&PIG+Y_@mS&34NOxnhlOV!z$* zSj+6_5A@+_a_z=S?a&?TU%h_RwaNc^)cSC}V9!O?ttFnkz*0Z*0CwmY&rCZ`i}G$g zqH?tIvRRnUjUu9uEhh#y%d9U85d7}fwLZNbT_d7+>K~O(c5C#}w?Q{`>n@?{bF`SB zV_Tf83X^D5AUZpGc%}8QzPl<@QB_oAOcjWyx9JsPe;kkMc%V<_lD%6DKY;$8yvy** zWt69;GbsaI)MgC#Zw>z+W)nhXst1DkX%>`PA8|6b3~3*se`*s&ed4)2?AT#w zp#R>CrJ31qi=s~N+K~Co01H{jZ4NtWZUw;XYK!3M zq#AwNDSeon>HbcAh)-;u^w=3->uW#Zt=wig&?6~DNH^qx5OC~)d(DCdKGaAuFR zRs54()VAoT7Dj6WV>K%EQ`M1AJ*mGT&vif3VnFrU+~_wKE1@E@XiIlJ&jg0fi`yRi zMOwbZZLv*k0Ro9UZWZJUJ|E7-uSthdSAFbgqPL7mB~ia-iS}wR`?}SuTr?6UQ)l*W z9bLG!oN+$K2^1SxHX0HMRT?#wZ9IB$ZZAGn8`XIV$j(55F&I*Gz)@tI$fc8Jdnfz@ ztuJCv`o6>yece-IXF)c^&QkV3TF*O;=dZmY)2Y2``$aHa#G6<1FqlTG=mwtpc1;_j zBBO=D-1ekZcvaVSrdHDiv&Y68bG2gRK3!+TFrt~bmi=Bf%DOk+I)p`54!1# zZ#ycf#N2H=zbh{CMri{^3HUHMyG+O0e}|WaAq<=p)rcKZ3OY`14(f-Y#TN3}PT=Z*wUDG80Mx^KVdz*01lkOZtv| zJ#H9k;KgW4$f!D2uk8*Tbuw9AzfB%a>!!#FFqh95CRCjXZ(DHxRD!SmFs>D0(h=;s^XzdBTspX4(kF2Q(?t@dOL4;O5zSGCqr960SDBJB>2Yvem!jn`>`Tor1(W78 z?5U_Yu@^=7f`je;=md!1Vm+sV3YKhkbW-UO{3O{|+_QEouiiw`d=jGalD5z9nwUV} z7v5;WQti}_BtHaiE|E4?+a||XcPuK3@t~O10(DxMzLsR)G8vj57$7T{YOMH zGTbwtKw|GO#E4MfC893!?=beR!>Ct`%Yi7T*eF#*?*;BKEcl}P->yHsUKuO(_`g&> zK9@B9seA-7vHz#^k?lXFkBTlfV1TH#6+{?pZ(wI?1F?n{s6&S`dX`{-puqD(D`lz= zw$p={T3adTS=l2!7qA=KlQ2U&P)0#PYiA95Mj#UjJrnc;1Z3tQ;Q#@(01^;A3sVCD zD`N{V2@nY&U~d4nf{<_kS&#tFdp!^689^Wt5nQyvLgdHL_+P4@q2@b40PHkSWSfxTArh?Or8<;w}TNcd8w&(}6(L2*L* zw*e0(7H{~2_98|3y@{Ofdsr8;3Hfyh7TiBxhwN)6dYbT;GaJ=mT(+<{ccx`Oh zhW)8taezPmyeUJw=78oy?b1e~?UYuYSCQ_cV6Eqb$za!Kbik?EAm?B*%Yj_dnhT zP;k(PJiDTzodfs}RZ!0!{Okb#PbW0Bvxf+o=-E9xmz3ULeI}?^s+bx=Ozbt7SXoF| zSXfDzn3(>2GcrQ`2s&l~0!bLz*hv08W`p)wSy}(IXZjz0AQ0&fFO>h8@0s?@!~WOz z|Hy>$vq9&d+rQ=hweHXQXL-+Kt$#W5e`1W}IRxdA0E*U1R;JH4K}eoG`X4S10{#al zQ4q;9YX6)E{cRo!6g2eyumI%jtPK>v5DftIW(q(N>b7+5VqQ4ed2Z{_OcY{7cop1M$B%5z>QZP-|o8p^Txn_+uL+fUFJJO2FVb7ys-0 zB!FiHtQ;&X{`CQb%9eG2SeRNp+wTw9|3K|;Rqp~05EE;=f5Y_*5j(U&p<@+>HV_cV z28Hk$GG;bt9||8UbnpjKXrGM{3ZoG8>Js#Y@s|i@s0g-amgl8x&}pb68afz&|7ZT+ z)`0T-;e(1{e%_Atul8)IXRH0&QqS9qKrP1d@2#L(3q$WtQ3-Q00zr(>^RR$enOT_G zXn~BBKp-Xc-_Ufn0~;YhEx?KdRp76Ogq4MbiG{?7D3k}}s zcRPCq{&?c3C?*J1I)u9g{sLnlB_<5@@c7@i=DcX|&PzLS4M!*_gpSAmpTtrl;D9$@ zI7!HeyqJT*LZGKrB^gzMf_e)jA^c9+ZDx1gQ~*T+=f&Z)OqM?x)nvOQ65@A*_J!|o zzj<*~J3ietqm-wa+N%Hb$o$egKiwJ7j6p*oqTGO}Ss`(LhbSy5h=_)K`@ol>!BjbH z!*;TZFf32gj|{H)c>IE40r&ss_`rhy_p7g6Pyc%LHtfaUZ)G3-{o;SmGUxgGt$#R6 zeD%rSAO81Q0@!c<{_G#l8g={ovwt}2U$+JI-)H^rZT-Vp|8VpFI_v+@n->_dM}i)# zG8@TsKUqf-UyvcW)_1kX^$x|mXMq*CL)3)ND(Z^@+W=* zj-zfmI`g5S@WNSDOXf`heFFn)b{v*drOx*D@BTgq#q07g!?-`rp&mB_g!@VXRYXA< z(idwvSsY~c=W9NQl6=)JB~p1uA&De8_xF(gKN_+BO^SaX?j?*a|1w*hyn}*ak?FTP z6B*4JK@}C40ZdJnf1VJeU>~Axn1YyKtt$&v8;nL7wAza~=@`q+wC@g_MY|iB#z)xA z|9dXcdVAvMyX4tvPOceljyF2^$n?YmTCFasHp#UEnB!TF)MCjd#JBBCC-<_#0_i5i z!#VkLOrC!JJ-oz$Hl7y_sg}tjKh@%E84l`rHIr)HC4MgsS~R9gsNAkX`p})PQ)Ngs zY|mw!&CM*;7AI$FCVs_Ep++$6+Fvz@aU7jx&KVeU-KoDz!Z!Ex-KUh8t!D9hu@x8R?>*zji<-% z=n3E5;ZghSi@*+gyp}ax(KPR%muVc!W+gdOZEbpKM={n|JC3|6S2s%9c(U8`C!%~) zX{nehT9;?0j%lN+F}v$`4tlO7@mO?n|1)lqP&ZdY%VN3S0oD0GNd47v+P|od53cGb zqKZ6=E1lojR`ee&($|W-!c5M%{pdJSoBf(*rlE>yDku0CZJGqD{w?J01%2z6Xw_W? z`lW-k*m|quk~`NhZE~lQA#!2)%BckOt&Q;Jfxc$?TEBz%9o{-~PJ~YOgIZb^qk`y< z!7voThXakL-&wOy?xmHh6i?@$L6tP2=LQTN7-=-Co+Pr5Rp$&3G=^F4obttWpl9d? zF-=eK2A?&Gcsr(OKtcTwfrav6G1t_7Ma{z8<0CwTmb7KUD`gBzSoK37kjx)3cwNyS z^;m3GWU->h33nZTX1&#?d*z;wp2S(Zi(Z|nJV(Mq+d){L>#w^vIr}aN@K5*PFFFeVVG4vK3;}EQL z@Tevu@I2Kfq~SR}nw)I&x{10b^wcvdP$*j_Fxgs6nVt$}$> z<(B<&Z9#eEdOqrx>Mj{bLCuj#1i--Kf;65PiqptRMlkKnt04M?WP8zCt$wKV%*odX zj)ituS~4EleI~ic)K=JJ-7|EMu~aqu?(ozv0nvTCy?uj^$)92Q-cKht?TbF_a^hqS z8-}7ooP3weHS3o*Gd`@kl3%n>jk>dscJOm6ug*!g#D75417d{g8uk!@A=ZRbhg_0lexGcB9bT@{G9ptZ6KAb{Aii%6ij(p<^njS+K1EHN| zOz~}cUz>P{r*!WzVYt{F$Ubbni|9^9nlLD0LgKMpuLpv>T2>P*IdLoZt3gCzQ?vm~OjSXz(S{ZN8 zn}B9EIG(3*RgCwMVh(>K`zHkCU6(VM|G4&L=jW%G{_ zZ8uj`%yRKDlUuMimxsHJeY_sCu#{~jo41W28ZGrol9K*a3z@Am>cjEvqAmW$qMO&% zT4F>CA|Kb{!T9+r_f-*C!mhsBY)7`Y6EAi>cm&FSp5i;cs*y`(Nq4;5pTg)u7KAnD zb2sf-gU0w6Y;C%4&RzM{yI{`T#xAeE{y}Ow8O5d)Z{V)7PgVKZ+D_?{4*^S<$^)h6 zKSx+ckbI?YiZhF0;@3(dBW0XBzk1;)d1ZV6JZRn0y(vC=64yHWje^R zr0mrq_FKy?)1wNolPC=)Wb9*8l~GvAYTj@lyI(*k`)TNny)ZMbs4mXmI!D-JBchN; ztXB&uf1w(En!PKwJQ|ZQtVo)w76ZGCOe7WdN)D0#0;^KQw0Eo0d+@pP_UA<$IW^Wk z#fH_nmA&1>ea>3ym_1niHiDv1aEmdt3CfS)_jBG6{Tp1bs4ir81G8VRyK171V>29B>w?pf$;dvK2PmT#2|1TPyie$&5i#QPG4J ze3i)ESg$=?TG;YJ=HV$t>_e^RexN9r5^Fyr}&KIVLhjCMIz) zF{r4hzo&ZD_TcX~8$y2p{SFS(}~5>62i1bbOwj{uQDU0^(lztCT} zuC8>@X8YY4tuDSHeSA#cit2|`)kx5*KnVX zjlQaohxr{#F10npneRU2p7WQ7&&VD`d5Z3vX`EhW!0))aBKxQMULE}-8udSvE_}I4 zf57i{C6ZEQ5a|BI_oDdLIY*rBYVy8Ov=pU5bpwScf7((yCW&R3>2r3A77pmP@@Ca_HR8rCBk2T7m(PfqPRh%>^itXS=D%*hOS%Lj6+Ga&B>iXS)G$>lnMcID^nux^Xj z)=E%o>gT@TCJ7}&kzg^!zY4u5nMqg7rjo_EAyvVqQb1ZFQaqyIOCQUF`rGuAh<1W~ zytgwfljJOWJA+Ue8l26V(Gk2JrHJVGS8kS;`Yy-P3htWguVPt$DpeS#-MpqsrYJV# zXVCtswyA|NhHF@HeY*$Nq9C*WW~lB--*)dJj}H; z3C*VkqLB2##h_AL+0z~jJTWfwDIw1+CPbT8QsNhpVFyt$=K;%nR&OOTN(H>dWC_JL zBg%`5OMc0IWMgzpKM6g2j!Tj-(&LU_-*7^$$@}}l=5eDVb{o@uAR!wbOe`UhyKB%;M` zYU1e{xWA*@_m3d6$fIINWx>DUPGP}6DLkl^S$hP%b5;!M(%hZrzdBe#a(}y>^M~dF z%0Rop8F&|T9{vj|C2tA14C@FFiFg8%US_>i_p8}Mg|mfp@3f&@K0XwsJh8p_cYQu; zot}l;Ds1kf?I)2co@eD~iZP|1lTBYl)1O?OU{JW{l%h*4mlc|cYg~M3xTX{-;Q*;ypD&y_PRef{wVE!+H$L1zBj;YZMyzo^{{S#A0~EwGx>-` zb1H(gwbth^cakZs1$DY2me9Inzeu|fb2T|JE@*o1@4fw843lv17afkQkuL^{`sR~1Nv^4H zbRY+mN)ts^6$9DulIrjBFY$b?k|1>l74-U7uVRdPV&ZPiGzd2iE}dhV3tKWi%`2(# zi{$;X0lD-xY$|&MNk&UU-&N*H9e^KYiIheqkBW5A7Bt#=nfS>8 zCS^AYeLh0xv}T|=7_yI;}m7oaq8s1I?`5*qqrX>+u9TI}VvY-jGXq`t1~ zSt=9bziu@7gan_lasLo+2)~}QGCxLYV>ON~rB{z~n;*m9gG)T9+_vo{gl6I<^y@+Mvb zGzrp)qkdz;P?Q&NK(4Qy`dqcYe>1!+Mpt#FO?I2NtaoaE>sYGF4*K5@5@$)`jAi)D z+ka4~K-PQ3X0jh+ZZg>kY7tmx;4#4QfkhXNVtqm?M{ywkFT(!AoKJo0OjJK)s#K@Z z?a08wqLA!jtfOOXuHI3lQ2FTmyvtk?R$rq=rAXEL=6u3`D23Pad^AVOpd7PXgn6P+ zrGH|g+5ytn>W154aP;x%3w$284@!cK2}wyV`*ZaQS)$mZ>4%4hDCDxjA|lJb%*cd< z+7a-$s;s7wGkVw;xLx<>KEq*TD^g}=h+KO4B(qsJIBh9*ol_GME*~zpb6P5xb4QAI zR1_;y(Mq`oS5`V6EHqc=x3|tMb`2-7S`H?$I@G5OZ&*6;=O`8k6OD`sMb27bVPOT2 z7?o&NOV*NuN3)zLL?e7ACdS-r#1tf~m?aukYrA;A!r9c^e3#5_Tc=GI*#0vpgBCMD zA2R?klXG#12VagVb|pA(c`@P*K98N9odAo&>A~W|?{Y(?MCtZ!&#%eabi;jpME=>i zx!9PPF*!Pxvo(9M)M{o)bU5TB{S}FcfMDF(-j2(GGqmr61*n-IxK4Y;0`I z%t8WHoi`T;Xy!a33dUAbX*}+26~!$rK8X?nB*-sC6nOBBb$O2w^o_dLBGT1LQm#Y!{nORv^UiV;5_AOW`euzRsL1DIE5f0E# zVzb^}Uj7I|AQXs@%He2I;%&vpng zOjnwAcXYr$`ve-l?VTOsw@?=D?(U?dq%WU+Y7cy47)ELxnV48W(Q090Qe)8h>M@|V zcXzh)4V|k;x3{+-U;*F>m)isLa&o}GdHMq37faaV<;eXJBgI+X|9}e69~d0;_V%`K zs_qQKVMleY=?=vj%M^io_DrCp(sX!#wl*Sn3yaz0{X8XYCPiyuopI1{5mYA%78a-b zu~C8Y_UvX%l0kkrI54FT^Lt&|C2IWs zKG5IOBQFhKs+jX?+v+K*h@@m6Q0PdJCH7{jy}i5;5v}ddwpDz6eLHJoqoYxvq2=Le z`p*v*^=Qy{c6LDF!+A1-PQd4d$?wx-VE*H1wHw4me6{lK=AiZG&z~$Z!->q@LqiBJ zw6vs?*<=(zJwYJIfQ`Iz^`dad_A z{a*0k4=*mZD&|On48jCLkEm!sc=%9@_lkv+W6_KQpW=953XIygFPQkm0SZnM3EdS0~_;>c{Db zfY-+m8XG$?kjRV#0(O6U<$He>n7g$#md9@P3+l-e3YbLc_5FQ1^pMx^@Tiv7pH#mD z2Pd(ZM=4WTFEm{Nbo19V4#(&9xV^MT2&{bn6WY?!64%6<(SD_)qeFOn8is-k6s5U} zaV{_&pTfX@6(?b}7*Alg#Rr4J0~!O5^Ia@()Af#~SH}<}#F8HsyC0rBt*EF#m3m6_ zXHZB3$NuQji;yQW1c-uK|b#!FaFE0Sp*DhaHgAUk8@ob7S<)vxmbwBs8Le=VI58^%Ys+649PE8p2_rn(W;W7A}WfXf+@~7ihwr+X=!P6h_DE_ z90Fr3(3xoeUcPsyD?w3O(P(lz+Lg|XnHG;O+rsj_r+8uVA6^Nj&e zx-XJT=W};+V}M`X+}wmfR1UWz?aX)13W=MWx+aHG+!f}ziyPCIim?9 zmA<^LnY1a|xG2yooBBh*ZH`&3)uTdW))w4$Vrlhi24o~qEV#+;M=4Gw%Ti-^uFn?y zJgY5@#+)|0b}**GogK~h)XNgP(`o@(ub(M*J6#(Tn-goSlgyS?%ZH4nPY|*JP>omw zKE#frrKJVT!S-%sfs$s=3y^k^{g6`i@=UNmJtiivhZ8`E!B+-Q@+4rEU+t8&f|A$R z=m{_ukBU$1*_+1=NR|BB z%ddwy^({-Uj^tn`ihU=gNZGvgTmz=RPswJ$T)k*x0n`3;f591hs1C9Fdojs+PmhOc zyBvA8Hm1ph(E?s%igBXchL_k7&-q9F>9uHYi)!^VMF4J2+dulCpLOE}Ay-;W&hkDj z#vZJX9ul^)*6W-zKD$Gmj$gO9;7lA~>Pz~%Hp5}sKNrImSy*bQhZFXDrbY7g)I1Wh z>iyMzAE+q7#gzai=lj6&MvR7MMXuA-J0%hE^sh0-#6u< zt@45rwY^=aj%_zvW6crvq(u+wig@kfU{NlGBT_#BomSJ$&5dG~WOZbyxh!+_T66dA zm_K*+Kt^LiJHeFtk^K}Q>;0o!p^|pzd>5?TeIVA(NVJ)(R4#3w6Pmr9I#8cm-1wXw z-hcUAimayiEA^AuoNiLn&S!Pp`)bb6+~+^}8Bx zz&&Rn^#6sMv<~+imC!%aJgG-R@C(cGBWiu_uD2(Ohyjf3_<{r=8mMH4y!-QwwH6ap_1b*E#&fR7Ydg77U==Uem;FmV9n`uqw_wM@6f>+;i4+IrXpXpAaA z16;4Y(CX`JTn!KPjiaya=@Vby2d!G0BR3v?{#F1fsb+=IU42d_9K0JQdg`H%3Y{E^ zFdNRaTiVD+<6j`~Nf-w4FtTjI7|!-qI2f{buMszvlJ~(z3g0#EQB6%(4~aeeq*IdX zU;u2trB*T=C8rc@29SahW9UfznQTVO-g*5xFFH~bT+1ZqCJWQMV9*hHhuEhsfpX?F zv0F7t#@DJaR-PGcN=jygHD0WxAkeG0e{kd*6Gz$?gXT&Qi^FE6?%~k@DviAS*L7+5 z@UXDgaB$R~1ZM^%yeCiNOFy=WlSF~6uPjb_gV*4(|#fgiqBM+qpP$Q+Kdeu&WF*5ARCLMsB=`MdZ%KqueT;@ zv23&HuMU#r?4b3o3`;xj*KN8`-K@&0RddIBSn3DHDGhh@OI~040K^5rXs}is3Yqk; zs@F)Pc=|7QfhT3roa-Ig z)SH&Qy*(@IR32GOr+wp+GAcO;m3f=GwPL@*sDJrPcu)woT6kjrt^(SpYc{LjO{-tN zy;Ab_+)l&hbrPx)IXW-@25`}5e}4)KtnqvWA;+P7M#C<^L5;EK!f$i~+tH$ZEDuld_~u|MJQxUjXgwZEz}=@|E2h4?d+ z)r6*a<*uio$SsJ7ing>=)L5?tFEbCJX_t$mdsSQ?1O&WZV9vZb~ZcDGME z-iJ{y3+wKAm5)wT7)ya(3$Q<6zM8A@J)BA3tkje>hbQe!ywNs=n`%Z@YW8sEOJ4+S z_KzO|Dpy`+X8E9XCo}>*F|Afjhnt*MmnQ%yNJvOteEbv?;^wq|6+gSWx_fr^}X_M8%D&#D=90J8*>6U zo~2~S1&~h1b1-@NGu4&=;3^7HO-SjMS{RR5LMj-W8(qw{-Y-s`q^l(suMIY^sg@Rb zdCqD$UqpO;L?x}y?~RnVMl zwT-?TEZG?^)}J=mEZhlFl<3(1cvhrbpx9nh-#sFyq35eJog8RuX1Ud1escP8p1ay9 ze}lzqHUwU|@S%opgAa0gdaA9hO{ZP=^=1qSAHTGyNNTJqB&1(%FO=rKV~H!Sl^`M( zLKmBYjF(EIuMvl)gJ)>YNF^L|qPX1|=}ar8hg4p?ISLDhQ?{e07e&(Sc|+O!;~FI~ z0)t~Z^p;(r^ww+0nKe!r?;%UhPzp{egzHSx)5<-8%2Y#j;wsl@6`J6+Mq7bC+aNk` zFIBxC4kF@PMA&E0?*s%sn56k!i9QFR*45Po97>LMLCcTCxE**8JdPa8r#M>NIMm5; zLaN#_J>JdN-jH-!OMt?PIpnTOwb-5IhihK%uwt#a?zJT`mg=P96{m{sAz)PY4Posy z?ZTmd7+m7~(fn)KW?`d~b_17n^qkY_DT&`$-57iPvbW%c!6xSHMO zsNhgfSh`}jy6kE4rPCwAe){yur)N5%-=lZV%N)>%GGo`**TF#@Nhw_z0~=DDVQLN1 zvJ2JLF?8n9jw8w~Tthbk>{5CBWh9c2l`lWu#nq${QaV7Srt-Dv^BO`HPvAMJAH3{8 zg+cPA3dC1K;=8B^H*yrs0Vipe#KyuB8Wwg}kSfu*Z?0px)Y>Z|Q>sV@UuL=I&KqWI zeDommy-2a_Lb}zDP|k2vnU)~&>b*^tM;2XnK395<-caqTZ49kn2i2rppKlAL4m0Iq zg&a+PAAdTI{=Csb`#=4o; z6x*7RJBJ84?baWw#)MK4%b8t*c#gTz(%E0E4<>{9B$YD?dRzcJ-k?xdiA3P@0?Jbo zwzsdZP@~f1WfetyzcJJF#jw`PH*Wyj!7ZYY!$W)C&&1jB-N%*uXU0hxlh(R!DVe84 zvIs4e-Ah6hu28eH){*XZrb^36qcU8_DobZR!fcZ=M%uUmo^uC5zoi?92fdYMxDe8b z&#WMK|7RFf2?b;rh^>tf(#IUji-rbNLJw9eY9?|+=CzJ*Rrh9Mj2=rTSNz+zU;^cC zrMu3><|+oikk6A#zrR@Yb>~S_rUC_Zw$@gSOZD=jk@*o;L##}NANeb+9iC$^Dnfr) zE0a_n7BacjViGo|**I`oo8%gY(HFUyLJ`Xgj$O57aT@|X z$mw&kg?v4VdXOug{9pmboS8>AL7cEz2O)TPU?vz_ehJUGfh^g3B|1YfTPJuQn?jKh z>samoR4&^1JeHIHfu~rlEX^S48nDYg<1epX2P%?9_d`1Gog>Ao05k+qkDsZQO*=mj z=+}O3OVK|aKkPQKY)oH0p}Clor~(`Zc*?gP_s%tZYnrCiyZu~R&xf#x_Zs*Au;xtW zqa=GeJ@Qm4#~X9-?Q>0_zZpz!4|pBjYlMr?-QQmX3OlBld5CBjHdr8#1(A`F`@Ebz zayGt8lX>3X*4Nfvgkmwn67qY8MU{nMRJ;V!kS`3^c^rZAg~~|p9iL>GkB-)%${R{= zY|iX?I)=h*!AY}?uZq#;me};sz2E`z)O{TQea=tDS-6LG+y%GMA%}*9WWPR;n6kU+ z8IZ7;NbF6`mu_oek(8Ktb#<~qa2(JX@0*wcPubh79kxws4XaS@AU(QKH|%hC>=FF1 z0-Uc(SG+mLgXSMUBFMlJq7LT3>PtNsDP5;(?w;f+BY5OU#sX%V204gMuSFUbzzln5 z=ew=NSE4HLOa?2J>X~9lL{>GsyJ0k(60PeK&ekr=+1kBmC2G^CV$bFyxgDO8&xDRDaoOJ4saE*Go}gXF7vL# ziy8?J{SBK^*4|TGTAGgYN<48_Lyc_MJwJYY149OA-L>B6;GN}_&JfVDqi1Af45#zc zFCXbrDta`7#0G*2wO-3DpmP^nef5yve5`0aR;ERv2zj}?s6UhnFL;Vge`g!CUADA) zq2O~CjobzZRSiw6;0o1j^XFo*>D8X%K`i%TkMI$YsBSz9L#f>T@$?Z-3uve6?(c5; zAr9W&cYykd{rwRLGb)0Df~`JxJUl$(HazafYk_YF*83MKD=PSW?`fiY=jP`81()M! zwIo@22WzFnzZPLSDREA{%aNK{(@uaZ#ce0UJ zU!lXxPWHn0Cc7Xs{U7w?~1Q)l^Rgy#wizgWmj~9?7P(`Y3=C8%(E$>yGx5ojW0*Knr!%JoW zr2X9GB_w=Df(&SHCxFxdqt3sb`}@tcKSm3TxlAON)d~OorD4xkLQO87 zd{B>vO6Ww+!Qy`d9_q^%SP>aS{0P_E%cH3DQRvR-#Kf)j^{xslK-JUhG@Mf7)`6@c zCnEz<)ob=RTOY*n^t=HGi=DkTCMG5d6G|cbt1-0mjTM|Zz5dIL%YXohd#ct?m5X9m z69-b~J&gI;RcLJe0~`LsT3^Em6equ>IRLT_plg9Ul#{SyYN|G7mBQP7X({^MLb!)S z#yfV*S$kYg>vz3kZB)*$w$LM$~!Ihn0e`Y6n##_fWKOWu&YwQKaWGw(2NX6^B(Bv--`g^UJkF=N%>B9N=BLSgC^x5V zX=r?ew`5O4;Zn!r?%%Iwv)*Jry~p2ImWePyPRF13I$X8A+m$)KMW3o`h&=7PQN~i3 z`>5u?hr&sy7x&I0(G!bAKey0yMr1)f4jYf2xzyrTiJ+4@P7FPy69{2|7Db~{rieWW z&NYuS2B1_E0OIQO_)pV~xjxNI%lGZgX|I3R6pKyl<^VXTVbT9RUrgePGpl-vS4l~U zwqX;E=jqwmnO2QeVsvw3VOO>4_Yfrx)?thn_WvO`7PZTH}bzJsd_3mqw zxTEHklmvAbnC^KV76)Gy4b2w`uqo2MNRl7}gbyS^OTma&dQckfMCg#k4B3mNI@>e@ z<(p-)(2NEn0=bRI)AwRu$I5CK2yLjG zO`;UvrDaFpDH=1HV;Nkli+~DQk5r}#i-@qDDxC*3rl62e zb91u@(Ma28IAbOaz)v=~9_Sjdw^+c>JKIPdguX31pJXk(Q?0!^JR7!<GWvwCJQ;9vlIv(+|OWucn^SE-Q(Q*P#^G)6>I`$ji!dygoIT z*^D?HD@Q`Gj^n$p=|oKEvEH+E<^F0aLSBuwV9dnXFFA&?8r8X2A*$u_t|uZQuErkI znMhTWN+C)Tbix2OGBHVti&HF5T8`%fdWqY1p^3=mU}FOV2`OWHVzf+IulTy5RaRfu zx>$L*Vi$;hM8w1=+N79WqoYx|TfkvJNyQX{mKcG~F&)koO+tS)rkHkl@Fl%@Nn2e# zp|lhz_*(#z6{tPrQczJ*6&?1cB#%j<#D?AKd_ zz^tsSleJzHnf<025Wf0fy~Y)%qqtKAM94u@%K6_C5XsR)d{ZOzEiATyuy4eai0&=h zx-mfGnI#Esv&>j-6|{>Lz^+iQ4Qls7wWZqYO@+ym65n|n2Ft1vx?Yb;+d?TJtwzA% z*OUa5HpNj8`@2`qOjleKLJV)}oU9<5zid_(rZn_y7rStir%TF#?b?DJr<#{08u9-| z4gf^q`O2c7)_9RtQLak=qS~T()PL_tQP{s}*z&b2#)S@0+;p)xE{m#h#vg z_`Ra=!32%h2eh+DaVp0cyLJh?AeNVK;13NAU7oN| z=m4b%O#IOW2IKH%PmO6LN;4d~bns!;eamf(`{N4`wx~UuFrQH%Qm;cFy zTtO~i%*Ts0YpJ$5rsk@urL9-95+{Cs^gXYej`v{f4FP|Xx1IRy=(5zlvHZX9OEbQ& z{^ZX>=C9jfDd}r0CVzcQIJgkd zg_%3)Ifgxj!#PG0gpDLmqvepz;_%XRy79L%`fr%sl|$0Rjj|G-IKEx@5BC+|?f@o+?cS3lq~!Fy4XwL$MR7RzSXbR3u_s z?IwSfhC3Z0WH*IMO18^{#7DK_dgVcML+?VJ@$H?qorEZgPF`b4OmX?Ghy-22?U{?8 z@-|R*BgH|R%$gPV(S>?}iL)&Z2fu0Y!=^c0kZ@+5vH2f|MMFhh2-x5=rMo8yOGs!- z7Av0|qrb{OqM;Z+6>6er2|v^H=35ru7%K=T5fv+MVMj12zMnS~ z{4z?4l~d0CN)NjB8HV&wx!rObyY0fETN40kB6##r6m!6l1?tt6mk%%#$x{Hw1#~+D z08`*008$VXfC}CKb}2BUR_r)J&}m0+i8jD9e13gZQ7c=Q4F&FfsFSOXD4U z$In;sM$&(6Wyv$Mq>29uWJAEsNi#CmIc^MHHa*FA2G0u`P-H>TP|QfrcecOmfKMpm z%a^4iw|DQ}1q1{DeTK24yE_7t@smELm{>QZQm)w|0xH{@;a_CGyuUp*uyF_U(Z+_p zlv)I@+p-;KHcbr;{g|=7Ju~ZG?0Wc{6#nD*0i^KMx5l?!6Jgm$2TI2Owjr)p zw^udoPAvUD*?B>=PHU)DvODaK7uK!V^rXUc9u>xTGeiiZ1#h zb!0fQjXLL@I6%?G_v5kKXcrt@)t2Ju)s5<~OEjIgMstAhT?fJlny8nA05RJD67bOj0wBszPtUKBk?B_7R}c$*u|s3PM9e!xBc5$ykhL2bs7qnLb%-B&~-! zuBD269_=`g#JU4=B-kRy!$VyOS)jQ4&(jQ|RS$6=GUKOqHFd67*ERLt`v ztpYw;+7e*Afo}(*Fui7#cr^VIC)`^MjpBfX(ZOD1J|Z+s4M2DJg@7Hy*uIwKUZtLtf>e z?9uBsVLpZx^e>C`j)A~iGgDOn!VUXH_1~>*pu)8~c{~~cfrk+W0hc0D9M};#UH7$d zNvtD14eS7y3mit(z)RTr$94uRvsT>P+@L5>tcNVG!~M8$14{&mWwxR@5TgU(u|9n; zgZm$;vFSAq8?a`*{>zL9+WK^UUsd=BHy(V1C{@HDVW4Sucf9|QDJ3h5&tity&H!kI zD`59~bdLdh5Lht4Qx7C8FD-re0EPOrzXDKyC?TDIwr+IU6BMWtF)~^MsfiU}@8SXg z1jiq%+AK&oU?>EQ;QCOiC8)E+*|Z?4(b3UIKycp#$seDTR7mkPS3L=bMGu4v4ENRL z!j$ z|MIORV8Y8gbp!n3vWp48Air-*bu}x{Zy&E36-9&yYj^Ve+izXK5_J>!_83(F|7Amc zJt5G!!J`3tE?8ThJb4mJr2>}0uU)1%ydG8JB#OoCL(6t{ZdHN~4#$8f0g^9ZC>{+< zkG3n&AnCUUFv2U9={AFY7<|_Xh>2J@?y?;RAT|={VdQ!Kup25g=y0C}J00G9Lj&2! z3`P>TnSj3*5UM~<2Hrb7psNGBD(J8Qq(DbU=U|&L0PeQnpr3VD(DK5>V&Tej74QfM zU3sF9YXTs)k~kfKKTw_rkYc`9$E3hT2GCu-0|eL@-bVMLR>Ok>OumnQypiY_80?_H z2I%kZ?&bo+iZGZ>_vVIW&)nL*9&o#)EI^&mzylK3i zY`*tiiPDpR!v>zWN1rJmhk$=z6_7Qq`!sqjJm7w|Ss(}30FQr7N|IEFk*C-N1Uy2h z>Q~7eU`8|5m>d~7ici8!Nle5-LRwx~`Q#|@w6m+L58?n&SK|DmvvEL#g@J(sbo7bL zrglA5g2KWbMQUYr+WS$YQrnXyH$^(zFA3{b%!}*lIB2&4;HM=7&SHShSF%UZi6S=v z!;2~ctnz33^Egi^1B#1jf`luqrYoY!<%qDcH$gQ5f(a!lsmM_~XzT6B%;DmUHR5t8 zBo!9-F{XFG=hQxR9%mNQzlno{iDD(sPEY%~_Ir$&1it{9b3ISgcpdc`O`HTdDHrJE zm;FN+)KYntKrSyWwZXcXvH11vBl;QO{DGT7TOHMum{3?wE+Ug6Y%g1zPR*;_W}yiy zu-MIFqVNp(&H(31N=63ms|a|9#aCOWft?Ik-=e;L{no3-NC8TeMVtRi0EO{776B?+`PP6kdzPiH*)rkPpY1Sj&{6Y z3~Z$F`AJ^@{Kz*qH?2V5vf3R2T76qv8!%CW-5Gsd_*mH3U_Nkia+-_SzQN_NJ6w7f zDehks+~)gm*Ii)+79A%iCzks3^Ye3XBdm;!KMASRfFr*ctQx>c0sEOO;t-^Mfe2o% zdR(WzUquO+(!jb2?24ynXCf@eL1AGfK&J#`EiW(c#z3Oq2dEe06C6pN@HX+m{@Tj$ zl?#wzs-fg-tQT8!j@m&?>^i}=46sr6n>Q-+HkyHf0Ye!+R3AfUs7L28*syT&xHkg) zPJmhZ+?%XFAJwE_oxMs>16!>h@1TDzO`+_A`x%sc0AwIv?MD;X`}_FwLYib3p&ri% zie7xEp!)mOUzag{#TU>9&Y~zf9{l(7g+N@y#Aat_0n^+72t}Z`fu;zo(Xz6#2w>6j zg8CK;9M**XRW|c8las1?daZ(=UxClpkKCSbkb=83w^==-Z&7j1@rL&(8ZlFaP^25a`2)^L-wMfd8+#FAt}3ecQHoyAYv_$&eu= zL#E6_s}MrwF)Ep-%(JDC63GzB7#Xq*Wys7)vaHhr_z77u(JEr>*n`Ih2Q;nU!bxx8?EO_$Rq=-hw2JFLe=>ok z<5)f&F$L2=vE?(ROj0tk&GmIQD#D@fpE9yCF(ree)!Mq8KoIG-5}^eV`J@e>E zh#pWF3eOO=`F;l!KYty)`72se{rN_2O9Mhi@d^AU`jxJhO1k_f$QfS5##&rv0B$_H z%ZB7=jKYzTnm2DUiP^<9-?tkqo&hmBgGL#64|@{K1K;(`&vvGDnu5cRi0BUW(G4sO zipa~4fBJNHswpxe%NSUo(8rH?!@J+A#6tZ0_qki+`K1H)O8HtrH!#zhV9kflfXFw( zc=Rj|s3vYs&YQ^+UH65{;2rYtJb9@53`9t*vc7S@$K|nIP2)XMa&kT%o(Hb3#^p}T znYnbKZfAMIyE7D@LDu;1rO4>`DnPcx*Q%wZW!VyUmqu?Qp^|)Qc^R0HU#}N#{SZE+g!jHSIpGr*(FyAgTsx>alL)(e3$T;kN z(B0(N**UBe3S72I`Br+^EGvAW(8;7kZArE@mL)vqeW_kMOInuvF0XCkSL=@fE^T%D zv&aWOp#IHu^VKbhgsU*4y^ppV!kPmO0Um@##eB|##aR$kkFJCkEpq0t1gBi3+kVs2mqjB7m%ZCCJNyV90|N@Cvd)8L zSqzepqn1@P3XUerpI=gF!RtD^ZCF!tr!3bzNOo>UddqpD6ipnze^u`P=oYx)krku< zRnUKH>20}u{SGCq&$Gsjy~QGW8X5^HDdB{p^)a9t31&weaC>B!@+)w*}{>vkwA##B{w~=CBF*+;WvMm#$y!u9T*Tl)6%6 zCrHXR-&)R4Hs9Kb!B*nrT5)QqG5Ic=$vc96(MVa}wo9FUXy+e#{V2=vvBDpOV#46-si88+*LhvHA|yQElYJP+PqhyZXDS!?dT^z;d^GVlkdW^W%%mS$-c#m}%jS1>7dwWQyTZZ#>Od(&lqfsLug_al0V zVZ>{4gV}{X*0l{Gpf@_&KCv?@k5^sdPHf++`N8`%-`To$r(m_kVjPK_z#+5IHKmwu zvawXgDRBp*W}kEU{V2aMn{_P>^sYe-?%4bp#1T&uhWXS!I{aO zQ{qKTQd>8&(J{sNWtZxf_9xZuGaK)|(OFxCHFCaY2|Qcz(fhObLF}@@M%v!r2f_(g zLHC~s)*$$E$dzL3=??TSl&Uk$ipHxvP_eN+o%GXGW7vE)5mF!<-M%&Hfx_9$4i!+H^a5iZ0@&c8i$5$KM0x*M@cb z@K*a5F`94n=a;n*By0(JOWycfZQJ@6%xukamP^GPL#Ys_5#Ky~JyDK=Av}ZWY9gPX z2ODgf(ICvLt;c6A-4PXi&ibFQwyuSW64}gAlJiUTC>`2bs)pL(7j$l1OV5$k?>VRK zn9a9%-<@tjdWjueU$X7*x4PniR?Qe%j8>L5WJ=+T>~+~{rVq_5(SH(iYRC`t;oj*a z3FbTcuK802yPrOi*;=ih9Lf>5Yi@2mzjmCM0(+GkAX{ z#QyXq{5eS1%D{j0tg*Yuy#9*gkW31PSK(ZoA11I)PvQnb;tJ(B-my+`+FvB2XEM1# zFpqyQZD%8wGlU8;b?Z~kaKxN#K{A=3YeFmbuZSH|2EqKMeFF;RdijsYJAIfiu6|@L z_v>zF%efYPfp@fs0kPy_4%e;j+(FqKvnzf67k<`CI@cQNLoYdvndFluC4F^qw?B=V z#!?~dSML=;5kMug=SBl>$YsokT5Ej?*LUvhwUIy6u0F3*&o&}?6`-{l<1%bxPQnjWb}dYI)3mKXOjPC83*tYm~(; z`qBN|AuBAg<6~s{h&-)WM(6i;ovh|vx+Hg7ZgvQh8Kh9nju88J7Cw(UOIeVag!=4u z+Y>3-H}yv6Q2l9t2&YPYqMRmXZkFAW%kp*Tchb8ZH*em!s8##g{Q>U9%g2&_J3F~n zFNE`fHZWrLf~NdtTD(?2_t zoA0y#1&m5l{r*Zd@K^Dcl2E_D{`8EdeMyWO%4^(q>#0 z1FY*!^O+OfCxdEAr9K#^RI10W zTezyo@vXa^N?B#>`|BuK`eK)7uY|lDhAYd9`C|Is)by*>8YoBQZYHTsg?@AoFz+{U zS(iNEeVIRI;T`5YwqhvX#;IaVU-UO6owyqfyAetC9`jp0S(7x4n=O39E>`#ZH(pOG z%fI`Gh|0PY$Ru76xx@1et)0*kV|~-RL}78e;RUUlvE<^H zOR*;$&vi}hrp&Y$*zeB1oxeTKBwOKJuq$|2W$fucvMj8=nBZ$H76|k-V4XNiNiMF( z6qH0f>;Q2H+X8USXO4&eNlZ)(-cWja`V6AA>zpXG@qI4=D1ZVShDsEGn=0R}JWx91 z6}RI9XVn6nI-WdpFkjFrk2E+F|8aQ@9TF=oEx*q?+Se<1Vz<_SV;1FAo7yD$0IEiI zT^XUx_Zh)F4q{sGBw80ICnq5B!Q0CO^VSyn>+rQ&mFxn=(rM?bMMShld9hnOnT(7K zSjfJ`EvUR3n1sfRi4;jfI7$-0y@YVa44f{Whu`bYq)KVgLL8;yOiAZ9k>cXe|kb3SDV1~#YZ zqYMqwIA9qofQ*P#qNbw*OBcrp6#_d6%BR|fp84garGG(qXImTj$&z z-qM9pFo%bSpFu=0ina9jCnyjR*~L@}rdREJ(ebH2e73$(GmDn~%4xzRxXt7QE2byP8h(fu!sZ9G}NxWJo?yKg`Vy0$Y z7;;7-^)>~OLZsjs&{bDME*GgJ0x~?{;zVTZ*85DHVSAA)QBhGGCNWIq8 z@_wucl<_)6K5Gk?62-+Smd@>7!=1tR1$%MR<0`WKHXjlTAC6S{AV@aq*jTM=R)WE(ZU|MAnwv>4t1HiDzvJP~JWJ(z8f(B>g{-dAa^lG6^5@FT zQN~-wlx7|)6T|a3uhwjnB;PAPd31+s!L(cu&&3mEY~Zt0!nvF@xEZ>)72scUZg1=0 z$6CPVR0a`IZeREZ)K|Ul zsqE}Sd$~b+FB_xG)!9z@9dq4C8V;u#q~AHvMVXDg5jjhDS5?l1XB1^0kRwlcv{;m^D<%KM z{c)CZ)JQ~ynt?!CxPyz8r{T?vdE}LR)J9WZ3Am`&*Xb$S?M*rg><1RnGs*=?y7SSU z_o|pha0R1is{kJ$Tx0#dF7($*-bIFEgKLiy<(4*ug@k}@|1A0AfdNCvtp{=uKtmnn z))v4Q0gHe*PZTscFm>VX+S;mitJ#^DYaT_eEu+(>t>cE`Gu~|~*7&k;XN>(`7v8Yt&k=agEPaO4XDkZIkwuWh2WsP3Kn*Oyba_Yz7YJMzp22n_t${ zQ*#jgV5?#;W@Sa<)~(Y5ve9->#4*azU_PP54_Yn}VPWzUpTWuIA;k>*gziwUSPXjO zK~Cvwbvia%yh*Cq32tfiiAPc@B#W^Q`#X!TU01SZ#*L`wsCBR&;aTUE$GLhqIWbDN zN2n=HZ*Iv249(B53C7{>&m@Rzd+ZnL&yCcSZfiQ>@WW?&f~OY8OltNK;YOKdR-@mF zxBW+A;^PE!C`@lJq{vP&N~&m<7GB&pdyMXCpT`9BNmdPF%-eJits;nm*!8BM;&d5Y znTlEv{w1v17?c$G<#wlIqvQ__QD}{%D+N&Rgk1mDrNOc)H&4X9_^hV~ooK1Wrch!E zH1EsrB&WW?kEs9JMp4gaXFDpy&&tyaDVNp-rE)0{S zuyIxgW!WpN^7pguc8nd!=AC`phW}|Vd?=*GEAJF&-y7Z6Dz~Vo9@y>S@!Uy3yH7K5 zwqaaU-AH~$szS1Ll0s0F$eTC(i^>+E%+}Fyg@GI@Q~+Tk!g-<7385E(Rva+ak3&OG zlMpF1F4gXB<@vhKR-e=0rhoM^B1xJ3tLEWH*KxK}YBHX*Dw!Xqvu0nV;+i?>$NSHX zj#q6j?sKv68DTP&9t%h&Sgu_m{N0od|eIznBBbwWjS@-Jbbtx$V<_ zHqDwoFIK0`P{~(?t&_(p_Dnqk^;36|!-0LxYY#VF!wOQy^5SOkMmwiF*(*g!*Hres z529&GsG7cXa@6L5ZD5XCH^$MIm=JhgapFr}`hPom|uD^RykXRPp~rEthzN0dTR|b;Hok+GU|3`&!uRTd#_Id zju2+B>jL!BKxqzKJa+9kAyNaE2aQ?$z@Q3T7qmg(tsDC_;p5Eg;G4d~8TOP|JY zTA<1AGw6N-o^54R8idYkpXoJn2rZ9-kZCL9$QIaIgg{zBq6Omx%;w{;FcI>+2h-o8 z0WGu?*Fen)XeR2TmYf6EBRiX$FXFD1^)NM^FKWF ze=^xbzd!!x3I93&e=^xbzd!zFvi~{Z?~lK!@qbSEzhTP%-85UfJQ zh#@IMrKle?&CrACh?(35g2$kBd5wd0?ca>}qmyFfdC>jrlEf zL=)Ss*uDVy3Ke=4Mulk0GGo7;m0I8`*+P^)KQ*vplz7&tjV11eSFw=04uFmp!9aeZ zDch!{y`2`pBp;Z}NJ(P}UV7-eQ%;45w@lGcK5rMDkf02+L%~waEVIjyFFrY$34R5D zBa}gZ`#QTLK72vQATO^xi!$*Q9m(u08#wfk5Bq259qq`7AQ8B;n&c2H=G)U z9)j{Mz++Nq{Rj7Nl+n%`2dAaNp>8csQ>?A=ATLMF{B|8ymoq zTHL$GslpDtER-vPCV{QDU#;1E-h6)nL=g%KL=STtLE->vM}gK2DD%J*5ja)Ct8Yvj zbf6$1;rT_-R(tZpSz)q+wVFoJ7V_^04=zKTCCsFO5K1{LL5u_J<-q$-X!J`3-8T;e zf^j&1xOI3_|K2DNxs%}bX|r+zr32^=RL|RefLsPzHnkQrojq$*=kG({ePJH*9Ny&8 zfto{?jk~9(*@t__;pzxP!RdYTn_$2rfNPkAe{;1ZOKt)%E#^~JR<5q7pnAgl zs(lu=7cd28WMuq%ShBR2fQ-z@y${fArObIeRiXDDbQl5}AhKE*X%+QDlOc3-^HX^CwZ0&w z%nwlSf#Kx*bxxwBwNbBe!ainKM!|479SFm}GUz}gQRTV(8i=tPA2;BFexEcQ+uGSl zNkVdqCJXi)P|9&rl}P~S3QR9Qo!Xr{cOW(U@9V!7g&sbz44lX7YJn7hOa?9v3OuFE zE;L$A`SN!gQGNKb3aFCS zM8H^x9S)Xa`JeSMseK?}n_dW(ldJlevN=AMjlTCGhVRZZu-u+kiGh9P(Qz`U%dwOX zz-YjN6J=}3>!!YK(U%k;R1EjDM}rhas>Iip=w9Z&5V#XuTv8HB1sf`he4szfNtQuO zPfw5E)&eLhzy$`ivWysx*80+g1L{aFitXY~$?A#p!mk5CueW2e-*yHGsjoWWvA&<2 z69RtD-{eMq~ZBCB_;hH=r+C+@}mr>eBTjGX<*()JzFgu7MAbDP`$IXW3B0coH`u& z!%bsGRZ7}%wmG;%r@pen`j%Lt`yc15uOzV!Vy+!!1}E#g(DUxRw(AD>Jgt?9ybs#p}Z^QB-|Fu8*whJHl`*u6G?~7+n09p&Z*A|!@%SJVm>V+7Q?x; z;BK#DL>F^yM#_?0rKqehmpbMedPqRhpj*AKbV`Uj<-p4$FM}RINR94wgp97QlE;Ub z7EGbcF6eDM4bR|F%5(vU1LB|iZO_!5X%NtvZ5IS?+>zD|Hll}D)6yhdV9n72e}ICj zqZV#BidSfPs=qAxL3CV?u7Xe!kTe>?{xjZ_;$C z0=@*X(drNYgncMg!%nV?^(ah90S8gOK1vV6wxHU-{=m>>!Ltr&=g)X5ASt503ySxid2}`#giL*pXpWF-jKAYVAU#>zE>|1XF)= zXLsbMp`!hcz{-5CMckfOg7v9n)`h&{YyCE&#s!|xZvw2bQ=vpMv>#-_l&v(-q8J(9;VuUXKYp{By1rTJyEW9K0{=GVc*RGdmj}9Sz!dL|r6tDqU=IDXbBQ5$;O^>l6FoUJJdppe#5M zOz^IP;f7bH7`JL&*Nd5rsQ9*>#j>B6CAL*^HLBQ{Kz-31%dO|f4B?HZ3VVg6Gvc2rF1|i$)_nBCu1$F2ms_Uu?p44^)@%>i zQ+i?5ldc48p$()`oB&KLEUh6(s(r6<$su`V7NS;Y6Yzg`bM>ySi^=1=ht@>uVi60B zy)JD~(+6QVs45_f&LmVf>}0}eEBDf)q6!@`IK1p@q(^Ip*jH^n&J)AYadAIqlbnCm z-~sjJ?I@Hw6+P~Jx3fN{$X&wX_55YPvcWO`WY*2J=>NfpCh?wh0jC^9BoC?4WJxz& zaYA^%MW&JWHP$Db8-0mXZP*iQ*U+4@tivHyvw>c;7@3kgIP6;<&VFo>5g*oj!+7Z9 zX9Mcz0;t)ly_DIdtJ7i|Q^I4$Sla{W=V!fT%)9K_7e(FHSLN`}e za7O!sIzenS7=|+UWC}@V>RYsZvBr`RrRipKUB$Il#sG2T;d(xS>)N_4m-8-V{~L1{ z`~2GbQ}Fd+lD4!kd>pdXzo9MXlXQK&#SHJ`SYT=bbuAzS3?)2HSJ|NgM zisxWwhv|I%{1NU>!u+89k(0mN{k}EEo5ME!707=;DNN8wxVuM$hqF_aVWGz&;5$d* zM1q^T9*HD86#h>qi7@U>8fOXOAM~J^@W!NgajJwrf4%~0h=;k4&~}c{92F+GS{x6d zon&D!A+k}xk_xislamVs`rWDol86p>Z(5_``_0gn!P3aA#Of3?D5H+h9)RkgpdbL= zpxXpN&Y361@O@y*%jM%&5^sXWmy(?PU#xo>Xn2?vM)Bf~L(>Zjs^|0WTuC~1>=^Vx z1yKIqkPnLIcl+{Q$e&%x z1R)J%rFW=1Ab0pg%nHex9OzjbhvOkD0OAzv8wr*^Fa^O1^!wObI9eJS?Ee0xaBZl+ zfc6~{vj3SunQV znShig^umMh=~uyv2D1)SENVAz0*D1+mxrq>A#+>Hp9>$NNW96#cHP@s0OgGRD!*MY)z1d7*<29}W4ybNnPK%Im>{^MpGfr>%6J zg1+Smd`2b|vgU_t=P0q4mdf;?Io*P)&P4ImvaGu*hQ$f;sCR5}k5k@+=X zH3sok+PyH*U~q_tqCV4j9sL95)X~rX9|(%yQoeKsto+)wbYtgYB|gHvsVHh(FGSpV F^j|4N9qj-B diff --git a/Documentation/state_machine.odg b/Documentation/state_machine.odg deleted file mode 100644 index 2f55a13dd4ef1fdd90c35f69eb1ef4691b68f36a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 18576 zcmcJ%1ym+UvIYu`OXKeD?(XjH?hcJRjk~*RqYX6fZjD>x?(XgnW_Iq(?#|w~_nh~F z^Z!&;#`k4pR95~Ol@%o?2?UG;000gE@S={ypAAIQO9=n~@bP&+1Ym7$ZS3e~XRL2$ zXJu}v?`UpoL+fl~L}RP(VD3O;YiDd@WNYYTZEWL6V`{H&XJ&5bAoov%c4*39@__*W zK0dz@8awLKxLR9r@xFiIIUCzMyi;-$(9_Tn;2GN(+8UYLm~s;+D~V9E5%BUra@m@g zm>U{%{80<_yE*!J?@${Dj^B&837qV0IDWH-!$#lQ*nz{*kmIk0ar{-AKU@-q_)t@HapIw;X@P{FTer*7kpl{_w}|?)uGi20A(> z+TZv8u-d`e-0Hur@k5u|(AL`S-A)558ND0w?D@v0T(p0y^E>i4#QQ}+{oXWV z9tJvk25LGsY6dzbdPWX<1`bB{f1v+akITrA~>9L#K7w0{(SX#EF^{!;S09mYoQ zEwC}AHgdB6?X2*~DbY*QGb{e1`hP3_XOy9vp_Q=%55vD`|KsrQx~9f9#_!zk-jOml zus4?d?b4=Yq+uqKGPiMZ)m39-(Pd%6`%9s&oxQDvv7sX^BQu>fJ&}Nuxs?(1A9egm z_dEUnj1dkW7m$Oaxgp+fZnrh~pm^`FPBxC*1T2gMv^-q@=novfpTR%&{)geW!@mz? z;NalDjg0Su;r|Hq`<8>T{>BKBE00l5`( z<1)i|5&R)0%2_xyQYR}q#5QjC4K|XL%rAe z?X!&hv1g0}z(CW7g3 zaF!-P<-hS8GLQN5zB+m;XgyO;OtPtZ-&}8Bo2fo42uvaD(6`h*?O zgy~O3sTxTT*OCH%-a?H^x|g14q~5z#^Towuz~eF_i{*#E$Mp4_>9t)K>@Fa5*SuvD ze=<|Mt@QF;B_?bnG!SaK7B%p8Aq$Q~@}QgUS+@=O6*&RhR^uq2jn5l?P%X8JfWsIg z&4NFD*V+J=S~r`Bm!HLBZgq9r=+ViX53wV}kGk+HtvnyMxG;AZN-{CN+EC7V*og*L zlW8p)CiSqjAxxGi14q{a-T;HCJJVC1FmaC0>r=yVn{MR$&M(T3PW&PtWBx|?8 zR2KX2$^9nS%0rGq%y>I^49N)$L>@oUj1@|*d!y({G$YhrLYYg}jd}W4i<%Vdeez7j z5H%-kOb6^c7eKFQ3u=dBpgAM{5&Q7D&A^Md>wdW#PeZ$F0mbh67;p&88P(EkEbA-S zdy|vC30ud5W@%UY?efxL0vR-7`AY~_>XNv0*XB<_&GSE%LasP0@rGAZB zigh&<1>C?C)wN4QJ1RY_KXK;8j7=?=&2Vm6#B-CkR_j^mc8n#XWggob&1bM}b*QiG z!e>OX9$Lwawd*!r1y>i9Knw)ON`?^UL1@?N$Jr164F>@@u z2#A6rq?sJBt0|j_$Z6EPimK*{*ds2k%JP$;W<(%?y~us6S`f@3Y7!{1JP8!nI_UN% zlxL>b;A5vI^tb4m#c*&S-UeK#wwKFY(C37H4&DRklxuwPg(R&y_95F={Qyf{qu}&c z=DZ7RIY}_^<;bUl;rIEP7Cr#Le;x#(-UmTLTN}rZx!?O3c%r=&b<~*XHLeN{11g3? zbVZ^-<(P>#S9Gcua|)2^2BB21^$lx*fvAb*1<@_zEuA*Cja-t%dN66YRPi*8gD=@w zr=YyA&kLV*W$oqEE!8brT)yz(&{+V8;UaE^D!ZucX=!lH=P?{t+WT%tb!{hHm_yQL z_ra=0N+pqZSQXjReZoU|^;ca(ymVFb;1&b5t;z)hxozo!bi0g-bR}lXO{ANOwt@=n z!un}p)k=#*R#|RlRrxe)JLap=^!zC|?Pk&Y0qU<7F1p)-oV>}Y9X|nYb~q}gxXH6> z9B*!%FXfbv(hsf=4#-_M`E{0MOJ?0IEHr&hty^vie@c}-Sfv?3@O;mh`YMxNKU@$N zJQQqg9jlVQqpbiPL{hQoFRzU%4k5kn6r0jxV|4fB{>GIzMLYVAn{FIu(|~SV$}pM2 zlP811)8C0B-#?E1v0y)fRoivZNGgHPUC;Kj)^TdMFy`z+kQ;!e2LTg+7Yf`euvoL=|2 z8BwOgO>2a7)T=@JnOQFZNjWV62Mx?sE7nK)xyUg}A{CgZpk}AHB5g+Yzfm0R7xMu`#*U?GB>oU(sgGsn= z)k9~Or2II+yINwoI+h&l{s>uZbh2MYZlf zS&;=EhQ9D{q%<4S*^+k90{kNMA0gz>i+SoleH0OGUE6O}8T5w1ic+{|x9b@3jkh&C zg~qxmW&+P-Z~!wi;9qjof6Zjk4Uw-@E)5&a9bAO5)&@(VnO0u%wffRu9rS5$qm1W* zJIFStpcQRvzcc|Bf3oNjoyG1k5^OA$_^Qz}WnP#kX<6nqt|HEd;c}d}tHFrp0LL07 z>vFx3<1|Y1CLdbctK+nav)B?$wtBUTQP~t4hd8_Rq}U=}3%8U7#Y}n}_%TuiiwAsy zDMvutOz`yzz@U?fC8Z9$o|q-*T*`BDchm%;!Xxuy*?%UeXD{ukC0c8nZTVo_4vb<} z*(17eK6;o*=SF$c!X}B!wk&wq9gd>|hA^KknD@5GKesEr4U@wpo>p@B#L+?MB}?WQ zRQ)o=Xi43zVX(U3@=$^*_(}G#(kU^zg`*+|O)Eh;(TdtA_DLtA%HnBz}aLrz@&=_KK; zVi<5dI0Bwb0cM>%L;?mv0eP^Ya%>m^RB*Tm`0N-0&w`uz{XKjBhX-a%0li=|)9yk6 zJcU{P#qLBQ-MUG6^`#B%x3w;YKAK;W$8{HJm$08{*HY)fxlX>WXB1&4${rieKtu)*ghW)cFn|E{YeB`8(WDOVd(hKI$|^Ra6*(R zx@2^ff7`q)TF!$!aY*}TEz&idY3aI8D`{hJIVEknp-QiooX84 zilY8!Wi)Hl*=61$GqV6`8Q2JA+S8qQyHx3B9~Tay(QAyqTrVL`ew@`C3tN$JEb44E zUyG)dDl4VF&5l>S__I@1MJYm&gwQ#BhJ?-=zK*s@`-GTX9d+@y`J|MNB?LvyWIa+3 z;4c@SvZ`BJX4=f}szDv&s3hmgL#RnC(mcKZQ)`iV2`#ftjz zu?YbQmkqFy$na$^PuqX8mOaod68{XMH@g$h^g8^Z|4SdnX`b!ZBp^J>7qZXAT;)F| z;5_X&u$%a>X(qlj;`xg$)P?z6APpP64hFdx0lCa~t_6JtvJP7~Z}fQB?%}-T zXY+)!?F}Z=Gci12!<`kb{&^mi9pNh45RWjY7xRS;kb^&9h(H)kZdAs8bDa12q9e#H z6P*k(gqXMKDr$KW#_3vYWCL)?_!RncLNKB!D9)k5#bCPX1&MBXoO&XvcEQGg*mNJX zoN%|*Yr~8C&*(eNM;yQq5LFbXmxz&FVvnzSde)vzC~j%^wmq=cG|6&Y&A#K z!WQk8W8Vc@s!FrL9CayTCh`%!5%55{f%_K|@FFZhjS)`SI|rKst+RqEfz`@5nFB_C z5*9#}Yk@$b3%PIP!j)eMBs=5(Wi)1mKZ6HAhq3K$lLbqwHbikxym z;q?_hxx*%WJ#CRYi44I3>7cPs#DpNg$9i6l316^o28b8~mdgf>v4}x9Ano!0ynZK3Lvv(ARyos0R16fLm{~#7v)oiq4+-!Dr{hDNgUH|5D;-Vw)js|xtv6cK!!P!rZkxCX}PQEa7O6|NQAvd5NDR80UPA5eN`J2)AgI-qOSZ*W0yYfOFPp&bFZ+x z0K<@k_v?n{_9%u7mt}^_M?)JK1!-4+*U32*FJV3vud$x!0Yq&*Hi%`*m5b;fCyiltsmo9JIXf4prv)Kb@0+Qphv?$vCRc(KN+$B5qONkLN}LK;W=#2XWJD;!Lwv za<@iONa7)N&m29!ctiv(x`=^!Hgh^GW|4c&|V z&67lU`4#^NjjLhbM7H6{1Q3Bc6ZgqirI<0JZ#+t)wr+Jzc#!dJY+)jvB@lNhIo=`P z{K$1B#3f~ryD7bLQ<~T!8Bgh)_`i<_Hi9te4J~kh)WA`=oUudJDtQ#<+c@CS4&Axy z?pz#<=9BOmiV22Rfa$7mU zcslx|K)~@y;RLt<&Y4{(sN^SYD9;c@+eq|lTniKysRnDu!VigOPP#W;O;%62GXnKp zZ-9^Xh4DMH`X2VUVB$%-Utpa zXurSM03!I!g)8{Fz$=7#h(tWZiPg0Mk3OClkl(>kVxJ(DIm=M{G2?9vib2Y?OV(WP zjXR9aWibsc7vLZVEUH)M@BtjkRIkp5;E1E2jKm+N8#`wqf$x(e4c(srSbKvZMp#t2CqAgk-e19tRXAaKUC)%DXXn>`|dp*oyJ=WM>gGuL-|AJwJwEsmc0y zMvY)4o6q~LR>~W0r$XZla%)ocO4{HIpYq61zm4p3eDktnB!Fd<8=1M`JLCX0`4oKm zrH&47h`pkoGsCIyCPq8vmfA(rZ5=`Ang9t3iC~K)G1&EMeyO6z`Jp?Ulea|3BBe>C zP_55m2a23DaF(uMl_$xU5`!%lc7U^@vrNyj%DTpDc4@%2`dgb=R$XK zhu}X4xq1<4S8>Pv%{~jzTRK$_M_PHM%>jA|Av^Bge+F2*kHz@b?T^sy`(UoSTqFE2pHJcjaw@svh`siuxN?ulbt6* zj~qmyoMMMrP;P}y102u{HXOer!Hmrd_@A72JszRQdN2a+R6<>zL&VAZL~_DSvfmVX z_hMsic5aG8rbW5$>=#mxXQZt)_=@$(K9m5-ic%s$ z!J@AI=Ek+$s~zE()AQu&Wf$t=+mc1KtRBkuV24<^YQ(EQ*1a5JNFHicV;v**<6kjZ!3#_C%C1~YgTG|-TS4vr7BalZHm!lWrfjz*R93)akIDP&5n(ei}Ca)*TbC3T4fRM zS#Ko7Wb*1_nI;<}&E0FT>U^$7E1IG=9`I?`rbD=uPV!tvlDE0;c*JH3^qDF4*z$c| zYkz;jcQ--OxIB4n18;q$_%hT!c!%{lzXJ%e-S+u3SH*?v?+$PKSOPh?&+lAl$C4~O z?E%ZTw{z@aP;uYuZ=w^QyvwPy>e+wzTm` zh10ehW-a>0q?D6M*jP=D11Mp=Y6hJNDb7NSw|Y1GGm3z)ED5R$)uMF;Y> zbA!7r0R*0k;#iNl=lT4^9D_{#*yT!)w}oIw@PcB|RE<2d@>nVRaEu0-{B42fn7hX=NoX=tywl7Zcky>f&SiWuHd-T{Chu5*1 zV|9B;{(3qlr9mt3>T31P&c5gyv2u|>ipWF&?qR>2S&7_a4BRQ^i@({X^zGI_B;!?R zJz|SX24*isnTkwmoN0ZrWpJ~%Sy6%vLR#@pR63KS3p*CS?t5UuQ3I}JTK5Me+76#mUdWgYTG4rgVTECWypRrWrw;(elsy&& zAph_eblj43O>t!I_3+}Q#;Bi%qVofL;U2GpJxQHi*F8da!)9RaL4gr8-VC>PnKUj4 zc_vS2$ZNR}5R|=U!i`zs2BSF&!qK2DH{{!w{%`(<1(31%MvTR^W^@_V_g$heX(;=F zi&ypRO(tt3s}EgAvL-6^_FJcs_8Vf4o*cI3* z=xoG@7o%eY{JL2>RYbKN2w@muV6ACAUHiA7&e;g!^y0P}Al|_P)b5xTUm*kD{piqP zXmL0S6zmdr1+ib&-EkgYOQ{Zm@fZn0%_qgw40g~3E%q!4V&|g|EehNzAz1_+XFDgz z?5l{5VjZvEQ-7A&G$Yf*0|kb$-AaTVgI#Mec%d?+ar}7OM%pKbuVcl7oohdVa@q?F!9S0 zFu{;)6XHRz)L=gvz*!?4?o+Vt%VLbdQ2W;GT@o+OU0HT=*3y&l>(t;%+x);>#n#Cl zt$OvzZd@rvQ+LjK0w=w9z!3eE4o&@z$MM%gJJp3>R^5wB>_%eLBgfoJ1>+5{S=`g{ zW|Fgp?%4Wbv?V{;XM%@OfI*6ug|%MMsDaxq(q|Ar!cwcNm9t+NPR=x5S0%Um8Fqb< z+kF^`M-7xx?Mdfh-8Z|G@xU!ZlVV%T4Ww8zA+G$Rv5>BBq5Hl0S-;r~>=ov1s1q8C zu(0Qplv=q)ZLbF|)~~A->8GGx!#L^?D@+^E`Ib3WyNRsWtcNE%H_nzbw>M4K+4OuD z8oWdU^bR45mry%cuco#KW=4Z9S_1lfX0>$V@;o*$$3~02deiNzlRRo+WBX{IQ|2>t zH|*d5-9=fWh0@`Cs^oBz&g^km6=xjo@6YQ#t{s|fW#O>;*ck^6qwCjj>*#&G_XC+~aRhn37_ax3)u@icw?J65hCZ5yXufKAve(#u*p|{mLgNWJ;crG(^QKma`hu@0#*-eMB}^u zF;c=p_*>8cqpD(ls&^}ds~I@x)AQ0v`x|Pd8s4 zLsv{swyW#n+S9lx=Z#SlZ?5WQj%`06somEh;WWUg8wkh)iK1BhkA5lrHabgv&gcr;kv+3<+p^c`w*!%lM)GzN6wi6TDWAoqyR1~k znfxV+;#-af0ia=galgw2HoVzmtJ2q*Tp)^oxuJ$oMt{R*seAx4p%ZMMP~g zi3_U=CyrnJOR8@hRax36IN?nNhd4dnZ_rHn)+YU!*tgQKW71Hx5Iqae zFQ9$VEme~78j-zMx<-lqKB2DL3490yk|EHQ)pgp>Hu4CG0=H_QUEu? ztHj!YOpv0E>)IDNltSFhGqIFt2s94kUYlx&?)aT=2GA2rHg9-BZs|^yw^f%iB~@|zC3yeDNcODwUM$}JINas3%C(G$naSLw z5Px!%6_qx3+u)pOwNI^fyTZxkVaah`AMOt|x8u|JVz;^NcLz^DYHn$lAyl%Zu|uZs00JU_#=|m|iB#g7S#BPu=k42Vo6w zHxn;r1+(j5-OH-vksCE%Mp zZn7V2HFOAC7AJS0DL~a&KQc*n+ifAJecwbE_h>ji9iR%m0)F@SWAZjxd=p--_qk6_ zY<-Y^NyBPG|GXQ{=U>e|x)P|_s`PUPHL@&Kp5TnAsdD5m=Z||X(BS~_>%{+hfr4p@c{~}3uEzc{+)=ES0mdWYWV8V!JV*z5E z>ah_hVRzp99ZpwW!x!TsH;HCq4y`>D_56}2j~aFsnx43fJX3ED{%yF9MLu954jy%? z=74ln>-N;GS$xK8FORT2YG7QJc6kQb-2C!e`mC+>2bo5N(n|stjKU7?F z_M;SmM^QvzP>deaFUd3~LV{qtu#8D|>u$69Ca@-yh0pje2~0 zT7`8k;y%wzjOU1A7D9!6eoXe^$(C>O z;J3aKnH*aXL9Sx(GhB~jBs?WPPfn;v%p0=`x40q~gmrt}RdvP9vaeRHU>aL35GZ_f zBn%g=IR!4eVe7;++Q**Sx|x%tve)@p&CoWk$3aF$uO9L@4A}i4? za~)nY8>Zp174sQr@1ey^ay9&5ac@sbot->N_5N%ns1Io}dq$f=NvF^u*oG6VPthP7 zl`$6GzT;HKb$D{TCGhu022sP7AUfQ8!R^vs{_y7E&)bV8d!n0$tZe_;+hHhV(+q&JV7(yiAZ=1?!||e zZN8>kSid^~qai^TfkYd+!`UnWBlY)+8kG~9A-An>&(kmgXZrw z_<~Pc1mQR=i~?FxEYkU;+uwUDd=s^!hDcy3{XTr1|&_RkECeQGz z%d~9rJv1!;qPi4Hq(44#WX5sJu8w=Lqqb2){fV}zXp$?Zv#2Q2X0RbYR zwu?YAltLbXNS4dD&8};+hsDqGL1?oNiI9YD2m&m<=5*=^8a@#IU&AU|uJ&76meCof zhP)oaz3;9nt5GaN?#6G&o_ASyiCVOAGS3!Iy^B~-;+F}|wNoW@qy=2R;Z}b)u*qs76Ay5h7HR{dYQ%b*rag;|LgRb zJ;0jlYhlh?!c5FL za>4+HdJjVE%9WFk&t4CZrFO4an6K)*Wmx$d>PqrL=T9{tp?N#>MHKHhD#kq?>a07S z;mvlQ`FAZIMnu?!3)R9#bb-nJ>^g=`(Prlgwy=FX+%>09V0jf-V3wwPDl*3FHN4?$ zeO}UOANHvF2WD(Nt|v3=KZjGx7&9J|A9E$y zm(th0bna!>mjjm|VdBC2zd+T!2yXfR?kp znC?8=&jxuuYXGqW()Z7}qDzks4G&5>r_!;~yu`yFiv}PT3mCH2P4Ku@Fq2eNo(52I z?7I6Hm5idiZYnzv*z`N&WlMgaeeaM=JqI!g zI<|mUYCvFQ`pgA+%KP^al7G)+L5%K+COp`t`j61+ii zF<+ETH1|q|>wr8R4z>tgfFeQv=?mN>)0f1SZ$U7O^8{1paM6#vUQ?^nVccma5Y{R} z?pM>Q(k$Ed*4(muYO~z-TgYD15-oGEayPV*8yC1!Kv{`>sE2!8Ohw`RB3j@6%Z#+R z6%^he6zhuerAl-3g`R!5tVdf(4IvVKwf+jGR{$>shM4P-NpoCXk#yEGf5*Uj*ze&$ z8NP^Es|u5ad!johH)QS&oZKg*MyT{5u~kLxn~56;xo&glVwTsyOIP{#r4#*%9za2G z_hW`;3&1axu{0dy!?@tm;QUE;b-96-%9z4tRAJ%TcINXk8wK*~y9BTHG0<;K&E}4_cW$@HwL^K{%NeU&_uX$ptG7@4;pCaK|O6&p4 z&H3?ro-i9Vg#?88UAKAkFGN#Za>}bHnQ4uc@)15FY|uJIjT0sXo*2xgL!0$O8ZXk7 z#0lAl&6BdXbG7jb=jc8y1!ZL!m?lobaOCLOGNaeTdwfp zT-*oQ5|fLd7d-~?PEOBs5>0dUpnRtk*SXAHRLwwC;?diZk#GWlTme&5CV!jZV>GY$2sg5sw0;#2DJXP ztKb^38LQG1NEHSHLNP${E75qqbD1m}OZn$VRUnFpj^JTA-)~R@s3qg_gQEkKVRW>) zwm_`!Hw^cOGsj=PLDj52+453^-_A(ozbVE9h}o{ zr@wx?38m3Zb#VL=P$o8vES^V5TRTSJf*K7v8HC$@ zIj}~Xwl&%wLE@{?G2&2HWjJB53u(hJ2HoBnEZrTxR}=rq9abh zcu$HG(GtCaj`rQG2e$VuDMzvHb=k=E!K!j4Ez4XQ_0H>h08#V;g#di?p8nU5qwzD2 zX;YarJEjwjGKM$4PLB4sMwL&|J}U;fPVwwi4Qzi?LN+6FcOoa^9#Mn#=F9JzRW*{?jWd}02E!z*8I2P;RzW4<^OlI=Wf76T zgvm=VqVtnfJQtiz?6Jl1-Mu0XANY-YbLMWz(UlM?930?zy8s| zPKVl%_qpqk7F_xLM$@TS8@r|5TNUD9lM=T`wo>(_PWWgRtv)XmEQtv(59;E%V78v@ zKHDM7?jE{!BdsaEiw46qNvbp`_xF(EV3y}|{U0d1i%X%`N~N_MPFieV1hP#+TfWip zujjqxk$Tt@<6Jsjm|?wp(^3DeJ&khpSHjRi=r#uFV+2SUMXf4NrkYtlEEP%7bA31F z=g--{jK^WA?$<5YwG_)_C1f0T1}GJP0h76kcO7nhqqnNAKqg~wcl|2AQ}V?aUvqy1 zVzhizKUh|yRT;&Ywt^SWE9>n>L9vq~1bGwGLya=(@*U`5Uf=+&uGR&@y@eRU1geZ9 zNCY;0%|>CBMeaI#fxfCd#~7LI&1(QzOXWcDDq$@`Ai~n6ofA@d204d`aphp?%df$T z2RRF{8wq&v5{Nz+3;>t3;*~yi-R6L`yPo>2;WRqEl;#b(kq522j+?7mE@jjb5p|2N z(p{{F9v%drR=(X#=@o7*A2hmc3wg*^SAj$i+uV-=afZ*DB-*sE@vdGy0F9!OtmtM* zmSYlfbfw@O35W+CdgJLdTm>PrKCA^Gq?l#H1?IAw{h9#zbaAh%29I`T{?{| z`u+~};gbJ5%EZd{JqhiPw*6h|6Y1YrsBdWao(cI|W*4oYlfC^vG6I0!lLx>)ay|h* zRtb98-y1l26{gzLqsT;q<1n0A-=sJ?X+UFBzNt??Kx=%+Z$jJu<-Rg*> z88tJMB$`B<>=f18D`G>^3f(Qj8ixj%VVsV8q)?KL|yCUp9 zP#mhZV)euFiIV@8FWnjxuylEY^rQsK9Zn|Peb$uubOTjU^>{REhpR-8k~zR-Sy{X? zyx?6axliGtHn%EmP%Y9~sNMA%^0nlhB|aM!I99b>h-Z&&QpMT5%s!{$S_BY;5nx0v zU*xykx2~JRyF`WaJK(-Xsgq=HQHM*G>$Uc;Ul3YEkfy8kT*I9yWJGmTmG}u3M%JsL zJF%bO>EkMq8}8$w-WZ0c)aR8y2P>JAf2pwWVT4&lqlp&xqg2U8!eUI)6U#iA(uUG1 zV6w+tc|=G4R4*?ENeTs`5-HY;9&B*=@U8Oo7bR&zl?np!wz~ZW2ZXNGx^f6=q1854 z$zG;B2#Ol*thz+_uUA4XaUB#jb|J&=ND33-uoaE+;!80V4%?fSWE=4sfxd6Cf=$F` z#Na`3(6@?pfFgN~&@upITlB425JakxWE*w`d2Uilo26Tc-r)>FxIG9X5>tL4<^VaD zdBBye`VAURJ9EAb%HnVtq6Y2!?iU#1

@Ozx+p?y?mi`ydQ!-wXs$H?0*O}Wn=Zn zhK=CSh|l=C1?MeMnJ+Jg&JU+;$S=*nDw%i<^c7(YvSa{lYz|qc2X63&ueVGK^2g5H zoR{RMw~bc%YY?|!pR$biWiDIh>Qr?bN%3kyP0WWe14%*j6*9ExBeddjTO-^l5rvjX z@OG~m(=-a|h~;Nem&GQ3m^zFenmUR$nYyWj)0UYqZ`YmEyqX?hX|=^#JvAwM@d)AL zEEyCOpKcGf{3=VtpF#a;%}CZO{ggp7T`Fvyb%><;!>-tFz)huNO(guBkTE|+3n|Ul zjQT9f!Fsrgh$*V*;XX?=<>2aF(E*j_S%#FkD3hC4&!j4@t7-4T(FHLOgVQF^C+YQl zQ!@R=gH9Ow3+5OKSi2~x*NQL9&?_td%lD~S3?Vr_NrFjf)W{0ECCcTcZ)JOrFatT~ zIfV2^W%O)^^!X7g$c923BE|hqnbXlC0ly}_4qmVBbgetpX{!um#s|%!&~$tYR*s6C z;g?C*yiB}4bKbkBm$Ny@;+ym&)r6CB3`e=Se}dT%UC*&3(SUE1i2)552%fmM0tX=( z!^IY;VI**TAcKFu(cW7>$r^y4SN8dwIRH0GGzCkd>7UpF1!(?d!u5 zLi4ICWF2~hna=8X!Lg{~TenePqXLtzDdZJc43>^5qdKA+@r>UI_b7t7pb>>@os9g7{jl5WH2(ue#o}>mTikl}X<|y1 ziBoJzAO=?&Wop$BL))jEfCGk`g|?DO>s3`zu2?%mVLRVZC*7fbiyxR*oP$0UcCTPg zuS88(+_`si@$_&D0@(X?wMXeYxA1|lFr(32-=-dL{LBL!_D&|C8|R0DGqL0*C;6)h z`bb8Oe@;$==qC_yHf_*WcZSrI}EpoJ7y; z=LnuxofL@M(ND-<-uQ51=ijpW5w;bY4tPkD9Dr&{EB1I6<(Y?U(rkQB-A_wW3ck*C z41V?B>pUwRaAvJoL%}RuD`GURJ)lTF#XpsP^iD{m#IePln%WXAZI0jp`NX|IIin{{ zhJLKPmhB=aN_*v?(tzz*oxaO zvwVJ%t$$js6){er_;tWW)b-Ihz(vP@QPHpCX{N9SOdLV@>Y=C(%rI{Gd$mtw1~3rn zpvpu|N6`v#OF9pCNlF3mz#-T3`G`H#HFH{x9rzd>TJ)rO=%n5?p3;pSo)hiesI_OG zx+jODix6ctm19j-J9uKu_T&IT8oZXuCeP)~`IK8ynemznc-s|dyUvf>`dml6Yl@=k z_T;FQ{2$Rkt!Z z%N|?Tvlx z7(4uy*;uaFWz&NP-F8PwaOzuL1VMbFKh>V|1R#=u1Ofd?k=chAp~SkdL^1!y#PF%j zlzaMkd`yKjWYE=Wfzn4GIp;RBE7v$XIQlX2#3j9-oQaz#E;)z7A*I56*k0&BnL#|y zK8DEr07!4o$@wdh&+TyPK^ir%)q;)U%DuZ`F3r`KR;Rm#MGi8KdZ}fgCT`CCh*ERt z2?k_8W(|3BMAGAXsuWtMOZ-whCJy>4kzgQ&*6*&t$?H-E6qTQ(`IJ1xWWi=}%olGK z8iNg;b&DgU{b=xE*_QF?Wj^B-K2jvPM7N>aXIM*V=GKBj5#Pw~V{NUazeFE(wMd|o zLU3VLB!g4F6is&LpR#Vw;jVZAeK@rgU}pdU5CC8m=)(@DJ1_s0D-sQS-5A7Ry>!u~fr{~TofXQq#U=}&R^8>T;luK$*$ z`y`F_;(-whal~bUik;x8T7oxVyUs0t9z=cXyxWzjN=rHE&j6 z(dquy*VWah&e>=0T_JKZVo30~@BjcHNr-<{001aH@RuI;9eBp3qp21A17WWqCIpm^ z;O~R~d9N=e_7!-2`ko<;INkq!5HJq? zUpM+c2Mo=`|Mw05|9AdBH~fFx`G0QsKL?-w-*=vpql{s9Mi0{*dTl{B_kDYW|Mv&~ zYd~)!w9`PE7q&l$;0GZ!bk4doHty}D!ra4X%u)vE$MT1GY zBY6WWYCn(0;ZdsQ_|A$09$$kel1??kdUVSq>nGPQNzIRlP<9`@PZAY z_hzJ5eYu(%s9K>*(63Un*qpJy2rBugoC;;=Y{V7XW9j8_H^F8TQ{sE0U*#+py5V_A zrRdlEvuC+J{n1ki&%SDI%J8o*%QlS4ZT_vy(+<_m^2$R(e0$5z>72~{<3J$ztgI|7 z3Bac-Bfozgtz*_oHqC{uoqxZST^Y*KpRV2x{*!X{=4vpmb)5bX)z^WTPIbcQ*?*JQ z9P^Ktzig4=1id%mE1O>|62 z>0rZ}>+61cu=0;~I{9u}xt7gmxuQ&|;_kxFdFJhp-*x*;X_Mv>5hQH3ff z5mHwt{{D44d)dA4=FU7A$N`Iq;T>8A%?89h-GaI9=j!VTx z21=Z|m}tZGUd`v?-?8K`D?Q*%O>73jq&KKG*<4bS)S`G|`)u&Z-D@Yh|K@H#{k!n4 z=Qy20MZl=>?Xyd|9o4K;!8lwew@dP7-}WzYpNAp$vj1T1b@7tYVVQ6nj{q(tv!7=J z_(FS*@#lRbyS`qpO`fl9h5}}FX-wT8SnI_FdcLpjw~C5 zX?+d73KQEDsOuiPDUR{;jyrVNpT(pSj`|x10jxT8GI0NUq~^%S2YiNG+IQ=<@-F8h zABJFdp@FUIxk#@s`+c<D(dUoXo|>}qH}P$Hk`XHg3uYJ>jkhC%a{y2n67lu*1X;#N{{^Wl9U~{nlYkYk?LNn?4v{Z<#3qLLypux4j}A!X6(6_#1}OZqgM)gtpvTd21&laJ$zwOQqBjdF|0xgY$0ilcv?!uvD?eVk%*BI(ptTzBtxlUr-F7XZChhp9>%(e(tG2 z!8_GtJ1g}LIPVipXU7Hln+F@N8u8gW1M*{RW_v@~ie>Tq2<81^SqlFVgH|Yv3ZkDb zM>obaN#Af*ggyXw?@u!twrD>v6!sqQnQq9Iaw2tleQh#wzh>_|0*g)IpFc$G0b_?s zNAElkiEsB7Vom9L>5aaiEqZmJ1W55ar$wDcCu-B{{E^~t1Y7m3orB5r9mdwj0;cFVKfu1X~jhsCeC6FLd=GRrOB zohvuno}I0j{{VyK|DGEb0&tm5x&1)II!I3Qnqw~GrPWl~jq{&CJq3%xO6CEV_4Jx~ z4$8-#e#}n}y0MW}#lDtsjGQ_@erd4u41(uJGbJJW#4h zt8w<;tUd|^7^RN$){YW3#lR!4Ub!>oGOV7oUFNqND)KQ5dMDjsn7>4CcaWItmpZ;e4;ss!v8h7Hd3C*mM)nU^!H$(Dc9|MWRSq&-=KA??5rXt=`GS-FZRj98F$>Kil5UgD zc%=$1{i?y;E;K#oNRE5TODgWa+u_HXe>rt-d~~iOIacz;Gc507@c;v>y#hFy`yDdzX6s!D^>1R22EdgaSM3 zbWIJj`RdBdsO;bbdRPdm6OJ(KG^zShO8W9F-;U<3R;}wWjus$Rtb83c$Uj$=VGDaaPCAVMg5u_D8_fnPj?B9lO7 z+@P-^W!BhOfB(qnsO>*g0z5n#rvJuSe9@$|w04&}k1fuLyW8MEFI>XEy$9Y&OM@SK z&Xj{}})TZSV`S%V?dPt@&&+(=swb%TK(u0&5%Z z_UCJ&kcnha5K1U0h(T=20njotMvpZ!QV6Y`+^*e3JqGWc~x#9&b1|NGfr zDylQrcB1%S+6)m&i%%2y12A{zM5QJtY@_2 zgb;v(O7nUe_gr9!>6QP1_FoV*tCxy|=jrZWv`BwHezzP?df(CfF*XgVnVHu)Qfz!e zP?M0U40PB~yHp-m zHw6Xl5n5pEZ@0lhEcx-yD7k6#-Tftj<-!sIeAnhr-1n`Aey9%@R0s%POijU`JazT$ z`T6aprVr527ZVC=9HLorN-8RC-Vd*8DwOfn6<+^r@kwIa_`U#daV$%k9VpaZOeL!v zUy)BHr@C8Gf>2khR9hE_iz~#-tIW&$!O}9iyxU{X zen!TxyuK_ETYP<5s1x>l93Vvx9ku3kt3Az^CKXxN6M3twdl3{dDH<{9Iw|qW32EBV zshaX~a_VXnv~&p)q@mSJB8GViREAr2Dn(mrSO9DcsRX*t69z088pN>Q)sffgXyjQ3 zQ^`M`&2)@$AdANkgO?hy5gv^7BRAC&N*>4u?SM1=ekciaOc6Oukx9}hF@!)NTH5IJ z^k%hEL$hLY>k4z@g4x<4aaj};b|ED6965X}N>ml4KXMgB z>5RARM6=d#^3A$mLIjl0i>PjXkxIxz3EBYogVl(Tl3xa^1yC`g`Y=MEQc^zi^0EpG zBPl9cN=a$s;rS=fvVM~`^#xMlg{~u8Tc0vJyv8 zyPOgCRg2Qmk))0VsWgYk~LOUgXer}rHwQ8@ht&m$*Mj*xgHFs zevFO|l+8$J^+14LTUE42_A$T_%_=;o7D0e|hlHdI2^m2qU0YU$gijEmt#y^kzFShn zny&aeJ2$sgEDAn@ms(OX=EsjXLqlaOtN}@>4<9}#%Wk4#Dk}^45pyIM#!IRcK>-@1 z3hYc1)zwT6c4iaxW$KSNj+U9q0l1$;=~j0)W8EIvBqnvF5?pAt7rr~u>TmXjUGCPv z2kM1k83+s8j{W#g`Lq@f3!6Myl4$neWM-;9o3FWe@`%(E5B==Q<45}HjR5UKDv@4X z92yy!QdN}@7+BucCO??aOGk&BpMU)<`9peBtsZ=r#GgL#)0IL%Pd_TMTCuv}`G zn7DoYdg2e$LrDpi4awwifY_BMCLa#S6Z*r1h#FAb-kud3tGqi>|MK!6ow{*MAMnyL z=lMAD?e{+lOk~f8D}IMUh>Xb$WW?4EV-&%d75>*FK7;p!ZvT1hC2>sZZfa^>MT#HS z*8@k>mA7^w2f;LWey?01x{ec+NdX3_Ha9m0JG(g%QB{lkvIiewo86DRi6s~m1*?^z z(9nUXD0&I05*iw)gfe*M(zjs=qMDJBiH?lStgJY_yl7xysj&y}sR#;n&8U>cDHK(O z4K{K+ADp`APyb;W;@CyKgA{nn6|7P^DhV$86Pw+^U|2@~_yG(m zy!+G9)&UD-)z^ao7+q5%(ifSa-CUTO^nDx`h%~(1*hv4)74LCv2EI{nvhe%HJ@^FW zB?Ge$e7}GpV4$kHc(QES?A#~zidHQ^Qs6BrWWffP|>Ya6kyNkU7tU}CMCoKazB z!NW?2oKYnFHj)fo5wDj?W@Ey@fFGiwDqGtSK+mo!QjgTH+=S$0y}<;d;{|oc)AG|b zpSBKMNR^_Y$jC^3S0)gSwKj5?%A@t!)(QyxA|;8f!WTQg=SoN*vs{?FzgKrWrka}R z&Hi+i!W>H`aylnCakYj)UfSYlPU@cKv^%mwr;U?WZF;%_8A;e<HRUS8Ne9%c%E4FAa2@v=~O!|Sj; zaJcH(hxT{v7pf*dzXjqO<+rD}#p`wj0;7W6k!?P=+|p7~iI}x>wLm`ubudHt=H#Sh z=+;0$IvgKWs_gNCWv__cx;KL>9t}$cEPEA&VEILdsJ$(NKstJ5av-4T;li z7^tp+@Y%Rj5A=fuiwcwZ?1<@K*hNBK8xD&pmjLTI8`BdlKVngx7Ndo7ZIV)flkVU} z&4wMEosvKV?&mW|Hn{(+ZJBLOP7uzb`1#xG>vIHs0+S_ivCj7jBNGY`N6%DbL{wCS zMk3F^d+JQY#E=)r^t{{~i>f7+*47?8CzWcAK$!gOQPFPUiXvRj)#mmvATaBsy14MF zsg#qQ)T}H@6|yo-aK&Sy2PHx$ z>}@J>4)a?9IzvEW%5jLD^&u`$11-cQEH;M!+MB!8_gm%tElZ4zE>hs3oF_|KYn zC8wnf;deTEIa&UQh8C_RGrD(cTvU@fO-FL(R!6NnaNS? zwtjGf&w*{)Yj(4n4;PSgwe}UOc)kaKxW0#fB+p2zTpsYT_Kn_$>S#0oOR~rLPRx$q zYglL~MGc*31#bnpqa>@yP_DL74C6h8k_W+H(dL zz1;|(7rKp?F@TaHV|p4ptTqFf&umt$4DM`#F_YWG!{Eua`ir4 z$^QGd7(-B$jvQ8KvMbv(gO6^rcb}8vd%PS0h;P$%Tb#T{)8h_jUz>RU?bg_FilG*} zxjFH=*QfJ*T>TMzP$6}>yQ1cWX~?WZ`W+B^J4;#tXZ!^i#@6O$o<13FFd4|OI+@-t zfWcRj=Ct>U4x>6RC-{yTs(XEHXlO_qgoH3x1Ct5^7ErlOg_LNtIs>txm9{UGl=y&z ze5r!O`F;NJLLENmM3%L#M=Wo#7}y(N$fSFq;{QfN`$SJoB91POjuTW+YzAfzHp9@S zMC{1nhyyfN*ZYcx2g#--gPoyUl%G$Zn{lEL?#*Qs|8UFX!={T1f9*COhjt;TUw*79 zpgT9RUA*QGIwtKj0FW2@~P+nebbARfO zRrdcztkk!>*xq(vT3&%gSGs~9C!l?q#`4lnOCR{rTvibfnaldQ!Crw{brq=avili1R(J7 zzC!Kf3zVGbOXHqP{zd#)JX-ZypZFJ_o>@F2E^p!nKp?e9(UdR4AgLwdXq)XVV@E`i z@;)DI^mHVrRy0&Mx7it*8j%68Q_}=6NVr5;^_97~);2b=^_Fmcof=sWGJU=Ihx8po z;xg&6(c{|%86ZN1@QEK(EZ60qs92R`t>bThI2d2=mP|%84?HOSx#~qCKJke-GvA7S zO#jsD2B>Zcex-BeZK=F(KoMp7K0P}7G|j(8s%NeuLIH6V3}uOLRdDe@|K4z|?Pzu- z1vsNH5wqClr#`s7Y&c=@x$13LO&>MX`8K%qROc{HOX+j}7pX=|spNdK8zV#m`n??h zw)TBkes8N0=pP)&_VZ(7w{BnQ+5q1=2;`suUB#O1pJ*7LNw6_LKp!oePc*ZF$xR&O zjldp0>1l7g)$d>tO&IE#UY4BiZ3;hj0+$y}F{k_w7l)YPk(fSe=lgDI@22&EN1eB}pGJ5JOhsFHTxAze?7Kx(*E*Lob_2$HB5+?dbd8r>K@^J-}$!wRbg04&z)h_JM2AQ@6C^_-~d4s=+}`K<{d zxw2B?;4tFx>ySHe5Io!GqclsSH=Jv zn+DU2G$19V+}9W5^JlF1gc}58Hd}iVicn<=Fayc)Br4!UIOjT&(MD=2h=f zeeI1SPUdGcHea=;TxN1+hRojs&|=unSlT1Dd1xJU96E^Kx%9g6RqGB`PgJqP94#y; zVp>~_km@nOYMJFm&(HTV^f!dMuI|?PFv0GUY>2=C)fPOE3BDuTU2Kp`HzcjaC>M z37-*}ioE=bjKYrPd{3*pF163Zp%_tITZ&d!{P+3U(TlpRt^~d)dH_g|C`o#aZXvaS zeX>j-0CJ&eSMab~JlE4Le8@K0hD^&|qMze5WmEoEA5C8Fs^_7nzA;mBZD0o(Hdkxf z7C((eUa-gi@_k?s&Tq`wX0OeB)^B4Y%XlQodCzCGiuj7Yz1R#4){e-K{a~W0 z9(~|feB4)y`Ref%FaHSXtpwVO3p*OjV$Y^1LJ28Jpwn}qHY%B(nWD4*L_0_~u9db$ z&EeDlj=0Hb>rY2S8f~j)yp{*8ZWQ@9S3yp|r#Xx4bn{kf&f{XC9}74;EAaK7;e$qv zT4tD)e$Meu(ul-`hWhhw8^m7v=7J!OEjGR&&H|y{#7uwL5PlLrLO-|Wd>=jRj{kG^+x zDYcv+z1qzvp$i~UnoLjUmyO9yF4z?tnf-CmlN;{Lxgfk*#(ZApcEbiq(dfa`jt=-x z!}H(C+PT(9;pAE6N&^C>kz13^W@raili2R4fI!`|QGH8qffID){!9d5KGC4^jhti9#_gzoj#jjKCpY6S^Em%cO|NYWX|Fl|M&_OA161WMc z0F*1ReLMMYF95?)Cjn;?%vG)1U^h)bv4|7~AV(%*+`fA)9{Rh(dP&OFz4_DKfe<_( z{(<$S;8xEGmn~eG0xWhMe>va6dHMRNE0Eyi1kcjq1R9#skjamfmfH#6bF=s8$|33_ z^PQO)IBdQ}xU`g%#axL=3=Hy~UN$0@pIeveky1^z1{DprTvZ(Uo1!8j&?<1APWMqn zHSo|7-{xA2aCSQy8o2}9;o|Cq zVGZ{W;d`BDo3=QCqcn@unauaRJ=K*{!mM;}sEkIv&gFdR$l{fNo1uYN3EMk^qWHek zSCNoE9hJ~(xs6*eCUgL7sJ%NDI@cyzUE>1-)jnTU{XmBsWRPB{FI%22W;x!?fdRfR zlq3$roF<@}4fjDUBl9=vXLq!e`4$#y;$)dkm2UnDT&xHnNZHQP-XymcrPZ_p!nGnH zjWU~qI`t^z{S(0%^x7HPDpB<{^d79+c(cbx4w>n(%F&g!8fIp&Vg@upXFZ4v&&_#1-f$)-TN)2%-+71@g(Jg1 z3@<&+RqFMOW*B&m!AML@!1`t0c?{7`|G^IN$q!5C?N%TLiPPyukoxTQe6+H)b8|WY zy%(Rgmshx*MW6YghY(lG}H)({wsvq7Z*OHl zym4}{r0VKQ0eNqfRWaJc#zu`|zC~?a1h*5oTC#$IKo!Hjrdq2v@{1|{Hx%#$7Cf)f zXnJbw=I!Gt$N(o85<$UKG}Q9&8w6pFHjLp>A;81N{9Wmq{)+(*7ZbPPf>Rjzr|(K$ zxRWYAI+a~lyH)K|{5v0Tl$#gZW#lrscOEpzp!I+xF}On4+u+^~lptXQ&hL+Rht1i& zy^h;h2&P>VvFQ*WkJ%loTtxLht8Dt$w=^5AcF2y^h9+Qv+Cs=z9#+;5w6sXfH6Syk z=5$W-G?P50!q-Q8($!4ft0xW((`Vb&D@3I;fNF}bF}D{U>W zH>oLAj4JQ5dP_g^zb;f8j&nO#!$S+kfU2;UW6hHX;-!D-SsTtQX#>KT97+~NGH0Y8gU||#xsV7B zntp_c#*(RtUd^u?JQSv{tFd`>2VL*%R6X9>Ba%!^9y+fHd{@HU!3r1~oa))|ffI3%3l>|J2BRvPckg5iUUc_&E<~hc(HB zP+c_ZZj1?2*837OtY?R$JYnXbesEK@0VAxZ9>Xdg0$@mfYz7@|wiO2Vx*MOFN#gBj zO0vtIZzjc3*c==zxZQ7lDHiM)8OwU#ls@}G^)0uHTy8;Ml?6yybR?$) zSGTriJ?zYGKJD43t1!Ho`kV?oIy*b#N$V z1{DmET_W$_>2WON%r(zlfgZ}r;93k0u&}e?m}_ws6nZy<0YcG;Fi_=My4vSnT1G%e z_aVlA_s)pN`(?T-@a~FMXwN_8W}lgwcG!GhA+#@6RY@y_+c_s~`SNhKiV4Z5Hh1f2 ztDl;cMF!@*Z$mHe7x>XB{i4Z&imTYQud{YLWL<5d>vpeV~&XdhwVcwna;mDTei3k0ZDaM73@Y$PG%%q zAOrT6FDum|@;Wc&GRi?RGBbR9WM!J54E7FGBMs;0uk~JGuXi8|hSPcLIy{e~lKTH` zhkxs}{p~fGpTWRQi`qDv#7IuwXMJhp8}z^357_%1r%@PgjG_K?+Y?k z*I%Bg;SnfPZjxBd-R!EBXUo+-28@x*F|!fkpff%6B3YW7uQlFn_RVUlgCr@rNM|E zv04G)&B+SvGnX>5Z%Og#Crn;E5;35_BWPun#sB(r`bijE#b$E+GGIQnuB?*a@lN05 z5GF6^ETlM9E;$PXohPq_A;Eo9cP<&zC6s)+@;Y8_M{~;rTp)+4Z+OsNn3q9I7+96&ESag4U7r1cQ*V7|v(-*zC`4$=xy+S~Az@@UfYA&nW*X zFC@;?+a;`L!>MF*&|auv=wNZ?&o>&ZRBk7n*6)4Gt*R|jwi9tBn#Q;0rzW4U!Ymh| zh8DcYZ>K4B+`qjVU?Bs)X^szi_uF`n-b|^jB8l?+=`JxubyFfVSdT|Cs$Son6@`T< z2~V|0_q;LF#i#5KXR?e(;T;`tnw}n8c5pbf3?lcdC(NvZ8$h_A@KXl`~B6+4bSMn+<_#N-`xqb;-_OWC)1+ z^K;AHq5E45OKR$v?CO)%*Ty<3CLuECv-E1VEhizq(Z5{_U0-8Mhax(vURyqC=l>pX z_524Ta^QPT0Q2m^!K0j?E$LsqH(&NV`0z;AM(a9W6cHcrIaZ@tZ{J`LEj_#@pFOyv02csN5en5Vfl||4uB3 z`WBYEd8Sr;JH1G+nZ%%?p+MHc;{Bpxyjxt(RA_af)jXALAQsd2xMuU`v*$CY@ql4t zl6AI<(qp;6AZaM*@zhruJKWLuV?9}mI8~MtHU5g@;%0a;Ix03hYQ&rb`1N#sn6))) z<@$qg(N?i;7lk}KgPfd4LZ-3GHHj1WaiVL>6bk`>gc-kA+xaKRl(Y`+OA5Y&ljS61 zc^ISm1l~yM*R>fBledX@ewJE0px`WYr{hCQMfJS3auE9V@3XA@#&A;T!LhxJ1x=qV zD8*%*&%v>>J`(Zl)fgf5>|*n{*Dp`k-QC+;On}RwxGz^k1nlcM8Qp4It7BB;&sVDq z-h@^TKA}R;E>*a@;&<`ALb_BfUS%qM59V{$N@T@!*)EeJSn`=vW(w+Ncgk4(y5>lNE?LGR}I?He8qLW$EpncqlmE0 z%$e=(>rOjR?40Q(B>oIc3GzgnTwNc6{0Y?kh&_&fF+}uix#w|YTU80QL=1jkUQm#V zdmwHaTVL*%K3$zXQjcwWq0F3jKq!3AVH={f`@>=@Pg!VQ7!L5`iy=Hf;qG#fjxMn3 z9FV#rr73pcjK8XV*qwU$5(p_^dQ}Dc#i#K#iH)8h%W zS!lc<>@-;_Aum|YPB>f`L{K@$$5T_;y+PwfLY|fAFeAJ5#VYSzyl-qQcn`27ba+h& z%P-8#U`E}pb^1neYi^X3)HFq%{^qWBpDaGz@!~BlD9Dj+Kq>+{tE?S#CTnK4+t?aF zhd8A%ha4s;PvSct(?c>pRb$1ftIE5x{8s06fOs@iIu7zzf>nM6Z3ekh*$l^E6f! zrLEq6XDt@Y-tsXfQw#<8rodnKa%P0)SK_ujZXK!n z<)_wKYUYTI)p|aDDv*({C-Md|t~;N#Tb!C(KyxBo=ml6GFLJ~A z6hNocaznJ;_ISx7in=|kzoPa0(hX^yG1eYGuDTIVX}Y}DxgzYl1lf` zq?eLv>(w)WTQZXl0FrZ`BG7)#ONLzeGfGnpyPo+(_nT#n)*J4Q@Rg{>^5{IYxr6q# zZnC!sYnGynC&c5t0D+EVlU89F@5YA6sjgQR-__g~A=qhTB*jTv=MxvtN7|mv_}!h8 z{fX^`hSiP0b*?-X=9=otU&IoUXRqn9`UMG+4>cP7d87`O za-V_ao!u~Uc5i0aB=3Tmn_e>(pKOjY9DpP8v2b{2pHnRiApUZ6Z_X){K$v#3I@rZ* zrY8tlIr=K&Zg~fYI1Pn~-LD>>kLTcb|H4!jMrm&CwY=C$=njqr##@{~&4%E=qAD8{ z^k``{`M7L+4AgB?*%UW7huc~!X<)Os0*NImzDV^31r>+&{1!rMHk-DhuQ<>t7GtG1 z8YO(^Q<1ga^aG9--4+0g!c$*VoA>?pHbnF)Pw7pYTQsTqFovPw`6c2jNpA3OK1r)he=>1}ceRA(wex5a(kSEUCVQ~A zHf8()t1Hs8u&9}tH*L}Bb2~ccbYl@|D5aoS!u%6owr@rf3MlHkS*5+(Eyp95?r3*f zx)X*53CfaRo=WWWLIsnp0(d?X9r@B~cqusm@ST*gB_HM``H}NL=%a%!!vqwu^J_p6 zcXnu;@}PI6b8iwYQFD=^x>^zj-XP=9;OTj(DP{)$))Zw{LV^Mn(nlsJU4*c=paXkG z`jJ#;hqLb@uAI8cj%(vN+A8Iwl@0fj`regKe>JZY= znvVB0))nMa8uW8bo$)Xts_mD~wa%uqBXy>eCt)vC)i!c4Kqkcnf$;iQ&_iR3{{>a; z{%&d~3v>VQcD^BM>(YL6lLT~4)W5AU`U)O)=fnbI&^lYHP-JY)PsuhjGm0_@8ldR4 zAR)zcJIb?jy8rz!CYR;=fOE%K!TL2LxwKYET^<78c)W=jK!qBAJzIws5dq)(baLDE z-w*(`&b}b~!e7=KmLQ*ytHVmj*qxV(ef_irO?EJXJ4*W_x~<-F?H?ITfq{E!)6l3T z58vTJ?FN~$^s)IBpgI=4#`R`J(Vq?)$?U?lSh%n*$?0zA#1*1kdg@0LCFOmW(Q*Nd z_6q9|BH&Xo;Jr9cRHC$^-GT*xeXr7^>IX|tPtb@1lXo%U2OV?eV6ncJR`zH>L@&ID z0lG_S3(RLjm$X7hopG7|I$!SGI(!ucmte_fdiuFler~RmO^#=y;h;3$642VAZl=2t zi16s?N$LCDRHUZ>zwha(PM@)l0SpNXc59u@!sO3-(tRW586^({;R`4CJ9wJ3%)))fO4^>_cN=Yd=m;G*tdS`aK|3J5XnXu-Zl3!v%=ipXC>lEf^2Nk zhb~cKE1aNEaJsQGn{PiwK{KrIC?9IJzvcwg>g!xC*^@RKOQaIt^{G4VUx?Tt0EM_X zcUDW{V^^1BV*!cObbAOt7pgV|Ds({MC_QE2tmDOwkQdh+9Lp;IZ)#s5DZvQc*vN#V0z)&tntE?t_V7W0d0JMV`;a{Hc&+N5|h^WCUAl z)}ENn@O$ENs`pM$>v}sA`OI2{M=?J4emf_Zi8D0DAl+{>o5o(cNyriX$i-y`-=nKo zuyOgYR|am2D5eBWkUEvbpb8*Lr^?KP>-pRqSw@?%T{bWda>e`8<;1;^Jas6?Jq*s%gMQBnTQ*W0s@Rb}Aamr_P`rO11*VG><@D5+*+uTxa|6HZ zBlqir8f&8GiIPaX)a>l+$pTp-PCHT_p4NkW_>9p4icmeAK%qYj;HCu728<~JZdO16 ziusIj@~NiBScW&x#bbWph|(oO`n0!uE!JDYAmi^H9+ngpg-9c3(TkHsLp|Q-1qVY) zEZp58a(Lhn?UtD4B`2GwvaG{yXf{3ZM+Q2YuC!Ky76HnG!#Oo@A3(3#PZ z>))OEEVmqXk*!BygObJcMzWj!29d5O_ykht_m;aO$F&}=o2@?-)YKZ?Z%=47>q*JU z?eWP`VdLIBZytQBQ&Uq53k&1pRhEnOplgMhiOFr$Zenusbfpas3roc@hm4k1I!o@& z)$O1hUR4Kfk24(jiAKWEO?;KdV0Rxfp0gQAu&FjP)^GYZPYNUv)e=%-U0$9tc-<$2 z);FrFUmGbzM0&Us6-{lcY!7EJy1Mc77*TExu0dRvF3xg!Z~sAinX6j4h1=;H5>gKy z{aZVw4r+K{-H}8R?S|UP1U0K4xBfmK>&(?*Tv}EK#$0VslH5io$*mPI7x8zkF@IrOvW<%fg@kDc?Jx85o51Z9K}*^-I|ngegtV7AKYo1mG>wYH=j8L?fEn{#=4$AV#Z&%5 zM9AZ!e`ON6>A`O0fP`4ejhBFdfw8sI`wkHn*=nJKzupym6P{l4x2LBkbMkc2XG%)% z3HhzGTTVBgH*yvB>n#@(=ymC$#f!O|&+k1zk*mpmx4ETdcC1Lj#AGjp)tpYNQO=P% z$WWbtAnml{)eC%P4?dzrQlYw|m7C*T;~}|$?c(?EH&0ilt1CNGrUF3wW6#NQiGjhT zA{DlkoijI!Hv9Te9`c+WyPp#?X)zy{P{Wf-yQYbA(*1{Gp z&Kx~Q5;>~U*3SE;7VIxy^rX#%`Y(3{V!+)<8RovA1c_~CN|`qS3M3a77rk=AqI4)H z^NN)57fQ-7guEIs!HIhhm!p6jDv|E*-{F>oApFlz92ib@Z*h>1i$9;964h?fKiQsk zx#8vDP@}=3*KOCLidVp#?(lxSySp13ljG;-Kj`4)(eUIUtZ+VEQ6BBSdwj%zl9!jS za@e0BlTN|sc0ybv7pm*elFfh+i<)>RD5A51?0nm0JX%SXp$%GpDob~ETZ;0sOSt#$ zY$b^)h6lJf&6ErZ*XN5A5i)pl?w-8<{K1t@nfgP^a(jVpW(v_4=ryi73@S8*SrV-- z=d!xGt|0IdHW-S)+rVwyz+8oq6J~Up`15vNQ}154q3g7}G-~MFjsKqeS_U%YtK7 zb@k%wV`ye$%eeh|Um_AF9xBOU{}$g!Ek1gOGrV&RDB=^W3}fZSqg*X%pc=9T=--|i z$4gq=fQ#?}5nU#Y3llZ7v`}t*hS2-AJUUFuV9q>Gp~+!iK~;73@%9wbr=VcBI~b+G zdiCX{s>>`wjb^3BSoYhuZ>emS05K2G()>KgUV0Vd{`~k!3BjV-naJUZLzc9dhGuEL zT-(coXJ(5zCNYjdGSBOBC&RfaT`ED%>12p$D6P)?b)`BlOXc)WhPRG-Ymz+0U&{rT z3LWi4_PXJ#eJDW+YU+&Noc_av%AmkA?ma;JNjL~RCj#OM>(!b2QtZxyQZT*w`1k~) z5LMHF+Y?&scSq74?_!k2#s8HdwMYNA7a#x*gA^T3M4pb0t}lv+osF$GKTPgeyxs0g zqbhxVwL)eY@5zlNFAPj+zwtSwbPXaiH_0Y5--&_<7&L=})Q>OE#pz053x-rCt<&a~ zX)K%fE#JVBmybz7ZC7l1b-vxx=tpi<&E?%sSc`kuvvPz7dhcg&dj`0j2@VY{g0$f` zkL$$vI3pQZP~X5YbWe8NFUEe)RT-Gz((Yis@x z5MU=PB4vIRfd_ViZdLPayl!9;<%k3&S8P0fki6g%0h#KzjeUvna8uKL%kA3iVr2KN zI6)uzy`Dz-UrXgEj*gFsz{LH%)90ZMfkZU?XJll3ZLJao=3pXy2A3n%VD(%QS~2vF zj?S~6Ke+LRw270o~G@; zYFMPS(BgdR`FK-Bvk2m&!a@ouslkUvlAD{Gs;VjiE{E?pMtzY4&yTl>gWGetXvGoM zx)nOhGv#?MtzbWla(&phk@WG^mz4E`cuetn!--i^%KMcTt9${_goY}G$}@u_nF?hq{d!d1?w%< z+xKQ0^fh-3H#IeF)34C??p{VjMD$1P8_3DauWxQ*prHxIY_0wAcRpECH@7w~`UD@S zKUF9Xj<-gIs)LE)>|`$5!!*i-FQX#=<`ncST}(~6d`1K0Jlf@i{WmUsiNWnqp!e>B zv~*TJnXa&KVU92=l$Ri?TgU%w`>?w*d9_@uB+ei+nk}Ey^`;#gOG->s-SpN|QNll% z+`W&$!|ygpPDSCg&-aR`ll%P}|L9crZVL`IU~brQPuClch2>xw%{YGGLveAb!aTU^ zuOLhKoZ4p`8iW*BrVFy5c zPU-IMMp9X%y9K1XOIoB^N>W<7yZf2<=llHl!*e(u-FxSrnJZp#MT}@@YBJN)-zOgT zMYuXguhWFX%$#c|%~40cP!Ehu_21B_ZGNBPzB5gx3T`1;Jjg&65mfSi-w zbbu@5S1q&9&9)LRg!~l{#>G=wr*E9n2xYIGTj#`5W1W8e7zBli$jRlG0Z34jokf|G zZ2~g_Xs%Saxe7x*KKSQIuDKZ*4QB}=$TaF!|Csb#F%}gP-5C>Jxq0&a^x{hzEp3DI z@-T}g9y7*DwJ2@Esk-_Dm!pHW(z5m~P!RwWl5Pk_8}!Tk;IG5}%=AS?X?h)OlKuR+ zQ(>Wz#QT!YACaZS$W4^2Fj3ai+s8seO6{|M)pL#KjI)ZlJ#m18{2%mDW%%%XEGjxW zj~p7hnfay6GW@d2@XE*e@QVG?Z{b0`@Ki6cCQv5O6S$X!EoMJyzIg%YBG)mG<=qwM zt=o&f0n}NRW27nX#P)`g?r(0s1{@|R8X9)y=OaL<6urcuc|j%@Ry0Ba~fM&^tMUyR(lP8Cf6l(T|8I?6!a^i2=e5sLAdO3^oNsTvkoSp+iPzTGorysm zv5_U{tA3nS%fSEn=0vSX(HOtc>vXL^F2(x}?5X8tAy`nKjil=qRydsZ0|MzL~EcI-!di;rG#1#TZ+Kn^+TS;lBFF>y~G2 zS8i)=H z)6lR8*iLaV*&dRMi{j<+^H$djXs$HVtnHuNne*-0MrSl=Zf?N+;mkw0UoT&x6*G~O-EO?<_s{dY_5uA%jHLI4h35) ztIvOY+(0#mhnKR@s{!p_Ejafgp&c z3YnQ93K{85HlMJO$uPeihwumowC3gIS1TJ?@$fQLR(>t1_&~frP5(HplU;R4a+uA1By7SPRLvH5@Q&ERH$#S3HsE~NssQs1Y| z$A*#R4vzQT*5f~fkY49%1eT-1pUM~*w0T+lg6J?+9j~)*oNc!7DDNL0`fZP9+Bht> zd4s)iw9@$+5=F!f6i{0;bAw&ecVDq01O){_iGc_&YG+s8(BRJ4CY@|NR9A<(wtk)^ z%q%U>peRE-HdH!1mXee*$wpv=uNcoGW5P2!!SOz2k|ARCC$yuZvY;R=A;G&$0R)@yS)8Ih#rZ?t1_Mf2t42r{dW;%zV75(Vwk+DpGo;#v^B>Mb6;d zzx|VkCIKgEm63K^Zg5D9shoG3UgrO?FPqoZzALzPSU%aWa4pDqI~9v&XhSM~Sz10``%CyaoAV03g80Jb2X?D~S_4lDhGBH=7Mv_CNLy+7uB zeO-=?t;gHDHXH@=3#h4_Ab~10G~vIU^cIGPdje`)*0#PJp8&%wzD7?HIVOOmbu zm0)$8EzP1Q1!Tv?gFjxeo3|e=gLIy4-rpV;Q#$W=s<8rx%=jY#Fk%!7T-@JK~MR$E> zN<+uYb!9FseRsHU%WR;&wfVSiMiX90L)?E^USZGg?m{A@_qU$5mh~Ii3&xb=s}qpp zte@PPk_oVQxQVBKPF}IIr?0KkW!C!lcs|y!5g)Fm=E!JB>Uqaeq5Kb_OBE;9Opu$q z-~W;L@$s@_Qhc#?co>gbiRwFl%H=;eITif>R&{ihJmfr0A!dQd8Dl+Jn8%Tv`gG>nXnHrCatK{eFOEfpud$FiyQ+fx1SJ+dYS zSt4Ct!oN>>Aw$S*XEod2x<8&n#l%FjK$R;=3maZs-Jqmro~^4*Cnk%TAofd+qKM0{ zuAXdhA1P9*(w9`vkw!s}!a(sMAsLzA=vuGA=^f{IhndR5^DUi=({Xwz_Y=LK?f%}d zhPig*!E~ACn>T5H{%F4@-RSgshZliN45FbdRkssZY3qnI_Cw!mjqJatczu!H9v8(O z4VN1?UQ?K{?xN&RtJ+RZ13#V76u1clTV_Wy-J8g5XUer}Ob{hhK&J-e;ZH`RsnV2t z<2l{`U35Sv)!}zvq1yxy7NYLzlM^RqW@gT|W3U$v<{RiCc1tbpi$9(B)SRGz9 zbK|skx&MKH;8!g|N*UUSyc17hWo6|Tq*gSNQWIN)Hw~fnCntG=KGhtDtPXnD_6xD( zpU%tT;@aBUu9w>@yP?yg^og44l+dpN!Y-8OPkumQ3ZYp-EKp|Qh=OzC)5AfiUw!ZHg3zR)L2i6}atjqQkzPB1Rx63V z-yLJVL90i;9Nu?IJh=j^8j4z`S3QO}R8&VEo|@7HmjVKkQj$-a@65z(f+3r)~jfCp9ril%^3DAq)-yj$fS`4GuQ7;$n+? zSvoh8w}b>hp2vX23hHaH$ULGfIEeU#mi9|#J+GQn^6IC_AtY;|-dl$l7(lg=-q)uF zBH{eJbb?Zij@Xyv!9H zLuaH0hlkzV+<>!8v1ZjWXq-hxMZt+sC0JWqr=_Pi+RidjP*Cvj{2W;!@J2;J86Fv- z4ZpkH&JL*L+!uPLPiD}r^*Gdtr*w630o^oZfCDC*v*+a=+0Vs)-i_B|=tKUi%IZGbRL#H-D(Imh*&q?8{Tasf&Pnxi zuQt%LH#0X+N=_C6*;$1nTp*|Ij51E|rijV-b^(q`l&CDpVnZ*M0E{|LO@{NLxP;C+oBT3ochx|*nE`|=W>OM>4qo{P_dQZa;1dbqNU|SP#=<%I37iz0=YJFY5v{zE5u- zf`j4V2$gOS(yosr%C!>!vy`n0-YC`h%S-zdCik6Lr8E@mpc_^E^yTTF&Z3_Ml%y@t9!aEadc@W(BsK}j}n0hw1z(+HGqEWt)xDkUYlaRJtc$u#^Ynp7LXb+E` z!LX#Hlu*Si@ZvX!Q2pvk=_N5R7@#$1YTx67r$C6#=@7U78|!{d+O_JoP}@7c+;N0! zc5|`{E+GI?6mKzs4&HB;;gyvYh`ZBMR85UDzyzF$U!$OWv{6S_k}8^BYzBK0s^94_ z*TM-kMk%?t3V%y9JbYBHSAymkE}~8*=6iotreTbqe9}(_!ijY3>sTDT7m(=k2*L&5 zpbjC?cv@rQ|D78fSp&O+k?a5qtNBJ(1^A9R)h zCI)A;J5f+f)dmBdp5fX9Ktha9NQfhx?wVh?FFH9%t1|G8B#DTl{E)PafwpL6fm`EI z@sUFGj=WSUf`HwPfdM~cZBa=$M`nqPd=&Nqt@{#{#lEFhX%ujd_g=wR zERkLpZn|`28D!hUs84;Q2~X#7rjSqpLF?-BvSQ2Nzx8om1Rcf>rWnp?1kgMjYGdkr zydqM~yR%A5yZqbix>cqL%1mQ~oLK4KDGYN~Hg`t%9$Sx*#jkp(4Tlj{TOG+1Uq2V-8K2Z+%&Pb$#^4}V76Ih_?{Mo z^irF53 zina(|#M*kd&T=f4&@d=DP5b!qzNn~h{{9X=8m}n-z;Tkw>_E%fnidP`RNLohUc!mT zrRJvZcZhUUlR7Sr5l^(F{uBYM(Ox?_DXbTz2EQbz9Q9*6kFXENhopFT(Xr>pDn&dq z@cF>kg;K_0xvlxm7ZC{w8{r*jqSH{{Ng2LQPPVYH;E5&^^uZ}PowkY)e=(Lt;&EA; ztUNG&k?;bE3$SIg1i}(U)uSp4%p!p@%>_|#f$iP|S4_bg0Elg&K@fEDLOrzpAOF6g%L2vYqA2fpB_Md`y_G9RT z7DRRA;Gdsw+2YrTYHSufd}L)8KFB#?NEsOT`}cgq_PhJBiYGo@uV4GMs0^k&)r*WB zODGGh9|Dbu(a|XpU6^SQ$iN4?``o3ZWE1hmtI)^;OrS5aWYQcN6_uWWp@+q8b0}$g zCBis0Kc6y99wgO)d)-B^UcHKiZGtQY<+C@ttBkuTmEI|F#0ErsY_2Qqmi+ z8BP25e1zsDB5>gXBO)SzPr>E2&)EjD!X!_0ll=njbf{7eaeOWf3Zv((!Op_pNPyg6 zlxeOLNAoZri!3y%h>8vnPzZ%g2Ey@CycxepN@I^BgpiMd0Pwvi?@PY2CECFOq&wW8 zLtK@7KUf*n#l$2Fgfe3-ShFkozL)YpfG_|3s|C^O^nb)V^tw9G#t40ngL3;>s1z&v zqnKFt@NgvMAZYr(~7b1KMN0VZ#*M8EH4d{WALb4;=d#>|WGR#~eEj^Hj;$|G}k zv|>2>rJklP8U%Eco^Q-c+#f!K6z&4BOT9aAV|iJi&3!?eTMnPIoTbvifkOe{d_Nk` zmsa<8(VN{$^Z~6m9=N!*E-r!q7sv4J^)Ht4_4x)+B`&snN=+?3nkgucG*9It(Rq1# zICXwvq^De=pQx7rodA%aeMwhB|Ks!Y06K69 zpF8q@7&*d{cex!Y6fnvDv3XVh0&S;MTi5NQ=P zs@Rgqt<`iy>f=4Vi>q_|fqp-BGqJaacsXXM9ooBBzd>{I_wTg`k0NUw2HY1S5x9&t zqSh?-MR01F9p+!s8<^0#)z#Hm(7vn}*X2n%U0lzyvGdR8g|_9cS;de7ZnVC^j#k>p)^#s@df(mO`8I!U|gal3>yz`OQ^wS?Mur+lv%v1Rd zu@DU|f8?wFus&p#Sq)K^sh3w^#h~V=dMWeY4QqaTK5MwSxychcX%9Pv%|fx zv#G8@8XPCyhFxLP{maPL+Z{C%kth0fciz0Z5#qToNA89fNz#hEwvPcpqyKbjN`2~^ z4Gu_9oMT9>r^}?|3ObPxC_|uN8$GvG$kdL2BvRxc3_DT1w2^Pzg}0l9&yZ&#T3N7O zfyZk$gZWC^9=`PD2gOMJLL29<<&wRLAN*G>knDG2Kr=vAaC3?$^+cvL(qDtoCS z{@_Upd!7GNYqhkrT<00xKJOh1I6vlahJ}O@sQQ(?ylVWYD5|!=V553wH4 zuZu|$B!dLn&er;cDhesKAV2~s_OE4@GpUdspDaz_q^#_18K-(bcq2E(FuXoV`~2?u zG33i&Yp7d#{kbHCxs9p$Fb?HcGOdGI4|S*X2iu|OQ}GeL`UkwDig@i z5|L-cy5A^IDj8$Iwgz19a673PF=5d&9IPtR1w{{!3CxC)>Ez36tj6&Fc=D75g#GpG zC6t+9Go_kU7U-(ll0LgdGXeDPMLH&5gnKtOsMW_qvkGI0 zSPS`b&{bXFb<~>|-})R7B;8}gXNo6c=42-S1nR)RMK`ohDWXuVJh3=5E77+r2{D4P-P*Nkq#!Nbcdyf7Va zs3jzM+sn-o8`0aP-vTO5axWd9r7~Q+h`Cxv)|IG++Rvg)S zQz&QJot;dtY+kmBKR;K)!N^D}`o9!J)B))w8;638mDfl{5#fjUPeUD6zEJbpp<0X{ zVyng?f|^LJqz2h#WyOEuV(gHCdG7t~f8RFZI}JVwgbv;-B03sQiS^uWoVv{)d)@Id zuHM0?TpQ-#kBLAaC^c*CI4p{$p?vKNQUf(RoTaocV_g{;E_L~@b{@(ipbuxM@TQ%a zt^Hhg`#wF$0gDWXm|iivc9LzayvA!J|4){t@?P1)DB6rx1{%q2XP^QFEX#~P?fVKWt+XlN{f-x_SE|FpDu z1tm}_=@LyNe2vR{ub={=DJ3FEK|hJBL-&h^bz!jd&1zu1mRe*K!B+j->K_!*s9Mhj{4e%e}q>Qf@O_DAw3 zp{7oji`llOJsqm}F3B#cd3a3Bl3`D+b2o?T} zH7vBq)G|RqUE5q{Ls=xx-d4VNASzMX{4Jl|VB}^?S`rVhCpna$nDu`B!I4{|Qr}q@ z>pdb(>*7kwCnE}xuDE3niXwvR9-!4|J6*^>I%=ed8>rm;wYjZUVAn8uIfq^xDJVpt zlA@o|^gJ~zOIhng*sO+s_7RXg~LEaiJ}(kS4g>n$^`pzj+JA zTSDDJUCZTf-J&Hy0YS*xZx`?8V4&&?OQ2L7I%WQ>lLUYD^1ZwC%-4pu3un3BVcgi( zt~#BEd-OR9{`dCBC1s}{%u${S;?6e2!_8XigTmBriWM5sWFK05=Z6kzOwx6R+ zHeOw@MLn{wig8nnzy0h*9$eLp1d*jM?J%Hf`F9upu8fpUqzJb4Vv?{kp)x)$k!}T+ zRFxnU_c;Sg&Pqdv3K0@nHS+uq-WgqNq)C_-2ZbqxJ_Yvve?Pp$(V?OJp!tu4hW~5R zMFqQz7s!>bfZJk&+iqE_XO(=$3_y?bk#pzrWjr-1^UZ2|Q1OVT8J?9uG6ywI&z9Ny zh^J>bzFuUSMyTl5$LztK{6SwBtIgr2p?EswbyW4EyoO;=|L;dz3}!vA!nVs`^gKPH zzvnxPsA?^WXpCI;{3cJ7wtTxoLA!b3a6gu}$9f+ZUk-)Z9TXxX-&NelSgC1D4Rqu9 zC4a)MOve4k16){tf1FN5jsa~HU?~OLj1v`wjGJvpS0-yzw2zjbm6y?Kc2E8`tuTyxa_oiY)j;+UXWj;qv?1UjgQr~ecj>bc7z(fZgn|MV&FBq6{&IV2@)#o>BoR+ z^pzizRWl-rwALKQW*I0D9}scbnCU7-C@lW16#ICGlmVm5CnLns(W3xKSml;xlc@Dt zM~$h{2IOy~@XzLz`?>|EEL=RukFMO-S*nH4E^8SS3Yri|dA|Jbz|q#DkWb$>9jmnI zl1%Vt@?{dX$Fe5@fI^d-_umib-tKN~aam8~2L?h&V?xt)75;I0Iv9Wa4cgNE_tzOb z{Jx6czj3IzB0!;ABN>*0UYH~}`3^G$0`w7x;}v{tE}Pw#uF>Ww^G`mHCzv2Q|JsQY zOz|M~a+-Un%T)50WQh)wLOPc6ae_8FOgBe_LMUVKm{A#L4x6`!qK~K$Ad$q2Ho@2V zu+3?nS@L%(moFcmeaPyUTvlVNkkenD_hwfMkTNE`?djL8cZix&CR3JEan2&<5ee(X zkM?EO*NH%TE7ot;U*1wzx)A4(oWa;k|1&v*p#Ysyf=*NB zl-tCSL2I_W7lk%M9CH%h2y?o`XfR%O*&HGdZs@AS&&rCU@5Zic7CjP?5%_Ct;=kTN z0^{P|bhD_I)RRAYyQzPqMaLiO>1ut>-{c>a?09837mP~Y;k{un*iRi@Q}9OAR~0f~ zVOy28QsXueYj7xdxNjW?36G!s05~Vdhgz|z22UNHIT6?F0x>1x)x*_1=ZDDtukHj>qTvD%oG!9fWA?2<*|46>OT zbo0-I7^e;WcY0EW`<(pi8i;$}P+u<~D0qFiK%JCpm9vsf%I}FHC`iyOU^i1< zPsANd{>?(I5LnF2d_mgdvXs|T{xwk_l&SxAK^kk+U=V5j$@QW9>8PRWQb#ds8KHP5 zAui+~B~vB&^QjJL>W#vV(V3<&uJycmZKrj^Xs`OQ2}?>xMdY8^znZ_Mr+Qvd2n&(^ zuO^W&(!Sa{+hh>wCKa^dLwT|^*4px)dEC`3h;H%?UBI*hU9#Cxn_==3Fs)1BnQE&&E6eX3JiQ<PiTG7=QO$0Ix_!|uirKBW3!{!j4v zTN7EsBQowSFRsAbYQKe0tpKyppyI`D0vTQ?IEn{;eyqfn)_j+D?hSN5>wl)^&~!u5%jUNf zRN(?ciZ)x9K7Q?JPk2+!JBVnwb7|I$+zk1Mx61!oC@UmGqG43x)3HgtxCJ48>9k>x zh#?uZ%w=R_C@3H~W!juXRh0u*y+WtUp6QP-7_R5q_RsY^T23_2bq{P$J42u4=oRv` z36U11yNg4-BfKlN9(nhacCoBagV*}k$)2mWpC3pbqc|c&j5K6R?^5AKG9 z5RRk6oKQH3q>W8HB-VM`-=aXBA}`2v{Fmelh(V?x)+aDUqZtH06cMfQBhnjFj0Vt!c({v`?({mj=gJDV7@`F0)+|Km0Qo3JFk}t*}l@-eNp||Pzn;U`{*@oKxXY62}OV#^Yn9;1wCYrBqzQS7hgiUcIc}Z>U=FPu;Jc!L8u!nMLCP zjX7X?|9i#nPNPLbK|;Zm&IJnvi%yMh_dN%948P^*cfjKRF6U5%ndqVxI_e(@}Lf@dc!_H$LjiGvO+p7FQiKW6(UMu)YN$*r7k`;L?H9(q_GE zKg)uYcyS}Xy|to}Lip0#1x{@Kn#kH|Q$*d|*yar)ReuRzkWs81BtT zWOjG`XJf8rZkiA8wi%tLm?9v^_d<#6;WCl%CSF;a3Dsx))QknhCBbp!$aO$PflK4FRv`OJkH+YLV)Uo z32Lktjtc3B`b_^e$-K7KdZY+3EO?E(PYmPYaG}X&1s+03NH`RxG?+Mh?1{mIKVBNd znw*`Lni}6d<+{s3abnhU8io9GXwJgX{hH&{Hn~q3qWX(9PxG zsK28EwEm5ajWBF#q0cv%4MUFk9WhGaeq@aw{^`2yVMLB4p6LuEnh>0%q~@`#5}7!| z$6IRXfBpa3q3xI-#@VA(v7S^r4-26zY97x43)zsZnW|>E5_6kCG4F$J?tsUn(N^~x z$vJ+cUo7xQKg>{YAzmKszNunQb0gb^kAiH5I5qcw%WN`HpBG;ipRW>CL;w(xVMw;b zqx#j`O|NVrdY4G6;&H|X+3q~`~X3uq}mh@(C zSFR($#ft5&%smA*;hhR<|V9_mzOs^Jslqkn8br-wR^<{xW<+mBTZh^mO`a9?6AV&ARS6=urXT0OS-q4dwsM>vZd<*>Aa^1+o3aeGWO6%eR zzYco#rH_aPCA9Ku^EEkRp=2=lGZ6nyZbxiJRLdYW2=MO z?9pPobypzO$Mcuq-=VQ7x_Lt2PFF!`)vB^S?@oU=A}t)5FXs`YQ%WON z{DSl3bS2pr@`ybr7wj-lz#ADKuP!gQgC#R!KPx&pU+zrpTl$yigkKXM zqH#V@AKOfbzl+14pN|eW`OpWuEdluZe@zwY20um8-qH zy}KLQJlohX+gL6OG)}Fr=SY*^+TXwL%HEqUYXX=eU15}SvmPpH1V9wYSI(ALtLx5z z1>1&8#N@_6qQ zpMSWo`hxWO=x@z>ky(*7A0wkZh;`C^=|4oTk1DoCdz}C_aa;U@obp?Gx|XhPe7`T4 zXfl+duA?(FunAEfTOwKV{E7vJrz9I&H530=2;@3ow_9UZGZ<>lo|$H6OpEglo1Bz& z9hBA8!Rp|Cee5^Uy|ynvm3=QMiRMmHDlhl^r5V7kq1~*UoPPH(Kv~dEcK7sjoUh-- zBa!`o5aD`%Odj7kZ8Vv%Vtl?bjXD(Xo*PITCa0$#ua6N#$2s&t6E#RA(5(F3JmO28 zMu!n)^_#WcFgzx5Q80ConK{zjP(q^QvkV~SK)PQEJ@YFDNltn1n^?SLxL0bi`sx#S z)>2H!01T+yUO^Tmqwd1%UxS5jkGXy+fn=UyX&T7N(A~ugf@Dg){+h|!S#}Db1qD+M zN=6a3KU&JlqCkxS$o>$X*I+XZoTwvGnDliX$qEk2AN5+?ko!+(Ds%&EUg+yDv0IM1 z?awGYDR!m+K-S;iA85sZ+5}K1hy(0&-d)0VSHoG39bKK!$S6DtlK(3@aZ)+olE!Vw zRmm2LxjLj*l=T4|J7-y0Ye`9OMMZOm%KG}LO1TtJ`IXAcs8t#EH|yEwU@p0FhHB8z z0lHaXK|w+Mgz7IAqq!m^jByS|S~`GVII|9J`$iHKeX1gjm*ZUVv&!uZkMlU+ic`#l zbX(*X*+z&@ubgTh)tNUXhfsykxk|wY7F2F7Cc6gMoJ|I>{W?=AFE0ml55SIYb=j1K zSgmwCW(Pc3+u9P5kv+ea;tzQG3~*m3;{Ws;Q^mo2YTDW*RaIjw!=M;y@jN!@O*ZX| z z*GQ6kujA!CzXg-z3f-7CSER7Q_#eoorIJ0&okj@8fP3$^;=;e)*zfRqY$*%R(7+5I z`o;Bu_<=Mg;5!?m`Nv7*hJN5a4z4dfrsJ6kB1mF#vZT29I7j<|ZQcmbCL;DbLydv1 z^^47DC$IAwg2E)Fj0X^h?lJx+zw^K~6cG`Tl^wbQN6~&k5>s4VeF_ATxKz&2=;qsR z8QkCwuC1*VTV7s!_?#bB`kPH2nD=;(WhI$g$jZrCHxmmPE6RgQGZf=fLG5;@m*}8b z^wU!@VKHN4CcmaDQyAccGr_@0vjXVL9U@C5*Xfs$Q=D998Sun7Q2Q?I-POVYKgkiO z_JB!;b%yEIK!ZTCg>YcNYm?P}lG%M0===mio!bk(I9>`p^Z5uxmrMtj|0 z@^RI(7{CwKh^GYdsO!0d1Od`x@PK+uv;Fe0~SJhn6S5} z*L?i;oHE-Gm;o1?N=YQWDSP8SUr0E=pn0xubi3=FnN zz_KMbHa>y*Qs+vwCUZW1Ez>tXk)i1_GzC+hBX#pxoRRUav0!i~-esQ2G0GxBeBa;4 z2FA{^8_YHuCwqoPNB24Fsi`IOufqk_s&#_vd0J`z$q_hHDokDgiFibKxbmZSN^o#6 z9<#wXhhQrq7d}K!UmuS_%W1tY>T-XUp9d5UP~-nNa!_NyPeVpVmYyIi@DIgkzdq<{ zUJU;EGvVRtdWKEUy;1)eU}lB;3R0OwN&0b7a9gxzZGvYW z2R(n8JoIh6cY$JmVAUxyG7|C+JmK!{E?W0+2KTXU^jx#6Wx*RDH^nOzKCT7b*ktqD z&mA!_N}QhBjdt1&4o5%{zWlVdy=`e_HNZ0bI|MZ@pEC*;`)*k-#RMUal+?duzFGT? zJ8Ec$pKylXM9-j%hK9w)zaMM`{@$k)(d(sVeVB$)3k7m;{bdHfC7hbC+I``6MU%gB zb#;aCxNN+F8iT^wkP!Q}+mcum4W9)90dK@=O68FoN5X!&jQ|2{pL8DWczL2TQd2*l z$Qc=tL%u?xfH6d2Y@5y%f!mBh^pb(d_2l2kCM=G;6bZUMQYc^IL!=L;Dl%79ePhw) z2P6#PcR|T8;X50#;U6ov&(3LAlO#I?1`7=s7Bg#XQR#M05>Q{Yjwz`4)7fzJAZ5Pl9HymNuyw!;Phg5SHG8v20V(5 zic?EIKw4aXeV)u1lza4erMvSLxmcqNUyre(bh|sT!@ok-wJeKNK-!6?1s9h%aRnD{ z+-LRU!K7;+2O2uj#ZC^JSTvAYsDJN?#f&s3xw}+*IzK9F#o#BF%p%feV5DL((ONf7 zt7E&qnx~(@o&E!#oS3MLGhMD-XFFTTiYA6Bet$fL+~lytN8DdmR|n)sDiU`<_IiGP zo)mG=34<$A%nUb96{l$al6&xs$phb2Z98kn=V4~exAm{9P7M0v(>gWEf^j z(C2sXcO%y}jY_#5-&u(zjkb5@Yl#2x=i8&90%-|lKRe&BC$TZc8iqD;l62}ih>9#9Ws zvF_iYq1+sHTC=FBsj063!P~~h1{j{RqD=z+`?1#pNZI2k(=swz&0)CimC_)`VE{ui zWn6$&#>#0mHkJGjn!UTreVZe+fSvA4%6k&wWx(qGPR@3;IJbMCmzw&`Ood>+O7HfM zH9OD)fE^C#r^xt)j5t65la~>#JOQ}mG0}X4f9L1j_QW;bU!%fn`AEg0|j zX&?xrTi{Ek6#0%{8$IOTc+4EC=LLcrnNntNZ%?*Bbu%|5=u_qNy(%cd9v>d8(hXYN ztQ8fbeP(h&f&yGwlFh*skg1=}>&IRj#@$e3e5w>!m3}K!XaDt!?$fMR5BHl*ykHn3 zZ0IgKv>z6WNf}{dG}}-Hjr-GCGy<#;N{2tS?`B$nX z1JrD+XmyQ^LatkAG5vKlH6{KXaW*D)b`LP-&VM|lgoHk;zY*QbVd(3<_T(|Q=rM_@R2zHJG4?6xyS1{9LU(`rC#~XZna_9d}p(=jzoJWA}7olyo z;s3`4ut#^uUos+)O#Lz@Oue||tCVRFVTcH{3nut|gM+keY*^jZ$()lFJmy0d_ZS zCiuzs7rTm@v%Z~=&^4-A>sL%or}x@~&GYkgb>km|nJR&}Uu(v9SJkcR4Viyi{05S@ zzgDuu{{hpq&n+qOzB-sY7W!Tw4h)9|2ELJh13cm! zs)uX<#vJ%=NI$C;{nXK^*Ymf3dH^!M#QcJH=6g&e8dZHVXNSTcK70TVyg53Q1o>fY zLSZ+Lvt-rNd1_F*VV{puS?Msk-hb86A&m>7OalhN2VFPQxc+AWlXFv6wEgL7&Aoc{ z`?A|e`75rx2w7EaZ5frsFJHvKaD;A_Wlr43YX8T(`>Vrsmu8@r|4$qeD$D7*HQdu9 z&Xht#Ol)Uut?f!}^CuTkCLR<=AJK1xdpbOit!Zh2(AyX?2W&Sz-P&%?$56r$Xw~rk zu&`k@SmitfL^pc)+m+iywj{RulLTBbRNIv`yZ+Ia{EP$2y2{2zm-dL}B5Ebg*u0Rk%}7-iX$>hGd3pSsbNw=Uic(My<_mLW@|QWyy+uKU)vA`@K&0b2 z*xA8l7Bhbq@YK$K zve?|w)uqSCsFU+etBy*V(x=UnS*ODgZ@0zyy(A_mj(a7HjDCDd80#aG{9CS#Ch>-l z@F;uWUyumo*8-_-Wh2*+c-Vi>t3ts@aMfR}*p=x*=kn@1{o@dF?&G(3W=?Q1BQgbLdDF|-*Q)D-+4iSNgSRl zARqwhd-chp{pEK4ZWh26OiD^BR(am$xw{8D=LBDvwA)$Rdbd|5p>ck$V5KcAu|)S( z2Ipi$Jp!a7C&vb@d84(<)Wm5Pk~`^PjC_qysEJu{fT$uxV>YOz{uPf1Dnk7soK6j(G#$J_m_ z?qjz@K?ts{X30^eNf?BOhX=M5MLwm_P~Zh31RP;>baf4zT|#uvcbgOx6q@xwmzri& zi!rFGXx8-piWV8!L%($mUn4&5&0@no6L(W2zh^9u`?ss0ApB@GtS}S?H)HLqgKA?2 z32Q|GPx7+GG@Qw%G*B8Dwt5k=+a(x@Lo$4 zSIXILT`=qKVL=J8x#k8BA4^$MQbIsRHpUVO=n$`YN`T%%T|F@;2RQUwuXMD7DPb>= zFhCI~L6<~`j}Meja@SJmbJ{vOF3o!Niv^ACPe`HA=%0QI1At|9mL)8_ShJ3+yRa=4 z!-f-bQSu0q&)?G%vhDu*Q{~$F%&^A_UDUNTCyb)&EWu+*auISN*>&S?F!|b!&$G|z zLbQy@h=#|aV$*z8Ze_iLwwIQnTEj=<9o#z%NenW(_w@9-MPSOuq^jygdBvws;h^Sz zx>|7D+S=0A)>bXyprp(PhEu{@Q)Ah}o}QjXG_vHF4^Q{UK+UHHC-{7`9s`O%IvkW> za-fAL;;=gDRy^F^#>2(kIy&;dKGL7+vwbI%!VDb0t5{g$fEpEuhBi4J4JK*T)Tus6 zFBPycA5Sl}0#%83O%0gsnRI)L681HR25MaWdU>5E8XKW&^9;zY7#X7u4nwlCG!Ewp z_<5#W*p*LKgPCBs10_~wWIU;`#uNW5&Fsfoc-d&c>OjHro;w?=YXd88^$pz*SP zRzJKEs8xAH^FEtMi+`lS`P_&jihr11qDe;N~Wcy6{pSW)RGCdbQp;O zS?n(sNMM3lUWZ@%))=?#1VY&Pds-Q}2tn^NAe$YXEJ_rI$Cq?!#*YR)KzbYog)e95 z(Z+%6_z+m_knT%-kg;^F(rBKr|4%y{y|1gI(_p{PX7?vYIfuMgqE1w02E z<4gXZ8hsq7(b*yJ`uaJcp@ zHeuOh!lTMK&~*lw4L%_kfl%ArR0$t0u5@<#`|ZJmVss)bW`o3(6ktN(%2Tfg{OmNv z#9+hnD}8-Eb8|qtpC=gwn86)Ea8Tppqe{#OdRNy7Rkb=Y!Mn0NK6W)dt$|vG!Bq%U zg^eJ3oeF@t83J?O0na4VgZ`ioX{E9Uj2~z$o}c=CuW$c;Q;T33CLZth4fcuaIOD8n$9|^%Dnyh2SGulR7ygS2I=mQlJ4%5 z?oP!aB&DSrq&p;48U&w=U&Y_jv6mG$p<>oSDC8^h_Q@{t%a>|ec&Ml$5fSKsXMi~eJbc%^6}zx= zW$=4oB5LdE;8S&WW{X;ZoSm@WMQu@$70D>eix&gK!_3sw_Yi66>Bx8PK#K9-@$Q|J zaHmOCVj>DUxI}*fbx*b z?ch&H%s|J~%@ScwV5I#vJNuKBDop^qF5dUiG1@PFq06^_4iG*$`wL}};jysJvq@&T1S8 zF~Iq|aH=sxAN(=kz`TfECo0(oOM%2Cu8YplxvlQJnU!{O(v#V0a;uY2fIK)IW6{atJPRdt`zLg z1frE3k;Wgh-@VIi4}hg!&9iJCi){b=(B^P0f4&hQ2M1LZruKWR77=sPRVmcei`TB` z@`dw_kLsLEXUlXMB$g=qs!K%-+x3mI<~}Kl526xXz4_>O$t0irO({MyT2aK3Rss8y z%qQ95S6=6>gQ>TA?FP?dU|asd(YM06GgH&`J$Wr)UFW(jKCf_bvFUgwhGO~K%T+n{ zG|F^TOxt#opz;LVCJIWr+aXqa?=hACLAHf#XD~xc_x<(k+siy zdw-TXxNWDia&uK}@?X%=B@6joKvd0)Em?$Y8qQ__Rznzpa|V=(OE9J@(K67}>%iIh zc7}id6Ky$j)FR#7M(fUK_?xWhhg!;%^d?;k@2I+`BMD78swlhd8LGOOOz?eh7--SL zFp!i*yhDP_w`&(kQ_pI$MEghAATue@vE#$;v5@Muc)Hi@0izJxMTbzcpUoZt(2SnM ztcvp1=`*_YC;mr%RAjP#AkATu!rK z!%!Dln)PdMYXZw-HwWzw0vo4pcXq<&>zxoGKaO1e!wkXZc6-6V36i|&ZdMzhNdZ1xOlSrELU>kWTm;)d3B!C z#xjt_-95we(%p`MwQ8K(GB#qin(C@B(=sSf6dR{UH;+2o(1-|t%sInS{f|-V0MTNYDXuy4I4Cy4>hlH(`OLRXoP6X@-CY!v z|AKlh1cHM)1FWg)kY1{E8ma_5PX;9E3`uNc7=M`sdKbk;oK! zoVqFubv-s!YR10gsXVQ+7;LSxp$imo)LZQD2g(qL&2CJG{cP+VNsQtA{%PcBI6Z>` z0{2J+EZ3HliQMQqmt9tR0D>KvZS_!b*ooVr`m!M9jsuM3xS>GF9X51=q&cUdG^WJ> z!}XYOxZwGCYg`wI>uSq=JMI?&kYURqK zoA<2t&Lyb+yFOdF#vp=&;p@UY4im9f@8kZiE|6AYDUn3z6CR-4!5H^}NGa2P^HS^a z)5~^mIeCl+55hu2vuGbkD8s!NX5+w(Y{eWrK3xo8)@x)D63QsBBJT0?^>yE!HNRFC z_ynS;rPT+m$$Xe9s@2e6Rd&QIQeSy zDaM{nO%{Wx{AU+Un9pqCL%Dr|X^_g#ZGC7FF;KTX(%~~g-kc#=Qo%GzL9P%pEwuOfyLY zFZQP%FIn60`yH!K<;#{NE(T|BHkW8Fo*!%KWQ%)tSouV#@3d#twS(iqtxiH zfBk9}GTq0JAy@gPhINth0 zSzrl;ImJ{(d#g1rm^W#QP3?u2fAShPyW37#{$xRa0>_l;XyI5Hs-cx*t*UP}OW!W` zLyxyc^T&XYH_*?*G(|;b^sCKJk1Iv^g?X<WUV5OR?)tO??A2)*IY^^#ib^G|oxf}@$*O<9kdcyqI#hV3_hZ?5ye zV2nPr;>D=9(dx-6MN!_);D+`*DFmG;(fg2EK6aLxnu1vmdm@!2+mK~mWbEGLI>5<=xZhTT=-iA`f+lU-Q<)_BRg(l*0w40k7xTTFw zPA1Ca1A@BQZ9DNEJ)lI`lfn3fHt9+<@u7lr{`oxNYMTJ=1-qGSAC?G{#}+K zitT2w8$gK>>{MHO796ZYP0hEq2A+TmclY3v6KZ>VI9hSyIN*`C4!I#-qZoG%kTXJRb0UQh~IzV{6~XuW!6uF>(ktLuKD zLf6huZESog_K2pH1_JhOkNGC=x{kN`iAwSD#0STNJ{LH^*D_puE)~VmSoJ_`%tNCr z?Ce-mC4YH)TM_MHNlFdv!x#F5l#lbx9D9E?TX|RoyK}m=@~suW(o`Ev`ldrcaZf^% zH|*!m|r{p?gdhcRo3VOI9D`&{w$vAVnM|Z4i3J!xPVs#j%VK9-gn-)!FVjZCEU2 zQ54bI(h`i^dE9rj0DemUGgpL6sYvZ~e{uhlQ>H0Xl5DKm%a?)S;SVpJjm~lYlS?GU z2MCuaFoj{Z55=1Y%O*K3Y2?yI1UNm)#8NEiNHCo#unNv02!q8(0vnd1XVDbcj&81= z7Z-O-O&KXD+G1kr-@mUfD*7_6*7IGi=iAGv{w?;7A__yl1mE4+fM|yWYXWq3hnecJ zQf)Yum7LZI^ZW9+&T^<^{~{vb*l@y~30Nu&U0Xtdf{;ytX#j z`Qyh?vj;5jTRojhIGTzTyYY1CYeN%Nl}1GFaRi5E<|G@FWt5BJrOgn!Em@!Tb z3;-MWnBY~f83>%p+1c)bKGgv4V~Wfau*w(~%}kPDc0wVY_1$QDyuW>zW2eE5J3kV!ne#I!U$ zHMP7b?k`J@j>J;f;;qW+)N%0Kmz81MMs?GMsbu!8I?Kz+rKP3$`ua)&yYBaIwZSXL;9%u11aF;o zd)sxyQ;h4V>SqExKMSK}$iLnVTq;!HJ>DGDflgi@w#Rmeu)0=B?^a zl3{+;0RbCFo4$V6L6L%TaWOH_U89Dglu%+-j`Ad>~PWlSE*A zaF7vPa{cjiaFZSR!;bqP2nGcpQKt*~a9xHO6*-|LmofhR#V zNmVt}l^7`Wo8`R}Emo_Qk%*%d8@u(#x#wl=ob zy$>GT*v{+3rbiy0i$xJT5wYbt{nRuzS$?}WZ+`bK?AEY*ww;8KGi2U*Ew5A}(C4@8 z@np1JPhk-~`1bO%76UVrMq*;WtPBfr0GQG7rSad!#C#G%jTjj8{v(o-iG^ljWW#@c zbImv0sQJz{g}snW=;m*mA3Rce<&}22uzIw;G8-vQa7$vk=kC65ijMx6XZ8xH%aXF3D4Aiy5i>WyHn$@F7Bpexl0%8kmTzOx#BM3-C*C z&Yfpw6{13?=RVgI*B%)~KQk2eG*Yu0wo9b{G88qASGcTrPI{PBWY*+6pSt2OS!$1j zkk-IMY-kL>F1k_G(<_Z)iy%X5kR0O;2!m7V^*XPFgap_^2mAW0e$>O(PA1JpLnC#l zO^1PwK5k)Vh{J$^Z;FpUCHjuo*YAF^oU)GfVu_}b+W5zTq!q>VoOqeGjD=3!hFZeS z9hE66Spgb35k%}zX8Y-!gRQ9%;Aa+n<8Yt6bK+_Bzpm^0$QpU@OkPjFN53@;1n{ae z$4sH(+msD6<9yk7#!}y-oYuSPUIi6JZN94@b;X(RMWKQ9VUXp5iz{+2_8%-K3=YgI zjqVtC1+E2dHyH~gciAVi?B>85xoCp#Sw(vqg!pZ0^l>3sTGl^k7N}3#U*z z+#bk!i=)hGrSJ?xdJEbIkSzKAybF0<2>+&s@wpQ_?+|paCYnPrE?$2}x;QnSW792X;z$`7_)%f#d z(Vw52-Q}n&+%7P%cJTXn;rz{N($Ah~R?MD&sdCAE)M%6GAErIEjEvIxY@R>Jc$-6K z|D*FirvJBt=2u(JHw|ALN8b4BqhcJ~-1wkK7^Vqb!xCSQR5_ZDBsQY_q1%bL13=Kg&9iB4>X#yBVqj z5MTojegA&MtQGtZ9P&v?Nj1zEi5J&F;uyQT`lwi3PHv3;*E$28c|Bpc4-XE4p9${) z8D3HIblznQj+3{S`y3LVF-c~fccu%Bo|Q)pZTwJ58`cc%DhyH}@&7+BfMlczaw3=f ztNepc?ZVIFoa*YN(gedzv{W0n_k^#_M&RAU&K@hko#;wbhD-7|0!0E{koD+KO$Ykm zk^6?<>roOhf5yF`Je&u?1@eLdgbnIrqod=Hk@=Ey;*t#cgEa~e-`Thl)bg(-8ZqfR~V~}KYnacv{;+YS4YV?(K|A7J1o5Z`t{}h?CN*}v&KjP z|4SxeUK5lewXHC5WcPi0KI&@AiGGiHKAfJhy`Nt0XDo9TDP(Z7$0;mW7BKkr{z=nI zW7VgErqjJOuX*|S;$J$&PVB-n_MrxogO|ZB){z_%NF5s- zCw3Pg^dYh)?@vxnx;bOO#6tjXJ1~?Y%=CJM@{f!ZNCrRqVfG1DnTII_Ac{cAS;#zTVxvKL6O>pjr9>AJ>?8XyYM%BjHSfX28au-G<3@{xK9MuQfRUI&-B` zOTb*?`gr?ofv$Yo^!Q`WEiD~PURShL#|MTjp5DI@a|BwOqaU&?t+je9U-W4ziM-Q6 zB_VJ{h}rmkjW;H^CrWtTZ|mlXtpL7i)I2rJd{#%u>i;WYd;_ zHZ*hQ_>|{I+iS%X%8Kt9gIn(ZEN^S2sMO5O-;iaV zw%QZ-t~!V1z_GBSm5Dx~*r`OEogE69RM9(LzI@4{n#)H;^+I2Z5NT?C(3H0S$IR!h zjS=}7OrB``N(a(FW8SJN*!8M0az~z!J|-U=mSVO2^YxwlPn?BtyuU|Bw6QH!X7}e< zv^G^L+y-xDJ^^shttwoV&pKbX}&BvVJclHkn@qkBFD=s}Z zG3@$-#r5U3t~QeVZL1N|92cSBmT?mtAS^PYTxAOOcNs4fOM?w>U%x228X+GJz??-F zOgJs-W29#`tE{`IjVdvu6~5r7kZrCD=o%ND7a$qO<*=Ev`TcV+`>(l!@S5x2L2X9h zioF`YKIJ*5>Cs`HJjHnrXt627%wD0AIiGT!AOvN)FnFRn>M=B$##QIpZhoGz-+zrT zitqWjSp_Mv6G-U2a?6c#&Y-;vL#3OWmaHGUUgqz+7^U&%O4zX!_5pWa9rn(%$D&hHRZ0^Af}cl zSASHigL^+$dA}m6U>!Ko3zKG28z7WSN%iD5n|EEr?BEtp`~j(HK0FL z0LGQYq9h?{E=g=Ps$C9c9Y#fP4D0ECr z7KU^T7&uPW*3iX?_|e?$zMk7;N6nle9MI?Kv72&LJg!oO`-{u=v-mhSN~*4c*N6%pG-=eyXjHYwMy^NMu%Z0lF0ZBN|A zWf4`Ihx5U|Qn8-IF1AQ}J8%E)c4$hu^D2i6leBd=h!}xjKfW}Vcd$cvR_$HpT9Mw3 zd_Ee*q<5KyRGC@j=3a8U#Y>R1-Rk)K9ho8~i3-=KXC5ripIFcjkAo`2mc`z@UE1r| z7H>ejscs=odE+WABlFEkk5L~T17rKdgySUZ5y~SQf$p5RI9QR^|{G&x;zLH$(0cXHPxaYG}Y z)-d59HjZx?8EkKtWAybIkI#ss>WgZoLP?_yZfzQQ5!bf6KigyPBM{$BzN8p7{YC2i zs4hEX(T-o5`JJ!TQXT!i5x3uVnnptG72K^QSR<(W3g!I|vEW(2m$hfQ@BipKi=5Hn zm-c%%LF8_xBKhK@I2!tZ1)W$h0d8k<^2BHB2`&8;MbAK3(d)T_jagY)2}>R!`ln~; z5`*t|usHQZBa4JQWlwq88Q(ufO^ep$ltQ_pkY-diLhDs&M}%<1Kqm$(V!{K*n0+OD zgt=L7$0(L?i|bPBFMS+a=|c4vYqC@ds(>(Nz%D5S+0-@kjDU%b6Q{4p6` zczqB+Pk1q>NaBR(+RgNDO1X8XK~L~F?^*T0MbwYg583JW)yb4cDX<3wpmgNip1rf9 zEOjkn-tld8ksZfNDe&9z<%sh*AkEHE14i959!Deagn){Z!RNMhBYX>+iJk@?4o4q@2u#cdy!ssnM{kvIS*lNQAtPQ((*@5R6AWaK}O z^}1~kv{~*G_Pas zP0PWMCyfu~`^;tK?^}w3=#w$_(Y%K??N2vWEhrwtnuI$1?5#_Kfowu6f7a!&i%^|> zCVe=6jk~wVYfU0pG^-CcxNJ`*ZRqynuZLSb%Vgu%BzDsH#r+D(q)ubPPbBfw(vt44 zAMSdeh&x?lPZshz<$is^L_SdwM z#<3BO>#Ora;8BZY*X-D~zKJbiw_fds=D7y36b zR5zTAj@nwRh&Sc=WzQ2bGl;#c?S2z4YdFQ>;s(SCs#7Or*K2^p3 zGi`tF9rfP9#g-R@l-`4xna(ScU&HaMzr6(0RDB%>^+BdEOo)&=TvG&_Ppp@w&oG>H z4(GO;X-JdKU2ks{2%0u-{#rgJ4nC?`nfKer57V47#YGscOpR^DnLf)H`*YVtxU}Et zTW}DKPgx{0U!B?ES?a*tkCAQsbX;UD#TmZ#vLSr0FkQEuUTBj{Na%uENwX*8)+Se9 zQnJ|o%MXqe64Vi;-ND$Yi1_@i%UVdrK}BUWMM09jgEQ(hgdC&qYOPCli9t9g4=(ozm znKeIU7jjcju>50MW4z5ItSIYs&Ue0$=zkAU+-olOI^@9}?)g`*e6HD6C+3Ckr6T=M zgfc0EnBYQZCWg5`@hF#BxzTYM3+=e>G}J;j%dt@cWSO=GBpTn<4${K*L=KE58qJNn z-uTGPxa_-q>$r@GHl)64_5Z~AC3R(tdPmNed)f9Rxz(fgS~J7viu%}GWouxLzkB+Q z$Vm+6dd-UnVu!^N{Gk3c~IPHtG};z~zP=MJ0_1D-hwh)DKFphzw~`36Z@PAyLhi#4!${rA%N zaBYy=ZuST!RI!wgP$1-ae0;25Wzq!~5ol0VqgOXJUIIe&<0nr5l=)AJy}mfsZLkL| zh88?EoSdA(!iM0DUOj*>z6?|Z=plg%4M8v~dR#&R9R9LFS^&SLT!sKI6H|G%R$Fat zJf*aoJ3jQ^75tdqVmZx!_YPTp?C#yWDMbpc|MiwPRdR^K!(JFKBl1Dx361{+Lo@GX z0O_vPf5>FM&2PL`CLZ?G*PN7->=lF{k?CL}uifQE7Wq2n>2$Y)TV2EU0S4I?duh## z@L}&q|82UG^?=pgv8l+IxCDX1JIe7sR=Y8_2$FWYkfh@pRfmUPj#8p$v9Dxx(aHSh zF8KHDKGdhWIS%|ju^>i>xTW2@X)MmA7QE49vpX*&{Wa3B_C&&t4Vy)h%VvN0m*htyd z{5t&KzL4n(IzJ**SJ1b!TN9Dfr;A@ZRo1`WxUw_DAt7B|gG-3j&>@4L7?3ZaT`(+4 z`jl>L%`!wDy=JtgIL5>(MF{c&At50k@Pgtvz9KAc|e2=KZ@j27bZApl@KVn>>ss zq?9gJqYpMl3xuo9`&anKYi=-RJ1@4gwWSRkon{N2jgA@I{x*vJp5LGNs}pEw85s*S ziq&A@UAkrOAZEvRK_DI)3io(K5zahCM$pQv;-dJhe&nh_yeaiN^yee~t8+Cx`8Z>) z;qoP>!)S%6F_`8D=P~k zi@(>_APm^(u-JA-bWpsqlcf|aI1tH^RZtk}?bWKcO%4hITRuGWK*wd{>OGJSciYUx#QeTybVdp7)W8~rEQ^Cn+Wz5DTrb&>QIYpO!M{z#OiPKTq+9Ko; z`#x@yf8_0`@RvNDQmq#1Dr&=3L^zUMq0S<3=6O(m8iuX4#@3|V$cU_m%N_3; zn36Z9X6t&61gr90^M}u|b(G6d5OTWFmm^(SzQ{<3H!_k}w>`vPQE6`01^*l!K~D`f zy3Zrx@BcnQJx7-A)s)6Y%g%=6?O(!Q2+3||XObQu3V628{BWl+4?I2@u|LeQTc<-o zu&p}PZ@Cm-FYQWM;g%5nS2ECpK;UjTmbiHgU0;q-CO^XM;v&#!vcw512+kn5puK#A zx@!Ap4*S<*rNKKL9UUaZ#NZxPF))bA*? z62*pR6l!#!9yp+Nw&xbcX&@6TaOLFZch&dJ0@nEs$48amj-~(YyfLxyII(2d2vAXn zGqfn)@qf>n=v@t%50&-uU71eISH0(6yM#n*7*bB~cRom<_+Z_aOwrX7AtF5>WRRL| z*5!;qycKFsS-O=V;Wy#Q@ZBYxvmnIKR#yJPqTqL7S-_Vu_U4BCO-spoT)bT0yI+^| zl_UaRvcK7#34|D=A0d%l&+hIher64%KmS!af@EM%f+sPR6Y%!3H-@?0|?6$ z3&!Em%2yZ<#aJU=8-1CWET2!I^;$|@SB`m~k3%NF-muqUQ9A9kb`xHiklu)>{zHM) zDVINV-dK~$-S8FZm%Lej$lT7;&5}U&^JhQgXr!+AZefaz$g~#ER6w zeLz?oy)IChNhNZUAX{-@s_;`Ya4<`e79X*zv2yR@9g*eCfbMv89*lu_$z8tKdx)mp zYdw@Yj|pf!LJLOf_|2X6=@ndr{}B6nJD%pwqj#XYK0ULku$EYZnpAf;H?Zi1dFP&k zO(^i)I}p{j`_e&k`xjDx-2)U&v_ObmfJ=+fuq`d;6JL8hG!DU(dC8Fl-G&dwLCe|Y ziS7SXQ%W(4&$XTc&pKG#9)EZf1PxFUQl`XF2D>zUR4VQmCpXp`m3Q%-7qlNrpkOX6 zkR!70$Ci)tlD^xhdpdsaF71PPl8oDhfs9we?G$=QWE(#g>zZulPXv8bP@Y#*%+YDL zHHw08r_u*q_I4#jeCLDrj%yITXc)YHzuT5w`tORAOhkO%b$WBvvFIDXw@Wegn*4?9 zX6XlVgkuI@L%9DgU(0>)nTIGO%W*j^ zcS^@mgW~&Eq!OMTAUHNm=!M+gf%`@|v=#hamVmKaAesN=F1Lfj{?5)$Q)@Bo#bG() zCz_XR6O1YMbxZNEzzE~!9IeNMFELVD$}kwpfg>@4X39WVaB+C&?%%&}$hrqpCQkC5 zckV@4VDgxE z!m@m=X5X<`Dc_96-<^*vzU*dq^FT$UP|na+9sd{6+dF!6R2&eWDJX_e!VEd=V)_}c zqH^)HKd-Z}iE7dOkER8}>T>eGzAqL^Z&qH%);rotIT*~yKg?orb#E|;n?zZZ{Z6N< zEbg@zPUM4+x$}2$<_@B^E6{GS(b;BZ{9kB2cEzR!}fo7@y)S9QxlV)KYuD@ z2+T;SGL@04f(oxv1TPmscYlAeeWch}t-Bq6NDF&GMTvN%z%#`n;5V;Ym3CiLw)KqW zh0eELE+1{e4wbReU6(3!?J^Q6ENbP=Cm#!4IujRl&cxLA7dI-mi<#m#T+=SOMd_`N zsQVO#5)p{@v1lU6IcG!`+qxPHZtmRQ9*P(2!Hf@mAcS5hjA2I{@u}rE!+pdX^Dk>+ zF1l)qnfF$lorE$~=v_=qcl~^)>owPRPEYOyk5tvVVxjK{1hln94&q-62$J7fbwrVr zR435gC7ShKe0{TEZECxLcKBd@^lrJ>l^hl^lM%x99;V~(n~2vOXYf>$oZPyYXFrD1wN5#WBb>@!KZP#y zW`&#Wz16|RBOCL4^^_Yv-c&Z5NxPlsONYgUXO_BRaicntlC&XlP`Sp{a)IbxDQf=m z4(=t>a}L-KAljmT?)LF&eOQ@zYV62U@)uWaG<+*=B5%e5xa7op{6;f;umY##h<=RB z$jP?4hFa=!?6X?`-Ah%bS#xI_?`)iEF_+Ey#1`4e!Xf&>8&|CurlRi4RgI>A-0Abrf4QxL0cOIsH~%~&`wQuC z6$0C;oI7yo07NyBzzH8E1mfY6#Q`{#+42FXP^VA0hl&b?(Bg+4TaYeINZ@o>XaS(# zgu6a0w^3nXTT>N=uU?^D9vF`hfWXsud^mh7C*6W^5T4VNm{|Vqo?8a@@Q<%chg7AV zPANHfzgMkNldDdy1On=<)vvY^*3bT4d+eE&DX*74M*9?CYS3zTg%)O=nyP6*vQ}B) zAZeBdG@{&>V%nzu8A;jM&&7frYisdrD0k#l-|4%ZhX_Bra$4@XkMd!2w?I?70U#-+ zfQ@<(^lf~cgPOX#@GDacx6R}Zys7YoP)i?xlNXAOMk`H+7XxkwSDhhE0ZDraWl-HK z#B3~87E0Ksdsh$mKC8YJ$*TJA;})8!n_D4+Jl^m0)wYIIUV@ZFGxILn#hZ|t!~KGS z_3r3lpM&43RG&JQtD5rJ{$QYE<0M#{Jx^L4;QPkE`#E--1^R4|esHlGmz`#A=z_>6 zU*%*85{1uCZx@@9K?!=DiJ7KD@5N*F7iMtDh0R>8NDUGr5PpTaJB(RsuwB8D13g#V z@?(JCO=d9;q?Y;vb4`L^UVeVazp+G=mD!P`1d^c*?u?)!P(-m&ia=l?jAPnLr9unz zyREeJWVt>!PHU3)Ew_Sx{8-xD0$r*&w~>N@ zv&0zfAEz=S`?*c+t+dc{j8GHm8NP@H+=yXZ!=oCg{rRsO=o;)!k;BwMt92uvG=tI-a6!W8$dC#SJdC|Ci z@2dEy59S04$!rq&DxiZxP!vG8+=Q1#1nwI@o+rq-fjBFCdo}j`yDfO<2|odZMiUyn zXJ;or+mEz--FCc8hFnu1*@H+*1VHhi0n}$#%NjX_aL6{t z%!ZE17I1R;=Wb7+1riJSP6JKn>pRr;tAlW85c;H?YhBkpI;xVdQuM6Hl%SxbWbVJV zBVx=zGPi_XaS{o6`ULANraJP82ssn04Hk5Y7qqlq*E&~gkvxK}0{ptMNi+lh#B%!g z;^}nJDn+yj(9M~W^C7^{fHn{jhzKKx8#oA!AG5;VDn}BNVA$HJ0-!AEyHI>T*jG8^ z*(vE1WKGMIN%=;T{I22V;b3b!(dGyJb;SqHIN%XW;xwZ|RowYW{6gP4qqWM1nNnZm z(UH&oKI&%;sy7K*40}@*nLr7em}vF81fQQ(E(at5!3g3FMo+jd0Aptx^b8+w?@0qU za6F4)|2Mo24kA+mi|Kd)n~C>?oD|Q50GXR=Oc2?3A4ODcheeu=LN8^keOH(r_aBC2c%_Xu(bit!W0_?$p|jx_fiTLZ!(Rs>nuf;Q97{E z#aPi-9a)H_KI=sc;1Uq7`AYkH=*PU8ZWE-7GnbGeYHmEU`{`+S;~ShVS4Nzt7Pj2@ z<;M@x->)VK-4w=216UGH0@jF#bUk)Lvn;_)K6-VfQ1e>KVTK$(d?sBsAt1ZTg&6Mm z#*ZI7vCvP>&r#R6YbxJp%drlMcqZ6XS^1%7MZd|ludlD@Q7U-Fw;|O5E_#zH&o6I~ z{{H>D<@c!WD=c%L^~wQ!wti$=8u&+b^ezX{*v`8`bVPqYFK%U}8fw0HEXk8N80u=s z$@OhdRR`Y5mkUOK?aqlOYYz=aLKR0o)_OkhuP3okW^QiB)Y!^X!mW?VP(*8;{1H0a zw}JivJ&1#YZe^usna5p<0xoNvKe7{^Hq3Z>v2vt8#m%Rs`%A#CBvb&}~%T3u+44M$h?yHqk#=LA^(lnka~kdPq#g7Vd{YPRzv z+FR;yJqF2X#&q~pmNX=KFG+VRvT*JRynFJNrg*ZY-eK_>9$xUuSqi6369lR^A_0Bl ze{*#XIWXXJqQFoC6?IBQBKn!&OXYF!9WzGw9?Yge>WQ_Q2hhJyQ=VTuW&qY z)DgcGLB{VJnW)nh*3PweR7t2BQRjv`N*>{;#pI5w`Zn zC`&6V5ZF(nHfexCCX;rx8SoV0;4ci^FaU4b}OhnW=fn&y3EiuQp`0kxYgs}T6;s!h(@U6q*!rj&PX zQXH!KYh`WlD|p@4BT*3C+jUC^h8+x553u~t&Ef9+2&apOxIVIKG~a>;H(;x`h5{|{ z`yNkogV=uY5pFPqt0N$#&ccF*iD|E569~ylxG&1Mx*i>EjsfN6pVz3~H|V9Zk`e*| zS8b?vBS*`DV48eSi**R=;P*{up0o!mLQs^&;~TGZ1<@3F8L?_Ln=kZnRDd?BF_i-M zxQH?VxYXZ@f7bJZw3I@+9x6ul_Q*R!d}WPA49sAokC6=xiA7e%zP^9Ar=C$rx?XP5 zglm-D)S#pocNP^$h#l{9^Z3sJcYr)wzdfoN8km`wxQy9pYt#ZGAmLtaknX&4Pd=6)1Q{nN z>r-}I+`tLpt5vhIv{GCck&myblW~ z`I}j5wI)(+l17n4c-(K3aa)5v1%9a&P0;%Km0tPJ^4+i%ogI&wL>=e2Cf!(S)O%R* zCBJp_$_^=pS1i@zb)l^=jn{=XYzy*rz!pp~%B`xeH>kIL8b}7nQ8;>W>Yf2H-b)|@ z*oqopd4%Yag@wj?gWQ6Z^*Dt`7Ml?1WwBP8Ex;{i~XlWrtoSfMp-Z_=Rd01U@ zX*Xv9Ubgct7m|k$ae83Am|4Hcr0p~bqbzG_(NY~pWe^aQ9UFy$R2nI9IlrS%1It|r zQ;gPM6(5NU>bMnQ##1WZK@_wGd(_|=5h$ic2P_*U^!lBkODMyWSwAt+|EfrOeiw^7 z;1%twUq)$S@33aJG^?Z;4O+D56W~!7^f}>}aj$V)`UWH8^|dvHk1R`&KIYtD^SC^* zLx96wS56K+ENAPZ=CQF^0qf>B7WDj>Gl@mN(|JYV>!ZveE0}0nQjxP&aVU?x9Q#|S zXqYM74y%VHp{O$8ruHSm1tg;1?0RF}r#eHh$VmA(J8nR10kV)MiiU~`cG9APFe)^1Dk_O0wI~8saY5@s%V`BsEQAiI5r1GGja$@8!#DZ35X3zq`>`sjHl$V{Z z2r6l&6z6j!7rP7i_;(lu1g*jzx0Ckg6pL+DpSciOV4Pa*GN`PKH%)Cw`0SYl?6Aqm z8fF@DF7$M0P(GgVIUzhdXO^N4GBR92@a#^IJU^xpFh^a52$33p?9mQEWZghh5v= zu{fgV!QHdn7sT zXhQuPKhut1OrDJ1I@RO%#MJY#Zy2oI4;34xhfnU1yGbd=^m_G5vm$=)Y;Mzng@A_S z;(Fzs>YfH~P$UO;l1fo2zlTLC#tZ#og$xenKW15BYBL)%w!6)B{i_WBCU&$!neDK9 zQ!lvs`uXYBSxfv6_h3`}9U8<_3P7X;TEySwyTQiCqNK42Lrdy@puS^^n|_Tclutc5 ze*#AQ^}RgSkzlkpVAm2=R*u_SsI$Ez%4yr=nypSR zeLQawS~|wwbm`yx_oy`~h&VevH(iM|VV!0{sMAB!>Z*(<;w~QB8+%#cvCrvd_sY!qIa755XGgf%F4o;^E|2#~y6a`*4uzv@gdP57^8#h9QT_RruT<9}t=kPYfk-Y=^V5(~jxJv`sr z+e7cDwVhD`!ZOSw-278PT!)tmwpzkZHeic};1I-cN57Xz=d0}0y#2>VX?I%bww{bl zO7egpK)!6!zn=K1si}d15=csb_>LBch7t%>31FT$-kaxVVR3|884yB;`udFdHCuzo zL!re=^YC0acY|4P?__PThE&K_1rM6Q;3vbhI*^PZ5yR6<`$dWKpv+fuaY+5zMJd4} zV2sQMh(S9|s|jJy#rtY;O7~MY`^K+B75Gn`82{Ct3~~Tq@3zw%FD{On$H>ltaW`8& zb2UlDoCEwF+84{y9whK1rD-48z<=Bdkt+wV+LlGpmTMNm}u#OQRZ}C4$4+ z-DN3cxc1vSLxs_F$DUtMesCUV=nH@m9(=k{1DAMf|#{s9IvLfP-iUYX5%|NM(y zy~N>9^DjqG12x&!NTbujx4xKf>h%2_R}rXgFIGQ#4d0k1(;yCi|H+TAHW$BHHc)!e zNg^Ee*Rz|6X@@2^(ei5UsD^5Wz2ZBiWlp$TQjuMu#%JPKN}x1h1sfO0rxqlW%wYsV zk^|@?JX~BS6D68Mnf<>sctJH#*U@=^0PhnDqDo5+TO7Wu)ObO-Om^3AmLvmK5LBrb zSE>MR1Cr+M&JMk*g0yrW95$ngc@M76T_BbTlaCb;>pdRaN4Wz61l&=q*=2hz^bchwCF`wkt zhS>fpk`w(3LmGo5$uz&`hsSF-|BtWl4(Ia!|GkZ*LXyf18QEm7%*ft*Z`s))BZZ7? zSs}88>^&lzWbc(t$ljc1-|zK1=lpT5^S(aUr>=VE;(g!u>-Bs+rqkFi0|cE+Iq1j7 zOXjL#`ii9r9_-v{D39Rt%zNJM&wc+W^(CW9x7V+-Ok3I5B0Cb^I@j~r$owLbPpcgl=LWN3 zw%l?G9Dmqsj7Lk1M=O@GUyv*dS`8%+=XdYzsxB=}(PO=fp&PY(fMQ7c_Pk)W-ge6B zcq>WY(1?X&PI$OgCe!ncYk~G!?{qDe9RKM_F&U0}jcOzqWjb&0k}Z&tdX(`k>B8lP z+C19Rg>a#g&1EJ?m*(c+00k7t{RhKH`SVnUVBl54=LFqhaj_CDKDr1Z4B#c)5zr$= z5TFFvW%&*;0D&2$;HA**u!XDY#Yb`7U=6AVH#IEZka@D?I4os3WK9F~_ukHq!^@Y7 z*%M!>IOH1P9q^^V0~Qn<3~5f3m|(bj0Jx}b)k`C23urvss*R+4esg_C;&0nKQO1T+ zN3)*8O?;8h1m=sYJc}K7lvKJZRKFv3$A2~ASXQ2Ts`ol70+#xS<Mb|Ew>ZRP2eYp-s==a6w#O#Gplcb+Xq7C1iExyFkH02fIaI zeagnxPqdT4f^L@B)wAvDnlGt@7)Z2)r`)#SLa;|))&6|VwRW~^)835^FG87M|KE_h z>^=?U`S!X$LGUq#>Fcc`O8+aI>|8q?77~&dBXj5aveQ$nIDwDek7^Wgk#YSA@nPwE zm2wODSU}=3W3VDtUZ9)bD5H~I2;3uTNG~3%G9=t z@cQhZwMh5n@rm1xL2~9d8174}Pi8zx$vZ|3e0o`XcC1e15rl--5gmbi`fCV;S0i9C zO`Q0vy2+ZA5EElnrEBLeB?Pfs#wI3#UZ)EXWzJ>Pj1GDGz(xpw*u{w8Vff0z!d*PP zNB2V@5(h#axLwv&A3x4!8DK(u({tXwZ2=t}s2`%C%t2e*<82MIN>oB z{<=}I;SGWaA8bkE7zAo0&0c}M8%5l<)+IkX9Cwdos&mx<4b$eSKa$CtNrliF7@YHy z^#sTsow&_B902C={BB$A3GP5(W)u}|D@Rstf&S|BXd9T|*ZZqVe&mYy zn**8MkRJiZRT#-2JUdV4%idR*-XPkv=Hf-e$E% zy^lJ7Ht=~Kda##X6}yc%C}sGN_|R00UAv#5Bi!{&NksTs>;2oc3j+MCeLQ_U3xDqS z9sWT@`*T+Z{hlnkNR89@O!Dc)6Swnk5m0@1L{|54JlSH|eK{dvWlv!CRh+3sI zgmL<7m&B;VK1mWWLjU*)WqFC`_mkgZlw2yJxY7oLXcDBjyb{cyM1}j_YcZ06pQF@;wPX66*HFVeWfq2*4Ks zuhqW(vv}V>HOZ;ItS$`&pggs>>oiRLlNfx+UUZ&dbIZC^sI_E z@unies#JrC{MB0h>vxRbncYqiya45g$j8F_;G^gsYrT05$#_OZ*PtkMLqP=v;j0*# zDBtVyDfST(k79h-*Vdl>6UV!Oj&wEaD&vGAW^cO%TjFy1&S{q*Zs^CO%`5Ilw8{pt zw_b2s!PZ3;K&>j6N&JJ|jSUqsZIqAn%46ziPI_~3ik)1uSsjmx8H|d&^#84rna(W9 zOy77;=KUb&$M2pTTD+F21WP-K8da1DRV@Esr1fs9gQ{4_OW1?Bk~Wu?T5}~Hm16Y3 zXe1R?=d>a}?D`<+8H8B0I0&$^M$GK~N6q?AQv94=GElP69}Om>C@O2M8c2Kx9LV)n zc)RD`vYgghx*{!TqXvLL^SL~MJO&e!1=y2UR{kNpseLP>yGy?Y1`^pVGTolpC@=53O&CQ=DyM{>)OV!$&Ct%nV>_9j zxPaf=eZXvh3K6LijdZ;7R-4d`iONMq;;U;Dz6nNh^z{XVKq^p>4_k%j&QW%8oazmW zBanH0^>C>)MM21uD}>7ZQE0KIeYm%yS;;gfmOj@?Bd>@6%jCc>yQcq$Jb`!f5@r1;ylx!&weN8#;VM)&O2=_7&e(5D!KDi$vHV$PJ;;h`Z9n6kzVT!I z0Rbs#fqMR9`A;4D@kMNqU=f_2p==2V|2@~)I(K#vTpO;WFeVHHlGY*90*LU!TjgI& zOuv`!;$&gBmumJ{y%{Yx$d(S5O(+>DGpU0qh7+u{kcwzekY zb)=%CG--Z!V->O|K9G07RI99_5>6(>jDPcn-&nbITzR?6%a^Q9GV0GhtkioEH`t8N z0B}4sB1nuI;dsRS#t0WZp}HFTsn6wTdivJJs5K!Go9%(xv4ljx&!4P*0+)Mz^nZR1 z*qi5HLnLqU-cdT}-g*drztXOW^Y1r5BU1cgJD3<&|JyXZrIqg^M$*1>WROxF|k%%HC}lwx>m7KH_!4BvJ4=Rn<~f?$j&i?@3%oMGj4OSTQGf)YE7}f?R#zc!$1oU4{!Co0*I!}JbE;qu(JLd z9DHkZ3=-woX^k{Ro5_j~={W!l5AGd-)7|;48^9dQLxo&o_uy)(;2#XXGPpMn#2aL< z!+W7MmxRk^tkj~9zRCn>rY?zRzlMi1O+q@Cc45s0*KAcz4yJfNtlDO#rvF&H)5_Q^ zU-B1_re$eq3899Ve(#^914a$c@+U3t6TEWO#8(S#!-VXI6*koY-P4mb2hnm#!FYJI zQSWenRH@|)dLEu@YeI-}yF3cYOYEd8&QKH*DcsJZEveE{hWb+Z>}#dkl!z$_>3CbO zThpAcpxy+>29MPSdx*$gfn&tCIU}7d9OaGmgN@tIX*_t!)`rHvWPa(Jf`E4(1>QO@ z-%g*=8v|Qae|}gQJoT-|BHFf_9rz-%g2Rj>SgP<0%>AE2rf@_d8 z-ub<7DfGEo-P)QNM$Yytv!58U$C%!?yaRwC3RAOX8MxPq@qWIi7?V^tVDIru|aBGoX2hde$sjlLwXE^ z2jcAg$N`)xH(^s%fY64gA+0s9PaMtMAg(!II#X1sjAMNt76x+60eBS>D{%_3^A#zf zql&m>+`^WMf&g`p1UtF8jrR8wa=iHEMoBA-J5->@G@0 zQGsCLAt`A+#Dml%488AL0Ts>(Y|L<`p^^fH4nIGC<5&6p?9XBMc2Aw9dmNSN2dwHD+=smt>hv!$>=fBxv^) zzQ~k8ea%fY)9eHbdz+-ijTgR)twQ1Nr6UqfFV8Jr4)xlW22?&nB!bDDZQZOwb}dU3vdbMUmR_!qsD%z3;x0k8AJ`agd! z&O8G&eYo-2y1k8mO&|{_{FD~mM{w}-Zw*ijE2V_oAD(rH^d2oAWiEU;oVVKc zbC{uWI^v{IsJxD2o8EY?a;Gg;sJ-mt)J(PGjy>^D>O>rU=f#hntvuR%UG-D;#%1yjJ*h&%kc*U$n-ga?x?&P?J z>t=0>*&(AU+Pm@{alC#R;mxV`^o{78-^k+yW#_^1WL6KZ0!R3c|-6)q+KcnAVc&d%6HD@iaQRmXkT z6ikHoLl_zaI6;EuFZzASakM~3qh<%rA-L$}x!G+P!(t$uf9RuOdt`5xnEf=eP`4Tn z8bud&Ak%31XENw`bPgYa5qxp)1TP3eRwUCDWs~{T3e-2&*WocaJ3SpqI#DLjFE;is zDzb+XE%+u34Gl#_n**?k*TejEVwHlQU2|{%bu0XznvM>F*tGOh(sLxKBXO-b5ky3Z zK%9agOERj7RaglZ3l!)swl<+UW#2Yura}AMQ2b=?+W`5N(~98Cw>Lk&Jx=02E7Th7 z&=J$pC2=}tMVd^ubniz$sSu%L<#ah+%O0DXJImLoOcf-R=$Duwcl*dlal?-Rzk+}( zbnPK$!`5g7{oMpY!gE1_fH^fib*(jR%M96xLkwhYWo4As6Z7M@>B@~Ps-dIf$%Tfc zF?&J+f^V8oAq&VX2((tu z&I$f)T&@{PhyPAme2xblL2qI86Q(`2pQDMQa`?n`;dkd9H7;gosPoqXY!Z?le%G?y z!~5Dg>@3wp{vcd(9mueN;sBfJ^@jvw9bbs1PBytk3na#Ej!xG;_bJl79xeP(`$~x# z@9AW1<-%9357l%xp%|}7_YHZ6#V|chvJ4Y4oJH#MK{Vo>OoWWFQaVW4+Q-S1G}-e2 z{n%W4nv~p3bV@F?~+sl`=jgGwOZfgV)bx`T+=a6#0OC&-SDH5 zdY_Jp&^H_b3Hq9`kV0)yv^ z{^lw(8TEoiQsZMhE&Z9pEV&!8d9A8F&GWlxP)W0H=%ELLBWp}q%SvpGBImn=)3d}hzoZ8>In^Y335fJV>MK@gaD zC2%wBYG_6|L4gA(FvD-+0_EI)?S9J2%}b7Jw3wL&tv`Ms2rhbYq0HU3;l2%sMSzss zV0eXu$VmTtLFD+qummcra&1VL7`94~l?W84ks4@eL2Gx&RF<+PDA$I`ek};Yk6c

`&nX!c6K`p{59KI<(&4|P zcj`$QgaH?i+qBeh_=qLh7dO75G9vg0Com{w0)A(Ie;-Paz-03Kw=t~Kaoymtlg@<5 zXPgI0e19Q6(=NtKqAC-T|D|PQWO;qv(OlKEQ+ z2_LkFCGT8%QI-+7yKU+I%-3KIKAde#-Ep)Oz?7AJtzJ;GH)&r?L9qp)_rnQ{1LXnQ z^w>#!u|FJSSXfqkkt`Wj_*i=y1a*QKcxf%{XX_K0PGA{j#nRE#Wc6CA1;!JveFrSu zj^32fov@WaL?08n2r3%d^AAJ^!1LyYl+>n%TWz-&soeMxYh12Cg+9~2s@t2!T_0YOPHCbqLOvazuNdiVHoV5_lQ zJSzn)ZO)s69<{*REFe1f`Ad$|lpz%j@sO=k1z3ry9ki!|vp%V-!!j|S&R<-3Y-h?4 zs~wnCSEohOMDp0puXTpb5D~*JC$TwBDKEp%{c=tzvqqbs6Ur}HygjqMZ6SdFJDyWg?-6{b95 z^U<~MlcJdy>T>19;%MPIyxMFN)A+(>>T5AmIJ>ySKvT6ATiizRqd4vQC7;WIk?iXf zK!jdN$dh_tr4sQJmJ-(fq4)|dl20q<#!d^`3xyP-adT4YpU*ydbF0mr;A0KBPdC3f zX=Sc;GpJ0doA7>0LP;IU~@9&YfzxUBcq_C3h#spS4gFYRqt}rz7Yih z!2@xMUE1@HIiInn=huhjyu6sErirCm z>7oSqUqoori;w;B{qj5^7V4$K7vlR3lG*p9lNiUayVIo*Z;U>&8kMw|CWih#(`JrNt)s zw+2dfe{ZE~x?f2T&3O8p5MTMsg=8jQW^R1HZj6kf3ev~kdn_nW{M+bNb2b0QQx|&6 z*UAYC>gd1}Mp0SXf9O-pABHhQ7e+YcT+`BVK(6&0UZ2E`u)(OKLLZBZj!nS&naeX$ zyCCet2khIoePEx3&ljRGUZAv@m&zzawHm`RG!7}I{QR{wH6E{Cfp4|My6M|J5!@)M zz1`hBa=otaKwwW#lOni;gj$MyKwRA2-28}-Z=$i2p_oPMV1sw^*um4QK{knu=Eb0Tf)>Su9npWsOe?iX6+$k&$-;;zhR zrqTM^KF;BbcL`$jy)c1JiV=_gTYM%DBFVUZ&h+&3G}~`pkQ_8#%X3P#Im^uj(_z9< z82W)l;0x{(Mb*N@bXw7TJS-oV<>U+y zmyp^RHxJKoDX}iZgu^iUkFez8a&>Z=EVERB$zW|8!f6u{2+>90A@uk6#}*8am84?h z<_;w9XlnZWWGF7}W2eWCF?L+-O_8vpKe@S|I$RQB&W_ejQ%Kp~RiAz!L~TDRx2?Sy zFluFa??*fL@u{)&lHKF%Sllvs9i5oOE@y;>+Kjp*ZiS_~^c{K78+o+)f;#KpxYC(X zR8sZ9KU2qhcON+uAX@>=gZ#v#u6RTY<@V)?``+<8iHsV3K@gN?3@XFOxqT(L4%`h7JlXhC9kW_!4SI)s6u#9kULm2{?iOlrqBUWH>j!oTvU|$ z>C^dm158X+RmULJK@j+a;Zn$CD#N&cmJGlCE8S7GWM$4&ri<=;NfOs-3Vn%bicme^ zFDk;{&JZhIt__tV+66S2e$4LnH3gYG9d)m0Ac zhXKC&nKo~v86CE`a&0|DMa5*%ccN*5f!9M?Av0Uc)%6epx!oY#132eCZ!YiinA+Oytwh??49Vi;c-4q|q{CYKYqn=st7VLo&rOg4 z-yj2pS~i^n+e9P+iJ`uUhoG+>qt{E%GDo7K97UIqhY8+Bd^?L32JUJfZrB?f2G(U2 zF3(L|R|~?=*IlA_pSsz!vS<197mP+MjZgvsQP$ANbFtpAj~V4^b^G@1M$aR=@y|M$ zkyQwiN!HbteqnPFk+PjpzbNy?vsjanE2(#32R=*~h#=$=MBk;QP8$%gz-_ND-*&qO zJxx*5df=MhXE+n(ZQeo%SPh%t$imLX2E$7Q(C_B6-@Zeu)FS9V?x1Tmymp6DRH9DG zKIoDJmLLA}1Tj~G*BO+>b=6@Ia7ecEIw?bIYn2D5aXU_0c{x0G*d>WkU%!6QtI5e! zt`KHrV+{RL(5rhY5fz%pI8Ls&}38Vd1UbD5m8>Z_gE+)S)uM5+#e>FuLCbH z5};frP8v6v)Qk6$4ePtL*C^562TuLVmZ3l~7OYs;Xwk5HKc8C~+H0C8ql#(*wXm8P zchGU2mDnGJJXe9s(wf1^B=uS2+21F;)YNnoThsY*Qmy!i?;|1X6{zK0jLyW3FX%-< z5M4P%MAZ?a8n3;8K63yy!034LiP##Zo^&Q2(zFDulQUJJ^6;B<+InX&4MR-6I3`vL zSOdD31_Jb<^gu&HLq|tPL7@mdw~&twzEOyc@fc?3%f2@3c6ZqNW{uyY$ef#J9-f|H zO#zmz(4cV!TpFJYfMNq6)QDgNK1!I5x%0ATLJ8TK^=j}RJ{0u1JooiQVBdrFiGm!H z$no&ctX{48Gx6z9Lg2g@+zsIgJ|H!d>g@lSoXN{e8_0e>K)q0dj~g|A-FWoN^V!dz z^V!W8+uKqOkH}m$wOhKKcK`MX8ITHMNe(c{NsOGN6uLB_5#GXIQ~9`S~oMB$NuWv+#E=Y;H=BF>>1U)r0zZp?BPEQ z>)y#yQR5}Fc8%K{0*OtO);|Pi0~nQ5>4)K#2WqRY?gjw|X0v&Cowt`yt!p|&Wm`K1drY3=F`8&4sA2X&y@_=Ev8RjZK!QApo<oq$i?2Gnm0G!V!#!X^L^mcr?;ehrj4(I9C@B{*;>82C5<)Q?%9bqdgHDkx)kOu z{`r;ckJ7{v^;=8^-jHO6*Al8-LE?U3)uN-A_k5^Z?LpL|?00e$wCR}+-QGAC9BMYQ z^0G|{zC%$%K5C@s59ori2C;6XH7623SEdfHczBG7Oc-4hIGKFy8uRNEUwfpub3SV( ztOySi1OD;jq~U9w;+!5+5LP@p%;jK&jKq^yuI1Dxh3#-Jf;7!;ylvkM5;~N-P?BVU2<*be+!(O${2oi0BlvK4J?BRZTazX4YIoesz`% zZcL3XKXM`n$TzQ7x${y+s zfZOA@2b35)X;| z7h4N-k+6qPgUKb~C-|8VzROB~Vw`h&qJwP}j{2 zUS7<=!K*nDAjaZ1y8kkfW3HE*JdeA_fQ!%c{=-H0aQWYsKo9K)v6`>*+_vNXah;Zv z^=I#{-zJjkqLHY1fk$2V$$mP#tXiQV9Rg*} zqhEBf5MgPdnX$inLm||h9=g!Lbsb-PP5f<_>K?TLbE7wHPi0VFWm&e2VzxFZv%Xn>8s?vfl{^xJ&tnvA&KxI9Tx2Utw4SVq#9! zt_7z*EHLnC?o(ij1lwbPLCuikqU3TH+v^8Kts!Sy(;<%41AqQ_6&Bjdr+jr&>j(-O zU-v!@YkKB#q^d|gN zFS8zQ@2E>tgCMG6hBOaLcXxt!DZKghH-s=Z6HglT}dZZ3oCK% z`*j4L=H7fPL)5g*{%^q=#IS!dpuF62`S**3G56nvl6(D5eAdH@4uG^mPX)}=W|P8< z_l0~eA^Mm`nF$dFz;G!3yQZvc&&FsG1?EJR1Lfcl;tS3_G29r4?*|k%i<7_#753ES zkpkD~$1RvqfI}*V+;@1uG7=XZx3Y4zx!`2KBu&y%CMW0Pef$fc>E%Q=)d(&?Eikd6 zplCsQDK_Y?SX=1##og2NF-o^hzMEKRMt<#{5! zh%eeZl5yHRtGJhHm>u2nx@{u`0+z{-{-rJU&$r1 zYJ8JdN>$ezXkELmPlDjauLu@d)lipH4ZEanyq~+HT#o-*r^H>`qoLD_{f8MQ0*==R z`HbVV8NP&JqSn?{f&j>`QL`!n{FmnO<7lc*Sn!>h?8=T+n(X^w#YMAdpg0ooWrKwXr3$pHR(4)p%Xy;gVE- z(86hriDj~Pa&fpx?6OJpMTcNbnQ2)!^=%{p*%Hfvw)VJ}1750^NyR44WE?Nc)%5;m zrjW^-omKTO?q7Y9i?Oh<6!D?o$E-$%mx`Kt9$F-GY~FtZT{SfRWM}`gqg>y}RL@62 zUNXstKx%0uRjw*Mr~WSVV!@=x^Ah4)Wy6_ZK!?3i2_H;mbpL){qIa#k`X#0#fwvFq zJ;iWU3CMhMoL10C`7&T>G*OUM(tKt8-LF?dLc#6NXH4LcFi3?L?eWD6Qfo!898TH1-ZFEy_d1XG!aiMn!HyK<2Wr^H>Se82JThSR{n zL@04PLC}+dOzpZ(&$}OSF~t6QG#YAmU}@;DpSi>#GgKjRXjLA^U6(&#J$XAC8L zSj_1M^}6QaC`lU(k$S51JSD31ne8EPoGDB?NMA4>UEb@Sn)*Z~rOjp;0n!FjGcyz< zez<@ofz$dvx(Kl20F%mEvksv`Gb?3FvxHtFb6N2lTKdN{%bL)nNJ_fEte0-p%~c)~ zRaVx0m&WD^d&pEnauaKO>u$V|kGz%DUYb|}L+j^xk;lQVU~03ImJXS3p&(F~$#nb3 zJZ)b`7fcRaDPk#o=IJ6J@C9Lm*82mNE{s5zz+2 zBU-HN2|nX~`Db9x{hD;3oIhMHux)H)1a9*BcbOva4iu3H82O+HXHZY51)>bw+Au^S z;E2pt@LkcGLaoBptp!2|LZvaDJj-O-Tlo6<|+4fAVks z(I*p<$3yQicT41V^Hx_s!X_S5yXn-|q2xxzo)^ zAL1LRZ@}z9^3=l_q~Z6b{Hdfs_a7B*6kwdUm2P~gDw<8=H$G$#15EvO!?^dVNs*GfS0rqK2{5rI1s=jAgp8e zt~1M)XAQPm7yca@>Spn?j@OIt=)gLd$_StOAIs{hUG=S{C&5NAwfa6*c~ITwx%nCw zmc#A#SZQ<-Oh4Z{KhjOwM;6-oPtU9g310k2`RwpNT7Y%oc-<7oBfFkR%AiWSc}Lz* za;h*f%-_E%?JHe2us$UxSbvv%AUCk_tjH(o^2rF7d}=g~n3@4yR1TF;^2wU}p;NK) zxthTPdxq_!Yukg%8L@mdzg9OkLRx==^zvsCcla8IK~zM9aQic6TH0UvFVn~227<#O zhTrGo<6}5ajr8VaW@SM&drYfwu4QUJ>|1O(iHIB)p}d%)au@lkT(L3vie z*RKcyIsVRyA{YS^&p*aJ@S1B1d3zn`5nP1T56Ep_qo>5g3@j{XGxY_v&bc_*kVcGm|=wRxbkj3*dV-fC+aIBr17$$i^!3X z^7q8|JMO;-tKb^E40Y~j-SOXHI;zN^UGMOvG>1%Bd$TtA&2RguCtL=pxA4CFn`}s3D6ah{orHk&75tv(A0*DKgITS}8@adF8 zMO$@E4VYaMF;5Pd#%#F479bztU;L}&8wv`Dn85<}rHe@aebFdjOkJiWFuAkmDiM0~ zv`R^_9Bzid=R-?(BZ8{g7zOjulTdOgOus5VzSkxuZzAu2i63GS`upeC*5D@UG`$%q zNr#u)YV2;5#=)(jr0APJjEi7~Tzf(BOi5QyPe!2++StYp{seu~l(l9bB4zb|blB`4 z|Mq(6moHDMN&Jl7wLZGx*Tjm6yz5>fCcu=HbC*keiH;hk2)^Gt4x5@nWE+eDAYJB4@LaVGi#PaA2?eYz_2ZYHy>z zc}vRAmmJf)*bv_z`OGimzknVF#=X+<%Ha;vx5+Tx2n_7&K(Gyi^moYX%;u;Cl>`Q6zlMv?h)F)Vj&=2m%4 zj}=lPsKz0LKg+h8f}DH~Ky83LEE4_FwvaD5uy%b+=Ig&wrlOOUlJeQ7T{+l@8d5cL zDAs0fH!b1bo|Ta*iA~XWQc;1Nb6}S3UyS|e?;jW(%y6-8TS-Y1OgAx_7qm|~^9eYW zj--Wp;n19%=Hpl5MrqpgYBE%yZE-iE@HO)C^n`~_Mka&-e|>T?slw7^CO0~)ns*S? z7rD0gXS5|1-$gto8TI&-)m3+~)fCg9cqd1_M90q(Xi@U z=QVx$MB+ytaGUI>^Qa>M=-)tdDgFpTlNsBB1JdMCzkf?9C`c)=%~z-_V&%f1rheG{ zQ7%O=*^)W{$R$U0R8*s8^#p+AuAI*rm%qkBDAe>t{e4%6zwxiX|A>J$QqpRcL*2lD%vfcz1{m4k(W^hHJkTC4#uzLg~;jc znr>wMC20-EB7t_CuyoqHJ-(ohg%=!AO)QU%;MKFEP3ZP#Osj&-5TbksK35 zC?<)1@ExT!Aj1wxr~z%{dL^0T7PBeW5XOzV(6^2pw1GgRE)pKvj#S>PE!AY4(EbB6 z^7#1phq?`rwU~C|A-=%UBqx*BD`hH!HV#_l2-|lcsRe>+;z)(TNvT|*4yVMg+U0o- zs?l5o`DSbX+Jd4oG#N)EEuAw;2CRQ5;((8rN{Y>m8*VPK`Zwu{TuGJ~5;fN7f0 z5$NHqN#ovG7)!s(Z;#RjYcJL2bXS3F@5ZC)GcmJI7YVAzi^|2auKWB|{L zja7T`g7yM})RiIbt==j!K7Ms`Q*OoiHa2#_^ZBG0X|qk@P%RyuyXX+1#i^XA$q2fe zIvV3=c)!PFbj)ubxY(M@n`}?mE~ca1E*ZMIK$RKWvIX1FQySgf&Xn~kx#XVSUfai0 z(Fo#uZuvPxJU^ii1(_Rec2!?qwqr10xO&<)8G)^G@$}PIcxSJzw(~=hsy*|lI`f_` zkfuP^vugK$?%5&QD(P$Fm`$vM_@T}xk&?p$CPiT=m_2*(8ey}q&9wFmv85sf?icYn zd^~x535HT!^c&dNAKt%zQFf8_?b}P((txmnMqRliF2omfZxt{4)4zIRh~T2WnS(sN zlamujhqx2cD)8`MeFnU%!0n*G?7AB$2>i$)I!HoVg%+Pm3eKvQ$Be~2b8C9%<~G>g zBnC}vrNyOB2L123I~*x|CF!?qi`7kMGfO+Q^>E&EUIbzN7r;p^)&8%$A-re^Jt@<`^Vc+O)q!qucqilSSrve!C{8FwNp$9Z|=pI!Q#fSxdxs8U|v(3?%D1QY*Wm#F-4_2G~ z)qaDTG;Tb&*`T4Cm*l5`&jtL(bAJ_DJde$+!7F6a9#&mly|lRalIIgxxPh4~_8wNH zi59_C?e2aCY57!A#_{HD%TQmQoW{j^~(yamlLN1j_*lE?;aoV)#E>!5)V~AV)L&1 zJQCVd%epzHA@lbRuLk$04piY^PDeYlX9WEl`tQTK-!oY((j~_=LR9F<_c1hYQMraP zAayxti9qZLuLkU|(}ydqd+g--%dc~ukW{{rj?2HHArnK*itfX$>OlRBSKRhh8H%vs z`w;WRh|0<%sDOu{T%WVeN&r+w0%d)O#2D}2CgH(tcbH&+?z;-AlU_!W%nerH=u<$V z{M5T9hCvVirntJgI)E`S;{Dg{2jW>JrASRiby|G31X<=d&>>>AsM3Rsf*>H0DrkX6 zTnS%1l1i#OoJAZ8dD#(P*NT(8ZaHy|dtnO*0y37~E{4?48f%l(%H(t2C8WPs_YfqW zB;VZezBGv!T_W;X>MD0SRIqr|MC*3S@MhmmrD-^GL-d*ZE+-?AEi!UT=1%4qrfvKY z{lBYE8VKRvMRunVu6t>viQFj*T#9SEp2yn=!mYyX>E$UG>%ONNf6djK6*6M z=mVTNkQ^$SnzYfKLsp#0XAnSwE@DW)te5$Q{QdpM2%?=DGfZ#L6|3xkDuT;|Ie&FL zFb-=7zBmJ(=;x{`0zYy{;&T^o9~n_!ZW9cG-fI&_X=!EAsag$|=wLb+bk#?_?{|NY zYe7M{l5K?CUcEiWd8j_8UPra|<^A79>tDBn?5MlqOQtO+zt^=K>Q7GhPXBuh(8Q9_ zRbWt-ya>8z`SmM9#>V?k?YSGS@5pK4uwk)GOPna~P*+tf#*$(*jU3zxXZvf>2?_rK z8sQP=4A?4xIC#LG2U}L-SPax(vJ`8c>wU?p!H|lAX$ahF{4VP;%DJK8;gH0a$qDMU zva%+JPx`!X$T3B5ArWNB5m*m+9lvgXttc!E=RySLK6F&L;(B^|f~g8uVAfpN0X>HT zEMXU|p^>n?cza*&E_E~H-0l_u`!9X0cXv+F`v2h?d&-CZhigP*3sRLQL;a($8jIWv>kEL;RfjON4(0v-C^j-%W4u~ zTvY?g&^ub~XB7tL7-f?O>$}2emUg-W$ameS=i!c^2FKZnATJ z4i5wFsl0f{!?oXJkXye z+VwBHcf7Lo8y}8wwpB1&HP=ww`njRm^Dcsp~qu&`@4{=p*V)DF_em zgN7N%V0FGccPArD^{~ZNy94ASsM}>&*i@~aWBNha(Z;Jyph)5Igrmp3J9lRpsa9h1k}q&Q7Vp3e794h34jFVBOXqw3?SvU=Dn9 zPBVRygb_Y=aR=EPL6bPxvsw7FI=5(QLI3%8rSriD2B(RA->W@wf}0xiOJpd^H+c|5 zltx|UDpvVa_u~V&QGK(!hiz6Xp#y~=pt`aukB&aH2{YEfo)hzf<3ID(|ZkAK?PvV(1tuW_2 z=bGiH%EC&W)o>nITEW%_M_fQ<5B`jorU{Zlr3eJY!TNXa(BBA##F{YGX9ep2nrT5P z0nh+o2OzS5c^q^_&cmzX_ek2MqTZ29Dk$6zm~U-9BB`5*d(EB?Z9Fdy3JwLCsw75kdOV7ub z$n|yLPmmN9-ULNMPEJln29=Od>LqZ`y09jL`vYW_jL@mZF_dd3ua~Rx+qciO(v+6da7w~zfw6~3 z;OYO{3abM5|NrKL*Rzji>j5;RCI7UuZDyO%%Ft}V zkFLC{g?Na5V1qo-;gjypPUy00U)WqPWjOZwhIiGtM0}0*S|O&#{j#gp%bCOa%7ZEM zZ2R_5Vgjq1Y*%dq*H)s-Cb1t5Pq)4g_dfk=s#Ehiaxauh>Wy$y8Hv~zKSkgc6vbqu zEZNVtNrkvqV6oi8q z@!kyt>z0mlIZ8iWLg2@(U0#A!vz|wpWcHi-JZHw854x@`?I|IDhpsCTqInXhF-A9p zwAnn|cRM^FygO2QrTuF<3Jpd1aQ=62YMfvTRQHvA4rvHzeJLu6iq#^Q$kD&B&a_%) zINjnxb>N=C@#%+{&^vvZs%5M7nt~NB76umc{ie_E_&Y{Q(t+ZmEIqC{bAy5DIoc^k zMux{bL}cwK;>EA(Fw_{jy)QPq3n_OJYZBjDlc`bRId>Hk$2)W1j^etVE#^GGkO zo-eEE9%d-xu6D+EV{U;NL_|?25E^Te6ZzdeJ5O6^YOL)_)!Myo6(fu zf6p(uVNmA$l83}&9(tyg8zcM5MAq^vRik6D33YGMngprRYZwxMM6>LRKzKW}Sd}@| zf!#1A<>6*B&=*E#X2V~#*x^Lq^??i@LKG@T9(>U$djYqxBvqcb5;QY_3R6y6dSLNn z%~_i@|DXW7h%GG4#;LcsAes4N>OM`e?=#Zta=#iKs6^G{Ro|geav5?H*H`tW<&H|H zS7KY&%E@SarjNu!ctTT5@JcSeKh9zm$j9NDvr9jo=#d{qijH#QuJg0-7xQ`j-JWN8 z+g5v(XJl#HZ z(~z<4E}tI3v427mKr~iH))Gz{nQL05pO16jCX4Rhd|jxDikVmWJ+kr58@*@+bqT`? zF3@nkGBN8d=Fu#Ab4 zGbKA^Y34ZMdrwb&X#b?ra&Q@3deBWpB?Tijh*DiZ*w`@34+jUx;sUIm1gCv)kR9>| zsqoe|HY_YGx=l-h<4mlrVOTXYG=y}%q~4K%0ea%~xW1LRfRFI|fsv6c4S8o57qA5S zk%QtN^^I?h>^Q522IXk=!tc_{y|UqX3eYcr>jaZL1n&>L-_#g7rv+DW(KyB>d?hb%Y zrIxjV!r$YaITQr2&#`cEMSz)ZZJqz^n?A_zpV6IID*{6mcnm3gR+=7`=>JSZmDhS@ zpgBiDFi71dC0$!tdG(#y#>R%Kjknl)52LWW>u+>hVE*}RNMoa!ujpt4-`XQXw_);> z3ridK#mSxlME%L}L`B=yH_;lt4m|b0E zvzO<2Yv-)-OqZ&tdTqP?XSBWN4|sIcG0zp(&FhOJ z8zJ#6l(Ay+C`!xU*DL1eWzO0FhD+Juj3&~@a^F%*PK)>7wGgF8)h?c&EFdZx3sK>KK zK3ev|_h;j2eTwqKsbn%|v*3r5#z(SMx?)l{Tqc_0STDKFp}t>D9#QJ(dZhZZx#I$V0EyNl7u}SS>n+$2T zrt99EoDYNN!TBrSYxv+v1Vivw`qv+G7bqm2KZi->oWNxpwU+}Jpn#u|XXpSx`a{COK7-nH&0+^nqTaEF1hnfSNAt*sKw#C(P5r~&%K61HB? zrU7JbHzf2py@X?T?PO&DJh9d>*rsXMpsQy z!szGx;vzBsjPGXVi(NuZ#v`u z?cWwJ%Ve=rUKW_gaTN{(tCpbxhR3Av3si5F)sIsPOIcfBbA(!c1~<&nHs#n><| zeW6`UUm!2_yN5fA@r@?`63UG=BgAfQKhCXsn`DND7O;gq6fONkaXi4{RFQ?13La2x zuPxXtTix7iycjoY$S;Y<2C23-uy|U0gwi20RxWtw0F_2LOSv;kh=t zFlFM_6M~RlNEF0Jy~oI?TAzh-6HSjy_2Sl-fNnSdq$1V_bB0aEuG%JD+MX-!d%3^q z8r;`;@huSXE%xu@8+~FcHwaNtJ~J-gq|?4j!a~Qv{OS?e{5K-;k<{tU4> zuNRNnSVgO7M=duY#C1l7)2YOMDt>gV=XV8tbiLq+8MFAmDe)*9D!bnZ|Eky$U%}7B8GffbrzCoFFvOX+_jXZ!0X+qJpAw z^-WphoX;QvA!i_BaWGZvlOf|^?Vzbhal_OT{XyE>SZysdl>M>;tLdSyH|i(g`~$#1 zJ53TNdFg0l3`}V%Kzoe!(eniK>ev5d(25yjys@zX4j9*laxss-$AItDHPczQ?i>aw z;HNR1qqYTW9avmLr{{XyuT;wXz!)-Y4$M%xCI>(h<($mL%#5F*Ae+&mcOUp753nBs zYhd__;vZKOK&83-#x8UFWMNmprSuS zHtXs5@+K1Wu&u8bLhI_qbagJ6E~8D#&3`yFNV)T*hC$*h?o0+IejDE627 zS*#z)8qMR`zd<)Y;X02vr+0r4ki7RlF2D<-965RmhvUijGx5CCx$*z(ex!?s)9B>N z?jBVci~@!J8fs&V{JF5mL=UM&%wH5ug!@HP%ST1Pt7tD*KC6gYl-8w(-)VEy5tBrdgxki)V< zaOy|NIm+S1bi+tKI071Eawu;EArgk{{{7RjD8hMQ;PY`*@$+~2Bq7ILhiB^#5s1Qq zv1}(`SDfx!stuo%`57J_9-{f`!*vE$UroQ7Rqm*cj6OhX4oZ7&aj@#2rznxtu1rc~ z@rckKm6oUWz=0r9czYYs{E$H`%t~m8P*zrP0NQ4-djnBFf>u^uo?77T*OZhg5RkLo zPg;Q601)?~Do2aP4_Ux&0%Zy?91UIOF-vqNZd_vYR}>X}zU%`_F`*t(QqmA^`G1f` zs5k)XpdIb4&|K~6n9LObmusx#X971xnX_ZRXi`@4M=0A7MieEeTR!>N{>1-z+Fips z&9cYmVtp6()oLERnbGIHm#^$49dUm2?)&!ewZ;{O-Y07)VV`!9$dDoMD^ge~UYfZZ zUh-o5UgEkmjNw5!W$%0Fsudf7^h|_GsJ@w zTN9I#+Km4!0+T#oKY=3o1_D?b>l4*SV5x^g!PBrdW7U@-J`h`7{a6ei;SK+>xPs5) z)FH+=EiH}h`6;Sx@7e)49_o|5`B!RY^J>~|?8@O7592C7Q?tJ)GijXjr{;YG4V|F4 z$&mg-gHEZIcC8zaJcJh3wqo+tdA=o4BHTB94Na5^9UAoz(}K7(>2K|tG8_6NFg<^s zLwGBk1!HW_##VX;7ev}U8g|CjHtLF>*k5PkfZiYI6YvY0ABgKXb!tYyd>0Zr;V5JU ze4>773*t~pfPVw$o^qzFl)OA-%%Gv&ef$oj@@9~uDv-4HShj7?-TzA!m<3W%F$V{K z{K)R640FElt_9>bNZPrBx5l;(qT4x0JVe90dmdKdF?h&^?hh%2307qkFL~WJJU-!w zN)j@(*;l8&gGX!$V0&5b^seWh4HMqVKtq8}qG!q}vr84E51)87=iwk}N%B@zYhT||k7WKVOv!8R09qk{#lWXr zCFm+FB;*V@>5w|O3i>(_yTAcoY_cGZ6n5U$1M)WXasYRNxU(Iq5y7xDvnt??z+bgq zSDtW^ZBsb&iw8WY#>7O~KRkqZ#;D(V3{rk4i1)SSHA-;>RNAFptQd*wls_OIvcZzJA8k5cOC(z${=l#r&(s_t1*TX4C^*tI)bR$BTchmbV* z{4P74U2L@8cg;V!avrdDe#HlTw@K-lqcZUz2u#4N^#(#crWRf@99h?Q4w%ucuUqD+ zcI^pu75gwgh?jj+qQP9-v{w`UnOrjH2?d;S3ZXx4=VupF zMGlQY=w@qUxx;a9YJdGktKp!B4sK&k)@&u2ti-qO z->CS63`0BWRZ*higoUU12imXlQ-uw7$7k9CU0USLA7mR?X&x#G5=)d_tLxW>xazWo z*WfZs0C*}gl8AzW;`VL0YJmD;QVl1sprDJZtEMBaL5Re58qDo-!*kG4QJ)|Q#9^Z! ztbU+rhiZ`5e(^T|?ocMemqqkxt1m-FFbw9ok&Mxobq`7}|Jw9;QN~k!*!aLgiY!xm zq7dmWSI5Z3^l;-H8dh+K>^Y^i>fz5!flOA#FVVMvxix99e@uG4TW&nK;@mU{2h0QV}bSA z3TD+q$az^`hbtEH%vwitzGhvWFNq?&LG6n5Vetnybg2`?##o5yF0OhN*60jt6QkzO z$Zt0c#mx0tb-2lTr*XiI;3)S*{>9bwBi_VAGGU8_Ewx|^yrd$#rFa0UM{8Z)LoE4^ zaL5sQk196XED38ZvGC{p7!$Axrw~wSdE*85iBx!~FhzBi7VA+QId%YaJv4s6?Skg# z1C#9utsmJd%f)55R{DAF5D?I+`lfhYR!V0WXuO+k`S8l!9e85ae2K=~qfjVx^@SDG z7SuM~z47y`(YnU`KAmusc0%7z)e=0(p3ANBxt-42)Ly{ER(2vxYj(O4a8rqWqBhFr zlu^tCrC=_uwlyaMay2QQ_JMj;P{Y493o{?vXVeyl$RYBdGKkI#;*L;k^L6Rw~w5_{H zHNp`BJXq5*O`%U+A7G+`q}BLFd;NC#6T4SdR_H_$WaI9CgC?833xq=n`f>|0HK&LL&eP|I!sBhU@Q9v{XCFq^f4!!Z@>$m?`L1C0jj*|R zJ>-=L91oxFwo=wENLX7#5HHD^$Yimx43f5I505(dP#v3gyw2mXT)&{8AS4|Z_|St9 z(LX@v6EcA?K-+nI_+v0+$t6iD)~3A;3!T2tUPE>{?(o9o>U3#gdBDWg!*kcS>p6cn z<-fx;-P8kQBD(JbAvZLds5y0ASc}oR*5~3x4$rT`=*+Q0#fZ{A%s5+1u91^i$YJ=< z!Ii{?s)sZ!`v>jYw2RhDQyvQBH(AxsuIh}Du=)FVJRswZAQ8k_CxAkrAfPn405;-} zfkK$+UO|5Dj7uFfGvbeSi|2mWz3Na2_nzsPah}m@X`re$>uY-9(GbVWlop{pdsj3} zUM}oWZvkW-0)XP|o6wb7Ifk^PVq$Dt&X0o;J&Mz$yp(@T~5JE!@L_>9{U&(v@@}dBe z#K~rY#sf=H_!Uah%VBT~P3r|=<#wkzD}5Q2MF+Enx-6NF02#skR_bvgE{mi7{EVj* zkFJtt!rxg7IPd%!Od{Di!);510^-%3xe^luZAJ(d->n$Vh1SEfF#>U@OrRPeNW`fn zk|s3j(G)=r6^d~tgpu%Xm}&TC$cUj#yHGkgSz^Mg4w0+iQ$!t1dxIB&&#|dt__t-g^{o(p z?ZQ50#T%E$ACm;_e;K(R9I^8AgEdvHGixk5h)Gbzz^5a4LlUk5d~q~iS`iVQ@fZ+3 zgK;Kza4K{m6=2aIE&3HeJW;!Oq=X`hok)9- zbb8h)s;m=iuHV;mNtqzayRNw=ccRDUo^s3gGhxZgK!HE`n!Nw-^Kv+qBM>T4Kl0>X z+a}(_D1M%IH)fhc5+9UC3$b|uP$h;IxVgB@_{Q#jEiA+rH#I?_^#+eB;FGb-o(o_i zXMg~8^Tv(eZ}wU~5XpZLP-F?@77~J1d;bL6(f7-VkMPYO7-L5aBHQ=0|VG-xB8k? z=fm}Qe<2+A-3}&LpHTEjrYY|K0{8(2iNZoc*l5iVE?%Hjsnqdn2QGJU(>maBJbUI> zTk9dH-QF|#iE)|DOl|vLV-QUMWzW9~DV6E)mN zrF7ez)}X}8Eo5+0pSH5qGyx5<>`=99dOlHU3k(k1_oThO=4C=X&;hGD%Nub+h*-C2 z!X#L22x_OoT7?gL6A{C2Kp=q6{iuA5;Nh^w9AeW+XLutV&1-%W}F3dg=-|HtPMrJspSnA%ksG zFl*qm@0??sR*|2J4?Q$y6*b5%^>C&0);+# zsHDEW^jpT!-U9mOhZMeO@R74O1=LKA$h^v)+2CAm>@+6-#HY^0++%-0K!~dGjW_K< zv})CTDto3i+`ymVZ)oZGs`oBm&M>rz*R(c>dj47{Iy(R?tnLg4&9_nSK4jLW!M1nS z4Dr_~SQ7Zt)zwA#=%G=2ICu&avAfN;e}!FFtJeXZOvwwu(hW z&E&d5IgUOfHA6Lve6gQD___tm&tGGo&)xr3oV(0H4L!f^6qpv2fO8wW_OlivZur6> zuLUEisHDUK@cU>swac@qtC&CsfLP17MPaB2cZ4Xod%!(>?IsRWuxlEU>E8xTNe)KF zOz1-as>N>t(C3SYhh~rs#7!)CmyxIpsEM)N@J*neCh>C-H5x>JnRL=4>QGU) zQPb)2b~*c1?Rd(S(x+qrvt=K=0RIVb`(Ju)`agJXVPG&wbl9ravLac%PPbOLbXje{ zjcrd&Itlk0`VhyWs14A3Mi3GdlpaL*E^WZfA8--%CYj^2GdAL2cvBcx#B}J=jiA8P zvE&2r{~32wYNyhjny+8KI?Rp12JO?fZ4D;Ls5Tf~lE)xWS_X(sCE;Wb)1W&g;_IM! zR~*-f_+pPu{Y9oyHjSTMr8`^{*nrFuV}is0D*tG`OBG#h?IM+;>GK;aTcRWaUZ~KQ zY+pPtJ(J&AU~#N{l<#KXX>}QHuEr(*T(D&iy@%RJut&77C#9MGIj3??MX9;}l6-Wc zDB%mz>VLK_fUZss|=iQwb`upG!q9IPw;I55L zbww!S%Hib(N84*qoyW*$hCsGsFV6&2?(p@$J4dJ8{dp}K8>`rYP-v(^VJHPIP;jsY z^bksjrS&2W%>^?Ekv@<`%Ha1FqzbclYptO$JQ3B1iS950j0dPSo8y9feC2=|;5Pxw z(O8R4m&}DOgGyX`%VOJ4n69XwKHkvZY-=)PHepK%6g)BcP z7CaNj>`bswF!;+76aUHO@{xyCMtTI!Rbt37sYmhp*T|=m;+(@7qMEN|W@wnEnv?Q9 z27tGD7f&$uYZA4xv@}gfeqi`3MBXy4I6Nxq8NMHWy^-MWWZ}m=JUpVJR{*$M{VOHN z=mu<)goLE_I5;u!wUJSJxb(>2-~r$SK$)i&^{kOh8-*qs%n2Vrb|`e7GWf@r)((#* zxa!Y~p{lCY!9%=ta2SUaM4;>F4!?&Lh zMqSAf6m=`hza$7jniFL3uW_tm=fG^uyv!9KE2S^71b*Ag0iSTYKKP>JDG?jPK-KIH z7B+Ue8Kk_wG~iVS`x-TCEWm+Ij^{qAyFglhDriH zMFmcg_^475uqOcqbiGKlK{lzD@@NZ3z70@+mKB@5gV_`{YBm_|Y;@^OQ$V_7EwUT9 zH(F5bFWh7Ep;3h(X6zp)W5-X!wnCP|=D4`|RlA2F+=9u8BbKQ_-PU!r@r)~{n+MUQ z_c8;cGJiY}!^anwv7gA6g_NzxYc?}Sp5c_|8As0^@StAGku3?s5`)7TGzriY0<|f=`%Q4F=$MTVm#mCX%wfg=K*nkmA}j~C7H5} zzWA8dM{uBS%QFjR3bl83LR##AAW9craO!^nEZ3I(je5*7%4ohbfQ;FkM+OEyH!_+Z z6Iq_0FNJSERI&s_6^&D}1;bz>2rQ6HFy4X-oZz&NUs~vWi8% zf>DQGBzMXQGFO$t!NS^`M@~~+h*dK9``2BIgtz)3s{)Wo%<<%dZ z@)+haT0h1}DIcs}9xJ}YGEI);mW5{^(ee8WOt~9pFtFGMxbz`5_+{41#dBv2Y_RLp z99xm7$T9ZA6(TM!K6&sl|5_>qKl32lfc*nY6YyrnNR~&BPN8>@iDCc7+zG?&wzls8 zFTxtIg1JdbN(ywEY{}YazHl%@Ea!6x2|)DNz)Ojj_W+I@_Ac0{icy7`Lc+q=n5J1D z1FY?%(*(lj_s2RmlF3sf7M?k7uXzs>EY|8_%~H3J7J{_YLE1WIwlOcUI5yay-hS}| zWu>>FfcvUXc9YRWot#3HRz%I`I93L2YvajTXI$}-w9Gicf-oVG8?@`-%6v;x`Nh?} z&}Ilw!EXWz=ZuurOF+=EX^q||o+1$F=z;HVqTdyAehWHC`#D5$pbpT*O!?&C^#4}GSapSZGVh&qTGY=MnZ8UEtrbG zU7HmM(^dF$oE+AE;9~O5ETi+JK84+G*FBCjYQIGINn& zA~)moLN~I*h=+oRh{&QwepL#vL#Ufz@PUo^+P|_nRZmS$?gCvo#8U(J2ux#XgC(a= zz9W6`cNIVl2x*Rk;PnL6E!5^j<2{|G%mMlgF`UWe$sPV3*F89a{v>JNhVMdso~3O; z_`_D~vz74mG!1(54&A6}RF)E3y!DZXBfc#|O)A>Eb91y}BXvs{LTECvUNa6&X5LRK zC?=j++FvzaAZc!8n=X$2zLA%$!0cxtVrB%Hr*L;W6UGw3FVMwQR%*OC0=L$+fovjD z(h8XM!-znsv=DydRNn~i3L=#x%}N$?23J9EU6XhG5h`{vYyb zCjP^r3IE>H9D-C1rZzq*Ph%{*)$q0lzl&Am!d?32Ej~=NJxqTyGX!nm>fkllMu0

uVe{&bQDr+;5aKu2^fYey9?KM?HUd$gLf8@%1Z{!KWWNu;W8KB! z7+Bb7RodNSV_Wk$1Lh;yoeM78dFj~fSQVx_hqjSamkhXot*JGQHf-*u3II5(PG=q2$UDmXD zqd{56&Un)A$Lu{X%|$x6^H{!A#dW_i%lE(YtCJ+Hx83$j>@6l8Djx6~%^O;AfC%7z zXjP7NQj!3ItFL2%Sw8_Dv+bgz85CVp))x4ZTpiSw4)1y$HQycu+AF$NYJ&40ZrEOV0K+=BtJ*ofZe_Vh}xguV8uc1Nn$h$kWYeCr$_$L3o zh;-m+)0EaUiyu;9CPvcIvj41sX2=)+_U+lEiCrIK4ZrYvGNgzGxG#otHPZT5AnEQe zl(7+<8KIOKF(icUwP#5H8-#rP2vKb52VsW)A+N@GM_huQhn_+`lp6HcR{(vE$lKN5 z{Nu5Umo}Qi9bQ5SLW};oYBR@oOvsv52udOCmKOC}XdrsIBuTm!pILBsYkX@wdrufH z;lsZRFq{Zm68UlUxm8m+PnF&;9iyLA`rfR1?C#T%_R^yD(jAx;LT3)SpfDG_cclWZ zG^iQC>jkD49P-yjn+cg1KBmyh!YGk~*Bm%L9Q^$JwBxNm+8)3rF<4RR&t}AP4lvoK zYYM_$n6z3&7W~wHoT}Sy#1duR`U^^@z5;Ff7fSC#s#HeD^jvsccRQrKy+4NYI#@8P zCXTj_p8Rr0G>rT*20xx7$=1SZf?W4mFn#Jz6-_l&Vm=* z%?~ebw6HsSP0yf^(^{-d^hLBOAp2t%2jD2YMaw{itJhNhaB&f{b%LWl2Z;8}%z)@U z2e1^1m8f3h=b!FIcP&7tp6~utLtQ-xKSI6gZ@47>!m?eBW$m_kQxuw2OUug?ZReF? zN?XRH_drAEFbT`u)11Xve;ANWN6f%PpX`*UhL@OXPInm@|Lbe-GB3hg5$8GJryIFr zjDL7i8<8^QnQvF=LLF@F?dJsY3Fq_6WO*n;TUwuVHbKdoDW7tefZ#no>%?3a2#xW@ zffSzSC-1GvfoK4gOCKeh)Ptao;ib6@KbCubO{4u|XVJARFLEZ#EA9xb?1_1Dod!_A z;KTdX7ed4P#@_|lLQKfEVmSUglLKM4L+dRqtuY~1%KF_lL4e-E4{?|?))SG(;vJfkowgdLeVp}Oo$#XyF=Z#{F(QznLSTeAB z_6TK2BWN(55y#u!#*xkTdZ}3;a9gM8=r#$-3_YprU}O3qU2?%t6)&H};Inh}*uuE` zf-E-6lL{?-PLdl8v@5CaY?U5q6!Su`D!w@AOWtyDad9OtWk|JX-MSWq?Q?Cf-Ch~$h&+Ex)m<)Zf& z*XOvi2{)z~J``kZttJ3Nz36v%^28e=z1^Rh@ld!VJK5Vu?xymj)A|8JqZ6~BC#=#@ zknVh)?Mr=P;MPSPtCZa{RIv!V$B&y_g&97xaJWy9Uc4SY01nb2*6L|TpXl7~=5HH_ zLYpvr{Rj)8r^M&91AWfEjOFR5#7)XGXSXx{^+#qVsfDk*NhGLs1haMDdKW-2N`;p% z?$gWy;pi-{?3a{8^;Na-@1~ZwV~Kh%@1W}%YWYDt*huMA6?k%1oX|?f+M6|h6cbPM z#Ce39Na=d8(v>*Z9!FSbyEt8ra}EZo78O+Y4fmqQ`K?mupYD!2J`8wgIlTp_@`hUd zML5@RlH7wD9m)K3oVwt4TtoJrH)bXH;!js`2sVa7kDtp^+Xhkgn|}1~k(?Qj$U;|| z6c7;b_A>vZ_w0LNVK@!a!j|kN;u^B{I^TKj?k?13yS29K2~n6~b0Vk9Y0`pGXuj`_ zH9p9M^fAai0TR#*tZiP|U%i#hnd>s{b8;fb6>aEl|7!OmUNP81@%LgiLk3lD?Ce-Q z&$@R~`=P;KJg46XgnwcIW%~!gYW>cW{yP*kb;HKNQ{0DV!k-8b-aYbtl>!Qg6+_P} z%VnQ!cOZuy?Ay=VDHG-2)p9wQuA523%{~4b!Z|p>=-A`;^4n(#M7!mHO3~(MWJvXG z9qdn2UYlp-@4)`>ICbsn&LanH9(064<(aEpJpU0Fg)4XABwONv<)7?Z)E-rH7&j0j zuEYEEdqhM9caJYuztN{yPgN9#tnIZ$M)0X$_ARImaopWTWmv5qBF*VeBgZ3SB>8JRLiJ+^!RI&!OzJQ*BFaC_)w0 zmjz2uQ4wD}w&4jI31@4C>dW()F!GV|t2axhJ(>c_-W}EDW~(D4pO2=#_Tz4%h(y&amB_pI+&QEBN}RkI zANcg4u&7qCVaM`qYaZS6`GQtMk*TDJN(+|}(&x|JA`v9ouOFGgx4B;JUg0)z%!tdN zXGfB?rmFdeUd4ULxS2Kb@#I0BqhJT;-J50O>&cbYaJ3`uZeBQ=7*&_pDYX*yBL_zwG~dVX z7&*m<%-AA0x#NFBDa_A*1o!3^$QVx+NRi)ia&kT$SR2&dxvm7M{2(n&xo?KX2yug5 z`@Zo{^w!I*0F6Pby_DByKhMX^f>m=`^-tqi#l@5ed+v*dH^Qki3zxBmN_lt%OWgYFN^KPZ1`uy5=*hD zF8g&n>;i3UL{Asm+8?~GdK@)tJ$==B$UC>j290lF_Mq2gpP^TnNWL4@T^q6ut7cK* z3RhiD#2;#_b7S$y`s$5IebwcvxOYVImse(ry=5tCQw!dyb3Z0RME3Ek&=&@){#;lc z%<(BV6`Yr@G=9yHi$X+|HuBT&p6s5?@1Zgzxbc$~b@zYxj)D+2KP)^KWclKWbnLwM zgfo^1^>cW*_m*)glyx+ILnLS5X07Z)1CbCimjr%)p_N4-VAeMU1zdE0Bdu(xu@*qER7HEa=^4Uz;k+d3C7ccC?Li8?i+@r}?kG z(CC|X$WGc+RP^wkFP_EK)ooVRs=cKaCw5K> zZSqKu%%cYroo^y!{ac}P6F6PAx{Vl~OnY53V%1dE?}taFLzWmvzl4RN@b1gs=DCc` z&(?PWE7B3|f=-V{v85-cU*n$)++*bW)e`?qR^QSnw4*12;7JP4X^Xk1ZF&SJfNPd~ z-_z5l-Qt(Yu+jX&9bINUfaC&q26zi7c8G$l@n~u)-G9|D+k$|k1gOUET?llV2|j6P zAlp`IiXt@b{&Nttz;6(IobczKGMB*6E#;NoH%2tc=!l4KOo;xy0}C*n(exZ?q( z9|EHhFApzC$zQ;WCJ+arTtV&}Ff?C8q_;>w>x-%Mo~G$LXWY?KN)b-yaja}vf-buq zw!ktS41|;-mx%PpyOWF6E$z!upuO$yWMgIS%Ea0)A>)5%zma3x5M`-|hNUf0H5`$+ z7eF^hnZl|Y!Ndn|`a2tUTI|&g#P=S4I3xOW#OjWvE~C30S`sEfPo^@$2C`uVqv`h( zAxGpb%iTTA)fknb*a(EVm;KJ~C<=#B$|&(Fs!(B8dSjG)gXCH57nKdP`8G*)st>uO z2x+4d6WQK7*xK3o;4jY4PmjefL(jY|za2p`v#<~yAMXN1f5eMez|3}qYzz(ifo$3N zC=Bd|5D37ovoo+Vyb%=8)Jex3c^B^BAhFq{?9j^!y0Ju$u$!mVNo8NroNa11?CEf5 zs+(PzeWLNgOfTxF=##Czqq84vP`uT4wWdS5ad%nfJu%;jd8&SRmrM`S3sNr*h_g~_ z?os{8A5ILv#R-Uw4i@BMxvH(+AXHGkWpKbU91;3-LboQL<-+>kl_+9tI7=TZwTwm0 zFhsOq=D3gJ!{D=tAasD5&nm~1?pY~duGq2d-Trj^=Q63)yzsAjTu#?5#7A5TD~`R0 zROYZbPypDJhGz4rXax}MaQ zNA4Y~)SDM`9ra%0`77R;Ev=LZ^?WHQ{kc6@pHF4YM+%lg5zMa-G4P`hW^>jz5r`G1 zemUw#muV3SjorR#Q&V>u7)=#kFYG)#xxxyK8&0iQ6Fp8kM{9-(5+?>3^vq*`f59&mQSo^zBXc|d&Xf)eIb3_H7*L%G)4b}5}j|; z(9jz@YUeVZa7ielioKv``mc`wQ3D(Zz4~MUOD<)aR@xJwd&cQ125XJ0(?8Gz7P03j zWwTm%*FAy0w9OVK7@v=;Fs0w)a~CnzMBO(&)#s4@`A#lNyn9|to!_ISK`hP0=HqXd zjOkK*J*j@4au$%ZEo|uY&Wj4X#ju?lG)`*m1Aia)sO!gzjy&)f4=9ar zABULF-eiQSye#?AMLZ7?h=z4YotD==PmLR)WRY-Jr$v4ZL_(Z zwp%fn)WT96(hG?ry0Z7ad?-Wwy_<5oSlSflt;CVnmBH*LDbb^+Z7=N^htLocSJuZL zCwe8sZKYK04V&j#^!*Vd2T8mynAen=(7Ik%JzJ983u40W9ak>>-5zLw+ri@E9m2ct z`KuX)cvi0|!%x*R^FiliQtoH^EfR0ZN~)A&?+Ux#$KHccfK&Z7QVC5neiNjVt8Thx zYUaflkAe-NjJq~T9@xOH_^@DQ9{-)`evF-5#O047E4~~@FhyPScFy%U`ChZA*4xTu z3G_p_kEk*~W$!bjh~m+tM@d&EB@KFFnD)DG4pnxWZm*9!c~A~m^<~PHxE_ccpB_KF zLO_NYjnu66_wRqp2hX)-sswHuh6f7hXBJruIsl(dmk~Zt*Xe18Xo`fzYd%EYCM7@7N;!G zV{*cmr*(7UHV)OPP30Xgi?L<%_{Xt<#&%rY_Ec%`g|?&!h;=N44d%Q)8usQB>py&M zo%ryp1}~*D7_=tSZToVSf4T5T=RzRb2a27zjI%JwuFhKLa+r>+wd7vKoifly+UNA^ z51dbNYN?A3Z28M}dOK`YU#@T31e70^_&?D#waXgYC@EXIOqlxhO@$xJB~RY7-g!ST zoYQgQ$vXpaKJALL0S=RL_w(Ss@DrSi1^44c4PRdif#T5*wjV}6D(CT0caM3lcwzl} zM7T9IO^Gk}M(bs*EP;v#fA2ef!DJZ@*#&|tTi;K4GF4BI8G;zuifL$VwrDs17%+fU z0D?`(@tc|EHw7T>CIBEHR z89=%OVQKDV;uC+HBd%emtKHVXu#pt-BPy%TxdD>P`VTYYL{q2BnDz5+C`h6Wb?R)q9)cu-T{xNBRz!YJ16W*aU@2*9GUHm%UxQA z*si?%B_Mb3$mv2pQ>a&HNJyfn7o1@*M7l0~*p6r>tDQd41Y!23@QB?+s3*6|U?@wE z%#IsOYmP;ud3V*ia-(Ev?&qeVBJeTY?&^-6Q2t`L_*>X~A3vwjqz^MYd(^ZhbUxzbPJ>9O)B96KlLBm6u!#$N9Xf7PZKxZ%<<%sbh_NP6H;IcV=YZK*3 z1^I9@5!ako{o~+1=>R_81r3Cl;iq2)2kb&DUuc3s^F9$iz)sf(U@>1mkSDWML~ud*TDdRW2fZKmIc~uF!Z# z4jOd&6mNR}!FA*Nm=ZoEv{jH;liHP~$0V}#YtoVJwm*p=-j>?)ldCObjob2kvI~rd zJ)*P{EL2pcYcDy{tobbTw;uL?YO|!8aF48Ya#V|_Wnz)RLLer6hx5qSL!-Ou>HlPR zRkqjzGo)i5l{IWPqc@Q1dZBfDgg^FDHgNxlNv6SMbnAp&z z1oIXxB`4LHnNq=e9@0nb4RLyKIBa| zMe-6lHd!IWxv_FX1VB7?Gb%c|jF;J+G+%tp*b=s1eKbjrIR!3FUBd#(oa~hVQQ@XB zx_JK~RCBPLUf1<|qnvaqbxjy~>zM3|9}(UHyOz)NvD2re zD>y4ky_DbG140OGi-=)dXRuh>0}(egM3$%#vK&p4DzK=<juJr}UQS6r} zeg_LvM>NPhMbdT<-ga|#hDW{Rjig$<$iNbB2O|Uu6B;pmU{pKTdZMGMd0Q5!&Ut^nHf4tx^+5^=`gQ3Z^1b-yHZUU#B?BKIyrnbx z)(&9jT#LoP9x((T6LkKzvwoU+`H$$y2nZmOQu`K(_E3o{ayuJKl1>1Opf$AbuwrNW zJ=>a)=`>0Xr8HF5Yx&HnSgD9WA&i(TpPW5keR%r4>N~=_@c`|0k{HOI3B-Y?n$U&u zie+za@A`#UIFPv65+=xIejs96b$AqmHLPNrLr}n8 zjgc`OK>6Lpxkeb>KN4IOS)+%J@tcc5BL~;t7?T_h+OZ{-65+*-=6xCFtTWV3PdmFUzA}efW*~>$a1IcX#rB zd{BM7tF(F#@x)Cuhdpj}e!gW-sQG@M)*pDg;_bz`It6MPPDzX*Zny~5R}s4){7CUU zT>%cFM$A1VBuN36^-xvY@uwwd2g2rn#HOOJjHDs|uvVp){^YIVuOiMkX{mvHZB)6l zG7F&k6X5GB->()JYl*K?Bju13UD1g6@DK;1v@=o+I$ghTqdxys=7daIzn`qe(f8=- z4Pl}Wg+Lv|DT$=@_z5(V zW$rd6$O;~9mAtVp=@DrjY6zm&#{SsYl7P6uQPXPs`vr`W-(sT{))u_7CWD={Ez|=q zR;{$8B#n6$i0{sPYP@vx^wkb4vs+tUU>Tdd1f#p=rX~oS8UVIQ*c?Mni1~YX<3Xv+ z5CIpAsl{i@h%9U-lY9h!%TyxtIv1FAc@e?uw%_pIpMG~<1cCn-)r!7^AmizG!k3>> zSH8Y2>_e)7S;@A1x*reROA5pX%f0kMiC4Y-PNWB`Jmybx$-&dAWxR$&w>^4Ru)*Nz zGvJbeDEP;#oFSMj0gI2;4?>{ot}f5!=jZW6jv@3HA0Hg%jL54v!a*RTKukhRtfJrZ z8A0pUy#IhupNE1#e8hxI`Q&Gr{!OWV9k~Pr^?1XU2u`*Bf&N@YfVixM$})8#+o#<|gRep#L0&Bx182Dpf?)goSh|7JL`N>TVie4OWg?{lcs zfEV_=qXPv2FWwCf1B%c$z}M`dw}+s@j4$tRzfe(uI$79FRb8K%-tZZIwi&NZ7#Yi^ z3%2i_U-zT&TK2MIIc>4~jn17daeiNkn#JzyITddzg#UQMrui@MZ1l*bp(1yv&(%sg zf}yJzbPN#PMyQn!cAUTkmAlproTNxuZJD9dU1?RazEuyO)#tQP)e?1-J<7bW>CBTD zj@i7ei!}oSs2sHd5iqk>R3s3?r)pCq=GANP2Be|x!AXG@CzvZOxr9p6Q{7Z$*>|m# z1Pu&?uYXNFZP;Z;#h-R4BQs0h#-DY$8@OV~O1?5&V9!Y8S9n>dKSDv)n=X^fcw1b3 zOr!K^#6Xh@k;&?-oLG{vs8r|Vp5MQtB&(2Fe1uA1^oe!ll>gGX9T00#Dc!s2?CNWe2n<9f|m=S!NDoJsb>-qOvlNHWOp+_)*KS zPoD~W`W9weLy)uynQ&AUHov~RBQy(0k0gbkw1GKqvQ3>cM#8)8J>`)xLkqoU zk(?_ME9^adb~X&sHoN;Sj6}M8rw$Pj44`|hYoN_3%6jdaHBl#HXt|F{4GoG^U={`f1aW3YQ>kL?22P_|vgh=(`*9)8qk z5PyN~o1__+FiGl*Y_>1tmuf?+i|{wCOTV#vqfAn@Kp&lwHzH63*1 zFHm~+1Z1g|JK8^e;=g_S1|q@zlm)JFo)v?|-;95tDqkB|0Im%=%U;P*iFqPxv~->- zcu6XoaW2izqted1h|tqFkBw3Gn9<5!*`~qXLNN2vD%UOXkV^Z!aB%w5GX)}3$T9#T zdkP!a;l#oqRW|8S8IU(JEC3Q!P3wJ;nZgkaNxT925U-)~-UCFFcXz@tpVv@5P#WJO zlWd0!-1pf$CuMa@{}lNRZr5u^3aIRbdLkKEvi<_2Ne({Fx)=rY2l(P0 z`y~s|Fx&7Y()w+TsTt`r-?W%UELqQm#nMaO@SC{(MIT!^KImU9B?4c-2+4O#Qg+4e z-T|gu-=SS^(|5v@dkHS~*Y(D~OmNG^7pHCe%mYr|#zw#>a3KN)$TO_||D)+D!>Zb% z?Lj~hQM!?Ckd_buDQN_xyGue+8l+nqB&DUL8w3@kr9rw|q(ss;x$ixH_<8TAoPG9Q zd#yRg9Kl|=abqt4En`SkOJ7kNM6;8WrbT={Uj?&<>@;@hv}dOeL35}v#@&&!YZjLxb5&CrIg3=Ic;o1V2;yZqae|HN z7puosUma}Q&(YzQRXNK*x9?V-?J2I@~Y@ zNgch-&ugz=c!rttKaY;~rKodN4v(MhZELhEEDYm@)E>C?DTlmfrbdSn^5R$XK7>B8 zq8LJyA*{Hkw6uXaA04meVb3S)#wR4yC>jR208h6A_)r7=;#RY=C4^>U#eD9u<{bH4 z#X58ZMf?1S^#lZzgp8g&h8W=s`PerYEn!>*L z!|lK*Pjt#Qw#W3piyR*>fh*Zu$WmXvJWSzJqPO=ED%rqZ=qw3h)C(K`%Jp<~xIMRa z1~@1{L0Nm5tK|J|bILi-S}g5qnJWN~!= zjCJTw`S{FF+wJxBuA`O?!hmQp`OD z?_sC%2KeK!)G@r5e2+r;T1YlBVFcU~q3B8Ui|9*2LbHY7=m7tl=0+~L+x^|$XWy9| z$hgVZg(VQ!p&$2DZ!UFdsly??$29IR2i!b(6c!pBkcYOCIX1qU1~gIBxp+zj$CP(? z-+DIjWtT5X#le9y@Dm**z^Z$Xs*;8_a%IuRZKcmVQ&4IL z`!dmNcWzm-RDavSq{8s*&QXxR-7{BT`jTFp`>Pfkt~eG6LhXy4a-`WH<9@_zG# z$0#pd;BW7IFwED@eI5nAQB2_wBry*S9H`@2etX_CK%!EW9FqeO=K1s6eO0*h@*jT> zu5KNoNr!5d5C$-XIWz6I1QE$Mc5?QAqmx4fp4`SvnprNR=+|Mo%3#~l!a+iNQ`^jV z6*>^H=H3?TnG4s*zyNO3-44(|KZu2Pr3R+nALyWq2vmX*bx+y~L-*TYg2T3xTJrkf}CT=_QQ z^UR=5f{!VoMVf%q>)OR$BlS31foM-qrJ35D0%r?9ZVB4k@BxfhRv$?~X&LqYa;*!L zmQPOqomZW#s1$;-+@%ROPq18%OYtfe5-OX9xko;fr)SdKno2JjG8CouW6 z#VpX}!Cp(NOUlLB=(0aCv0)~d5lIXU>qCRi+d8~A=#uC)Zujt5S{?;0t1~K4^j0jEv4>vppMl7af%#Uatc+>Fp$vhIRl~>(){O6)Gzlbm zp;+0vG>4bd#N1e2NEuJ2&(3i~(I~z)i;5@ zrw8w6d`aIoKRs5x?^84hx4I-Qzcyj@K7LbgH@>z?nQB*Wh@>3wJG)danm44|D~uK; zVj%4Cx>mWVPLc6<=J*~I(NL(nL3dY_F*ZFd0Ky6|YWUjJQdT%~?mae9@tH1^qwCC$ zj1VOo9tLpEREnH|>TRaeaix%_!qn{mf{(LyHSfLVKjP*1n=eUiy&CpSa7(6zKwJ|T z^X}aXz>4Lwg{%X#@g(1{yy4nK%Qs4NazgrmMvQ$I1s5q|d8_CpcGtD-%o7w8EV#YB zO&>9sMX~(#{38}ZS%%7gsD{z8aHF!avfk_lQkkG)gOW35gw39txbgIb&9u*P@0CRH zR!h_h>w`xZqjfWj4-ywD4f<1zsTP{ppkQfpTtn}xYQH>`D^#S{cqdIAOBq;IRfTR? zTXLLrZo5JlhVkjo!SLe{<2*INy zD`R-(M5gI)Y-oT~!myaN@9N#k?(fKPGw;RwJk_km!Z4~Sz>vZ(scWqGve4)=p3=k! zjAfhViwWH;;Iy<3Q9 zypITNGN-1_hl3rCzKq#tcx<2S`vw-N6v5=KaB>IOcW`O;sTyqYJ)m~7qh~_d7EC*( zy^TRSIdM|EL6YE|i~R+;`rj;mHg8#$n&x~%< zNrA{ON~Q~N&#h^8UFqYt49n0DI9fW7ta5QD(o1L)sieJWQe>UEJrxzlN^ECrWkecu{G+|^SV3sNE@z2oGBw3%wnhgtKl7QvzGJ5F*QO9-hTCnp!V{2jn#&?HaK67FKu>iOc=;mnUc zSIPcs z$&*!Wi!m0`{yQ3)dnkw{rckI*eR4?ck0o5{BBNHQ5?U3Xeq+(spIA#lk2P$Z6g_S0Xth4HMbi{g(ht*$={Xk|wK1nG(2 zuc*Puy2DE*xas2S~!cvtS2!vAU|EDBSx#SP!RCKWXc)GX5XVrtf6m8DqVqe&>P~=x^B1@x1h2w%1$90|>yQ?$&B-=DWJ~q()l` z&`D;sCAg(ZUB40GK&X}K5~K0ae*rxR{I*T*qYO!UzqiK%SjH8h%ubP`#5&1;uZ0ii3ps( zfu?PGK2QFhMb>X_;2=GMmo4`Y~#zQLqVyGC$}I1C)Oy> zBeYIHf=PHRpPknaXU&XVJAQlrR)j%9$StlI$Mk{lTd>8``usCbiX^!=x?jiZUQ5}N zlfb*U99=h-W`G848Pq|dSXTquM3ATJYn65f&nz_i3zOU^%u{dO2^~R@<2%DP6!;@u zz)9YAM!%R@4NubE)1K=$TE3N@yw^YGx4)V1+_}G8tNon$%6Wh!=XQ2NX+-Y_oXSm* zYg`gM?enG&74v>~4wrsYXJVmbCk#bkfyEhknF#t^^4}1;ic8u{*Mi^KFG+JxWQyK@ z8j#sOSZJVgdewmME;2WDv@QYZc&%GH;9~obl=L2A&A0~@0g+7{T^_A%uS3GN3JbjJ zPs3d1$ggJ9-&C6Fzq5^1Ew;OrR!uLTLW$;IR<@^M;B97IWns;Ys{C)vR!1yitO&}zhQN1bl6LAp24lBPzh#T1^yD2w;4 zzh53Kc}JeQz}ygI{cdN6W+RPAh_5Z5*2KjhH=n++H~u#pY3MR`oz zy1n1b40vpX>|UW5ccFr&MjvZ zotez$H|=MkG0*<`O?>-ID#7aU(~aQhm=D*UI*^s}aSgw5OS;x|9F;HRrj~bw9NrnN82yf7&q1Tm%(CvKhxb zDMz^)!I>GQN$9`jWV8BxHW1}G^PcyjAGjUC!YG~yB6P=&(C7W8aL<+HEGaN4LAs&6 z$jHP*eDoN02f4ErNO0>aZG(b?;ffUD=U^*x`eTBs4b%0~gHm>45llMSZOKN*YL)ce zd*bN8dCq2f~~ z$DYEDR$$3OTqGsKC6-7R*(st}X;>oOY(~xW2>4dsb+c zu}c@Elc!#!3dTc(lEZn$b#NMtOX7X&d{}U8G2TU_{jhDlgttRD6PC$Aaqr)r)UMUO-1mk3 z&VjKvI^wA}IYLS47V7r0(+bjuzobL*SQZu=fXvX*(k5INf&XR=@D2cJes5K%o_UpX zO=z*e`K7J7MQ*VV!)U^`Zgy&fzFoClDw?c=NRAd~lwJIcV#l9z{j77+NK~ah_3=Wc z|Cf=z;z;zDnfwmR07&vE{DY}1m{t@Noqg#K!OLM@#U$x4<+LNBnFum$I$aG66w$6< zuhD*AX1gD7hbfgl6-#!eiFTEa@)?HSEz*Jbqc};dtGz3h%qjpe5HU$f>gRB-sI z{epBY{^)z?=p=Ah_E?iA9C6PZ4J>mDRhgq^C>5rk(U-)z$6~tP zr>`dvD>C9B;^+b)z682|5fu@J;1k#WuqZRyIJ=p87U@O-F)giRQ#CHh#7GzAEwz^K zcbZi{3${WqAtjn@e%0{{TQf6oSg25C#w35rZ`6r0(iias1V=7U9*TX0Vbxm6no3d4 z=0wntT&R0O>DW;YrwWD1+fkc8XUr59(wlD`vq@b)b-?w3x+q${_cxZ(^!Tm>{Ub3NEsgBY3gZq<68 z_>&`UWgx>NR4Z0pa@Q|YPwtt9S&=u072%!6-BDQ$YdF}thDU0Z>I#tC>(`71gnFx{ zMd#f*Qm+4md9KQQZSelu7OB@Y!o~x-M%W?Y9~Ua5nUAzdCVw#@M_4zEQJO?6SrcjK zf#Xsb9!mV-qr$G}C}A%mWz{bZE89^dk~~xi`7X-Ds%T0F8hR>fMMNB^2~jn-%AGZe zRN%c6o8)4rdg8qK8XRuG$SH#y{o6;Y8k06JY&Z`itb?VJ|B$!R>{S_`&hqB-YeIYtwBTinLxABk zKg;3<0qS4*bGg`$EY|Q!t9Wh01ZX-|Phk`%cbU4T3T|ym{M^eUDt6 zo3|>QSXWv(!Qod*db;kp#VKr-ec(t8)BZG30-7?YZ2Pe>f?I_==NGE)Aa23X-DMFmP$fYiHmyVWxUc|A?NTin>Ozv? zL4rYiHQo2}&y~l(y`*<__lD#vO$&xKT>H%)mGsMCM0p2Mq-w1z&SF5s7ikoE?+wwT z`uG6RSDz7-4rS}%xYuE$w-BEO$Db-)M)B)e@%R9z04A$>jMgx?S);3;$t{(lCV15} zMth1cW|UlEGTlpdOpR8p1p{K+_X0(`u-1_fj_Ypq5dLl;1`W1PR7_` zC!_EL2gKgA?PrJwch-uR`@z@UF-1n0$ku#ipD1Eb%mw)l0LE= z2XnrELn9J8>vG4M8mAGhc>g6-s*`$2M7??2d{Zp3b)SlV?q0u`4waf*X- zylBDC^`rcrF-oF{ekKCLR%|9Tvrt}cCzERP7eg7jjKzbY*cp=*4EYRq=}q-`T5co4 zDGIU@k^?#aR2~(5T>c5;D?EHsQXRO=>1u{9evnC0QFV9;y2a8jgUljDzu)q58%}qh zf$HXFPbh;tLn>x;B>G>CdX2rMt|HSv3Jd+&tU`)Rzr4kIYb4+c`^@^ z*%=NVp^R3srGKV+hM_j=^4Zy?$u9`ejjrSVb9gv5=VO)Q18}~7zFz|n_R-$rx3tik zHf7@s?1oaVgP_^Lrjlrlex56%sK|Rw+S(aMCpS;?zK@~r^m6J^Xs;-%?WpB>jpSv-L_zs~Pw>%$9B_`<^xLYz;N#3DqR_?~Q;+!k zw7h%}kE1+;zyMvO+M;g)Ik^)vy29-2ZGkk=3Jj%h4s){Zao}2kF~-^}ZiBZrq#Wa+^(DomVg!2-X0rp|`-374 zDWoUl$QRLRZIozT&te_1ceua~7{0?A>Gbl(1|b1K9Wbyuy?A%Xrt$_tSV>vJm%qo- z)Z0u`ha1CJS4`(O!Wd(c(sg$Yx;;1U`~O@3qyjPZNxBp+PZ$TH;-jk&`qmws7tc5HY%%Z+SRq^Tu=XY8+R6csSgXm| zN;p8HaA&^t!q*_*H2N2MPyu4&)9VCfy6JUr4|*YdM*H}2qS-WPji7w0O&1nXRLeh1 z*;i^rZY;u*jfXBY`SDk@Kovy9a(rBX<}t#z0MpEp@gyVCCvSeWK#5Ny6`hjkA{zYB;7%m}i6ik+p^x7D zA6~79q2hK=gE;*P3!*L}aTT@{9;=a?Ae?H8Qk8t!8}mLe&hq_dIQ@FQ(kXvo5e)Ja z-*bUmflU4gSc1aDwKe@ueZwq2`H>&h*GGY~s%ZH#Fg_Cd_>@f*r!+TWeST?`B^4xCU z=c_#j5tbNSDI2@S9&BA(Tf`I;|H}CQWMfQ}1tJHRy)~eb|E{lK+}-Dpo}0S@#3X0$UIVg2~1dGSO=l?hMDm8%(@wfw*+rNa8pXC0l#W%)fn-BWobK-7nYSpp_UT#7XYpH!eE+i2m9$q>f2z#k`LZ+Fz>+l zQe!*g3QabM-qxDxGa?0gR9M4?84`M4BEoaP1uxeB_Y%iP)$Zq!Zty-Ca(r@h-#FQM zb-X2RN|nH{BleQ+6S2_Cv@opVsS-AXp_v(^FT+qpM|}bnkqXX2Fxmz~lazQD_qQ#7 z-n`Nv+*4W^WPym#<#Z8hYGVi$fxX`S@~?xdYaJ!pb8)%R8qVInl)5R+_e*OmIgE!- zhmM{iG_|#v@xlRDhrizpIN*L(u6#Pb1K?fubKL8{e)+&S4Lp%sG1{Ymdk5yJ6u<^t z;V)8s0zVz*nCgC(^*TNEZn5?o3(>R6X!-VfSYogz3zLQM+3o%skxWbqw*1-Zx;K9Z z6HI=vwb0i3o20Fnx~3?J!cPK9`jGs>Teoi^ARmq-ik_Ld7-NP5e2^h-9V+72WZhM) zTgRyNY(y*6n#phh;5!Vy6Q{6t$htW(#7B9Cj{GSRe)9BA&d$z`jv%V!WUJQH(t;Ss zTJ4Oqv=UY3qr*ekC%L(}5@hos-n@(#hTd#!c2M9U7MGTWVYNex%VRyZIUv&x)Mp4> z1z33AMs2Rig`1nZkJ-7~kb_mLY8BEF#&%A46rh;9@#z9SJ^qKRkN3A#U6>Khn7fM4 z?`O-G$~DT-D>72>iHiQ+*~nraO0$UkZvVu^x_WDrDK0EciM;Hd!Z2PAPkI4A!{GQ@ zxTbT>>(Z%nz`p6|=!ASO8!%>m_b_BB;nAUWg5x|0MqWJeM&eX=JZ68Lb3Qved*f`O zT?=uSBw*sd#y@Du0H^K(P^KVP1ib6a{kwb;1vjjIKaj7M}Sfdw&G2ls}ktm zIOs&0;rAUMQ0E3K^};(H7?Yn*7wfN7Wh(Lf*WNe_4Hr%Xb=Y@?6g;wIn^Hx~kQq#(T$M;Dhpu$KX106d4n(JgqpgL}j3h_2{|7v^q}@$sXucwmXE_mW&+oi2dBbRTXn?3)Us;E^inb>pME z!lJ@936{vxL^Ag$N%C?8;E~=#XvSMwiQS#QkT~e=40f?|e1&@iyBuruik{Lkky0N|vUIpy{DboGr!J|?IMgtHvfot9U?Hd#w1LNcPh`6{o zNR?UJ-33(I3nYRT7KB(>zq3qkELryU^ga&Q!_p=d_5zlRhjQjCv`#Qt17$TD zM0y6cls6|I_{=$~G8Foy`+8*JHt37Ces`lv5Vo!*F|h#y@;u4}G%Zffo$U!B5tHE0 z4qQ4j`WL5f=9&^sacB}ecc@KF4g0y(F=|@WzviUn>wKHw*~;Dfq7Z{3$o` zOuf1RfZi%#D*!`3IKpKbf);*E8CmGX%bB)(0TM!VH6GxJuu^f^PsOd z;GvKQkFfA{2!+p7qf?<`VVbaa6U0+UDzj@$!5svbyheymJN1Qe?H`c0)Z5M!j0#cw z1fBrnUw#y91kuU6}QeR8q)%-7cK)^4_>($a{t zv0Z8}%BrlV(=*L)e$F-LP)e7UHrdT-*E(51eaXXAtx2f3_$gG#_9;tU8xj%{kxBGQ zLGb(x_=R>CU=q&jM9>fYY^malz%uYjHa z(Z^kDwPRyr8uiY+Hd8;Qr_ToTOxYn0*$QSM@D9RDX>d+}__1>WbIyGc2;De_#u17> z$Y68*HOq7}Z-$_$@UXB(FuDHr=Mm!d<`Nb5*UZNraa7`rxHZ~kjN$n96!h6V_O5(B zS10u(k5%mE#L(2hXUyS67S4j$N6QIGF*y!Az8h>8qoGrz7)EP63MP?YP1jdP2a6+@ zF?^-r#}B2E{d?a_hF3ug1-CYZ%Pd^KBDu#jg5Xhjbo9+b*s7TT-&1feYk*WOpgESr zp5uhA>LHzHXJ-RE4(O8mD>7AZ!E$sw)WM7l4=3R^j|9t9fQkV3%7~3MviS@W6{u(V zY^DtR>69w(zPLLyW_s&$XcNtML#l+kPcjtoB!M#t@BrFs*Ed_6F~;NOeYaM9W3zGF z?&$fD2R%L1xpoT=0;YPfI?thI#}ALSpZ2DxE0i;rN4vJ9-Ly&4ijO!@dgvy ziZ&^{Zx9VMJ~wv-?_qRksN1BJnT18WwH_3M5XAYj(a8dwjlt0vSo!AW=C}Odf$}YQ z9RVc`Hh1XP(q2^MHYRUS2RIa)jl81f3vZSG*fqEeM zkxPAqZvc?3#C&IgL(Yz^%drQ@_s9xQr&ql z?`)HLryWx(C?=4-`7TOQ_m~Il0`B4|v6>Mi&VgZib#*m>$-OOfa0-)f8lwyyLD9Ik z&@QrdwckNhfQbNy{Yzl5LUsX!FhOn-Gfb5A*^JG=2ZDjuU0^v`sd@z!pZBaI(>bBr37*qcgR(=wfi-bzqUxAE8}PzKfr+~0II;q zFylS~Ik`S4uQ@TQ4Lfd)oZMU12PzUoLn072hU2i{`eN;o;2gO9i8U=f{i%6B5#oDa zAD~_;*l|4HO{-uZ7|Ie6;pJ7&R{`7?Y=^DPf9W6$4{E>hNY)=%nLMJy$3!y==9C!d z>I#+?W&EzNcV1 zBuVh_oFT#te08A?u7rjx&xFW5^@!&Qw>DOg)j$FEV>GiM&b_wxHm&q{xB=R&g`TI? z3%=~H(}SvyJ~(Y?U;ajx9F-vU*U}`+UHd`ABPsl<_(@`crQE~_87;J(yhBG_c=Be7 z;4cjelA{aQv{bGCGK6&Lx#_D57_EW!3CBKjA)zBY;1v@^G`W#)%ergXJjcfxkYOF;brB)Xt3%D~_U577~DBr_kz{|#4wxdrqCNPY!d z5EtfsGOn?9s_o_F#nE*;zzEJ<7!YpGHda@DrYpaEX^{c{5ytlt8$bmNxgV|Ds7mUGHye`{*@eKKJzuW7@V@q-_6ep~AjR%%6E21J+NTO-1 zv3g@bWfh*&JEyNMX65L9eK|MRL_B6aF;WFD!XxtmF7ppmSp9uX4VsOinqx=j)LCkM zR@jt+MHvFp@}o7X%#vtxt)7#3KXa8B!B5;OHB;~n8!@87pOYNsFHmvP;q(A^fW;Jt z7iM3;)q|i=bbm14c7}5Z+)-yS2Qt6M@B*#Lb6Fi_-&4kSNY;I7={YBcJ&v$gV+VRPp3aMtVAw zG*%CE-onk~hb=Jh2c+!5)ai7cw6v@YBKHLC=UZTs5<`9%cYldgGyJ6Tv@(ABW{Z*Y z@OUEjeK6Wtva{Wio12fhM{z{{>k%*+TVD3o!i1yvn?HE4L8)q-GL|vK`E8?auwGkGC#6$ zRg$x4gzY&5l0I?W4aGV?=%yI(!bk^)V<-pkBnQ$3z}Gr>-DwHq3!q98Y{{=`e?q4n zWAMcbMq+n+Q508iPm;^Ss)l4J0iqRuQ{WCFr$0ZEI$9^@@jIJ}TXz3&>T4 zq6gz`Bv}=F&XX8FRE#PAN)Fsah2ok%IiKq@3xu?c4Ce;F%}OeAw*zeEH-JT>UR!eV zWH>&HWvVa?!+|c*gSmVmaI%TlrRh&gWk)4(Uu@dbDp3|s66RXesG=N1b#FFf&KHp$ z#nu?KG}yV9OFyUd!rJLnVGa72*FvpLC{)N-!r}drWzU$Fk@2H!A~Vqn{MfWTgl3hg zjEV|QUllZ1Kxo3i{|lkO5Q^iL$*0YKnD&?a&+Gz?S^nc$>lh&-l$XGoj>y^k^-D32 z!%0GPYOeL7`qiXmu$8crd8=}6C_M_i`4I_8K$R>|WLaK8VogcxEl~ftMh9NHxMJW> zunYKy`P2o}l{W*ENC!wJfNt0#Qv|6?+B?Y%{{M|pybtcem#93_9LBm6d$~Nylv~R2c%xt#vf{+z;>Ysv4##jzE9dCcXji(ZD^eCoV^WTJAY>|`D;>b=m6jE8+yz@+CY zQimY=Z^OgNc;6tMVgjQ*0k&e;pCBi2{pFvSm>B4P?)r1QnqVzcmwUdWgI$^OL7oFG z*lxTDR&s%#Vj-^N@X*jZX`?~i%Y}cx_NN07)(^<0?5@42(cWq%*PC=`D=Fy$;#G5o zR;I*gnF?VNd}S3`IRvbleppXD|JXnVftJe^EH&6M5uYJwNG3cJ#3vjWxsy9LD92&- zUv+A3YDre=Kh-zM|>(|xj(6KffoGNo8z zlJgw55&n#tRY~hKU{r}fq6zY5Q;oao6OzSsavZZkaGf=c^4K<`J@=e;W7$))OSU46N?_u&#vy;R_Kc z1=GiJcn=};OBoMf`0Kwbm^oc(m-zn(#W|54Ai)rq={J-*H=+ay^rOI0OIXE*N+omz z1jvf%hL2ePTTb&Ko!UqUCU+)D!E{1*l=a%u=~6B3=oQe}DSWa;zVo1_zMiinC>hYD zE$1hx1s44&qCTjRZtm_-=|4b#IhFXBTl|I9sU$1!Z<}W~iwTO0E))*<$kpFJvZr5U zaj96n6Y|`>x(cI&m2}uKIjHejtbjM3QS%w}_jeKh8M&uu&kzN3vb9{oG}j#G;3h00 zwE*_Po#kb*CmV7%7J>+AX=y-ksjV+VXw`5S93OdW<1nEWJOlRxg;9c4t!6Dpr<3jP z;vra)kFWpCKo=4E-v=_lEDbA2SC38klOKSZBpQDd9*I=Nf_EAy*kF0~VjOmW?VN<9 zB>YDrZLC)YXwCmqs{z^`N>b5zH@)ivcI8xqib>Ax4!qEah+M{A2%MKTvNL@ynQ{F~ zaM|AQ<=l~>u2pf6ZtVW83_**1V^Ytf*=mOFwexqZb>Qw zAS!`geaoZ;YItZ%r>2g7wr2&d!$!=+2+y6!B*2jI=Tgh}2+f)}&G(5D(1l`rxj7UI zrdy!xxwyEv=MP9KhcX_^Z^BCVBS?Jk__Hf>DBacrumpmVoqZp=CW)wI-RSoIk z8X5#4H>U$>5{?`?W28eJTQg&;$|9E7Izf>E_-{v6_Lv`tq1jG-dRwpsF~?96X)IoN zgG~ctILKWnSNbofNokK_#yu`cA0LNco;1vONdEFkpth+(NRMA_?Xu9XCyz5 z8%M<`r{mei&Lpsxzc%5Ku!P}9ZGMmZPMwj+^`-U6%_NW?7z#59q>a|&%t>Z|HZxlX z&qB@&Olv@V6VvgJ?e+t*??+znjTNN`cCzAQk|_%StqQ$Pv0*mRfrBY88q9o_R71#1n*V}m@31|Ni+mYpoX^dXUEJH1>_G$jNs8`Iy(PXOkJ*e<2d7H_Bs3_)_9@d!3{- zT7b)5x*5v=e%8m!;X;E7{^Y;frNko_&x%{9} zWEqxsQD;kGIEqeKZ}vLGUOjUn5F`C?bT+FXYI~K$*KUBXb^Y>ad+^}S(M6c=2o|@_bjUj;i$(wf~1i&Ys)REEc!r*9!KzNNO$MjEhQgj_FDp-#F-0m46rmmPg zxR2lX%jVngKTt0tC=+E{TUx#^`eMR@g*oXKpxr5jE60J=))-N0Fi>PSIIyZfnI#FS`r}(xk_2Dz| z`kZ^CE2})0y;&$AyTp@}$|4E-R9(1mG@_4wc=^N-hOCpIgLhNyb8fZvsXD*1JZY*d%uNMRru@D z#INXY1J~-+^>K*zHKG9n}H_Hm@%5B+t%bpDLgI z_+%t5iUo4_$QP~yx>3zcZ-~PyW2a)GVJiY4*D{q}j&1#!o!4c?9z=i+6ez@N>-c`C z{^2MmY_pJ)pS&+26cy!3l4d^3XwKfIoi^3kqj-4e>PN(c3|0C0*mqSwk`D4X-v#C} zJe9kY*a(asY#GG%OM}NxPP(*kR~+3xdG9Zwbf)2XkLMS>QqW&?x-Y3EP?@BOd@E7Z z%+3+w=lcygT7*OnJ^febRi5-}equ81vVG`xXo{KD^)KSq_o<1-Dr(Ei1rh{S;+r?u z93Rv^)r(~-sTTd4=3^P8Zz=KL?9)sx4LKrZD)x1G=+`csU7L~7To!o-XXC$Gwjq-f zpJun$gP#fBW}*jm77kj(yGpLD&Cfk))CuTC56V%Aay9tpqr*h7*mM|m*|*Vo6v65h z0L*1Hf2C@31+K$|7x}V@SYkvgfB(AWJU2C`73WkWP=rD(3=1Fs8%Jb70CH?jr_*`! z{wGRl)<>j14cew+9-Da+Q5Qb#mzp*6l^#373vBbwh8IK&d=`=RzR^LPx7}LTQH}G4 zl9isVa{9@gp848bunTVZ?#gex;eY%4wxoee(UuCXN$HAn%XenNmG{85cP zknjvi>~Qe#N1IG*1V}eDJPHt$Zw@YgL(FTIB39t-dh}zR=2cr`#YxN4dVS$x`opG| ze1kJwF57J_1qB6RloBeT`>f>(rTi(5OcOhR|~KA*OeW$^Ly`Y#QS3WNp2|= zRNbz$jQ@8gu;SyXYrEUKZ!I8y?Q<*HU0YMOmel_)piui2*4wb2`ZJBzB{cOY1-k$Bc_0t|7 z2$A`8K>0Ahkou|5WlGLRU*Gt<_z9&cDc`?@V2hQl_ZzJpVmcFeukMTNMp}^cw|;sR zvwuYF|7St~AF+6g_B^iXPUDySuQNl(-ns@n!!cyBHkZj?^NYF36nb4tXQ~pf?(GDq zac-~+o6SBVM%iqIH7a-1c+u-K;xbxw#0TDw0}6JKbCFtrD%t>3 znz^P5T5WIN7+vA*DmE9L`oG-|{@fLgn(@`uc(C1G=v7Z6I`7r-{?S#d7Q!#vz~@P| z_x?b20hwic^Sf@rEORCGYlWYJYo(~6P9>9dCZuV-*Peidl&KWKJk;f2`5U2#V4N$9 zE8FGQuv?bOdiBO8R8^-28nqjHzMiWFZS(mb zVuSwWs1%`yLZv}DH8Znwat`PY_%Dz4=SwT+8%7G*O7DsI7a8g{F>F0&e#+4Oju2JU z+(P5c>UYdH1Z+oE^nNBv3a5lGc!Q4R(%uy!PyH6Vo|n{aJYvXfFBAH-`Vdbkx0Fvo?CSfl{y;Y)A_IMCFJC86nSCarqsEcqF|m&3i1ti8`W+le#aeKH)$8Tb_0raYE8tKFqgb zjqK}vI^N&urT^^NXNa@YO1iq(ZwHUC%S$!YTsd(mlSxs6U-NZ{#Gf^#$CtX10m(vs zPxQVK{%)GbK1=ppL1#~83`Z<3DgW)>@IUOx{$}D?`{1q;Q4!fl!9v0UJ6-E+VE4DO zSJ0oo$sQvy~W`C-rwY{2@piQdC>unNCS6z#f$a(s5{Gp zW$&k2W$sf1iD4_X_XWCWjE1K+A(4U2UaF!Z{kt|w@pvlZ;qJkZ|7!QqQB+Y%BTxLx zWCpIop7-2-N*9t5mVc1f&uh>wTZ-uN>@Lk`90-|ocxftZSv_XGssKkSB_(w3I0y&>}T2coBL7@0xgzz2* znljomJBx!6)R#Obz06M6lPA&N+x?Xohut#SjeiIvH~1bGn!L+LLYVC=t*~>Ner3p) z)Su;f4rUgr0)ht~uRj`P(zc?uJ9o&8F+((0fm_YZnf3njP z|H{+1vF_jE4-wZP>%Ggv{+z>oR3XpuNG!zX&hb7y>88dFU!fOjn0Vn6%4KC`*ka&^ zw5q|Sk<4P)vCxrq^WcD<;+~0#fkCUHYRER28id+0GF-X-`7OnpWMI!b8T}FaEK+2 z4HEjHXvbiz%)U9GbO0R;WKIjg0HszV==cXyM*A!=rmGssON=BSbY{0U)ymTb$w_ekU7OEd0Z*g)#!UTtkIyd(*^EMiV%J>G%Av3y|H z=YER^o6wQT=`&K|bjXdGekParX8j4vLcLY` zg1_GF>kqXh(qJFGlaayeL?Q&Dv_;rrwHFP^MrUZg%~3k^;eFlhd^3al`UL7K>*?x~P>kel1+Eq_;$R!rab}aPFW&f}3eLv&BIblQI_Yj}h zqMr9}HZ~sB9e))J^Z0n#tL>9tQD1(+rgW1UkwJ3Wk;vqUOUO}v%5$6s?zl0pRfxzFPV(cjQn)N zuF;D9pq^gKAN_g(Dn|t8)o#_C6(YKI;_?aWR{|u&r}BYzy>_muEsetPgr1?FKYuFY zm8~rQvYqMD)|R!kRrVPfW@V|b_9T{*mC5Jwyuc*X*0v@>LB374i1o}4Kw7^I_Z1SZ zX%6+bXBGn_%2<}cMM9=%$^p+9Id@csa>>~bw^ENg$u~`xX#FiSC-Q+$lfwwcFJ)Tgz^0_wTcTZ<=Tw-N4%YtU*?;XsI*(NUry;8^}gOQZwe)I>^2l7qd zgNXl~UEgEb_Rk+R^TBPwuNasrQ+HdNDB*wfzJ3=!VnhT7k>uyX^rOALB^$}IG&=bk z@5NQ^=P&lTo0z!wKkf*gdaNj;Q;K^M4X&8IMyTUC?YlC2*0udO{a9R$HktW)?xMF^ zD%V&{-vi@rv?s%2rx3rVZMGNXL_>++Yo1E7v0u9*4M~q(mttdMEwIoAa&lV4`~ryX zw4WE3=`vn-a5o%UV(r^hQix(ez~U}0wT}r2+?vMqT+?P_&pbwgzw*b$0|_J3no+BJs(h+ z=W;+&Qdm=ytUX?rNFlN$-J7kU!jVlh$9W+6p%ld9yyW!8GQHBhs4!pC4=m~}Jl2aK zbbP5a-PILns1~*a9UG82GjRR=c>gFX_NgeB`^*08uQD;2JYR|^{*>+g>Y?H>7*Dmd zohZL|RD0^mn;H{Gz1o}n{Xph)-;xN~VrNyjrRB-Xj-P$%SSdpeL*9aG=zA9xT5;xL zwIjA;9Z5443)3$p>rL;us4yI=3W8PqD_4;0~^n!}ZPLhV2I zxr!?1n>%oj5VSul#xez~oVVPMm$HBUl+}B@H+R<~G873BTf`XN8* z1uK~mO-C5iNYuguUW7O9AMLccDICuq>4mVN$+y0Fb#VTiMMFaV4d1I$My7~Cg=glv z)IZCj->XR$6l8F6zHo7={``4*R(p5;!^SGOk&HBQBYmUrPHL*%lCFr5^h{%?nK0-? z-@hknVU0C-qhTFbZzU3y5ct4M(3bA@EtA|*=*oIX)kKt?r>MoGbx#-QC9Lhp1igy4 zez3B#GO%jYl`)^AbyeG|mBUR*sF0_`ctv`WdVgs_BNqMRe`hN*9&3O5vSrM8Tz~uG z@lmX?6aB6fuSLxc8&Uu9;VR-$=~-ZOxoSOyqI(i|-8Tm|&OIuhPkVpMo#mv$2v=Pv ziuLDD!0qBnSF+bwL~u?(n>uH^;2X*aUei{hBi9A&mnol2+bZXnc;fzc*Ue03YvYXv zJdd!K2_nc#gBF3U|pm%**TEJlW^Z{=LupEp_;Sm%MoV9vX~V1Nd1E`3X>dnl+nXQ1!2Rwgd~Xplc1+)r3IzBI zre}8C+{hVJE3B-ay&XeGPICl*Ua+Cs)29kg%A0Mh#~6LWZ9k;y$1uFYMoyzC1Wa#a z`H0PABi{9{X1VRJ`(<$xcRT}LAK?p7QBeV!ZLjgh-99KmHk`~t)pC8PMJ%r2aGXFE zPv@MuK&<`0`=m$RDdd~(2R*wi?$0DXo17s%y$KB{y)y97Tb!CR(Z#cZE-0AcuH}vb zF%l}-t*mk?=RYobk59j8#0$K_bksV3eZ6A4a2{}~PV~5{rbaIWH7(qaINy?G`}f&+ z2V$&TaPP)6YSK$NUnzfe@1yT`g3ABMi7#WV4~iBPI^9Jj3uzDtq~UActI)a2 zg=B~yD!Gq-tt#hx^Mt0Ew7knzLiQ{_L7$*)lgLz|tV*OP9yTp4Vc*!;98r>fp;A_(h)tw zI(BXoHnB-w5tesIebgyGd2y~L_DXxYoPKoN{j`{eQt)Uul*sDj8!Eydiuo435I zQSD-~8OFina4zJsMvU8baD6ag?L))Y zuge#_-qIQn#b#0Wl;CHAP26%W2)Ig1WA77KVEZ|`$zBHY! zYQ48!UR=;;k@P$&@gGMnluTXO9G6_0ls*`Bi?}y=%5iNziyGTOe$VB|@M&>QjwkNs z#zyYcPS*nrtnD4_?VbFanx%iXGB$bT_C0sEDBR^D4T(0saxESo4;3&%?#xL>#!x<@ zpsMOEW2_X7k|AxOoRWCS?-vQt>3OY-L%r`1@M(raj|md49(Vr(41njW)6vzasG#BC z&_Rr?{G-MEyzt@Z?nFQiHrOE2OecZ%Cz<9f92+`Sc^@&zNssYVk_H3$V5cxRDq?up zJDYehgoWspC_#|nA|0>vi1aa(Wr<>d+s(sZudCFCp zrSp}fO3irSxIc@mDOyN~-C~ICH(_#JRTYuNI5vVlmOu=P#GL4+Lo9@<%vaPRZE&(@ zOW*(H+e{jkVs7d*ZrV)7mx_^5ifT$UOw1}0G{Ovq^q4QOn4-F(yYm(oD=grK_h)B0!%*kPHw7F`uuwgn<#}jz?Hka#RpikBYcubx=Q~I)vem^IV0U_)^ zQ5pe{qQg(-UFqrjt(2YlotN8qOEmW;L`~C3)Cs|nh>eY1t?3T=60q#C59PnFbF`L} z>;k)5k!JNn@YR4n(XY_}BEXepWyfGYD6eD|&R$B&{m3;YG{DE5K3Z;Mv2B-InZPm} ztX48Hcz`y3pFc9zAjtH?p?xqhqJU&)(*n0fj z4>!@&W1*YOyNBaPIs9$^ub7X#}*4$EK759=%b#l!ErH!eS?OFF9=GwPlhY&Y<@H}i~;Ke z1;wl*th^s!h!4q*+q1mgdU#gWD$HC-9etUYn4U8*Bm>h^?ev#vckY(a*RkCODprWy`E~2y07@+rNn0=f$Uy2L5hBx8`muuspa{LL*UEo zI)G6%S`0&)y|ITCxy4#bN=i$r$AgsAFP&y$0#!Dp0o3xv<>jH?-tP3rPHMz&h8bUX z^>jza#4Lt{9B+*$l$%rcETa74VjV0kV>g?v3#_dzudK8VCV2HEaQW3pGT`|U2oYR* zo{~)@>UWLq-!eBi@#v^Ha09+H@HW~+u-#MZe~V+F+dOc$FZAp9weVD7g>Q`S5nrFq zYW+KGdrA<3!1NEa#A{&9y>X+)Y5^?uJPg3N!_d*tK0*wJdZ0dpgk!VW_Z|$afByWr zzFO=BRbj9wKuHwn@@vFxV z6vWy(p{(u;Gc=Of&elChT^`4175_V_Mo89z&4JakZ1{lqL5iVP2uJ8^1^G8>e$Jb_ zTU#!G=-J#e4khuX0>})vL1#Fu_&|nIxiz4BFJz$ z1_yB^p-T~dDj}3wS(p2^_MQQH@S>5GW}s8y&e~3+|MKE2(hjena0Q85a3s@FL~1VEh8l_fv7T_4hOZ4{f?_M#gG>FlxxlLokE%vQ8+j zryeRR0vw-?Ern@cvY7r5>vMI3{nUb&5H``tsCM3WM+_l#K6YH~X zd{#n2U}S6(Ix8+J7(dJ@HOR}(^!4>sYcjuk1HQ2I^cFk}rtayUZRm5_pSL$yo@ooFM!-JU&ZPdw(S?hY z|4-`#af|f`Itf0Q;Mk=r%|s1t#};!vXgBr`lRLQ9o8mn`7*g>nGg3#z_)L#4)A z9_MZ8V(4CJ)J?1i-I(`Dgm`$MXYHyKs_Z*XZSM?xAxm()DARl_@-2;8PC+4Ei2;IU zK^byvdX<(PcSXnB-wco7=Xwc`G;zh-Z|IGpmdIs=OU5Wjf3(m~(UjISjV)4A$tyg* z&9u?e2LuMnCp>RvWu&2L?d&vxfj0yxA>>#GR+_c`Z=_1JP@*C#CI-&@-+ec1c{^qB z`jnTKCrZf|(W4{g5vpCN)ZCJZaJCq$u|J_FD%qZDZ3Tve_FTQj@joX+`3DB^L3MQ* z-rhcn*;GE778b*?Oyn1*_SXyOZhU-p*&_lT+1KX4Re@JrqS^+vq+lwZO#%~T5s#&~ z_~z~%>^scA+N_{iVri0c#bCJ=Sw-aeh>A1dS27h6Vq>%P#yNl$rr!~EaQ^S`&<4)c zkYq$tt_KT0*!iNOo?MoKg-1l;{aO-1L@Su;YHBVIWloWikDHk79v#;;I+s@+tdW?$;&(bk zK{PELpdceDh{e!5ABd{SBT>IHjd&1H^8<)nwidR`{q@P#^{4*p`*v1X{)nIqv&4m; zvMEqe6&)MPfS`M*x0VCyXJG4wA*SQA8yIB zWp8w}wmd)F=}T0eieJYj?LIn`OF1tBswFJf;Mk?{4LVq(^q5CUgDsf}|1oS8@JDB+ zW9AMMdggejCVp^N&Bn=WGrCLmHsR<%FfNz7lj6RVO1dL&O1E(*x zp70x7h;TwVJ#abJuWz^@Czef**>T|MiO6Ut-5@1vaYA|f2EDAeZwdu1tjfkPOoF{Q zqjj(I!BnyUywRhaS?lLVe8B`3)ps0FE+}rNj5Lzy=;-i=j&NSV zY+@CUCPwwjdAT+8JN-%DP;OgpihVSWj(=HA5(nD1U%|E0RW|+$=LY+kb>U zkFl98X<*^WvspO7ti8}{-It16#edX?7km{)QNHv0bN=@`Na0d68-Ru-;dd;oI1O9v z+hbN!h>h{Zzf=KQ11r`re5o|P3?j)+nB}{}A|L(MP%k}bfbV2yiVF&iFYMv-)pBvU zywEcCUiuqOEyjv<3C3+IpY><^ToCKRYO&%@0($Uc4g`W$nU*Nb)Ve$zzg%RXJ*y}E zwTQ>{dGI^V)78FJG5^Dp6KX_IWaOIveg6u}Miue3k#K5au8%*kJ}+NrGC-D@@C{@z zA9E-L{%!G>WFE)2zz7x|$+TaLb*`)+i^@i)<%9Ei&08$E2^FnfGNeq zFeKAV{`vD4kSL8;r=(vxqTXi0q5`Lnf{sxZ$fmTi7Gz}5@bi-ipyuhSeHzVECi253 ze&I79POX4I$f+v_A-(&WADZ#E?hI3M(r!=i_|MPk$G=CS@u5qn{44t}M5;ka+5Y}_ zx67i@-#h|#CLitCFFwh+=;`UPVl5q=Pfq5D<>5oQj2NUf99bigy>j@rkP%j_HuDds z1IhvhcztveDoZNO@*5zh6$cfc)AcT@#7z^;^{8mg&gx?br6Y~J&C#>!nZ#W)SquhyS)*+NUXj`9}IDt|eXO*#}=H_Hl zP9k1jJ)-u`72s-;?H{UVXFFI=SEa8FM98JUXOPsh!f85$BAND7e0fTji-K0cKONbDBPfrI-M_P7v2Wu}# zQ*eN{|GTdnYq(WK2iXxKzs$@`0oT8{0#HSLkAM+@umd+VG!o>>OZ%1}Bj@ypjjfPU zv2yN$1A3W|Wi{|sJ*UNx`6NDcCNa1{0AKt57isClX^jR=zZb@?Ns!4~;@;idgk6&M zh2^Xd0#~!Bp^!=8j#rN2*5Y`xY#04e_YqM=g-CA^T@hAKr%CxN@edgI<2J9ao0Qj> z2?;gA&i=oRo;pH;PA193!om&CT{R&T8t>F%U}hhzK4&^d9;9 z^{pYTkDTlsT8+!t{gacafp|7r9w(!ZAIE8>%D%FDAv$Lp>MLzl=xmRKcpYT!-V+Pf zy_PmJWB6ajM*>s%@j)*!&KKk5WuFXTs?Et7$9R`{qW+TYqx4Cct9#|X2!x;Ea@oZ$ zVt#EcTaF&anxjms8dSLd&DNd63Jr1xIs%`701X9&-C~j*$ld)Jf2ypXh~Tp5G}PH` zMDhxu;$yzHvSMvvh1L9a7j|a64h@MELD*OEN(AkB#U><-N7BC3Zp3jvAF}8riX8CA zT@`Y&nH;dJZ*XtzO^EUJmB=(RNhAnvW0wY^0cmd9+hsvl47ITe@%wNvlpi1SZIy)0 z5a$<9oYK^vr^rvMxC!sPPvn-iAWelgj0l|A5Zfs5i`$!@w*vM7Ji|&`;c;GR)cc+e16-+8B{%)>^6au0TfrlrIVNE7}DWCT+L_sYgWq>}W zzs3K_?G{)8yZ0I0F3Owft{TNlG4|?28kzRSK-DR<`J;0>Iyy3(HOLp4J@s_`QF zn6Ga^njdv!I`ixsl;6_>EUcWLRNUP=CQ7Rl6LFijFVF7V?bM96(=oG0%QK9sB=y9x z*m9G>aRIAEPF0@xP+ydxJV%^mudb?aZ`BlSc68UTw>>C9SHh zjiMob@E~o~?RQJd68O}>OAZf5hqWeioaIynRQq*LOhtJ}e7c`5Cd{HNV!`4l?^&)iwf$fcuaz$<5E_ zvsvymp3@cE1=qZpxjDFCz3!khjBc0i!lg9*`*$9)eh2{B*~?QD-cKV=L^T=9OxBj6 znRr1pzm}2F^i+1+<*c18B(iIlS&KwZ&qlvLDKGM2xxy1_YOgHQvNt+yoedt89o9#j z7UB39uddz`DoQINiF+>m3GF2<=g){Td>WKC)V8rXjdlkO%M&*?E)KAXBTwc|XcdP6 z?h)9w2oEqU!^jA#sILBGfvt@V(+?kTiHL|OZ~DBkAdL-}h3=&T2y2ZnO#Ok#FptBo zW?~lPHeWz~X=Ljf8}(VIs2EZS^GTpuz6xyMvIE^_93RPKB1062kESfY`Zk*j-4xJu zMHBl$zj?Z;GlVH~gmNCz=H_C(o&bQu?b^`+cg&=aq$=(+y~8&3*t7DJOyZi1yjS0* znt*-Tv4n&Gs6(jp@?|&;F;sm4)FdV4mIst3hk>AHVG#l?rM9+Km`_b6XZLQUyiYS?Hm_;5ryQVm{Izk=>Y{YLlOW72Ga z6xY{}j0XCLdS+@33Gy!yh@KyC=m<4pS4_TAKO9fK^KRj{plI5X?0vJahHIst5SGmy zZI4a~&duF`3Oh(%l$MkL6883J2)$F7Z6Gih^~OV4vF?BWO+)1ZWN3|zjNB)ljTP(6 zL0ThIfd`tJj_n?$p!wj25wWHJ_z~W*1WPn`R-;veZvh=`7{?j}5c zXb*9Uq#ncQZgCJAUT`%wI&&1(NFuXn)wC{H0fy9yOx#V_urn~M9eU@;EYfgqU)!(t z=hLCjB$Gyl2cKXpo^HKiTWE?E(Bw#+8PwYFC=6(_YG_EyN@HHz@;N>@&;|YKGkT8r zSctE08@TV`P0>~ z`}_CtaE()9*a72@wstaR54Y3dazFq^Bn?D+#z8vx?tUV_g-nI^+g0iF=lsl-de`%9 zZ{z{umsXJ(kAgZ4dpI@JGPN5DBF8oA-%!#bl-LwlblR&m1)e{@UGr1MR_<|TmHjSX zSe$lIJ0tn58L~Y3ZSB$C4wv`W3rdfO3llMyU#eHT0PcDg)IBgzoR=s1t%P%Zb2E(i zCEer4qK_lMz)}DWEs&3a{3ZgCm<1qr;7$mdj}^c+02df9VIcI3!lq2=@sEv$=9UHl z8C5s|f1WFt#f=(Ri;IqSbaBbw9QqE60|mb$t|+(3U@8F4(;AN1x*x5;MO++)*UjU@ zM>A!nDjz@Q|I}wAi;Ig+Iy@6v-_c5pNYhhI3=bEUkN)!IzL}kJIu$2Di?w1j0kPNL zcb%61Y`IN~ESMvM`e~9)^|kXeh(8*A?4s=&cs(#$O$-MHiO3Ao3s_X)a{v13u=K~z zp9zrFgS`U@f$94gkVilhfFDjkpuVguT9?RIl=@-d+qZ8QmzIeA(o7Q#CpQ0B4AQ^zEYhngk$-iKBmU&DG75%hw*gWBu-OFy^gg5MK$9YsBFKl{((DdZP$cF_B< zLYdAT*2%Q+1@phj(I0C+RO^LFK-dz9OG`G@w~^RyhvxGKj#@Q#K#OqtyPqaO19lHM zgFk+}c-w>nsWE^Bq^0SW%l~4<5(UI0u;@YN1=J8DBNPQb2yUa1L`Faea|s|VDk@no z77O5IS!@kdR#t`$2~tC=Hq|*TBf`~nWG$@7@GLy|FrD6(@l+O#lDlbi$Q%C=`NPAn zq0*Z%&l#*tA%y)ISEccZoLD|qxM6;)o?q72)9pYIiv;f-e!W@DiT%z@r{hZN+$KuU zA!rd=Gi7J|{>|gKK}P9CgDWXf!(B=a1E;zlYZ*Fp6XrdokMHly3hc-ys~mqi^YthY zsIyv_2+7@xl72BdCJS?VH{y!3))H!K%VN#1#;3__4`(h6 zJ6jcf`{=&$Uz!tsZft)I+2Y$H6Z}Iy`(MTS*47z76(E;;bIp>gl=$u2Hz*29Nznm& zJ$wX!Y#O#RG+cpx+2G({U^GDc3@KnkKh9R!z7xT?T?rsLbO*tT1qh#5VJcy_??yrS zL2Ov&xc6ya?U?ZBy(;y(W7(HN3EG^p^}$A(7!&U&vVR?v&Tw*=4bHpn{$OSnv?`$- z7+J=S0eY4gIy%Vt@&jX;ac(SFAK1k@9<@4Q2nedpst=HKSP_&2roU2sIqt0L!(8RY zkjz0`YCAr}NrFJI>V*%#YLvEIvRT*OovBaW@G1?F7N67JgB^> znh^L&6M-NaZZs9z<8T?DOa8H;MO;B+Q+@O2yAzYQY_j$r$s2)Ne$Nl6o`V)}fRE

D6i06$#>f;)_q zl=S=94b370Ti60w(&r45S61b46#w&^llyOTJX^YIF?3md;^w;qyc{QYRfP6$P#Q42 zt?cbzhvvUEn5mNtr;$}96jNKm4H#ISntO>H)}$~VNz?h61!wFKS6^Bm=T~57kO@W* zuKH@0CKYd`-pudL<%gKa&Am5GE#hm071yn*W;Lt~jHvsyvgAf*s$@9hAE&Rk9#mGI zvNj9%L^BxXRMOtH<&n z+yE)*4^eUEj~|1>!$*Mdz!e34CsxZ~<&?TYT22$9ojTm!)Rl;j4_(lWcmInJcVc3Q zsI}Wzfxg>?QVe@Hb}K+4p9O6OHU}vM!#Io;M|`dyM-ukAMxa;!ojlh=)F!*v$FA%g z??{BWMjz!+(|Z%2YStU2W*&DnoIi2Xv`DIVkFPkDQ2O-f--uT9#|E5E10Xi5?I{6T%H*IRW&tKd{#I)F2u--Y2-2^hdPg@8#0^rN>L8nt7#3QgXt? zNC)~Is-@Mwov^Tpvt5p&e5hE{`x&nr?`|?KI=W~fij0<)@Rby<>L$2jhDlT0L7Ccd z4Mpi@F`Jd4PNW1s?porJ_|es6A=Rcw?WWAuST!SLThiBU8(A>c|G4R9#9xinmR$Ir zA0TH;l|AY3PV|nJ9zLVFa=9#naq2Mp)&7Fm?H2|5gVIeJ2w1SV2@1}(wfXAC3tj(h z>Fa}8SLT9_w`f{Chxu5l$Y&5i{<>a691*I=C2>vK&W)+$C0IQVBq$=&4<56=AbIrQ z_e&a|d7G8YOmWB&lv`12)Yd1HAj3EZf$*l<9$a%8P3LF%l1ASn^X>M``}qg+j?WH8 zk|*wLf5GURD8UNBw<-xb5p%fsx*5J*vJ`Z3D&PKP7yNPCbyv7(8H`w^TI-DEYvXVx z4EtHnhIk!#zUTB%g{+#N)ubzzkrsh4In_S4btq2Ipi}qEz#cxO^Z0uuNJRzpN)Zwn zd3-_an0epZX0f$tBLPf^u>i+3;5^**mXMaV7|k1nmz3lXhab*s6_u5M8RU~527UuD zrD3Ie!*p3K5u_JsxS6T_fDtGL!>Vrx7!{czO$n2C{5 zjxUcW=+Gus_rJQj|L12#k>Mugv6b9iAoMp^YzS5+>=aEL{!@0pZ_&{l9!s*#%vB2}(?R%tWTK8mIIj(Qa zxw2N+T#o4R!mD)Om~;#E1p|KSOGgXqHk{#d%*O~l#DkUfjf_66!j0b_j`fY-ggmrm zWxu57goookf1VF%Lk{7&QTVZ8;ezsAT$Bg+_{WQF_o5X~dcx^xh{6se4YZVyqGFjo zczvzXUiWCdWi6|9;7T92H;H^ zp`p;<)8Kd84f>u-*_&v!-Cmfoo#R@TS~*wHcX{9UW75jFLs!cCo`jx@ul1BUpEvB@ z|LB^-ZO|05^_WCA*Vfe1f;$>u4duoQSgyke^0QJ?=Ye82>ahzo)Bv!A`-KRu-p{{) z?y_=lfX0-M7^4J%uN1T1nF3(#)hm>q68K#Z+Mb3-A?3@PS)GeVpYxD$_jx3QA9+2& z#R4T@{a}gAOZZt#G9?FtbBiCE_8JUJgVG@aD|eLp5F|H!?*7rSHLqo_B1^RrlZjY!y>V;O;%~{ThYPX&RSjp0 z*mvwE*0zkuByRkj4vvn#o7Q-R_>CTf9%`4p=NM(vhi3Y{q{7%SP{}9=3Dq~X5UD- zpFZsv8zT^nkBKq#&5GPgnxCHs;E)^lnCYx5AWlFdyP2PBX=yR;ON@z#kaxp_nG=+} zab`hk&hpV}1SK8a252p_dj#1XQ629p$W@ z)4iXE6XJe0!E(}xZbzH0S z7qS|)Y08H%Zh<>r@qyoK_P01^>k*WA`a3He$f*8La8m{xrtjr``#~NzpX_X($LTA; z#Bb^+smj1#;On$GxMKFLMfAuQ<=NYgBWEB*KVDy@2{2?efIF3;ZH36pbFyGR3wS^=fBR;X$xHy_A@wrFL{rZOS-*-ko^ot z>Lh{aC4$=ue{%Rq^smX8RQk}_^eG1cL#S*wgua8))}RiP=j zfClSL1yZ&biBwyT^JQ$Nsc!8jm=LDxsuA80T;mESD8#BqUUW6@uI_R-QQsqNetUI6 z%gP#_o&)?+za)26+Hlq;VTUaQgZ!O9xOgd7BT8kB7bvBm`XO zK)rq(v3`ruzMQ*}i2TR-aR1%cugx}r$mz2PPj3|jBHUiyg10~6c;V3zuv3?NmE!=b$oXAdSiIk#R_Xi-RB_?*WVu|3A;h?v$CT4+`QTv;>E>YMLipV^7KPy%XtH%xB?VU6GA{!qQ zHEaoVPjX(nzjHU&_$N@Hv#hNY2nsHCdpoXYCf4T{A=J3o z{Wb3}zFHl($=@Rn4lyN8VI;HSoLAVSeflK3O48bFmI3sDTmBJT#vpeuM_EV;@BkqD znA4}iv>1x7H8iFMt_*?5GBgB&))lBw@PyXY)eQ|PRBLMQDCC7=`sv~}Z+?ByVI4_R zURDOG45YhmBke0IfIa7vmhLOAYgd0yho_yKIiaT;^Cb+Z0FFkteJuOWZjZ3=6_Kr3*V`I^Zi^Ub@IR< zIqZ^;bApRoQitck849<)Ce-=4lkv~|-bAro%suYUT`s$t-I@O3mp!iLCNA&(pEd%G zs&H`Y&!JW?NR)*=9T9)HJs#OeV9w?%eu?25CL|EO05|4)I5>h<^TO}my#qN%iNTNv z4erBA^1p)Zwfg!JaRjayK>B(p+Q}LMy;#qlNlHjmfsF((9Khl|J!!~PX*xug@|aFQ zMIbP{rkekGD7=4cJeng#PYm;msQkcP9Q&rK*TIyO{PU*f&ohUfG&G!lp&Yk#16jpW zHy$pB4X@kiLxNj)$Ql|1Z_mR4V{I+dVxPYwvBJ0cTbAIo`~($2Z}J)-KZ%vyU|^y0 zQOITIfp?8}QOGv9exTzpuj;*0BRx8$%e z1qOkU@8Z9PFEkzD-R@dC@DZgpBYY$l9qx(eLohjl>SYo?hT8IjqC!9-iJ!=0Kg!qs zyvEs8fUJduMoaFDD+gejfp_0VXd1gR!a6dNWQ>J)bGX@m6m*9C(@ODXiA90Z!elNW z*6F3P;oJIM{maR_RwK_%V*MCLR;jnr-^AC{gawBzZ>$e0Y^3eZ%(ZqvplPAsIy<)ZN($DzLbjtEHLg1E|)KN#U*V2=jRQ6rz>*la(7B?km*>&rnttt~tr$ zvJrBwcB%D)PVM>=H^uf&`~9UaBiEj)hU`sD%79cvK6yWpm_*~yGFX_0Dk%r}~w` znLRx-a~AzAdOU|m3Cqd!nbdH*Ni79R`Y&}t_>U|icK}FmU}nfziI@J z)J4)h)#gL_S7OvsL%XD|Iz265v0p$+>w2sCoN%EE4?6wo7y2Y))_yrp^W#?XaWmel z{$ih4X4iMf^ZA{kEDPyk<+bd_C7RcR|BvF+I5HKGW6P8=@QI?E>Ur`t#rkkbuJ2&? z1!Yx8qhi_{^3O)57^!IJOpz+$u#aqcETVKRN!r-R9Pjkd$Jjfa!pLWnJPA}vIgK2m zx4F@2rg*BVw@xm@aC@sTsxPTI+c|&!y$?#`M#=Vzls-v3lx*-;(R^Fa-fsU+z_b~E zPJPgF`+(o;XgHGGe6V|-i>FT{9t^J4Cv1V>@n zi0NG{A6%F)55GPOa31<^zDfHl7w|)3E|?FCp3uE;OPHLJ?iwv2rT!Wy{MEyrG8up9Ir@P`(W zek7+b?E{JC?$Ra8>DAn?%%g$JZm#6pYJ?5e#uo~?egm1K-^yfM-n zuD|Lrzfj98GP-|hr>pcHbN*6>TxCZCfzYhAzASc;r>j8Qc0wQ&N$OYq=e`)Q6FY47 zHp@7ltl+XwF$s}|U9{9%5``n-nph7OW;Zy#OJ;m45pWM%n%|-S&qQ@kv#-7FEYJu5 zIA>xKkSN?1PVfi`11Zc_uHPJGQ7Si>IucF1WppG)%F01-=De%9MFS`M{id~c{mMx3 zTS1R2Cf3uGCF84clm|uQ3u_yN2y)v^T}gY#`wN_{!}BaV>;*H42&!k%gL4&h4Gj&q zN49})eE!a6Vu+X9)y{pwQX5fjN8%S%liV&>tQI>FIoo-%%$RAfx*j8XlbB{*)D{v| zn6$Rv&1D`&id*tU_9Dye({t*md8l^AwnL}p(-RGcmG-+RxX5MibY?c{?ahaGXQ-vc z3*SdLp8hwJ1nlT!8p-F+pJy}%Q9GYtKEYVlzzy*G2yRro$#-%ux?PI*e(vMBOk$g} zVTr!a&FN+6$s>HdjB473c<=naUdT&yoy(RJd0*Pu`lQm{D}sXX(nVP6Py#`9RH({f z%bf&6mna%Ibjyq=lA`_p3r2qxH8}JT&_qqiB3vWQXTzBDOk#rFO*XP_HpHd*+R*ln z>gzbMkugt0AR8q6QACOs&PAXcv{c*rg@u)gT3c`biHwfsRp94_)lpU zXu3w*Sxw?+_(Z*IKy)xQz?^N$o`;Zk3g zEI+FI-8bHt^c)r8DYnqc9hnosHIXU6sGJk*chdOPz+1X1dX@R0h4+8uw zwT}NfpI)4zi2UbLvJ>T7tL{K+wFrYxXL%p0!{UO|(3)_?MUoCXk*9z)a4)0phWAdLNh(tahS}@2E>LOPiKByBJQ^MkM z_Qq?O+l{fUaubA{yR`(#0p|ZaDA?Zh=%232(@|NsgbYSIv#}&vWXV{^eY-U5tNzRN z!hUWVRWtx;c>x!Ga&tot@F*m;Jaf6an2dflcWDP{g7h35a$c$xWh}{0oK37?f`?`K z_u#F!y==+^0B4!n`N@qrUTlT!^u&hV^j^AKy89Um+<(SV0{TBTL|=~6M=^bwDSblm zq0qmAD`zSK>r2PhVA>u377;dmY^1^pMY`G#=Pv%(2_+x*BJ}+o3Nem#aPPnSm+eTr z=u?q^gw)+kAe&OVXtIgk{#l>vNJz>sIxC&9S-dEBwxQ z8GqET|F9Q&PF|j6kG3Qdsx3l{N${)V2X!F_^yg{zinV8^90x_bwBl$)!u_ZRT%YQl z%Tol&Kl};S?|9f?-0$owDk6`MNQFDT#HUB!6=<3fgD<$mL2n3cs(EK3fYicD%oOZO zu4dbnEbXF4^rrN9>EFfsg5nK9hZd`}?cMF<&)NPy6g+<~BY!qrU)oer+!OOti?r9i zMa~7K>*?!1!bIIHKEWE;Sc{5N3H^_@w$%3A+v(monJnj#hU2!ngu@-O56)VI{U@Bp z4~xl#95-H1pcj!2n^vw5m4{mw(u`L!s+IlM!|`*gDs)^%*7n@0oUUlE-mwLtb$VVy zj6SqAT_^0PAS}>9uxC|P=|)NV(rXe$R+-^B5`xID?%v|ffm;3KNSm)R1IyK4ebYDX z4!lwj>PC3BEbKe-XH*AK69%irj{f{1e5&^(Z>4KP*^ z&=`CCe0>4sh-E)<;XCL+*|@O%7yITwC;rn`Zb!1r)r|)$<)dVwO##L9B~HDQzz6w4 z{JWp^5L}z}d~6;L^_s~>m&$~e=_+Uli98yjra@7{Rv|&g@MZ8pe&XeWE5Xv$1!}#c zh*kC6KSt1!X(Tt-*QtIf4?@XsxUL-}R^ep(1dOqs#5=|)+IQ=YE@U1lD<4seUXfqy zIoCYrFKnoYr^1@u#Qz!UY0j3aDtWIRk1DlB*YFXE}b0V0*-BH;e-pJm5|LKy5(6Xfbz}x~mndkQq-H2|mN<`%-I|VrbB76!_G4S_hJ1LxYPYzNC?#Ve z;H8_;9MsGeV=4DUd5t(YFfcbKN7#(2;dxNVlO=(q$+LB#KbAQ+eDEF21^o6Z6+3+$ zIAYWiXXC`Ea^P4837UEC28$`q475eQ$Fj8t@6rT5oCR70uk~H#V&~4=U77ysp3yxMMgJVI zBs*#{R4l6IrArhTm7_>?js0r{=l;DV3=}2h(Lkg-L@SlOIWY7#N&E=q^h0WG;Q2tn zpfJo24a|8a>|>d=(hf-CO`@O1qqI2Uus)K$V^ex-{kA%ttb7>e=+r)N z;rTMqSdI@0h#|m-gsAv$!h1y6l?4M^06VonK@@=)AL+th73e8KhI#f+MLfo*oEk;U zZ-0cNB5=9Acu^Pixv?px&HgzenuhCLhM{VWuJJCl5(5yf%5sA@Mw4dOH z_JA_KYL|3JjXn>bwoW={V%e@@``x0!da2xq48jvY-C`JD$aoIB1Oy%gu=rTc{34)9 zsZP>HMJlq`G7zq>i2*{L-0Qp5_)6a;12A8s`svd6A-Cgl{JyN5JKotQ@?HEF@L(uC zz4+!=dirAw>aZmck0rE~UGnhpKX8Yox8Vk~8*9NT#5K%$hZ`dhC%4)lTpYJe!P?gv zQ+?-?zCm}Xj@0$f!UdQ+vts2J6hJ3~C^_MQ7FDkc`X#1z;mHQ?xhqnKsTJ2urFh4e z_zK6_D$f(*rmmi_V&=C>@?fJ)^JHs%x=X~&H9tffIiRYfl1wi6Z>#Y+p!$QTFa%S+ zlqm}^1P8H_tzn?t>V6Swgoq|t3Lz1KWGP-%@|Xj*3%=71wj{52ubh2&IWYfU6~XqU zJ-9~1#l^`wpbo;5mwAydwDsMEg+P7t05MAow~vg!4ku0}gNyU-7ySrS{fljVzg;!Vb5bHY zGdQDS#hHs0RAzeXCVGm-JAw`*w9QM$SYEMw;-6s~G)szvhH`viI-BOQT*4 zOia*URKO38mS|T*E0=sZzn!2lP}-*4i=Oi8ygy1+`qP^^uA2i6vFuTw9WFYho3^sO zten4rKUpv(N$=n1Bj-^6E1z4?ifI280Z(=!C*D&!ox1o36z=A~yt4!a>6n>y{wac} zi6TNoLh@Ky`M#RuT|Zq{3ya&Ep7K((Gf#eCmZVfvEQ(0M7i}HeF5xrb#I!xbImH)m zN7TW(Mk5)i8xJ;3Y7R617ZwBezxfZ$mF@kVI3g5WZr!OH*j4%OJQz>vjlH=k6F57< zcF_LS?G#g{9pPMH`U;%!*VX8X%5ssW$(f7}8UMT3PkKYJ+Zk=#+G?OGf}H? zi1!*APb8J^`@ZrFnc~$)DR+)Qo z1&W1)^*$w6T_xbi@Y;F`g^uI@UEWDQl9d`SQsZw3WpuqVNx9omI(LKnt;&5l$%XET zSXlC(+CPNBe1a|?QYc#7S$5eS_PWHjI@GhY)H$8IT5SFXE)@G+HVchid_|^Ouluk@ z$@i3FNo2#tI0c_O>usR?+v>9)ClmOaO)1_FjpIyDwAt%r@7>dPo4Nn{_p#$JX@bFcfZ+MTx zt(xoM9&%fyYEfvB4H3okaEM$+68~S!b!<$x*wf>AlVI;B=FE>+H;1er; z?j=3nWmL2I{Aow<6cFY>`+$V|c;_4`|B<83@SjUOw8KW9*r z%5eVgq_XLcM_9^k2(Lh`z?U~!^lm?MFAFj?auBtBD`iD?J zDMe}NQbM}ByQI6jyIWFHLb{|ux>Jcmcc;?bo$uoLz4ybte)K4ubN1eAtvTi#|ACG@ zKl9=Q=ekrq*VGhB_0ALywv9%$N|*$g&d0{ygcW(nCxHFVzmnluERF|fj*5x_LFCR) z@$Xe9eof1lwj27Q{`N;FaP!GJ{1j4)KR(u=@!``^&m39S4ol8=6Zbx@pD%fZQUi+- zOfys;pNQ!Kc~DBwe#380H$l{H-89?q*5Y2O+(N`xR8%Ip?;nz|Zm#A)oOBP>IpeL@YkY+F)+oZf|g6Vee%pgjT!sB6Us<`s5bRXBM@N$ZxXv_wP5n*HdeedtIQ zrz+#`Eub8XL}8!2XpA#v#Ob7`)u`b&C?=@ULRC|l=z<5sFx0mK!#Q1XmO` zbFId3_y}I5*dc$Ti6oVat-iG&BcT@h)_CEF80Qbi|Q_~~gh>cYtI2W{V zQ)DCTX2m3?{8hVoVzgNC%jC*b*IS;H4!J|CrZa2boYWZ6IJytUaC3%xV(KsT@H)Lh zC2}LxnUmRN9fP_09v|tCeUV&ou^RLh0*OM+PUS zeW0jZPZl+fja4qx*JrXGoQc+h6Q|XD%|}H=^0L=P*uVw;T;-}gSGkQ>r;pIPcCRzW zT;@*Mr`)ktN3KB>Db#^?rkjad8oO%KB14FA*PihGMMW*vp_Lb0&eNm*8)%7-4NTzOzKg5>`koMb^6kx* zG^yRthsfW#EvAhQzH9AYzA)u|3?qjy*D@*j>$i$l|6V$m-M_WZna#aE#YkN7RziTQ zW4~O#tR48AfcFyFNh$T)BDx?VQ59Y2=MElv`kVWkZ+L7rv}$@wwIyI|yOvv?22<$S zanN|A{5CO14e_S836yzaJkcKB2VNJ<=R`pzN9Dh=)er_yIlVrF{yvDVpYbMdq!{`J z6BCcyB}!IfT& zUcUSkBZf7xQ{iM9qq&p*B}u232BBPcX#u;SYPfU(tHcba#!!LlVooyBfC>W16i$64 zYJ+b#gkF1ieADtNwS5-l2XcW^z#f0gK|zP>eJvd`3ehApqu_HXKii~-%{t*o5m8C0 zn^Br$p#jT1ZcO&FLTChS%A1^n)%)c84UiTXh$b(OsUo2fT<87tO^}Bw1H|5Zg4H>KdaQKkJ z%|m=UHn9CO&fZ@8=a9WhdZQnC7Vw8}f^{Ow$tk*dJd;oCLfYRWKr+7kjbe)Z{EP0; zAWQTMy0X*ze)`~R1F(Ar>$Zp=-zdgzgA%e<>pU(aLl!+KKcC{QJWJW@PJTp|7-s<@ z+*)u5fv-oQU{LJ)WLZbf#5o8-4>eu|%I|JdxE3@^<~u(BZk>PITH*n_o7q)LAKXh@ z8Mr!sODLC@OZ;d-Nc;a1UOwIT&dGQt4r~JhUTG=KWHjHamGRavZql-IJn{?jZyq)c z1a&Son%zUz1DN+!k4{aEPxo-Klz||B(+fciIyva~bokHDlFMahJ1f^D_RADb4|?e5 zo?@w_!xB{tvK!7%yUV8=wH##B)DdJ7U~Kkhh9s;yCV%KOxGf`>o3>9bZfCE4!?a!g zp2rOb@D=qPb$#qQ5(|-~lAmjh>@)^adTfzf2s8IpW*ftv{dKw1I&Cctfx}qvNZt>@y2#5-l$GfAg@6kNHLjTs$-RHIt0zjLlZ_C>G55EOf5+r+(x8B9BN|AsfNc z|I2H#R8-itcz=JtxGsiOCwo>q-2t@D8f=ha&UbSa_4G6pZwBN5AD{kTvfE4+r1++g zUQ&f%hOVRu{Y~kR#|Ic0v2xu^pNEOxtuJ1@zz*KYUYb^(Y2t^ln-OEco;d62#@0E=|J;`( zQk&C6KutP)J3WEusghNq`OaSqq3LPHAqj+g--9F;8yg#7epJL^0DyTwokR-AD!g)G zqHX8NU;5$cVK}^`y(h3lFkv%z5FU+Re&EP{SrHwj;e>w_xGeWN6V(pi&R`qK36Ho9 zTaseoU{@n0xo>RzRe1DFeQjCxF_`QF?d*e{9rwLyTC();-;9HjaY5L1-$d>ziP3dM z0z=nbn4GJ}s@-YbTbUiqy9z_2-{Y;Zn%rLOF#o*jI!K!h>gOF_>J zn32R|qGug5l1obFd>@nY6EG!5M0e*KYd_A^jsIDBXjHn4jf3UVu2sLy)_Vt5^QFLR zNp{%Zy-$WmrJcq7P3$eQi@+Uyr6`Hx7fJF7(V%|TAaZFn%OIjGH+OYbd$!E59$PQR zkBGDk_AOR}^X?rS6zx6w8*Kjv-m^i{io>wlD-PGEOC8U$2rOV1mfKk0x12DUoG1`n z65Lt>3kggI{M19?H!3EelXZ-#qQWYC{P`L(XwG7Kz4MRF!1m|I@o!x(J`;ty`#TT}k~SK2hd<|}1VD6iy=o2pSEfunh&?%R zvyL-i`&yqo7yflGjILENt*SK_SI&sY6fq#LVQl*g#-m0;qlUgkcviSr?_ca;^+X?m z{#8BetFHmZ>SWrVU=%>QON+1W-^}sc-1ghZ>@w?CVxgD`^iYG-*I%`Vozf-#28F9w zBhRS?&Fv>vt4Fos`LZd;hR>rxFzK|!(ZLJ>Afr*Aiu#)+VM(;(s#FJozxQ zgo%JYSN~+~(NSEx_o&6|Dp)Rh3kkRtN|LoJW-PMDMkN;$jc3dlNSxZ8MqxkPIb3p0 zd>^CmB~P)E#?st8%u9L9oYh#;e$Z)fuuD{wg_}DDiXQsvqqcO7^zGyU93vqv-q_!uRkyl86NlKmN=Lvujh8;Wt9?g4%MRG z#|fSz6HC5E?)2DSF#WgL!!UT@=Qk>o+Qyhg6>dC-%VI&KtL%gui4*wm+V!knGL@O( zm!>L0Sv4{Gd!;5w$J=Ofc+qt;hj1!6iPiPv;7JG4qHw&WOvv z0dL|n^Q&J+j2=b@-=soxHdPX$a`jm{{4ojNuM5Oez-O*Jotv+5I%9`7ZSUc=SWG zG0y*{q%PUfXPf?K%mSAxA-Lqz2TI$2Se^1wW*!n!+cmYJRH^gd>@-~ITXS%BT1 z7I(I%vX5y=ILSovip`RO>C3GVtn?MtQXbb8QT1%6?_p1b?j24DsasUEyc`*5*$&*g zPL`ct`J4_p52mKFwI|t)JQcUQTA$CtK}yvs|IE#CkdqsOk+NrpxkE2yO$r^a^NYsp z2E?)y_0DnY)I+z=XY{vE=;4xW6&7EZCvi+P6Z-ibJ7Tf>r9!9zx1@D_x6`@q7V2bB zQCgb~zH(9)926^q(P#FkGdJ$_%zl9hiSGfb<(q1C6*p*K5D*gcMa*JR{I3Ok8acM+ zMQgPOwb{R=+B=Jmy+Y`$Xc%n3v$f4qf%gMgbAa@!q}c;DV#T5up*Fu^*>7&Rr^mk^ z@ibw=8Iyq#mL6;7mjG3e6 zW_YvXPow|Vyhc6k;GlkP=U#L~BtZ3!WLUjsvYvRg0%&v?#XSoN3 z-9AT)>GxeL!QQ9ejsR7=>gwXqL&by>8DAW*JG;aOsp{JNvc(L8( z-+2*J(qXGdfnKo|ltJB?M2+TpZ%lU^M=<_?Iy_(Q`kDq4Q9~aatW8a4CV*QAYgfx;q?%|GoE3rAG6>X4ZuxnA%*5Q99Fz%xE+_OV(Uy>dXtwChz|o z%yDUElXkT(AC?p?;+MDpQKh|s%B|zNT^6JCH;ZL%-9M3{E~VmZdc$L=)=$2mzj9)G zs-Y3YRojMJ&)+l>%V_xVs%N?V>b}JwV6X98rWWBgLP#K=&-ePA2Gh@dJg=lJSkAUb zYc-SVhW3;&{uNRZqZ`A@qAy+Tn{${(!9xAlCd0zYN74jritvB1bG{;rvo-9Y59s|C zAv9)yD2$|=+P-P*K7C#@S!v{d(Ymg={r6QTX5(jAR63|u)JV9PH4-F0KOciq7Tyn> z_S!tJP&weY7bo!x=c?-9;iMHO#@N|b`?y~DF<+#x_H#Qylds>B?Zx#Lhw*vim@l_V zzwB*g@9*AuVm^Kq3Xv!8HunBiMas&Eu9wM07X=e~{+PLlOlb#+f>U;I!u4}EjJO{= z3~KY%CjGnIE^(J{B4%0>Aow^b-kNGHF=iQb-Sw5K3rWOCq(<0QwK z?eNN!HI{`eTuqErVS9tAhpAsU?BXbK#icNjpdfTbXhHfe(HGJQu<7H%p1i zYccy`dlp~jTr`2VnFV8NDRA^VwFb&)bE+INNZMS6utc`k{%2tZMswXr+#|2+i$x$g7 z5CBX7L)al}*8tI!lao{2#1)iC$3lF%J;x@AYIl%Qi(HtbO6myXcYFNFf7PeX24SUZ z8Jmc@vm(}WZ=`{ZVeQ?!kJBW+$A9m4U3ws4(HN(up@xh)A-?eRm8@g~m;0gjqco9V znmJpZLzp8rA>jq~bnim5?9noI6m+GrdU*bJYAm;x={>F#8{6tYsr^s+ADB2{&&@7L zDs6gX&E3j(kY5juwA?H$^wlTBYd7$j|9*7WW94oR8Uk_|K+G`9py4q7EWQgUT=vn@ zJQ*;~DC@}(-vs&B8f?x_6)@j7WeMkfMUW>QsxcoY|GBGtXwvY%z3nd>ao`;)wr~8* z8g-7tVl|x?PbjlYS+%!34X+qg#*uz(i;qX`TeDGa>c_G@H3>n0Ad}ibG-T}ad|ZTm z*#AP@(G{YMOiin4EDbE?_x}ENv7Cv6g-Q7CI1V+9E-2t;cym(_5TO5~F=7DAAm3O@ z#^zUJ3AF<#oaR8`gzSK8M8*1(!(;KQ;MsS{>o}xg42a&BUW%IIID|~l*)hkEh?C3U z1}H%B_cL@9>C+#Ow$-sly4-@I2KM=G)s2D)R^0!ZRAt4kR4wyq76#d}nOsn5hH9+T z9*n;5Jy@=G-OezUzC(mhbMI*hQGr95m1MH=ky-0eiTr|Pkur7K+VC=z%jxk$bqX16O_U{{&wk%~V z;YKiXs+P#Y%KFl;2iRV`ZxlE8k@2xy&rGt?mpU)@I1)v4ibI)kuDT(?moGE(J{JRkn;(@)!pW>qBeK$8n>Uovk@UXug@1Zd}LfAUD$dvSmKc{i-bu~U$ zjcMJIXU=FgH&^Yb?IdYu^{3Zzqnl~KYu8v;y#hIm6-sY zKNMtSVbmMqS9B8U*$p5~JOuSa+nt}Lre;B2UUyd)=qu*9Jbjy1q*e{&u5P@^t$v1O?*R>7Nn~W>k<_ zm&3I8SZtTwuh%i)bGq(#|Dj_CTOZaWLr55DPqii+{|uTm45P=AglFHEXXAd(1f#Yf zjr~)wK8UmQyg4Oz5LfOT7?3*NxEzJG2etrvdx546YPEN1fmFcKw8}0EEI1dQm6i4@ z7?ih}ytJ&Wo7kH-89crkYH5UQvauam+(L^;cdHNi_Yc{O<}6B>&dZa|bMFE5vSh6Id!ZfgmqdN9R<0&v)ccJ==L zK5$}^x)P&5(K5?a(@=l!dv#yp-0bpYbyZ_1T?!GNMuu;$=|ax&>@@}j)%bYKo{#q~ z3QoYApu{kV)j$L=HbNRggr1-U>bHE^RK#!M!?MeSb?x-2VZ#_;jb;|R)43EmNC}ar zdbWN^#DUOd07el&EwTXgU(8mV$@zIsGP0jQ?des0K|=JR7b*0V*fv{EtYGv&`KSCg ztL^d;A#V+E5MUu#?;tA~f^6GBqmZM4S;cJjj}{>vX?Jky5F>cxK3cN0r#Ab5B*QT zfl@4b#RMM45XGWnI$jsIadONvDy~ z?ZQH%tOr6L=d`_0zp+0T?Bdd!+#ZB(jO{Kcs39!uq8Rsy=}U6#$>r`;msoV^;v$Vk z-8(!SB#>i1IQVUEdg@n{%N7ZGf>M)kff$#SlOBhQacaUB?R-o#q3Rl^$n)IQTveI! zh(NlW=^;{J$X#C6$sGgcpl8rlFY(4lZIGyogv8-_$IYm+uolI^V&pQ`UY3bp+tCU5p=Ql%&hzw;whC|MM_bNke z&>kP0wyW?vD`;M0Q%p`LDwUX++3I#qRJ%kIaBgm=2l6Yu+JS|@$su!}pT_*4l)aRh z#x%n+tG?=9eq$;MLHOPNf-R9%6eUeePwy`o@(%}U7m_eLa|I`Yjd;s6b1q&5y+4rxRKzv z4hIJZqTPW*+I4SQ1{l2AvAzgrFvM#jOJH?<{_~wuE`{0r&(>LjI5P1#L-pVs_QYV#|RS3(NMs{ik9U&IDSkBS19@TH9!$qzDN-RfQ9$ln3-DQMnreMtgLfO z>xbKm?^!H3@Hv7~Nv<467NunZ)is$VD~uz?FXk)oH4U{Rh23)k!#blBLgb3jrV9R%8F8abcPEJE(1#CS4T&7C(?%9&{Ys`!u8KA6O!MX-wV(jhBCktbL z{W^3-6Hx#Js&fEyA_Pc4V0QvYo)V=`_)vH542?1h#2gUE3r42F>z_Fz)!r}|f}P;M zZwX)@fJu}FGXl`O!_eZ;@x5H4Ffcpr{W z^EjC>=)bL>sYeFGjg~0np3GKWgrL5EaJr|5_5V5G+qoX`{pr%@o2J)93T4ewSC*^w8a~XV)GE@+j4wFWxALSUCHv#ZrRr>!Bo*ET z>*GWFjH*_A?ySK<29!p|PS)>40JrFw++k^J7Jz341qF?BnnzyK#ZlP3yi~&o|>*eNqvAcb? zWnPO5wMXUG{B)t!R0BF2>;hRX0!r$~;m(b>g5JQ@i5-04+s4O8TSZ@euvB+um!Ut;!8u{Hvr)X(c8v&={e3pFF-TaNXD;1?f10wfqn09>iihZ9jClR(91r)Okjq@x49 zUw7jIO^6?K4dA#Az#;@ZVE+F8;9J3mehm%=&Q*4HcCc)3QQyH@e#w!H7x}I#_-Y4J z_$DSc)?fdJJQYp1VG29vCAXbkzSi>5U@|TN0et3&y;jdcJsTFCmZf>)pWbb|Xo7ON z%zPg&SDA#jw5~~X+JLcXJkPAGf*GuzSf+u}=3*@>D!N6h*{@U&@l&73Zv`aZk4aZN z_J6v5!@$K*Qe+S?8p+gJjJO=G%g<@S$I-q2YECzC4)4J%hQ`HHN{^=rx4aiCEj*4EaZo?@_+Qr{})-18QOQs=Y);01PY zSa%*FDgUvXOFAbCxQSF`hXF_1(s_?!bowR4S!Fsk0t@YGzfnumv$ghO=U?ZFR@*lt zX`h^tOkGQ3XU9h`$)YaA98i8?kdPwiwp#3Ls{G1j4yZVqcb@!CNlL&|WwDgfNiQPW zGgoQ&RIJUl1E?3$h@e3LA;~baOe!N2<#oSW?=2zynoMicsuocoQaRb+xF*l!+tbnU z4E7*G@9OH32F_NFbun-$qtertK$WcgDS@9zt;S3NJRBgC_u{b`(E+)$$!X{9n>Y41 zr^bNbl4uOrTt>FGgy`tU>ghhp&mUcw$mb)#u>lBmg0ZL}GL%-c<`~?#9v-*x4eZf= z5TIkz#~E?RX2hQ}Qf=$qT@KXL&h#3EcwTx{+UnX!_Lm>kPpX!)&Xl;C_PteBQTa%~ zx|ZqdQg7qkU@9kK@#$~F_vn$y>uVhWfm@cRflqQ%yEBAd8~xYEc9wv(Li8|{s$Hh> zfsmd*HZeGZ2;2$noIDm+W=gGZhQ@me~lzpkB{0_f1mhn zy*OBs#R|cM z>tVSEmd`PvApY?URa3ApaHmnK4w&j@YX2A-^$;pUDK*au$-tGYX13TLDb;Ch0t4Q- zktRS31iWPt)Em07u`y6hf=_RX-Sg+qDp&_X&GoC0E z5H`Rr1E`1xB|jM6(FXJ1Ta3SegsYbpF^fUq^$%CaiRtaM+^+F!JqD{ye@zsma6*=#qJweLm#Vs8qm&CZSGCP|QS zY1X)TZ%QN81r%0Qp*kOU*!RB^&HX1uw&Zev`ySU~_3!a(7i?sd zTV|QOzH%w&XH_Wvh3HBZ$c8t`9_G8jA$W)Zh#_2Ve zYtC?njMp&{4@GeQ&;~@DmylENrRc7z2Lg<=G$1kBdeQf(Q&NYb4(GMY>aE z`O!)kxK|#242ndBbNMm@bJbw0q8`qU6B0smIV=^I>O}gJBl7x4D5R^Wr`>0yFEor} zHctv1-mv}rBW0c(w;mS?S>a(Nl5*tbU!Cy{F)1g@45hq8L!%ok9U0?=l19Bo{Jj@e zKIAO#-1vlnkG~HN+zLt&n6vPUl) zwhm6$bgBC`k6!%_KAX_owh9Tk6@)B9G{`A~?}rseeRs78Z!e1_2O zU%=p8BZ*5kSS+G1_QXCWaL4xE9qTs_r%Sn{4PIZ@sFshDkbnhdzsW^pgaX_z<51&} zf!v>Bw}KDXMJHdCGZ(MCR(h*R{R6GF>u)B{1j;fp0aKKK!y$+$6a*F^MR<4-Io&Z%0{5J1YHC08^T8y7 z9)NehzZF$dS0~Kik@C4`r{(5mVpYkA|0yo@#nhAu7sU==6rEjS6&}Xj5*HuJh%7ci zGXM*<#}-A0AKp3(5(M?x%rxfqHsZy35GNYT zLOVsHRQ~uLSF~L;GB{V11&1x_bL?Uo+YtzAdm*FbId)@+6ymh;~1jKFGMTAE5u z{wY6ezt(dr6yjsqX~s;Lo1>`HChdDh0rsz|?{QTt?W#Wag^2^^d5pG8`%G)3B>hb; zD6k6e^Q4S4j2?zAaH39}PqfEOMD$H;nwJiHR^Fd=F?=@wEpz!!Us1r{vX}(OXh|aU zG%nZS&Q7=+;oLDWicCpCvC7VCHCq9q2b2QLn!xCs6OaxlDG{J2fF1*M@0?)K@fRl% z^1u^tetzE3(a~}qoq!f)yb%^={_h`QZZ6YGTLLAyF(oDS_&E4-Q}(Si%1q30*--(^ z0@T|6M0WTH$eoYxIq(M@@Sz)F_=y|rsFa9bC=1r1(Z2hVyq4Gjql}D-Mn;fr>QC~6pW3`930GQQw)Es;)~6UE5;_W z^3X<>_By(NlZ%gbzD^46HC0SkZ-xEW!x_04%30frnbDM}x(_4ge1W*UeBePr!DYU_ zKFL+1Y4d$*%gr@ZzI@q94}gat4D8iF6+m5-NqY(chcuw6fK`e7Z66@W6}t(M?gU&r zgUYA3uMbe`rdq!h!fmh*0j%Uvstn}LCggJbLAZZZCyvPvQ+wbb|YGKEh#3E?WA z%p-&IsDg9E{j)S$J?vc%@3+Gcd387U)9(ItLbuHz6_=;Gp0~{9G!eV;l>O0!uC*2k zxCA;i4%8_r85!}49QVsS=T;;!P9HHGm^n6mQwF9^b6l(M-=8KOk?SINqIwb@nnZ`6 zcnbglvAWt(MI{jc8qLfK^YV-noV$N87=okeSN+-ek6#i$>*@gNENyWx-QK0rc z&U?37O-g-EuOW!e&LKb``1TFr2Z#RPb^>QC8VtOWg@MH2N(kL@o|lzAkgMf6@$u% z%Voc?lvLH#^$L`ir#JVrv$NnhsS@Bkqev;19tbl|8+r=1u&6blk;PK`gqGJOY>BPR z&$n5srn(%cg)9EdQ?E1o=Lk-*p`ks7J&Qm1GF7O^rixJ-T_QinDoKuP|45E(@XahQ zi-Z{k2XoC-N=&RX?UC=|<9|AVcA$VDM6{z=w|~@_DR*40JhwI+O+DB%-Qi+W(#Rf6 zh{oshar3RkWBK-c?H+K=z{3i-xw(O&B|*}7s__ayUVt1_qEwv1VhM6ravW3}0hxUd zl*EVu4S>H2{#t%SjL7H3PJoKG4<>SnO1sYi0S`!8d|y;lqhY<$dN*59@dk~cVfcr> zQVC}682;{bBsjl>bqm=n7NUz#N`3Q>9P&HcLh|=hC@Env(=#(Iu(o*B{Ugp$>C-1R z)teL2U3u{2_hWJiHQ(5rA*He7*q z*`9onlS6A<4H;cuhd_qclAD{R59huBA>G7^W_XPSm&ZfW>pm+23ojZcmo~wtuAR}* z#6lSU_tw>7{mAI>ukkx5!01iGz+elIaeK|`t&7*ccnvm_)uT^FQMoKBv?#b*X`C!0 zors|LF#ZZgZ#;!O!}DI^6UwX20xuu*jsPnrz)HsD$?!p;X0Uz`JlVJBJ7f~UK|vsZ zpl{<;(suwr3%yQOUx2n!opq}9zxPShI3V7bo|##xWC|4UL&L+OJcRz&wt25t#rhVy z^^HuE-e7>XtAlQZ-u&IwatIpN`5xsx#qD8ci7KJ(JUl+gt{m0i@lbk$)p-Bd3`oBC zBH9lRt|0M?QdnfpX`gCxf|_KnGAx%=j>g1{)2K6;kCs;V15daIF4*a-0y@G-TceMW zeCnDCD=NV_%uJ1@(A)K;>*hVeGO_fmj_i9NfQ!d@UGA%cpGkdXatOj26R1@gktdp6 zk3Jz24?RMsl~sI6@`_ z^(Vi47I~Q>sOJ2p&CV?*&Dw3Wr|jPZ>x0kt+R52GVYkZ<#=vlm!1MB)&rx(_Tv4%1 z1LhJwJ8>XnsqKK#`I9L6?%?2;K!i+u#vqjv1>fiAgkqAhxVFO@#{Uf^sjNoDXVEfHfN#Hp-38WH#u-Qg=%Uv&}@#!YS z3LLw6M}44{URF{8vvIAc_#N&olfAuL&8~2MA_Iwrx@}G;7w@-seG+^J8&qhGMMZ0G zFIrW~aIr8|TJ?nz^>tppIB;-QR$A7FfJ^iAVqul-LmUpl!85Dj@V2|+j%up0tKNWW_|AO!<>HIhUesO^%J#+8^vFwoJn z3JSy&KsJbweCCMIP%+5+#Sw}}0}Hpi$a*Ywza&0b+khhcw;{Ow!DM$`=>?D8M0TL^ z-ZYJjZW^OVLNXGBU4r%M4DaeRFE2H`zNE@@)9>re{wA?dSFsO9!K<@f;q~W_$;em+iw98IRZ@WV?oy^jw{_y?ZcJ5j zsH%}f2Ue>*bC2<#5;OxjymFQA9AI-6do`Vl7Ln$jgx(Tzi#K>;k%nI4u^yMKk9!a_ zVPgJbGKKA!&~9EwLb`b}nrM3n>g@$P2%?h{P>`PLu#G$4kb=2a=)}0<);j*~^25Q! zUZL*u*5~b|?R9{1@G%P4$w2;%z9CE*oCV%gzM4gE5i!y!{3P+KpQ`0LKoOsrm;i|= zfY1*H9nHymLvqK=07Sf}%If*-B&$;SXST(iNdO%fC7;359|-)ZZN6x*DGiR}!ZGYq2=>CH-5~tmj0sjyp|T+rDL85zlzKOH#$nL zfOif**sLxAV+P1m;WKnegy4hD-APUqbktGTxjlg$Wnej@Y@ zeis+kV0~@^w8orC2^2Ir5T62>e>y=3hb4azkofrMr>~EIhS{*S+|iT2^Hbt$9s_-` zvgK?#msePj3e{z;b&0r0!U?Dt<5@HR^!PpRT~?EGe+Em>OI=)+`Y3Py75x(l#Sdz1 zya6c}3$>Qes(nE1OiNFvKJ4*MG~OD?M1z3VRa~D@p*@V=fAKivl$5%F-t7+O51x#- zcFvp9dg`>Kq<6(lsVCHFl(J+uUQzmobh3w@LiCw;y# zBg;WJQY=rmVxSzdtnxcfq0s`HOod1wa`|H+)bY(lHHqkplf?lB8FCL<>yCfDq^yVqwO)ws_k&w4b zs|68q2m@o*M~>DeJZ`ke9J^-@86j70;?dA_-iyiRy{~@emM9@@x*qk zW|_ILf-z-%hmJqx-i*wq)LEt|+2-i8U_52G@tyGQ;(Wct#@DSh=mw&k2#Er43AFn> z1fvoDDm44@8N|qS*|z|x3IJ>iWzL#GUkn^ETYR4g+~KTKMdQ)jkK}506?cPdmIo_o zKE9p8<9z47#sri&h5)_E-5Jy2_DqDfBLXY)XemPLzqeM&R`XQ7lu0JL zEZ5S0zkEs}JY4ix@U6SYLSyMhZ|mni*(67J7LWno;qI|dN~E_}H$#mfzeI}m_4E9vgV_d;`$L}ZJKe!}#W73Gej`Sy%)L3?w7ZF( z+mucl6FA5y5?8AcqxzY0Y$M^JP0Bpe(T_w_n+FrC_RL%3O(EI$uHMzQpH&g4lci1e z7QJ_;|HiMbi@w9bO<}PP$LInhO;Y=sS6^Qn4-eCbJn-lToUVyY&OJW_jJbHxhh{Ue zCOdwbFu#$0e@(`Ti2RJ&M753tl%)@7PQsd(5&1w5iYDZ{JUb(mU?e8~JvGH*JN!7) zehL8W)ieWJX8@cYJkP*~9SkJ0*U%H79w-^}6`H*-77L>?-3fs0kxV*gv#nZbU1J~a zo~ajKihFQMccsqUfC^za1W|zC9*$U5wn*Cv$EokO-<^tb>rp;5T_}8d&7apk#4=9m z|3&x^e|O$y^|m^Ct-5=PmR7p=+mAb_3bO6ahAUm;Pxa}d>#R42-dKe0*yWh!vHYej zjn%$wu27Dv^(UXss?!karrL9Lr)vSLmm`yZ1n-I0d;cu!v?YZrA1{OMMWQ|s;HE%> zu$`s_jerauR zDDXsjNc+D4_JM};M{R;qO#}#ukPwC#lq5(>b{lkGGtBs#H%h;J*5PaQecIXEf<9=5 z8`|(au_ALms>uh%ZcT#FF3zq!d$6a8hoAw=fBKkL@Ez>HvX6QvKRS|-w>@as zuRfjjJ=~3~a3iIRt9>Ad)l6GkaM=wybHj)7tkjox5ll0%x$0IxI!{6|C|8db1+-E9 ze@cDKB^~9Mc>)yepVSj~ga^7^tNeT+K8Co_zad=rr^h`pk%bXnSb)~Ky}eDq#?FBOlxMjt3UvXF6{&f7x-_P2DJQ?8d^w zZ3oWRjz{iTy1F0(Hzg+u4ZoKWdDj_~PLj#NQ+U6us^hx)QtjDhc(hc5HVAcmnG;y@ z)GX%n%z@u0OXpM@99@Ca$^(G1F)%QK^+5nC*tZ+O7=bRm&pt>2!G{7&Ned%IsO=7b z9!0GIWQ@o!exiQ=7F>03+vZC#F*)*j{l(5d`N1GEXUxZQ68bX69nEoih)vyphZ*Pa zOD^PY_ke5Ru|1jn=KB{pY)B`aA-7E1EDp5#JY)MKY;UXQsdAXZ><`yNgYWHpp%%HZ}LSi1|q)jAraz&?ub%U7JysTj$kTQMtEZ(*#Wf(9LTU}14sg#?n%rGK9 zG4L9qmhy;x`Gpiexw<-`nG0%P4+|>~eJ)&X^{`zkW(443{Zmw2c}LZM(K!XCWcMET z|E1RWnHZqrwtpfXPnpxEh=1+n!_UtTnv76 zm*=F~*Rd*NDdbMIL~p>0J_Y#_yyGtpoIi@_eBcm7gwIDs6-j02M<$0LlI7S|A+3@u z!K(ZYdMnT-fKk$~00+s=>wGdHLB`q*1L4!Jipe5yxyMvP2A?nr;z|JB&Ej=C?w@}K zLbNRnrs(EUdGOI!r+>M^PRV%3%HowCFFn0h?Cgk&3oScj|o&$#f5a!|xG;+R`n=*is zZ1}nnB97bcFXZ`?O`9>}My+)jFn}u=d;AwhY67%m-&>0!)_{!q z#I14Nr!eJyAf0r*pJgRTlquYa9O5UgD!%?ic9%ddRCBrv;`~IF6RH2|~fyPWs2PS5wK?lHjRpolEbNeyr+}o;_=BO?mgwP-IS_ujCqa*=m4` z5OF_3N0HJW>l5=wAi1 zcR;H(ZGU=I=6((5Ydr~m#lOB-q_S*)OU#e}fspaa3>L&S06OHAuNRBJ>g0qne2kCJ z-O!|01Wnp~pFh)4gfDi=m0S7r>>5qrOc2%dKxP5yl>s8O3?vJ4EQ5Lim-e?_Xy~yXTb+K&0N@-h#P{pr9Jt zmF3Avr@lCHzIf3a5dS4b7Q6jVBpzB5B-&}8mY9g?AW{@#w}m>q7Iq#UYZ*ar&SzNh zj>!0_7il5WXcQ1Zxvh@Y^;5&EJp`2Ym^%wN`7c-2LTKCLvNj=**~P-OM>x~3qYze7 zUstByRG8lv_={x_B6DbIM>8Q6M9a#R{BgK(fM{nj) z3iB?1KN`MhVTn`>8A8nM?$ih>xdb3Tw_!^Jf8Y%AAbM7!{)k&S6|a0GCiY4?8@?-K z>%>fWVbr*FYE#=(iQoMA`&K49RlfaWvL9ICyY8-z0F7J=Sd1Xza&lm?Zv#zS5YBui z*w{7zUWD;8o&!lP0K<-pjg3se&3=^BO-w-%Y&@44hPhT1FjLy}sH5J8wQ@T7VW0~1 zGnMP0Z`u6`G=({0>URU`c6?2uL!jw-Qp)7%oDv{smq^08sD_<{f84Dn3MbMn#@<>0 z3*qi1P>_nXn_Hj0B9~~)Lm=?}Shd&T=4|QJzOf;^@*}LM)+TG)tJD3BQQCVF0=6*4 zuG-D6#cNxWhF%K-OkBIL@^X*+3#0vYQLPEyB`dIm{V!$Al>=mC|1^DfrMVb=q1>D4 zjW=yES*1MDRLeEonq$6gerX6Do1t`Txo&p#ZJPq_#?Emk6)*0*`x9p}x~+?%jofCI za_f(v+F+ETM9UN@Sf*+qWXWIqzb3Vjw!4Leej}Y!n{=)HHI)Tvitp+y`>U?o&Mwmt z-V>gzwXuCho2WW#bvy~x+kN0UBN^?lQs&=-yrn$qT1vLJ7F9T+L|&LN)WtBzKq*Of z0U(p(+`_$hJ9cq&pyfP^hJa@aG$#6m^GvC&>iK7S?B3jOfMXgPGRYWa0F;SVj-&0bic~bi?f*(`O z$$6|V!)a>a%G1*)w919o=>3Ocv|Wcwad-4>VS&rleWdy-rQ)E!u8ogE8_a0f z#YxkhTGsziD%SHlnsLw%at%a2&EdO=5fBOm}PJ@N-=yaoXB_%?E^TBBTRWP$^ds)b3DYgND zw}<~o%l{+mtHP@4qINeSpaLS&Eg~f?-67H`AtfNv-Q5C83o0cYk|H4;0v|2iE#2LH zhW|PL)me`hDx&VS)|_*Ucf4W1=dr7q#k$VeoAxNM1EE?aU3Gdso5B42O9J<%)m~7Q zS;^YgW?6@`NR(_gkdTugpH(IXRc!CvD}V~bCl@E%p1ZR`UyU0}Su>81#Bd@bBi-@o z?g!GyAlwdD6h5-XD+mk#c}P}(%uOn;xM29#g8T*;n4Zuv%&kkNAej*HnMQ23_7TiFj zu>Dl-Gcj@N`5C|EW-Il;FRe141zgTgzMOHg*%ePj8f~A^g?JuoXJr2>Fz#06o6PYz zCb$oV??>k)Q4A?(V{x*Z*FHR(bG97Znt(CVk{Eb{D>>$iH}P5v65WR zm6u4sjHqX=ERzy6X3eUaxt@;WJr*$*j4wxkf6_R26;XE@i-8&dteF>*lJ(w~F1_FQ zOiWA=(Md_3ppSvi3_*m|H8nqUt2rPQp-;FNA?^=+DguJhbP06GVFaw1@UD=ef+FUH(Oo`LNLgw16K252)8Jtoo7!5^_-Hhi`z_^2O+ZpQ+r?ss6+uAtR z($S(+lrr3&>0iY3APFr6#l)&M`O5ur@w?t}kEY~`PgSkCg;Jb00q9K!n~LVbw@+W? zv9iAS|M394d}Y?sYFkBCimiDA*hMUc504VcF6SHDGZ!mx*uc+X5XeHbvPSv+#x@2d}Kig!3A#|jn z6Ekzz^O?rX0wbZZlrV~AuL+vnfZ}#!Q7poOu4F+m9mYG6uim};+%>Sp?`lF!d()dt zc^RMEl;PP&si*rl<1nvB%NhIWLlk>BGV`BxgwF5OqdZYZh>{H3 zZmwIfq9XoIRh6IY9TXPGL2$NAdwaEegudg|>?UW*aMz@4e%P~D)VACD{d1022@mwM zQ|^+?&${k^3fZ^#L~z%sElJ>V)zkHx<8GOs!SVx5C(HG+wY|V`%#^&Kpfib%PeJwd zUaZ;pUVXL|*heIl>yws~uulWu5ize-A2}CK^v1B+HXtYLhIwM@q!nB`!gx5dY$cM zQqsK8b{hUDViHah8e~V#(VgW8UCmlS4_<*iZO(;RSf^C6Ip2Z)FItT?@7Mnyqx;1 z!#`X4m&FJ)iU7PoUND$AOn`eC=6)hWG5b2j6XLP@mz2*fZ& zy6Vcod0(+ zrJYQe>_KvQ;ygSxR>_TBj_S8`EvG~WnXccinikmoS&93PU)$}dFU4M-rZ&3ca%PwC z3uZ*y#vPg39`Uo(;yt`sQ`{TMMHdL3GNNh}_8gpjea|mlZip&z1`$ z=wgw=1s>$<+r6)cx-i%fYRp_EY8+!ASHN^aJ#KK24O6m&=@~Z%V{d=`K>0a2mS5QP z)=-rR`RZ32W|FZV>sw{>d{`|8X;lBq1t@*vzvNG!(De@i|ZA6If z(tOIq!?&uem+qXqB91fF^uG+rqkM)mcKPiM-bTcbKBCzl@gnP`>*wc>Vfhk;HbSzs z-4Lg=mnr-bi(fc*ZQ`25gKHWF$*yGnj{c9tpuxvd(R4 zFU5@bP(@LMir_w;oNQr01bcJa5)Ft(ArOBPDiSM%etM@TxiQmiX^D)Bp`#<@4Q732 ze*_(~8>CoGo~z#ROR9Qc`4o)#SM~~SSG_yE?f0zii5~BuklpXJ$t)`Bu_udR!FZw7 z!iL#y|F(pvIzx>UQ%dExy>@F1i)dFJ&kTR1hkVGzO3YT4?`)m-_u(>!9bx04UzV1& z((YeoV&6)%sD5Tah+?4fMt+xkfp`04qr>_zV4*WdZdbV8-l~04@_E~lA32t8g3*2eu^-r&sU|t%_`~4gL!>nM%rjHdKr1T+Ox@ zkd#e&U^vl91d+(m(Xd4Hzy4k1RG0%Q4s3Ez2B54~*3~Y1wd)5ZP%B7-L+!)2+0P>A5dah;=`xnl39N zq7M)L7?J$0%2awZ<5l*es^s#+i3ed6KHj{Z>rz_HxrBn-ie4~Jg2?*7<+He(grPL- zxwKYgrJ_wjRTeVrq^S-qOaN-Oeg{P%25`iS6FcA%aZm?*pk`Eg(G-q^Ul#A!Yl!cx*OJ)6 zxbh(s*+h*konGb-b&O;0^Ohy-xhSpcX}w3tp~`*xc0bqicN+9&^lV3pJdu7Qi6RWB zFzz8x5NL>TDG@D%0fG&F*8u4^vglm|Ho^+AQSbSwpE$bS+z?XB>B*-3Ie8rtbC7tK zS6oOZGkQsA2j^0AAYr-Gzp2tCu$({qNQ8f|k&h(0C=-P~lzPMZ3%Z14(87M#T>Wzg z=j+iE{Z9ZyRagrIo+3?jl;+0rbRm?VNY}6kNTfNL6BKS%>`3m1C7JW^h|Eqa7AHsj z>LYZi7%mM@AX{|!lP#+|vTN12S2DjtyVDM}B_e-112 zh_xmr63jbo_3Qr>LWB+Hao=g4qMUVGV<=>s`9*)?jMmJ02Pa`$a`?@cC4cK3D>QNa zo6~;n?a7U+L%x?IOjGOrbgeEX8Ko?y`XeUrrA5D@$n76;JiGs5NwAM-a~LKX~mQgFY}UE%v>+7 z|6}<*2rwOSLtyMz63&lfZe(~Jp6pK?a+#i%y;J|*uFL;0@qHN*j%HYA%@(HrV75Ev zJXMGL+#xx(vvh$xskgb))n~U_0vG-9IoT;j57qKb_Av{YU*h#u#I<72xp9Jmg7jy_ zl$81=C$%B)od!2MCx?K5ATd6k7gRrR@$(bl<4=r_cPyud4F_4c%nHp@x2xA#O7_!X>}x0XMk=Kroowa_%bU_epC&1NgnF5xjmO7<&fA0!ray19 z-wWSRGS9<9_z;sn*oYnCQ2s^49nH%5q_NUS) z@XJQk&?zcnJe>U9$@$&;6j5}qRQA`#_aT8Rby|!HM@?Pbn)RNbr??+=SwI%4n)f+_K0*Fv z42>8LrO%B>05<|J09dk5Fd{PW0&p;>rBs%L{${@3yGKYasTG=m*Cz~an;D;4)~k|H-`f%L?q9f{lRFhtgH-Tpuc<>@kNjCV8v=RBsqC9mO@nhQah21 z5TDrn*5-wq*ALF?i<*bjGwpOaa}=?Ux?X7!>W`rkIhBU@0);cBzQcymk@m%lvN-OkF@#zYw8J-fa3bKGh>v+E;c zsB=8wn;T)F-Sa0xcsBaH)IWQ37Zo`%XJmL-xH2$5-y&1{^`F(lXAsT`PN0m8Zh~)| zow-u`G_MNt^5*y5LiH^yEZ|LmNw#b@ya_CEu{3$g9RD&7C2>$A`Z*P1#Seo1-U*N=bV%Q;q~OY$>Se((R6pkHHWL5{n^HoQatkII_xX4ru2jp=fBYRDA?e z)tI`NwE^F3wGX9w|MV$;k&c9pw`7f)8hA%N8_~fqLraRF`cRmY!yTl2j2-I|qA+|)r$6&zFUsAgpIWPM7hErCmx*GuAL;*_E`?4;ZjDYEcp>$W z`VVjoyShRl2I2hb^XJdtLk=d-rlzKZgoL2=gM{ine9fa~kxdlI(C)**p)exu$kB~L z0&a>1_)#_*`bsf;dy$eZRPd3$kXhOZT^q9b>|(MM2jVyRZ5{cR>A@!=9Q9T8K;H84oS z;Rco|bj*N~viW1acpS|27f);kulv?B0~76WT-Y`8Q1TDGt`M3At7c zLtbWW7eRghjA=DBG(i6Wdnz3rou;Pdqero}#bN{1G#CqwVaLk}A!x2sU+?l?5&O3G ztzGLstO!a{Zr_$I3pg-e3y^K~5TM-fQEIJ#KOi8Z!#ABAR9ug=w#6sqSgkW1AYB_6pY0{l; zRCr>g=`-jBO}Tw$5l{}5L8vA9N36YkB(`4rRNBE1A7K7 zjGK@cGN$EB-+nJV?QcUM%4u%rZ|)4S(7(LSqGmYmvF~_Tv?KRjYjz^m$8l#k*&<}c zb-)M_bGtEIXKpHT`Zy=$5}1B}Kl|D~A`rj-Ngzp3yXE?Sqm&aL4fzeMrg|)K zZFj04_^C$i>p3@gy$p3`>Oa3JBY7p+3N=$(+sggRXc{eD-EWXN4>LPRtorgr9aIpI znW?Ux9nBM(N7}k;Y-|h>iT4aMaRli@9eByWht%8K8vr8EX93~6x2dV=zyDBwl$*=; z+xh!=(|>*NQ%ybF%g5QexrS2*H7E!p09+t83&aydMPsuP(;t^JqsqpmwoKYs-oFz> zr=MJx=-@n&Y&_**eR*(m!FX}^)gzBPCmtF{R#ID$xQ3nSHz5szdMM{E0Df3-wIApY z4-doO@!yCl`@X?z`SD*{!Kb5fCBE1;jjzW3=-z*XXM%SRfspMja1Fol)Cja*Fhipr zI_Fufnnm4eSbalrY^TRjdA-eCe4rFr(Ks=go?TPNbg1CL7gR~Xuk!5bMd45CvKRz& z{G3OOY{g-ewa4?l%FDa8FL}xOE7|_*<~X<`I?>dKJiq!efV=r z-=Crkq~BIKlygGTx0K8ecs2wY7ALd&%n)jIZMEh;l4`Kwbi6ACMgY&)4$bfA8sTc9 zU}BPgmxr4dzeCMyrrwT@e;6mEhk+VZOiT>)Oz!S{QSGnfCqKNPhKNiEkc^La1I9+H z6Bfd+^=)230VxSd1qg+KvkMYBAhEoskZNSHi{8{P2Z?C~ER4kV|FUv&bC0%l%-V`o z6H*jkeRg4X%<-0~86H-q$+LKeYJJ~-aQXYgzvRjcd37;f#&faW+EzthcAhm3@|olb z#qSxI?e*6ZyQ1jd`HCSY9uib)M^OIG$gg`jv~}UTQmSGS_jY44y5f{OVdf;+g!kFo zrLyv^&m4Y?q~ph1+XBYDRVJtCJshyB)4RN?8ZqPI@0%$jh3b{TQiP z{r0p`DT~ng>a&x|&d;U6wg!P)j4HAu73|NLTb_}LWnLzfj=hZ!KCF92xVELV#*oyv zyJ}o6tOHk5@^3L{&ABv}#h?E~>yv6XDT5yU-;djyj~ThpM*uOQ-sc*qpjzz9xqDx; z=w%tdFy`36j!>*y4eBfN#5Oj0IAcKVGCf@f-wHtWj~_q4erT^Lnk|0g^E z6n<{*^OBM;>+Ah7`jX18r60Z*YmYouPuHc%V2~YZMxG=Xw4<`izu3&g$og~m+0@HN zFmeIu8ijUJ>B{0^4E1;2B;3zLF9y`;0u|?d<}H}kDsB$e_rS1 zexWZUbR$1R?)lV2Zk6?d8&o?Lpvq{sPmmuaLubN8CV0uTl|-pvF>I1b+xaW>LZJ0!MvBV141F1i0^-QODMgi zK#N%=+u6SGlr8vj+V?s&wRUMOmP5X~rmysgK<(`IZQi!;xfUCO>inbTgDnB~<)&_3 zq`O3k%mVJ`ipe6`ajjBDN~r}}DiXv4A^$GzlFc?L zQ^Y-3^edWFrH@e_&0@<~tNqG;-Il0cPNDyr;?Y}N36aRE{NRzcge6wMa`TN}5Tu@iS z||hOF3QVOSsI5?p8Mqq*l3vE4G_h70dGow|4-oG_V)II zOsce`#6Qf`hhSu6gz^AeY~zj*4^JpfwwJKN(DA$188pqlXG=rtoCwj8pVnn!)7koU20x1)>)(W^eue zDL*;ri#kZX?VZNge%hGKH0Yv=MfV7CZ|1FCyWCcmhnBmbPX<7hcdO|y$l2Edu(dZ+T$g36WCNTtaPh+Fe#nLrv zltRh~KciXren^9wjTuh=v38Y*mz3gs60#+ag7R^~cEA~y&%fI@>$2f5(S4a%@=){u zEIXC79oPlTF5F^04G#-Nd^B&r2iN469(}+-l_Vxp^v=$bulB$NInudWK~j9v&VqzY>c7EYVb8f~5Y-FMoiO3uWHuxwxEw-V?Umou#EL>BPJb z1Apf2pe)C`UAE(e;Podj!+D+7lx=KSyqr17Iy*bz2!73E7V7ct`=d@O(94`NT{i+%M{lQEhp&2XTem_$jC@?$^PRD*tH!Y$Q>4AQbGct=>Sg1$Ft2Z zw1xpGyFq5-Aw?8AdD{lLk)|f9rkq~ zy86xRiu`cQYUvj!{T}^P zA#~`R`rLc=OXC!A*`e`3cl7*YMtOX*K1wBU0+0|F2iC%j*HPl})n@0f&M1%D8*fOo zS_F~r&n8ZHWxQYDl2BTj$YY!GR?gYk8Je9JFJ6d)#gaBjY9AmN0Jp;hW*Z0u_&q^M zS6f?qd3FYDC-ww+v$ow}5Y7ZX8RM~*ijcjB#VjYA@2O71%3OU9LFIEbC92dbBE^}T zsEdqHKFd)?wwk5O8mr_wTSD3I+dhcNg5Nh-vDn|0KlxDlCG2ihGIhtFT-uq>C4Ixn zQd!9U)Ry13KRi5EH9Q(ELP&mbcIM;f|9MB8EXu4%3N8oq2s@%2I294<7qZ%|fReypyOt0MAhTl_&xM3BsVP6LQ=83v{+1aYIAH z`GHI+Af!MxvI<_dc}-T<63{WheF)kr=xE_K0qwUiH`g!ck^mJMDS(Pi7mS4=yY@Nv zOZzKxQBges876#M=vOYbRa}}(tA=kWn}|esmIALNQgVMH5LwZzmr4QmRMi;ZhE&wx zo}80xbR0gBvO^1;N|&e~CaAO|WQa53-Kn#C{C__!gV9#o)=pVcP>E{SE8VDSjSr2- z0`(c)q0xqqt`r}1#xszs~3nOcXg^gXbufMRkcn29tVF<)g???Tv z2!({|?>?eMMMpP%_YR6|DBge&0{~@WlK}z&xDFi70`?34fnWnPtDc^osRFLpy=`7d z)w*gidM2cjgn|8`~0*!&M!ZvoiMl)d05NaAw*rQ za?bR9GlI#gOHZmUK%JeR_XX)-JQ^wL{$rIFj3n0>Fs_bP+NPcdM0mNM= zzsYN@nW`rro}lq*#pBN}d9{;>JC{1gQK=-w#Tl$mvkq-~NFD9NrC9<_t_+!8|Ma8! z01i`OFZ#D`O+ZOW6r2E5OHxt^OVNgdYf%+X&r7H|>)rOnsXu|m*!krp+?kXf;N1hS z0Zvoc5;-|J;RMZ5N~Itq{Qi0p>HKvK0%1q?L!ii%zc29)&I@XsrS|r*JZj@9v0f|0 zy9YP-dSZO9(DM)cZ#xVnE?tfV^p!2Q19JJ!c+(JSx*}v+7Y|mA-FHU(r0*iEq--q} zQHbgGuiO)`<@$sWHKN0qEC(z{Pe0li*Z?@{E?>B&s@fAQ;I)>)+VWP`Hj zUiWK^ogDueQ+%n&nHCruV2xt+NbXU(kS`_>NL%f{W#mFEs98kRV;K%6rf`~0aJ~?= z6t$4s94!KK6xh-4Ad4v~_Ch)OFX{Uohj}6kBO@qoKEwS<>H&2Y&=r#)1wF0xw`T}@ z)oAvt%5&~fw&xP;OfKz_{Oa$`Ty*%0@DWD^&Y1)$3QNzN;3+Tt{xhNJj>yG&E%;y6 zN!O#H(>FV&5cEE}_0e~>Gjg$uCVN zV1*_xg;db!RXLa5gLTHd`9dd2ztBndmV%~bah`{Mci@b<&UBj)LyB; zl-mEcLDrrb*`7ifcyfhA&%ogB<_0mh-fcInplp1{K^#EUuY;*71qA`Tx_E?ybhsaJ zadF|9+Pr)Bo(e+@2X?QUn;S4pf;9{bKF|FHNk{I_&4!rV@xf_};ly|{Id2+S2*Wmy zI)CcfS)5X#AP!hrH?4QlsDI*`bLrSJltzz$Ip0W~Q&NwJUyTKK-pU2s zybNLk0rKi*Yw~G^4*oUKvyiw&ui@(4oHf$>Z|P5@PDN}YtMh(ju{_OkwCN=#5G;I& zcHK<+4J@%Da@L{8H<`7*DAvM3wRd(N85|54^&7sA5dcO|(9rS-2_^Tfh6D$n?9AvW zC}1I!RaESOZU2vFpO<%jb_RzWl#0_^;O`IOTUgrUw2Ck6zkTjbrQlVrOpMQIIgy+d zsdLK>3!+u|mXN5$G*;?F-moydNP1(FI5!m~&N~{bC|FbNX(HnJ1e=vdC^Op1aKw3Q zWAOpy4yDPY!Q*zyA39P)oW1j}k2ciX^C@o6O$W+Mi2~=zanelQp(c?np?hoK?J7vm z+?B;l^l~o!{MkXh+Wyr7rn)7&qc$xg6y#>mz&7;inc}Xtr;fGoQ&jOcZ>-t zxpyZhGKBo_%zf^SMqK8lL31G2%;;aDH?LoxHm zW%?H?co*SZI4PvuY4nWv7;jSfP>SHT)EVEG#371ZFE@)>mOce zIB%0FPAg2mTFG*HzKMpYN^lu+C|uG+=qzaPp(E{?z~fX<0_j}_ zy^+x(FdLgIkj@$Gc)vjaUd{VMQoS2c* zc1Pni_)Tmo?(WH&byo+|x7$48v@OJ#r?6OeWJ6Pg1QyolnVuQZGhhihw)GD@tY8PA zwNX%bRG2VW&%m%yRV8oe;rHRtVQu^|6U({d+S&ojCy$IYLZ4kGZ}Xf_zN>O+d>qed z9`oY|ix`fNk57;L)*&bap-3kRzJrP?+K%6$6w+f7Mar}D&+5k57|amZczDneuu**D zwQmO3H0Y|KB?1UpVexH{_~QU7CW8C3r)U`<$k4dH9HMczZM_GdpzN1~yTidyOUOe6 z*=odrQf&4C(P9qypIFy(Rya1?zO0RRp998(A@&ibX z(=#)$qOo-DWbLP=r?dOsT!A(kRw-=ojL37@(9I=s%D^k%2S_>Jxn|?blGouGdlJ(> zkER+ajY^hqWzOo{dqy!d+oHZNIeg8@X?J}ZnPq;lo-Sc}dHm!Bbx!`q8Tx}iLPCZ^ z0ix@JS!@LgLQGtR6{1+vIbDWlGRjE8Ng)z>9+qiUAe=6Es{d$-ju}ifDVy~?*4ucMS1dBdKwYB zq|=~dl!Nk_o#5c)(fY5$`|qlCcPM?YR8&=QK^X-WXLypv924*kf*94**w}gDzq<+Y zCvtOGyi*ftxoexQI+fUx16g5&hl>k|>33$o320s&JPln$!KO5^J&MzBio)Y}8Ml++J)JuQ<+2N=ky`Vq7P91eg?T z68xncyrOddc&dMQNo08(>iuULh4f5JURP%&adCu@z+U18jtXG$3x2pazrG%Xy`V;g zqV-%jaV_x8Z@5dN$G zs+_Vlx0ru~Zs=8#dK$o#P4_A0IX+lR|4Z!!i2^u5fKXK?2Bs9Sq1n5-0#LfoYJXQX z56>ga+xG!lJB+~;;;8&n?AmvTv_;BwSh1#v(!_k-?)} z2_Vqf-2bl~dOBslnrNqVSA*T%Fd~y;+f+^g^Sn(}%vM>+Z13J9;)nbh@@i7i( zckkUB92|s6Gx(Ybz8O;bUIwN-t9_}@iNeAAMZ0Cva385WerYR*6e?%Ld`oO0OPW zUnQipt3RT05>t2fsavs2uRJ|XjvdX+|NWgDZ)Zm2JKJOb;N3d+Czi}?%VWV+M27xn z){|8q%}>xspGTsF`%t*B=9B5pu8Eo1xczqbX|hsh!7p+wEKiD_$9Qs19u%R~CC(0g zCnmwc!L%+$8Yvr(+Y`badJ*4^jmx&z8GsZBxrhc~Z6}P|Rv(;@K;n zy!3K64W)VYLr-95rDCX`&7uWOMjc-i=ZWd+dSA-%#IH>OjSkU&VCUpd;;m;-e#q~z z5li+^r0mDPPwV6ly#R11nw&(C4pn8%atU*EQUr!#^l$isvPZ7 z`ZA{Qcatqp$4n!23BPY}S?^zcoEaIUK2fA7+3p!59C76TA=ogX`2e99hmX{blJm<1 z3DFT_>39)7q?Ek zt)9gam)k$Eef2x6I{ERrXWyBQIl^xtcbvKv^%v9SN%C6*uJPDQ*OS;R<|nJV?UzOT zUOPuA?&OTNyU83DngnfHU?d8&Cm7=vXcQq3&^$vtPF#Jx_mforbaQQhdMieEiJhB& z_Gy2i>5hrn0Yp|o(>1PSzh|QC+0f8KRALI;jI2Bv>1=-?PYqLJF2hB<|Ju1|U1W4TW`96VlO z;k3Tv(69I40!XyjT($;)ri?WRf{Trbp{AzRuC&2INXyHE+42T>ivqjoNu3mc zSO|m=cViiPi-DIjWoX9P`T1QWq|3s>3N!PWc%j<%l^&ub<{yQE1KDA@h2}NPYB}H0 zPc|e!v@&sVHSXD=C0*Z+1*j!b5}um11Ut^o3Pgl+7v!g$?#ndV2jYB01g!nC66z*sG2W@WjgU z%W9Ih(5~AzI>6x)THN=GX8>N9_9TuR9jLvO0^?jEZN@Jo#Kbf8o^jU$r>thY&-jLJuE#nj42aXrRP?gsyWlWBHP6%C!=a##kA87HK3i)UxwA zfIz~;t>Vm+ifn9C$TL1=!PWjCdygY+v-aJG^~(m@{CN(~1|g~imj8y!w|2Ad54IR} zOC#RP@T7J|NcHXH$7D?;*P^7azCL*#kNe%Y_kI{Cn5)Z_N}ZBoT5^6zI0*Nf%g zM09hqJp~qdueG!WIIlNGo+&9QfggHY#2*D|CW4kBLrq)rr04 zSO_WiI}tB>#%GyGqV~E4&X#>5H?QO4c#b<`M+4E)Q&W2bM1A;qIh&$P!)J(4@B_tG z(eGv<7Z1Hz4gPjma&q2~f24jS5fUQY>n*r*Q03)w)9OmtqT0-TIxbjyXoVS6oU&^O z1rXHS-(gnjegG!#(AYF5cF75Ha12gO=}><%GdGu%lG@~66lI5s57MN;>bJd}?&(wb zIdE5GvsJ+tJ|K;Z{x4E#S!u~BOe0{11|SY8X%h78fH_xMjD+rEJ!udjd{MjFrhp>F zTg;R8YbLvcO_{FuZFNZgv2yr48PrEgdW_}@k_@sYrveEUl zJc1{6wlms|s7+4>_2SW`)>R{ulvLn(x>V?2_$LythP6(&CZ0nhA}Hu}b9Jtzr3I2% z7_!6oVY0!yw)d14FNBjbOP7U-ArAl^29_TT3=hA44ejds@5>il3Z<^aPE_OsX&Sr2_hM1>ZQx^LecQP8B_1pTP!gO^`OG8~ag zs&IWiU>^SXeur8Dq8A zJDB<9%)TDO&vRUS)~F%%<7;%xQ`fIs5p$%xH2tj|cM>lIc#Ha2BwTh-@RCqWi2Zx1CtchOM?c+_}#mH&WH^9z$Q_ZBimMS z6;6dAPAm?jX3;fS?Gnj-&5tiswX`7Ps(a|W(j!#x-HPjWc6FuXa{vQt!tbAc7#b%; z@#AdQbMBn+jvI2n9XB)6>F>d+K}z52a%r4&<)I5Whu^Py)(s zzFyM@GkU!2pzET-P__}M3X@%H`S~AXLEHn`cx>-UJL^lWz>$HdgD!17cf}2CO0(mA z3!HL|>q4+B1m`*3Y6oMG%0SI-+WQS2;Qr~UKDbUl`6wHn(bItv5G{M|?!LS`tDcnu z{3Q5!z`|P@2Vkq8bn(5MnTE^j~0jDifN~kXc(~Vr4a6 zUG~2Hna7EIqxa=tR@NYoEw<|hCp)9;NdKN@rM3Cng-)9pcp>P6^Bk(lgoM6zz5_nf z=0-j-@%n2m^GfqfOQX!JbR>}@sEnz8`tM9Xe8LrwdbdKj{Oe;$g*~?vuezR?Xkv4Rp!q8&^MW@Df7p59N za&k^K->8U+{)QrFiD}Y#JO9%)QmWT-Jum{A+hu9UO0D4N+SkBHq0{ zzdd}{@yxLRads5o@YTNv=>wzNCpz-H(^)JPjnA*M&LYeWvhTk=OkI}oau(rbh*4*d z!AHbb4!8N|U*pheyq=C2m$H5Cw;g_xk7-TF`sn9sZ(zsRK1YO)@Tl{N_0j(R`dINC z>^tB(#rj1S;AGeBN$0=6{U1vNUrkTF7;=hrn)$4z8Q0*WcXnjHK2-^@4rx|moII`(^gM?hDiJ=$K(EUlM+Z;=QV>F}`=IxDr5V>9LA$`lpF!3?aIX|+n z-;iJHEhtkAS1YXeex`)I?Rz>Ozq!*)P}mXghqac7N<4g<18m3OWkrD<#)$A=6W< zrl9;;iAlz>5V8L|fd6M}2WS9nfxuprl;d^Y81739QDYjq9eJgyvAVSMLUOsi?Q6Yv zcXuCQT%25xcw&Y!s+c`ltGyo;r=*HQwRmM3Z{#xuhT#tm@Fqaq@XMEp1O)sV8rm8f z@XNWXQE}zhXJ1$%V`4tm3cQlcW_#?fuiS65HI5YWpunM;(q&E1@+*9ATzeGZmoMb& z!{)E0KN!z7G%hf^`D~3BRXfUje4n1bK}cb z5>C*!;iNyYm?&UzX1r?078a`7m}N}Ybz56cf5fU-=%io$pYh!!q&Q>WXBYwhZ0Gg$ zePJ`_N+?%(V!vR9nKqq7l@N9sUZLax8TgCRcS*GR5jkf zdEQy@s=9NZ;OL*R(&l`2NJeh`zv~({6thG{Y3Xs$=fEGK!R>^4=^uReFUHt$l?BqT z<>WT$62-F*za>}~Tk#26*-hZ-(-~zahNJt3=m!wAthkvy(bq`~H{*@i$j7@h=>BV{ zWmKEgF}Q=K-#0RV>Psiotakj1ZEq*>)+@NSeR$cZ=<{Un1jk8R{PVDSv{rdyv-YlP z&kd(PA>Y`#$m49tiTUQQ7E**uV!ip-Wruc>`CLSzCe|yhTf!mLK7X0B9OZ!bF=2W9 zn$3R*#LuD&r?;sQ^iO%cgDW)iq{_e%2v*kH^}%e|?>zPwTA@vcoFw?D+?Jz-l)L-4 z-7smEF69ss65!wvq0Ipz-W$cp+!_*P$O6F#^iQK#h`|#>#K7FbsAQak1a^xJ6O)?J zQ7|5xR!kmNP}sD@=e>O1M;MS1tf*)a91OHfFh<>O3*VpqDORbFq_i{LHWrsz0>YvcZWIAq2H)B|@I)FN1=M zCkD7~8v_>7d~|KPJ0Hwd+GQ}#uLbxgGgaySu-7SOsHM!341c~jS?s}*W1hGmGAB@z zc{i?`>lBND)+`bJ8uzP`Y>98$_SL$NJa;9(XCkB9Rg;f3sE()Rx_MZf+qsfHVTrRG zo}4h9P5EFoaI5e1Vm7Zqmu1XiQsQQA^%XA1_=j#TQqQu3mN%)q)){}DY~gEdi;25G z`v8|#S5s5QGv-LZ#>R$%QREB_OaoxD5l+TeIv}jEke{E`-w!l7a}GfJ7$H1QgkY9=RN%her)rijcnE#E{M`m!ao z&&*iL%KoJz9b6Jid~-IY9|v&!tf|N9{(&9puJy#_R(~1e9}gl+Cc-bpHH{lf-La^W zX&Cw412bc`b3nLY%jl?lrK>9lWCB2YyJHUQI*P|!Fh%X<3yQlZj<6}{w8U0Uh@ zky0=NNj$;Ipx*$Z1^CQ@Z$hZnLs00!Lf6vPzB!9!U}c3g!y!OrjX8)FhQM;JDc}yQ z7XS2IQaZ>LgEWMQ4<7*QgRcPI3UFm^+(fl)Q)}x}c6R&zG%+aU%xTa*?YUJypv(yl zT5fOGG&bo1*b))mDvqF9a!90kh-VC>^Z3LKAOTcWC%EkX7%6>v@SGYe>rEpCryZ4B zk{dH5jY+a5dBIiL>ITyFs6B zZj?}vF%mFMOKL7IUA0P(#SGi-OAn#Ls9Q3k(B$1(N3E8tObq7$+eac&!#s5n?_%9I zJ6C(>JVQ1ycpuZ_t8>m_CMqZ|l-AQ&?^tKp5)3z`a~Vv}^>lRsY`=Kr(WZY9-}w%# zd4NBVDNoyCUk5c9L@d(M(kfhz3VNQv?raZksi(a`FwBn70e^0vFMCwhjjDf4~FA zcd|QzCJb!v1$~8An*zIzoD!5jApAHIFamH?85D*vxpjt`n}0f*K37sIvzZwtQSfSR ze*gYSWF!n(R$JRP;E=G{dcFBr;&a2}iEcva2CwsjDtm_#qO@F+IDxZahF4K9Pt(0f zadEkgfL-t|wBFKn_L= zoZr}hfx@^v_0ubdJ-51q=caFJoMhPb+<~nJZ*s6OoM_(K+LLf9Lfq@A#2gW-3J&2Z zEj|6=Y<*Warf3XNAQD^n=T5WGxAY9=@kx#Xt~MjZsX=jswGZnSgg@%i+#})bFIA$f zRmt37FE7chyBe)?-(}IuSaLvZ?}2l%))j2L)t{(Xj(t~R^}PH_jS=3oCg|x>dAym> z)wOpXB)X1#-Z?GX$R+r$N}2ZEe4+YIfkt(4zSQlH+;6$-hC|N_IAjuEAXyaKHfEk; zyFPL?JF%sqr#AzOO^DS-_!*9aR{)g4w`CrGI1;vC>IPH-e0+RPg+*Rr@EHJ3xjE-? z$2D*a0F4IO9|8e$WLTVFip{Ov`j1cpR4H84^o$ILooPN>TiY`-E=Ay&(JFqUCkRWB zUx5t(Tr6kOnil?9eIzFf88*MCq|%fAA8@y)+7ZTY>U?~DG$QgvRP^~aR#r<3gOgKJ z8Jet$&wDj5{jaL3x)<@rft1^;7q-eMQrp{5jihN(xQ>WV1h9e@LT1l1uVF;-2OAu^&DU?4NJ1 z#7xNzJ{!VE4lZb$nRF~Dj$jS_J>sJ;1-{2{$Dw!!_=Y}okh3Twg99uRg6*5mm zi`uRHNq|<84k8{Z42VWyF8~78)c823dlCq+z@S2}&P|0j7KRJ&gM&dMf33-P4kG{v z@5uT7{Rze(RDlq%2fjP-3W+Z{oCEpwWOuIEj^aKR);2g~OOWOIXWf^Kac5`m!zS;l zbCi1hCNhIQz%WZUG9%Zd`zyhlH^AZ|<`>|Z({&8ShH)Gru^>qeg!VSpaZ?yhe$zrR10 z%bDej@ZNjwJ!kJ{KOs8AT?I84?D?NW(jp@VfFK1XAQRXFl+c^O>fD3~c-Ta)twAYr z(@O|?NZ=s1zUiZo9xRVcOmqu>im99x@8K>|wKrufE+ME>!^zAUn?-|%kd8E_p|$68 zD&5^J**z?b`*(MVme!V8N2?X14CI|B!}+z6;lX(F$v@4>E+Ut}c1%WYZ zt$9R6xPr|c0nwX#>n*4nnTM)QC1xzvCSCPFd1>QI*=6AwSMvuT3~M`^X^Occiz_1` zaefr&wU`!J`NT_1;)-7%0YozBWx>20wtd-5C2@B#r1v^Z)F`)+eqW$G4grs26}lKH z3Z+~XF#B0@2>ym1F>io36*?ujxW53A2{LZ7)OyN%yHJ&tRE5)&CJ{pW?hFoSy1G3G^P3(G3gb9QW zz#45uMINLI#_YJ#_|lZld_flOSOWPi!u~Ou2@A_(G_w*rs;KDpMMGBF7%-WV%4C-& zM|vYi39DyhqHYN2~VkNgExb!s<{~o3~u$mE-;7n*72x|NW~Kj7T3*8 z*LyrMm!Zh#wHmHd#h=lopt&uKjrXli>qu+HOW<>cjy7l-;j94JJ0$07si-tB?9v3^ zM*6l*hT{7jjzaM|$z7Gwu??7T#DD$D$IT5vMSU$TnPWw3OaKPj zvDK*sfdKHiEGtU_#Ew){Sv<|^C*ou%hH#_=vrGcG2G8ffNO7v0t)t^U$R@O;@q;N| zG&U_bZ}$WRE15s~q!5uC5U}rim(k-`qJc9PE!T%oSuNIkT@Cs_lkMr<{XIB4pzlP& z#uEo6^XqSc$_j&kY2k?jOdW|N%d7qH8gG_H~=B&dv*;bT8EnxTy%87f8K1&H2A1HZ=_!h6zHEzDpvmPu+C{&GxCt>+q;M#D^JP# zQDVH~e%zBdWT5o-qTru&f68(S%}dIRMHm*yIVZTL9DVKy^>8jJc$zZX?+_I6Oc_H7FZvX=wog3z%>1)N^S`gc3c%!)rDyk&%^6 zPD%n(b@gN3M+wG4r_?~~I`O@$U0yEY=_RY*aF4xPN!3Za)Yw38y4WLv}9M<`|Mlf2~rVV%`b=Fn8d{_ zOoXqn%(|32!zfBsRTW4b?CdE*K2V}z+U$J*Qy7TMilA6sS#g0Fuq-dQ!ykYrn@(d1 zj}@@?{9GDXaUVWpHEzQO5qMG2Q(Ro-I8PaP!=T=UCM+3BI>f}jq2U&Twi*GcLS3pU zD=fzGaplG^n($owbC53&+})#hJUH!lt6Y|rLPaxy^S`p@_$}whslNM^G~|mmZD%=$ zK!8R^qP-!t}+USScXSQ(%CNhAM!X69`rLypl zW77MWcE#IojIt6VL`6mG4DvQwPW58s5kG$(h2S%PuII`QNJ}$-;}F1Yn4W^; zEG^yXctuTToVtk#+0Cd%R(055O(jk|MCITxZHx@+3LqPaSc>QMx}_d;ybI2PC%*@S zXT@Uc)CltuL`&88*Bh0Zq!OE1lPIJ)vc^v^7w~zR*49;o`uerBoLoWNVP7a|t_n=c&WDCnU~^ntG-irJ(-tvW297$E zi(sh-6eXC-z==EaIw&ROX*gm6kiY|4Wj$iPquJvb%14ia-5wXlG750nls;ugc~u61 z3Q&{DWAo4+hab$4G-$u-Afz$+(LD=9YkA6UQpa~CI-bkj3A*+*19SuCFYgdNLm7~% z8HPj9XtVX|z2-Olhc=tnB`zZds>a)Qe)o1wR-wlAguMSA`CVf)2j%DJrwV76qV+th zmGQb@-JC$(H}``L-#?>#Hf8U)c8r)x&G*KL#-6+67ZkKJTAp<2(OFJbmH?!5+vk&@ z(KaI(dH{0D9d=_Pj6h_sdF}v42r9N*l|1ms&}r}{u@t$B58Y+4zEJRY2x%bYcYSts z6+t~dWRjGfy_(DyE%E`o(QY!&e!)3kUES(0IypKL(wAx#2LlU(%gb}bQVaNEEr+-` zjSbIa`nWxQ#wxVC9pJN#HKG5F_8E(>0U>eIgo^Ep;ue0aCs_Zaj-~_ZTFSrm#;bXH z)~2UFmmdUJV7k&)U-kS1Bq5{%?hs1_B7=2MNhHxenuH1VjjVU@U5)c5lg_XAJ_=~4 znJS41@pv6eBzCnA{pYy#@*P*4>D7tGCPd%dLPAoC%kwo|J;eIUTwA3mY9-}sZ928_ z^7xLLQvM#p9fbYy%#^;pSxdz)EA&om?mu>)qoXnNxXdL62|3+4?cxPD7_;trwUz@) zflo|ake(hD9ZeAXj^kjn(l$yDQ{G3RB?&q zf0yiSy(r9xmeeEBynf@QqK4Oq-3s~43G0c+j;mbt{jPj>YUn)P3$Fh6@tE{#N7E&- z{Q6*L10{UEDYhO2RV^>KvUCC4Ouazk){N<+8QX?S=aU@+-)C@=LrHWTqwc_PzPB?+ z|H3rK!I39cx7(hGSii<$X))mi*=Lx0=E|y83Rzz_hu}Uc_YH78qB@fFAa&xjzoMmd zQ{Q>3+(y-4=FO8wOx*M^K%+S^P|ls_FtN|oH@(CthL`DjLR&6B_?Qp^BFD#hA^8YE zG6seMIv3_77K29E4x}SLhlG^9=i7ahB9VT>gWH||^zs=BDk?C1PB%IYne+vPoUILH z9w17&g-2c1Imx)Wi@&{rURRa#^?f8HDc#?aY>R|OJ>gY&UO|SmIMinBUrYLo$Wmvo z3-)Sz-0N2Rvj&S5%;?Kl{R~jxb0}JmPL-TDOW^8u>*O~IpUzAhYN^)tjsjTa>E*?W zj)sZ~$(4Glf;Qj-0V-pNf`_gJMsas%j2`JbIFth2-P^k!V(B0a6#{JndY7A z^1tC@wF#T@ny;?MW-*BVQG1V-&D9r!&#A>;S+nZGOa?jM(eB`@hCXu#+SIH4z zAYAXLVedRa5~p~*3tN2o-K1HIRU9j$3ZP01gq{W}!wKeyaa#YoRJM$AL=e9hOfBmjJW zAD?SF4RI(`K|R5T-UK+%9cl&<^YL;E3h4p%I?G|Yz*goo)qFLmHJ+o815^Y^JxUt% zFxEeQdjE1}6dk;sTYi3ZX_O*RX5Kg3&>Uy*W?CExiAL}ri`tSOMZm%ScAU{fr67i~i}JKZk-ITjF3Fwm@Trc=kHUHzN^WHR zHO4Gelk?9U@U0>6n2CuAe*AeFhTW$*>dT_qrUJh3e>VDIXs9uB-r4eBf4c3PrYXk9 z#N1U5y`+Qg4zNtx+5PK0Wy!+}9@#-;>A$2eS{=vO>ce`jQ?_L?_ka@BX8>F2%^j9x z9qOo|kDJjgGGIr36(7{?>@qQxW*QKz+*tmdy$Qjgdz`7}|SA$4|;q1&M#zC;|W$$0TG! zzP%?aB`;l)ucw>YuVFAs6Iq_4T?zNGH7rcOTJ=^g8Z<4WAP5bX^3|CwdG=ODM*)#S z(5Muw?|A&av+|p?0RJhBC zZqa&qw}o(@Z?N*R;hDQFYa!jJnKdjYF#;fC;psgxnBPJdf{pyTYgpvBLL5lSMq$&9 zrNow*?@{9II|KDrWirT0U3@!~#(wX_RTZ(}r=*;@COOeQz;^-LrobP3|J^IjVH zo+3Ahc4JbXCAB3bpE|EiWZJ~>67k>={Bf|>c{Q1Lp1)B!x?ViA4a~28bxE}0PmhE) zS_mt@Bqe!5*-NMT1dEvaJvQCg#gA0W=v3%=j#37=sfeP-_xK$rLpKIR33-1IW8mk$2scqRAq$= zJV$Sc4~eP@){gg6K9OvnGN24ubt<&SUh4E?EMDh{~(lNsa6K0a0!q9%#t7!xpYiS4dCl z^L{*tj6A9^w|6^xr&S24v=VVPL^paZ@|ypIo;)>pE~5oGIMZTCiNs)6Jz)PkwU2 z>AF}IVQSTdu14tkbZ7F!+{nSe;V!M4y?cm-YObJ>_D}0S_BvEi!#S_hhqzK4+OBcuRaJkmdO(3E29pyM-@YD=yL8`n77&%Z zy!9R@*oYsAB)oFLVa^+4gMh)om;hN=2g)0$L-q5`7{GG?%>Wtcy`gSJBa7Eg+R*o* z+_>y}V)yzOi6v%f3Em)&H2XxUqM#23&y+&rGNc!@_xZRI z&v7_LFD|SVj6S~_pD1bfMe(zy)~{nloL**N-W5(K!mOvkcO~^MDX!=l;ncw9uV4CB zrdi4w_x5`A>`w-EM<0)T4M_){Gxy#FDOR$=u`K0=<&3pGp2%>kemzgaD_S|KU4Z%_ z5y^l+O+^KH|FbGhxt5n(NA!=&bInkHY8+6%%WEUIV`X(&^7v^%_e)|H}9Ph*Fx6E zPtOR-iCkL=?WP(KLr%V6*c_c3BJN-`H+S}CPqthWVNCc zz*Hea-EBUU^AOl1O_MM%gYUA#p(?!Cf*=Ly2OlqyXd5JdU77XD6cz}2-U?d)xc_i( zFE~8>cz^$VvvNi-%I*ca7|wr33FW-$*3r9zL8yVkYgm{h6C8I={}?fccbjt>z1rug z_SH`}`Y5N)nY)`I9ZF5+SBj^J|DE|H;5;D1&zQE9y_|}UkB*Jr!LiNsbJKzN*^$H% zW1+Tl#rC+yUyX^~f{g;by0a)rD9YpF;zn|nv-5cP)&TOr7NL;l<%yABNGVC~ms~)x zt1m(#^E1b2BJ(4A6|>7p8-DiVl<@gsfpxc7{LyfA-a+8GLeorhYlGJld=kPdeg>vE zQ55?P^{)lp$&50&bWqj9;sfIkreH7El!V3ff6dM`2xTf_dwO5KP9HDU58oHuKQ4y? z;YNE5Ee#BD&yKg5alG8q{Y*4bKpp;a?Y4|C9A3JXE>KcmMrz9reRf}(it!P;@Q^4Y zEc@F1cW(VcgtS@1n!kLjFU=`{-0#8gCv~IZvxXy|qzmrcXF-NJw^je_AFL=SrxsN; zKOJQ!%_eI^xFqV)JW@ab!gxKqyi zjRy3t6gW9zp7AamWf8s@xlifyCF9>Xr}f*THNA|rC+CmWP-JWw(kd&DfvEvj3K)-; zvyCjy&T8GlE3FNNES1Pt?RUOG=&Qcl4Q&N%VU`?D|JN5`-hz!H^1Z>?tkns!&)bly zpg~*&Cvj(!8=Y3g#gRitpeN<&~ z<)@;%A8;Y-I)7hOS!6^|W4(St_m`ac&%XtmS3g5+8NCyaq77+sa5A@GHcO0vja~g$ zr2U?ml{=OOestIB-$Oz^pTjUwvyUlalw#BS`UCB?+)sYX6f=OPpD1)0##Ma{|5lWi zR!Gf9n2ZOhVzWX?h+9E1epq{#Oa)dCx^f5NN(hV(_T7fkndYIn6ErXsY~uqKosECd z@TYVRdIx=m%H3BBGp)7@lLrlZ4yXnxJ==@V`>hYGTRDihiu$=Xi%WP)R%VhKp1NGR zo$U`bs`wi@#8ibxl1?d9H=HaR`h8*2SEq{M`N~_PUFD&A?7(L4Ynp%q7*RS+-g#xw zbw}8*-81#}b)l%LMP1DXzQ<&G3o+^n=s&M!S?Kp7_pn8lco0FL?hadE=xhbWdVwZx zUbjL-YW%;EpEg$$mE7SgYwHtk2u!_QQ+W-*kwL8)5*&O}GDpVo7Cw73dAeOoh$EPL0T{vhcm?;+2a+2+TJ-oX^n&Mp^P z8k)Z8fFkH|#Oa?TA9HGkVwYME^j$O^M0ff)@Y7(CHJ7}rT4I7=wM-?j9`S1Rj$Qon zCHZh|3DNS9VztV%Dm<06c(kkzj7ng>_+jCf(DeoGy_>o$gXxM%xX7Pe z^tRXY1Whm7!>Q()yKA>|IQ93S#fF3Iw(#Ag{W$glRngDbGW=fugpV5P%DIPYzOGAt z=1&R57Lh7cj9XBJz;H_GNC?;Sw^Y6&2OIP8^4CjCyUp{0)UVhtugK`ZRI1gUpPG6F zM#|Uj)UJMb}k2U1#ATFu(a2%62K68tXw9Bq3n2rvvEe!x{q8yw|x z5FWEpg)EI7pLOr-)!*OS_(e>Vu-BQ(4c6@L=SMbTV#uD?(JqX-b-b?qkW%9e+kfv=8!S z$wp7<-KS_&9EmELxbgE;FLHZv_HZ4dc`RRb+sUO>D~jjh?Bm)}O=f5W8xS^=ktvwd zuyt+5befiCzff3j7he_R!ojfu0~26=?{q7_Wx2{p_aogBTt{ghwU<8i{Hg!s64CIw~{{8Hi&0|MzUL^1vg+>r`w z1WhHxVRjGoGpPGs;1O#5)6iJe9%j$coXGi^pPL_AFR#hWr`*HO&o3e>3WGk-p-XcI z)o-;$JO^3x;P5b{Qu~`nD@;2WO#WK&_GV~mo1D6@Ti-Q8yPB~BkS!S6i29?SuB7^u zhl62WsDvX(mw<)*vg?1VQv_wm%1pe^#xQGeCJTBKYprY{lk7N?J*U0@tS7m8%sIoR zrj$e5yiLe3PDNT_+HG2u=m%te3*1->54k@W5X@sYv9im)U}&-@##%v@PJ^CM%G#KT zwKz+?yQi;bdUSfYd01=aEKb%M9IAko@&Y(hK%jgXb5i~7+cTIirYUMb0oG4r#n6O| zPD13pM6z5%bZBrwp<-kwZasZdRn zy#p`3Kk45D*UL&Vh%{Y|_KjB8EY>rt z59OgJcCVG(NHoI0f@51HUk&UFZbr;7g7Qz?>CV>!U5oEC^F(+?Ev6mHW#cNjY{`jT zNZ4~ady=_dCk|SG=z`z#q;Ggwl}|H?(@7eD1Bl&5CjGCD6q>0Rwc7u<9FX~`ggAty znfm1UdiX_M%l0zwGIr9ojBb6dlybDnm*_94U!qf^b>frs;#1Pv+SH6!@*JSM7EdIn zEL3@6nV4BYebpe1N&e&b$_Lfe<|jO@0o<{$#wHI#xSPq<&dYy_KKp=+EMfj+kj3vI z@T{(DgyeB3g03s69>C3T^~Lh>BH2sy`m;q`>3Fg;r-)l`FWt=oURg~n8Uz^|KiIu8 z;Oc~h3BtGtxQd{e%A8gNF@YN?DJd~xe{YWhCrFWI$ejHPIL^Fe{ey1wt;=o94StE6 zNHU`6*&Q8fVib-Ml{z67NH#ad8Leu%x+gJ2RJ7im@P+{>(i%47N!g-kA#P#2KSQ-l zorRydlH;(a;wHZKT}0j>B1=k|b}3p%JU=>GsXK?(e}IK3IMY1Vl-u8k=dlq_Gb?cu z8$)RSHuE+M(fN)NmMDS$bsXm9dD}U@T_9UJ3q6?p{w_JE@_qIU#pG)xOBb#FOy!?H zD2OKtDH|2;PMRB;z`Edn8lJWK{ymbuzP?~83`fK7`-J>&BZ(M&GM4(!i(E3H?C8&U zcQ_}##S$#u$b8Y*lW}H?nr6iGeZ-p&Lwlk)#vFjF9e7_zFgLOBh+36n z(V2^<@G9_i5{pQQ=RZ)n%YJTqpBf{bw(sJYzD3dFdMrO^2#kmuAD&WeV&fAqs!5dZ z2Z<*Ogs>D$@64G*S3dKTinN9-Zz-uZfO!FszK=l!COER#%>emCd(&L__-Z%VK(f}!RL6&K^CeZ612_)=S$$L3yd6QjUO<4 z@d?E}aEb5le+_e9ASrfZXl2|&npL(-eR6?JA&i;NwXr!=ITE1b5?A#c z^HC0(+O#&UHnUZ2O^J`6P|NQY&6sC6L3YF=daWOdJKNfRv!GXp#(bKPjT4+M{bUlq zHa#tXNlY_Uy9BdI@Lhm&n~2B3*wfSV-MfSH2gUv7FtFUYXXx#H1=|f6({Q@&8FMrJ zw~^*(XpNOu^Ig0>Sp3(IAt@_`8t@Ag!sn?Qwm-(-h|LDJ6-c4HUZRSSVnOfh?k<%2 zG#^d-IydjZ2yyaFYV|K?R&2#!Jz{=Wvr~uI?*%X*^;yHy8*iV3FhOt+1xgA#k-WWL zI6#1Pmq0j~?fYNtMqWBxIR!=N*2d(ZmjYL*wclKPq|#GQ?;kx!yv|=YehN+NWqjZ` zp`(TcMQ;LL0lmzJe+Sx6{L9Tb1h|VEyXS%EB8BZIg^U{#mv!>(o1;-Hi)BSn)Zp(B zd|8vJc7=o0K}ku;?2}>_N5_!QpJD9zoS5W4h(|>S`PI9!ZD*I0se^>o5G`gl96~Zo z%10FP)$Hwd6$a;`o7)uAA81tBI4pTgP~#A@ju~w6&%O?G_JQ_4DB^Hz_q$J;YIdIa$lZ$@pP^-b-Xjyf16vwJ<*6c zUo|u(vn)a4!ynq4Z;@a9U;yCgSE&Azs9~!8w_UQda`2;X$aU=U*%`lYUH$|{7<$v2 z?!$raZC#Vwb7`~;iy^rhN0a@`QHzUzxNp9;{0r- zyM1EJ$&9f{i@<*=cmMCCzERnqtlh0v>gTT-&9C%z0TiVT?&$3NsOYKe>B-;30_3Sr ziqXXB{luGp3t1RLsqv1m(Af)>v*lc?^&xlbsNnELCLWmAn) z+*dEPYZn|9v))XNLU!P(cE>8AVD3A9-tkEF-QripL=%O%A1feKZ>+j}O~7O@hWoC1 zaLc*>=g;WD-xE1)9t>wKGQCQQ#~})i$~dle8U|yY0D&G@NA87a2qgf@)9tzzcz%`e zcRKTn^u4rKY^od`n9uayRXQM8la~K^1Rb9xZKT(Tj5PHw7&l9E6#Bos6p@Mq>NkNu zlrQ=5wy!0(pK@BOOHqYj$KWz^{aqmw%ho@w6AekDSC|ZMf7G#IskQ#NS%ACB!91h~ z?IYW@?o(V^y|)_+9B-9pqmW}h$TNEI$+FR(T?MH&X&;Xf=Zc{0qOZGoa8}}z`(Zbj z4szPm@h2am_+iiEMR){o*a}$;R`oTDlza-Upk?Md`f!~$$5>~YtdJ&??W&)xNVDj` z(^)E?$PN#)$Q&YENXQjiG^c;G1OpLDpPKyOQzI~=J?rM~HvIr7>K`N6+UYml+OeWj z!r#Q2*sez;ALC=`e@2T%*=gavX7=8%>khBy&+DV{j=?gtwCq^ey@9GY!qY=SLKJC; zAtb0$FUPH>EHqPX>W|ecJ*;ZGHw#5yJYxr&w>EUT2L?*DCQerjml(i=H(#c@z91?T zxbQaHqCr4tde`xqlpZY8mwoPKTa`b_*iU)8^?C~a&e=D#v75hvFiqYvg{vI#dr(IS+iLkKPtlJT(^@VwK`hHWmoCC0}%FC@QcPsK1Th3$QbR$N9lU~vZW%LvL zN;w9-&kKB0lLU!Oy}I;x!Npv)?AD`wzkk2XRQh88dC|-t)bMxmBX=l8*D&3<=MDZ$ z`d&^QbN#S>`3AYWUqLD5B;{yWJ9Fe9H7h`mSV{3gpsM)apElZI3xKicZn&sC@v$4} znohCd#Yo}Li@>9IJvsI_L&tG15UTwpi^1xTEfNp?M$a^c%_k{GpQ)ZW89(-Rg#`^i z$Z#z%RTQ8ZH~f z_mD*%YX6P%Q+12TE3O)f>{%e|?#;I}Q4eBFudEAL6)uKH$9mClbwaNYED_ zpm-LVZ_5$Lo@*0^EpugdmU@4?b@6hdQ+AenE*1BF<<+$2QRb(oRleD`6bSu3SBD+4 zUz(q1$Zt!hkozsV^!m}?To$k;Fgr_0c;DSz7R(mA-S_g6rl7JDvzY!U07a^(pJ;OiBM zVUA+H>Z^a=J(mZ5?$|{Sp!L1S9ahEwC;!yX7D5(C!`b~)`a#b7oiUS$l-u#~TbmZr znGk~z91B0ij!wKs4h4VL!~b~PBbE#1X0Mz{tNIlb6=24Pz8KXPp_-3ot1)G4bT$Hhdao1#2$wZ8<_^| zafVDb-sPvS=1CGW^)nlYTnr{p&=wdoV@WKX3G{4TjWmsjKmJ6d20aS|E&`&p6@+PJ z8o42gk~@DM8pWKBU#ab7{LATW_@G8Z=x6s)t&>SVr_z2Q1y@~vr6l3u9|XB?xJ@E; z&Y08mOuod>$hjxS8&z>jKWwsyD_h@>Xoun`WErm&t))YbIY7lCi~`)GwY3M2mJxWF zS!Y-TFY|}}D=eKxf9+Do8qYO;f^tGFS0$DIE%X*3uV2}pd-K1`3ZBRHB=sPLU%_cb zt$I^Hz1ys;9RAE(M|1gd^n*{zmFRp%eu9-yoOivGXSY)qnW0b%7)4y4EQG^gyObeh zVWx*dsEf?*112e%pXH_Z%D5lV;z$|ArTZoR*7|ie@AJL6&Dq&+>*`EGGAf89?I8sN z2N!*pvR(|&-=BDI`(Zz4?z1D^CM1)HNEbsPi%9uG^J(6zAE?~_D@=FQjqj5#rJ_65 znkmQ|kkR5mF5%+k&>!dyj6px-bA5SCjlm46Xm=>9e{=o0G*zVhf;?8`ywX`8_h|o- z0)n4p#4agj=s^=paHgJVZIYu`n00cOafNhhloyk@KHV-IYZ4nJ)mQ%<{1KoKu%atN zeqJj1X~R3QVhIdgKgGt6Io}m(X8XpNw}d<&e$|tD-b_Uc8AZQIbM(FHxkeM*q!IGEBz-#|=2_ z1MC7$YbrT(Ld!j+CbFsk!W+Xf!xtPJPIh*)yRP7PeYwRYo8*-kh&?blxj}l}k3(6_ZONs--)`vc4CV#h+EZo8X$+kzwKX3K92gktw$fYMn!y!6+XZB`Gp-C>xyHj~ zpmzWXk++Mok>i7^PdD^=g& z*?wDA;NRy{0nnF7y&ejE!WAvEbX45yzv}gkkxd}vxxa>g zDPRAbGVGdRGji({N}5?n_FJs>Gp>L)OA!e5Yus?`yoo{>pkp_>;-F%YMceT$ChKIX zyg+%loVu3Iza5)~APR^}x^s$idJH@`TUbtX3sc}iJD zs2wkB$Lr!Q>P9P5yzS#Y!)y#}=izX31+qlG^(atkAZ&=xALO`G(X`5f$2fEb>gT2* z>578_#g}|CLhdqAb`F-sxn{}_MWl@N(i1fz@Zz$>Q06d=!cMRICy^urm21a`viH|m zh{&3`N($df;bk>v;gS3K$zO5%m?x#9koo2Oli$=T4(@-eHnb}>`V@<#nU?%GbhYjo z4L+IQ6O9oT;{l^6w1*;X-zWT)pPY~G$m-Sh!bh{3{Kbl}2g3lkbAE&S9we)O8JFk9 zeJLa-8*I0h)zUgR!4n?-<1;_dNjww*MDI)T?VEiZ>Ef51_;UMBl%(EMRC$bH7NXnF zU6B=<%(-K6BSokev^a3ee0yIM>EV)yx+I5vkLdE)I*T#Vj`te5i;}^l1#Cn3;$mTe zY@nrG*O{p5XMUrNIkGjCTYR_&6ijg_3=(yQ= zl|!+aO6=bLtv_xH64kokN@bc%hk zPj`A%6cyi?o42ui)?nBIjWvui=Dz&5<0D0f$pYilItggvrx>U62zvN zV+3Ho7Soc^z8dpV67o>c{jlX?L#TvbI6A5UonY7k%&oZ0`<~@E0Dm78`NW7*_&Pfi zd0CH^sc8M96p*d3lMYs*E_x+h)eIPBKF{! zb^4vYDB1q0ouTvDy(SbKG9rVvm*%skbAL0P{z^}y6P^nO>0%&!B7((FXe>;rg?Ymt5>`xuicNRJyeopVAF>%Ul zRT5qAC;mf*X~6Jdm$kX{wuoY9j@pZL(@o2AE2D{4MProQPIbRepQ>tV9EmGIq((Qr z1J;G`*67BXj1+2f-CzZ$^|ETli(&4E+=*}5EtCQpuCFv(+S=Ms(9wZXVhCQd;C}J? z^+N3Oyvg|It>Z3^7E|>4Cem*8-}Ti}<`@WjPhaM!jwJbHZOuwc z{j$3BlII_Azf^nP=<`4iq?F4}ODhcxe@APY#b6d085x+Z0n9IwhE3P%GIrxaZJsmw z`;CmqZGCduUfmV2O674}22dUJlI^{{2o|{-KQ!^z&}kE70XZ~6s@ZV&{F*0BnFbHC zr$7~b?UTA_et*k~ohWSK;NXCW)0!KeCb$mZtaEqV&}NX3GIJGmU3rci-l)vNgdg=3 z^+Bk}*Y;V0S7q!iijZ>?jK06Hm*CPhIqhh6_%)MxsCZr&`XY#f`flM4Y@jEc);Wp7 zH~tF0KiqjJ0)7Ik!}<70GBZmpb4?$b0-pQ1lL~G1)p?w5s1&LJnBxqnBdB5-Iv*h4 z4*sqY3yf(XjKP`k79g>Z$Bgif1y}t60~n}Q1wg3=o~Ltjb5Lv`>?0|LEjhv#Fo@XW z1-+`n!^2-bd;c8shVg`?sPj4RrKpTJvPd9pU{D*Ib57dzDQaslyEs-9sa{ak-oL4I zt}$D-M+wC9uH4~j{lu*X6#m#abL0v21x1=uv40u)hBg!je^7;~R<*v=h66DnAJlu}Ak{cSXfeP>xtT_hRg|Q)oj$#bRX5t}_RsRek z|MzIk^7XF@TT#nRq_7^Wg{~e^h zfKmbdUdNffToKO+3f;r?5h2eL#fdu@h+V*13N_2JUZ+ba!q#^KA`AMUKCEoY9*$i3 z&Rb9K!nkfCPoDAWSGm=~-$F#{>%zZNf}{FsUG!VWM!NibZqxGB9vnw&3yX+;o_?MV z;;;o+ED9-f1NQG=GRG798zooKvdBoU>6?E@g6#87iSB~Lg!Op!tXaKU*Akf9qBqHb zXcM&Os@ZDbLW@qo^4=gG-~iC8++`C|T zI=*`VZ=lb`E&`~)YANYu5I+Yya3%PNBqhN|u_G?luG|879yr6M0c8T%h)AAtB=wU` z9@$HK6NrFuPuGtz?&~86Bk#Y_-)2{jT55LBG7ZkqJH<>Sr`$d0**VzR=-G0g(aJ_- zX2b-F@+TplyK*-YhV}m-3R_}9ADml{UyUDIo8bM*%~ftaI+T}NSif03F=M^h76F8B zY7}x7mcEIJ8oHreKR;y1@&o(UjSXTVqCApmjNl-nvBI97G27{XS{iaeA7yrVx|WtF{0(2dw-5zEbjQrABKGGHWXopy z&6i3~W>vlE&?-kw|B~&=Du%sSIB7xO91svN$j*rO;KsHI>aGVd1m(6ff}EVrFx*Ca z%%GU70<$d;3d{hDxv;P>%^kuNaDhrO8}NhB?2Ie%q|vB5bLvk1HJ4B>)gK?v0NN29 z&H&o` zi_*3E8}$@eD7?lShWP?CL#lrTRlu@n>W2YH4nTp|WZ!{eLzzK2^kHpc(z z3$PTka+r1DLzpfCwzqb8>(r=wq! zKl%z}g+<>*IXBZVI?1AleDg=0B?OHyY-J%9C1@;9eNsZ4e~EYogDXsX6f&E~VmKM^ zu>)PnAJPsit=~)^BkDi&y=;uzL9LI+TaT;;EhabFBPsC=6f%nWAOL14B*@WM(GD|3 zXhoy~(J;jBiKJkYmBTX%U1%A@1U$BICxG|YZh0fJ21&5&;5&F<0h@&Q(j?s(@sx;? zKdt_0Ii@d6%jt)uN!W?Hfwuv+2H9%)lsHhGdYm7u?#nhe&&*s`&Uiyv;3?<>sq}Ev z`lW%!6psI#`F~yK6F%2o3oYhL=K*3BH9b02p3yZ1yUaqed`<=`cOQtT$1#jOs`phA zTM-K|^Fyq(n66n@l01;aev(N8SR-=@weXKt#y>ha+Qkj_*V=$e>AVfFpUoE?^Vbk{8Lkjr&A%r1S-@&$hrmskH8ckCHzV zpHJh|=AKfEZpJ7qv+wf^&))P#$qu0+AF5|{|I|c(k3RT*fbJ#{OHQwxl91ljuD*hw z^8l}0gs)3NKA$j5809sCIBPU#YMO@3*Sa6Xoj*Qv+8Xd2&G_BFJSGvJBzGq|<_9;^ zrC-hZVBrDzMI1!(P!K;AaL>rjzMnmKOegnh+T0A$|1MwXnxO?X0!Wfz3QB^DD;l}@ z!=MQSNGi^<711QY-+>oV?sM%O{C#6%1Mp505X?ESun6$PK{<8z{(aHu zJ)@%DgeE0C+Q(d9dCJOv65`?x=Bef%9K8GR@&`iC(7UsRW(#uxSDf7VD0~_Mzb`*_Ys&(te+4pZWG%v> z`yUq|WFj~Bq>xFj^|YT6p~H06dhgTIC)*?&HhQZPah>!XL80SHI^9z;S+;$8TZ-?`;2D9VTrsub|Qoeqr$9r&N9tr=y40aB@ ze;A~KI+;q+nFG`cDMP?tql2lK5SA`Hs=d~elngBEtR#-K$$5yBXu$%OrRD7w-7fQ-*w}soe;=%L{ z{Ch#5Czz_={#T^VenA4(MU^h*(sh^D{#kZO&7q(uBN| zUh!>eHw}1=(W}~58iVUyiN9`; zX@^&n9w(@r5^NYBc9z;vUH<3_45akD(&wL!BH@!U`RL~629sp&u#lE{@R(Dr57ce& z)}_D!dTNwT`Tpk;uFEOvR@$zT25-Hhbq-+kkFz=s2*o?vyVoIeaC zZIFnO*0eJU{MeP%UQ6BK z<8wtGK*sfe&h3PRm>2>jc;Nl^eb(621i?*0a42ufUU!6WHk4LW3}e2v_**are|`gR z6VnBObQb6BRHI$(Wwn#5MS-Od_^1V7kw#Kf+0BW7pt^&I3x0n@ul9w45C?}1CZ;)3 z|J$#L#42jnBZAJ=?oxQZTZxq6t#R+w)+6an{5~-KT%otIvTFd ztbiy+6zcyB1!VE?LotcDzaY*NP$!`;gr?#U?0EeRT=`SN!+YVS20MpY*BG6SDC%o= z+c55;-XL7eshYTVR=PU?y1m~K?SIz!T1}){ zBL3CT2sQ;0kM+Ndu_mnOQ8Jl6px6MBxL>0K$;0N-4KStvt=ZT3_%?fDe*>7tkAhkg zin2LBTE_E zI}MnVd5+fqzyy=1>K_R!{+xtQD6IP?DwCsf{f>7-&Ad6bucn9F@}3Mp^d>Y~;5!D^ zZjlrgiI0QCU;;+KVF{$HLYWd0e}nkGzP_7#3c^fK2om@MJI+7@niA;krgC0C&za8L zI`}4B97ck>w%*&(_FE=43@CR%x5az(2<(l(Po(0(y)q~!p;>qw(gGGpV1TMvgM{>m z6yy&t?H^4OPq}v$&UYDRE|lyq7yYd^QNuAAI>lDq_@7nGRM^J-m^%BD)ZdahSRk;Zy~dH4Z1i2|I5qc8PyAO z*!Y3O0=#}f&l47Y{>ia1LQ5i~Z{#0uilS0d3#W(x24Xg@9Rn5rBX!^7{+C`;KhK|T zSmmRoT?%8kaG=X#?dQ!owIAb%rTfluZ`so4e?NG4&ZK*G7dhI_>c%h4Wh)6LJeHPp zU1$X)SuqI-t1$ftQMrvo$9>Zmj`*Q=>FNqK(A6|+-G6Lx@|sTTkYSUsv&02=`*9wc z)7>w()lf>*i`rhWu@Hkm)D4yE5Qa&cch6v_A+r@mF(3f`ekp7W`Y_NXBm2|Zde0De z2RG21J4Gn|x#-8238N?G&pS&3McH)6K=$aBboNq?&iC7lk0eUM-&~{lMU_VRLY=Be z6U`D0U|ZUu6#Rwx73_?98XCU7bFUBx@_Faa(^B=QgBRO3rJfKEXb_YxIvl3@N> znFZT+&>kF_Z3b@44IQN)f-W%?H`gpF9$&=}e|V3_+q z!rn5f%e4z1L@ZK&Akxy^AQDp2NVhZ!A_59ZN{fPYm$Y;VNH-|m-6`GOJsZ#apAWNU z*7(7-&N?bj+|PaQeeEmKV7#0hr)l06MvoY|4~jgJdbV(Bo4F=TuRBOT>b~4FL<&R7 zmUVnU5=lSYvo5)(yZ!G73Ey04>@UpLu6;JFb@%FMX@WI}jk2Ww>*F&|rpiJ;(JPYY z5rzlir*@&6CHe1f2A_E2XleqkWl6l0|5CWM6cWQ3zK}tj?se6le-Q*=Nnzn09HxML zFD)$Gz5xlsuwSH#P{&0*`OwzNvuLHjHF-7$asbsMTJy5)OaKT0k5XjM?R=EBvE2V=z$$@;RN-h4{q->a9L-J88hd6V0A1m(|( zCJ?L&ocTmDrh>@Dygk#Pr0@hUFtR)Mh*9z{^ntqh2rLci*61&R`J z_mu|Yty*0z-{Y@p^D@E(;d-1N0geil2 zM>7f$u?Y)9v%rChDz8`#Z!(|+C}okSYkZst`HUKP;jcBXHv$COzX6vjg-A@(;QS0L z$IHviwiys`^HNJrqzBUC(cBfg^UMiawSj^8AVh$X_Qj55YiXK#Hl#j4w+?=rWF`6> zFMor-h>D8JL$ups!1;vXLilaX>MN!#zv2h#dR`rgJYLOt<|lCrFu!v?{S?o^%0L3esPHAxKqPI>5saC3BDL2@P+M(aU#4YX7WSx)TQsDTga0%HXj&m(fBiHvz3r=@;R5UFxxK#*aJvhm z9?KYgRY(wQ{0LiMx!>+|O10j#RDVv#d?hwqb^lugM^wj~ZO>9+9wTYhtgLqmXAmIy z694f0#45ub=`$M28~mGpJ*5a)4{P^BeP5a~HT;zd`yv+z&&UWtot~TBz#j>rd@gTrHBY}JsZ@SXKIup>C#?Mn}G?zdl@%k&&?< zJV?Zb4U-Hu%pbQhI%p*$<(9{5QXRkE+01#m|LAD=&zZ>ro29<8YhS}1ACDG#AyE=++4c&;`>7d#Ap6E;fcr;H&1yE+&+W{o|z4OAf^qI z-WV%o4aYR)Bn+4KK$wpFB6mMp)6vx}#)8AnARiz3-=6+i`q_hGtM$5ZG*5CO?vDLT zLoo{XjP*#jHDlQ$ZT64GmD&BoZ68|k0ul#eUEb4PbPF=FuW~$6sqpWQ7~bC;0+&%J!HTMBNY~6e^xgQy0zh1Y>Qx zg?9Xxfz@YzzO$y|NG@;QFshk+vBqlrhM8|Dv#$Fy@cT%khJl!&KcQn@{?WI|5l2xh zB^-pPQr7;IrmbDunH#^o9Q%DTnd(c@-F~A&$Hk|{Mqq5cgj4l>gL7Ski`+fvw|!2| zB35B*X*{!Cn8`9eaJ;+sdV726u7`Q(&x(IY-;<-jG`8kEX}8vFDsvXPTkyA(irOS; zrJu?sYue*NlEtyw|2ZSsSksW)Q;ZKW99duKSuk+MXMWeaBkoe(^-**W(otg(SIV@{ zG}X&t?p?ess1Ws{Xw+Agsv6t&cB%~Tr<#wHjcjQ-S|%~y!v@W0XlVhB4wmAaI$fTd zwmq zmNrtT{M530uKMQMxieZ#%MbBx5^sy@>UuQq6qmCA^{0z+`%idO^cli&adE*s#DEj| znbFsAX(Z{R-r&_1DO-`l>BSbSQB+N_G}`|CAuOMsuX9iD?~Yt#A5{iM-M&rGD?Ih$ zh#7zCV?(apZ4Hj{vI*_VnAPuuW&~#5#YGKT4$1=T%<8++@_%6@+&?R{i9nY_caGa8 z^frlxfVQsT7k|qF_7=lu+TUCUYA}bka=IYV3tAMPu?TJ95fEUXllL99+~O0FI&Xav zIj1RtGSk1wqW3|-qerf0&*=fddE0pVnc9bxD-ZiFWf4nr^QS}y3hho(gnrYu@47qE z+!1|mS91+%19C~tbN=MfftjgXKhQw&gOC(Q|7M{-%WQ#<2ca)ea5=1WCaH0C^`d-r zgpuf;gl}|bChPF>_={!P7}Ex^ajK8zv-%`Bc{oDq*BGa>hcfo;#BN)TmWGv?E z-P^)1Q~JK$yc+@c^5%^)jv5QM-(ZZD>F~USxCK@5GOxwp-@RnlPUo$Mx%d{DGP_^Q zkMR%&g7*FQS!^z~oxJ466m&Vxmw$(5?zrtpE7#WL#k4J0MyK`n_p_7T__qq5#q4YG zK`A9ni0nW#*H;t=siY)Qe6@s&#C z?vCY=d2|{PCW)+X+wQOmc+TV-#CZHZi=H|g$LkqtnEM}(?A-`l><}VS1(X#YR~G`;!Ds#M2;rXd>M)4| zj4SJ2_lTB8cSK!&)ia+(xn6AD$-4Q!OBODUq*xChJvt%ZFa7wViUiwG*3a0xbFs|=nNK!nlZ)k7|NTeH zMaN?sM`Bm|D$hk4N!4{&s?37i@rn4EC`aSrrC#Huqje%aX>k*i*=8#guZ6}f$-W?h z_bMuvCVmQL2BH@j6iS^;^r>UOUGaBAJNHTh`TD_Toqg;rHJf6P9G3RHyy%Wfh-u6+ zO3$0=Ru}Io${fPp!#44W@cl5ERVAQZ8*lLaX+VHhQavwW2W2iaP3IO!@{(et0DJl^oQVL72TVLlPC9T^t5)`iW%E@8w-t+Ky$R8#4?xnth zulqx%D(gPuzHVI%0ue7o{G<8Et@K!CEiVntAM;oC%}=CLa+oRH{dXJ)xQhb4rI;d3 z--$$sB>v^;nwlb^e1N1_fu!oF^Gg0kayBE2ry1!(j{Y<)nNEdNdO{iU$imO{p1vhk zAMrV*9^_e=o6Dns2Pg;k)=x%VWiS~FhMIb`1SZJt~aOaPtlMYrM+)}H{iKKT|u_BCr zpMCzJCuf?&qJH##d`GFT0FQY`g`GQMx9?~sblK|uknKRdb!1T7Hf)AnB_$|tSI z+vJQ~5fmwVbso`NyyrJK@y2Su zI+PvuCDj$mQC+WfCA_*wSNKsB<5ameRa(h8@dyl8A^+{ce}{UwWM-YMf1Cr~R;{Z( z@0)EQ0l6WgXNJsjC88~#ep%*}*0~Jq=gAQmjYK7HN#zLNC3$B`u)p`$Lg8mQ$6i(p zFBc7c_|G~f5wFAvgi;vMmOl}_NRgkPtai!3MCCyC3s&gZr>9BXt}3}Lrr0o4^7I76 zZv6X}xtdarqU+bjZ@so^`;{ESDlO6RNaZS2&6?il4b@W{Lc5j0Db?igud^4E!yf9> z8+vO)8cFwrTxbLE{o{H%Rb|ZQ1zTqtPHAV*xUC*pzc884vb2xq9%_2gwIKHQWV$OB z>sI1m7(JnLG9b!;RM5fHFY2lidd&! z+{~ZIT7MQ(=dlbO4cWOFtwf?cO_wbkd+ZNU9>=(_m@u z;*y-%c4q`tcpxbH^0FmEL_^fvWt?rU*-IAsoN6&h)gosL#6)Dq-ou;g5C*)T z&Q_|Biol$ zG&v#>DTqM=mxJ9aU$7knOjD#~Z>gJIjud|0_2)0ZLOZMWE5lyfj5k%@rNFMU#xvhf zx4U(Zrec6Tu$6{iJBR@9L{PSI*VXCf&KP5W7sjJ;KEm00T}zA5X%5b0>Ru6?1+vE! z6px=qQ>63<3Pp7D0q~`)pukE?YYY=IKybzJ&Km*CLm>yUiui33q<`msvH`b;YO`KE z_nX5Lsm%nJk;@M)9(oSTN!X4FmwIBp`>Cg1NyPlqRZ$2EaL!?EW<3Tjo&EOTKQM4e zv_7c>UPvz|gqAA$)J2paeeS#c<7wuI9Qnz>xG#T~U~3Qv0z^cZu}DaslY@Mpojn+_ z`*kr=7MSl)I@K`Psz`~C97K9xx>VV`Qoo6MnzZiJaVdqu-rtzULWp;8oX;VYK#{WX zQ*+^@29t=3^T`uAX=$x;ONhs&eL8y|;8_ZHd;$U(E?}4-Jxldy489?~uoWXxLfENtY$G!&-KBu*^-`t%j?&xcqv$6%_4wQ-NrviE9O+6N={M# zgU)u@01nTE(I$!S$cdV6%>g^alD>^{5`J`7cEi2B^jcm{Fm?sBe)*n6)OvJqmKId|)FHffOaJ8 z)z5)G_I2VtJY;H5lT)PB27FshhsU1|X=6k7VZ?D6Y<|{;fN4uaG(7QSL0Lrw zyfTGRfKKNJ!{sL0e^0-u!NKP8iZgQPeNVY)c~wryo)3Cykjp4qH%2-N^_vDxk2Zy` z@fKrL2nuetUvI}tkYn-zzyy*9j5%Oj25IXxO}5Qonhl?8sxm!S#f{GlH)<1a)O>zA z*ll%SN9kZ=K3-v?9XUlg;VQVpk7~7){c?ea;Qw#|Xc9C?v6%ZpXZ2h$u|Eke570{^ zv=riX@|oGWxUNkOn<`_*@_%!rAeHK6?O9&i%xHrtTQ=bydU zvLk(rj>eJnwJL8@o2_cjOLq&c&1jWB@?yL=&Nt1EaKNIYsnjED`!SJA`NQ}?&9l^f znjL>Htf-ZjDtMSaRdxz$iqGiUPAaz;s@Q>rRZ>)>nmuUP_^U=}C!b zx5-+-<&h$ySO^<{5_H ze5>7>q2PMQwZ8OVyrNYwwt8PUbF_}$x;u>eK5yg+Ey;vtuRB77t~!?};Ic=U`@CoU zz(r%b7{{Q%fG6IH(?$#@`m|?$-pT3E&v^762}yX$^Ef^`puSd-p}@?&!tuzwbHx{U zjWA%;MYyvYHd(I?VSfFu!Zpj9@1g4Z&C zyTp9b)X*?lIa9(9KluB1jR#LDczNx?EI~T8udNNb7+w6Rf7|Prt98m#j*z&Z&WnS) zI<_LX!7Htt6@mo}yqr-Z2XE69E>1p5=RF^GpxQH}i9n+>Ns7%1V#c|Zm}(-El1N^| zXV-_(|I5`?f+CYYC#3Z?IQK`kFThX}i2ACTs)J4$*{V11V6?Qhp3MDb=lIt*+t8M7 zjf$M_w4CZ2URoz52UHi#ye!Jl3_K+iApNmWJWsV|NOM-&ACfX1;vEsp^_7GnYFgQq z(%p+riCL35B@uPy)hkU>A+#?&_Pt4MLnUD64}+!`4B;>Zttc-?6)DzT6G7bK<}L*V zskhi}J8Lbc=>W=qUB!TVV8HV{kN(xAshGJw!-*v3y9)6Fj=O({8mIS{`Oj*H5@T4fkU|KG$-MM zU^X=Dj|ktXh=_?9hmG4Lx&|_PKwY0@#tPON5cTPiwgNOEuwEvq$41H`W@12Al-6Qi zj2FnVy>i+5Y8XR$zLO!$cf?%j@-9`*q~rs~sp-xHZuL;d^2o+JyRY~m`k!p)0`Dg1 zmJ@}@JlWAW567wrqa&}qC4|LX&{O&hC;E4$s&ITfayOq`jJgR?IrKwd?+m8xq))9| z>gtkCb9hUj0)-*d9={N{zd#m(!GA3#q4@t-@4lcyZS&!%Dyg`^aHEk=$vtSo_ii03 z*66-wkx_k76UV;XbB{C+1EbfSCmVIQ)iYD@(>fv2v?LfuJdWpM67X=Rrluez>o1Qv zNR9^6&>^((Xs=rc=zlP_ge_7T$K$`A+7zFQayepY)J*S&68-HYt;NIl2A+Pl8>ZR1 zB*wRk^n7>tHY;-i(9r{AyXIcs;qs3j8^TRikzO!7l#DRejwzPFiQazKN$8W7qpJgz zKZ6w?Py_*RhWIMvn>S%wj0+1ZGHkvVojZodZXXXs{X>ZP(u}aNwuT(5k`xZ+P!K{D z6q1S|DYiZMLR{M^I=&xYve@EpeEBMP#zJ4P>bN~AKkliV;KM|wz&js!u~_vQd^=)_ zY*r@1T%4_U+=IUd|SI&!K4w7cHN_3YFZYKu7xJ*t^> zGB>ufAMx%d_lS0~BcJ=zRy>7vrqo}{Wfb;!XA>qUgBR{$HC!J0X(ol=}Va3L1A|f z4Gr5{42~f|o7FH4zq9B6wi!$T%62(*t%J8_=fjw)_;ZIBgdqb*nS|BrNuOMgY!V0U zDu*kIe>OG?Ry~mPJ5^YIlVvp2=^Szs)e$@Q+5PZ&s;vu5R7&cK^E` zn#}$(+b_d0ezkg2h+WF_St;G-3T3$(zL>}mNxu#MM)wc&f~AyR>M?ql^X>?(G*()G z`T|K9ZY1!K`Y3)+&O_}U%1JgEE79iG++Zj-?gB;x7@Pq!izi^b+OaezX9Hr?7_Ghn z>*$@CStT4jV1+_V41Wgt5&w@U*DaVSmr4D{$I-RBAGBSlnU(@~#p4baTVl7mf`nyg zIS1aZ{Qoq7W$Y0eT$2mgxwnyF4uG&Gz&d-^&y~*fdM#B$nd}AmzD|vdkj7e zHstHqiiDF$y*qY5EL440!gO+An>0S-eX7dh3vT-A!**K*^n{|L^@k!%cP;cM$G@xB zKCRvSD`Qk>au<)+@SuOzk>o5EL6O#IW3xu#&(VO3dnZAN6-DH1v@p9FtJtKUhKJ`E zo*!^5&^!!)AOyZ+_(Cq{z^IaylVePI4$L3$-rEEAjYb5uJ2)x;15QPI+}>Q<=A$oMXuK=K@fBaQz4 z{TrCmOiZ#?7LRaox!~?V4{rw6yuy*j(^OmRj(e2 z;26bv9@7gM`~wvXhgbq2(O0SXOW6dw$Y z!6H4fRtbIwze^yT8@_%$kn%hfKJcZ*MQjmRAJ-~9@UFP-@K;t|4cvGp_qm(}Nzn>i zzpT)$P|2&;jwA?;mjBdwh#~ghzh6^7YMoWiv<6_{I#1Hq7rx&kAeMle01%U|X;w>J zkAx9`?ybQm1m8JOfNX$|0hB2S!_(ITD$zFVgm6YcDjp!8SXfxVR2H{TEz0)G&)f(`2Z93(J@A0VdYOvxd+9s4GqR7m;Cyr0qj*^Wq~yi z>}HM&ZQ(!$z{SCVXYtMb`d2KUU2ewV4-+lW$3qm11`_~x!hd<>bJVj3O(Tr1zE@IU zd!vwx_nW{|h~~BseB1K_i&8>ETiej@27m)dp9zCL#jrVGh&{zS%=pU%C_0uO}XY zYIBjx#YIK29N^3k&P$=zy;YTLj1;Y7ou^V#vpj9|Mu>+aFV+ zfB!6!;2(6Sw+?j8AM0Z<;2UYQJF|_S!_P01^Ts>N#R4+lzhCsHW=bm@PCOE1NYCbw=cLh!a*7i17cxa04`L)FAJl(;xZ=S_Pefm#ivrwZ{Q3D~ z@`laqJnN2M25_}u0ssenj?M^T_UrP)_1c!(vj~!i@&fpgn>|=j^=L3VSmNUcVo8)g zYVdw$>*4nd?@h@GyjyOGQCv3TWd0mGZ+8qRP=L1jz2u!Yrw=6~BRcGP&%9w)hcqD8 zJWUemMTLn;#KDQ1#C&sQYr47CK^*18^ui%UN%r>b+c@Hh)&Tqo{=1GA#wOpn@*9|U z$$U6I+I0~NBZ~a}*3S;b2^$*s`uwh|?5 zj0_5T)?cK-B!Tna`@053%v(_Q{DEH)WUv1mcqDK+FnQwW2H_nMkHVPHHt4RjiU_Q5$dI zig4C8;)oH?`mML(`0{^2;raTtB2H>vUf}Q&#lIHUAeZt3d6z4hn!ZzLsf`hSpHf%FWsU~Pegoq6-!q$WcM{0OXr?N<&`D02PI zcAH{^siB}DK>3oGNS^c$Lqpo8)%4JGYjuNIk)F%DDLWqKUEj&KtCZ%NZ1r8?Ap!pD zxnvLQAGn9>no${C%j9HbJ6c*m#Kqt3`R&`C+qZ$U38|)R7+;+@XXeL4tA5LvtPCG~ zD7g?9oT!SzB9Ui@GruyZDKddKRCQT>-A)%JGHa8@QLXEBOdQlt|MNoGxB4^7Ds<$oO z+M{r#7eNx4J4}_GO*E|Ry&bJ41$nH<^iRCS>I&Yyef#$79ZUeuuklWw;Dm&$zkhCm zj~wh)K)u}MXAPGo_%>s&m!ob)3{r9krmY9B&*(H?H2er4d0r$tVEHxzLcU}lE-jAI z+t+8>o74ytsc-j5&5evaf@B!Tx&JuC6hCwKG{3L=P6r{CX%88wA6Aro(r5);&4;oc zBGW&LFamg+3=_Rs8jXnBlJ|TAM$t0P+`X}fvF;X)5Js-B;JFQ zlnMMl&;@|@_|k}d6x5zVLPEgr{rveeoF>pFo}WAUB*A{Fm9uC+1(}`T&Gy*1tEi+z zV!e@b?eOO$tKFKH4F~S)9vs{kOsNyc$8m>;Kc&HUbD5l0o-9b&Hy{9V2p@WjnHCe8 zAYFq_bV6`KL3XnJ{xYa3D1tMVYoT~wg^+K6Y92j$RQqAr7dBle3H8c8%m7?J9TCUFZJi*ma;JzYi~(!SKt(2~zN zgjWVQJgA7~E$!vy@AbjQPUCcdqUgZitzY)x&(zdqc3zDGWZ(4Oj)2Ww7dX@~egUZ+ zh^ekQNxPG$va+(EJGw3iA&KzUFE%^7qonuif-dLB_4kDU;I;qsDJ3;EQBrUz=!%>= zI|WrBubw|e$yDh+>9^@>8Ftyc&KRXqr^LU1Uw(V_ixlLgaPIjVY92y_9$<_>`vWHu zPVxp&?SLN)xJTS4;a`TFyhU}?!otGwd_zest!NM-K*dM!O(`3k&fY)f=1yRHC1PpG z;jqMdOIYK;`e91k(f=r(dGSI2835bX&;XHw5 zK{yWuHqf;}_Y)Bzp`;4;23;>MHui2O_jJp`uBDj-oVBbvWkKJ+^B8v#XR5Y+oB;jk z`}gl(Il`rj4I0t3 zwa1~hORDu@awzjc%&HD&CcY9)QF=N`DkP{~_-)&%zc;y4s}$~#MNkkFVqfuz9|M%96XvoNZz(WF)i@)|YU}qm391QhY z-vrY+>$RK$HaRdr2C*1`&n z<-a`!=bvsVb5TB~&wRV52?}W#$6as4@4y=~5eiU9TQbQ1)SDy@6FaDPvXM#OMaP2z z9+>Um*D`2&(3dLXiAkgm>Of>) zX}zMHoK{mMV{b=(j4apNUcnT~hV8ecEah}DX1w>tEeLno$#5*`HZnaUt6mktw~>a1 z29D}$Iu60{N_qk)NVAnQ!4?qkp6q4j6%b6p-g2M>JQCqiSz&eCOVLm^8C!eIECFcqhvsB*LhFX%9wg@EsZbJ=?0C2E}fB0Vo=G z_x9k!%&TY?Q5t~SpZnbiS+Eoks32Exc6K()`To==*EzX9A}r>ye%HY7ScX!Obifj7Wxs*3l&Q*>KAf=ROg6wU#24*Sb93ky(xZkT>hggqF7 zQM_bnASL#?T>w{)C!4|%#_2iq!hUZN`aXbU2G^0m_O%GcMVYEl#9fO+!==?Q6)MpSBlxxI(9aQ`R0K2*wtV0=)Dn`eLwI(xA3^=c31C74 zmZKMUZ^P)ko$`hxolo@etN6?S`a8DI8~N>b4c63!5z+nx{co2QZzZ7uzreg_Ivef{CAG4IgU!BLl+-sjUFFE80JYa|d{X+@hjYENS1>~# z%BLzr_=_bml!v7M+aO-UJS<%{DoHsLf&+K@6@&(3Zrs4H@#&@Uk!{RK@ZeRvxT z^;COB6+dRV#ov7RQ$+ix^T&Dd=sF=Y>d*&xc3Bqs>WM*vxf`o1&y{dEdSfBPqn~rb zYYl{7*9+Wz>BOSuMB?9At1~NeniJxw@-z#-rLDj`{N(spwNX@K`=#(Fi856x0fF@* z=(O+HdS{@c$vYjWy;6^mqOq!Ue9=CFAN6(s)H-SmgTTQ+{O>*TKwDvLT_i>I6wsxE zap!_#2-bY{>eZiub&&IB>CCZu>P_vL-Y0+U{4Fj}9F!z`62zzTNxj~_EzmDn(>w*Lx$dj)?qUeH;~ zL+g@lb!NoZQ0-^iRF8{UUJm{s^});Dq>Q`w>4G!%W*bKuQ;FfEa7!}*-(P5n|F<~G z%wabHzu*3S5Jm+{z^dF>U%w^1y}g~m@cz*M=+Qi{)E@@ZcC%>$M@fc|BvKiw?c*K1 z@ltf+VGtj8`QlLqS#Gc8)xt@pURH7Y--jp$|CS_*38W}4w&RY%jw`MN5C_z>;kCuW z^upEhhixyG*4nHS6r9WxjonC?f`7qlR)}e03~!Q)#t^i{P}ytutgWrp%4rgVwpKa$ zmhdw)#r`UXgDk-L+=D=iXuUZ>0Ho$y!oLa%q+wSbEnI@_fWb?TCp;k;kIWshMIgyf=XVH4V3ykd!jJ4-*M%>A*cqUi$ z<{Dk}@VLDiA*6@{3QgeCK{`<+Y+5Gc1PMgb3vVO$&#j|0Y#rC%4=_`Q&u_Up{6;GI z@vQy#%RXPc4DGf~_?jWZesEA6qHM3v&aweh2<0v14T#~hW9d5{fO4nNfW3PUG()*5 z>67-)+9q^9d?Ux+^8^Guq*{}y3znpIe-gsz3CYMD}YtM1}4rB9WPAix->hRl$t7z!V8}c zwMhsWiZ3Y(iJiSpV%D#SpF;wrj>*vhA`0PB5}%H57%x@LzYdmNbXfFzf3(?>61y>7 ztIvcBI*--0HA?W(fa9!jc4MP+4@{R~h$%+sDygIjf!5$V1#Tt`qK=RsZces?++vPvD8#pE=6y;709_X0tyNq=(U;}qhc7t30o$-n~@YW)v zs6c}eDn%tVN9s@TSRz#!u)o|oZR}uzUMKxM$KWG6H^Ozc5sL!SLks%Mfxmz2AH`!+ z1JU9?Ux24{92{bnCmAx4*Wd}w!WMx3z@h#^Ci|W3#{c@RT-dwNzw|uf?r_qBm&Z4BT-#ZhBc;hh}Cb)3~%!$ISwZ=? z+K-`dvyV?VsQ~{lsX2Yv`y`lfVO04ecA8r^c+++?2dpTAqk_Tn%AE7KzT>|0#>YSv z?-No%r#IU#VgFuP@ju!vSarwzz#t3X_NPxg?FFDs7A5?*iTkX9HVWGt3}(cru+?7k zg|TzHkWBXefk2FjiHhfE0SBF6s6I(@X?NF=Wkw7F%&qp^BKzEDYw3s_kIkgbA^4!aH;UFfU|My&ZvX8;RZ`iddkZ(7_N0smr*-TB*7BHgpOFZl{N5=klEbdg>?@3T$L!JKOEhE~r zIpGtdgcsIIsdbCb{o3su3Aj#LOFqWwxO@t0bls!}st5Fnp!8g@%5vVjkUNVzoSr<+ zeWpf+^<3RnpMagQu5s)(Wl0K8_-dc)C7B-TRrGKQfM;5C z6RQrGC{v5vQnUh3GGT;!)5A*dGKSMG|3LSk3d8&QT9<0NPq{xWeV)ow7Q7Gi00Cd}Q5FFdFv@ z)@)w>zG0wJnK6g$eyCWdg8e9th&jo;t7|O5afQJq)OxsKfC|IoxszzOHzkibn2wVVsVWd&AsIMjZD$-VEy1u+Y?J*U?duCdkT7H4 z`U8qKC||-*otW=F@q$FeTR>Zzu@E|O4sfh2-s%(WVzzug{rh^MW_h=_kOm&7Q?B>?tSfhVtBN%F*pQ>@ zsi_^emDO3|QXvYt_ubQxC}1ooxI`b7K0bH-p2kXNNV*yOBtusemb;Z%Gs*PN(*x(R z7;0wtHXKR(4X;#*GDG4w;vN@OfAs*ahlgnM%-;R0BYZTy4)b?2JoSMH5#*)f5)N)V zt;>>at5jbpDj$FUi`|jX-H?*gcQ%55e-=w**BW1Oqgvde7zi2Ex)@v?u+OCRj1`+y zHvOq=Z_}4Tw7L0HnmSweEJiX=u~d}=$ijdQxd#EolpGW3GlyF?i{e+5FV9edrKl1d zMf84`%s85ReAF6Z9^+P%JiRzvpARt}PWV|{t@zAnC^`C;&YvduM$(e-RsO7G7e&c28cwyd>rZ)>_t{!xwP>|3 zB_bmtG*M$mXgqGM*14m{-$K z{Z8vSObaqm^pPx|(MRl7SMPp1jylVfz$17ge5y{sa zICi``g?v=MktbL9;OfYPl=Tz#9EnwgQ@<7?Io(vE;d|*v_Mc|w=Vp-S*j$d>#4lD& zl*AO91Sa@xW?64|(#TsZFPxCdV5y`J?}}EVIn`P`-gk-^{XOUz$=8OW)a9X7ho=&p3*mjw9v|A+F1JeQVEqVsw6-PJi_p{PDaa^zu7d&7Wje7W)D-l0|1 z*TZ#m{L;kEs{~7Jd7=F259ApTQ@s z!B0cXo5yYLRzTW{L-87>75<@|uf;0SOYbR;P$1$D z&k4y#Zbx_O-LS<;q>E0v9sTAl7Bz+Y2mbU~Rd*U?3Dcza2F5Rk`+gc(R8GbHeA+6; zfl*cP@a+7g{8jy~iVA%+m-(3WK&njf#yUdAsDAGpC`nKcgAW9;jOxvQr7V51mK?yC z7vrst%+0tovqAzQCZjyj!IGp8z8XACi8|a0jOJoLOTm~a5ORNmErQdHi@BbAutd~% zTouSfPDM_a7!;OetwdepuZSfwUXmYnc|vQjH-x!BwVLyr_WvP&AJhuki-&pX8I)U7mQ1BHw<|_CQ@c?F)ipF!*Xi zo?9!Im2y5W6`hhkRKZ4GK43p;psRIr-Yqn3EbWfvO)P&`FvZy&FJ1Dy-|go^@#Tk^ zx!~^ZLdC;M0j%?En2>`dUXnOEbkF}gRvUoKa9j9qnJXhX+FsbXKFKUP2O0`Fg@E&D z`ml;%wS%yX4V62>pmuqsdTZ6Yy=2r+^@TJF7z1DBEY3dU^&s?R1SqO2ky%ql^1-{* z7r_H)jmgw9dKbIs>FSTMy^~|Kx89F8Xlbne*!A)9+CDm>b!XDAA%+zl#>^y-_Cy>& zJs4i2>p9DxT5J_w>WppkZe2V;A&Te8cX?oAI-lpJTj6N)=FdxG2b_E5!n7h z+mNMi5!0QM3keVrUSd-@uv>}-*&Qf0nixWoq2RH zER_}_BP$Cg!W87!F8^0GIDG%Qx?^r}MoL#O$KO*x)jQY-G3)gJ)e{Juw0ApqpSiuY zN#L$Y+}HPU8`E8q%cm7X(Ghg$%CzGZe{v({(lYSO?nMD=FAVl zbEnM7IZoSgukQQy_jkH$C6tk|+cgJPc9e^*H6;xW$GMXCkGdZX)#$zFqTh9X9WwUA z#S;rXK%g?e$Z&)8?1$3RfXChTkK(w?iai1#tbj&tsO;$H&7;8cW*>;~9Sgy(t}451 zn9TO%%oT^D377**Tcrg%{0Whf&3jHTPGo!6CJC_rnN|t^)@pQQtZct^e=w!7q-1F{ zKY@+R!vZKquIH7lV6g@#>Sr3oE8A(IX9s-%r-I*Hk=gJjv}CTAs6>us3YDpU8tk_! zWp0|j@V64TxfWlRikThp?Y(hbDu|OK1rKcS;)zbXa%MK6djKd$sd0Bem21KhPxLF$ zd9BwP2b#1;NTrzq+llMR6E#2xmb$>8O#rxBJ-2jh+z3+uoCaTE2?_O7iEP7rnD2(F z=6b?e_bzqbQwzG{%c11Iw@_Ks9&)s|XU9lRPxoX`R=S;;`GQt%tUu-X@y0l)O|>=s zD=dxv!8KV)p!xuMO1?%FxSIX9pZ%37FDnDlC9r0)2Hxf?^`BBPkJ(Mv<=lUuCLV~| zcI-)%&U~LtY~q!ZLLo;&!Qnq+)OW95xv?jc+k1Nt((+Lz80Lwet4UsTk+S z)_F1gg3eajhTass4D68zkq*y|3Biu4b)iQ196+fA(;xiDMl6gBtAA!26Y*GaHv$+! z+WA;@Mm9Z38@>0~K4iH8 z;st@I13f)#V8Qg?@VxU6rlDe?A3pmmIJbi-i`T3bP_*?pdvDvc;~Ai%-wb%Pr&r2C z%aXf{#cVjYnXO)Yyhx4uH~DmCBLetBP?A}C*|)3FBFr4~Y(B}}|z&%o;) z5uLUHEVTjy4-;S9mh@8~r7FnE`T@B7X`77e{%s_>yWiK4pL7A#3Y;t8EI^+}@J*O3 zAsT$JVbXz#i3#Q{K@vMg?w++H6;E3FRia{KlyI*(1gO*I+Uq$*9}hVn-gqz zo&*3IoSZxd6BM9<1okbcz_bNMx;WyU-`Q`PoTHcgVmq$$z#A{2zIzMB9VeX5QnVg- z+GUO3@Eb|V?#~+lTiah|?fMkMiOFV!ivb|MoKG}o0Sb&$Q7jP(uh+=>~0Mp?+ zw{E?RK>tSqz%HXC~-?=ha3hzdK-GHYKfNoD2m<@oLTB`EO=4K6Ss)X?ps;a7B zXlNgQwGgQf=1E$HR$%<*F5tVRmr}Kf&XD|Q4WklVb~pA zLdlb^?Cf;P34?@X$v{hNY;dx8PQ~AjEgVEd$VJTdGKiKu}>*>D)U9?jw*+G#=cGS}MCGRBM+m z?=f8-3dauTSMk44HxuNKq-Z|&{PXoubHHF}NmKK!%MUP=^?pE$_J4JC-GNl^efSWP z+^DQ1q+^vCaW2ZH(;#G)Sw?PI4VzL@WF1jB0UULI= zfW`<_`Xz4VwYVQkrn?q%chqfq zY`x&yJ%GQI%%;n2#oI@MA}X{W_H&zAsx1^8R85u{5;!1Cn_^8y$H zCspugMMZB|*xQv8nqZWF_`u12pu4Qa$h6bc*j|pyBPW`lG0v78$3d@pi9`&rf}dQ! zzEMN#CXvV-D_tui#{Ac|K7TzR0U{!-iaL|LC(B>FP@^w-#XwNGOylu2J3Ct|oL9VB zrQBy}e|LK?-!Fibu;+Ozoiz?A5N+~im887g-Nz=nLfi8W+>0sct?Dwg?0x_7Rp)u4 zY6P>oC>xP{B!J%~ff#&Ot^e!TSZ@2qmvt;ja^hBRxB^2qOV}+IJSi>?<&sXx&24)B zeik?v92UK%BM{o?YeacSE>@j|wgLRmh@Qe`B9^t1XAd6qrQfqC>^u*1!nxh3?&tS( zL8-IPug4S?er#w6i;H`^>~+z=AiU+&dyS$abegsGC_vfgte(*t z{z)mBaB7^@&lha?TU1gvQ8w#Q&e3!u|Hb~G=NlM0jth}l2lL$y9=sAoURen8(G5?n z==#`ZJ2m+=*C?oS{IQ8geCX6j|HPFZyX_>MLDIEh!6Z)lYZ1f%qG&KB=r|+gu67=g zOwrKWrm4p|_%nq|tA8|mX4<7~}KHRinbBbdf>?NE@f@_lWfv zVB)RqMmRsoNw6PuApuYe0q5)!B2m6T3jQfQ~yAnWJ% zsYWF{g0=afdN(bt!{3(~gy-kGobijyDQSpXIKQ)cv~m5d47atlv2$`7o0~Tkjw3Gu zv-57_7A!aM0W_n3*RD-;{jUm{k2fB_?j>t|hbS5t;5TO^Ossz_mV2^wFZ8fw)ihSJ^KjejndVZM9tAiLuM3EpoLJ>FAQh{vux@<1E$xoZIi z_~0o)iCru8dmyJp8MHWSrQl#oeb-q;f=8=@E+XaKy^D;OVwA(ecPN2E2{2%uHl*$! zDRzvm?Y|Wg(%9T=Z^{w7{z7xKMmd+~$2)4 zu_;GO5C)qY8orR;*3}6sEBpU*Ybz<2V0jtY3`d}!Cg!2FU|#O_5=w!1Po&*UTM0hf zZ(7e!^{&PDu4p|x0fxLFk+?FV>pv=fVGZj=Ku_TFUnwAxK@l$ZoE7rgT+l7L)k>?CSkA zaV1^99FYMR+PYX8FD5Ao(o-dnYV-3{E2FAgAYDOGYU*Q4%lD$>Ut*XL4UhuWzJHB( zUR`dlHd5?OGQ;5oiY8euW(pCyy1ZD>3~M0y5_&(J5;}I@3a90tKLcO~+1)_M1tjbc zxZQLraIS}`^@hP2;7LBaH_tlKG>;4~N;8a^x~ z_(Y**f`n#|O@V`K9KOc)sAe%I3c3g&cCoRsvd4FZzQTWip7BIyQPA*`{bD9I0HY8W z5D<6^UJ$tz=+@wn5a2AvP-q!2Oc$@tmsU3=9qe)}b}asskdT0F^=D}beJfJd%zZ&+ z_%-0_04FCBEI_7khuVRi10v?4sQif-qNt>#Gmar4g>skgW>66I%5sRATwPdW@OZJ^ z9u*4Erx!^)z+S-8OnTQ-)w>15lPCW+uaFZK)@IWrQ$&Jstm8Y|Bu^FCKDjq}^p_L1 z^P;%3DTshCrvb}4<+o6Qy85QIiv{7??QSP9;r*^$DdA^CI|I=4OFx@+Tl{qxi3=7B z2YBPkQ!6#2unINijP&%Xm6=8w8XDz>s*dv|05k#h^>uKND^!a@9Eyy|%*;d?40!pO zH2S{!J6Z!++|$_5AQF5;N9PbQN=MSwKn6ix|FxygHQ9H*6U8nTJ89~jHH{e{k)cm{ z9P79jzYhS^g6h`S$LHCA{FAN;c6Rn;2s8uEnQvY(Ki#iRrkKRA)2UL3%F5OFuKn4w zi$8zv@ww`J8K>)5gC;L0S148izVAYhH_HV+YHE8>Efe2_T3-=7TR;zw3vDM;fY@f! z3>(nU!v>FaHFszb!er3E;?H#ba|I?(D=M1oiaO6@d^I^fj<-Um3gxM|49rJ8lQKqt zHqEelc(9v5*rGw!P(7KJw(^Cux@O$x>Qo+XzNl#Z`q?M&B9f;{n14r%8h>dnW;i!s z{;1r;o?AUO%f*4SY?BnTrrykcb}~hbBSh_?m1zt=qaNE((jM}*S}EYR0d$Wexqhki zoJ~nh6=kZRrS(w;tbnRz&}0WNQGG*0ob(w6kh)PxTy=gvyF$e=SX7zeR`&Eb?T^K0 z5$6c0%#tQk@N#HFs8pvrcX*%}u3K)oL!}qEI)q~7#l8(;189TLg(6tpHUZeroX{7P zlbH$8Y^)ciQ;i^I8RcMG1hlBxxVeK}2!8ibxS&J%@Zkd%IdgD;bG;LrFY#Z!4jel~ z<1r7P;Se_?>M}$T>m7?HaXrMu(9T%U>7+tf6HimAT7 z{uV@hoNF>SUo~)Xb?vNh&sTfsF+NKnc23L#cZ41mY%+iaim?jAmBuF*5$;A%5D27O z>7>C!qN1M>66ORE0bK;5gpMz-%r+;_-4P_;w9YsdTZlRvf=fgOerQ}T4N3ZYLi@F% zJ5N6gRDZ0sy!QW#cJAEy^URw!NA= zjVG_IJhI5whJ*OBAh3}l0V{^Qi4^l}ZYi5)iy=Gx3(+`Ck^*{4krSY z+}7SM!(0S;iJ@v&ge&$|ll2DD0)FOyZ|B&hrvNo9|NNPZ1$iy1{st#bVAXFx zMuw0c8@2<$Ct@NZuHr2(OWk=&AaTZJ6crXedup+kV-f>t6&q7I@Qlh;s{uZgK@vsL z1BM8N2=*{X0KDj~JSnDe@2fuWKT~ zxFxG?`F?`RlE8egtqdzS$IDNhI(i6qX$SQ#Y0WeiI>*UrQ3i3$f(bKXi?P0bK-q)l zeS7yZv9S36`q2(wuH;z*$sG3b4U>jnOj_oIgmz%KjvhVA_cP5RAM-2u*kb|wuk*WB zR#q?>#-tn9h?RRz8uS2@0vk=R8R}e_YbzJOg!nHtS^~8f!Aww5zM;oS7>OgH;81g zu=1ZRX9opoqb)Ku-9dZ9Vl+hZ*OiOx-|Ke<(g}`!Z_@NiP2=P}pogwHnIhAhQ zxDg}xZFB{Yx~{COM415!jPq`#9De^qBp3k@@Gj4RP)=Gtc;97y8do3>k!Sp9k6?wu+(Xv?7KYj z2%fqUwssV!j(8nhv3DIEi$hyvKx+YmL22Rh#g4d539uK$MoVmHG&fHql8NNyrKPIb zw~ClAc*`0B*F((+?NaegfW%lP3eRs)K=4&+&N-RAX}ge^`O`TxJZ`S8sxPMBBkRKS zdT{ev9Egko#Cm9~RjsZ5q)Nu3m_=+{K2TokgB5Nw`K1sqAn~wij{H~#cAL7YZpP1+ zpxcFRe08x-+0NFsbK*(>zeq5*ywhi-c z7qtTT+1S{i(gR$4X--ZE4$M=q)Lq08+D_o@o520CgRfvO!)jgQc+0#yg$N2CnUb8` z3-~7rHn+;~z3T;0&B8@wRH{fe%DL?9BW#+1YFJ-c=L)#Ff`ZrEgg@a)*ptG@^sEA_ z>%h<8Iq3DluBb&;oRPM%kZLi|mr1VFgCrG9g5aZ=Gz=On7Dl{aE5COyA$rU9;95H5Z!MBo z-2rFH!?~epu2EbDnKJ0v)7D0924IWN|B+fZ-K+Ll6%{z(o<%AZ-MiP(!GTpX($+LM zWw6Sr*eur~U-$4~Y?*~eh{^36^XBH}hDp0X1;|7tx$0$3Bv4*a(w#( zIbrK^*phnFIs$u8P-v@68No5}h>E(1ULNaPJ-cjgTBE{?;Io#Fuq7)B6O?sH*bt7CD4x6JF1I4lg^fA+AW<0wV&=uPGw0cF4aX<0~>6+I1= zIBa6#G5j_W#1`}^OVQF)N59CUO-VzU4Q>~{e+b}i%nY@#awGak+QJ;JPm;3#Dn1T+ zpLGQ})rTh_59vZ8lHJyo2@-H@0VR3uJ6zWmgb}OZbl<`i6cu6HD4S5F8bOlr<42+3 z6s6~P_!-OJu+lx$&+_r{!R!tTJ5k(H3tCwE-?2;92#JV~n1F&(f>B3%YwL?yB~3lC z#)ifyk>Htyh49eO<9O)kd>pyNh$A1w90ITLsZ(ezPk{r33CX*6?|OP9@*^T2#gZx5 zkJmg)r&{*(>FA}W4<0-~z8m|o4F3X^8dGro+PVfRxo>u6#_4mJ9?HYkRsog^^?S?% z_(?ol{(OVy3uCyMo{mr7Z@vcxhxpXzEfaeTdP3Ngv{zglrR5~(_R!YAEnAR|si19cuqW*r?Jn4ETZi*r`j z1*4Zbs-jYZt_m_IXz94OZ@(_;`P(9=Pa-g|adKjlSvpG1yu7zoQef|yj{wTf|!<}jUhDaV~Y)f z`;ntZ_wC#Fm!l*1&Yi$6qtYH?A10Dp*MubH?-6egdzN>-mbb!+7SK+kkEEMXY5Ecp z5^h~BD268|aSap_-?p_GN*u<&z=)fvswgXiO3`b@G->96k&&zx2U3^}cc@Vg>eWX@ zMNtD~>ra$WWj!Vo1q>vK2VII&Y5cK_k`lSpmX5YI+x@ZVBT(>kO@P@SKG8Dp2*RXx zZpx9>*+x0QQz2{wT)$phTf0X<05iv3yu2u1U95k{X_b8I0+UH#v2l=t`vmjChr@w15lms zjfue-=K|H>08n*@3dIImS~%){)c-I@%yQA|e_;a!1z}A^Ia?mHZ6M_su0KRggVG*c z%v9<_-HF5zGSp&qYo*qJ_etd1sXWJn;hM}g6i*p2ymTnBc@=x5#i>o(R^ zDrFChjqT*(;zBOmwrv|2MGjWT*i>t#K5DY`ZmoZ@?oZUOsD4F#{Qn96{rle^|M&0z rJpI2v{`cSidD_3P{_l^I3fDI11ZwnMIH&JTeG_C&9gRFStAPIj#_vb+ From 339c2599a44f82c177eec63c669d2025f88c539f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 29 Jul 2013 00:30:37 +0200 Subject: [PATCH 27/88] Hotfix: Fixed sdlog2 MATLAB export --- Tools/logconv.m | 534 +++++++++++++++++++++++++++++++++++++++++++ Tools/sdlog2_dump.py | 36 ++- 2 files changed, 564 insertions(+), 6 deletions(-) create mode 100644 Tools/logconv.m diff --git a/Tools/logconv.m b/Tools/logconv.m new file mode 100644 index 0000000000..f7c291b48c --- /dev/null +++ b/Tools/logconv.m @@ -0,0 +1,534 @@ +% This Matlab Script can be used to import the binary logged values of the +% PX4FMU into data that can be plotted and analyzed. + +%% ************************************************************************ +% PX4LOG_PLOTSCRIPT: Main function +% ************************************************************************ +function PX4Log_Plotscript + +% Clear everything +clc +clear all +close all + +% ************************************************************************ +% SETTINGS +% ************************************************************************ + +% Set the path to your sysvector.bin file here +filePath = 'log_second_flight.bin'; + +% Set the minimum and maximum times to plot here [in seconds] +mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] +maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] + +%Determine which data to plot. Not completely implemented yet. +bDisplayGPS=true; + +%conversion factors +fconv_gpsalt=1; %[mm] to [m] +fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] +fconv_timestamp=1E-6; % [microseconds] to [seconds] + +% ************************************************************************ +% Import the PX4 logs +% ************************************************************************ +ImportPX4LogData(); + +%Translate min and max plot times to indices +time=double(sysvector.TIME_StartTime) .*fconv_timestamp; +mintime_log=time(1); %The minimum time/timestamp found in the log +maxtime_log=time(end); %The maximum time/timestamp found in the log +CurTime=mintime_log; %The current time at which to draw the aircraft position + +[imintime,imaxtime]=FindMinMaxTimeIndices(); + +% ************************************************************************ +% PLOT & GUI SETUP +% ************************************************************************ +NrFigures=5; +NrAxes=10; +h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively +h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively +h.pathpoints=[]; % Temporary initiliazation of path points + +% Setup the GUI to control the plots +InitControlGUI(); +% Setup the plotting-GUI (figures, axes) itself. +InitPlotGUI(); + +% ************************************************************************ +% DRAW EVERYTHING +% ************************************************************************ +DrawRawData(); +DrawCurrentAircraftState(); + +%% ************************************************************************ +% *** END OF MAIN SCRIPT *** +% NESTED FUNCTION DEFINTIONS FROM HERE ON +% ************************************************************************ + + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +function ImportPX4LogData() + + % ************************************************************************ + % RETRIEVE SYSTEM VECTOR + % ************************************************************************* + % //All measurements in NED frame + + % Convert to CSV + %arg1 = 'log-fx61-20130721-2.bin'; + arg1 = filePath; + delim = ','; + time_field = 'TIME'; + data_file = 'data.csv'; + csv_null = ''; + + if not(exist(data_file, 'file')) + s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); + end + + if exist(data_file, 'file') + + %data = csvread(data_file); + sysvector = tdfread(data_file, ','); + + % shot the flight time + time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); + time_s = uint64(time_us*1e-6); + time_m = uint64(time_s/60); + + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]); + + disp(['logfile conversion finished.' char(10)]); + else + disp(['file: ' data_file ' does not exist' char(10)]); + end +end + +%% ************************************************************************ +% INITCONTROLGUI (nested function) +% ************************************************************************ +%Setup central control GUI components to control current time where data is shown +function InitControlGUI() + %********************************************************************** + % GUI size definitions + %********************************************************************** + dxy=5; %margins + %Panel: Plotctrl + dlabels=120; + dsliders=200; + dedits=80; + hslider=20; + + hpanel1=40; %panel1 + hpanel2=220;%panel2 + hpanel3=3*hslider+4*dxy+3*dxy;%panel3. + + width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width + height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height + + %********************************************************************** + % Create GUI + %********************************************************************** + h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); + h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); + h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); + h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); + + %%Control GUI-elements + %Slider: Current time + h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... + 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); + temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); + set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); + h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... + 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); + + %Slider: MaxTime + h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %Slider: MinTime + h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %%Current data/state GUI-elements (Multiline-edit-box) + h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... + 'HorizontalAlignment','left','parent',h.aircraftstatepanel); + + h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... + 'HorizontalAlignment','left','parent',h.guistatepanel); + +end + +%% ************************************************************************ +% INITPLOTGUI (nested function) +% ************************************************************************ +function InitPlotGUI() + + % Setup handles to lines and text + h.markertext=[]; + templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array + h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively + h.markerline(1:NrAxes)=0.0; + + % Setup all other figures and axes for plotting + % PLOT WINDOW 1: GPS POSITION + h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); + h.axes(1)=axes(); + set(h.axes(1),'Parent',h.figures(2)); + + % PLOT WINDOW 2: IMU, baro altitude + h.figures(3)=figure('Name', 'IMU / Baro Altitude'); + h.axes(2)=subplot(4,1,1); + h.axes(3)=subplot(4,1,2); + h.axes(4)=subplot(4,1,3); + h.axes(5)=subplot(4,1,4); + set(h.axes(2:5),'Parent',h.figures(3)); + + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); + h.axes(6)=subplot(4,1,1); + h.axes(7)=subplot(4,1,2); + h.axes(8)=subplot(4,1,3); + h.axes(9)=subplot(4,1,4); + set(h.axes(6:9),'Parent',h.figures(4)); + + % PLOT WINDOW 4: LOG STATS + h.figures(5) = figure('Name', 'Log Statistics'); + h.axes(10)=subplot(1,1,1); + set(h.axes(10:10),'Parent',h.figures(5)); + +end + +%% ************************************************************************ +% DRAWRAWDATA (nested function) +% ************************************************************************ +%Draws the raw data from the sysvector, but does not add any +%marker-lines or so +function DrawRawData() + % ************************************************************************ + % PLOT WINDOW 1: GPS POSITION & GUI + % ************************************************************************ + figure(h.figures(2)); + % Only plot GPS data if available + if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) + %Draw data + plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); + title(h.axes(1),'GPS Position Data(if available)'); + xlabel(h.axes(1),'Latitude [deg]'); + ylabel(h.axes(1),'Longitude [deg]'); + zlabel(h.axes(1),'Altitude above MSL [m]'); + grid on + + %Reset path + h.pathpoints=0; + end + + % ************************************************************************ + % PLOT WINDOW 2: IMU, baro altitude + % ************************************************************************ + figure(h.figures(3)); + plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); + title(h.axes(2),'Magnetometers [Gauss]'); + legend(h.axes(2),'x','y','z'); + plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); + title(h.axes(3),'Accelerometers [m/s²]'); + legend(h.axes(3),'x','y','z'); + plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); + title(h.axes(4),'Gyroscopes [rad/s]'); + legend(h.axes(4),'x','y','z'); + plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); + if(bDisplayGPS) + hold on; + plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); + hold off + legend('Barometric Altitude [m]','GPS Altitude [m]'); + else + legend('Barometric Altitude [m]'); + end + title(h.axes(5),'Altitude above MSL [m]'); + + % ************************************************************************ + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + % ************************************************************************ + figure(h.figures(4)); + %Attitude Estimate + plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); + title(h.axes(6),'Estimated attitude [deg]'); + legend(h.axes(6),'roll','pitch','yaw'); + %Actuator Controls + plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); + title(h.axes(7),'Actuator control [-]'); + legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); + %Actuator Controls + plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); + title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); + legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); + set(h.axes(8), 'YLim',[800 2200]); + %Airspeeds + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); + hold on + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); + hold off + %add GPS total airspeed here + title(h.axes(9),'Airspeed [m/s]'); + legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); + %calculate time differences and plot them + intervals = zeros(0,imaxtime - imintime); + for k = imintime+1:imaxtime + intervals(k) = time(k) - time(k-1); + end + plot(h.axes(10), time(imintime:imaxtime), intervals); + + %Set same timescale for all plots + for i=2:NrAxes + set(h.axes(i),'XLim',[mintime maxtime]); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% DRAWCURRENTAIRCRAFTSTATE(nested function) +% ************************************************************************ +function DrawCurrentAircraftState() + %find current data index + i=find(time>=CurTime,1,'first'); + + %********************************************************************** + % Current aircraft state label update + %********************************************************************** + acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... + 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... + 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... + ', y=',num2str(sysvector.IMU_MagY(i)),... + ', z=',num2str(sysvector.IMU_MagZ(i)),']']; + acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... + ', y=',num2str(sysvector.IMU_AccY(i)),... + ', z=',num2str(sysvector.IMU_AccZ(i)),']']; + acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... + ', y=',num2str(sysvector.IMU_GyroY(i)),... + ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; + acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... + ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... + ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; + acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); + %for j=1:4 + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; + %end + acstate{7,:}=[acstate{7,:},']']; + acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); + %for j=1:8 + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; + %end + acstate{8,:}=[acstate{8,:},']']; + acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; + + set(h.edits.AircraftState,'String',acstate); + + %********************************************************************** + % GPS Plot Update + %********************************************************************** + %Plot traveled path, and and time. + figure(h.figures(2)); + hold on; + if(CurTime>mintime+1) %the +1 is only a small bugfix + h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); + end; + hold off + %Plot current position + newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; + if(numel(h.pathpoints)<=3) %empty path + h.pathpoints(1,1:3)=newpoint; + else %Not empty, append new point + h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; + end + axes(h.axes(1)); + line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); + + + % Plot current time (small label next to current gps position) + textdesc=strcat(' t=',num2str(time(i)),'s'); + if(isvalidhandle(h.markertext)) + delete(h.markertext); %delete old text + end + h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... + double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); + set(h.edits.CurTime,'String',CurTime); + + %********************************************************************** + % Plot the lines showing the current time in the 2-d plots + %********************************************************************** + for i=2:NrAxes + if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end + ylims=get(h.axes(i),'YLim'); + h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); + set(h.markerline(i),'parent',h.axes(i)); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% MINMAXTIME CALLBACK (nested function) +% ************************************************************************ +function minmaxtime_callback(hObj,event) %#ok + new_mintime=get(h.sliders.MinTime,'Value'); + new_maxtime=get(h.sliders.MaxTime,'Value'); + + %Safety checks: + bErr=false; + %1: mintime must be < maxtime + if((new_mintime>maxtime) || (new_maxtimeCurTime) + set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); + mintime=new_mintime; + CurTime=mintime; + bErr=true; + end + %3: MaxTime must be >CurTime + if(new_maxtime + %find current time + if(hObj==h.sliders.CurTime) + CurTime=get(h.sliders.CurTime,'Value'); + elseif (hObj==h.edits.CurTime) + temp=str2num(get(h.edits.CurTime,'String')); + if(tempmintime) + CurTime=temp; + else + %Error + set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); + end + else + %Error + set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); + end + + set(h.sliders.CurTime,'Value',CurTime); + set(h.edits.CurTime,'String',num2str(CurTime)); + + %Redraw time markers, but don't have to redraw the whole raw data + DrawCurrentAircraftState(); +end + +%% ************************************************************************ +% FINDMINMAXINDICES (nested function) +% ************************************************************************ +function [idxmin,idxmax] = FindMinMaxTimeIndices() + for i=1:size(sysvector.TIME_StartTime,1) + if time(i)>=mintime; idxmin=i; break; end + end + for i=1:size(sysvector.TIME_StartTime,1) + if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end + if time(i)>=maxtime; idxmax=i; break; end + end + mintime=time(idxmin); + maxtime=time(idxmax); +end + +%% ************************************************************************ +% ISVALIDHANDLE (nested function) +% ************************************************************************ +function isvalid = isvalidhandle(handle) + if(exist(varname(handle))>0 && length(ishandle(handle))>0) + if(ishandle(handle)>0) + if(handle>0.0) + isvalid=true; + return; + end + end + end + isvalid=false; +end + +%% ************************************************************************ +% JUST SOME SMALL HELPER FUNCTIONS (nested function) +% ************************************************************************ +function out = varname(var) + out = inputname(1); +end + +%This is the end of the matlab file / the main function +end diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 318f72971f..ebc04f4d03 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -55,6 +55,8 @@ class SDLog2Parser: __time_msg = None __debug_out = False __correct_errors = False + __file_name = None + __file = None def __init__(self): return @@ -87,6 +89,14 @@ class SDLog2Parser: def setCorrectErrors(self, correct_errors): self.__correct_errors = correct_errors + + def setFileName(self, file_name): + self.__file_name = file_name + if file_name != None: + self.__file = open(file_name, 'w+') + else: + self.__file = None + def process(self, fn): self.reset() @@ -154,10 +164,13 @@ class SDLog2Parser: show_fields = self.__msg_labels.get(msg_name, []) self.__msg_filter_map[msg_name] = show_fields for field in show_fields: - full_label = msg_name + "." + field + full_label = msg_name + "_" + field self.__csv_columns.append(full_label) self.__csv_data[full_label] = None - print self.__csv_delim.join(self.__csv_columns) + if self.__file != None: + print >> self.__file, self.__csv_delim.join(self.__csv_columns) + else: + print self.__csv_delim.join(self.__csv_columns) def __printCSVRow(self): s = [] @@ -168,7 +181,11 @@ class SDLog2Parser: else: v = str(v) s.append(v) - print self.__csv_delim.join(s) + + if self.__file != None: + print >> self.__file, self.__csv_delim.join(s) + else: + print self.__csv_delim.join(s) def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) @@ -224,7 +241,7 @@ class SDLog2Parser: for i in xrange(len(data)): label = msg_labels[i] if label in show_fields: - self.__csv_data[msg_name + "." + label] = data[i] + self.__csv_data[msg_name + "_" + label] = data[i] if self.__time_msg != None and msg_name != self.__time_msg: self.__csv_updated = True if self.__time_msg == None: @@ -240,6 +257,7 @@ def _main(): print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" + print "\t-fPrint to file instead of stdout" return fn = sys.argv[1] debug_out = False @@ -247,7 +265,8 @@ def _main(): msg_filter = [] csv_null = "" csv_delim = "," - time_msg = None + time_msg = "TIME" + file_name = None opt = None for arg in sys.argv[2:]: if opt != None: @@ -257,9 +276,11 @@ def _main(): csv_null = arg elif opt == "t": time_msg = arg + elif opt == "f": + file_name = arg elif opt == "m": show_fields = "*" - a = arg.split(".") + a = arg.split("_") if len(a) > 1: show_fields = a[1].split(",") msg_filter.append((a[0], show_fields)) @@ -277,6 +298,8 @@ def _main(): opt = "m" elif arg == "-t": opt = "t" + elif arg == "-f": + opt = "f" if csv_delim == "\\t": csv_delim = "\t" @@ -285,6 +308,7 @@ def _main(): parser.setCSVNull(csv_null) parser.setMsgFilter(msg_filter) parser.setTimeMsg(time_msg) + parser.setFileName(file_name) parser.setDebugOut(debug_out) parser.setCorrectErrors(correct_errors) parser.process(fn) From dc542b2a4818bfc1c3c1cd24c5ee513d5b5ea0c4 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 22:27:05 -0400 Subject: [PATCH 28/88] Segway stabilized. --- src/drivers/md25/md25.cpp | 17 +++-- src/drivers/md25/md25.hpp | 13 ++++ src/drivers/md25/md25_main.cpp | 27 +++++++- src/modules/controllib/uorb/blocks.cpp | 37 ++++++++++ src/modules/controllib/uorb/blocks.hpp | 23 +++++++ src/modules/fixedwing_backside/fixedwing.cpp | 37 ---------- src/modules/fixedwing_backside/fixedwing.hpp | 23 ------- src/modules/segway/BlockSegwayController.cpp | 19 +++--- src/modules/segway/BlockSegwayController.hpp | 13 +++- src/modules/segway/params.c | 72 ++------------------ src/modules/segway/segway_main.cpp | 22 +----- 11 files changed, 138 insertions(+), 165 deletions(-) diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp index d6dd64a094..d43e3aef9e 100644 --- a/src/drivers/md25/md25.cpp +++ b/src/drivers/md25/md25.cpp @@ -116,7 +116,8 @@ MD25::MD25(const char *deviceName, int bus, setMotor2Speed(0); resetEncoders(); _setMode(MD25::MODE_UNSIGNED_SPEED); - setSpeedRegulation(true); + setSpeedRegulation(false); + setMotorAccel(10); setTimeout(true); } @@ -308,6 +309,12 @@ int MD25::setDeviceAddress(uint8_t address) return OK; } +int MD25::setMotorAccel(uint8_t accel) +{ + return _writeUint8(REG_ACCEL_RATE_RW, + accel); +} + int MD25::setMotor1Speed(float value) { return _writeUint8(REG_SPEED1_RW, @@ -461,12 +468,12 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address) MD25 md25("/dev/md25", bus, address); // print status - char buf[200]; + char buf[400]; md25.status(buf, sizeof(buf)); printf("%s\n", buf); // setup for test - md25.setSpeedRegulation(true); + md25.setSpeedRegulation(false); md25.setTimeout(true); float dt = 0.1; float speed = 0.2; @@ -568,12 +575,12 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu MD25 md25("/dev/md25", bus, address); // print status - char buf[200]; + char buf[400]; md25.status(buf, sizeof(buf)); printf("%s\n", buf); // setup for test - md25.setSpeedRegulation(true); + md25.setSpeedRegulation(false); md25.setTimeout(true); float dt = 0.01; float t_final = 60.0; diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp index 780978514e..1661f67f9a 100644 --- a/src/drivers/md25/md25.hpp +++ b/src/drivers/md25/md25.hpp @@ -212,6 +212,19 @@ public: */ int setDeviceAddress(uint8_t address); + /** + * set motor acceleration + * @param accel + * controls motor speed change (1-10) + * accel rate | time for full fwd. to full rev. + * 1 | 6.375 s + * 2 | 1.6 s + * 3 | 0.675 s + * 5(default) | 1.275 s + * 10 | 0.65 s + */ + int setMotorAccel(uint8_t accel); + /** * set motor 1 speed * @param normSpeed normalize speed between -1 and 1 diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 3260705c1c..7e5904d050 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -82,7 +82,7 @@ usage(const char *reason) if (reason) fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n"); + fprintf(stderr, "usage: md25 {start|stop|read|status|search|test|change_address}\n\n"); exit(1); } @@ -184,6 +184,29 @@ int md25_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "read")) { + if (argc < 4) { + printf("usage: md25 read bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + MD25 md25(deviceName, bus, address); + + // print status + char buf[400]; + md25.status(buf, sizeof(buf)); + printf("%s\n", buf); + + exit(0); + } + + if (!strcmp(argv[1], "search")) { if (argc < 3) { printf("usage: md25 search bus\n"); @@ -268,7 +291,7 @@ int md25_thread_main(int argc, char *argv[]) uint8_t address = strtoul(argv[4], nullptr, 0); // start - MD25 md25("/dev/md25", bus, address); + MD25 md25(deviceName, bus, address); thread_running = true; diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp index 6e5ade5199..448a42a996 100644 --- a/src/modules/controllib/uorb/blocks.cpp +++ b/src/modules/controllib/uorb/blocks.cpp @@ -42,6 +42,43 @@ namespace control { +BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) : + SuperBlock(parent, name), + _xtYawLimit(this, "XT2YAW"), + _xt2Yaw(this, "XT2YAW"), + _psiCmd(0) +{ +} + +BlockWaypointGuidance::~BlockWaypointGuidance() {}; + +void BlockWaypointGuidance::update(vehicle_global_position_s &pos, + vehicle_attitude_s &att, + vehicle_global_position_setpoint_s &posCmd, + vehicle_global_position_setpoint_s &lastPosCmd) +{ + + // heading to waypoint + float psiTrack = get_bearing_to_next_waypoint( + (double)pos.lat / (double)1e7d, + (double)pos.lon / (double)1e7d, + (double)posCmd.lat / (double)1e7d, + (double)posCmd.lon / (double)1e7d); + + // cross track + struct crosstrack_error_s xtrackError; + get_distance_to_line(&xtrackError, + (double)pos.lat / (double)1e7d, + (double)pos.lon / (double)1e7d, + (double)lastPosCmd.lat / (double)1e7d, + (double)lastPosCmd.lon / (double)1e7d, + (double)posCmd.lat / (double)1e7d, + (double)posCmd.lon / (double)1e7d); + + _psiCmd = _wrap_2pi(psiTrack - + _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); +} + BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) : SuperBlock(parent, name), // subscriptions diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp index 54f31735ce..9c0720aa5e 100644 --- a/src/modules/controllib/uorb/blocks.hpp +++ b/src/modules/controllib/uorb/blocks.hpp @@ -57,6 +57,10 @@ #include #include +extern "C" { +#include +} + #include "../blocks.hpp" #include "UOrbSubscription.hpp" #include "UOrbPublication.hpp" @@ -64,6 +68,25 @@ namespace control { +/** + * Waypoint Guidance block + */ +class __EXPORT BlockWaypointGuidance : public SuperBlock +{ +private: + BlockLimitSym _xtYawLimit; + BlockP _xt2Yaw; + float _psiCmd; +public: + BlockWaypointGuidance(SuperBlock *parent, const char *name); + virtual ~BlockWaypointGuidance(); + void update(vehicle_global_position_s &pos, + vehicle_attitude_s &att, + vehicle_global_position_setpoint_s &posCmd, + vehicle_global_position_setpoint_s &lastPosCmd); + float getPsiCmd() { return _psiCmd; } +}; + /** * UorbEnabledAutopilot */ diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp index d5dc746e0d..f655a13bd7 100644 --- a/src/modules/fixedwing_backside/fixedwing.cpp +++ b/src/modules/fixedwing_backside/fixedwing.cpp @@ -86,43 +86,6 @@ void BlockStabilization::update(float pCmd, float qCmd, float rCmd, _yawDamper.update(rCmd, r, outputScale); } -BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) : - SuperBlock(parent, name), - _xtYawLimit(this, "XT2YAW"), - _xt2Yaw(this, "XT2YAW"), - _psiCmd(0) -{ -} - -BlockWaypointGuidance::~BlockWaypointGuidance() {}; - -void BlockWaypointGuidance::update(vehicle_global_position_s &pos, - vehicle_attitude_s &att, - vehicle_global_position_setpoint_s &posCmd, - vehicle_global_position_setpoint_s &lastPosCmd) -{ - - // heading to waypoint - float psiTrack = get_bearing_to_next_waypoint( - (double)pos.lat / (double)1e7d, - (double)pos.lon / (double)1e7d, - (double)posCmd.lat / (double)1e7d, - (double)posCmd.lon / (double)1e7d); - - // cross track - struct crosstrack_error_s xtrackError; - get_distance_to_line(&xtrackError, - (double)pos.lat / (double)1e7d, - (double)pos.lon / (double)1e7d, - (double)lastPosCmd.lat / (double)1e7d, - (double)lastPosCmd.lon / (double)1e7d, - (double)posCmd.lat / (double)1e7d, - (double)posCmd.lon / (double)1e7d); - - _psiCmd = _wrap_2pi(psiTrack - - _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance))); -} - BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) : BlockUorbEnabledAutopilot(parent, name), _stabilization(this, ""), // no name needed, already unique diff --git a/src/modules/fixedwing_backside/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp index eb5d383810..3876e46301 100644 --- a/src/modules/fixedwing_backside/fixedwing.hpp +++ b/src/modules/fixedwing_backside/fixedwing.hpp @@ -42,10 +42,6 @@ #include #include -extern "C" { -#include -} - namespace control { @@ -231,25 +227,6 @@ public: * than frontside at high speeds. */ -/** - * Waypoint Guidance block - */ -class __EXPORT BlockWaypointGuidance : public SuperBlock -{ -private: - BlockLimitSym _xtYawLimit; - BlockP _xt2Yaw; - float _psiCmd; -public: - BlockWaypointGuidance(SuperBlock *parent, const char *name); - virtual ~BlockWaypointGuidance(); - void update(vehicle_global_position_s &pos, - vehicle_attitude_s &att, - vehicle_global_position_setpoint_s &posCmd, - vehicle_global_position_setpoint_s &lastPosCmd); - float getPsiCmd() { return _psiCmd; } -}; - /** * Multi-mode Autopilot */ diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp index b7a0bbbccb..682758a14b 100644 --- a/src/modules/segway/BlockSegwayController.cpp +++ b/src/modules/segway/BlockSegwayController.cpp @@ -30,23 +30,24 @@ void BlockSegwayController::update() { // update guidance } - // XXX handle STABILIZED (loiter on spot) as well - // once the system switches from manual or auto to stabilized - // the setpoint should update to loitering around this position + // compute speed command + float spdCmd = -theta2spd.update(_att.pitch) - q2spd.update(_att.pitchspeed); // handle autopilot modes if (_status.state_machine == SYSTEM_STATE_AUTO || _status.state_machine == SYSTEM_STATE_STABILIZED) { - - float spdCmd = phi2spd.update(_att.phi); - - // output _actuators.control[0] = spdCmd; _actuators.control[1] = spdCmd; } else if (_status.state_machine == SYSTEM_STATE_MANUAL) { - _actuators.control[0] = _manual.roll; - _actuators.control[1] = _manual.roll; + if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) { + _actuators.control[CH_LEFT] = _manual.throttle; + _actuators.control[CH_RIGHT] = _manual.pitch; + + } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { + _actuators.control[0] = spdCmd; + _actuators.control[1] = spdCmd; + } } // update all publications diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp index b16d38338b..e2faa49169 100644 --- a/src/modules/segway/BlockSegwayController.hpp +++ b/src/modules/segway/BlockSegwayController.hpp @@ -8,11 +8,20 @@ class BlockSegwayController : public control::BlockUorbEnabledAutopilot { public: BlockSegwayController() : BlockUorbEnabledAutopilot(NULL,"SEG"), - phi2spd(this, "PHI2SPD") + theta2spd(this, "THETA2SPD"), + q2spd(this, "Q2SPD"), + _attPoll(), + _timeStamp(0) { + _attPoll.fd = _att.getHandle(); + _attPoll.events = POLLIN; } void update(); private: - BlockP phi2spd; + enum {CH_LEFT, CH_RIGHT}; + BlockPI theta2spd; + BlockP q2spd; + struct pollfd _attPoll; + uint64_t _timeStamp; }; diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c index db30af4160..1669785d31 100644 --- a/src/modules/segway/params.c +++ b/src/modules/segway/params.c @@ -1,72 +1,8 @@ #include -// currently tuned for easystar from arkhangar in HIL -//https://github.com/arktools/arkhangar - // 16 is max name length +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_P, 10.0f); // pitch to speed +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I, 0.0f); // pitch integral to speed +PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I_MAX, 0.0f); // integral limiter +PARAM_DEFINE_FLOAT(SEG_Q2SPD, 1.0f); // pitch rate to speed -// gyro low pass filter -PARAM_DEFINE_FLOAT(FWB_P_LP, 300.0f); // roll rate low pass cut freq -PARAM_DEFINE_FLOAT(FWB_Q_LP, 300.0f); // pitch rate low pass cut freq -PARAM_DEFINE_FLOAT(FWB_R_LP, 300.0f); // yaw rate low pass cut freq - -// yaw washout -PARAM_DEFINE_FLOAT(FWB_R_HP, 1.0f); // yaw rate high pass - -// stabilization mode -PARAM_DEFINE_FLOAT(FWB_P2AIL, 0.3f); // roll rate 2 aileron -PARAM_DEFINE_FLOAT(FWB_Q2ELV, 0.1f); // pitch rate 2 elevator -PARAM_DEFINE_FLOAT(FWB_R2RDR, 0.1f); // yaw rate 2 rudder - -// psi -> phi -> p -PARAM_DEFINE_FLOAT(FWB_PSI2PHI, 0.5f); // heading 2 roll -PARAM_DEFINE_FLOAT(FWB_PHI2P, 1.0f); // roll to roll rate -PARAM_DEFINE_FLOAT(FWB_PHI_LIM_MAX, 0.3f); // roll limit, 28 deg - -// velocity -> theta -PARAM_DEFINE_FLOAT(FWB_V2THE_P, 1.0f); // velocity to pitch angle PID, prop gain -PARAM_DEFINE_FLOAT(FWB_V2THE_I, 0.0f); // integral gain -PARAM_DEFINE_FLOAT(FWB_V2THE_D, 0.0f); // derivative gain -PARAM_DEFINE_FLOAT(FWB_V2THE_D_LP, 0.0f); // derivative low-pass -PARAM_DEFINE_FLOAT(FWB_V2THE_I_MAX, 0.0f); // integrator wind up guard -PARAM_DEFINE_FLOAT(FWB_THE_MIN, -0.5f); // the max commanded pitch angle -PARAM_DEFINE_FLOAT(FWB_THE_MAX, 0.5f); // the min commanded pitch angle - - -// theta -> q -PARAM_DEFINE_FLOAT(FWB_THE2Q_P, 1.0f); // pitch angle to pitch-rate PID -PARAM_DEFINE_FLOAT(FWB_THE2Q_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_THE2Q_I_MAX, 0.0f); - -// h -> thr -PARAM_DEFINE_FLOAT(FWB_H2THR_P, 0.01f); // altitude to throttle PID -PARAM_DEFINE_FLOAT(FWB_H2THR_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_H2THR_I_MAX, 0.0f); - -// crosstrack -PARAM_DEFINE_FLOAT(FWB_XT2YAW_MAX, 1.57f); // cross-track to yaw angle limit 90 deg -PARAM_DEFINE_FLOAT(FWB_XT2YAW, 0.005f); // cross-track to yaw angle gain - -// speed command -PARAM_DEFINE_FLOAT(FWB_V_MIN, 10.0f); // minimum commanded velocity -PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity -PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity - -// rate of climb -// this is what rate of climb is commanded (in m/s) -// when the pitch stick is fully defelcted in simple mode -PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f); - -// climb rate -> thr -PARAM_DEFINE_FLOAT(FWB_CR2THR_P, 0.01f); // rate of climb to throttle PID -PARAM_DEFINE_FLOAT(FWB_CR2THR_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_CR2THR_I_MAX, 0.0f); - -PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) -PARAM_DEFINE_FLOAT(FWB_TRIM_V, 12.0f); // trim velocity, m/s diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp index 8be1cc7aaf..061fbf9b9d 100644 --- a/src/modules/segway/segway_main.cpp +++ b/src/modules/segway/segway_main.cpp @@ -64,12 +64,7 @@ extern "C" __EXPORT int segway_main(int argc, char *argv[]); /** * Mainloop of deamon. */ -int control_demo_thread_main(int argc, char *argv[]); - -/** - * Test function - */ -void test(); +int segway_thread_main(int argc, char *argv[]); /** * Print the correct usage. @@ -114,16 +109,11 @@ int segway_main(int argc, char *argv[]) SCHED_DEFAULT, SCHED_PRIORITY_MAX - 10, 5120, - control_demo_thread_main, + segway_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } - if (!strcmp(argv[1], "test")) { - test(); - exit(0); - } - if (!strcmp(argv[1], "stop")) { thread_should_exit = true; exit(0); @@ -144,7 +134,7 @@ int segway_main(int argc, char *argv[]) exit(1); } -int control_demo_thread_main(int argc, char *argv[]) +int segway_thread_main(int argc, char *argv[]) { warnx("starting"); @@ -165,9 +155,3 @@ int control_demo_thread_main(int argc, char *argv[]) return 0; } - -void test() -{ - warnx("beginning control lib test"); - control::basicBlocksTest(); -} From a569cd834c13052ef3210ab9b8c1afd03b81fef6 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 28 Jul 2013 22:28:04 -0400 Subject: [PATCH 29/88] Added segway rc script. --- ROMFS/px4fmu_common/init.d/40_io_segway | 122 ++++++++++++++++++++++++ 1 file changed, 122 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/40_io_segway diff --git a/ROMFS/px4fmu_common/init.d/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway new file mode 100644 index 0000000000..5742d685aa --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/40_io_segway @@ -0,0 +1,122 @@ +#!nsh +# +# Flight startup script for PX4FMU+PX4IO +# + +# disable USB and autostart +set USB no +set MODE custom + +# +# Start the ORB (first app to start) +# +uorb start + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/params +if [ -f /fs/microsd/params ] +then + param load /fs/microsd/params +fi + +# +# Load default params for this platform +# +if param compare SYS_AUTOCONFIG 1 +then + # Set all params here, then disable autoconfig + param set SYS_AUTOCONFIG 0 + param save /fs/microsd/params +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor +# see https://pixhawk.ethz.ch/mavlink/ +# +param set MAV_TYPE 10 + +# +# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) +# +if [ -f /fs/microsd/px4io.bin ] +then + echo "PX4IO Firmware found. Checking Upgrade.." + if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + then + echo "No newer version, skipping upgrade." + else + echo "Loading /fs/microsd/px4io.bin" + if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log + then + cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log + else + echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log + echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" + fi + fi +fi + +# +# Start MAVLink (depends on orb) +# +mavlink start -d /dev/ttyS1 -b 57600 +usleep 5000 + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# Start PX4IO interface (depends on orb, commander) +# +px4io start + +# +# Allow PX4IO to recover from midair restarts. +# this is very unlikely, but quite safe and robust. +px4io recovery + +# +# Disable px4io topic limiting +# +px4io limit 200 + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# Start GPS interface (depends on orb) +# +gps start + +# +# Start the attitude estimator (depends on orb) +# +attitude_estimator_ekf start + +# +# Load mixer and start controllers (depends on px4io) +# +md25 start 3 0x58 +segway start + +# +# Start logging +# +sdlog2 start -r 50 -a -b 14 + +# +# Start system state +# +if blinkm start +then + blinkm systemstate +fi From db527ee88139ef470007f82675b57ec313cdc495 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 29 Jul 2013 11:00:36 +0200 Subject: [PATCH 30/88] Removed unused code --- src/systemcmds/config/config.c | 213 --------------------------------- 1 file changed, 213 deletions(-) diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c index c4b03bbff6..2dad2261b5 100644 --- a/src/systemcmds/config/config.c +++ b/src/systemcmds/config/config.c @@ -198,216 +198,3 @@ do_accel(int argc, char *argv[]) exit(0); } - -// static void -// do_load(const char* param_file_name) -// { -// int fd = open(param_file_name, O_RDONLY); - -// if (fd < 0) -// err(1, "open '%s'", param_file_name); - -// int result = param_load(fd); -// close(fd); - -// if (result < 0) { -// errx(1, "error importing from '%s'", param_file_name); -// } - -// exit(0); -// } - -// static void -// do_import(const char* param_file_name) -// { -// int fd = open(param_file_name, O_RDONLY); - -// if (fd < 0) -// err(1, "open '%s'", param_file_name); - -// int result = param_import(fd); -// close(fd); - -// if (result < 0) -// errx(1, "error importing from '%s'", param_file_name); - -// exit(0); -// } - -// static void -// do_show(const char* search_string) -// { -// printf(" + = saved, * = unsaved\n"); -// param_foreach(do_show_print, search_string, false); - -// exit(0); -// } - -// static void -// do_show_print(void *arg, param_t param) -// { -// int32_t i; -// float f; -// const char *search_string = (const char*)arg; - -// /* print nothing if search string is invalid and not matching */ -// if (!(arg == NULL || (!strcmp(search_string, param_name(param))))) { -// /* param not found */ -// return; -// } - -// printf("%c %s: ", -// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), -// param_name(param)); - -// /* -// * This case can be expanded to handle printing common structure types. -// */ - -// switch (param_type(param)) { -// case PARAM_TYPE_INT32: -// if (!param_get(param, &i)) { -// printf("%d\n", i); -// return; -// } - -// break; - -// case PARAM_TYPE_FLOAT: -// if (!param_get(param, &f)) { -// printf("%4.4f\n", (double)f); -// return; -// } - -// break; - -// case PARAM_TYPE_STRUCT ... PARAM_TYPE_STRUCT_MAX: -// printf("\n", 0 + param_type(param), param_size(param)); -// return; - -// default: -// printf("\n", 0 + param_type(param)); -// return; -// } - -// printf("\n", param); -// } - -// static void -// do_set(const char* name, const char* val) -// { -// int32_t i; -// float f; -// param_t param = param_find(name); - -// /* set nothing if parameter cannot be found */ -// if (param == PARAM_INVALID) { -// param not found -// errx(1, "Error: Parameter %s not found.", name); -// } - -// printf("%c %s: ", -// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), -// param_name(param)); - -// /* -// * Set parameter if type is known and conversion from string to value turns out fine -// */ - -// switch (param_type(param)) { -// case PARAM_TYPE_INT32: -// if (!param_get(param, &i)) { -// printf("curr: %d", i); - -// /* convert string */ -// char* end; -// i = strtol(val,&end,10); -// param_set(param, &i); -// printf(" -> new: %d\n", i); - -// } - -// break; - -// case PARAM_TYPE_FLOAT: -// if (!param_get(param, &f)) { -// printf("curr: %4.4f", (double)f); - -// /* convert string */ -// char* end; -// f = strtod(val,&end); -// param_set(param, &f); -// printf(" -> new: %f\n", f); - -// } - -// break; - -// default: -// errx(1, "\n", 0 + param_type(param)); -// } - -// exit(0); -// } - -// static void -// do_compare(const char* name, const char* val) -// { -// int32_t i; -// float f; -// param_t param = param_find(name); - -// /* set nothing if parameter cannot be found */ -// if (param == PARAM_INVALID) { -// /* param not found */ -// errx(1, "Error: Parameter %s not found.", name); -// } - -// /* -// * Set parameter if type is known and conversion from string to value turns out fine -// */ - -// int ret = 1; - -// switch (param_type(param)) { -// case PARAM_TYPE_INT32: -// if (!param_get(param, &i)) { - -// /* convert string */ -// char* end; -// int j = strtol(val,&end,10); -// if (i == j) { -// printf(" %d: ", i); -// ret = 0; -// } - -// } - -// break; - -// case PARAM_TYPE_FLOAT: -// if (!param_get(param, &f)) { - -// /* convert string */ -// char* end; -// float g = strtod(val, &end); -// if (fabsf(f - g) < 1e-7f) { -// printf(" %4.4f: ", (double)f); -// ret = 0; -// } -// } - -// break; - -// default: -// errx(1, "\n", 0 + param_type(param)); -// } - -// if (ret == 0) { -// printf("%c %s: equal\n", -// param_value_unsaved(param) ? '*' : (param_value_is_default(param) ? ' ' : '+'), -// param_name(param)); -// } - -// exit(ret); -// } From dad76c56c63a358ec2c4ea2248ef617843b48bab Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 29 Jul 2013 07:42:23 +1000 Subject: [PATCH 31/88] ets_airspeed: cope with zero value from ETS airspeed sensor --- src/drivers/ets_airspeed/ets_airspeed.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 2e32ed3341..de8028b0f5 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -157,6 +157,14 @@ ETSAirspeed::collect() } uint16_t diff_pres_pa = val[1] << 8 | val[0]; + if (diff_pres_pa == 0) { + // a zero value means the pressure sensor cannot give us a + // value. We need to return, and not report a value or the + // caller could end up using this value as part of an + // average + log("zero value from sensor"); + return -1; + } if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { diff_pres_pa = 0; From 5d356ec3d841602cbe7668028d01e670c3411d4e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 2 Aug 2013 13:51:46 +0200 Subject: [PATCH 32/88] Fixed USB startup --- ROMFS/px4fmu_common/init.d/rc.usb | 40 +++++++++++++++---------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index c89932bb5d..7e28f3d81d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -13,35 +13,35 @@ if mavlink stop then echo "stopped other MAVLink instance" fi +sleep 2 mavlink start -b 230400 -d /dev/ttyACM0 -if [ $MODE == autostart ] +# Start the commander +if commander start then + echo "Commander started" +fi - # Start the commander - commander start +# Start sensors +sh /etc/init.d/rc.sensors - # Start sensors - sh /etc/init.d/rc.sensors - - # Start one of the estimators - if attitude_estimator_ekf status +# Start one of the estimators +if attitude_estimator_ekf status +then + echo "multicopter att filter running" +else + if att_pos_estimator_ekf status then - echo "multicopter att filter running" + echo "fixedwing att filter running" else - if att_pos_estimator_ekf status - then - echo "fixedwing att filter running" - else - attitude_estimator_ekf start - fi + attitude_estimator_ekf start fi +fi - # Start GPS - if gps start - then - echo "GPS started" - fi +# Start GPS +if gps start +then + echo "GPS started" fi echo "MAVLink started, exiting shell.." From 9220f33ce06920e81a93c841e1d5fc4acffe3fed Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 2 Aug 2013 15:37:11 +0200 Subject: [PATCH 33/88] More USB startup fixing --- ROMFS/px4fmu_common/init.d/rc.usb | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 7e28f3d81d..2807c2bee7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -22,6 +22,12 @@ then echo "Commander started" fi +# Start px4io if present +if px4io start +then + echo "PX4IO driver started" +fi + # Start sensors sh /etc/init.d/rc.sensors From 241244ab960e62f32e01b92f86450586b26ee386 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 2 Aug 2013 15:38:17 +0200 Subject: [PATCH 34/88] Hotfix: Added missing drivers to USB startup --- ROMFS/px4fmu_common/init.d/rc.usb | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 2807c2bee7..5b1bd272e9 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -26,6 +26,11 @@ fi if px4io start then echo "PX4IO driver started" +else + if fmu mode_serial + then + echo "FMU driver started" + fi fi # Start sensors From 24c43ad62d03fdfc0a13b5e6fae22c29bbc827c3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 2 Aug 2013 15:47:04 +0200 Subject: [PATCH 35/88] Hotfix: ROMFS autostart includes now IO upgrade --- ROMFS/px4fmu_common/init.d/02_io_quad_x | 22 --------------- ROMFS/px4fmu_common/init.d/10_io_f330 | 37 +++++-------------------- ROMFS/px4fmu_common/init.d/rc.sensors | 4 +-- ROMFS/px4fmu_common/init.d/rcS | 23 +++++++++++++++ 4 files changed, 32 insertions(+), 54 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x index 131abf8c4e..c63e92f6d3 100644 --- a/ROMFS/px4fmu_common/init.d/02_io_quad_x +++ b/ROMFS/px4fmu_common/init.d/02_io_quad_x @@ -39,28 +39,6 @@ fi # param set MAV_TYPE 2 -# -# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) -# -if [ -f /fs/microsd/px4io.bin ] -then - echo "PX4IO Firmware found. Checking Upgrade.." - if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current - then - echo "No newer version, skipping upgrade." - else - echo "Loading /fs/microsd/px4io.bin" - if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log - then - cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current - echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log - else - echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log - echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" - fi - fi -fi - # # Start MAVLink (depends on orb) # diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330 index 4107fab4fa..4450eb50db 100644 --- a/ROMFS/px4fmu_common/init.d/10_io_f330 +++ b/ROMFS/px4fmu_common/init.d/10_io_f330 @@ -15,20 +15,19 @@ then # Set all params here, then disable autoconfig param set SYS_AUTOCONFIG 0 - param set MC_ATTRATE_D 0.007 + param set MC_ATTRATE_D 0.005 param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_P 0.13 + param set MC_ATTRATE_P 0.1 param set MC_ATT_D 0.0 param set MC_ATT_I 0.0 - param set MC_ATT_P 7.0 - param set MC_POS_P 0.1 + param set MC_ATT_P 4.5 param set MC_RCLOSS_THR 0.0 param set MC_YAWPOS_D 0.0 - param set MC_YAWPOS_I 0.5 - param set MC_YAWPOS_P 1.0 + param set MC_YAWPOS_I 0.3 + param set MC_YAWPOS_P 0.6 param set MC_YAWRATE_D 0.0 param set MC_YAWRATE_I 0.0 - param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_P 0.1 param save /fs/microsd/params fi @@ -40,28 +39,6 @@ fi # param set MAV_TYPE 2 -# -# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) -# -if [ -f /fs/microsd/px4io2.bin ] -then - echo "PX4IO Firmware found. Checking Upgrade.." - if cmp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur - then - echo "No newer version, skipping upgrade." - else - echo "Loading /fs/microsd/px4io2.bin" - if px4io update /fs/microsd/px4io2.bin > /fs/microsd/px4io2.log - then - cp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur - echo "Flashed /fs/microsd/px4io2.bin OK" >> /fs/microsd/px4io2.log - else - echo "Failed flashing /fs/microsd/px4io2.bin" >> /fs/microsd/px4io2.log - echo "Failed to upgrade PX4IO2 firmware - check if PX4IO2 is in bootloader mode" - fi - fi -fi - # # Start MAVLink (depends on orb) # @@ -128,7 +105,7 @@ multirotor_att_control start # # Start logging # -sdlog2 start -r 20 -a -b 14 +sdlog2 start -r 20 -a -b 16 # # Start system state diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 73f40c5039..5e80ddc2f4 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -25,7 +25,7 @@ then else echo "using L3GD20 and LSM303D" l3gd20 start - lsm303 start + lsm303d start fi # @@ -40,4 +40,4 @@ then # Check sensors - run AFTER 'sensors start' # preflight_check & -fi \ No newline at end of file +fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index b22591f3c3..f0ee1a0c6e 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -81,6 +81,26 @@ else fi fi +# +# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) +# +if [ -f /fs/microsd/px4io.bin ] +then + echo "PX4IO Firmware found. Checking Upgrade.." + if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur + then + echo "No newer version, skipping upgrade." + else + echo "Loading /fs/microsd/px4io.bin" + if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log + then + cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur + echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log + else + echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log + echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode" + fi + fi fi # @@ -121,3 +141,6 @@ if param compare SYS_AUTOSTART 31 then sh /etc/init.d/31_io_phantom fi + +# End of autostart +fi From c14a71c09564567936707edd96d4e266f9b67c74 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 10:06:10 -0700 Subject: [PATCH 36/88] Move NuttX configurations out of the NuttX tree proper. This reduces the diffs we have to carry against the NuttX upstream repo to just our local patches to the NuttX code itself. --- Makefile | 87 +- makefiles/setup.mk | 1 + makefiles/upload.mk | 2 - nuttx-configs/px4fmu-v1/include/board.h | 395 ++++++++ .../px4fmu-v1/include/nsh_romfsimg.h | 42 + nuttx-configs/px4fmu-v1/nsh/Make.defs | 179 ++++ nuttx-configs/px4fmu-v1/nsh/defconfig | 957 ++++++++++++++++++ nuttx-configs/px4fmu-v1/nsh/setenv.sh | 75 ++ nuttx-configs/px4fmu-v1/scripts/ld.script | 149 +++ nuttx-configs/px4fmu-v1/src/Makefile | 84 ++ nuttx-configs/px4fmu-v1/src/empty.c | 4 + nuttx-configs/px4io-v1/include/README.txt | 1 + nuttx-configs/px4io-v1/include/board.h | 172 ++++ nuttx-configs/px4io-v1/nsh/Make.defs | 166 +++ nuttx-configs/px4io-v1/nsh/appconfig | 32 + nuttx-configs/px4io-v1/nsh/defconfig | 559 ++++++++++ nuttx-configs/px4io-v1/nsh/setenv.sh | 47 + nuttx-configs/px4io-v1/scripts/ld.script | 129 +++ nuttx-configs/px4io-v1/src/Makefile | 84 ++ nuttx-configs/px4io-v1/src/empty.c | 4 + 20 files changed, 3126 insertions(+), 43 deletions(-) create mode 100644 nuttx-configs/px4fmu-v1/include/board.h create mode 100644 nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h create mode 100644 nuttx-configs/px4fmu-v1/nsh/Make.defs create mode 100644 nuttx-configs/px4fmu-v1/nsh/defconfig create mode 100755 nuttx-configs/px4fmu-v1/nsh/setenv.sh create mode 100644 nuttx-configs/px4fmu-v1/scripts/ld.script create mode 100644 nuttx-configs/px4fmu-v1/src/Makefile create mode 100644 nuttx-configs/px4fmu-v1/src/empty.c create mode 100755 nuttx-configs/px4io-v1/include/README.txt create mode 100755 nuttx-configs/px4io-v1/include/board.h create mode 100644 nuttx-configs/px4io-v1/nsh/Make.defs create mode 100644 nuttx-configs/px4io-v1/nsh/appconfig create mode 100755 nuttx-configs/px4io-v1/nsh/defconfig create mode 100755 nuttx-configs/px4io-v1/nsh/setenv.sh create mode 100755 nuttx-configs/px4io-v1/scripts/ld.script create mode 100644 nuttx-configs/px4io-v1/src/Makefile create mode 100644 nuttx-configs/px4io-v1/src/empty.c diff --git a/Makefile b/Makefile index 7f98ffaf22..a2dcd97b8b 100644 --- a/Makefile +++ b/Makefile @@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES) # is taken care of. # $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 - @echo %% Copying $@ + @$(ECHO) %% Copying $@ $(Q) $(COPY) $< $@ $(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@) @@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 $(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@) $(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: - @echo %%%% - @echo %%%% Building $(config) in $(work_dir) - @echo %%%% + @$(ECHO) %%%% + @$(ECHO) %%%% Building $(config) in $(work_dir) + @$(ECHO) %%%% $(Q) mkdir -p $(work_dir) $(Q) make -r -C $(work_dir) \ -f $(PX4_MK_DIR)firmware.mk \ @@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: # XXX Should support fetching/unpacking from a separate directory to permit # downloads of the prebuilt archives as well... # -# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4" -# NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export) .PHONY: archives archives: $(NUTTX_ARCHIVES) @@ -146,15 +144,22 @@ endif $(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@)) $(ARCHIVE_DIR)%.export: configuration = nsh -$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS) - @echo %% Configuring NuttX for $(board) +$(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) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)/nuttx-configs/$(board) .) $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration)) - @echo %% Exporting NuttX for $(board) + @$(ECHO) %% Exporting NuttX for $(board) $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export $(Q) mkdir -p $(dir $@) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ + $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) + +$(NUTTX_SRC): + @$(ECHO) "" + @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." + @$(ECHO) "" # # Cleanup targets. 'clean' should remove all built products and force @@ -176,40 +181,40 @@ distclean: clean # .PHONY: help help: - @echo "" - @echo " PX4 firmware builder" - @echo " ====================" - @echo "" - @echo " Available targets:" - @echo " ------------------" - @echo "" - @echo " archives" - @echo " Build the NuttX RTOS archives that are used by the firmware build." - @echo "" - @echo " all" - @echo " Build all firmware configs: $(CONFIGS)" - @echo " A limited set of configs can be built with CONFIGS=" - @echo "" + @$(ECHO) "" + @$(ECHO) " PX4 firmware builder" + @$(ECHO) " ====================" + @$(ECHO) "" + @$(ECHO) " Available targets:" + @$(ECHO) " ------------------" + @$(ECHO) "" + @$(ECHO) " archives" + @$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build." + @$(ECHO) "" + @$(ECHO) " all" + @$(ECHO) " Build all firmware configs: $(CONFIGS)" + @$(ECHO) " A limited set of configs can be built with CONFIGS=" + @$(ECHO) "" @for config in $(CONFIGS); do \ echo " $$config"; \ echo " Build just the $$config firmware configuration."; \ echo ""; \ done - @echo " clean" - @echo " Remove all firmware build pieces." - @echo "" - @echo " distclean" - @echo " Remove all compilation products, including NuttX RTOS archives." - @echo "" - @echo " upload" - @echo " When exactly one config is being built, add this target to upload the" - @echo " firmware to the board when the build is complete. Not supported for" - @echo " all configurations." - @echo "" - @echo " Common options:" - @echo " ---------------" - @echo "" - @echo " V=1" - @echo " If V is set, more verbose output is printed during the build. This can" - @echo " help when diagnosing issues with the build or toolchain." - @echo "" + @$(ECHO) " clean" + @$(ECHO) " Remove all firmware build pieces." + @$(ECHO) "" + @$(ECHO) " distclean" + @$(ECHO) " Remove all compilation products, including NuttX RTOS archives." + @$(ECHO) "" + @$(ECHO) " upload" + @$(ECHO) " When exactly one config is being built, add this target to upload the" + @$(ECHO) " firmware to the board when the build is complete. Not supported for" + @$(ECHO) " all configurations." + @$(ECHO) "" + @$(ECHO) " Common options:" + @$(ECHO) " ---------------" + @$(ECHO) "" + @$(ECHO) " V=1" + @$(ECHO) " If V is set, more verbose output is printed during the build. This can" + @$(ECHO) " help when diagnosing issues with the build or toolchain." + @$(ECHO) "" diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 92461fafbe..168e41a5cb 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -65,6 +65,7 @@ export INCLUDE_DIRS := $(PX4_MODULE_SRC) \ export MKFW = $(PX4_BASE)/Tools/px_mkfw.py export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py export COPY = cp +export COPYDIR = cp -Rf export REMOVE = rm -f export RMDIR = rm -rf export GENROMFS = genromfs diff --git a/makefiles/upload.mk b/makefiles/upload.mk index 4b01b447d0..3aebef8637 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -27,8 +27,6 @@ all: upload-$(METHOD)-$(BOARD) upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER) $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) -upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) - $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) # # JTAG firmware uploading with OpenOCD diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h new file mode 100644 index 0000000000..0fa93a1965 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -0,0 +1,395 @@ +/************************************************************************************ + * configs/stm32f4discovery/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ************************************************************************************/ + +#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H +#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#ifndef __ASSEMBLY__ +# include +#endif + +#include "stm32_rcc.h" +#include "stm32_sdio.h" +#include "stm32.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ +/* The PX4FMU uses a 24MHz crystal connected to the HSE. + * + * This is the canonical configuration: + * System Clock source : PLL (HSE) + * SYSCLK(Hz) : 168000000 Determined by PLL configuration + * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) + * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) + * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) + * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) + * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) + * PLLM : 24 (STM32_PLLCFG_PLLM) + * PLLN : 336 (STM32_PLLCFG_PLLN) + * PLLP : 2 (STM32_PLLCFG_PLLP) + * PLLQ : 7 (STM32_PLLCFG_PLLQ) + * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK + * Flash Latency(WS) : 5 + * Prefetch Buffer : OFF + * Instruction cache : ON + * Data cache : ON + * Require 48MHz for USB OTG FS, : Enabled + * SDIO and RNG clock + */ + +/* HSI - 16 MHz RC factory-trimmed + * LSI - 32 KHz RC + * HSE - On-board crystal frequency is 24MHz + * LSE - not installed + */ + +#define STM32_BOARD_XTAL 24000000ul + +#define STM32_HSI_FREQUENCY 16000000ul +#define STM32_LSI_FREQUENCY 32000 +#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL +//#define STM32_LSE_FREQUENCY 32768 + +/* Main PLL Configuration. + * + * PLL source is HSE + * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN + * = (8,000,000 / 8) * 336 + * = 336,000,000 + * SYSCLK = PLL_VCO / PLLP + * = 336,000,000 / 2 = 168,000,000 + * USB OTG FS, SDIO and RNG Clock + * = PLL_VCO / PLLQ + * = 48,000,000 + */ + +#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) +#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) +#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 +#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) + +#define STM32_SYSCLK_FREQUENCY 168000000ul + +/* AHB clock (HCLK) is SYSCLK (168MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) + +/* Timers driven from APB1 will be twice PCLK1 */ + +#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) + +/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ +#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) + +/* Timers driven from APB2 will be twice PCLK2 */ + +#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) + +/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx + * otherwise frequency is 2xAPBx. + * Note: TIM1,8 are on APB2, others on APB1 + */ + +#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY) +#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY) + +/* High-resolution timer + */ +#ifdef CONFIG_HRT_TIMER +# define HRT_TIMER 1 /* use timer1 for the HRT */ +# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ +#endif + +/* LED definitions ******************************************************************/ +/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any + * way. The following definitions are used to access individual LEDs. + */ + +/* LED index values for use with stm32_setled() */ + +#define BOARD_LED1 0 +#define BOARD_LED2 1 +#define BOARD_NLEDS 2 + +#define BOARD_LED_BLUE BOARD_LED1 +#define BOARD_LED_RED BOARD_LED2 + +/* LED bits for use with stm32_setleds() */ + +#define BOARD_LED1_BIT (1 << BOARD_LED1) +#define BOARD_LED2_BIT (1 << BOARD_LED2) + +/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the + * px4fmu-v1. The following definitions describe how NuttX controls the LEDs: + */ + +#define LED_STARTED 0 /* LED1 */ +#define LED_HEAPALLOCATE 1 /* LED2 */ +#define LED_IRQSENABLED 2 /* LED1 */ +#define LED_STACKCREATED 3 /* LED1 + LED2 */ +#define LED_INIRQ 4 /* LED1 */ +#define LED_SIGNAL 5 /* LED2 */ +#define LED_ASSERTION 6 /* LED1 + LED2 */ +#define LED_PANIC 7 /* LED1 + LED2 */ + +/* Alternate function pin selections ************************************************/ + +/* + * UARTs. + * + * Note that UART5 has no optional pinout, so it is not listed here. + */ +#define GPIO_USART1_RX GPIO_USART1_RX_2 +#define GPIO_USART1_TX GPIO_USART1_TX_2 + +#define GPIO_USART2_RX GPIO_USART2_RX_1 +#define GPIO_USART2_TX GPIO_USART2_TX_1 +#define GPIO_USART2_RTS GPIO_USART2_RTS_1 +#define GPIO_USART2_CTS GPIO_USART2_CTS_1 + +#define GPIO_USART6_RX GPIO_USART6_RX_1 +#define GPIO_USART6_TX GPIO_USART6_TX_1 + +/* UART DMA configuration for USART1/6 */ +#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 +#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 + +/* + * PWM + * + * Four PWM outputs can be configured on pins otherwise shared with + * USART2; two can take the flow control pins if they are not being used. + * + * Pins: + * + * CTS - PA0 - TIM2CH1 + * RTS - PA1 - TIM2CH2 + * TX - PA2 - TIM2CH3 + * RX - PA3 - TIM2CH4 + * + */ +#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1 +#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1 +#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1 +#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1 + +/* + * PPM + * + * PPM input is handled by the HRT timer. + */ +#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) +# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ +# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) +#endif + +/* + * CAN + * + * CAN2 is routed to the expansion connector. + */ + +#define GPIO_CAN2_RX GPIO_CAN2_RX_2 +#define GPIO_CAN2_TX GPIO_CAN2_TX_2 + +/* + * I2C + * + * The optional _GPIO configurations allow the I2C driver to manually + * reset the bus to clear stuck slaves. They match the pin configuration, + * but are normally-high GPIOs. + */ +#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 +#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 +#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) +#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) + +#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 +#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 +#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) +#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) + +#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1 +#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1 +#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8) +#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9) + +/* + * I2C busses + */ +#define PX4_I2C_BUS_ESC 1 +#define PX4_I2C_BUS_ONBOARD 2 +#define PX4_I2C_BUS_EXPANSION 3 + +/* + * Devices on the onboard bus. + * + * Note that these are unshifted addresses. + */ +#define PX4_I2C_OBDEV_HMC5883 0x1e +#define PX4_I2C_OBDEV_MS5611 0x76 +#define PX4_I2C_OBDEV_EEPROM NOTDEFINED + +#define PX4_I2C_OBDEV_PX4IO_BL 0x18 +#define PX4_I2C_OBDEV_PX4IO 0x1a + +/* + * SPI + * + * There are sensors on SPI1, and SPI3 is connected to the microSD slot. + */ +#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 +#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 +#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 + +#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2 +#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1 +#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2 +#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2 + +/* SPI DMA configuration for SPI3 (microSD) */ +#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1 +#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2 +/* XXX since we allocate the HP work stack from CCM RAM on normal system startup, + SPI1 will never run in DMA mode - so we can just give it a random config here. + What we really need to do is to make DMA configurable per channel, and always + disable it for SPI1. */ +#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1 +#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2 + +/* + * Use these in place of the spi_dev_e enumeration to + * select a specific SPI device on SPI1 + */ +#define PX4_SPIDEV_GYRO 1 +#define PX4_SPIDEV_ACCEL 2 +#define PX4_SPIDEV_MPU 3 + +/* + * Optional devices on IO's external port + */ +#define PX4_SPIDEV_ACCEL_MAG 2 + +/* + * Tone alarm output + */ +#define TONE_ALARM_TIMER 3 /* timer 3 */ +#define TONE_ALARM_CHANNEL 3 /* channel 3 */ +#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8) +#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8) + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +/************************************************************************************ + * Name: stm32_ledinit, stm32_setled, and stm32_setleds + * + * Description: + * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If + * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to + * control the LEDs from user applications. + * + ************************************************************************************/ + +#ifndef CONFIG_ARCH_LEDS +EXTERN void stm32_ledinit(void); +EXTERN void stm32_setled(int led, bool ledon); +EXTERN void stm32_setleds(uint8_t ledset); +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */ diff --git a/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h new file mode 100644 index 0000000000..15e4e7a8d5 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h @@ -0,0 +1,42 @@ +/**************************************************************************** + * + * Copyright (C) 2013 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. + * + ****************************************************************************/ + +/** + * nsh_romfsetc.h + * + * This file is a stub for 'make export' purposes; the actual ROMFS + * must be supplied by the library client. + */ + +extern unsigned char romfs_img[]; +extern unsigned int romfs_img_len; diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs new file mode 100644 index 0000000000..7b2ea703a2 --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs @@ -0,0 +1,179 @@ +############################################################################ +# configs/px4fmu-v1/nsh/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m4 \ + -mthumb \ + -march=armv7e-m \ + -mfpu=fpv4-sp-d16 \ + -mfloat-abi=hard + + +# enable precise stack overflow tracking +INSTRUMENTATIONDEFINES = -finstrument-functions \ + -ffixed-r10 + +# pull in *just* libm from the toolchain ... this is grody +LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" +EXTRA_LIBS += $(LIBM) + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) \ + -Wno-psabi +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig new file mode 100644 index 0000000000..49ccfd41bc --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -0,0 +1,957 @@ +# +# Automatically generated file; DO NOT EDIT. +# Nuttx/ Configuration +# +CONFIG_NUTTX_NEWCONFIG=y + +# +# Build Setup +# +# CONFIG_EXPERIMENTAL is not set +# CONFIG_HOST_LINUX is not set +CONFIG_HOST_OSX=y +# CONFIG_HOST_WINDOWS is not set +# CONFIG_HOST_OTHER is not set + +# +# Build Configuration +# +CONFIG_APPS_DIR="../apps" +# CONFIG_BUILD_2PASS is not set + +# +# Binary Output Formats +# +# CONFIG_RRLOAD_BINARY is not set +# CONFIG_INTELHEX_BINARY is not set +# CONFIG_MOTOROLA_SREC is not set +CONFIG_RAW_BINARY=y + +# +# Customize Header Files +# +# CONFIG_ARCH_STDBOOL_H is not set +CONFIG_ARCH_MATH_H=y +# CONFIG_ARCH_FLOAT_H is not set +# CONFIG_ARCH_STDARG_H is not set + +# +# Debug Options +# +# CONFIG_DEBUG is not set +CONFIG_DEBUG_SYMBOLS=y + +# +# System Type +# +# CONFIG_ARCH_8051 is not set +CONFIG_ARCH_ARM=y +# CONFIG_ARCH_AVR is not set +# CONFIG_ARCH_HC is not set +# CONFIG_ARCH_MIPS is not set +# CONFIG_ARCH_RGMP is not set +# CONFIG_ARCH_SH is not set +# CONFIG_ARCH_SIM is not set +# CONFIG_ARCH_X86 is not set +# CONFIG_ARCH_Z16 is not set +# CONFIG_ARCH_Z80 is not set +CONFIG_ARCH="arm" + +# +# ARM Options +# +# CONFIG_ARCH_CHIP_C5471 is not set +# CONFIG_ARCH_CHIP_CALYPSO is not set +# CONFIG_ARCH_CHIP_DM320 is not set +# CONFIG_ARCH_CHIP_IMX is not set +# CONFIG_ARCH_CHIP_KINETIS is not set +# CONFIG_ARCH_CHIP_KL is not set +# CONFIG_ARCH_CHIP_LM is not set +# CONFIG_ARCH_CHIP_LPC17XX is not set +# CONFIG_ARCH_CHIP_LPC214X is not set +# CONFIG_ARCH_CHIP_LPC2378 is not set +# CONFIG_ARCH_CHIP_LPC31XX is not set +# CONFIG_ARCH_CHIP_LPC43XX is not set +# CONFIG_ARCH_CHIP_NUC1XX is not set +# CONFIG_ARCH_CHIP_SAM3U is not set +CONFIG_ARCH_CHIP_STM32=y +# CONFIG_ARCH_CHIP_STR71X is not set +CONFIG_ARCH_CORTEXM4=y +CONFIG_ARCH_HAVE_FPU=y +CONFIG_ARCH_FAMILY="armv7-m" +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_ARCH_HAVE_CMNVECTOR=y +CONFIG_ARMV7M_CMNVECTOR=y +CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARCH_FPU=y +CONFIG_ARCH_HAVE_MPU=y +# CONFIG_ARMV7M_MPU is not set + +# +# ARMV7M Configuration Options +# +# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set +CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_SERIAL_TERMIOS=y +CONFIG_SERIAL_DISABLE_REORDERING=y +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y + +# +# STM32 Configuration Options +# +# CONFIG_ARCH_CHIP_STM32L151C6 is not set +# CONFIG_ARCH_CHIP_STM32L151C8 is not set +# CONFIG_ARCH_CHIP_STM32L151CB is not set +# CONFIG_ARCH_CHIP_STM32L151R6 is not set +# CONFIG_ARCH_CHIP_STM32L151R8 is not set +# CONFIG_ARCH_CHIP_STM32L151RB is not set +# CONFIG_ARCH_CHIP_STM32L151V6 is not set +# CONFIG_ARCH_CHIP_STM32L151V8 is not set +# CONFIG_ARCH_CHIP_STM32L151VB is not set +# CONFIG_ARCH_CHIP_STM32L152C6 is not set +# CONFIG_ARCH_CHIP_STM32L152C8 is not set +# CONFIG_ARCH_CHIP_STM32L152CB is not set +# CONFIG_ARCH_CHIP_STM32L152R6 is not set +# CONFIG_ARCH_CHIP_STM32L152R8 is not set +# CONFIG_ARCH_CHIP_STM32L152RB is not set +# CONFIG_ARCH_CHIP_STM32L152V6 is not set +# CONFIG_ARCH_CHIP_STM32L152V8 is not set +# CONFIG_ARCH_CHIP_STM32L152VB is not set +# CONFIG_ARCH_CHIP_STM32F100C8 is not set +# CONFIG_ARCH_CHIP_STM32F100CB is not set +# CONFIG_ARCH_CHIP_STM32F100R8 is not set +# CONFIG_ARCH_CHIP_STM32F100RB is not set +# CONFIG_ARCH_CHIP_STM32F100RC is not set +# CONFIG_ARCH_CHIP_STM32F100RD is not set +# CONFIG_ARCH_CHIP_STM32F100RE is not set +# CONFIG_ARCH_CHIP_STM32F100V8 is not set +# CONFIG_ARCH_CHIP_STM32F100VB is not set +# CONFIG_ARCH_CHIP_STM32F100VC is not set +# CONFIG_ARCH_CHIP_STM32F100VD is not set +# CONFIG_ARCH_CHIP_STM32F100VE is not set +# CONFIG_ARCH_CHIP_STM32F103C4 is not set +# CONFIG_ARCH_CHIP_STM32F103C8 is not set +# CONFIG_ARCH_CHIP_STM32F103RET6 is not set +# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set +# CONFIG_ARCH_CHIP_STM32F103VET6 is not set +# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set +# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set +# CONFIG_ARCH_CHIP_STM32F107VC is not set +# CONFIG_ARCH_CHIP_STM32F207IG is not set +# CONFIG_ARCH_CHIP_STM32F302CB is not set +# CONFIG_ARCH_CHIP_STM32F302CC is not set +# CONFIG_ARCH_CHIP_STM32F302RB is not set +# CONFIG_ARCH_CHIP_STM32F302RC is not set +# CONFIG_ARCH_CHIP_STM32F302VB is not set +# CONFIG_ARCH_CHIP_STM32F302VC is not set +# CONFIG_ARCH_CHIP_STM32F303CB is not set +# CONFIG_ARCH_CHIP_STM32F303CC is not set +# CONFIG_ARCH_CHIP_STM32F303RB is not set +# CONFIG_ARCH_CHIP_STM32F303RC is not set +# CONFIG_ARCH_CHIP_STM32F303VB is not set +# CONFIG_ARCH_CHIP_STM32F303VC is not set +CONFIG_ARCH_CHIP_STM32F405RG=y +# CONFIG_ARCH_CHIP_STM32F405VG is not set +# CONFIG_ARCH_CHIP_STM32F405ZG is not set +# CONFIG_ARCH_CHIP_STM32F407VE is not set +# CONFIG_ARCH_CHIP_STM32F407VG is not set +# CONFIG_ARCH_CHIP_STM32F407ZE is not set +# CONFIG_ARCH_CHIP_STM32F407ZG is not set +# CONFIG_ARCH_CHIP_STM32F407IE is not set +# CONFIG_ARCH_CHIP_STM32F407IG is not set +# CONFIG_ARCH_CHIP_STM32F427V is not set +# CONFIG_ARCH_CHIP_STM32F427Z is not set +# CONFIG_ARCH_CHIP_STM32F427I is not set +# CONFIG_STM32_STM32L15XX is not set +# CONFIG_STM32_ENERGYLITE is not set +# CONFIG_STM32_STM32F10XX is not set +# CONFIG_STM32_VALUELINE is not set +# CONFIG_STM32_CONNECTIVITYLINE is not set +# CONFIG_STM32_PERFORMANCELINE is not set +# CONFIG_STM32_HIGHDENSITY is not set +# CONFIG_STM32_MEDIUMDENSITY is not set +# CONFIG_STM32_LOWDENSITY is not set +# CONFIG_STM32_STM32F20XX is not set +# CONFIG_STM32_STM32F30XX is not set +CONFIG_STM32_STM32F40XX=y +# CONFIG_STM32_DFU is not set + +# +# STM32 Peripheral Support +# +CONFIG_STM32_ADC1=y +# CONFIG_STM32_ADC2 is not set +# CONFIG_STM32_ADC3 is not set +CONFIG_STM32_BKPSRAM=y +# CONFIG_STM32_CAN1 is not set +# CONFIG_STM32_CAN2 is not set +CONFIG_STM32_CCMDATARAM=y +# CONFIG_STM32_CRC is not set +# CONFIG_STM32_CRYP is not set +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=y +# CONFIG_STM32_DAC1 is not set +# CONFIG_STM32_DAC2 is not set +# CONFIG_STM32_DCMI is not set +# CONFIG_STM32_ETHMAC is not set +# CONFIG_STM32_FSMC is not set +# CONFIG_STM32_HASH is not set +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=y +CONFIG_STM32_I2C3=y +CONFIG_STM32_OTGFS=y +# CONFIG_STM32_OTGHS is not set +CONFIG_STM32_PWR=y +# CONFIG_STM32_RNG is not set +# CONFIG_STM32_SDIO is not set +CONFIG_STM32_SPI1=y +# CONFIG_STM32_SPI2 is not set +CONFIG_STM32_SPI3=y +CONFIG_STM32_SYSCFG=y +# CONFIG_STM32_TIM1 is not set +# CONFIG_STM32_TIM2 is not set +# CONFIG_STM32_TIM3 is not set +CONFIG_STM32_TIM4=y +CONFIG_STM32_TIM5=y +CONFIG_STM32_TIM6=y +CONFIG_STM32_TIM7=y +# CONFIG_STM32_TIM8 is not set +CONFIG_STM32_TIM9=y +CONFIG_STM32_TIM10=y +CONFIG_STM32_TIM11=y +CONFIG_STM32_TIM12=y +CONFIG_STM32_TIM13=y +CONFIG_STM32_TIM14=y +CONFIG_STM32_USART1=y +CONFIG_STM32_USART2=y +# CONFIG_STM32_USART3 is not set +# CONFIG_STM32_UART4 is not set +CONFIG_STM32_UART5=y +CONFIG_STM32_USART6=y +# CONFIG_STM32_IWDG is not set +CONFIG_STM32_WWDG=y +CONFIG_STM32_ADC=y +CONFIG_STM32_SPI=y +CONFIG_STM32_I2C=y + +# +# Alternate Pin Mapping +# +CONFIG_STM32_FLASH_PREFETCH=y +# CONFIG_STM32_JTAG_DISABLE is not set +CONFIG_STM32_JTAG_FULL_ENABLE=y +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set +# CONFIG_STM32_JTAG_SW_ENABLE is not set +CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y +# CONFIG_STM32_FORCEPOWER is not set +# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set +# CONFIG_STM32_CCMEXCLUDE is not set +# CONFIG_STM32_TIM4_PWM is not set +# CONFIG_STM32_TIM5_PWM is not set +# CONFIG_STM32_TIM9_PWM is not set +# CONFIG_STM32_TIM10_PWM is not set +# CONFIG_STM32_TIM11_PWM is not set +# CONFIG_STM32_TIM12_PWM is not set +# CONFIG_STM32_TIM13_PWM is not set +# CONFIG_STM32_TIM14_PWM is not set +# CONFIG_STM32_TIM4_ADC is not set +# CONFIG_STM32_TIM5_ADC is not set +CONFIG_STM32_USART=y + +# +# U[S]ART Configuration +# +# CONFIG_USART1_RS485 is not set +# CONFIG_USART1_RXDMA is not set +# CONFIG_USART2_RS485 is not set +CONFIG_USART2_RXDMA=y +# CONFIG_USART3_RXDMA is not set +# CONFIG_UART4_RXDMA is not set +# CONFIG_UART5_RS485 is not set +CONFIG_UART5_RXDMA=y +# CONFIG_USART6_RS485 is not set +CONFIG_USART6_RXDMA=y +# CONFIG_USART7_RXDMA is not set +# CONFIG_USART8_RXDMA is not set +CONFIG_STM32_USART_SINGLEWIRE=y + +# +# SPI Configuration +# +# CONFIG_STM32_SPI_INTERRUPTS is not set +# CONFIG_STM32_SPI_DMA is not set + +# +# I2C Configuration +# +# CONFIG_STM32_I2C_DYNTIMEO is not set +CONFIG_STM32_I2CTIMEOSEC=0 +CONFIG_STM32_I2CTIMEOMS=10 +CONFIG_STM32_I2CTIMEOTICKS=500 +# CONFIG_STM32_I2C_DUTY16_9 is not set + +# +# USB Host Configuration +# + +# +# USB Device Configuration +# + +# +# External Memory Configuration +# + +# +# Architecture Options +# +# CONFIG_ARCH_NOINTC is not set +# CONFIG_ARCH_VECNOTIRQ is not set +CONFIG_ARCH_DMA=y +CONFIG_ARCH_IRQPRIO=y +# CONFIG_CUSTOM_STACK is not set +# CONFIG_ADDRENV is not set +CONFIG_ARCH_HAVE_VFORK=y +CONFIG_ARCH_STACKDUMP=y +# CONFIG_ENDIAN_BIG is not set +# CONFIG_ARCH_HAVE_RAMFUNCS is not set +CONFIG_ARCH_HAVE_RAMVECTORS=y +# CONFIG_ARCH_RAMVECTORS is not set + +# +# Board Settings +# +CONFIG_BOARD_LOOPSPERMSEC=16717 +# CONFIG_ARCH_CALIBRATION is not set +CONFIG_DRAM_START=0x20000000 +CONFIG_DRAM_SIZE=196608 +CONFIG_ARCH_HAVE_INTERRUPTSTACK=y +CONFIG_ARCH_INTERRUPTSTACK=0 + +# +# Boot options +# +# CONFIG_BOOT_RUNFROMEXTSRAM is not set +CONFIG_BOOT_RUNFROMFLASH=y +# CONFIG_BOOT_RUNFROMISRAM is not set +# CONFIG_BOOT_RUNFROMSDRAM is not set +# CONFIG_BOOT_COPYTORAM is not set + +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4FMU_V1=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="px4fmu-v1" + +# +# Common Board Options +# +CONFIG_ARCH_HAVE_LEDS=y +# CONFIG_ARCH_LEDS is not set +CONFIG_NSH_MMCSDMINOR=0 +CONFIG_NSH_MMCSDSLOTNO=0 +CONFIG_NSH_MMCSDSPIPORTNO=3 + +# +# Board-Specific Options +# +CONFIG_HRT_TIMER=y +CONFIG_HRT_PPM=y + +# +# RTOS Features +# +# CONFIG_BOARD_INITIALIZE is not set +CONFIG_MSEC_PER_TICK=1 +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=y +CONFIG_TASK_NAME_SIZE=24 +# CONFIG_SCHED_HAVE_PARENT is not set +# CONFIG_JULIAN_TIME is not set +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +# CONFIG_DEV_CONSOLE is not set +# CONFIG_MUTEX_TYPES is not set +CONFIG_PRIORITY_INHERITANCE=y +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=8 +# CONFIG_FDCLONE_DISABLE is not set +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WAITPID=y +# CONFIG_SCHED_STARTHOOK is not set +CONFIG_SCHED_ATEXIT=y +CONFIG_SCHED_ATEXIT_MAX=1 +# CONFIG_SCHED_ONEXIT is not set +CONFIG_USER_ENTRYPOINT="nsh_main" +CONFIG_DISABLE_OS_API=y +# CONFIG_DISABLE_CLOCK is not set +# CONFIG_DISABLE_POSIX_TIMERS is not set +# CONFIG_DISABLE_PTHREAD is not set +# CONFIG_DISABLE_SIGNALS is not set +# CONFIG_DISABLE_MQUEUE is not set +# CONFIG_DISABLE_ENVIRON is not set + +# +# Signal Numbers +# +CONFIG_SIG_SIGUSR1=1 +CONFIG_SIG_SIGUSR2=2 +CONFIG_SIG_SIGALARM=3 +CONFIG_SIG_SIGCONDTIMEDOUT=16 +CONFIG_SIG_SIGWORK=4 + +# +# Sizes of configurable things (0 disables) +# +CONFIG_MAX_TASKS=32 +CONFIG_MAX_TASK_ARGS=10 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=25 +CONFIG_NAME_MAX=32 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=50 +CONFIG_PREALLOC_TIMERS=50 + +# +# Stack and heap information +# +CONFIG_IDLETHREAD_STACKSIZE=6000 +CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=2048 + +# +# Device Drivers +# +# CONFIG_DISABLE_POLL is not set +CONFIG_DEV_NULL=y +# CONFIG_DEV_ZERO is not set +# CONFIG_LOOP is not set +# CONFIG_RAMDISK is not set +# CONFIG_CAN is not set +# CONFIG_PWM is not set +CONFIG_I2C=y +# CONFIG_I2C_SLAVE is not set +CONFIG_I2C_TRANSFER=y +# CONFIG_I2C_WRITEREAD is not set +# CONFIG_I2C_POLLED is not set +# CONFIG_I2C_TRACE is not set +CONFIG_ARCH_HAVE_I2CRESET=y +CONFIG_I2C_RESET=y +CONFIG_SPI=y +# CONFIG_SPI_OWNBUS is not set +CONFIG_SPI_EXCHANGE=y +# CONFIG_SPI_CMDDATA is not set +# CONFIG_RTC is not set +CONFIG_WATCHDOG=y +# CONFIG_ANALOG is not set +# CONFIG_AUDIO_DEVICES is not set +# CONFIG_BCH is not set +# CONFIG_INPUT is not set +# CONFIG_LCD is not set +CONFIG_MMCSD=y +CONFIG_MMCSD_NSLOTS=1 +# CONFIG_MMCSD_READONLY is not set +# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set +# CONFIG_MMCSD_MMCSUPPORT is not set +# CONFIG_MMCSD_HAVECARDDETECT is not set +CONFIG_MMCSD_SPI=y +CONFIG_MMCSD_SPICLOCK=24000000 +# CONFIG_MMCSD_SDIO is not set +# CONFIG_MTD is not set +CONFIG_PIPES=y +# CONFIG_PM is not set +# CONFIG_POWER is not set +# CONFIG_SENSORS is not set +CONFIG_SERIAL=y +# CONFIG_DEV_LOWCONSOLE is not set +CONFIG_SERIAL_REMOVABLE=y +# CONFIG_16550_UART is not set +CONFIG_ARCH_HAVE_UART5=y +CONFIG_ARCH_HAVE_USART1=y +CONFIG_ARCH_HAVE_USART2=y +CONFIG_ARCH_HAVE_USART6=y +CONFIG_MCU_SERIAL=y +CONFIG_STANDARD_SERIAL=y +CONFIG_SERIAL_NPOLLWAITERS=2 +# CONFIG_USART1_SERIAL_CONSOLE is not set +# CONFIG_USART2_SERIAL_CONSOLE is not set +# CONFIG_UART5_SERIAL_CONSOLE is not set +# CONFIG_USART6_SERIAL_CONSOLE is not set +CONFIG_NO_SERIAL_CONSOLE=y + +# +# USART1 Configuration +# +CONFIG_USART1_RXBUFSIZE=512 +CONFIG_USART1_TXBUFSIZE=512 +CONFIG_USART1_BAUD=57600 +CONFIG_USART1_BITS=8 +CONFIG_USART1_PARITY=0 +CONFIG_USART1_2STOP=0 + +# +# USART2 Configuration +# +CONFIG_USART2_RXBUFSIZE=512 +CONFIG_USART2_TXBUFSIZE=512 +CONFIG_USART2_BAUD=57600 +CONFIG_USART2_BITS=8 +CONFIG_USART2_PARITY=0 +CONFIG_USART2_2STOP=0 + +# +# UART5 Configuration +# +CONFIG_UART5_RXBUFSIZE=32 +CONFIG_UART5_TXBUFSIZE=32 +CONFIG_UART5_BAUD=57600 +CONFIG_UART5_BITS=8 +CONFIG_UART5_PARITY=0 +CONFIG_UART5_2STOP=0 + +# +# USART6 Configuration +# +CONFIG_USART6_RXBUFSIZE=512 +CONFIG_USART6_TXBUFSIZE=512 +CONFIG_USART6_BAUD=57600 +CONFIG_USART6_BITS=8 +CONFIG_USART6_PARITY=0 +CONFIG_USART6_2STOP=0 +CONFIG_USBDEV=y + +# +# USB Device Controller Driver Options +# +# CONFIG_USBDEV_ISOCHRONOUS is not set +# CONFIG_USBDEV_DUALSPEED is not set +CONFIG_USBDEV_SELFPOWERED=y +# CONFIG_USBDEV_BUSPOWERED is not set +CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_DMA is not set +# CONFIG_USBDEV_TRACE is not set + +# +# USB Device Class Driver Options +# +# CONFIG_USBDEV_COMPOSITE is not set +# CONFIG_PL2303 is not set +CONFIG_CDCACM=y +CONFIG_CDCACM_CONSOLE=y +CONFIG_CDCACM_EP0MAXPACKET=64 +CONFIG_CDCACM_EPINTIN=1 +CONFIG_CDCACM_EPINTIN_FSSIZE=64 +CONFIG_CDCACM_EPINTIN_HSSIZE=64 +CONFIG_CDCACM_EPBULKOUT=3 +CONFIG_CDCACM_EPBULKOUT_FSSIZE=64 +CONFIG_CDCACM_EPBULKOUT_HSSIZE=512 +CONFIG_CDCACM_EPBULKIN=2 +CONFIG_CDCACM_EPBULKIN_FSSIZE=64 +CONFIG_CDCACM_EPBULKIN_HSSIZE=512 +CONFIG_CDCACM_NWRREQS=4 +CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_RXBUFSIZE=256 +CONFIG_CDCACM_TXBUFSIZE=256 +CONFIG_CDCACM_VENDORID=0x26ac +CONFIG_CDCACM_PRODUCTID=0x0010 +CONFIG_CDCACM_VENDORSTR="3D Robotics" +CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.x" +# CONFIG_USBMSC is not set +# CONFIG_USBHOST is not set +# CONFIG_WIRELESS is not set + +# +# System Logging Device Options +# + +# +# System Logging +# +# CONFIG_RAMLOG is not set + +# +# Networking Support +# +# CONFIG_NET is not set + +# +# File Systems +# + +# +# File system configuration +# +# CONFIG_DISABLE_MOUNTPOINT is not set +# CONFIG_FS_RAMMAP is not set +CONFIG_FS_FAT=y +CONFIG_FAT_LCNAMES=y +CONFIG_FAT_LFN=y +CONFIG_FAT_MAXFNAME=32 +CONFIG_FS_FATTIME=y +# CONFIG_FAT_DMAMEMORY is not set +CONFIG_FS_NXFFS=y +CONFIG_NXFFS_PREALLOCATED=y +CONFIG_NXFFS_ERASEDSTATE=0xff +CONFIG_NXFFS_PACKTHRESHOLD=32 +CONFIG_NXFFS_MAXNAMLEN=32 +CONFIG_NXFFS_TAILTHRESHOLD=2048 +CONFIG_FS_ROMFS=y +# CONFIG_FS_SMARTFS is not set +CONFIG_FS_BINFS=y + +# +# System Logging +# +# CONFIG_SYSLOG_ENABLE is not set +CONFIG_SYSLOG=y +CONFIG_SYSLOG_CHAR=y +CONFIG_SYSLOG_DEVPATH="/dev/ttyS0" + +# +# Graphics Support +# +# CONFIG_NX is not set + +# +# Memory Management +# +# CONFIG_MM_MULTIHEAP is not set +# CONFIG_MM_SMALL is not set +CONFIG_MM_REGIONS=2 +CONFIG_GRAN=y +CONFIG_GRAN_SINGLE=y +CONFIG_GRAN_INTR=y + +# +# Audio Support +# +# CONFIG_AUDIO is not set + +# +# Binary Formats +# +# CONFIG_BINFMT_DISABLE is not set +# CONFIG_BINFMT_EXEPATH is not set +# CONFIG_NXFLAT is not set +# CONFIG_ELF is not set +CONFIG_BUILTIN=y +# CONFIG_PIC is not set +# CONFIG_SYMTAB_ORDEREDBYNAME is not set + +# +# Library Routines +# + +# +# Standard C Library Options +# +CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_LINEBUFFER=y +CONFIG_NUNGET_CHARS=2 +CONFIG_LIB_HOMEDIR="/" +# CONFIG_NOPRINTF_FIELDWIDTH is not set +CONFIG_LIBC_FLOATINGPOINT=y +CONFIG_LIB_RAND_ORDER=1 +# CONFIG_EOL_IS_CR is not set +# CONFIG_EOL_IS_LF is not set +# CONFIG_EOL_IS_BOTH_CRLF is not set +CONFIG_EOL_IS_EITHER_CRLF=y +# CONFIG_LIBC_EXECFUNCS is not set +CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024 +CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048 +CONFIG_LIBC_STRERROR=y +# CONFIG_LIBC_STRERROR_SHORT is not set +# CONFIG_LIBC_PERROR_STDOUT is not set +CONFIG_ARCH_LOWPUTC=y +CONFIG_LIB_SENDFILE_BUFSIZE=512 +# CONFIG_ARCH_ROMGETC is not set +CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y +CONFIG_ARCH_MEMCPY=y +# CONFIG_ARCH_MEMCMP is not set +# CONFIG_ARCH_MEMMOVE is not set +# CONFIG_ARCH_MEMSET is not set +# CONFIG_MEMSET_OPTSPEED is not set +# CONFIG_ARCH_STRCHR is not set +# CONFIG_ARCH_STRCMP is not set +# CONFIG_ARCH_STRCPY is not set +# CONFIG_ARCH_STRNCPY is not set +# CONFIG_ARCH_STRLEN is not set +# CONFIG_ARCH_STRNLEN is not set +# CONFIG_ARCH_BZERO is not set + +# +# Non-standard Library Support +# +CONFIG_SCHED_WORKQUEUE=y +CONFIG_SCHED_HPWORK=y +CONFIG_SCHED_WORKPRIORITY=192 +CONFIG_SCHED_WORKPERIOD=5000 +CONFIG_SCHED_WORKSTACKSIZE=2048 +CONFIG_SCHED_LPWORK=y +CONFIG_SCHED_LPWORKPRIORITY=50 +CONFIG_SCHED_LPWORKPERIOD=50000 +CONFIG_SCHED_LPWORKSTACKSIZE=2048 +# CONFIG_LIB_KBDCODEC is not set +# CONFIG_LIB_SLCDCODEC is not set + +# +# Basic CXX Support +# +# CONFIG_C99_BOOL8 is not set +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +# CONFIG_CXX_NEWLONG is not set + +# +# uClibc++ Standard C++ Library +# +# CONFIG_UCLIBCXX is not set + +# +# Application Configuration +# + +# +# Built-In Applications +# +CONFIG_BUILTIN_PROXY_STACKSIZE=1024 + +# +# Examples +# +# CONFIG_EXAMPLES_BUTTONS is not set +# CONFIG_EXAMPLES_CAN is not set +CONFIG_EXAMPLES_CDCACM=y +# CONFIG_EXAMPLES_COMPOSITE is not set +# CONFIG_EXAMPLES_CXXTEST is not set +# CONFIG_EXAMPLES_DHCPD is not set +# CONFIG_EXAMPLES_ELF is not set +# CONFIG_EXAMPLES_FTPC is not set +# CONFIG_EXAMPLES_FTPD is not set +# CONFIG_EXAMPLES_HELLO is not set +# CONFIG_EXAMPLES_HELLOXX is not set +# CONFIG_EXAMPLES_JSON is not set +# CONFIG_EXAMPLES_HIDKBD is not set +# CONFIG_EXAMPLES_KEYPADTEST is not set +# CONFIG_EXAMPLES_IGMP is not set +# CONFIG_EXAMPLES_LCDRW is not set +# CONFIG_EXAMPLES_MM is not set +# CONFIG_EXAMPLES_MODBUS is not set +CONFIG_EXAMPLES_MOUNT=y +CONFIG_EXAMPLES_NSH=y +# CONFIG_EXAMPLES_NULL is not set +# CONFIG_EXAMPLES_NX is not set +# CONFIG_EXAMPLES_NXCONSOLE is not set +# CONFIG_EXAMPLES_NXFFS is not set +# CONFIG_EXAMPLES_NXFLAT is not set +# CONFIG_EXAMPLES_NXHELLO is not set +# CONFIG_EXAMPLES_NXIMAGE is not set +# CONFIG_EXAMPLES_NXLINES is not set +# CONFIG_EXAMPLES_NXTEXT is not set +# CONFIG_EXAMPLES_OSTEST is not set +# CONFIG_EXAMPLES_PASHELLO is not set +# CONFIG_EXAMPLES_PIPE is not set +# CONFIG_EXAMPLES_POSIXSPAWN is not set +# CONFIG_EXAMPLES_QENCODER is not set +# CONFIG_EXAMPLES_RGMP is not set +# CONFIG_EXAMPLES_ROMFS is not set +# CONFIG_EXAMPLES_SENDMAIL is not set +# CONFIG_EXAMPLES_SERLOOP is not set +# CONFIG_EXAMPLES_SLCD is not set +# CONFIG_EXAMPLES_SMART_TEST is not set +# CONFIG_EXAMPLES_SMART is not set +# CONFIG_EXAMPLES_TCPECHO is not set +# CONFIG_EXAMPLES_TELNETD is not set +# CONFIG_EXAMPLES_THTTPD is not set +# CONFIG_EXAMPLES_TIFF is not set +# CONFIG_EXAMPLES_TOUCHSCREEN is not set +# CONFIG_EXAMPLES_UDP is not set +# CONFIG_EXAMPLES_UIP is not set +# CONFIG_EXAMPLES_USBSERIAL is not set +# CONFIG_EXAMPLES_USBMSC is not set +# CONFIG_EXAMPLES_USBTERM is not set +# CONFIG_EXAMPLES_WATCHDOG is not set + +# +# Graphics Support +# +# CONFIG_TIFF is not set + +# +# Interpreters +# +# CONFIG_INTERPRETERS_FICL is not set +# CONFIG_INTERPRETERS_PCODE is not set + +# +# Network Utilities +# + +# +# Networking Utilities +# +# CONFIG_NETUTILS_CODECS is not set +# CONFIG_NETUTILS_DHCPC is not set +# CONFIG_NETUTILS_DHCPD is not set +# CONFIG_NETUTILS_FTPC is not set +# CONFIG_NETUTILS_FTPD is not set +# CONFIG_NETUTILS_JSON is not set +# CONFIG_NETUTILS_RESOLV is not set +# CONFIG_NETUTILS_SMTP is not set +# CONFIG_NETUTILS_TELNETD is not set +# CONFIG_NETUTILS_TFTPC is not set +# CONFIG_NETUTILS_THTTPD is not set +# CONFIG_NETUTILS_UIPLIB is not set +# CONFIG_NETUTILS_WEBCLIENT is not set + +# +# FreeModBus +# +# CONFIG_MODBUS is not set + +# +# NSH Library +# +CONFIG_NSH_LIBRARY=y +CONFIG_NSH_BUILTIN_APPS=y + +# +# Disable Individual commands +# +# CONFIG_NSH_DISABLE_CAT is not set +# CONFIG_NSH_DISABLE_CD is not set +# CONFIG_NSH_DISABLE_CP is not set +# CONFIG_NSH_DISABLE_DD is not set +# CONFIG_NSH_DISABLE_ECHO is not set +# CONFIG_NSH_DISABLE_EXEC is not set +# CONFIG_NSH_DISABLE_EXIT is not set +# CONFIG_NSH_DISABLE_FREE is not set +# CONFIG_NSH_DISABLE_GET is not set +# CONFIG_NSH_DISABLE_HELP is not set +# CONFIG_NSH_DISABLE_HEXDUMP is not set +# CONFIG_NSH_DISABLE_IFCONFIG is not set +# CONFIG_NSH_DISABLE_KILL is not set +# CONFIG_NSH_DISABLE_LOSETUP is not set +# CONFIG_NSH_DISABLE_LS is not set +# CONFIG_NSH_DISABLE_MB is not set +# CONFIG_NSH_DISABLE_MKDIR is not set +# CONFIG_NSH_DISABLE_MKFATFS is not set +# CONFIG_NSH_DISABLE_MKFIFO is not set +# CONFIG_NSH_DISABLE_MKRD is not set +# CONFIG_NSH_DISABLE_MH is not set +# CONFIG_NSH_DISABLE_MOUNT is not set +# CONFIG_NSH_DISABLE_MW is not set +# CONFIG_NSH_DISABLE_NSFMOUNT is not set +# CONFIG_NSH_DISABLE_PS is not set +# CONFIG_NSH_DISABLE_PING is not set +# CONFIG_NSH_DISABLE_PUT is not set +# CONFIG_NSH_DISABLE_PWD is not set +# CONFIG_NSH_DISABLE_RM is not set +# CONFIG_NSH_DISABLE_RMDIR is not set +# CONFIG_NSH_DISABLE_SET is not set +# CONFIG_NSH_DISABLE_SH is not set +# CONFIG_NSH_DISABLE_SLEEP is not set +# CONFIG_NSH_DISABLE_TEST is not set +# CONFIG_NSH_DISABLE_UMOUNT is not set +# CONFIG_NSH_DISABLE_UNSET is not set +# CONFIG_NSH_DISABLE_USLEEP is not set +# CONFIG_NSH_DISABLE_WGET is not set +# CONFIG_NSH_DISABLE_XD is not set + +# +# Configure Command Options +# +# CONFIG_NSH_CMDOPT_DF_H is not set +CONFIG_NSH_CODECS_BUFSIZE=128 +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_STRERROR=y +CONFIG_NSH_LINELEN=128 +CONFIG_NSH_MAXARGUMENTS=12 +CONFIG_NSH_NESTDEPTH=8 +# CONFIG_NSH_DISABLESCRIPT is not set +# CONFIG_NSH_DISABLEBG is not set +CONFIG_NSH_ROMFSETC=y +# CONFIG_NSH_ROMFSRC is not set +CONFIG_NSH_ROMFSMOUNTPT="/etc" +CONFIG_NSH_INITSCRIPT="init.d/rcS" +CONFIG_NSH_ROMFSDEVNO=0 +CONFIG_NSH_ROMFSSECTSIZE=128 +CONFIG_NSH_ARCHROMFS=y +CONFIG_NSH_FATDEVNO=1 +CONFIG_NSH_FATSECTSIZE=512 +CONFIG_NSH_FATNSECTORS=1024 +CONFIG_NSH_FATMOUNTPT="/tmp" +CONFIG_NSH_CONSOLE=y +# CONFIG_NSH_USBCONSOLE is not set + +# +# USB Trace Support +# +# CONFIG_NSH_CONDEV is not set +CONFIG_NSH_ARCHINIT=y + +# +# NxWidgets/NxWM +# + +# +# System NSH Add-Ons +# + +# +# Custom Free Memory Command +# +# CONFIG_SYSTEM_FREE is not set + +# +# I2C tool +# +# CONFIG_SYSTEM_I2CTOOL is not set + +# +# FLASH Program Installation +# +# CONFIG_SYSTEM_INSTALL is not set + +# +# FLASH Erase-all Command +# + +# +# readline() +# +CONFIG_SYSTEM_READLINE=y +CONFIG_READLINE_ECHO=y + +# +# Power Off +# +# CONFIG_SYSTEM_POWEROFF is not set + +# +# RAMTRON +# +# CONFIG_SYSTEM_RAMTRON is not set + +# +# SD Card +# +# CONFIG_SYSTEM_SDCARD is not set + +# +# Sysinfo +# +CONFIG_SYSTEM_SYSINFO=y + +# +# USB Monitor +# diff --git a/nuttx-configs/px4fmu-v1/nsh/setenv.sh b/nuttx-configs/px4fmu-v1/nsh/setenv.sh new file mode 100755 index 0000000000..db372217cd --- /dev/null +++ b/nuttx-configs/px4fmu-v1/nsh/setenv.sh @@ -0,0 +1,75 @@ +#!/bin/bash +# configs/px4fmu-v1/usbnsh/setenv.sh +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +if [ "$_" = "$0" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +WD=`pwd` +if [ ! -x "setenv.sh" ]; then + echo "This script must be executed from the top-level NuttX build directory" + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then + export PATH_ORIG="${PATH}" +fi + +# This is the Cygwin path to the location where I installed the RIDE +# toolchain under windows. You will also have to edit this if you install +# the RIDE toolchain in any other location +#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" + +# This is the Cygwin path to the location where I installed the CodeSourcery +# toolchain under windows. You will also have to edit this if you install +# the CodeSourcery toolchain in any other location +export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" + +# These are the Cygwin paths to the locations where I installed the Atollic +# toolchain under windows. You will also have to edit this if you install +# the Atollic toolchain in any other location. /usr/bin is added before +# the Atollic bin path because there is are binaries named gcc.exe and g++.exe +# at those locations as well. +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin" +#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin" + +# This is the Cygwin path to the location where I build the buildroot +# toolchain. +#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" + +# Add the path to the toolchain to the PATH varialble +export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script new file mode 100644 index 0000000000..ced5b21b7c --- /dev/null +++ b/nuttx-configs/px4fmu-v1/scripts/ld.script @@ -0,0 +1,149 @@ +/**************************************************************************** + * configs/px4fmu-v1/scripts/ld.script + * + * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and + * 192Kb of SRAM. SRAM is split up into three blocks: + * + * 1) 112Kb of SRAM beginning at address 0x2000:0000 + * 2) 16Kb of SRAM beginning at address 0x2001:c000 + * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000 + * + * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 + * where the code expects to begin execution by jumping to the entry point in + * the 0x0800:0000 address range. + * + * The first 0x4000 of flash is reserved for the bootloader. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K +} + +OUTPUT_ARCH(arm) + +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + + /* + * This is a hack to make the newlib libm __errno() call + * use the NuttX get_errno_ptr() function. + */ + __errno = get_errno_ptr; + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + /* + * Construction data for parameters. + */ + __param ALIGN(4): { + __param_start = ABSOLUTE(.); + KEEP(*(__param*)) + __param_end = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4fmu-v1/src/Makefile b/nuttx-configs/px4fmu-v1/src/Makefile new file mode 100644 index 0000000000..6ef8b7d6af --- /dev/null +++ b/nuttx-configs/px4fmu-v1/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/px4fmu-v1/src/Makefile +# +# Copyright (C) 2013 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + $(Q) touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep + diff --git a/nuttx-configs/px4fmu-v1/src/empty.c b/nuttx-configs/px4fmu-v1/src/empty.c new file mode 100644 index 0000000000..ace900866c --- /dev/null +++ b/nuttx-configs/px4fmu-v1/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ diff --git a/nuttx-configs/px4io-v1/include/README.txt b/nuttx-configs/px4io-v1/include/README.txt new file mode 100755 index 0000000000..2264a80aa8 --- /dev/null +++ b/nuttx-configs/px4io-v1/include/README.txt @@ -0,0 +1 @@ +This directory contains header files unique to the PX4IO board. diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h new file mode 100755 index 0000000000..668602ea89 --- /dev/null +++ b/nuttx-configs/px4io-v1/include/board.h @@ -0,0 +1,172 @@ +/************************************************************************************ + * configs/px4io/include/board.h + * include/arch/board/board.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * Copyright (C) 2012 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 NuttX 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. + * + ************************************************************************************/ + +#ifndef __ARCH_BOARD_BOARD_H +#define __ARCH_BOARD_BOARD_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#ifndef __ASSEMBLY__ +# include +# include +#endif +#include +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Clocking *************************************************************************/ + +/* On-board crystal frequency is 24MHz (HSE) */ + +#define STM32_BOARD_XTAL 24000000ul + +/* Use the HSE output as the system clock */ + +#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE +#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE +#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL + +/* AHB clock (HCLK) is SYSCLK (24MHz) */ + +#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK +#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY +#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ + +/* APB2 clock (PCLK2) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK +#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY +#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */ + +/* APB2 timer 1 will receive PCLK2. */ + +#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY) + +/* APB1 clock (PCLK1) is HCLK (24MHz) */ + +#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK +#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY) + +/* All timers run off PCLK */ + +#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY) +#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY) +#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY) + +/* + * Some of the USART pins are not available; override the GPIO + * definitions with an invalid pin configuration. + */ +#undef GPIO_USART2_CTS +#define GPIO_USART2_CTS 0xffffffff +#undef GPIO_USART2_RTS +#define GPIO_USART2_RTS 0xffffffff +#undef GPIO_USART2_CK +#define GPIO_USART2_CK 0xffffffff +#undef GPIO_USART3_TX +#define GPIO_USART3_TX 0xffffffff +#undef GPIO_USART3_CK +#define GPIO_USART3_CK 0xffffffff +#undef GPIO_USART3_CTS +#define GPIO_USART3_CTS 0xffffffff +#undef GPIO_USART3_RTS +#define GPIO_USART3_RTS 0xffffffff + +/* + * High-resolution timer + */ +#ifdef CONFIG_HRT_TIMER +# define HRT_TIMER 1 /* use timer1 for the HRT */ +# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ +#endif + +/* + * PPM + * + * PPM input is handled by the HRT timer. + * + * Pin is PA8, timer 1, channel 1 + */ +#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) +# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +# define GPIO_PPM_IN GPIO_TIM1_CH1IN +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ +/************************************************************************************ + * Name: stm32_boardinitialize + * + * Description: + * All STM32 architectures must provide the following entry point. This entry point + * is called early in the intitialization -- after all memory has been configured + * and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +EXTERN void stm32_boardinitialize(void); + +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_BOARD_BOARD_H */ diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs new file mode 100644 index 0000000000..712631f471 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/Make.defs @@ -0,0 +1,166 @@ +############################################################################ +# configs/px4io-v1/nsh/Make.defs +# +# Copyright (C) 2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX 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. +# +############################################################################ + +include ${TOPDIR}/.config +include ${TOPDIR}/tools/Config.mk + +# +# We only support building with the ARM bare-metal toolchain from +# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. +# +CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI + +include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs + +CC = $(CROSSDEV)gcc +CXX = $(CROSSDEV)g++ +CPP = $(CROSSDEV)gcc -E +LD = $(CROSSDEV)ld +AR = $(CROSSDEV)ar rcs +NM = $(CROSSDEV)nm +OBJCOPY = $(CROSSDEV)objcopy +OBJDUMP = $(CROSSDEV)objdump + +MAXOPTIMIZATION = -O3 +ARCHCPUFLAGS = -mcpu=cortex-m3 \ + -mthumb \ + -march=armv7-m + +# use our linker script +LDSCRIPT = ld.script + +ifeq ($(WINTOOL),y) + # Windows-native toolchains + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" + ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" + ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}" +else + ifeq ($(PX4_WINTOOL),y) + # Windows-native toolchains (MSYS) + DIRLINK = $(TOPDIR)/tools/copydir.sh + DIRUNLINK = $(TOPDIR)/tools/unlink.sh + MKDEP = $(TOPDIR)/tools/mknulldeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + else + # Linux/Cygwin-native toolchain + MKDEP = $(TOPDIR)/tools/mkdeps.sh + ARCHINCLUDES = -I. -isystem $(TOPDIR)/include + ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx + ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT) + endif +endif + +# tool versions +ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} +ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} + +# optimisation flags +ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ + -fno-strict-aliasing \ + -fno-strength-reduce \ + -fomit-frame-pointer \ + -funsafe-math-optimizations \ + -fno-builtin-printf \ + -ffunction-sections \ + -fdata-sections + +ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") +ARCHOPTIMIZATION += -g +endif + +ARCHCFLAGS = -std=gnu99 +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHWARNINGS = -Wall \ + -Wextra \ + -Wdouble-promotion \ + -Wshadow \ + -Wfloat-equal \ + -Wframe-larger-than=1024 \ + -Wpointer-arith \ + -Wlogical-op \ + -Wmissing-declarations \ + -Wpacked \ + -Wno-unused-parameter +# -Wcast-qual - generates spurious noreturn attribute warnings, try again later +# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code +# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives + +ARCHCWARNINGS = $(ARCHWARNINGS) \ + -Wbad-function-cast \ + -Wstrict-prototypes \ + -Wold-style-declaration \ + -Wmissing-parameter-type \ + -Wmissing-prototypes \ + -Wnested-externs \ + -Wunsuffixed-float-constants +ARCHWARNINGSXX = $(ARCHWARNINGS) +ARCHDEFINES = +ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# this seems to be the only way to add linker flags +EXTRA_LIBS += --warn-common \ + --gc-sections + +CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common +CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) +CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe +CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) +CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ + +NXFLATLDFLAGS1 = -r -d -warn-common +NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections +LDNXFLATFLAGS = -e main -s 2048 + +OBJEXT = .o +LIBEXT = .a +EXEEXT = + +# produce partially-linked $1 from files in $2 +define PRELINK + @echo "PRELINK: $1" + $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 +endef + +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx-configs/px4io-v1/nsh/appconfig b/nuttx-configs/px4io-v1/nsh/appconfig new file mode 100644 index 0000000000..48a41bcdb8 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/appconfig @@ -0,0 +1,32 @@ +############################################################################ +# +# Copyright (C) 2012 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. +# +############################################################################ diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig new file mode 100755 index 0000000000..5256722333 --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/defconfig @@ -0,0 +1,559 @@ +############################################################################ +# configs/px4io-v1/nsh/defconfig +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX 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. +# +############################################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_family - for use in C code. This identifies the +# particular chip family that the architecture is implemented +# in. +# CONFIG_ARCH_architecture - for use in C code. This identifies the +# specific architecture within the chip family. +# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory +# CONFIG_ARCH_CHIP_name - For use in C code +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# CONFIG_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization +# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt +# stack. If defined, this symbol is the size of the interrupt +# stack in bytes. If not defined, the user task stacks will be +# used during interrupt handling. +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader. +# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture. +# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture. +# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that +# cause a 100 second delay during boot-up. This 100 second delay +# serves no purpose other than it allows you to calibrate +# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure +# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until +# the delay actually is 100 seconds. +# CONFIG_ARCH_DMA - Support DMA initialization +# +CONFIG_ARCH="arm" +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CORTEXM3=y +CONFIG_ARCH_CHIP="stm32" +CONFIG_ARCH_CHIP_STM32F100C8=y +# +# Board Selection +# +CONFIG_ARCH_BOARD_PX4IO_V1=y +# CONFIG_ARCH_BOARD_CUSTOM is not set +CONFIG_ARCH_BOARD="px4io-v1" +CONFIG_BOARD_LOOPSPERMSEC=2000 +CONFIG_DRAM_SIZE=0x00002000 +CONFIG_DRAM_START=0x20000000 +CONFIG_ARCH_IRQPRIO=y +CONFIG_ARCH_INTERRUPTSTACK=n +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARCH_BOOTLOADER=n +CONFIG_ARCH_LEDS=n +CONFIG_ARCH_BUTTONS=n +CONFIG_ARCH_CALIBRATION=n +CONFIG_ARCH_DMA=y +CONFIG_ARCH_MATH_H=y + +CONFIG_ARMV7M_CMNVECTOR=y +# CONFIG_ARMV7M_STACKCHECK is not set + +# +# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): +# +# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG +# +# JTAG Enable options: +# +# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP) +# but without JNTRST. +# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled +# +CONFIG_STM32_DFU=n +CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=n + +# +# Individual subsystems can be enabled: +# +# AHB: +CONFIG_STM32_DMA1=y +CONFIG_STM32_DMA2=n +CONFIG_STM32_CRC=n +# APB1: +# Timers 2,3 and 4 are owned by the PWM driver +CONFIG_STM32_TIM2=n +CONFIG_STM32_TIM3=n +CONFIG_STM32_TIM4=n +CONFIG_STM32_TIM5=n +CONFIG_STM32_TIM6=n +CONFIG_STM32_TIM7=n +CONFIG_STM32_WWDG=n +CONFIG_STM32_SPI2=n +CONFIG_STM32_USART2=y +CONFIG_STM32_USART3=y +CONFIG_STM32_I2C1=y +CONFIG_STM32_I2C2=n +CONFIG_STM32_BKP=n +CONFIG_STM32_PWR=n +CONFIG_STM32_DAC=n +# APB2: +# We use our own ADC driver, but leave this on for clocking purposes. +CONFIG_STM32_ADC1=y +CONFIG_STM32_ADC2=n +# TIM1 is owned by the HRT +CONFIG_STM32_TIM1=n +CONFIG_STM32_SPI1=n +CONFIG_STM32_TIM8=n +CONFIG_STM32_USART1=y +CONFIG_STM32_ADC3=n + + +# +# STM32F100 specific serial device driver settings +# +# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the +# console and ttys0 (default is the USART1). +# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_USARTn_2STOP - Two stop bits +# +CONFIG_SERIAL_TERMIOS=y +CONFIG_STANDARD_SERIAL=y + +CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART2_SERIAL_CONSOLE=n +CONFIG_USART3_SERIAL_CONSOLE=n + +CONFIG_USART1_TXBUFSIZE=64 +CONFIG_USART2_TXBUFSIZE=64 +CONFIG_USART3_TXBUFSIZE=64 + +CONFIG_USART1_RXBUFSIZE=64 +CONFIG_USART2_RXBUFSIZE=64 +CONFIG_USART3_RXBUFSIZE=64 + +CONFIG_USART1_BAUD=115200 +CONFIG_USART2_BAUD=115200 +CONFIG_USART3_BAUD=115200 + +CONFIG_USART1_BITS=8 +CONFIG_USART2_BITS=8 +CONFIG_USART3_BITS=8 + +CONFIG_USART1_PARITY=0 +CONFIG_USART2_PARITY=0 +CONFIG_USART3_PARITY=0 + +CONFIG_USART1_2STOP=0 +CONFIG_USART2_2STOP=0 +CONFIG_USART3_2STOP=0 + +CONFIG_USART1_RXDMA=y +SERIAL_HAVE_CONSOLE_DMA=y +# Conflicts with I2C1 DMA +CONFIG_USART2_RXDMA=n +CONFIG_USART3_RXDMA=y + +# +# PX4IO specific driver settings +# +# CONFIG_HRT_TIMER +# Enables the high-resolution timer. The board definition must +# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ +# compare channels to be used. +# CONFIG_HRT_PPM +# Enables R/C PPM input using the HRT. The board definition must +# set HRT_PPM_CHANNEL to the timer capture/compare channel to be +# used, and define GPIO_PPM_IN to configure the appropriate timer +# GPIO. +# CONFIG_PWM_SERVO +# Enables the PWM servo driver. The driver configuration must be +# supplied by the board support at initialisation time. +# Note that USART2 must be disabled on the PX4 board for this to +# be available. +# +# +CONFIG_HRT_TIMER=y +CONFIG_HRT_PPM=y + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com using the tools/mkimage.sh script +# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format +# used with many different loaders using the GNU objcopy program +# Should not be selected if you are not using the GNU toolchain. +# CONFIG_RAW_BINARY - make a raw binary format file used with many +# different loaders using the GNU objcopy program. This option +# should not be selected if you are not using the GNU toolchain. +# CONFIG_HAVE_LIBM - toolchain supports libm.a +# +CONFIG_RRLOAD_BINARY=n +CONFIG_INTELHEX_BINARY=n +CONFIG_MOTOROLA_SREC=n +CONFIG_RAW_BINARY=y +CONFIG_HAVE_LIBM=n + +# +# General OS setup +# +# CONFIG_APPS_DIR - Identifies the relative path to the directory +# that builds the application to link with NuttX. Default: ../apps +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_DEBUG_SYMBOLS - build without optimization and with +# debug symbols (needed for use with a debugger). +# CONFIG_HAVE_CXX - Enable support for C++ +# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support +# for initialization of static C++ instances for this architecture +# and for the selected toolchain (via up_cxxinitialize()). +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz +# or MSEC_PER_TICK=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. +# You would only need this if you are concerned about accurate +# time conversions in the past or in the distant future. +# CONFIG_JULIAN_TIME - Enables Julian time conversions. You +# would only need this if you are concerned about accurate +# time conversion in the distand past. You must also define +# CONFIG_GREGORIAN_TIME in order to use Julian time. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console +# driver (minimul support) +# CONFIG_MUTEX_TYPES: Set to enable support for recursive and +# errorcheck mutexes. Enables pthread_mutexattr_settype(). +# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority +# inheritance on mutexes and semaphores. +# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority +# inheritance is enabled. It defines the maximum number of +# different threads (minus one) that can take counts on a +# semaphore with priority inheritance support. This may be +# set to zero if priority inheritance is disabled OR if you +# are only using semaphores as mutexes (only one holder) OR +# if no more than two threads participate using a counting +# semaphore. +# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled, +# then this setting is the maximum number of higher priority +# threads (minus 1) than can be waiting for another thread +# to release a count on a semaphore. This value may be set +# to zero if no more than one thread is expected to wait for +# a semaphore. +# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors +# by task_create() when a new task is started. If set, all +# files/drivers will appear to be closed in the new task. +# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first +# three file descriptors (stdin, stdout, stderr) by task_create() +# when a new task is started. If set, all files/drivers will +# appear to be closed in the new task except for stdin, stdout, +# and stderr. +# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket +# desciptors by task_create() when a new task is started. If +# set, all sockets will appear to be closed in the new task. +# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to +# handle delayed processing from interrupt handlers. This feature +# is required for some drivers but, if there are not complaints, +# can be safely disabled. The worker thread also performs +# garbage collection -- completing any delayed memory deallocations +# from interrupt handlers. If the worker thread is disabled, +# then that clean will be performed by the IDLE thread instead +# (which runs at the lowest of priority and may not be appropriate +# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE +# is enabled, then the following options can also be used: +# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker +# thread. Default: 50 +# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for +# work in units of microseconds. Default: 50*1000 (50 MS). +# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker +# thread. Default: CONFIG_IDLETHREAD_STACKSIZE. +# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up +# the worker thread. Default: 4 +# CONFIG_SCHED_WAITPID - Enable the waitpid() API +# CONFIG_SCHED_ATEXIT - Enabled the atexit() API +# +CONFIG_USER_ENTRYPOINT="user_start" +#CONFIG_APPS_DIR= +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_FS=n +CONFIG_DEBUG_GRAPHICS=n +CONFIG_DEBUG_LCD=n +CONFIG_DEBUG_USB=n +CONFIG_DEBUG_NET=n +CONFIG_DEBUG_RTC=n +CONFIG_DEBUG_ANALOG=n +CONFIG_DEBUG_PWM=n +CONFIG_DEBUG_CAN=n +CONFIG_DEBUG_I2C=n +CONFIG_DEBUG_INPUT=n + +CONFIG_MSEC_PER_TICK=1 +CONFIG_HAVE_CXX=y +CONFIG_HAVE_CXXINITIALIZE=y +CONFIG_MM_REGIONS=1 +CONFIG_MM_SMALL=y +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=8 +CONFIG_START_YEAR=1970 +CONFIG_START_MONTH=1 +CONFIG_START_DAY=1 +CONFIG_GREGORIAN_TIME=n +CONFIG_JULIAN_TIME=n +# this eats ~1KiB of RAM ... work out why +CONFIG_DEV_CONSOLE=y +CONFIG_DEV_LOWCONSOLE=n +CONFIG_MUTEX_TYPES=n +CONFIG_PRIORITY_INHERITANCE=n +CONFIG_SEM_PREALLOCHOLDERS=0 +CONFIG_SEM_NNESTPRIO=0 +CONFIG_FDCLONE_DISABLE=y +CONFIG_FDCLONE_STDIO=y +CONFIG_SDCLONE_DISABLE=y +CONFIG_SCHED_WORKQUEUE=n +CONFIG_SCHED_WORKPRIORITY=50 +CONFIG_SCHED_WORKPERIOD=50000 +CONFIG_SCHED_WORKSTACKSIZE=1024 +CONFIG_SIG_SIGWORK=4 +CONFIG_SCHED_WAITPID=n +CONFIG_SCHED_ATEXIT=n + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=y +CONFIG_DISABLE_PTHREAD=y +CONFIG_DISABLE_SIGNALS=y +CONFIG_DISABLE_MQUEUE=y +CONFIG_DISABLE_MOUNTPOINT=y +CONFIG_DISABLE_ENVIRON=y +CONFIG_DISABLE_POLL=y + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve system performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_STRNLEN=n +CONFIG_ARCH_BZERO=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled +# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added +# to force automatic, line-oriented flushing the output buffer +# for putc(), fputc(), putchar(), puts(), fputs(), printf(), +# fprintf(), and vfprintf(). When a newline is encountered in +# the output string, the output buffer will be flushed. This +# (slightly) increases the NuttX footprint but supports the kind +# of behavior that people expect for printf(). +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=4 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=2 +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NFILE_STREAMS=0 +CONFIG_NAME_MAX=12 +CONFIG_STDIO_BUFFER_SIZE=32 +CONFIG_STDIO_LINEBUFFER=n +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=4 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=2 +CONFIG_PREALLOC_WDOGS=4 +CONFIG_PREALLOC_TIMERS=0 + + +# +# Settings for apps/nshlib +# +# CONFIG_NSH_BUILTIN_APPS - Support external registered, +# "named" applications that can be executed from the NSH +# command line (see apps/README.txt for more information). +# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer +# CONFIG_NSH_STRERROR - Use strerror(errno) +# CONFIG_NSH_LINELEN - Maximum length of one command line +# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi +# CONFIG_NSH_DISABLESCRIPT - Disable scripting support +# CONFIG_NSH_DISABLEBG - Disable background commands +# CONFIG_NSH_ROMFSETC - Use startup script in /etc +# CONFIG_NSH_CONSOLE - Use serial console front end +# CONFIG_NSH_TELNET - Use telnetd console front end +# CONFIG_NSH_ARCHINIT - Platform provides architecture +# specific initialization (nsh_archinitialize()). +# + +# Disable NSH completely +CONFIG_NSH_CONSOLE=n + +# +# Stack and heap information +# +# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP +# operation from FLASH but must copy initialized .data sections to RAM. +# (should also be =n for the STM3210E-EVAL which always runs from flash) +# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH +# but copy themselves entirely into RAM for better performance. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only) +# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack. +# This is the thread that (1) performs the inital boot of the system up +# to the point where user_start() is spawned, and (2) there after is the +# IDLE thread that executes only when there is no other thread ready to +# run. +# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate +# for the main user thread that begins at the user_start() entry point. +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_RUNFROMFLASH=n +CONFIG_BOOT_COPYTORAM=n +CONFIG_CUSTOM_STACK=n +CONFIG_STACK_POINTER= +CONFIG_IDLETHREAD_STACKSIZE=1024 +CONFIG_USERMAIN_STACKSIZE=1200 +CONFIG_PTHREAD_STACK_MIN=512 +CONFIG_PTHREAD_STACK_DEFAULT=1024 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= + +# +# NSH Library +# +# CONFIG_NSH_LIBRARY is not set +# CONFIG_NSH_BUILTIN_APPS is not set diff --git a/nuttx-configs/px4io-v1/nsh/setenv.sh b/nuttx-configs/px4io-v1/nsh/setenv.sh new file mode 100755 index 0000000000..ff9a4bf8ae --- /dev/null +++ b/nuttx-configs/px4io-v1/nsh/setenv.sh @@ -0,0 +1,47 @@ +#!/bin/bash +# configs/stm3210e-eval/dfu/setenv.sh +# +# Copyright (C) 2009 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +if [ "$(basename $0)" = "setenv.sh" ] ; then + echo "You must source this script, not run it!" 1>&2 + exit 1 +fi + +if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi + +WD=`pwd` +export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin" +export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" +export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" + +echo "PATH : ${PATH}" diff --git a/nuttx-configs/px4io-v1/scripts/ld.script b/nuttx-configs/px4io-v1/scripts/ld.script new file mode 100755 index 0000000000..69c2f9cb2e --- /dev/null +++ b/nuttx-configs/px4io-v1/scripts/ld.script @@ -0,0 +1,129 @@ +/**************************************************************************** + * configs/stm3210e-eval/nsh/ld.script + * + * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and + * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH, + * FLASH memory is aliased to address 0x0000:0000 where the code expects to + * begin execution by jumping to the entry point in the 0x0800:0000 address + * range. + */ + +MEMORY +{ + flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K + sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K +} + +OUTPUT_ARCH(arm) +ENTRY(__start) /* treat __start as the anchor for dead code stripping */ +EXTERN(_vectors) /* force the vectors to be included in the output */ + +/* + * Ensure that abort() is present in the final object. The exception handling + * code pulled in by libgcc.a requires it (and that code cannot be easily avoided). + */ +EXTERN(abort) + +SECTIONS +{ + .text : { + _stext = ABSOLUTE(.); + *(.vectors) + *(.text .text.*) + *(.fixup) + *(.gnu.warning) + *(.rodata .rodata.*) + *(.gnu.linkonce.t.*) + *(.glue_7) + *(.glue_7t) + *(.got) + *(.gcc_except_table) + *(.gnu.linkonce.r.*) + _etext = ABSOLUTE(.); + } > flash + + /* + * Init functions (static constructors and the like) + */ + .init_section : { + _sinit = ABSOLUTE(.); + KEEP(*(.init_array .init_array.*)) + _einit = ABSOLUTE(.); + } > flash + + .ARM.extab : { + *(.ARM.extab*) + } > flash + + __exidx_start = ABSOLUTE(.); + .ARM.exidx : { + *(.ARM.exidx*) + } > flash + __exidx_end = ABSOLUTE(.); + + _eronly = ABSOLUTE(.); + + /* The STM32F100CB has 8Kb of SRAM beginning at the following address */ + + .data : { + _sdata = ABSOLUTE(.); + *(.data .data.*) + *(.gnu.linkonce.d.*) + CONSTRUCTORS + _edata = ABSOLUTE(.); + } > sram AT > flash + + .bss : { + _sbss = ABSOLUTE(.); + *(.bss .bss.*) + *(.gnu.linkonce.b.*) + *(COMMON) + _ebss = ABSOLUTE(.); + } > sram + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_info 0 : { *(.debug_info) } + .debug_line 0 : { *(.debug_line) } + .debug_pubnames 0 : { *(.debug_pubnames) } + .debug_aranges 0 : { *(.debug_aranges) } +} diff --git a/nuttx-configs/px4io-v1/src/Makefile b/nuttx-configs/px4io-v1/src/Makefile new file mode 100644 index 0000000000..bb9539d16a --- /dev/null +++ b/nuttx-configs/px4io-v1/src/Makefile @@ -0,0 +1,84 @@ +############################################################################ +# configs/stm3210e-eval/src/Makefile +# +# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 NuttX 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. +# +############################################################################ + +-include $(TOPDIR)/Make.defs + +CFLAGS += -I$(TOPDIR)/sched + +ASRCS = +AOBJS = $(ASRCS:.S=$(OBJEXT)) + +CSRCS = empty.c + +COBJS = $(CSRCS:.c=$(OBJEXT)) + +SRCS = $(ASRCS) $(CSRCS) +OBJS = $(AOBJS) $(COBJS) + +ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src +ifeq ($(WINTOOL),y) + CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" +else + CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m +endif + +all: libboard$(LIBEXT) + +$(AOBJS): %$(OBJEXT): %.S + $(call ASSEMBLE, $<, $@) + +$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c + $(call COMPILE, $<, $@) + +libboard$(LIBEXT): $(OBJS) + $(call ARCHIVE, $@, $(OBJS)) + +.depend: Makefile $(SRCS) + @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep + @touch $@ + +depend: .depend + +clean: + $(call DELFILE, libboard$(LIBEXT)) + $(call CLEAN) + +distclean: clean + $(call DELFILE, Make.dep) + $(call DELFILE, .depend) + +-include Make.dep diff --git a/nuttx-configs/px4io-v1/src/empty.c b/nuttx-configs/px4io-v1/src/empty.c new file mode 100644 index 0000000000..ace900866c --- /dev/null +++ b/nuttx-configs/px4io-v1/src/empty.c @@ -0,0 +1,4 @@ +/* + * There are no source files here, but libboard.a can't be empty, so + * we have this empty source file to keep it company. + */ From ce2fa29fe3f0abeb01482e9932078f3cb25378a6 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 10:06:34 -0700 Subject: [PATCH 37/88] Add a missing module -> module makefile dependency --- makefiles/firmware.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index f1c1b496a0..3ad13088b0 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -385,7 +385,7 @@ define BUILTIN_DEF endef # Don't generate until modules have updated their command files -$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES) +$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(MODULE_MKFILES) $(BUILTIN_COMMAND_FILES) @$(ECHO) "CMDS: $@" $(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@ $(Q) $(ECHO) '#include ' >> $@ From 97b75951b13b9f4a79058d11f4c8923444ebc544 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 3 Aug 2013 14:33:43 -0400 Subject: [PATCH 38/88] Shortened segway param names. --- src/modules/segway/BlockSegwayController.cpp | 2 +- src/modules/segway/BlockSegwayController.hpp | 8 ++++---- src/modules/segway/params.c | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp index 682758a14b..b1dc39445f 100644 --- a/src/modules/segway/BlockSegwayController.cpp +++ b/src/modules/segway/BlockSegwayController.cpp @@ -31,7 +31,7 @@ void BlockSegwayController::update() { } // compute speed command - float spdCmd = -theta2spd.update(_att.pitch) - q2spd.update(_att.pitchspeed); + float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed); // handle autopilot modes if (_status.state_machine == SYSTEM_STATE_AUTO || diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp index e2faa49169..4a01f785c5 100644 --- a/src/modules/segway/BlockSegwayController.hpp +++ b/src/modules/segway/BlockSegwayController.hpp @@ -8,8 +8,8 @@ class BlockSegwayController : public control::BlockUorbEnabledAutopilot { public: BlockSegwayController() : BlockUorbEnabledAutopilot(NULL,"SEG"), - theta2spd(this, "THETA2SPD"), - q2spd(this, "Q2SPD"), + th2v(this, "TH2V"), + q2v(this, "Q2V"), _attPoll(), _timeStamp(0) { @@ -19,8 +19,8 @@ public: void update(); private: enum {CH_LEFT, CH_RIGHT}; - BlockPI theta2spd; - BlockP q2spd; + BlockPI th2v; + BlockP q2v; struct pollfd _attPoll; uint64_t _timeStamp; }; diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c index 1669785d31..d729237174 100644 --- a/src/modules/segway/params.c +++ b/src/modules/segway/params.c @@ -1,8 +1,8 @@ #include // 16 is max name length -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_P, 10.0f); // pitch to speed -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I, 0.0f); // pitch integral to speed -PARAM_DEFINE_FLOAT(SEG_THETA2SPD_I_MAX, 0.0f); // integral limiter -PARAM_DEFINE_FLOAT(SEG_Q2SPD, 1.0f); // pitch rate to speed +PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage +PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage +PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter +PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage From 9a97001cc849038223aa5eda6a76ac0fc6f1094f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 01:50:58 +0200 Subject: [PATCH 39/88] Added queue to mpu6k driver --- src/drivers/mpu6000/mpu6000.cpp | 254 +++++++++++++++++++++++++------- 1 file changed, 201 insertions(+), 53 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 1fd6cb17e7..d37d39a7ab 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -181,13 +181,21 @@ private: struct hrt_call _call; unsigned _call_interval; - struct accel_report _accel_report; + unsigned _num_accel_reports; + volatile unsigned _next_accel_report; + volatile unsigned _oldest_accel_report; + struct accel_report *_accel_reports; + struct accel_scale _accel_scale; float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; - struct gyro_report _gyro_report; + unsigned _num_gyro_reports; + volatile unsigned _next_gyro_report; + volatile unsigned _oldest_gyro_report; + struct gyro_report *_gyro_reports; + struct gyro_scale _gyro_scale; float _gyro_range_scale; float _gyro_range_rad_s; @@ -306,14 +314,25 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } +/* helper macro for handling report buffer indices */ +#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) + MPU6000::MPU6000(int bus, spi_dev_e device) : SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 10000000), _gyro(new MPU6000_gyro(this)), _product(0), _call_interval(0), + _num_accel_reports(0), + _next_accel_report(0), + _oldest_accel_report(0), + _accel_reports(nullptr), _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), + _num_gyro_reports(0), + _next_gyro_report(0), + _oldest_gyro_report(0), + _gyro_reports(nullptr), _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), _gyro_topic(-1), @@ -340,8 +359,6 @@ MPU6000::MPU6000(int bus, spi_dev_e device) : _gyro_scale.z_offset = 0; _gyro_scale.z_scale = 1.0f; - memset(&_accel_report, 0, sizeof(_accel_report)); - memset(&_gyro_report, 0, sizeof(_gyro_report)); memset(&_call, 0, sizeof(_call)); } @@ -353,6 +370,12 @@ MPU6000::~MPU6000() /* delete the gyro subdriver */ delete _gyro; + /* free any existing reports */ + if (_accel_reports != nullptr) + delete[] _accel_reports; + if (_gyro_reports != nullptr) + delete[] _gyro_reports; + /* delete the perf counter */ perf_free(_sample_perf); } @@ -361,6 +384,7 @@ int MPU6000::init() { int ret; + int gyro_ret; /* do SPI init (and probe) first */ ret = SPI::init(); @@ -371,6 +395,21 @@ MPU6000::init() return ret; } + /* allocate basic report buffers */ + _num_accel_reports = 2; + _oldest_accel_report = _next_accel_report = 0; + _accel_reports = new struct accel_report[_num_accel_reports]; + + if (_accel_reports == nullptr) + goto out; + + _num_gyro_reports = 2; + _oldest_gyro_report = _next_gyro_report = 0; + _gyro_reports = new struct gyro_report[_num_gyro_reports]; + + if (_gyro_reports == nullptr) + goto out; + // Chip reset write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET); up_udelay(10000); @@ -462,7 +501,10 @@ MPU6000::init() usleep(1000); /* do CDev init for the gyro device node, keep it optional */ - int gyro_ret = _gyro->init(); + gyro_ret = _gyro->init(); + + memset(&_accel_reports[0], 0, sizeof(_accel_reports[0])); + memset(&_gyro_reports[0], 0, sizeof(_gyro_reports[0])); /* ensure we got real values to share */ measure(); @@ -470,12 +512,13 @@ MPU6000::init() if (gyro_ret != OK) { _gyro_topic = -1; } else { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report); + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_reports[0]); } - /* advertise sensor topics */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report); + /* advertise accel topic */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_reports[0]); +out: return ret; } @@ -555,19 +598,40 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz) ssize_t MPU6000::read(struct file *filp, char *buffer, size_t buflen) { + unsigned count = buflen / sizeof(struct accel_report); int ret = 0; /* buffer must be large enough */ - if (buflen < sizeof(_accel_report)) + if (count < 1) return -ENOSPC; - /* if automatic measurement is not enabled */ - if (_call_interval == 0) - measure(); + /* if automatic measurement is enabled */ + if (_call_interval > 0) { - /* copy out the latest reports */ - memcpy(buffer, &_accel_report, sizeof(_accel_report)); - ret = sizeof(_accel_report); + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the measurement code while we are doing this; + * we are careful to avoid racing with it. + */ + while (count--) { + if (_oldest_accel_report != _next_accel_report) { + memcpy(buffer, _accel_reports + _oldest_accel_report, sizeof(*_accel_reports)); + ret += sizeof(_accel_reports[0]); + INCREMENT(_oldest_accel_report, _num_accel_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement */ + _oldest_accel_report = _next_accel_report = 0; + measure(); + + /* measurement will have generated a report, copy it out */ + memcpy(buffer, _accel_reports, sizeof(*_accel_reports)); + ret = sizeof(*_accel_reports); return ret; } @@ -586,19 +650,40 @@ MPU6000::self_test() ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { + unsigned count = buflen / sizeof(struct gyro_report); int ret = 0; /* buffer must be large enough */ - if (buflen < sizeof(_gyro_report)) + if (count < 1) return -ENOSPC; - /* if automatic measurement is not enabled */ - if (_call_interval == 0) - measure(); + /* if automatic measurement is enabled */ + if (_call_interval > 0) { - /* copy out the latest report */ - memcpy(buffer, &_gyro_report, sizeof(_gyro_report)); - ret = sizeof(_gyro_report); + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the measurement code while we are doing this; + * we are careful to avoid racing with it. + */ + while (count--) { + if (_oldest_gyro_report != _next_gyro_report) { + memcpy(buffer, _gyro_reports + _oldest_gyro_report, sizeof(*_gyro_reports)); + ret += sizeof(_gyro_reports[0]); + INCREMENT(_oldest_gyro_report, _num_gyro_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement */ + _oldest_gyro_report = _next_gyro_report = 0; + measure(); + + /* measurement will have generated a report, copy it out */ + memcpy(buffer, _gyro_reports, sizeof(*_gyro_reports)); + ret = sizeof(*_gyro_reports); return ret; } @@ -661,14 +746,32 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return 1000000 / _call_interval; - case SENSORIOCSQUEUEDEPTH: - /* XXX not implemented */ - return -EINVAL; + case SENSORIOCSQUEUEDEPTH: { + /* account for sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct accel_report *buf = new struct accel_report[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _accel_reports; + _num_accel_reports = arg; + _accel_reports = buf; + start(); + + return OK; + } case SENSORIOCGQUEUEDEPTH: - /* XXX not implemented */ - return -EINVAL; - + return _num_accel_reports - 1; case ACCELIOCGSAMPLERATE: return _sample_rate; @@ -726,11 +829,36 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) /* these are shared with the accel side */ case SENSORIOCSPOLLRATE: case SENSORIOCGPOLLRATE: - case SENSORIOCSQUEUEDEPTH: - case SENSORIOCGQUEUEDEPTH: case SENSORIOCRESET: return ioctl(filp, cmd, arg); + case SENSORIOCSQUEUEDEPTH: { + /* account for sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct gyro_report *buf = new struct gyro_report[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _gyro_reports; + _num_gyro_reports = arg; + _gyro_reports = buf; + start(); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _num_gyro_reports - 1; + case GYROIOCGSAMPLERATE: return _sample_rate; @@ -959,10 +1087,16 @@ MPU6000::measure() report.gyro_x = gyro_xt; report.gyro_y = gyro_yt; + /* + * Get references to the current reports + */ + accel_report *accel_report = &_accel_reports[_next_accel_report]; + gyro_report *gyro_report = &_gyro_reports[_next_gyro_report]; + /* * Adjust and scale results to m/s^2. */ - _gyro_report.timestamp = _accel_report.timestamp = hrt_absolute_time(); + gyro_report->timestamp = accel_report->timestamp = hrt_absolute_time(); /* @@ -983,40 +1117,54 @@ MPU6000::measure() /* NOTE: Axes have been swapped to match the board a few lines above. */ - _accel_report.x_raw = report.accel_x; - _accel_report.y_raw = report.accel_y; - _accel_report.z_raw = report.accel_z; + accel_report->x_raw = report.accel_x; + accel_report->y_raw = report.accel_y; + accel_report->z_raw = report.accel_z; - _accel_report.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - _accel_report.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - _accel_report.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; - _accel_report.scaling = _accel_range_scale; - _accel_report.range_m_s2 = _accel_range_m_s2; + accel_report->x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + accel_report->y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + accel_report->z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + accel_report->scaling = _accel_range_scale; + accel_report->range_m_s2 = _accel_range_m_s2; - _accel_report.temperature_raw = report.temp; - _accel_report.temperature = (report.temp) / 361.0f + 35.0f; + accel_report->temperature_raw = report.temp; + accel_report->temperature = (report.temp) / 361.0f + 35.0f; - _gyro_report.x_raw = report.gyro_x; - _gyro_report.y_raw = report.gyro_y; - _gyro_report.z_raw = report.gyro_z; + gyro_report->x_raw = report.gyro_x; + gyro_report->y_raw = report.gyro_y; + gyro_report->z_raw = report.gyro_z; - _gyro_report.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - _gyro_report.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - _gyro_report.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; - _gyro_report.scaling = _gyro_range_scale; - _gyro_report.range_rad_s = _gyro_range_rad_s; + gyro_report->x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + gyro_report->y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + gyro_report->z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + gyro_report->scaling = _gyro_range_scale; + gyro_report->range_rad_s = _gyro_range_rad_s; - _gyro_report.temperature_raw = report.temp; - _gyro_report.temperature = (report.temp) / 361.0f + 35.0f; + gyro_report->temperature_raw = report.temp; + gyro_report->temperature = (report.temp) / 361.0f + 35.0f; + + /* ACCEL: post a report to the ring - note, not locked */ + INCREMENT(_next_accel_report, _num_accel_reports); + + /* ACCEL: if we are running up against the oldest report, fix it */ + if (_next_accel_report == _oldest_accel_report) + INCREMENT(_oldest_accel_report, _num_accel_reports); + + /* GYRO: post a report to the ring - note, not locked */ + INCREMENT(_next_gyro_report, _num_gyro_reports); + + /* GYRO: if we are running up against the oldest report, fix it */ + if (_next_gyro_report == _oldest_gyro_report) + INCREMENT(_oldest_gyro_report, _num_gyro_reports); /* notify anyone waiting for data */ poll_notify(POLLIN); _gyro->parent_poll_notify(); /* and publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report); + orb_publish(ORB_ID(sensor_accel), _accel_topic, accel_report); if (_gyro_topic != -1) { - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report); + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, gyro_report); } /* stop measuring */ From 234ad240818e6486d39a3149597956a534d59ea0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 21 Jul 2013 23:46:37 -0700 Subject: [PATCH 40/88] Simple ring-buffer template class, because re-implementing the wheel in every driver is silly. --- src/drivers/device/ringbuffer.h | 192 ++++++++++++++++++++++++++++++++ 1 file changed, 192 insertions(+) create mode 100644 src/drivers/device/ringbuffer.h diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h new file mode 100644 index 0000000000..37686fdbe3 --- /dev/null +++ b/src/drivers/device/ringbuffer.h @@ -0,0 +1,192 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * 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 ringbuffer.h + * + * A simple ringbuffer template. + */ + +#pragma once + +template +class RingBuffer { +public: + RingBuffer(unsigned size); + virtual ~RingBuffer(); + + /** + * Put an item into the buffer. + * + * @param val Item to put + * @return true if the item was put, false if the buffer is full + */ + bool put(T &val); + + /** + * Put an item into the buffer. + * + * @param val Item to put + * @return true if the item was put, false if the buffer is full + */ + bool put(const T &val); + + /** + * Get an item from the buffer. + * + * @param val Item that was gotten + * @return true if an item was got, false if the buffer was empty. + */ + bool get(T &val); + + /** + * Get an item from the buffer (scalars only). + * + * @return The value that was fetched, or zero if the buffer was + * empty. + */ + T get(void); + + /* + * Get the number of slots free in the buffer. + * + * @return The number of items that can be put into the buffer before + * it becomes full. + */ + unsigned space(void); + + /* + * Get the number of items in the buffer. + * + * @return The number of items that can be got from the buffer before + * it becomes empty. + */ + unsigned count(void); + + /* + * Returns true if the buffer is empty. + */ + bool empty() { return _tail == _head; } + + /* + * Returns true if the buffer is full. + */ + bool full() { return _next(_head) == _tail; } + +private: + T *const _buf; + const unsigned _size; + volatile unsigned _head; /**< insertion point */ + volatile unsigned _tail; /**< removal point */ + + unsigned _next(unsigned index); +}; + +template +RingBuffer::RingBuffer(unsigned size) : + _buf(new T[size + 1]), + _size(size), + _head(size), + _tail(size) +{} + +template +RingBuffer::~RingBuffer() +{ + if (_buf != nullptr) + delete[] _buf; +} + +template +bool RingBuffer::put(T &val) +{ + unsigned next = _next(_head); + if (next != _tail) { + _buf[_head] = val; + _head = next; + return true; + } else { + return false; + } +} + +template +bool RingBuffer::put(const T &val) +{ + unsigned next = _next(_head); + if (next != _tail) { + _buf[_head] = val; + _head = next; + return true; + } else { + return false; + } +} + +template +bool RingBuffer::get(T &val) +{ + if (_tail != _head) { + val = _buf[_tail]; + _tail = _next(_tail); + return true; + } else { + return false; + } +} + +template +T RingBuffer::get(void) +{ + T val; + return get(val) ? val : 0; +} + +template +unsigned RingBuffer::space(void) +{ + return (_tail >= _head) ? (_size - (_tail - _head)) : (_head - _tail - 1); +} + +template +unsigned RingBuffer::count(void) +{ + return _size - space(); +} + +template +unsigned RingBuffer::_next(unsigned index) +{ + return (0 == index) ? _size : (index - 1); +} From a3ab88872cbca30be62b04461c8294399923ec89 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 19:02:54 -0700 Subject: [PATCH 41/88] Add some more useful methods to the ringbuffer class. --- src/drivers/device/ringbuffer.h | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index 37686fdbe3..dc0c84052b 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -104,6 +104,17 @@ public: */ bool full() { return _next(_head) == _tail; } + /* + * Returns the capacity of the buffer, or zero if the buffer could + * not be allocated. + */ + unsigned size() { return (_buf != nullptr) ? _size : 0; } + + /* + * Empties the buffer. + */ + void flush() { _head = _tail = _size; } + private: T *const _buf; const unsigned _size; @@ -114,11 +125,11 @@ private: }; template -RingBuffer::RingBuffer(unsigned size) : - _buf(new T[size + 1]), - _size(size), - _head(size), - _tail(size) +RingBuffer::RingBuffer(unsigned with_size) : + _buf(new T[with_size + 1]), + _size(with_size), + _head(with_size), + _tail(with_size) {} template From 02f5b79948742d6b7121399e39444286cc01f161 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 3 Aug 2013 19:03:24 -0700 Subject: [PATCH 42/88] Try to save our sanity a bit and use the generic ringbuffer class rather than re-implementing the wheel. --- src/drivers/mpu6000/mpu6000.cpp | 255 +++++++++++++------------------- 1 file changed, 104 insertions(+), 151 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index d37d39a7ab..f848cca6b8 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -67,6 +67,7 @@ #include #include +#include #include #include @@ -181,20 +182,16 @@ private: struct hrt_call _call; unsigned _call_interval; - unsigned _num_accel_reports; - volatile unsigned _next_accel_report; - volatile unsigned _oldest_accel_report; - struct accel_report *_accel_reports; + typedef RingBuffer AccelReportBuffer; + AccelReportBuffer *_accel_reports; struct accel_scale _accel_scale; float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; - unsigned _num_gyro_reports; - volatile unsigned _next_gyro_report; - volatile unsigned _oldest_gyro_report; - struct gyro_report *_gyro_reports; + typedef RingBuffer GyroReportBuffer; + GyroReportBuffer *_gyro_reports; struct gyro_scale _gyro_scale; float _gyro_range_scale; @@ -227,7 +224,7 @@ private: static void measure_trampoline(void *arg); /** - * Fetch measurements from the sensor and update the report ring. + * Fetch measurements from the sensor and update the report buffers. */ void measure(); @@ -314,24 +311,15 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } -/* helper macro for handling report buffer indices */ -#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) - MPU6000::MPU6000(int bus, spi_dev_e device) : SPI("MPU6000", ACCEL_DEVICE_PATH, bus, device, SPIDEV_MODE3, 10000000), _gyro(new MPU6000_gyro(this)), _product(0), _call_interval(0), - _num_accel_reports(0), - _next_accel_report(0), - _oldest_accel_report(0), _accel_reports(nullptr), _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), - _num_gyro_reports(0), - _next_gyro_report(0), - _oldest_gyro_report(0), _gyro_reports(nullptr), _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), @@ -372,9 +360,9 @@ MPU6000::~MPU6000() /* free any existing reports */ if (_accel_reports != nullptr) - delete[] _accel_reports; + delete _accel_reports; if (_gyro_reports != nullptr) - delete[] _gyro_reports; + delete _gyro_reports; /* delete the perf counter */ perf_free(_sample_perf); @@ -396,17 +384,11 @@ MPU6000::init() } /* allocate basic report buffers */ - _num_accel_reports = 2; - _oldest_accel_report = _next_accel_report = 0; - _accel_reports = new struct accel_report[_num_accel_reports]; - + _accel_reports = new AccelReportBuffer(2); if (_accel_reports == nullptr) goto out; - _num_gyro_reports = 2; - _oldest_gyro_report = _next_gyro_report = 0; - _gyro_reports = new struct gyro_report[_num_gyro_reports]; - + _gyro_reports = new GyroReportBuffer(2); if (_gyro_reports == nullptr) goto out; @@ -503,20 +485,22 @@ MPU6000::init() /* do CDev init for the gyro device node, keep it optional */ gyro_ret = _gyro->init(); - memset(&_accel_reports[0], 0, sizeof(_accel_reports[0])); - memset(&_gyro_reports[0], 0, sizeof(_gyro_reports[0])); - - /* ensure we got real values to share */ + /* fetch an initial set of measurements for advertisement */ measure(); if (gyro_ret != OK) { _gyro_topic = -1; } else { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_reports[0]); + gyro_report gr; + _gyro_reports->get(gr); + + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); } /* advertise accel topic */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_reports[0]); + accel_report ar; + _accel_reports->get(ar); + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); out: return ret; @@ -598,42 +582,31 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz) ssize_t MPU6000::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct accel_report); - int ret = 0; + unsigned count = buflen / sizeof(accel_report); /* buffer must be large enough */ if (count < 1) return -ENOSPC; - /* if automatic measurement is enabled */ - if (_call_interval > 0) { - - /* - * While there is space in the caller's buffer, and reports, copy them. - * Note that we may be pre-empted by the measurement code while we are doing this; - * we are careful to avoid racing with it. - */ - while (count--) { - if (_oldest_accel_report != _next_accel_report) { - memcpy(buffer, _accel_reports + _oldest_accel_report, sizeof(*_accel_reports)); - ret += sizeof(_accel_reports[0]); - INCREMENT(_oldest_accel_report, _num_accel_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; + /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ + if (_call_interval == 0) { + _accel_reports->flush(); + measure(); } - /* manual measurement */ - _oldest_accel_report = _next_accel_report = 0; - measure(); + /* if no data, error (we could block here) */ + if (_accel_reports->empty()) + return -EAGAIN; - /* measurement will have generated a report, copy it out */ - memcpy(buffer, _accel_reports, sizeof(*_accel_reports)); - ret = sizeof(*_accel_reports); + /* copy reports out of our buffer to the caller */ + accel_report *arp = reinterpret_cast(buffer); + while (count--) { + if (!_accel_reports->get(*arp++)) + break; + } - return ret; + /* return the number of bytes transferred */ + return (buflen - (count * sizeof(accel_report))); } int @@ -651,41 +624,30 @@ ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { unsigned count = buflen / sizeof(struct gyro_report); - int ret = 0; /* buffer must be large enough */ if (count < 1) return -ENOSPC; - /* if automatic measurement is enabled */ - if (_call_interval > 0) { - - /* - * While there is space in the caller's buffer, and reports, copy them. - * Note that we may be pre-empted by the measurement code while we are doing this; - * we are careful to avoid racing with it. - */ - while (count--) { - if (_oldest_gyro_report != _next_gyro_report) { - memcpy(buffer, _gyro_reports + _oldest_gyro_report, sizeof(*_gyro_reports)); - ret += sizeof(_gyro_reports[0]); - INCREMENT(_oldest_gyro_report, _num_gyro_reports); - } - } - - /* if there was no data, warn the caller */ - return ret ? ret : -EAGAIN; + /* if automatic measurement is not enabled, get a fresh measurement into the buffer */ + if (_call_interval == 0) { + _gyro_reports->flush(); + measure(); } - /* manual measurement */ - _oldest_gyro_report = _next_gyro_report = 0; - measure(); + /* if no data, error (we could block here) */ + if (_gyro_reports->empty()) + return -EAGAIN; - /* measurement will have generated a report, copy it out */ - memcpy(buffer, _gyro_reports, sizeof(*_gyro_reports)); - ret = sizeof(*_gyro_reports); + /* copy reports out of our buffer to the caller */ + gyro_report *arp = reinterpret_cast(buffer); + while (count--) { + if (!_gyro_reports->get(*arp++)) + break; + } - return ret; + /* return the number of bytes transferred */ + return (buflen - (count * sizeof(gyro_report))); } int @@ -747,23 +709,23 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return 1000000 / _call_interval; case SENSORIOCSQUEUEDEPTH: { - /* account for sentinel in the ring */ - arg++; - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) + if ((arg < 1) || (arg > 100)) return -EINVAL; /* allocate new buffer */ - struct accel_report *buf = new struct accel_report[arg]; + AccelReportBuffer *buf = new AccelReportBuffer(arg); if (nullptr == buf) return -ENOMEM; + if (buf->size() == 0) { + delete buf; + return -ENOMEM; + } /* reset the measurement state machine with the new buffer, free the old */ stop(); - delete[] _accel_reports; - _num_accel_reports = arg; + delete _accel_reports; _accel_reports = buf; start(); @@ -771,14 +733,14 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) } case SENSORIOCGQUEUEDEPTH: - return _num_accel_reports - 1; + return _accel_reports->size(); case ACCELIOCGSAMPLERATE: return _sample_rate; case ACCELIOCSSAMPLERATE: - _set_sample_rate(arg); - return OK; + _set_sample_rate(arg); + return OK; case ACCELIOCSLOWPASS: case ACCELIOCGLOWPASS: @@ -833,23 +795,23 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) return ioctl(filp, cmd, arg); case SENSORIOCSQUEUEDEPTH: { - /* account for sentinel in the ring */ - arg++; - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 2) || (arg > 100)) + if ((arg < 1) || (arg > 100)) return -EINVAL; /* allocate new buffer */ - struct gyro_report *buf = new struct gyro_report[arg]; + GyroReportBuffer *buf = new GyroReportBuffer(arg); if (nullptr == buf) return -ENOMEM; + if (buf->size() == 0) { + delete buf; + return -ENOMEM; + } /* reset the measurement state machine with the new buffer, free the old */ stop(); - delete[] _gyro_reports; - _num_gyro_reports = arg; + delete _gyro_reports; _gyro_reports = buf; start(); @@ -857,7 +819,7 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) } case SENSORIOCGQUEUEDEPTH: - return _num_gyro_reports - 1; + return _gyro_reports->size(); case GYROIOCGSAMPLERATE: return _sample_rate; @@ -993,6 +955,10 @@ MPU6000::start() /* make sure we are stopped first */ stop(); + /* discard any stale data in the buffers */ + _accel_reports->flush(); + _gyro_reports->flush(); + /* start polling at the specified rate */ hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&MPU6000::measure_trampoline, this); } @@ -1006,7 +972,7 @@ MPU6000::stop() void MPU6000::measure_trampoline(void *arg) { - MPU6000 *dev = (MPU6000 *)arg; + MPU6000 *dev = reinterpret_cast(arg); /* make another measurement */ dev->measure(); @@ -1088,15 +1054,15 @@ MPU6000::measure() report.gyro_y = gyro_yt; /* - * Get references to the current reports + * Report buffers. */ - accel_report *accel_report = &_accel_reports[_next_accel_report]; - gyro_report *gyro_report = &_gyro_reports[_next_gyro_report]; + accel_report arb; + gyro_report grb; /* * Adjust and scale results to m/s^2. */ - gyro_report->timestamp = accel_report->timestamp = hrt_absolute_time(); + grb.timestamp = arb.timestamp = hrt_absolute_time(); /* @@ -1117,54 +1083,43 @@ MPU6000::measure() /* NOTE: Axes have been swapped to match the board a few lines above. */ - accel_report->x_raw = report.accel_x; - accel_report->y_raw = report.accel_y; - accel_report->z_raw = report.accel_z; + arb.x_raw = report.accel_x; + arb.y_raw = report.accel_y; + arb.z_raw = report.accel_z; - accel_report->x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - accel_report->y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - accel_report->z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; - accel_report->scaling = _accel_range_scale; - accel_report->range_m_s2 = _accel_range_m_s2; + arb.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + arb.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + arb.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + arb.scaling = _accel_range_scale; + arb.range_m_s2 = _accel_range_m_s2; - accel_report->temperature_raw = report.temp; - accel_report->temperature = (report.temp) / 361.0f + 35.0f; + arb.temperature_raw = report.temp; + arb.temperature = (report.temp) / 361.0f + 35.0f; - gyro_report->x_raw = report.gyro_x; - gyro_report->y_raw = report.gyro_y; - gyro_report->z_raw = report.gyro_z; + grb.x_raw = report.gyro_x; + grb.y_raw = report.gyro_y; + grb.z_raw = report.gyro_z; - gyro_report->x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - gyro_report->y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - gyro_report->z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; - gyro_report->scaling = _gyro_range_scale; - gyro_report->range_rad_s = _gyro_range_rad_s; + grb.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + grb.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + grb.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + grb.scaling = _gyro_range_scale; + grb.range_rad_s = _gyro_range_rad_s; - gyro_report->temperature_raw = report.temp; - gyro_report->temperature = (report.temp) / 361.0f + 35.0f; + grb.temperature_raw = report.temp; + grb.temperature = (report.temp) / 361.0f + 35.0f; - /* ACCEL: post a report to the ring - note, not locked */ - INCREMENT(_next_accel_report, _num_accel_reports); - - /* ACCEL: if we are running up against the oldest report, fix it */ - if (_next_accel_report == _oldest_accel_report) - INCREMENT(_oldest_accel_report, _num_accel_reports); - - /* GYRO: post a report to the ring - note, not locked */ - INCREMENT(_next_gyro_report, _num_gyro_reports); - - /* GYRO: if we are running up against the oldest report, fix it */ - if (_next_gyro_report == _oldest_gyro_report) - INCREMENT(_oldest_gyro_report, _num_gyro_reports); + _accel_reports->put(arb); + _gyro_reports->put(grb); /* notify anyone waiting for data */ poll_notify(POLLIN); _gyro->parent_poll_notify(); /* and publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, accel_report); + orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); if (_gyro_topic != -1) { - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, gyro_report); + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &grb); } /* stop measuring */ @@ -1267,21 +1222,19 @@ fail: void test() { - int fd = -1; - int fd_gyro = -1; - struct accel_report a_report; - struct gyro_report g_report; + accel_report a_report; + gyro_report g_report; ssize_t sz; /* get the driver */ - fd = open(ACCEL_DEVICE_PATH, O_RDONLY); + int fd = open(ACCEL_DEVICE_PATH, O_RDONLY); if (fd < 0) err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)", ACCEL_DEVICE_PATH); /* get the driver */ - fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY); + int fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY); if (fd_gyro < 0) err(1, "%s open failed", GYRO_DEVICE_PATH); From f45e74265e3952f350970d665adccdf539e136f2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 15:15:41 +0200 Subject: [PATCH 43/88] Fixed driver test / direct read, looks good --- src/drivers/mpu6000/mpu6000.cpp | 111 ++++++++++++++++++++------------ 1 file changed, 70 insertions(+), 41 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index f848cca6b8..9dcb4be9ed 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -212,6 +212,13 @@ private: */ void stop(); + /** + * Reset chip. + * + * Resets the chip and measurements ranges, but not scale and offset. + */ + void reset(); + /** * Static trampoline from the hrt_call context; because we don't have a * generic hrt wrapper yet. @@ -392,6 +399,50 @@ MPU6000::init() if (_gyro_reports == nullptr) goto out; + reset(); + + /* Initialize offsets and scales */ + _accel_scale.x_offset = 0; + _accel_scale.x_scale = 1.0f; + _accel_scale.y_offset = 0; + _accel_scale.y_scale = 1.0f; + _accel_scale.z_offset = 0; + _accel_scale.z_scale = 1.0f; + + _gyro_scale.x_offset = 0; + _gyro_scale.x_scale = 1.0f; + _gyro_scale.y_offset = 0; + _gyro_scale.y_scale = 1.0f; + _gyro_scale.z_offset = 0; + _gyro_scale.z_scale = 1.0f; + + /* do CDev init for the gyro device node, keep it optional */ + gyro_ret = _gyro->init(); + + /* fetch an initial set of measurements for advertisement */ + measure(); + + if (gyro_ret != OK) { + _gyro_topic = -1; + } else { + gyro_report gr; + _gyro_reports->get(gr); + + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); + } + + /* advertise accel topic */ + accel_report ar; + _accel_reports->get(ar); + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); + +out: + return ret; +} + +void MPU6000::reset() +{ + // Chip reset write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET); up_udelay(10000); @@ -423,12 +474,6 @@ MPU6000::init() // 2000 deg/s = (2000/180)*PI = 34.906585 rad/s // scaling factor: // 1/(2^15)*(2000/180)*PI - _gyro_scale.x_offset = 0; - _gyro_scale.x_scale = 1.0f; - _gyro_scale.y_offset = 0; - _gyro_scale.y_scale = 1.0f; - _gyro_scale.z_offset = 0; - _gyro_scale.z_scale = 1.0f; _gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F); _gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F; @@ -461,12 +506,6 @@ MPU6000::init() // Correct accel scale factors of 4096 LSB/g // scale to m/s^2 ( 1g = 9.81 m/s^2) - _accel_scale.x_offset = 0; - _accel_scale.x_scale = 1.0f; - _accel_scale.y_offset = 0; - _accel_scale.y_scale = 1.0f; - _accel_scale.z_offset = 0; - _accel_scale.z_scale = 1.0f; _accel_range_scale = (9.81f / 4096.0f); _accel_range_m_s2 = 8.0f * 9.81f; @@ -482,28 +521,6 @@ MPU6000::init() // write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ); usleep(1000); - /* do CDev init for the gyro device node, keep it optional */ - gyro_ret = _gyro->init(); - - /* fetch an initial set of measurements for advertisement */ - measure(); - - if (gyro_ret != OK) { - _gyro_topic = -1; - } else { - gyro_report gr; - _gyro_reports->get(gr); - - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); - } - - /* advertise accel topic */ - accel_report ar; - _accel_reports->get(ar); - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); - -out: - return ret; } int @@ -600,13 +617,15 @@ MPU6000::read(struct file *filp, char *buffer, size_t buflen) /* copy reports out of our buffer to the caller */ accel_report *arp = reinterpret_cast(buffer); + int transferred = 0; while (count--) { if (!_accel_reports->get(*arp++)) break; + transferred++; } /* return the number of bytes transferred */ - return (buflen - (count * sizeof(accel_report))); + return (transferred * sizeof(accel_report)); } int @@ -623,7 +642,7 @@ MPU6000::self_test() ssize_t MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct gyro_report); + unsigned count = buflen / sizeof(gyro_report); /* buffer must be large enough */ if (count < 1) @@ -641,13 +660,15 @@ MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen) /* copy reports out of our buffer to the caller */ gyro_report *arp = reinterpret_cast(buffer); + int transferred = 0; while (count--) { if (!_gyro_reports->get(*arp++)) break; + transferred++; } /* return the number of bytes transferred */ - return (buflen - (count * sizeof(gyro_report))); + return (transferred * sizeof(gyro_report)); } int @@ -655,6 +676,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) { switch (cmd) { + case SENSORIOCRESET: + reset(); + return OK; + case SENSORIOCSPOLLRATE: { switch (arg) { @@ -674,8 +699,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) /* set default/max polling rate */ case SENSOR_POLLRATE_MAX: case SENSOR_POLLRATE_DEFAULT: - /* XXX 500Hz is just a wild guess */ - return ioctl(filp, SENSORIOCSPOLLRATE, 500); + /* set to same as sample rate per default */ + return ioctl(filp, SENSORIOCSPOLLRATE, _sample_rate); /* adjust to a legal polling interval in Hz */ default: { @@ -1246,8 +1271,10 @@ test() /* do a simple demand read */ sz = read(fd, &a_report, sizeof(a_report)); - if (sz != sizeof(a_report)) + if (sz != sizeof(a_report)) { + warnx("ret: %d, expected: %d", sz, sizeof(a_report)); err(1, "immediate acc read failed"); + } warnx("single read"); warnx("time: %lld", a_report.timestamp); @@ -1263,8 +1290,10 @@ test() /* do a simple demand read */ sz = read(fd_gyro, &g_report, sizeof(g_report)); - if (sz != sizeof(g_report)) + if (sz != sizeof(g_report)) { + warnx("ret: %d, expected: %d", sz, sizeof(g_report)); err(1, "immediate gyro read failed"); + } warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x); warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y); From 9bcabc5ba90d225f63e16f00595682fd4a4b857a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:09:10 +0200 Subject: [PATCH 44/88] Hotfix for attitude estimator EKF init --- .../attitude_estimator_ekf_main.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp index 1eff60e88f..9e533ccdfb 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -224,8 +224,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* subscribe to raw data */ int sub_raw = orb_subscribe(ORB_ID(sensor_combined)); - /* rate-limit raw data updates to 200Hz */ - orb_set_interval(sub_raw, 4); + /* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */ + orb_set_interval(sub_raw, 3); /* subscribe to param changes */ int sub_params = orb_subscribe(ORB_ID(parameter_update)); @@ -236,7 +236,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* advertise attitude */ orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att); - int loopcounter = 0; int printcounter = 0; @@ -384,7 +383,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds static bool const_initialized = false; /* initialize with good values once we have a reasonable dt estimate */ - if (!const_initialized && dt < 0.05f && dt > 0.005f) { + if (!const_initialized && dt < 0.05f && dt > 0.001f) { dt = 0.005f; parameters_update(&ekf_param_handles, &ekf_params); @@ -424,7 +423,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds continue; } - if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data); + if (last_data > 0 && raw.timestamp - last_data > 12000) + printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data); last_data = raw.timestamp; From 36cca7a31b428408eb686df592f092ba5fc24006 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:10:56 +0200 Subject: [PATCH 45/88] Added rate limit in sensors app. Just pending accel filters now --- src/modules/sensors/sensors.cpp | 66 +++++++++++++++++++++++++++++++-- 1 file changed, 63 insertions(+), 3 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 7ff9e19b4c..0f1782fca6 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -92,8 +92,35 @@ #define BARO_HEALTH_COUNTER_LIMIT_OK 5 #define ADC_HEALTH_COUNTER_LIMIT_OK 5 -#define ADC_BATTERY_VOLTAGE_CHANNEL 10 -#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 +/** + * Analog layout: + * FMU: + * IN2 - battery voltage + * IN3 - battery current + * IN4 - 5V sense + * IN10 - spare (we could actually trim these from the set) + * IN11 - spare (we could actually trim these from the set) + * IN12 - spare (we could actually trim these from the set) + * IN13 - aux1 + * IN14 - aux2 + * IN15 - pressure sensor + * + * IO: + * IN4 - servo supply rail + * IN5 - analog RSSI + */ + +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + #define ADC_BATTERY_VOLTAGE_CHANNEL 10 + #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11 +#endif + +#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 + #define ADC_BATTERY_VOLTAGE_CHANNEL 2 + #define ADC_BATTERY_CURRENT_CHANNEL 3 + #define ADC_5V_RAIL_SENSE 4 + #define ADC_AIRSPEED_VOLTAGE_CHANNEL 15 +#endif #define BAT_VOL_INITIAL 0.f #define BAT_VOL_LOWPASS_1 0.99f @@ -731,12 +758,27 @@ Sensors::accel_init() errx(1, "FATAL: no accelerometer found"); } else { + + // XXX do the check more elegantly + + #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + /* set the accel internal sampling rate up to at leat 500Hz */ ioctl(fd, ACCELIOCSSAMPLERATE, 500); /* set the driver to poll at 500Hz */ ioctl(fd, SENSORIOCSPOLLRATE, 500); + #else + + /* set the accel internal sampling rate up to at leat 800Hz */ + ioctl(fd, ACCELIOCSSAMPLERATE, 800); + + /* set the driver to poll at 800Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 800); + + #endif + warnx("using system accel"); close(fd); } @@ -754,12 +796,27 @@ Sensors::gyro_init() errx(1, "FATAL: no gyro found"); } else { + + // XXX do the check more elegantly + + #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 + /* set the gyro internal sampling rate up to at leat 500Hz */ ioctl(fd, GYROIOCSSAMPLERATE, 500); /* set the driver to poll at 500Hz */ ioctl(fd, SENSORIOCSPOLLRATE, 500); + #else + + /* set the gyro internal sampling rate up to at leat 800Hz */ + ioctl(fd, GYROIOCSSAMPLERATE, 800); + + /* set the driver to poll at 800Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 800); + + #endif + warnx("using system gyro"); close(fd); } @@ -1360,6 +1417,9 @@ Sensors::task_main() /* rate limit vehicle status updates to 5Hz */ orb_set_interval(_vstatus_sub, 200); + /* rate limit gyro to 250 Hz (the gyro signal is lowpassed accordingly earlier) */ + orb_set_interval(_gyro_sub, 4); + /* * do advertisements */ @@ -1395,7 +1455,7 @@ Sensors::task_main() while (!_task_should_exit) { - /* wait for up to 500ms for data */ + /* wait for up to 100ms for data */ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); /* timed out - periodic check for _task_should_exit, etc. */ From ac89322d74ac1f5a29a6665feb4220aba3025f82 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 4 Aug 2013 15:09:16 +1000 Subject: [PATCH 46/88] mathlib: added LowPassFilter2p object used in gyro and accel drivers for better filtering --- .../mathlib/math/filter/LowPassFilter2p.cpp | 77 ++++++++++++++++++ .../mathlib/math/filter/LowPassFilter2p.hpp | 78 +++++++++++++++++++ src/modules/mathlib/math/filter/module.mk | 44 +++++++++++ 3 files changed, 199 insertions(+) create mode 100644 src/modules/mathlib/math/filter/LowPassFilter2p.cpp create mode 100644 src/modules/mathlib/math/filter/LowPassFilter2p.hpp create mode 100644 src/modules/mathlib/math/filter/module.mk diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.cpp b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp new file mode 100644 index 0000000000..efb17225d2 --- /dev/null +++ b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp @@ -0,0 +1,77 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/**************************************************************************** + * + * Copyright (C) 2012 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 LowPassFilter.cpp +/// @brief A class to implement a second order low pass filter +/// Author: Leonard Hall + +#include "LowPassFilter2p.hpp" +#include "math.h" + +namespace math +{ + +void LowPassFilter2p::set_cutoff_frequency(float sample_freq, float cutoff_freq) +{ + _cutoff_freq = cutoff_freq; + float fr = sample_freq/_cutoff_freq; + float ohm = tanf(M_PI_F/fr); + float c = 1.0f+2.0f*cosf(M_PI_F/4.0f)*ohm + ohm*ohm; + _b0 = ohm*ohm/c; + _b1 = 2.0f*_b0; + _b2 = _b0; + _a1 = 2.0f*(ohm*ohm-1.0f)/c; + _a2 = (1.0f-2.0f*cosf(M_PI_F/4.0f)*ohm+ohm*ohm)/c; +} + +float LowPassFilter2p::apply(float sample) +{ + // do the filtering + float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2; + if (isnan(delay_element_0) || isinf(delay_element_0)) { + // don't allow bad values to propogate via the filter + delay_element_0 = sample; + } + float output = delay_element_0 * _b0 + _delay_element_1 * _b1 + _delay_element_2 * _b2; + + _delay_element_2 = _delay_element_1; + _delay_element_1 = delay_element_0; + + // return the value. Should be no need to check limits + return output; +} + +} // namespace math + diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.hpp b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp new file mode 100644 index 0000000000..208ec98d4e --- /dev/null +++ b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp @@ -0,0 +1,78 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- + +/**************************************************************************** + * + * Copyright (C) 2012 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 LowPassFilter.h +/// @brief A class to implement a second order low pass filter +/// Author: Leonard Hall +/// Adapted for PX4 by Andrew Tridgell + +#pragma once + +namespace math +{ +class __EXPORT LowPassFilter2p +{ +public: + // constructor + LowPassFilter2p(float sample_freq, float cutoff_freq) { + // set initial parameters + set_cutoff_frequency(sample_freq, cutoff_freq); + _delay_element_1 = _delay_element_2 = 0; + } + + // change parameters + void set_cutoff_frequency(float sample_freq, float cutoff_freq); + + // apply - Add a new raw value to the filter + // and retrieve the filtered result + float apply(float sample); + + // return the cutoff frequency + float get_cutoff_freq(void) const { + return _cutoff_freq; + } + +private: + float _cutoff_freq; + float _a1; + float _a2; + float _b0; + float _b1; + float _b2; + float _delay_element_1; // buffered sample -1 + float _delay_element_2; // buffered sample -2 +}; + +} // namespace math diff --git a/src/modules/mathlib/math/filter/module.mk b/src/modules/mathlib/math/filter/module.mk new file mode 100644 index 0000000000..fe92c8c70f --- /dev/null +++ b/src/modules/mathlib/math/filter/module.mk @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 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. +# +############################################################################ + +# +# filter library +# +SRCS = LowPassFilter2p.cpp + +# +# In order to include .config we first have to save off the +# current makefile name, since app.mk needs it. +# +APP_MAKEFILE := $(lastword $(MAKEFILE_LIST)) +-include $(TOPDIR)/.config From 7c3ee6714c0e184c297ffced880488a41e7d255d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 Aug 2013 19:14:25 +0200 Subject: [PATCH 47/88] Enabled mathlib --- 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 e6ec840f9a..38cf437e03 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -94,6 +94,7 @@ MODULES += modules/sdlog2 MODULES += modules/systemlib MODULES += modules/systemlib/mixer MODULES += modules/mathlib +MODULES += modules/mathlib/math/filter MODULES += modules/controllib MODULES += modules/uORB From 97e4909d9e7c835b73c2eebdf4991d395c4ffb3f Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:40:57 -0700 Subject: [PATCH 48/88] Improvements to the HX stream protocol implementation. --- src/modules/systemlib/hx_stream.c | 191 ++++++++++++++++++++---------- src/modules/systemlib/hx_stream.h | 42 ++++++- 2 files changed, 167 insertions(+), 66 deletions(-) diff --git a/src/modules/systemlib/hx_stream.c b/src/modules/systemlib/hx_stream.c index 8d77f14a8d..8e9c2bfcf6 100644 --- a/src/modules/systemlib/hx_stream.c +++ b/src/modules/systemlib/hx_stream.c @@ -53,14 +53,26 @@ struct hx_stream { - uint8_t buf[HX_STREAM_MAX_FRAME + 4]; - unsigned frame_bytes; - bool escaped; - bool txerror; + /* RX state */ + uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4]; + unsigned rx_frame_bytes; + bool rx_escaped; + hx_stream_rx_callback rx_callback; + void *rx_callback_arg; + /* TX state */ int fd; - hx_stream_rx_callback callback; - void *callback_arg; + bool tx_error; + uint8_t *tx_buf; + unsigned tx_resid; + uint32_t tx_crc; + enum { + TX_IDLE = 0, + TX_SEND_START, + TX_SEND_DATA, + TX_SENT_ESCAPE, + TX_SEND_END + } tx_state; perf_counter_t pc_tx_frames; perf_counter_t pc_rx_frames; @@ -81,21 +93,7 @@ static void hx_tx_raw(hx_stream_t stream, uint8_t c) { if (write(stream->fd, &c, 1) != 1) - stream->txerror = true; -} - -static void -hx_tx_byte(hx_stream_t stream, uint8_t c) -{ - switch (c) { - case FBO: - case CEO: - hx_tx_raw(stream, CEO); - c ^= 0x20; - break; - } - - hx_tx_raw(stream, c); + stream->tx_error = true; } static int @@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream) uint8_t b[4]; uint32_t w; } u; - unsigned length = stream->frame_bytes; + unsigned length = stream->rx_frame_bytes; /* reset the stream */ - stream->frame_bytes = 0; - stream->escaped = false; + stream->rx_frame_bytes = 0; + stream->rx_escaped = false; /* not a real frame - too short */ if (length < 4) { @@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream) length -= 4; /* compute expected CRC */ - u.w = crc32(&stream->buf[0], length); + u.w = crc32(&stream->rx_buf[0], length); /* compare computed and actual CRC */ for (unsigned i = 0; i < 4; i++) { - if (u.b[i] != stream->buf[length + i]) { + if (u.b[i] != stream->rx_buf[length + i]) { perf_count(stream->pc_rx_errors); return 0; } @@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream) /* frame is good */ perf_count(stream->pc_rx_frames); - stream->callback(stream->callback_arg, &stream->buf[0], length); + stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length); return 1; } @@ -150,8 +148,8 @@ hx_stream_init(int fd, if (stream != NULL) { memset(stream, 0, sizeof(struct hx_stream)); stream->fd = fd; - stream->callback = callback; - stream->callback_arg = arg; + stream->rx_callback = callback; + stream->rx_callback_arg = arg; } return stream; @@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream, stream->pc_rx_errors = rx_errors; } +void +hx_stream_reset(hx_stream_t stream) +{ + stream->rx_frame_bytes = 0; + stream->rx_escaped = false; + + stream->tx_buf = NULL; + stream->tx_resid = 0; + stream->tx_state = TX_IDLE; +} + +int +hx_stream_start(hx_stream_t stream, + const void *data, + size_t count) +{ + if (count > HX_STREAM_MAX_FRAME) + return -EINVAL; + + stream->tx_buf = data; + stream->tx_resid = count; + stream->tx_state = TX_SEND_START; + stream->tx_crc = crc32(data, count); + return OK; +} + +int +hx_stream_send_next(hx_stream_t stream) +{ + int c; + + /* sort out what we're going to send */ + switch (stream->tx_state) { + + case TX_SEND_START: + stream->tx_state = TX_SEND_DATA; + return FBO; + + case TX_SEND_DATA: + c = *stream->tx_buf; + + switch (c) { + case FBO: + case CEO: + stream->tx_state = TX_SENT_ESCAPE; + return CEO; + } + break; + + case TX_SENT_ESCAPE: + c = *stream->tx_buf ^ 0x20; + stream->tx_state = TX_SEND_DATA; + break; + + case TX_SEND_END: + stream->tx_state = TX_IDLE; + return FBO; + + case TX_IDLE: + default: + return -1; + } + + /* if we are here, we have consumed a byte from the buffer */ + stream->tx_resid--; + stream->tx_buf++; + + /* buffer exhausted */ + if (stream->tx_resid == 0) { + uint8_t *pcrc = (uint8_t *)&stream->tx_crc; + + /* was the buffer the frame CRC? */ + if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) { + stream->tx_state = TX_SEND_END; + } else { + /* no, it was the payload - switch to sending the CRC */ + stream->tx_buf = pcrc; + stream->tx_resid = sizeof(stream->tx_crc); + } + } + return c; +} + int hx_stream_send(hx_stream_t stream, const void *data, size_t count) { - union { - uint8_t b[4]; - uint32_t w; - } u; - const uint8_t *p = (const uint8_t *)data; - unsigned resid = count; + int result; - if (resid > HX_STREAM_MAX_FRAME) - return -EINVAL; + result = hx_stream_start(stream, data, count); + if (result != OK) + return result; - /* start the frame */ - hx_tx_raw(stream, FBO); - - /* transmit the data */ - while (resid--) - hx_tx_byte(stream, *p++); - - /* compute the CRC */ - u.w = crc32(data, count); - - /* send the CRC */ - p = &u.b[0]; - resid = 4; - - while (resid--) - hx_tx_byte(stream, *p++); - - /* and the trailing frame separator */ - hx_tx_raw(stream, FBO); + int c; + while ((c = hx_stream_send_next(stream)) >= 0) + hx_tx_raw(stream, c); /* check for transmit error */ - if (stream->txerror) { - stream->txerror = false; + if (stream->tx_error) { + stream->tx_error = false; return -EIO; } perf_count(stream->pc_tx_frames); - return 0; + return OK; } void @@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c) } /* escaped? */ - if (stream->escaped) { - stream->escaped = false; + if (stream->rx_escaped) { + stream->rx_escaped = false; c ^= 0x20; } else if (c == CEO) { - /* now escaped, ignore the byte */ - stream->escaped = true; + /* now rx_escaped, ignore the byte */ + stream->rx_escaped = true; return; } /* save for later */ - if (stream->frame_bytes < sizeof(stream->buf)) - stream->buf[stream->frame_bytes++] = c; + if (stream->rx_frame_bytes < sizeof(stream->rx_buf)) + stream->rx_buf[stream->rx_frame_bytes++] = c; } diff --git a/src/modules/systemlib/hx_stream.h b/src/modules/systemlib/hx_stream.h index 128689953a..1f3927222a 100644 --- a/src/modules/systemlib/hx_stream.h +++ b/src/modules/systemlib/hx_stream.h @@ -58,7 +58,8 @@ __BEGIN_DECLS * Allocate a new hx_stream object. * * @param fd The file handle over which the protocol will - * communicate. + * communicate, or -1 if the protocol will use + * hx_stream_start/hx_stream_send_next. * @param callback Called when a frame is received. * @param callback_arg Passed to the callback. * @return A handle to the stream, or NULL if memory could @@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream); * * Any counter may be set to NULL to disable counting that datum. * + * @param stream A handle returned from hx_stream_init. * @param tx_frames Counter for transmitted frames. * @param rx_frames Counter for received frames. * @param rx_errors Counter for short and corrupt received frames. @@ -89,6 +91,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream, perf_counter_t rx_frames, perf_counter_t rx_errors); +/** + * Reset a stream. + * + * Forces the local stream state to idle. + * + * @param stream A handle returned from hx_stream_init. + */ +__EXPORT extern void hx_stream_reset(hx_stream_t stream); + +/** + * Prepare to send a frame. + * + * Use this in conjunction with hx_stream_send_next to + * set the frame to be transmitted. + * + * Use hx_stream_send() to write to the stream fd directly. + * + * @param stream A handle returned from hx_stream_init. + * @param data Pointer to the data to send. + * @param count The number of bytes to send. + * @return Zero on success, -errno on error. + */ +__EXPORT extern int hx_stream_start(hx_stream_t stream, + const void *data, + size_t count); + +/** + * Get the next byte to send for a stream. + * + * This requires that the stream be prepared for sending by + * calling hx_stream_start first. + * + * @param stream A handle returned from hx_stream_init. + * @return The byte to send, or -1 if there is + * nothing left to send. + */ +__EXPORT extern int hx_stream_send_next(hx_stream_t stream); + /** * Send a frame. * From c33048b52186b88ddab2a9c9fdad24c7b64e7e22 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:42:16 -0700 Subject: [PATCH 49/88] Add the ability to cancel a begin/end perf counter if the begin turns out to have been in error. --- src/modules/systemlib/perf_counter.c | 41 +++++++++++++++++++++++----- src/modules/systemlib/perf_counter.h | 14 +++++++++- 2 files changed, 47 insertions(+), 8 deletions(-) diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c index 879f4715af..3c1e10287d 100644 --- a/src/modules/systemlib/perf_counter.c +++ b/src/modules/systemlib/perf_counter.c @@ -201,23 +201,50 @@ perf_end(perf_counter_t handle) switch (handle->type) { case PC_ELAPSED: { struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; - hrt_abstime elapsed = hrt_absolute_time() - pce->time_start; - pce->event_count++; - pce->time_total += elapsed; + if (pce->time_start != 0) { + hrt_abstime elapsed = hrt_absolute_time() - pce->time_start; - if ((pce->time_least > elapsed) || (pce->time_least == 0)) - pce->time_least = elapsed; + pce->event_count++; + pce->time_total += elapsed; - if (pce->time_most < elapsed) - pce->time_most = elapsed; + if ((pce->time_least > elapsed) || (pce->time_least == 0)) + pce->time_least = elapsed; + + if (pce->time_most < elapsed) + pce->time_most = elapsed; + + pce->time_start = 0; + } } + break; default: break; } } +void +perf_cancel(perf_counter_t handle) +{ + if (handle == NULL) + return; + + switch (handle->type) { + case PC_ELAPSED: { + struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; + + pce->time_start = 0; + } + break; + + default: + break; + } +} + + + void perf_reset(perf_counter_t handle) { diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h index 5c2cb15b2f..4cd8b67a17 100644 --- a/src/modules/systemlib/perf_counter.h +++ b/src/modules/systemlib/perf_counter.h @@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle); * End a performance event. * * This call applies to counters that operate over ranges of time; PC_ELAPSED etc. + * If a call is made without a corresopnding perf_begin call, or if perf_cancel + * has been called subsequently, no change is made to the counter. * * @param handle The handle returned from perf_alloc. */ __EXPORT extern void perf_end(perf_counter_t handle); /** - * Reset a performance event. + * Cancel a performance event. + * + * This call applies to counters that operate over ranges of time; PC_ELAPSED etc. + * It reverts the effect of a previous perf_begin. + * + * @param handle The handle returned from perf_alloc. + */ +__EXPORT extern void perf_cancel(perf_counter_t handle); + +/** + * Reset a performance counter. * * This call resets performance counter to initial state * From 567f621754f1f68ed0aae560e9590805045fa3e0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:43:05 -0700 Subject: [PATCH 50/88] Fix an issue with the pwm_servo driver when using one of the STM32 advanced timers. --- src/drivers/stm32/drv_pwm_servo.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c index 7b060412cd..dbb45a1380 100644 --- a/src/drivers/stm32/drv_pwm_servo.c +++ b/src/drivers/stm32/drv_pwm_servo.c @@ -88,6 +88,7 @@ #define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET) #define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET) #define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET) +#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET) static void pwm_timer_init(unsigned timer); static void pwm_timer_set_rate(unsigned timer, unsigned rate); @@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer) rCCER(timer) = 0; rDCR(timer) = 0; + if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) { + /* master output enable = on */ + rBDTR(timer) = ATIM_BDTR_MOE; + } + /* configure the timer to free-run at 1MHz */ rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1; From 4b4f33e6a4fb18047a6ca73d3a4872a900519b5c Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:48:20 -0700 Subject: [PATCH 51/88] Add direct-access methods to the base Device class, so that there's a common way of talking to drivers regardless of which of the specialised classes they derive from. Make the Device destructor public and virtual, so that arbitrary devices can be deleted. Likewise for classes that derive from it. Make Device::init public so that arbitrary devices can be initialised after being returned by factories. --- src/drivers/device/device.cpp | 19 +++++++++- src/drivers/device/device.h | 70 ++++++++++++++++++++++++++++------- src/drivers/device/i2c.h | 14 +++---- src/drivers/device/spi.h | 2 +- 4 files changed, 82 insertions(+), 23 deletions(-) diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp index 04a5222c36..c3ee77b1ca 100644 --- a/src/drivers/device/device.cpp +++ b/src/drivers/device/device.cpp @@ -223,5 +223,22 @@ interrupt(int irq, void *context) return OK; } +int +Device::read(unsigned offset, void *data, unsigned count) +{ + return -ENODEV; +} -} // namespace device \ No newline at end of file +int +Device::write(unsigned offset, void *data, unsigned count) +{ + return -ENODEV; +} + +int +Device::ioctl(unsigned operation, unsigned &arg) +{ + return -ENODEV; +} + +} // namespace device diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index 7d375aab91..a9ed5d77c2 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -68,11 +68,62 @@ namespace device __EXPORT class __EXPORT Device { public: + /** + * Destructor. + * + * Public so that anonymous devices can be destroyed. + */ + virtual ~Device(); + /** * Interrupt handler. */ virtual void interrupt(void *ctx); /**< interrupt handler */ + /* + * Direct access methods. + */ + + /** + * Initialise the driver and make it ready for use. + * + * @return OK if the driver initialized OK, negative errno otherwise; + */ + virtual int init(); + + /** + * Read directly from the device. + * + * The actual size of each unit quantity is device-specific. + * + * @param offset The device address at which to start reading + * @param data The buffer into which the read values should be placed. + * @param count The number of items to read. + * @return The number of items read on success, negative errno otherwise. + */ + virtual int read(unsigned address, void *data, unsigned count); + + /** + * Write directly to the device. + * + * The actual size of each unit quantity is device-specific. + * + * @param address The device address at which to start writing. + * @param data The buffer from which values should be read. + * @param count The number of items to write. + * @return The number of items written on success, negative errno otherwise. + */ + virtual int write(unsigned address, void *data, unsigned count); + + /** + * Perform a device-specific operation. + * + * @param operation The operation to perform. + * @param arg An argument to the operation. + * @return Negative errno on error, OK or positive value on success. + */ + virtual int ioctl(unsigned operation, unsigned &arg); + protected: const char *_name; /**< driver name */ bool _debug_enabled; /**< if true, debug messages are printed */ @@ -85,14 +136,6 @@ protected: */ Device(const char *name, int irq = 0); - ~Device(); - - /** - * Initialise the driver and make it ready for use. - * - * @return OK if the driver initialised OK. - */ - virtual int init(); /** * Enable the device interrupt @@ -189,7 +232,7 @@ public: /** * Destructor */ - ~CDev(); + virtual ~CDev(); virtual int init(); @@ -282,6 +325,7 @@ public: * Test whether the device is currently open. * * This can be used to avoid tearing down a device that is still active. + * Note - not virtual, cannot be overridden by a subclass. * * @return True if the device is currently open. */ @@ -396,9 +440,9 @@ public: const char *devname, uint32_t base, int irq = 0); - ~PIO(); + virtual ~PIO(); - int init(); + virtual int init(); protected: @@ -407,7 +451,7 @@ protected: * * @param offset Register offset in bytes from the base address. */ - uint32_t reg(uint32_t offset) { + uint32_t reg(uint32_t offset) { return *(volatile uint32_t *)(_base + offset); } @@ -444,4 +488,4 @@ private: } // namespace device -#endif /* _DEVICE_DEVICE_H */ \ No newline at end of file +#endif /* _DEVICE_DEVICE_H */ diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h index b4a9cdd536..5498793523 100644 --- a/src/drivers/device/i2c.h +++ b/src/drivers/device/i2c.h @@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev public: - /** - * Get the address - */ - uint16_t get_address() { - return _address; - } - + /** + * Get the address + */ + int16_t get_address() { return _address; } + protected: /** * The number of times a read or write operation will be retried on @@ -90,7 +88,7 @@ protected: uint16_t address, uint32_t frequency, int irq = 0); - ~I2C(); + virtual ~I2C(); virtual int init(); diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h index d2d01efb35..e0122372a0 100644 --- a/src/drivers/device/spi.h +++ b/src/drivers/device/spi.h @@ -71,7 +71,7 @@ protected: enum spi_mode_e mode, uint32_t frequency, int irq = 0); - ~SPI(); + virtual ~SPI(); virtual int init(); From 1fb4705ab7038fb4b135b49c58f14b48f0cfab48 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:48:46 -0700 Subject: [PATCH 52/88] Add size and flush methods to the ringbuffer class. --- src/drivers/device/ringbuffer.h | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index 37686fdbe3..dc0c84052b 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -104,6 +104,17 @@ public: */ bool full() { return _next(_head) == _tail; } + /* + * Returns the capacity of the buffer, or zero if the buffer could + * not be allocated. + */ + unsigned size() { return (_buf != nullptr) ? _size : 0; } + + /* + * Empties the buffer. + */ + void flush() { _head = _tail = _size; } + private: T *const _buf; const unsigned _size; @@ -114,11 +125,11 @@ private: }; template -RingBuffer::RingBuffer(unsigned size) : - _buf(new T[size + 1]), - _size(size), - _head(size), - _tail(size) +RingBuffer::RingBuffer(unsigned with_size) : + _buf(new T[with_size + 1]), + _size(with_size), + _head(with_size), + _tail(with_size) {} template From 1acbbe46d178c7eb2d11a9ba3349d274a3dd1581 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:49:19 -0700 Subject: [PATCH 53/88] Make it possible to create a cdev without automatically creating a device node. --- src/drivers/device/cdev.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp index 422321850a..47ebcd40a7 100644 --- a/src/drivers/device/cdev.cpp +++ b/src/drivers/device/cdev.cpp @@ -111,21 +111,21 @@ CDev::~CDev() int CDev::init() { - int ret = OK; - // base class init first - ret = Device::init(); + int ret = Device::init(); if (ret != OK) goto out; // now register the driver - ret = register_driver(_devname, &fops, 0666, (void *)this); + if (_devname != nullptr) { + ret = register_driver(_devname, &fops, 0666, (void *)this); - if (ret != OK) - goto out; + if (ret != OK) + goto out; - _registered = true; + _registered = true; + } out: return ret; @@ -395,4 +395,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup) return cdev->poll(filp, fds, setup); } -} // namespace device \ No newline at end of file +} // namespace device From f8951759f8265fb57f25238d0bf6ee9dd81d6a49 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 4 Aug 2013 19:50:23 -0700 Subject: [PATCH 54/88] Add a top-level Makefile rule for building "everything" as a test. --- Makefile | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Makefile b/Makefile index a2dcd97b8b..c02a986cdd 100644 --- a/Makefile +++ b/Makefile @@ -161,6 +161,12 @@ $(NUTTX_SRC): @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." @$(ECHO) "" +# +# Testing targets +# +testbuild: + $(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8) + # # Cleanup targets. 'clean' should remove all built products and force # a complete re-compilation, 'distclean' should remove everything @@ -211,6 +217,9 @@ help: @$(ECHO) " firmware to the board when the build is complete. Not supported for" @$(ECHO) " all configurations." @$(ECHO) "" + @$(ECHO) " testbuild" + @$(ECHO) " Perform a complete clean build of the entire tree." + @$(ECHO) "" @$(ECHO) " Common options:" @$(ECHO) " ---------------" @$(ECHO) "" From 5ddbe24d8e5383a19f51957463211a4d8922d366 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 12:26:31 +0200 Subject: [PATCH 55/88] Fixed code style for meas_airspeed.cpp --- src/drivers/meas_airspeed/meas_airspeed.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 7a2e22c018..15cae7d704 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -122,7 +122,7 @@ protected: extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, - CONVERSION_INTERVAL) + CONVERSION_INTERVAL) { } @@ -171,6 +171,7 @@ MEASAirspeed::collect() if (status == 2) { log("err: stale data"); + } else if (status == 3) { log("err: fault"); } From 901a9c3e35456445465e7008d3c69b0bd3481e9e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 12:44:20 +0200 Subject: [PATCH 56/88] Hotfix: MEAS Airspeed sensor fixes from Sarthak Kaingade --- src/drivers/meas_airspeed/meas_airspeed.cpp | 31 +++++++++++++-------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 15cae7d704..ebae21cf72 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -34,6 +34,7 @@ /** * @file meas_airspeed.cpp * @author Lorenz Meier + * @author Sarthak Kaingade * @author Simon Wilks * * Driver for the MEAS Spec series connected via I2C. @@ -92,9 +93,6 @@ /* Register address */ #define ADDR_READ_MR 0x00 /* write to this address to start conversion */ -#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */ -#define ADDR_READ_DF3 0x01 -#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */ /* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ @@ -160,7 +158,7 @@ MEASAirspeed::collect() perf_begin(_sample_perf); - ret = transfer(nullptr, 0, &val[0], 2); + ret = transfer(nullptr, 0, &val[0], 4); if (ret < 0) { log("error reading from sensor: %d", ret); @@ -176,21 +174,32 @@ MEASAirspeed::collect() log("err: fault"); } - uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); + //uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8); uint16_t temp = (val[3] & 0xE0) << 8 | val[2]; - diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); - diff_pres_pa -= _diff_pres_offset; + // XXX leaving this in until new calculation method has been cross-checked + //diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f)); + //diff_pres_pa -= _diff_pres_offset; + int16_t dp_raw = 0, dT_raw = 0; + dp_raw = (val[0] << 8) + val[1]; + dp_raw = 0x3FFF & dp_raw; + dT_raw = (val[2] << 8) + val[3]; + dT_raw = (0xFFE0 & dT_raw) >> 5; + float temperature = ((200 * dT_raw) / 2047) - 50; // XXX we may want to smooth out the readings to remove noise. + // Calculate differential pressure. As its centered around 8000 + // and can go positive or negative, enforce absolute value + uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f)); + _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].temperature = temp; - _reports[_next_report].differential_pressure_pa = diff_pres_pa; + _reports[_next_report].temperature = temperature; + _reports[_next_report].differential_pressure_pa = diff_press_pa; // Track maximum differential pressure measured (so we can work out top speed). - if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { - _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_press_pa; } /* announce the airspeed if needed, just publish else */ From b5d19d08ea02bd31e27f4259302b30946e1f673d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:05:08 +0200 Subject: [PATCH 57/88] Equipped MPU6k driver with Butterworth for accel and gyro --- src/drivers/mpu6000/mpu6000.cpp | 74 +++++++++++++++++++++++++++------ 1 file changed, 62 insertions(+), 12 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 9dcb4be9ed..be0a040284 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -70,6 +70,7 @@ #include #include #include +#include #define DIR_READ 0x80 #define DIR_WRITE 0x00 @@ -202,6 +203,13 @@ private: unsigned _sample_rate; perf_counter_t _sample_perf; + math::LowPassFilter2p _accel_filter_x; + math::LowPassFilter2p _accel_filter_y; + math::LowPassFilter2p _accel_filter_z; + math::LowPassFilter2p _gyro_filter_x; + math::LowPassFilter2p _gyro_filter_y; + math::LowPassFilter2p _gyro_filter_z; + /** * Start automatic measurement. */ @@ -332,8 +340,14 @@ MPU6000::MPU6000(int bus, spi_dev_e device) : _gyro_range_rad_s(0.0f), _gyro_topic(-1), _reads(0), - _sample_rate(500), - _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")) + _sample_rate(1000), + _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")), + _accel_filter_x(1000, 30), + _accel_filter_y(1000, 30), + _accel_filter_z(1000, 30), + _gyro_filter_x(1000, 30), + _gyro_filter_y(1000, 30), + _gyro_filter_z(1000, 30) { // disable debug() calls _debug_enabled = false; @@ -714,6 +728,19 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) if (ticks < 1000) return -EINVAL; + // adjust filters + float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq(); + float sample_rate = 1.0e6f/ticks; + _accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + _accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + _accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz); + + + float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq(); + _gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + _gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + _gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro); + /* update interval for next measurement */ /* XXX this is a bit shady, but no other way to adjust... */ _call.period = _call_interval = ticks; @@ -767,9 +794,17 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) _set_sample_rate(arg); return OK; - case ACCELIOCSLOWPASS: case ACCELIOCGLOWPASS: - _set_dlpf_filter((uint16_t)arg); + return _accel_filter_x.get_cutoff_freq(); + + case ACCELIOCSLOWPASS: + + // XXX decide on relationship of both filters + // i.e. disable the on-chip filter + //_set_dlpf_filter((uint16_t)arg); + _accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); return OK; case ACCELIOCSSCALE: @@ -853,9 +888,14 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) _set_sample_rate(arg); return OK; - case GYROIOCSLOWPASS: case GYROIOCGLOWPASS: - _set_dlpf_filter((uint16_t)arg); + return _gyro_filter_x.get_cutoff_freq(); + case GYROIOCSLOWPASS: + _gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); + _gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); + // XXX check relation to the internal lowpass + //_set_dlpf_filter((uint16_t)arg); return OK; case GYROIOCSSCALE: @@ -1112,9 +1152,14 @@ MPU6000::measure() arb.y_raw = report.accel_y; arb.z_raw = report.accel_z; - arb.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; - arb.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; - arb.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale; + float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale; + float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale; + + arb.x = _accel_filter_x.apply(x_in_new); + arb.y = _accel_filter_y.apply(y_in_new); + arb.z = _accel_filter_z.apply(z_in_new); + arb.scaling = _accel_range_scale; arb.range_m_s2 = _accel_range_m_s2; @@ -1125,9 +1170,14 @@ MPU6000::measure() grb.y_raw = report.gyro_y; grb.z_raw = report.gyro_z; - grb.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; - grb.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; - grb.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; + float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; + float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; + + grb.x = _gyro_filter_x.apply(x_gyro_in_new); + grb.y = _gyro_filter_y.apply(y_gyro_in_new); + grb.z = _gyro_filter_z.apply(z_gyro_in_new); + grb.scaling = _gyro_range_scale; grb.range_rad_s = _gyro_range_rad_s; From a2f923b9a3bf403e3a9fcee39d87c7aecc28559d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:05:34 +0200 Subject: [PATCH 58/88] Increased MPU6K poll and sampling rate to 1 KHz --- src/modules/sensors/sensors.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 0f1782fca6..5dc23f5c13 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -763,11 +763,11 @@ Sensors::accel_init() #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 - /* set the accel internal sampling rate up to at leat 500Hz */ - ioctl(fd, ACCELIOCSSAMPLERATE, 500); + /* set the accel internal sampling rate up to at leat 1000Hz */ + ioctl(fd, ACCELIOCSSAMPLERATE, 1000); - /* set the driver to poll at 500Hz */ - ioctl(fd, SENSORIOCSPOLLRATE, 500); + /* set the driver to poll at 1000Hz */ + ioctl(fd, SENSORIOCSPOLLRATE, 1000); #else From cfd737aa734f9b0cd97f79148d6b959978b2cad0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 5 Aug 2013 21:08:19 +0200 Subject: [PATCH 59/88] Made sensors startup routine more flexible --- src/modules/sensors/sensors.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 5dc23f5c13..f7b41b1207 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -801,11 +801,13 @@ Sensors::gyro_init() #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 - /* set the gyro internal sampling rate up to at leat 500Hz */ - ioctl(fd, GYROIOCSSAMPLERATE, 500); + /* set the gyro internal sampling rate up to at least 1000Hz */ + if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK) + ioctl(fd, GYROIOCSSAMPLERATE, 800); - /* set the driver to poll at 500Hz */ - ioctl(fd, SENSORIOCSPOLLRATE, 500); + /* set the driver to poll at 1000Hz */ + if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK) + ioctl(fd, SENSORIOCSPOLLRATE, 800); #else From 9ca5cf3108b21ce1d3a15d49bda53beeb7b5d1e0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 5 Aug 2013 21:05:53 -0700 Subject: [PATCH 60/88] Fix CAN2 pinout selection thanks to heads-up from Joe van Niekerk --- nuttx-configs/px4fmu-v1/include/board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h index 0fa93a1965..5529d50972 100644 --- a/nuttx-configs/px4fmu-v1/include/board.h +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -252,8 +252,8 @@ * CAN2 is routed to the expansion connector. */ -#define GPIO_CAN2_RX GPIO_CAN2_RX_2 -#define GPIO_CAN2_TX GPIO_CAN2_TX_2 +#define GPIO_CAN2_RX GPIO_CAN2_RX_1 +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 /* * I2C From 338e506a28e4233bc8a16493530f3b82a0dd67e9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 6 Aug 2013 16:33:01 +1000 Subject: [PATCH 61/88] mpu6000: set the default DLFP filter to 42Hz this allows for apps to ask for slightly higher filters with the software filter and not have it completely ruined by the on-chip DLPF --- src/drivers/mpu6000/mpu6000.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index be0a040284..c4e331a30e 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -477,7 +477,7 @@ void MPU6000::reset() // FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter) // was 90 Hz, but this ruins quality and does not improve the // system response - _set_dlpf_filter(20); + _set_dlpf_filter(42); usleep(1000); // Gyro scale 2000 deg/s () write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS); From 28fa96e2db8fcf91fa8bb5cb0095b08306985402 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 6 Aug 2013 09:53:52 +0200 Subject: [PATCH 62/88] Made sure airspeed tests reset the sensors to default state --- src/drivers/ets_airspeed/ets_airspeed.cpp | 4 ++++ src/drivers/meas_airspeed/meas_airspeed.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index de8028b0f5..cd72d9d23d 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -383,6 +383,10 @@ test() warnx("diff pressure: %d pa", report.differential_pressure_pa); } + /* reset the sensor polling to its default rate */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) + errx(1, "failed to set default rate"); + errx(0, "PASS"); } diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index ebae21cf72..68d2c5d655 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -415,6 +415,10 @@ test() warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature); } + /* reset the sensor polling to its default rate */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) + errx(1, "failed to set default rate"); + errx(0, "PASS"); } From 53d69f9e919445d13fe1c98a0164d238b7ff4af6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 Aug 2013 10:24:38 +0200 Subject: [PATCH 63/88] Added highlighting of current line to make editing and double-clicking warnings/errors faster --- Firmware.sublime-project | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Firmware.sublime-project b/Firmware.sublime-project index 72bacee9fd..7292307d5b 100644 --- a/Firmware.sublime-project +++ b/Firmware.sublime-project @@ -32,7 +32,8 @@ "settings": { "tab_size": 8, - "translate_tabs_to_spaces": false + "translate_tabs_to_spaces": false, + "highlight_line": true }, "build_systems": [ From 2c24888d6d34183ec01a148a84add27e72e1637c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 Aug 2013 10:25:12 +0200 Subject: [PATCH 64/88] Fixed rc mode switch PDF --- Documentation/mixing_architecture.graffle | 4398 +++++++++++++++++++++ Documentation/rc_mode_switch.odg | Bin 14631 -> 14872 bytes Documentation/rc_mode_switch.pdf | Bin 15841 -> 16097 bytes 3 files changed, 4398 insertions(+) create mode 100644 Documentation/mixing_architecture.graffle diff --git a/Documentation/mixing_architecture.graffle b/Documentation/mixing_architecture.graffle new file mode 100644 index 0000000000..da8027bf77 --- /dev/null +++ b/Documentation/mixing_architecture.graffle @@ -0,0 +1,4398 @@ + + + + + ActiveLayerIndex + 0 + ApplicationVersion + + com.omnigroup.OmniGraffle + 139.17.0.185490 + + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {1118, 783}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + CreationDate + 2013-06-04 09:23:13 +0000 + Creator + Lorenz Meier + DisplayScale + 1 0/72 in = 1.0000 in + GraphDocumentVersion + 8 + GraphicsList + + + Class + LineGraphic + Head + + ID + 508 + + ID + 635 + Points + + {106.17826841821868, 273.42634001636537} + {213.16101457128596, 357.82365814026997} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 613 + + + + Class + LineGraphic + Head + + ID + 507 + + ID + 634 + Points + + {131.96398352136816, 273.42634001634866} + {238.946729674436, 357.82365813972365} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 612 + + + + Class + Group + Graphics + + + Bounds + {{482, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 617 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 618 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 619 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 620 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 621 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 622 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 623 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 624 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{482, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 625 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 626 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 627 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 628 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 629 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 630 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 631 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 632 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.5, 235.24999816050627}, {208, 36}} + Class + ShapedGraphic + ID + 633 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Control Group 1} + + + + ID + 616 + + + Class + LineGraphic + Head + + ID + 587 + + ID + 592 + Points + + {605.82627753848249, 74.5} + {716.81658859616107, 159.07205874840687} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + + + Class + LineGraphic + Head + + ID + 581 + + ID + 591 + Points + + {576.14671565757703, 75.907219770052052} + {565.99614475502062, 157.66483897835485} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + + + Class + LineGraphic + ID + 590 + Points + + {565.49194626385997, 201.66102838314328} + {565.21582473837202, 338.8005880984627} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 573 + + + + Class + LineGraphic + ID + 589 + Points + + {720.20623661457341, 201.6610283823652} + {719.9301058948314, 338.80058788427203} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 579 + + + + Bounds + {{743, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 588 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{717.21429061889648, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 587 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{691.42857551574707, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 586 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{665.64286041259766, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 585 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{639.85714530944824, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 584 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{614.07143020629883, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 583 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{588.28571510314941, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 582 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{562.5, 158.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 581 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{743, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 580 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{717.21429061889648, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 579 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{691.42857551574707, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 578 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{665.64286041259766, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 577 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{639.85714530944824, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 576 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{614.07143020629883, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 575 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{588.28571510314941, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 574 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{562.5, 194.16102937420345}, {6, 7}} + Class + ShapedGraphic + ID + 573 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{552.5, 162.16102937420345}, {208, 36}} + Class + ShapedGraphic + ID + 572 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC Scaling & Mapping} + + + + Class + LineGraphic + Head + + ID + 509 + + ID + 569 + Points + + {80.392553315069293, 273.42634001641937} + {187.37529946813521, 357.82365814202342} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 614 + + + + Class + LineGraphic + Head + + ID + 506 + + ID + 596 + Points + + {378.46463924118007, 273.4271429546975} + {271.51750416091619, 357.82285520170717} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 629 + + + + Class + Group + Graphics + + + Bounds + {{254.5, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 599 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 600 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 601 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 602 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 603 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 604 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 605 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 231.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 606 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{254.5, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 607 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 608 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 609 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 610 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 611 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 612 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 613 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 267.24999816050627}, {6, 7}} + Class + ShapedGraphic + ID + 614 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{64, 235.24999816050627}, {208, 36}} + Class + ShapedGraphic + ID + 615 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Control Group 0} + + + + ID + 598 + + + Class + LineGraphic + Head + + ID + 474 + + ID + 411 + Points + + {322.59687445702775, 444.84226761008853} + {379.20669915150745, 526.90773238985753} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 510 + + + + Class + LineGraphic + Head + + ID + 477 + + ID + 412 + Points + + {294.62113860994009, 444.9967148570675} + {304.03957452010235, 526.7532851429479} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 511 + + + + Class + LineGraphic + Head + + ID + 490 + + ID + 413 + Points + + {290.76782961936522, 443.67073351699491} + {183.53574398902853, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 511 + + + + Class + LineGraphic + Head + + ID + 491 + + ID + 414 + Points + + {264.9821145162158, 443.67073351699491} + {157.75002888587912, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 512 + + + + Class + LineGraphic + Head + + ID + 492 + + ID + 415 + Points + + {239.19639941306636, 443.67073351699491} + {131.9643137827297, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 513 + + + + Class + LineGraphic + Head + + ID + 493 + + ID + 416 + Points + + {213.41068430991695, 443.67073351699491} + {106.1785986795803, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 514 + + + + Class + LineGraphic + Head + + ID + 440 + + ID + 417 + Points + + {304.49194626386003, 570.74999900893988} + {304.21582473837134, 707.88955872425925} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 485 + + + + Class + LineGraphic + Head + + ID + 429 + + ID + 418 + Points + + {381.84909342488743, 570.74999900816329} + {381.57303538097813, 707.88955851048831} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 482 + + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{379.35432048604451, 719.00347978513389}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 421 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{396.74606011338682, 726.18083608931011}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 422 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{391.6252245834844, 724.37750550833903}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 423 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{386.29980802056684, 722.50213058402392}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 424 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{375.67643661590967, 718.76105153253593}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 425 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{370.35101205342835, 716.88567379113056}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 426 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{365.23018452308935, 715.08234602724974}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 427 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{345.93778549185652, 717.4003115566619}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 428 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 420 + Rotation + 19.399997711181641 + + + Bounds + {{371.98798359082144, 708.38955751823028}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 429 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 419 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{301.99718791759841, 719.00348000010274}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 432 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{319.38892754494066, 726.18083630427896}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 433 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{314.26809201503823, 724.37750572330788}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 434 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{308.94267545212068, 722.50213079899277}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 435 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{298.3193040474635, 718.76105174750478}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 436 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{292.99387948498219, 716.88567400609941}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 437 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{287.87305195464319, 715.08234624221859}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 438 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{268.58065292341041, 717.40031177163075}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 439 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 431 + Rotation + 19.399997711181641 + + + Bounds + {{294.63085102237534, 708.38955773319913}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 440 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 430 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{151.85433513439526, 676.40348606783687}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 443 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{169.24607476173759, 683.58084237201308}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 444 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{164.12523923183511, 681.777511791042}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 445 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{158.79982266891756, 679.90213686672689}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 446 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{148.17645126426038, 676.16105781523891}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 447 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{142.85102670177906, 674.28568007383353}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 448 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{137.73019917144009, 672.48235230995272}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 449 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{118.43780014020726, 674.80031783936488}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 450 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 442 + Rotation + 19.399997711181641 + + + Bounds + {{144.48799823917219, 665.78956380093325}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 451 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 441 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{126.06861430919994, 649.30352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 454 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{143.46035393654228, 656.48088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 455 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{138.3395184066398, 654.67755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 456 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{133.01410184372224, 652.80218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 457 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{122.39073043906507, 649.06110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 458 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{117.06530587658375, 647.18572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 459 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{111.94447834624478, 645.38239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 460 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{92.652079315011946, 647.70036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 461 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 453 + Rotation + 19.399997711181641 + + + Bounds + {{118.70227741397687, 638.68960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 462 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 452 + + + Class + LineGraphic + Head + + ID + 494 + + ID + 463 + Points + + {187.62496920676753, 443.67073351699486} + {80.392883576430918, 528.07926647675936} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 515 + + + + Class + LineGraphic + Head + + ID + 451 + + ID + 464 + Points + + {154.34620841108131, 570.74999811167606} + {154.08771587848975, 665.2895656892573} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 499 + + + + Class + LineGraphic + Head + + ID + 462 + + ID + 465 + Points + + {128.55726775049197, 570.74999689176411} + {128.31848992771231, 638.1896106116875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 500 + + + + Class + LineGraphic + Head + + ID + 538 + + ID + 466 + Points + + {102.76581371331335, 570.74999379087535} + {102.56212456317996, 611.68961371257615} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 501 + + + + Class + LineGraphic + Head + + ID + 549 + + ID + 467 + Points + + {76.966539516560758, 570.74998251647355} + {76.84574963416425, 585.18962498697681} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 502 + + + + Class + LineGraphic + Head + + ID + 550 + + ID + 468 + Points + + {180.14284120598458, 570.75} + {180.14284120598458, 685.34997558593727} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 498 + + + + Class + LineGraphic + Head + + ID + 527 + + ID + 469 + Points + + {205.92052173345891, 570.74999897014993} + {205.64439858308342, 707.8895785636937} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + TailArrow + 0 + + + Tail + + ID + 497 + + + + Bounds + {{482, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 470 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 471 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 472 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 473 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 474 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 475 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 476 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 477 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{482, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 478 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{456.21429061889648, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 479 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{430.42857551574707, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 480 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{404.64286041259766, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 481 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{378.85714530944824, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 482 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{353.07143020629883, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 483 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{327.28571510314941, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 484 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{301.5, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 485 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.5, 531.25}, {208, 36}} + Class + ShapedGraphic + ID + 486 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Output Group 1 (e.g. FMU)} + + + + Bounds + {{254.5, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 487 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 488 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 489 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 490 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 491 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 492 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 493 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 527.25}, {6, 7}} + Class + ShapedGraphic + ID + 494 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{254.5, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 495 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{228.71429061889648, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 496 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{202.92857551574707, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 497 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{177.14286041259766, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 498 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{151.35714530944824, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 499 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{125.57143020629883, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 500 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{99.785715103149414, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 501 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{74, 563.25}, {6, 7}} + Class + ShapedGraphic + ID + 502 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{64, 531.25}, {208, 36}} + Class + ShapedGraphic + ID + 503 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Output Group 0 (e.g. IO)} + + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{265.12499809265137, 357}, {6, 7}} + Class + ShapedGraphic + ID + 506 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{239.33928298950195, 357}, {6, 7}} + Class + ShapedGraphic + ID + 507 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{213.55356788635254, 357}, {6, 7}} + Class + ShapedGraphic + ID + 508 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{187.76785278320312, 357}, {6, 7}} + Class + ShapedGraphic + ID + 509 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{316.9464282989502, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 510 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{291.16071319580078, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 511 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{265.37499809265137, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 512 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{239.58928298950195, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 513 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{213.80356788635254, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 514 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + Bounds + {{188.01785278320312, 437.5}, {6, 7}} + Class + ShapedGraphic + ID + 515 + Shape + Rectangle + Style + + stroke + + CornerRadius + 1 + + + + + ID + 505 + + + Bounds + {{177.14285278320312, 359.75}, {208, 82}} + Class + ShapedGraphic + ID + 516 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Vehicle Mixer} + + + + ID + 504 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{203.42576152599673, 719.00349980074725}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 519 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{220.81750115333907, 726.18085610492346}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 520 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{215.69666562343659, 724.37752552395239}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 521 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{210.37124906051903, 722.50215059963728}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 522 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{199.74787765586186, 718.76107154814929}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 523 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{194.42245309338054, 716.88569380674392}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 524 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{189.30162556304157, 715.0823660428631}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 525 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{170.00922653180874, 717.40033157227526}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 526 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 518 + Rotation + 19.399997711181641 + + + Bounds + {{196.05942463077366, 708.38957753384364}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 527 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 517 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{100.28290111339905, 622.80352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 530 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{117.67464074074138, 629.98088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 531 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{112.5538052108389, 628.17755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 532 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{107.22838864792135, 626.30218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 533 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{96.605017243264172, 622.56110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 534 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{91.279592680782855, 620.68572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 535 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{86.158765150443884, 618.88239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 536 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{66.866366119211051, 621.20036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 537 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 529 + Rotation + 19.399997711181641 + + + Bounds + {{92.916564218175978, 612.18960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 538 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 528 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{74.49718852803673, 596.30352977035523}, {5.0056232242123722, 4.9183513058348947}} + Class + ShapedGraphic + ID + 541 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{91.888928155379034, 603.48088607453144}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 542 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{86.768092625476555, 601.67755549356036}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 543 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{81.442676062559002, 599.80218056924525}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 544 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{70.819304657901824, 596.06110151775727}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 545 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{65.493880095420508, 594.18572377635189}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 546 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{60.373052565081537, 592.38239601247108}, {1.9456694882012362, 1.7352345929064885}} + Class + ShapedGraphic + ID + 547 + Rotation + 19.399997711181641 + Shape + Circle + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{41.080653533848704, 594.70036154188324}, {71.838699340820256, 8.1246847180976189}} + Class + ShapedGraphic + ID + 548 + Rotation + 19.399997711181641 + Shape + Diamond + Style + + stroke + + CornerRadius + 5 + + + Text + + VerticalPad + 0 + + + + ID + 540 + Rotation + 19.399997711181641 + + + Bounds + {{67.130851632813631, 585.68960750345161}, {19.087577050122338, 39.91038694100309}} + Class + ShapedGraphic + ID + 549 + Shape + Rectangle + Style + + fill + + Color + + b + 0.153172 + g + 0.153172 + r + 0.153172 + + FillType + 2 + GradientAngle + 145 + GradientColor + + b + 0.416928 + g + 0.416928 + r + 0.416928 + + + stroke + + CornerRadius + 2 + + + + + ID + 539 + + + Bounds + {{64, 104}, {54, 36}} + Class + ShapedGraphic + ID + 1 + Shape + Rectangle + + + Bounds + {{125.57142639160156, 24}, {36, 36}} + Class + ShapedGraphic + ID + 6 + Shape + Diamond + Style + + Text + + VerticalPad + 0 + + + + Bounds + {{158.14285217276469, 695.84997558593727}, {44, 24}} + Class + ShapedGraphic + ID + 550 + Rotation + 90 + Shape + Rectangle + Style + + fill + + Color + + b + 0.243722 + g + 0.864482 + r + 1 + + + stroke + + Color + + b + 0.051159 + g + 0.160546 + r + 0.18663 + + CornerRadius + 5 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 ESC} + + + + GridInfo + + GuidesLocked + NO + GuidesVisible + YES + HPages + 2 + ImageCounter + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2013-06-04 16:51:32 +0000 + Modifier + Lorenz Meier + NotesVisible + NO + Orientation + 2 + OriginVisible + NO + PageBreaks + YES + PrintInfo + + NSBottomMargin + + float + 41 + + NSHorizonalPagination + + coded + BAtzdHJlYW10eXBlZIHoA4QBQISEhAhOU051bWJlcgCEhAdOU1ZhbHVlAISECE5TT2JqZWN0AIWEASqEhAFxlwCG + + NSLeftMargin + + float + 18 + + NSPaperSize + + size + {595, 842} + + NSPrintReverseOrientation + + int + 0 + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + PrintOnePage + + ReadOnly + NO + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UniqueID + 1 + UseEntirePage + + VPages + 1 + WindowInfo + + CurrentSheet + 0 + ExpandedCanvases + + + name + Canvas 1 + + + Frame + {{176, 63}, {1581, 1355}} + ListView + + OutlineWidth + 142 + RightSidebar + + ShowRuler + + Sidebar + + SidebarWidth + 120 + VisibleRegion + {{-164, -216}, {1446, 1216}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 1 + 2 + + + + + diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg index e35a83372b18cf42baf2e68dea03be681e2ef760..a8a6f93f31f90c26e4e6d2ae4914fcefd53301aa 100644 GIT binary patch delta 9974 zcmY+K1ymio)_~_6+}*ucad($eytun-p|~HUI20(wi@Uqq0b1Nj3&o{4#ohU7@B8n1 zZ@yWXBs+U&X4cMRC9{iNQr*y06kuR+0RRyIq--w}(3BCMFOp{qJ0EJzbz#&5xH!#t zI5=5&1uVJP*#%hmOgY#sdCXa?%=vjaIk{L&d3Xfa`GwgWE!|87tu5bLx|q5-xrho| zm<^HvU6~;u=BBSa%yn!2y(CsvL~X$(!+7`DDem+3c|91xD)MQy}`5MPZENeg+UY$g*3LHQ00>gQeN1X^s6@#@cjdT{pK+cX^=lAKg0x!J z6M5w9aMGU#4aWcs)0ppai_}#OmRNPEieH7n;=hW5_+h@<#nlDexGGyj+6WUWt2(e1 zvlV6xhI3NKSn;DrzE0Dw8}Vwt#I5_bG&UI+qM{-z1D`F^B4V8}W9k;xsjjM(-@MJ$ zzZ^4zqlFTUIGdn#xwSex=}UP!KNqpj#`Ty zN82$qlj!Bn;xPC+85u4_B^jym;7D-YkK8z}^Ur)l`{3Z>&f%WSsy?A27`^*ZWszzR8xyZieB>&R4@-BWQt-8rv54)) zG2}A!wRngLg*r{{$RMYSzP@2Ro)SSyvI}36Y46)e|0?b#n@$SH1`Qr30t%$-v$nFB zRfY1;A~zSc7FG({ma>rn`1bRo-tbrc>UBp_?mDl^&c&3>VT3CB5f}J4ylbu`!NOmC z@?9?oG{ZbmHb1|+*dY|<^QUCY4=V4OK!z-0tG-<1;)By}kj@Mp9^whk+y-?Fhec!H zuhDR0NjQEeK@e#YR4>3x^ba<~G+Y&Fidcb_DlJ{g^UPt>RFd%HbIbc|-_lL8gP!P{ zv`*U6hFr(4)j>Sm^K@mq#<=-i5{zbK9)ZGdwQ;(S!)T7j)!9&c7B58N}T0s;YVA1+&Wstwg|j|o+3w1|T)F9UxjNN*G1X);es zA_(G#bzTNl4ODlB4hOFMgw?IBT7jelD~;(Sg{{dVi5Qu89mekkEQzaTX`a0rp7*l+ zKx9i6*~(FDKZwMIi(P7S$7v+Lamr`CQ_Vw^ZT1uHw#k2}-O-WOs*kX-`!dO%aE1rp z?h&S>QAo-=m|w>Cp^;|~iGGODD|K%yyxVAY zd8=*XJ@~WM`}woCvSdU>?!W9JOT5)A_tV4$4;CDQ8C|lz^Jl$vC3Tdhr&DcY&!n?> zzx-uN#p<)HGl8Y*Sb}`E(67mz%!bLxH-wcSh!BKk8!YRMQiM?k@mlxw*#>ZT#dSGU7=j`gA z7?F#?xj3D$!gpNVc}t<25krwYJ=7!hR|IDuPu@4xJ&6w8O>|u2ai`{ZIyOQbaw|8A+ zc7yk**1al={Z`_$LNaEZzoz7SY>oW^%YOm-6jQc*xaR1{vri-rS$uQUMg z&%A+%i1=sTNL)iEhv+Bfx8Ma#ROftF7;`WqiuAQ^FXnAbDo(SoFIJ!1u#AFVql*p# z4o4m%g}0tIQ>1@c!S?ex@Lhf`-P>()hYio~yOMkTda9Yi2tVjtI`Kzb?*fv{sdQd0 zPHO;vcjo=UDr<8icHqF(0PCC=gr`-xgU|eF%QW)2N3p726-p?5t@$3{U2|f zBz+~mXN^narWMNc@GILU+sq$2lYbdR3 z-V)f&VBP<=?W*?_8S@?87oHy)4@gFduF7j^Z;$%L`r+l_33JNeYpDL z*Q%>ub-|^dzr=Y4j7qlYibdt=X&U8v&AGZqGMCr?a+SJ;c;{cc{<7w_jSwRFN+#rN z7yUZgUB=wStDmOmJhI*I0sEa)fe7AU#mlNt_2#Q7G5_1^Iqw1#U)p^qf~;H9^trWR z&fQ)NkGF7i3+oLYJ4gG-22E#sG>b$&ELCIJ#INPF_~M&|kZRiF=VjvNUhIUk8|g)k zgU7ruavL&?v`0>QhHWDOadf6ZNDQq=X-Ho~q{9R10g%(p%7x=2-@ro`f; zZejD91h3WTE{etN-IT`A4A1gI9G4OA=KUyPNr!sAF+`HiQC$xGHJK#dLrSkRnEZv_nF}*?A3I#mbktQN8)fxhepa@6(A<_Q-V?4}f4x%L_2J;X zXY47)_dK=pW41kuiGWK&7On}5U^(}YxAGr*sBvc4S zM}Bd)V1~rsE8=)~_cJqr@|xjh%RPi{SmpAz$FJK?X3)e+mDciekd7o%i9fSh<$%#i!ovOd% zA+t=qUa(}0m}n1ADJeerDB0XgWFTazbYm@6U>tG3>3bR3c3;i*<^I%y-ZWae=t-aA^;wN0kyMIRVa4q7x>Z1*YzFBMU!MQbGwp;psZ@YV%u?F z8`vHOE~RK|MSHv zIN-~DFew<|B=mX%L#?ZN$$bi1D~^_t?=Oaw`-0T6;22IoLEI7VvaCmgF%aJ$O!I;l zPiyzvz8$OtGuMikMzq^1`ijhm`3LUi383#rHGbHxDLu5^feGfjYrhfY&m%n?6cW3_ zAoH+}v)!KmIiUvm?ni9pR3+_h9DaJ!EONL2y3f60+1s$pYZ+K{(p%c}^dK#S+}lGG zrFQGdioOo$B_(aRDNChaqx+_1J#gdEn2EXSz=+I68Y_O$;*)zYp3OI<9%sBU$h6#< zqA{7&yjFf_tE?JiQa_dU23)xQ))QlC5r#r>BD@aS>^ngL(O}z-@EN(vlo(2_bT`v?lR?j~|2h}()Wro5X0lY(qxh^4amPT$k1e>v z#L5OdZy!^vug5yxY1q5N!<*O7-1Ng4=_=0ZM7^$|BUqI>K7>2f9ChD|ikCi<(!`#v_B%qq zWYV*GB{+p*`C2;lh&@BRwe5?L|J3IxeI?nvs6#8$R?>SzSVw~rQ3QFMaW=YVi((>!X>W7 zPmfsiw3Ez$S26~lTfyke_e=@-5%&c5ja)L~%;xFSDac&N*CH-Uh1Vs9T5Pmlg5yop z0iG8gT-0vL`}y62jgVql3gM&&oBh|-G)Cr^s7NdCOwv{8>-)SjAsFou1}kT_y^QAH zHR8=u!^-TF8MQyCiD`XyQaOz@oHdC%#ksp#O`96HZ>D{qe(Lgq#_c;9h#b7xbYeZP zeOwr2GI{$6A`dBDOndZAJBpn2Q|J(+W|hYufo>hKLfr3|Ry{&j2B-K+DZ1`fYsHqo zKB8uv-d$y|NzN0PLgwXHUg~IDg;nijFfknr3u7EzQ3$_qtSWB$ZK>KJ#Zzg>@+R=} z+v<{LCj8xGpcqEuYxTXtJ*2#b0nd#bMXuNF@-dpXCVM%$Ni-WUHmvL!7HsHMij zu^?7{KXslK?p?w}qmpci5G+?Kos!o9Ws>}*K z27<)Ud0VD0fJdz`(^g?;vbd_rT%D(PGx?RUzhZdf@N8wMHqw2KUhWgO*7-C_QpVTm zVD4IH#R6uM#pNXhvq&VHAuqY3?RrDJ8(doq<)MQbl|8Pl zV#^R%LEtZhAhHhc>ILr5zz8e!Be&uo>^Ao z+52U(t}y42EFdt$;Af0@hsmj!M^v@&ooB=aiCTtbEcr>YV6CcY4bdoxpSd-ooL88Y zs_L`qB*?g^oOO87!5TeFBLkC-S77#PRP*~-9!W>riPX7T?!^r0FF3JRG|_~MGN^Po zkd;C;Q_J1V7n+qP0U~cF^qN0c#?(`%5OrP(YR&LqZxhBPxWxv2rQ9W!MU~yJlXD>9 z&7dE!A{y#lq|s79es9SUIQa)-0m&_mAaF#SZTqX&)% zYOTyNE`%TGR8``5Wku$%LujB^MJN#aM4{%{G>2`*+YM!(x)9nVzcvx12) zTUh;X;+a7W2#^MZ2G6yItILJ(CeXb247AUZQWJbk^vsPtbel_2q5(87c{&-&#SQ~P zM0>{n`OM?tYHNK;CkjE@d9BN}4tJkCrHDMMZLcJC-k14GGbMJEbBlRpkrv+ih&Pq=)L7rrkwk@CVun^(X-8!w zi?IchCQCcEls9wmuu0RCI(?Jy>l7Vjt2tff@+VWn-ZIw8#5g`W6DbvV78_vXR?J8h zK(M7=r#pk);#NowFcO@8^P0*`w?U7P>$s_Yme3~Bla$UhRSn854w!UeH6Dl%mNKRM zQeaB$irpxA@eL8yubL#Xa;Xv<;%Ok|kucbY@(_ByzWQ zFQa$Ow%?5Ft@e()b0hqOQvu^5x85fb|@wlWsFtcBu95@a&v083<>?p-0n4sW4y z)y4gAr}g$XF4vQBEVI#B$i)}!B3cO-MCz?3jZm0nB3FCYU0I``-({^Ee&xST>tguS z#!Wj2Qs#(~mQ4$Y>P&Z$zo98KE-SPu#;0JxlnRqGopkbh=UhIRR@x~a-cPQHC_oO+ z@0l0a^*YEqGs6o^qo~~r?0N$~e)~wv?ZUvm*QfnH5tO=)F7hEdX+ar0fY~<)C&S9_ zLew|7dEN60FRjcApMX=F>!YTFs-p`izrUw6a(gp4h=Hv_*karQ0SfyM)F#2rZ&+vs zds}!=!@duhegpx;&)mX7BuFZ#=CG|R66nTtJa6}szDTJ54!4)bgelhw9KxLfQX@=P zwIYVTgqI15t2-dp!_vJN-a5gMGX3gx{lpg2 zu$VS7pS%0I{9I_J6?d9TPu>2V8KZ5T`Rl?Ja;jaD!w|^HWw>RIXeCm`=i-uQ9CzuI$lNL5@5H+(u4<3!dZ}vqTFN^=40&p>B$0ZQlOQjT z(SIkBuEH-10wZ#a`0M) z>pMPF?H{O3O8a^mc}GqpCEy{%UODjst@YV2RyN}>C{g|*1dbQ+W*!uuDbi6<^`ok# zte}DkmVg5P&PT}3Vyf)aZJR?lqZgU_IpA~~EnoRB|B&gr}M5%}P~Ngx&Umlgi%&}^y3 zdBko-M^$(kE-x1aQu>4gVM!=qApSERu;RW^j!hhNm61{kSeIR<*YlsK(9*tHwPG^w z7|^uYz?d_{?||KaXPm#fnNZcgLZEw*UXwy^DjU6kz(SC6Xv{Cj=eeBy z>d%f!7-Td2Y?=Tg;courhv&@|&U0r%$=VgqCxkz{Ke)$juI*R=z#szp&+gBE{u)Rg z!jX6t!l42{A!=eWsRRVoK~7pi!|U@wrfS{vOUy8V=CaYx>|U#jdVsifBQ(S51*RP<;POxB^Kv?UH1(eO+ETM|sPB zKnB)Wt3|}}ZOE?gx<|JqX7XA2RZI}?w6Mr>Q6fNx6X@%ZQ^?{o#rx4RX^WI4hBiV! zFEV^{2W`g%qL}Phpde5$Sb*Yx(51(BTOH58q>z}pmBxDBTLP3lccLxmkibHD=QQJM zA%s!7q~76QJVVh5x@*>BLYpINAEeA0wejYDa@d{Y-tFeLHcjF7Z<=(_^M8{DPk@~c80^U)DP>sXwR%}q_)Hv{LUfR9JvcG($N zpFh;W6(3Hus?%nud>|@>AHTp`dYvt#kf6SIR{JuLW1H9^-wlP;*K?ef>|qMCi92f? z{nIW4pGqngPZt+z*WmG9S-NI~n@;MJ}a>Gs(=Pm$BUgo3^aMGgy zXw%A5yOjLdN>G@abSXTt)Jbg!2*7jTlL8rt46I*2*;8qL@K88H!|G4Zn zBJe^uSX{}_i(#r!oxdHf$MA+Uju z7&S=Gs_9r@@iUB3@PE`?TY$-@UD;~BzO^XnCdAd7V#xhb_mS~1Wa#n!`rxjeK%em< zl_MM8$LntXNwgJ`v||rFJzt2^7BZ@LegcWw2DMi`@5E z>-GJOQFL^mUo}*1;pr+GOUBkwl@)84WAdPg6p&Q*g1OlU^;WlKzx$j7(=8?Nv7FJC z;oEH*;f~!k8N}T5JfF?M_mXDPX?Lg?OL`A%vX!Lg-N@DeTDz?s$!>%xOo=P>!m)Pj zHjZ7QYWsXBO6U_B+dQ^&{Zfs1C8{qpMG|PVs!JJ(=7CBy3J2?q7~jK; ziVcOl=%j?VFrn}QB3bi9IBbA2aUg`B_W2rv15NLwMD~$}4?-YBvoJwM6#vB!6N(zc z{_Fy99F!r{FURr+!5Ge>K16Qb_%?8byK(OtfGrm=b-7-W#DG9g{pTmNh9<0Ipecvb z89Cg!L_-Sz*C1w|zf_F#_+nm=uB!zPQF`qk3~cSe%}HnB?nMaW3r{HV;jMyVUKn@p z<9hK@_(*)m;2t9l256WUR6OV!Hj(3U-Io^yz~XE>h|Z#hzSS7y;=Sqe9P~Oc{lL#J zpKw{Y1_*&pN@q-*7!be?h6PyRPztpL)PYN1iR9n#b~7&pGATR=C{RmaR`iR;e|+I7;H@i4zyjOoy(YDkS?5<_LmlZAfOB=J?1Ks zA~nsR>=_ZIK7MNmh#F1?s*rtz`k?jVP2!1SS*;?0jYgAJCb#Qp7rHsopzmVQXxpUV zcpJgoot=pYRnVl7%E0xLM3F$n(7>m`Lqa^j9I62gZ?1kgO1#sC2qb1Z87+xIOuawU z(kn&^KTk)_+<&K%yALR9)uVe4Gd}eUgNTUG(T7cBSxeAj<%E zQ3Z<@-GkMr98Wq@G}u|6Eo%$kPD^k3OWH-aX1Dkg@tf(1PetIq+ay9f@g%RI-Nv8S zu@#mo`JQoxJ&@(7L-9G?i2&yPRAR$;UAV~`EHbgGPW#w?1xt$t<(Gx$1nCeFS40!> z#3CpD^?iMHYEVrq5-j`ZpdJcw4(O6W_S~_JD+pkA{S03>*SqG10G?I2^2FAQU_bxr z0+4|D4oqG!F;>UK2m2% z%0P6)zV9}hs_<^qhMgT3#T-J!eO5jDrqlt5IT)n}KCad?6k6pXc_{Jd<|P*?_-3~W zZ0%vdhhXAP*R;@2_WVH~r>!(42xdPV1Fq`>ja}B&iu;AVf-nRjWEvNQ;hC_AtKxe3 zBZt@^$W|*l2+W_1=E0r?CVnX-X>wlYt4u>b$)X7z@NC3$UX&Qn=>7lVYKjdCYrYet}DsmMRiIrXm z6#`k1+kvOYyGKi&&1{Npf5?@YQ=xclMQb=@g?lT#QJKmB&y!7wFSEJxO(_agAHweM zw0PKz+UuedJ7Riq*>w|Yw=_Z5h}5*iu$4+-*lDEFZvAm`pJ`*4+@5(_KYV^cd;u;` z>o7%OnUco*s2mAp_hHpRVV$_!Rm&%W@v$yl!>LTC%a+V^VCReZ9J?Wv@|}hL)O|HX z4Bo`i@6Shc$C%cFWQ1w(X`KZX&hr(2YPc2+>Fu`^#d-xi_-WyKzevfmVH6Q5Z|nA__$^Z2^%*P^>CLL4A+W!WRdx9gaeRB<(#C~-FP`N*xWuFbPEElICG{9FXkCkQDAx;85 z9kqJK8M|Wy`tN~rj#{fv*CAKshxJd$9MvL*%)AE*FJF+%y2K{Z@C?b%@n(Yjzs=PJ z!aEYY)Dy#j(MLm>V@R0O!Q&SI8Bh1yXkuz@q??(m}Ap^AOGP$gQ z6cn5kZV^jVvHCAnk$GEtNoD=NFutv}deKlPc~QrpfVKHCi7zQ*ix+b09fYDz0IlB; zxf0Xsx`1YR3_oU6@xs+?SV(fIRDOJ9pf>eY=aG*L1t_>{!rOqUtHpYB3|iSdpNG*Y zjWfNO&?#<2aql?nz(^G&aUweol7w&4pFCvhE;V54N0kf4 zU?#sg`$!4;4yd~-=tIEAds)(*28X2!b_M9nK zWhr8{vSvQ3h!y-c3D>?zF_g!n7;XNFI?NK`t3K6pJFB6x+^U%pd=w<4wF0{shDs?p zF;t(9VKsS1ycfFhJ&_Gd@JX@L2Z!TtXFZ+Yy*4Qzwhw;3-$%82H ze8|00madXC3I3mOr^Jqzf`5aKI2foBqj^zL{wowJk%NKfUl|GC|H^V1`2NbU7^xB~ z`H=rd4~voOuk1CW#=mX48L|K5>whqIApXrHa%q76O82!H z!;r|#%ksBqz)J#JN>t&)O^o5i`~Mm+9%Et;@5_ISN{op}d@uiY^WT<9|GNN$GA63> zG5*yt<|hGn|1p98kr5sZ1jYsajWJ7nmVqu3SNZ7wwnTnz$;6aM&;QTc{-YSolvv3~ z`syF8|3nx_9`QR^hCfHCHFE+0^8a+(!UO=WZr%=-uB={;4k`-&qnEh!Y|xWC@s^(+ Kew62r-v0rh_(^5} delta 9745 zcmZ9S1y~%t_V8zME$%LbVr6l6iWDhQwz#{uxGoOGVR3hNDehLFxU{$w*P^9B;ZOVC zd%t_X`905O=A4t9Z1PMpNluD$@dr#51$YE}06+nNFh{{SOl6d(L~_$ywy@Sj3tr8P zQ^1ImgPV=h*x1aJkCP3|%gJGC#>-|Tz{kVMZ^FiJ4(8=G6=t_Hb2bvRFta!NVC3xZ zK~&h(M9|d8*-VrZ%)!M5=3wLGeapck2<8^#fIUNCMC1@q;^u(~BCvxvVb%!laD2S5 zEd);ZC)Y3%L@MZ-(;`2%Z&z2q*>c~?GB!Mooe>;`FR!A%8koL?&xl=yNXwYMCFtRb zkwgxaSklaUMu5_=rtnm!a=tB_&|XXwnf?N^xjPb4aj!8x0=T4xmKxL!Dhu89+-m+l zP8u`+7F;*93%%Lr-#$Xx2q_t(g+u0ggscf;>gOZx!Zz1+iAAmr=WNQAm-H9w zSH4?%e2{^PS{!mf%i3(q)@fQY_S9(_dR&3_KokX=`kX84P|8vUl##=U1YUC>%up!)|=9Gs2+TA`C_9GMZSm!7;_WrTtjv5_Fy$ z+8k3V7bD%}#u1#4Pvkh0yf3ys!uyU$-GT&sg;7|a0zw_2$fE?Q(kV1}vUuXfy;`;Y zuoVNHg~>!a#CRYypgaS=!bOU#plx!QL)4maes9GDb@GKQ8jR7rBh_hGhAFI3rzGP(+)@p^1R-|O#EHGuh<$fFv z^dZJwXPPI=EEg;1Y&UqZ8(A(p^rM9Yq)LJb6~^>cU5^fv%pGdS*PX&qB4lRdLvhU} zcTZx&qGIcnx1&`Bb+?0J;32`j#b}S=^;y?*~xy(4!$m%zi~a9c@dwmG;~6#{8ic zdIIU(;+(QabJiP4lZGAv-XY!PV>I%%4lC|{ENtothZmLXLBh;SVl!H0Y=ovfgx%?K zd84D@f=Sl7(b2(YHC_d$XLnS&oa+-%On)|Bg8SDsr6lEQ9OO);Lu9OzdTJ~6PWaoe zGzM@K4t`NlJ(zbdcsG z-Q(ez{MY-Iv~cO@oXi!9xjG$}relAS-`jgKUu zJl^prAf8kZ_&c- zH&D>-&FJBAt)KO(zZSQO>gM)0lu#}S_d4;RawoYzyN#y)Rz zJIRc#Zua$t*>fU0V=*Y~LlXLd`a_MWKaPGvolV+e=)sWLAv0q76?_yHZ&c=DrFN8Y z8W;zny9&l?Qx%Ds?9757H&qpDgr+9PxOzJZjRp-A>MiY?$o@`?U}xpH zJ00D%YYYDxDjG40R-`?s@9fCowD0)<#$eI#2x+gkIKb6{5J7*Prd?j>pY48Au+qgd zI3X}te5k8)Z(cRyW(XxxG*-@bhgA#W@JUa{`LmvHz2<)}=Wzu@x zMiW__lvn=ky(=`F(%iX$GshsYLE0Xt5VNS5iH)+e%!XK?xMv+PDio)1+^V5Qx|phm&@w%)y> zBpvz^_un7B9lOV%Q8alBA+@r?q~+Z-R)1HcXYuade<6mJxU1ReN}9WEQ_~}7nyTv6 z@L7GLa!B(TmUeQww=Qhs^e7dIPSP zdu*elaTFK1s@Eo27HCutGRgb($)X|Yvsd0wh-l7dp_r6f%M4HMIO40C-NB7h=Z7N! z@^dr#^3f}(;-(-cVHmWSqfNvlsS=nwY zx$nHe8iRQdvb(YnaswW6dkP`fRR~>Ug4tfEZOH|cQQ*$a+l)esDaPpNH_o~KJILr7 zulzwvb?Cf4!$8{??}5e7_i;NiZgyg+rYp=}wVLGjyp)e$U$K6jb9u$2*85rClZk~p zX&c%)UKDE+C%pJfU4r!#r&3x(iDlSjlr&J&>=pd`qack_gLXe(y7Q*&1@?m<4r^h* zj)$YWpg4z1M=R;1-6%Ggi^F6n+#wNG7`G&ow0zD6g`b!Udl2sppf2yxUFIc89Tqj- za>oisr8*xYY9K+7(OxQ!RVPR7^OKRSkvNRjl?oEO-|?^VcGW}9ePT{@`EvK~pDQFL zMsIzs+G_g5fj;R=wTLC-$r|YYbGnq_G*6wL1v(NJ;wy!6kT(_o{@_~6FUdke;XcH0 zQT4rYu8vc-RkFhGcVba??;H!Se<{Di8}4UBbJN32ItXt>SEwzewA$m7j*NEL8S39k zY~tGr9Q~~jA)(1}taw+(I+y5amD16IyX};mFmXYCwoF)p;bWi0sDL-1H-Epgt^TkO z-3#3^c%;koznps(e{WGZ0{PIH2a4)=eyBL1ACH0?m;6!-QDmVu`OQrtmVCRI=2Q(% zVWD@?ID@0*5!c?xlJeZjC$}wG2F!Kd=z?*trcTjuUYah2se8n6htt*pEz&tjY6O7FczYx^x2S{WM*xU>~Kk=WIJameb zWoO9`+EXr2O06k`x4`#MXP;HPT%Tb)AX3M`B3mmiO<+7fJbI|Vx5(n&O&_thc>LM* zsJ>9`3QHrX7xs4TZ=%wC&C`>!%S8_jO?|Mj9x^caij`|XY6x>gLciJCOv<*t;O5CM z(-z%st}c-M=8sV$g}b2Os(ui{!4~D{L#QTGk1eys%vKO>Npta(M48hB%$7IAilzl8 zlsCk1WcgI#7mrP`7U(l6>(FWM3BFH@DV61nbJY^pQ+PSJ7%|S){i;`LuN?{z3-9Q3 z6ElynzKLG*_D~Y#-R*kcNO;_+eFd{4eF-_HXNsz??0vO3G26%|>SoCaqKvUzqh1o! zt^AGy!T+sRbaTxj1`hNIO6N96zY5UOOO5~=EMVbjh#8AGnXhVE05A+2)y+`ds59Ql=OZO13sZRG@` zIdy}|Y(KOgUDW%-LNXRKuBp4|{_OihdhCu;%BN{8wE4u~T$bC1FR!_{3=(eGvvp~Y zCyIG53XPn_c`H-dbT9=^CrbFZc5L2YeYQGcrQy1Ku-&PGyWXi2oIM%~)3IZ0QWT-H zS&262R)6rJ4E~r*1>cX58p1`xa@k)%=gB(5n&?)1hi5Lb zbp0*RrAC4T6Q0SuGsAG!u->ya{UQPw3?Gdv;||u(f`SnLMI{|8Bov<2Nej>g{e=;z z$`5^+z~;TvgTA10uz`-LMTi4W+|u8PJ&4-CjiElP&Lc1NMyd4hqej8O76txT6ID`p zodi@ALKdFZn)5=9$H`DpZh!XO@%GzDRxO+QGXM8c?`qqltj($-I3l$Y7goML(wpEN zE=GI@SJ^pKxFUUpjjnhYZzjlT@iup8j82*o9Ci=?VP<=)Nk~|mo&Tqxu%>L;^Zuh$ z^a3nt3m4a>Yh2$FmS$0){ttM53(zwQJJfi#LQzc%(ZJ3tuDS)C0M-HgkVDex`m=M> zUB{&azqnHEz}*i|UvU`Dz+b>1LHD1kO;+I`9J6(665c)Kl1xz*F~pRA$OOJ*8P7&x z>S4sCr}6L2YO*2^&QIzbD z5j~XT)Ev~cqYSm8w!Ckmp<|r!!7cI?g!m|J^q|~7bU6i`ICE7fTb{Ua5r4K`TDe5N zBVmwoHu1~Gky&2-#7@vgU--OlivN?J-roM)1?{3C*tdJ2uh{}%$k?H8cxvl0`&UN>|(!fXOf@Q z1G4acF%XtD@c`tx=pmja{)DsvKZ9yQkinN&#hXma9cM&>+zth2^7WqF?_MZG#sk4ed4&23EMv1k5qdId!JFQAlG z=V8q4XbeJuvzFNMN{%ie!hZW39ki@HR>0P>o@U-HF(i%BcwdkNy7M0`*eR)6miQZ z_H4xW@Qzca#=g6KAyyQJQke}!9$v`4M*o=2-(*6ww3M7c@iZBS&mh?xqScjBh1)1>VYWL#+yU5%)KpP488O8+!~dXN+cbn7ElsAv2{HH z?g3_XMVpfF+MCT60dKGLD$3BSn|rm-;8=Ppnt#Q!DD4YHJ_xr$(_Uv+3375DF1O+a zaJP``&j<50;2|=l{fOrB9qjVBPR=-1nfr_-x>8*B(X_?kVZFm54`=Ft@%33MqOL4_ zN;pysoG{vt7v1^9E>0Ms=7pGJA}@o3S=Grl)qa<#jjiw?1pi`|tgkM$M3 z(_q2r`lt0@LF3O}(Zb2Z6ukCYpJDVorL^|O4(IC3(<~J(PbiE36$HJB#oth^8iB+r zO#t$o7#=d==9+dwr*MZfQ1P230J-|KJp%QC^v>bZ@n6TOyj#X=Hg_r+Z24x%L*7P!L9 z_w{SG`jl4jpf`s|0gk_KLq-hn`<67U^d1_O*Y4d=Gh7HVN-7>3Gr`d*PCc~8yBQ$! zz)a%urd3z+=OKsH8NN8unpo;_uaP=c$2JEo!s@XmS6y{ZHcd|u$q`T~pSkm|Zzy*6 zk%*yu49aZ?2}0qP=%p5XBcc>$8x+W_w83o{9JPuh107O!lY6cL{G}WJMYnjk97qsn zCnv>3lMw{JL5a)X5pu4NnQEhOYc9WbH8;&LeR-QD>9a?Y!0M9-68VAumste&1D`bv z+Mrah47>=4v(0NA*hXaW)BMXfRPm$Ie2M03FIoN)xz1Sk*x*@?O^GUW1So*;2gfLc z$*_hWjc>f9*fb@4cKI?TWX-Ch2|3wW$hj{mLQ>x701BYLDESqxKC4R98bn7Vv0Nvq zQ7jg^W4a{Q_Z8Rr%K~c7(Qu#yQr$IT;Q1ChDv}W<2{tAi67Uy(?rCG%Ix$ky-1_XE z#n~z7o>pi78|LO3$Jk(MY6NM-CtRLOyDSEB%aQ3H3N`Z3laGXk2C$G1BO_Y^VE89u z(7yaA;uSah%QjOkCsy@8ia*M((_TVfUseWMew&d=6%K=yx=5)oLioSqzcOGpWbiGI z5SbC(MhE}w$VDj@O2d;n{PI1G=A?kZb{-~1K{qo|4*U~=EJg6>shEP`!|FQr)lHj? zo&6FSc8UzCckufitp_MJKBrCYUwPQ?0n_}mI&QNXcKA_!zm`8R^y;3H4q0Rr@#ep} zRS60<6h*iIWr8x<$ukdkPuL~@?16+BoCnNZ_eu%wwa>@*ZJR5Rc(Rg6)=soNBLCU5 z(Ys*#^&STR^uVBh?b-ZmyI+#tikSQk9RTjoVJqYkQ1o7TX^FS)8ONChAC_NW52luN z^qdH6hTbTi(QKBDL7sC-RLHQ!;XvirZQo+TPJY z0zkH7rVs%`dTcBPG0uFkS3nX<^#m&tI)E$ zuPf}xMcF~~GZ55a<`7CU;UJ5u*iv*}v*0HD9DTM#F_N8q_50-1fiilzeE}j}Q zkb^h)vZFe_V|S}hWn%u9XswQ4MQ9}{qThi5%@-KoZQ^@-+BL7D;eb>w0Wj($9Mq2^ zL4@hRNe%0%(V_%F-H#vaB2QA)trR$Dr!a>bf)zIKM}AnM$6`_h)RDprTwzr9U5AGX^$L_DI-Y z#azXUrR_J2@^X;M+lE3viwOjmlJ(8YZqgiz^*gr*FTVP0`oQ zp}*Vqp}tD=KEBPuO^qL|XL7PA-DbKL_@IMq3s)~M?28QEQ)35NGr9P?9{xtUg)QzBaOh479h%ph3B7VF$_5y&0!C``odf2&B$TR=8UQ87xva)k zwxB5z6ua`MNjmG7D79B$)cIZkpfAvEM9iRlnW0|v zlUVxtGNd{NseHtBVtbMEM2h8)y~BMIO7j==k`SK9}_7cSAEQYm1 zDfI4KrNUj`04?-O(D+AYCTsI(QJ|fAG7R+=0A7IL*2Up@C|q6Rz`x}{-RN+0J(|=2 zrysySDXui6_%ha?2#R10Yx@Lf`=xdV5u>KyxGIBbWO~U>{B_q6DMG8dI6n!)_h{y% zDH_T5@Pt8-O#GAJmG+eVA2d+JD~Y(v-maFP-t;@Gs%8?^!z0?|pn?2|wQSTa3dLAj z5}6Qkh%}u*EwJ3iKi0D(Mew1bRYAkFJ>9e(uKsAW^7BwS>ipLL8kxUn@NkC(^|1HL z$pC8mLeNu_t40JdcQN6~1`v2kxcKik4T>`Rp%v$325E;x6>ja%ps8M``VwpY-6c4Rj^4)zR6Pu6}(`RqNN+32ocNpC`B#J^$m7DL5)E8t4L%vX239@}Fe;KXdA_`;+z zMrH8~_jomNJoxyN>HTbW_LnYbHgA^38Bt?1Kejjv@8OyfwBDhuR!U4? zR1d1{R+<<~@afc1g4z!a%r~svlIY(y^V{9?uvly|%E+td$X>)3C5Irr#cRF`s^}@r z=;vy(9OhyhC~9z$1A5X_O_AY!%gM;c3DdGuAvg(fqt^CoS-5RXw_sOnmoKz%ZV_9J z!F}nm@?=bdmOtu~QgV+iuG8=;Sw~6%sy~$|OKwO|G!MMG!14zYa5J2XT9|p9Tn(v# zL!mpuOkjYWnyeA#+bZd`b*jwymW+ zKkdTQytqZ|-R@Cz=S&Pd|R-k2Q1(fgiM0Hcw$@RmO z{o{?h$M~U1V{^`l-sLq}5BbIXK>5G}nUzrNVdsqS3R>11F(G53&yDAHLi42ea)i2H zqvmC5WrUkQ%SL{qW^NL6R*3g5$%D=(+GLtYmDyZ^+68@^e3wX@4PLF=ai^qElG%>I z`icW2Qr9cPx2sj4ShC^t95aP*-{3&agbqL5$=)y9NV|FVBSk1!x0$9H27J{1#cchh z(N+LvP0i+4sovIdrRLi#Gw?3=VjB+J$^G_4PXG#q`A43^6#UbQ%xpy)X!3-ZJ|~!60zPM=)FKUk zq5~YjTAcBGS<{%^egMHOco%J_dnjZV4a0_kU%YQgPR2!>nix%j@Uz7#6%KzpH|`OI za#Lzb6 zgzyquODNj|3hjRr^8#O=EdpWbOkbazFU9W2moKfw_ja(M; zgnlei^IP&B4$fzOWLV)-w!%+;Zid#%gZk;?ffj`FwT17e!U}v&b_1~Na-w8u=Y^+z zAeusecOkgR;5pNI1E$BcP5mMtA8%S~TVLgOKilI31)-`Deb$@dw<+}!ZIv+j?#CdSMCLpAAbmGyLEr`eJUGuHS)GUrw z)S{YL95sL`?x%u-m%&s5cW6#7GF77IhRy`EB9-xy8|BqlTIF~lR1V9=j(yl|-4sS(m~wB4O) z6qo0iNAL&Na6k1+;V&vlvsl!5{Oow(>5_k?EL|mO81O%#Kav0dt6}2%8-sJe#PhF| z1}4Rf|My;-`5#$4^FKB*EHtnzel+y|iXMXfk{qx`)I z;(iPIt6AdV`cJSCjF9&w=AX!;|C}$wRC(E`{z(3N_42e-`LAmhmdQ&>{m172tz!Uy z_`fUwz?U4hK~9RLq5y)!2mTZ16wgNnSN#G;!N>NuCQ46_M=xNx%y=*#K7#*<=$T*~ z%#^T6KD7UcbeUkcd@ug`{BJkp|NQ_YFg+DTjrl(wVJZS-aN~apB*Zf|`oRAGRp^fz zgaDi3XZ-8xj-L!92&?78gE0%x{gwRD$NiPmu%NyAr|5s3yi1<)+nR+w1#mTS0sz|o p)MSVm0GymXY|Wfry4%_Q+vmSe?8l#~6v72N6ktSJ;{KEG{{X3Wp78(x diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf index 823b1d868467b426659b246bc1083d1b446e8966..3141eed7fff618b07a1b84db8da60bdc2cffc9bb 100644 GIT binary patch delta 6826 zcmaiXWmMH&^EM(K($XOkf(RTqaDYQdcQ?}AB`NWvM7p~>rAr#6B&6ezhX$oP54_&b zr~kU|5AXi8*R^NnT64{;S+m!D*8Sq-0Daj?hE{^EZX;DIaS?f}stLh8NTi9Q8RW*; zm(|BUlr?yl3xG#(h{)bQ8LXG65DpVMO>& zN~gcNI0emjb?=E&%T~1EqY9oGiNw5}G!!&UU=-CF8z1u8)%=8c2v|sJxqFx<{XCQs zCH30zrJO){3d;6)gEtu9Gc`;B>-YH4qGuMNA(Wd=W*F z(mdR|{>9d-O)EVi6?u|Dif=#IDd94Z*Ddzzu6XXpZIVEQt7dWl1;1Y|<=fwWECdij ziYdl2o>6Yscho%}d=p)#ZrvfL>)1h0OYeMe^B`s}pn3luE1TY_&9^r${Y^}s+Jy9W zerXDh?<(wLku+lQ5RM2tA2{+=kaG`MoyTo@d>A@W8N5`650yUsTKaM~3)po*(-MV* zH|~hxX{pB;NwMKTH|JpP$6j(#wF>_}d$mFx&18rmc=Dgdd3e?YNxgga`H}rb#}5BC zl<1EtR+FJX|6Q5j#Y}>1sCI);>~fW!XFK|(OvUfPPeza#0U6;s&AGEMH=YC8OyNuF zx9^Fv#@#%9(uCO2X zouZqZfLuU04a;0m7c3~sqP1j3oC#H0CZsI(u24O@6&F6ql9WeFL27~!=3T|$Dzd_B zx9o~l_KVeTc_6n8Hs3w7$0>bsKL1qq!26>cR{zIuMa8E)z^Xv7EvBU$DOW^lipzOq z4wGELkU3a&#-A$>VP1>j`)*tfPmra5tjvrF*ax3PIpFzbUl30}H!9Z$pJ;%dk`qwn z*C-hS@#O063x?lH4OtZz&B>Q$p$V7esMW8X59C+{dM2&}e|mXS_K)mJYYl-y{>&$s z27$#Chi4Yq9`TdkJlgUaU%xeRTkDTyZ&zX--m3?#s{S_rL{GBZeqdfA!J6dZ8|MVT zUYWereAuhakCYRaen)!KQMdj6%ZdZdOyCPjy}z*yYv~1heIehm7Dbq|uk-*;J<#bQ zx@W#1O;nRdrACxy=FgQjm*C-(t@oPKD_s?;{t|iM^ zgz8bNYT4-&%bdh^e(wLe_Vnj2U>d2nbov^z8eTc}w>mLu3YS8z2*oJ;SCo7LO1+?GqJ@RKqu@;jW{6?WnjMpe6bP(1Rz^MbkL3 z+IRPE@-9O=GK=4d3&3Ssh?pYT=gXC7!+1^(Mg3pT&1j1qF z55es^HlI?G>jZ}dvkU>e9cjn1>cz_-4jsbQ8V>3YmYC_%ALbZ;BiA2m$eaz}+PgD0 zs_!i%ZFIg$hG2ek(}%v6&aUWHONEkz|DB++B{bO^!mj+w3neTK5Fg-zDJ!gSc^{*G<{{u7+Kw*-ShhQ@y+c?4uxm+)!!#ddrMD zGcx{ewVhe4fvNVTIDrkrB9q9WZ)#~76%1oa*5N(w83zi0I`awpg=daJs&-Vuc=iSx z+}XBX6AHZJc2(xO5SjAyH<&xR0&MEJsN<~{b#+xU%CZd`PId}bs3Kuk8SKKaE_e3< z_I4e<&+%U!cNUjO{8Fi#uh0t*ms+A-UG+^i1cf88;)}L^uxP$X-Df6tl`eYy#&}^F ziW+-Ozm54e;tifo^Hr8weUnu(y^{vTn>hPFHbMYtzZZwvgzU(3VJA1BJ|Dt%a5H3? z^T#{;WK7s!lxEQPPIm0m4B@xR-_8#)EtKL9h5C z@cV&QoTRc+!Frn;*Wvti)3!7*XS|@yCVUm7gaR#I>Kv<;ScgnMo{}Sfj)rhIg%Y>^ z8lqKll9L32%#ZisLfPcK0a>BPf%&E$u+QsFZD6Y0gst2+c3w)$F`cMMs6~#kKd^V7 z^}dk7M0Ofn*)1bin?SR8md)&k2dRQrx#IyJ67?j%Fv!hc3#_9%VD8qxpzcgV4_Bcb z9GY2i#llxs6c;uQu3CpJM<@Hp#2?h~79BD1hawF=>&2JB#3I{(WM#Cgau?;{4kHUF z-_bZKbbr{V;bm%ycp;lqeeC`N8XbPG>{PN+f>?*!PBKg)ex8nKH`)!x-g*ykJ=_C2 z1m8#Kxvx%|-&{U*DAl*{iDgL~*&8X}GVg4vKlZPa^E+7+XdT}o6&AXQ^qf7js&k3R zB(KXWV=nB(@sw4<9L@51&Zhhf-EqsU8P9iMs>B(1KRx1-6QywE-8*ipbSbJuldTqg zESqcy(JPiqJsOv_Rn;0-l;J5tN0tCknT>8nTeTgESPunRqt#MUduuY~3USatDYw7WRrS%H`zB2Q)m*qclWO$zU9o& z__tZ{PgT`8&qw(5YxzZy%VVCP-D`Y}`W|TJq8nIiy zT#w9d_Y_Yp%+zv4d%G@zW%s1o5`MM_XoNm>7~JE1(Wi`+HtpKQ>;(YfD!+sC6C+ML zT6Cx&+45rWr}rw(IzF65>)+$%X`(C})r6Wqj*It>OxF03wQGW^gvicMjJfRan4p4b z)`#D>zM!k?`*0Soe{Z}n;_U?%s{OKTZaD6no?NLOM{Ewe^+TT`bnj~})Uc`$+7H&n zjMWJ3sS_6#`KQwu+j9U!-f}@}B3pR+^`baq(sx%z{wbbi1qhj(2pViV5~**z04+=) zq6nH&j>Mv;drxDU)?-0^4ZBIWxH$CZ7J%02)6w&@f$*AWVM@hq^caNtnMWL*J zuZ-7%`B#SD?sDH94@KaGzkBOH6JGs&GQ5YSu6G;HKicg+0fC6E?qA_VuXmjm{%jlD zaVt&!HdwOBWhx|N{ie*NlU7n;CWo=*gof{T$5LZKwR6K`ez*6dGdBJ+w~rYoPw421 zK>q!JA9nG;4T^YPJ$2VloVIjO%Z4>{!$Maz!QJsR3=dor6^ z_0k5{+LVxwJOEyc#$;T0#6^E0HOB05-M0OBzIH4b^H9Su&d`~3JI;pW3#Vg zKj~l7-|@z_UH`QFa+=nTo!z zcJ96I+GyCGn=4kfjdd;pZ%nSIj91?vuh?2`j)4dcHcsD%ws5+9#E%>mTRGe~O|!FX zOqScjqp)xzb#kWZEF{^7h#Uo>6mOYEErV^nmQl+!C_F{ChLzh<7$9PeTYN`BjgUja zI2G4cKzfU$)P0bNTnZN1{UAC=CBBn5&mT$UZOshQPRB z=0`#7jWuVPVHj%DyM!<9x_19Qc1g^w$u(BxY>Y$w`qQQKxB;A=e(v?!rknhg=u0^& z=5EEw+6S#rwYv}G(LY`${Pbyci%7U^;bKSv4m}weeu~MSNOqarR^b$zwi_@dEx*Aw zuzRNqyftgy^?ptMcenQb8!H*4?gQ!Xqm6_Q(~)x+*M%<)T`ZBCSUpdi;_G;CLp7cU zi?PC>*R@4SDQBzQWeFbkMyDdt>`tG`oljfL`^Kx9jDqC~k*TH1#*gZ>P6?9I%b)?q z$Ue~u#9e6Ww05KO=#s|DggGiD=ng`^#MLt-`L?XxJ@E3M5wr*Va`M5`Ew>QPAWu)A zT~!&jIut|OU7ZpdYN6#k#k!fzaMos|{d~+uGE|Bcg~d@iP-mp*l^ltZ;P7s|fpm#u zBCYhGD3eKHNbSY(9kIf?L5m{a_1peer+mw!cI+g!28Vq=MR@X{LSp^#Yaa;8E(WKc zkaUyBJQBz7C{e&%T#&>=Jkh`3)lJ?Pe&aPK9|MQ4Mear%UW{m0SUz)rPI!4-9Aq3L&cpT`x1u&jOsT^0%mTyv4E5D` zGqRp0??*dH*zc*h*0sfx(JC=RpQm@r$4c;J+-Wo8G-}wi3;N8q9kUaKp!Tnk!TD(} zyO(NuGw1WUq1_01ZeF1LcHYR}OC%-L^UObrW8E*zZ0c#?c6)HXM)}Ft&rC|WZqG%h zHa8QKdvpS33iOI4(i*LP_D@}Xa5!q3Qfr2(Pgz%&viz|^NnLMm*7swXq$(fjdm-}c zXKQc(mHS8z3$N^S+#seb{;VFAY(3k~q;F+Cqqln!ctmTCBph&5LVz>D>ra=&78m2} z;>3Z(sG?$}!3Ajbd*GAr;nw{ulb-b*#;BzB ztN;re@5|>Aic}a8jGflrzI)glJq6itONUuC?Gqbo@0lF>UiUOh#7*|{jI6d+!Rhaz z!LR-KAnAQmn-571zJ@x4R`PwOpUtonY2+z%-_tkD&hZsY+$DQP+AZi#*t{a}vK0 z$^*M0RuYWGaVJtx8>G0PB-y97w8=n>q>n{}Ikzv-DlDypiK0%Jo+kDxZ*~W$`!0}atA*{!_ZkcUW0S+X z6(_W}R!yAob+w9Ar0@a#utkOQ0U*%+ij6=Qsg;0$AhQu;@a?dB2QtOJmt@~5)}5I% zJy$r`T#fNn;=*XT=C*+GGg<1|Fh1kYJ8$jfsB4?aVq~o&-NgqP%!Q4hw=RgqYv}7a z(i7ZjbR|gKWPECYqk6`K7F{Y36{6l86rff2me5|bLSNmB;I#o#oMhgfsTA~8k5sa4 zt%&A2v7(qhv>VT6pm1r+EFrLRo<^{My!}JWl0z6v9A}GNY;;qh^A^H5q=D*mRR828 z(2@>rmfrT0Vv11Zd)#gqQVY*GmqJgP0eNWH3WVYH6f5a+1NG1VhbSSyhq*}jT{clZ z*(mHMN74}GOx4){`|{yb-0d?1uU+0(H3m3?2lf4J`DPyZgY%S)gY2KK5vGoyY>`1W z3(M(s>My~^oiC56b5gNiM!=yROO7K~{1!tF;v<}2cA(HuK8W1p^MUw}K8pMi9v`kz zA(;+JIvBn?yBZ9FA@%WqY<4(O0sJUBqDT1P*qxyO1`BykK;dMcN?E>%@5t#+fxN~^ zT#@>1Y(};0_OZ{RBox*|#HNOxkLKaMHA!{>jt((Zu81b}aC#w0ftBcz^y~Y_M55{d zO0jX~;mF@AB1-}-IJ!2HJ_fEu0wXhVuEp+bd+j(Qc3(LA`GQ0gXG(J$alAXjty0mBv6p1Vm=HTDI@S(j%%$rn=dFXc*e=KmNmE{60o;Kf$gaUIw)(p zhoO<$rTl_-_J+W5Sg5Pql~F?Af%oW6v4JqjR~^~0g^&BIiI`HGCoWE48tF=5y9O56 zFXJ79b;~Ik)0Kh`CF`+eIzi+c&3ozmW)z2q7Vl}N%2NAxNb@>iUoFIK?YU^GBSJQ{ zB}<+;)J3?p$IVZN06zHfF=rOGaK&Qh4o5=Zk86_7ElD~@H7@N6`_?5>%8G;!m}dv~ z&_?qK!iz;&Jn?~XEh+J|r2FgmLVp&sHutLrsOnbRP>U97+jDOG`PJPO6wVL|z31%$ zZQOz#jvELRa~9uUU?I^pIL;IL54hh{qCXkUGv0=5vQc^*2p1QK2gC{De#^;~=nmz1 z&cn@{SOsMSxIqv)&VLS_BOTWNE+8;3g#TX{CzzX?@81|N518j)*k2AV&VON?yga%z?ZAAX|Jdcj0`ZATaDs)g z1pmJ#bOu-)5>95~))r=VAKe}3I3V0yU_LMiBFZVo&o3bg;^*X*k`&_vi*ZUxii=C~ gV+jjmeRMN%b@Re^wXnnj@qqccu^1U8m8G!$A2*@?OaK4? delta 6568 zcmai1XEYpKw+=xNHNp@zLCZS% z-wNZr|HJ%;b~qL7BFVO`#W+HxA#iOF5e3-sZ7&AAESv+=58U ze^=I?CA|1%N9|M0!a9{OFQu=XBTb0f*qfjJw2~4FUbr3EH|8a z_;w#@J=a+;mbOeMd_^@Myt6#A`mC9Xx8wO}K9XU%kNL`=yNu%U#m|b}n!*;nbeBCzM}-bhTWO9wsjx9_vxVY_r!iic*< zjhdUA?Z^cyWx0{CG<+%@2Sr9=h_@i;><^yhd}N2u_e_Rc)^%J|%%f7Q5>VHy4u4Iv z(*V3IyE;+Fk{pfTlgKf>*}&q*c7a z%}NFdMBMHPXve`yYuTOzm#KF~kJqF0zEE$N=F}2|3wegGf9U0HSn(T+I;QUkp)RSg zil4BuPp+tNJxG0}iWTSn-q1y=U5IP=Y({XrW^+Q~J!Oe$#-#5w8Nzf`t{?$3S6vi4 z%kRdZ2dCFq(^#Y*H0z9Ld#Ao9I~P_;IdDQ3G+vWrclLi>zmx?c8zM>z9JCiPl*wk_({Y#3z5`w|o6(c57Qg!TTBa5#>l&Ki$_FdKhg`(IA z0N1fiTencqJ`8Tb)Cv5RkK~O#lvZO*%WE|Jb=0%)+->^*x@Iu*2bI0`3%$JRDo)3# z3E1D5kgZ}u+EO7TWaMSSOVXI-p~WvX&E<$a2CVyK<=`Tw1W%!+YCs=IEUz!&`*_ed zK=tJ*K`362)D7TecIW7g+banZW`AhT$a~*QQx1BF??xBN+;9| zb;hYxpemL9V7|t`>hwlm_QSy2ZGF^2oMtzEql2p#la2INfM~2h{6&46`&ud7)&OM} z5W86onQCsv+`0g%--yytFgvV#qK(|+;SB-McA@m+!1)#op?%Eo*zF$wPRYG+c%dj# zHsKIPD{IpJ5?yS*)-#enbvIu0zFF9wiesi30f2SVWqsS}OG$r6%cOk{>Xj3D_80Gr zzNw9vABxaLWuGSCh$<2o^Jtdw8~B*vSCrRyRn23%{91(-36{{{)1io#ApG>uvZ+M* zaYYBwI|5OLCd&KtI`}d8J@WbwQfOC_f54?@v*P27ZF9R(dLJF^lkw0WXX(wZ#v-e46 zKN92d?<7M6{mE!sw9iL~o?7@NbKilc^45}2kn0a-UllXa#m3EzsUaCZXd?Yuj zcg1yN7s2IwP*WJ6B%Id#mw2JS(MmV6!W?7B8_?2L-r|UlK4m4Z;(}RCINuf3gzT}G z$yNX(*CETv-R%gT@8E+Q$A=dY?2bwLm=Pn8b4ye|-;#8PP=gL{*K^e$3_NkNJ@?DK zf*)$OcC42AbYyBUQtrDbiJfw$pbv}0m9yGk{-y4!Q*O`saTD_8Ss(eitJPhtFtPGb zfQj}znfThuc~hUyqB)wsQ~M*E&GKJDrmBFZ^$C-n&`CYBk$FqmYpjCShds4GnXjLJ zMXHcKbN6RGA+1~k$?Y1@QZ9m7B%D)j_?E^vOWn=o@IC8fDOFrw6Fy{#qEIHlt1Gp} ztg$7V=`i#N@Z-my)XTa1c8qr5URbPGAvp6HC(RbI1(BkKT)ussdwdU@5_bce{3 zu_6`bF!ueu&?_b0ii)aPeT#HBa{YlCZbyrEf(+_b(@&|2w3Ik|zg>%|$Imip*^_K! z#_7EK4}qEp9y!_XHZBS#38@B0!p7ha6?Ixk_F`7=a`zY`DX2+wy;(_YF+p;YRvsl~ zNfd6#o*-MT&%sMgm0e$>bBX#`#sH7Y!_?|z|e(j-XSmYAS zgtp^(-73s)68C#gjkDK}DF8jbl(>Ol!9njOJw_X3rQ&S)m%@Mye%!By`ZDbtIdeIF z)5Y@;qm71nRAx57dO^5Vn59;RpUNqcUQg3wi0*XxO=ZmpM4gaBRn;D6y>w|bubq=0KopT!`LQHpvf`QB1rGJRIrSH@zZ80gP5tQB z8CBPGYWUUGhI$OYAgSK(ZFg|^W;?rEkd^Y&o55$mwi={ zhktO@y-?(Fuo>j_VQ_>2UVpRy97#@gW#anwceuB3@6JI>ljCLm?i)HQiaEcPWgsWO zSU2$j8%|P0ih@RJrRI7uyWk8pqIfTL+SZ)Jb-?lAr@}ZHTyBo|mB+|mLK}{6+N?ie z0%W7{3#z!pttRfolt(m6Hkk3EywXN40o3HAPWmlru94LrkUd8`7Z9dZvj;V}dq%bU{2Gps7UU zT!UzZ{PK{J*3^7V+?5)m;7?g{JP!;h{%Q?=Y2ADf<;iCaC~0#B+V%}7Q&m!fJlN=a zpv1j55&E;PZw&hVc1t%(G~LcrjY<@{J(U1g^?@G6c&MjegjSV3`ZQPyEWBGOKxi`j z#4(_cQq{-Ev2nDedj`auSHkX;>no7S{3i}yfW-VN3Ozu=rx5hz-U}Wt@=(kavu;D^ zXrAHd)0nZ1rt*~sUxFKaL(Bh^_REFE@`T%=u!<38szE-j0Y*Vc0hrMF3M)2eoCN~w z)uEv!13tz{k-$-Q3DOdPy&?eQwdwmOCpCr!ZIhQQwwu2!`$-|ceQ2t;uLeB0*q*j& zy2M{C4S)Z$Ir-|4%){jG7ctXggBkn^SQm^_lG?!u;cQouK@M#WpPYbz;%qAe?+-VbPl8WOWXK>8UbxkA0T zl=lpxN;&>^_$-n!KRg-dqtXi7Lk^igy5hzw{V!D00e-7DfZn)=npR&7qmOY@eaglE9io7^mNAo#|& z>15KgrKJ{iu8mByTu9Y;VLn}Dc zb0QtE(bX*)T^@w-M-HQnp3HtHGJb0~H!`DUv7wygO^lsjf1^+5tIAeTiMs`W<#WH> z29;ii3qRpxJ|`5(?0sh;4%j+H8_X&B_b>Qag+})d?#cVj#C~7!n{dk!sbx;G5O>-- zZD%}|TQ{>+q6)e8`7l4TWzk~32_wLEi<;_I6iR%#X}eueis*r6G{>;xZhxg& zCHk^v7=7@`ms7qEvgLdO9~C#)J)eFoib)M`z;4{{0lUENB_<4DP_dv$yRj@aShwFJv%qv%#kHCuU z-2%GIbz^M)k${kk$5ApJV~jzqD@qP9Q06lkBv9|ev%J6uhl`p6zG7jn5I#=V*(H5z zAs)UphLLXzeb8#qs?NgLpw)T}&%#I(+u%P+(o_*9N0cPLBK|p*iYH zj*+re5|`kXmLG`3(gD?76(f>2p`4W5V|iX&)*_*+>)U4*3`@~AbeoTdj^a{E51DTf z*MB?rTeN6*mzi6#2a_<%}c|HqiGDe*^ROQ23mAJZRYn@JUPYV&@YOA)i(?|cH4Enu{G_ae(U3ll>2Bo z+HKM1XU8!BltxBglRi}SJ2~V#ZaCg_LRTauS9NB+mqUxHYKpVfk%)iY*ijDOR50N< z-5-z25GK59_T4ng1VK`-j5s{avd;Kt{gzCFwa<;->&YutJ6M}w;(u;Vs8=ge-I%Fs z%H8gQWhfOiDW16&J51@yFKmy+otxJmN6~OsWZrtaX|WYLqiogtPYb%I)tb#5bKZTf zXf<}#DNFcni3EL`=?M6wKNgwX9ooE)%R6^8Us`6kLo7!2B6d#8s*Y^Dl({7#U1+;c zNl?u95M=LcJ1|;rqW@%r_ajYm$Lymo`l~bF^J3Yfd0FCT?d%yeZLj+pI%^!$^BwKC zYp1tIaUvpvt9 z_u*1P0F^SPAlOERJwI+=&U@@03qE(kjTMDnZ=ztXyLKKp13cI+i&pWy{YmU}CI^bw_zhqh2wdd8$nKD#yA z^+N=!snO40_9+r7iO(UF@flnR?uACy)rQ;Q!lq9?th}oW{ZHghXBBm$MtY&ooEJV# zlH{f^rE5kh65+Rvs|VhR2qtveJ^BA>D)>@s5g@+WbO!JNEo5{6%wP^Ie_*pQ!Oo9(XM^xZ|k5gtT|7<2u8~b^mMXvrHOQghT zXOz2?fAsT7b4>Af?hnCr?taW;QS!CD-OujpRfu}Z2)KV^s2!)!VzEGVGtt}2ul8KF z5!xWu(y%KV_Xj1KyTNYpkUaKJflr4iaZvVI)~WuW1~3U_gOh?>o(><}M)-ZSS>Q9w zn@3;S0~0t>p0`lMn{g$;3XL|RP3q?JpB~+>-yd?6GHsxZnYE5|lkVP?imiaz#+n@O zUd}F93SpuR`UXC?3y?in_I|M>EJ6<8eJt+bS-Y6LhwghnAChcAHt69_;*3hnA*YSa zn78lK{5oGh44-vCf0tSj5HDa|mFA+yq)ns|vRrI06%y{Y-$dA~3`%VcpYXpPa^2vXkmEbbnlu?$>E{`QmC7Qf@uN?!e~$%0_oWtths?s?xp} ziv4lZ>7MS}fu_@S!e7(%&XUgbMC(7Ydovm4jL$4C6OA83#*WF;#CS9n)xE#4M}!R> zF_rcC9n5Mtge#4rjE%(uXI~?PZr2m20K6FW9KqishjY3F+Vbv(z5EOv24r=BADpyc}>zF1GzMX1;jeUF@4;ooV7;RQtLu zwM`iWUzl`2gn2;)pjayH+AsKnQb!3Wy+9)>V5E|}s84Xr6zyu@@Cv6da!?PN+QqT{ zu2=!?qGR=Bgr-EQ_Mw-kD*TdS`!B}y^XZ~CvHT9l!PX1;@JZA7^R>DC(LE_sC(BvY za(OM}(nyx>i8?U%_@|$y%1fZgnU1pv!#Z=;7CvCI#^ES2Ov-TaXFe&hAD}khUDtElADk6zq^1e=c zH6kq)5NTF0oF9?VNf<2t3SN0cNX?#M(ETna301rj_%@xWlmt**PdoaJ@G1rVfbLxu zXo5^I)#236?~fi&qs<$>-_zWUL|nhgM2cTBFe}NgW9)c`;P1|dh3MpPs%9*R93$2S z=C24!BN(Ifor>$i3KW-aKDvm4%a0#kWS9(ixj?AE4OFt_=|1*4pM-(;o%ei~RPRX_ zW0{_5(fGaT~IWI%!-#J}tW!Qg+BgFye=SN1=YL4r{5 zznx)%|E$7Y&d`4`h5%u}1Zpu+3 Date: Fri, 2 Aug 2013 20:25:26 +1000 Subject: [PATCH 65/88] Merged commit disabling FIFO in L3GD20 --- src/drivers/l3gd20/l3gd20.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 98098c83bf..1ffca2f43a 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -333,8 +333,13 @@ L3GD20::init() write_reg(ADDR_CTRL_REG4, REG4_BDU); write_reg(ADDR_CTRL_REG5, 0); - write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */ - write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */ + + write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */ + + /* disable FIFO. This makes things simpler and ensures we + * aren't getting stale data. It means we must run the hrt + * callback fast enough to not miss data. */ + write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE); set_range(500); /* default to 500dps */ set_samplerate(0); /* max sample rate */ From 4b342c4a1f4adf47fd34144992a787107ecc539e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 Aug 2013 11:24:27 +0200 Subject: [PATCH 66/88] Hotfix: Give FMU its own interrupt stack to isolate the interrupt context from application stacks --- 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 49ccfd41bc..d338161296 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -328,7 +328,7 @@ CONFIG_BOARD_LOOPSPERMSEC=16717 CONFIG_DRAM_START=0x20000000 CONFIG_DRAM_SIZE=196608 CONFIG_ARCH_HAVE_INTERRUPTSTACK=y -CONFIG_ARCH_INTERRUPTSTACK=0 +CONFIG_ARCH_INTERRUPTSTACK=2048 # # Boot options From 7861caf482584afcc19ad235bcbedf26386c05dd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 Aug 2013 11:24:57 +0200 Subject: [PATCH 67/88] Hotfix: Cleanup / revision of log conversion scripts --- Tools/logconv.m | 3 ++- Tools/logconv.py | 59 ------------------------------------------------ 2 files changed, 2 insertions(+), 60 deletions(-) delete mode 100644 Tools/logconv.py diff --git a/Tools/logconv.m b/Tools/logconv.m index f7c291b48c..f2ae6e5f37 100644 --- a/Tools/logconv.m +++ b/Tools/logconv.m @@ -16,7 +16,7 @@ close all % ************************************************************************ % Set the path to your sysvector.bin file here -filePath = 'log_second_flight.bin'; +filePath = 'log001.bin'; % Set the minimum and maximum times to plot here [in seconds] mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] @@ -111,6 +111,7 @@ function ImportPX4LogData() time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); time_s = uint64(time_us*1e-6); time_m = uint64(time_s/60); + time_s = time_s - time_m * 60 disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]); diff --git a/Tools/logconv.py b/Tools/logconv.py deleted file mode 100644 index c47d22a451..0000000000 --- a/Tools/logconv.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python - -"""Convert binary log generated by sdlog to CSV format - -Usage: python logconv.py """ - -__author__ = "Anton Babushkin" -__version__ = "0.1" - -import struct, sys - -def _unpack_packet(data): - s = "" - s += "Q" #.timestamp = buf.raw.timestamp, - s += "fff" #.gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]}, - s += "fff" #.accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]}, - s += "fff" #.mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]}, - s += "f" #.baro = buf.raw.baro_pres_mbar, - s += "f" #.baro_alt = buf.raw.baro_alt_meter, - s += "f" #.baro_temp = buf.raw.baro_temp_celcius, - s += "ffff" #.control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]}, - s += "ffffffff" #.actuators = {buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3], buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]}, - s += "f" #.vbat = buf.batt.voltage_v, - s += "f" #.bat_current = buf.batt.current_a, - s += "f" #.bat_discharged = buf.batt.discharged_mah, - s += "ffff" #.adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]}, - s += "fff" #.local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z}, - s += "iii" #.gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt}, - s += "fff" #.attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw}, - s += "fffffffff" #.rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]}, - s += "fff" #.vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw}, - s += "ffff" #.control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]}, - s += "ffffff" #.flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality}, - s += "f" #.diff_pressure = buf.diff_pres.differential_pressure_pa, - s += "f" #.ind_airspeed = buf.airspeed.indicated_airspeed_m_s, - s += "f" #.true_airspeed = buf.airspeed.true_airspeed_m_s - s += "iii" # to align to 280 - d = struct.unpack(s, data) - return d - -def _main(): - if len(sys.argv) < 2: - print "Usage:\npython logconv.py " - return - fn = sys.argv[1] - sysvector_size = 280 - f = open(fn, "r") - while True: - data = f.read(sysvector_size) - if len(data) < sysvector_size: - break - a = [] - for i in _unpack_packet(data): - a.append(str(i)) - print ";".join(a) - f.close() - -if __name__ == "__main__": - _main() From 36679fbb39a57139c03cce85d7d0fbd25383a98a Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sat, 10 Aug 2013 11:22:08 -0400 Subject: [PATCH 68/88] Some DSM satellites are fussier about bind pulse timing These values work better --- src/drivers/px4io/px4io.cpp | 3 +-- src/modules/px4iofirmware/dsm.c | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index ae56b70b36..5089ce3c7f 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1445,9 +1445,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); usleep(500000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); - usleep(1000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); - usleep(100000); + usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); break; diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index ab6e3fec43..b2c0db4254 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -125,9 +125,9 @@ dsm_bind(uint16_t cmd, int pulses) case dsm_bind_send_pulses: for (int i = 0; i < pulses; i++) { stm32_gpiowrite(usart1RxAsOutp, false); - up_udelay(50); + up_udelay(25); stm32_gpiowrite(usart1RxAsOutp, true); - up_udelay(50); + up_udelay(25); } break; case dsm_bind_reinit_uart: From 1d408b80ad70bd8ea873ce7215c8a92a62461b0f Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 17:19:54 -0400 Subject: [PATCH 69/88] Support DSM bind via QGroundControl --- Documentation/dsm_bind.odt | Bin 27043 -> 27123 bytes Documentation/dsm_bind.pdf | Bin 34300 -> 323311 bytes src/drivers/px4io/px4io.cpp | 46 +++++++++++++++------------- src/modules/sensors/sensor_params.c | 1 + src/modules/sensors/sensors.cpp | 12 -------- 5 files changed, 26 insertions(+), 33 deletions(-) diff --git a/Documentation/dsm_bind.odt b/Documentation/dsm_bind.odt index 66ea1f1bee22eba9943f6077e7fcec6c6ef6e182..587a38883bff56f458ed0feed62a1731b69a4459 100644 GIT binary patch delta 5385 zcmV+k753_*(*g6-0kBU4fAdE4-RuDX00RU700;m80BvP-VJ>)WY>ZP$kJ}&=zE|ph zu(;dcENy~p&#kvEQd3pxjlzq=)CLQl>&d?_#wN|Am)_u8-U`*zOW$R`!Fg>>P0E6i z42-l&o3A4e~K&wGoCM0O-5(9 z6<&L8L=T>$k8{ysw9OD<|;ici;|MH z&X-P`UpM(QO~tg0hVpnk(#Vo*?elI#8`7li=j=@tYiPlM6KGxYQA=mNJ>%y%B3kYX zmfgVb)~Sjsemin)#8M^S_qe0ZV_84rSy@AT%3RZgciNXNMEpakl4-{a9na7S56H9EZFtPaDQ} zt0S>X4upQ_LijAso?jfCYx2puUUY@B*oVcEL~x1P?037Bb9PE-89rmwo3MxJq7nQcWJvyxy?l3^2SeA_ zJDdLAZjD6v0uKPQM+JRQe#o2FT-tle%m-kr0$re|m86KD9;)4e_&Q zPbaUj$iH5{YU!1iL&eNN+vl#R@|ChfcN4G9?+=v|qGae1e|1dt!l1Ou!Dl!;hMv;j z(-+4jR+ocgDo`Kn&oyi{ETkN0@9-Da(cp8A73yvVhc!s=U;!bUA(sskg^Bxm@alH3 z7KygM_m(2SopNA!{B#nQ8{fU%`ut>cz}cToc(o6oFWXO}MU%+a z$ls&2Ow=eH=9{a0*mkaD@@*78*NmftVV8h zJMA2m6*`b9O6?Pb^^LTeOcTy6Wnr8e#q($?;!ANUru=gu&hhsmn%vLgwMNAeZ`4k_ zHMuNKu=+Vg$Ix1mI33HjKBJ@fBFj_p7@S^;3+DX%f6E-#N)@m4X6sMzd%WK9a?I`j zreIPl{qz((sa>Y^g2p-O=d$upjMvGCjoEq)e>?D)W!xCNl$P)UlZ=8pU2D%qXNhuT zQDsM^+^Bl_^%AJ0_7=9wJi;MzV`aI81BaFN$*8md8P;o;!hrr#ivW%i3&H8jBrr+A|*&}S=L&PqLsCos&9o&E%FQxz#@6`28%x3X{{F@D~uG!5D3jaS`~txURadwRm*f_}{^G}6wj(S=Z3 zf5kl!rV!p%3am3l83?)AsQWJTY>V%8L9<}-;@xZEq*qy{y%JU>O4A(SY7#czeMkrg zlH{&yYKq0d6;9-p^J1mMij*U~5mLBPB^qOA!8*#dN23T5YVCyIs=Y{LL0cegDt6j$ z>8U7hFV=ZADcyxOVx3WUEofS8O_nJ;e-=L$!tYC+$V@oxE1tDE?9@(Z7r1tlg-p1$ z(r$~hD@Qt!td-EOwkn~c3zc|KfoHn^bG3;ZEwTH2wA0|+VJd>VHRk7*1~6ms+CX$t z$I;nNm?GN?G`Kf9Rbu%IY@#=X%&60~Ldj&?NG3272OpW(!9TYGJvV&L3s;q;f3d{e zYR}9q-(QTybLWZb|NXcBG)gnU92_n}Wjfade2y6{6!wyoq|%%$u5R%z!NCnr zsfw6d!FLZW@aV{onW7dD#%?s*f7gy!Yn$(&zwwuSeTjKmtIJkldawPEHgVN z_NF2Z%gWbYbizsC5VZ`sN#PambdiuQz~@>?UqJ;{{aV2s2_+h9se@mUPNdXx7ELkL5V@JqL7z9Z-qIX=VOqjP~xO1lKfhH!d z?dP3N>D|c1`25Lbv%Xc7?&i_?IG%=wJWPVkk$afjA@9+^wSC@f2@AChI!E0Qw=_qd zZLM0*qgYD@$I^>5JSDr3p!w z3NvLGgh7@%aD>d|e+9iyLI&P(evQxQ8Im!F07yAbajP>~#YtGEHxe(3U?mC@)0b<2 zQ)5cBxHfgzbA&W0hS+@j{KMN<@dpU{fpQDL2|Su=Z&Rb43Mqkb&FGV|M%>5@x?5vz z&ZnU$f>WdzWPy+;{{91_p68(u&juvd$I*gsM#1#QEX4!%e?N&9FOT@)JWQZL7aI0O zsiFMI37Z{)FvJkno<@tx*cGA(Z>@uqPy!A>YjPjk?9T_Z!6oiEh!>f^)aBD7p^pIG zJ&q?ZJQ)DZok<6i_{Z+O2w;{7E2 z1pfS|scaWqe=tggypMcBOt7}WCqTFcHprv{&_RJCHp!?6Clp)uzk-MLt-KC(6aVI* z@JfuRQ4#7%Pae${1IU z#m@{Zk2W^)G^dA*)7TC`4gulGj9p+NVkug`|MATWf6fO8;t-KBk`N4!MVOnSma9A?o8BGe z30~KMrbdr$0E1l<*fg+|_ZC;px6rjV-@6aWSQ z2mk;8Api+8xbs*D004y@000UA0047zd2D5KE_iKh%vnos<2Vw&FR=eXP-B4IgJL_6 znU2x!!D1G(m+nDhrw4ncCEDgh76poqll}GkRq-K8R?_P3%O*eqvx>!!^)C9|&rioX ze|wasQ@YvYtE*+6$)?nmYWAD_kI%mrZ}Y6PqNzl!8@b7!Wtac_{;z*|r*}J5%5|m7 z(@{3I=&h+~g`%i{saPx?3y{!q~YI zn0c^UH#-IV^8l30o$jx;bN5!limmA6e_(gH$q&}H>&2oynfgkb{h}%tvX-Q%Zn3&r zEpo4@%G^}5&jRn@93#&2_lh%2nr`3extpK5y4dNW)W;Tv+SY^H?zEY0YT`{H>`hhG zQCa8n`RaVb>bhPoZx+xRv|BtXd43c0brkk6wPAIC|90^aME>*fL*$oM%)RCjf4nKW z=5*XjGj}&(MLkk%R9( z9qe&3I^gX03#LZaS~U+-VjU|{fAh?{SCZ_n^Y29kNdS}fyJLw3bQA)VlNwM6mnyCR$WI`g#<0gD^Tq2BKPyz6>^FJN{;iLqnSgr9(F58Ef4WW&*?1W} z#}^@AXFmezU3SaJZ@!G!D>eI|_6IwGcTDfGjM09Zf=R9Pn<#kUT_$=#a1OuDCXBvP z$(=aWz7q)MWkqgsjv{!QGdh1NT7z!DSOq)n^!g~wUNuE6cZjZ~g2i0qZMCVSDUQ05 z2!>MEwP-t(vfw~xqbxo$f5RrPO<}iTE4*}%riMh4yDZ${1DFBPU~vjNQb~O}Hlr)J z#q=ibj1wGJw^khmr9s+QoK;1o%bJt?elSL#M@X=83F8Qb65$}pr@UG(5vDARkL>Xv zWm{Oim-awKP@Js(e%z(3>k)8TN|EE}ttcP%MxUCBl&5jJHKOTSe_>DygWdP_b9*SX zQK3E-NNiS>0$##ky%oc1;l07?HmCcYjcD0M)c4Yd@3|eIi9KW-;^pGX=x(gmv$BVx z;X2}=zMyZ$sVaR&$+%|J+O!9#B7EE$DISWgL|H*vcCxtUxZb5e;+J5KMs>lo$s6?Y zEUy)nYxOzeoNIIke}N+dlUpM}1)qleZIQ;K9okb<+7ovu1*s8LNHmD#7@&lwAZRdP z36!dmnso(>;4;CUT?2bqUDV=PpKP%=s!D)6AugUVj+l7-WcWMGW6M*YPWRx8`*gF_ z)@t;x%c~WBDC@u!eAy5)tL5DfygJJ(k+U!f>9(j8O-*#)f92I3KvH%U^T!^#~jk{xXn)8%mX(gwoSeh zbw^D{uTKLp_}^cMY&OU(p>Z9A&BH51HEYj|hLl8uSbpHFC#E?6D+WES4w(f7YP0{NwkqIq-xl5~ow9XAXpk zE%D;Qj5kHn@BauShKcnpyGiuE11gVfgayhu<(#p3gf7H?8w3ebMT@LgOwn9xx5;BU zi3P^_#-N2ta5*>Xn;ymxnw?8P|8%X}r%=Xzg@Xqr4B>gsEV5=PZ-7hS`jmHho>Rbo zBw95lf3AmzICAzkF#J7m1kt@F{8lWW1#s_ALmh_u#x0{->}vqhHD&4LkN3B}09+J@ zgf=P;h~)XH{UR~D%X56BDgJ_Q6!6!t1^gs2I`@jnkoWD*@>yA)(KuZW4L2ZtgT+FW zP@ZAke3L-v<%xCsk4+^*#fBc9rIkS&bf9%rOA6#O*e*224r-{+j zj{Nie&I#b<0G-S?Aza6qZ4@N21B#P!U$`ZItcez$>^)16-4$(YPFhrLN`(=~7ZKu{fUg3G_on13UkxzcA?E8a^b>SH zcLX0ymeQi(1GgVhkfrFm5mWj1hZp*RL|iz5MR_xXsNu0lmC-u<*!C})D^=O`btd3` zO++}xi%c(3;d_JiPSqHcJ6)?P&*DmGe`?>{ZSS|$ou_DOX)Ss%*L^ZKhCuxQSMn0* zAnurlE%*M$-eT; z6P~hIXLz#mFIY5}!uwU}%1wOBN(>f4g^ls)!!mYY2~VnCBwVKW2cNe*{?UNIf2(n< z7x4c)LHt{?BWq`TKDmd zFCk;?MO%Bq5ntTUzvC#FOo3%L(&F z^xf)B005>W000XB000000000000000ypu<19vcZW nxbs*D004y@000UA000000000000000#gl+(9R@{c00000l45wL delta 5307 zcmZA5Rale_w+7%57`jVoVd(A#rORRH1_zODhOQTsM!H)XM7p~}2Bf<~kQPY+;s3sU z?Y$5Fb-30#d=BpGxtMuYIP_5kDhprV?DP?Ew)*TFc+`F@ zB3fNpu42fW7@VMIJ2St#f((C%d`}yySx}E|=Y|f;&AK^b_mi~4GBFgp2H?DB&lJcL zDJGtOVJ;L{#jchTDZrS}bdv~DAr7P&w>SW2X#cJDjqRLgH%ubg?qQ=*Tp*io)KS5v z8RM4XicUb1x_<~IlWKtXU^P_zDJ!mD zr#(kd6LH;uk=&bJM>+~;0AorbwUFnePOqbQSP}|P4lS>Pb-q&&;pT8&^-EWJp0so` zsu&~pR(HaH&e3{fjtyx4+QzZ%bc`uk?h~6DW~xM979*B0 zZ3a&czR(jEhxV1KGD$2J#t&+LRY1bTX^*97}$0G98QZ&R^Ape6_ig!4}bES#O(EuGx|&B3nGn$yY%Sr^Zw z*Nd9xD`19i$;VIz1EbGNzQ%&z+9Fq=)gOq&NK5I(Rx|Q#f7sC#-uvD&-se!@E3nnc zk%F;BdEsi=0s{N{65W?Sn!PN0okE4RbSqeMa~0m`M5ifj|t+mMl<}!fMuA8EQ$s7Bu2LEvD(OtmPd6a9z1%mI%Qo-8XWcJ<4 zqcFOBdc`nvOdgzq zoMRNKtw6C-R;Eojr-Mf(d1u{nQ%)03Y1N;lrFZC+GVMvmY|F3E0#a7@N`(g|@?K?i z_7&V;9a_S8IO#a7u$Jk)bhVvAXxp>Ag*?5=sLz-z;(h}DcAMypE(E41?oT(LTW@ z-0y4zb&L&!dVZ1d7Jso5>F6^p0lMB7XkJbtue)qV6+<`Yn@!aCV_r4yrSQKat}YOZ=2--1wdWz4dNwX>u6d(Hh$+H5$+`RrRn2nX zSK3ihauh7C*PKVEpQHw@4RhXl;dJ%iGZL|=65Wgdc+_|IM166Pt^RCE}ku%*iX z=(!`St29&GZCpJK6+}avg{l#t#p+8KbE9HHer3oXfyPyv-dAsgQDQMRr^`dKGd6Yu z!vT`jG`W)ft#y(&-C-;j420e!+3!Bd_QbOQ^)o;71!Ao2iJUsqD(ME9Cm#qzAyVRD zF%OtbL$1)<)txw6n8v;p&x--N~n+NMwI2mn1Qeg@2v&TKx4EHW6n$M!w1) zDS1WX?I-55D+R*MkPcdxxPiKb4S&8wY2fcWMvqPgrYohm_5HV>pgYnx(!Pa51aqu$ z9Ct%`)ef|31(Dt9b_e2tWhTDwL682$q_Xa1V506=->@n0R>TLP)$KOoj1Xi%}yvapJ@>nzD1(1wP;ebQ5=q&ScGbZ&BcI@VhgTAs)T-KiU2VT%Eq9M;hAj!8QR?r9T3hvElzjZ(0o&SoOnGq`(-a(i0x4i-A*V;nqjF zTG=Hik5y*Oz}UFNq465dBM#i20OuB&V{j3heew7KTgBP;`nrs{Jrnj+ve{e#N-uj| zQd!v2TMjF)#y8%*pBiGQ<|&So!&G*}gzJT1CM1l|*m^3tyG?aS*Vf6LjFLV>?Prt; z_oq^Ji{?a&n|ITyE>669y=%m%-cXWkHoxMR;^jL(9r|^2k6(!I8fRd80)HXL^vz^E zWxDfkelZdx^5M?)D)kz{1*~nBgGG>Uv=>xK5Lr1Er*~_AlGnVsWTdDDJx1N;unkg+ zv7z40#rpEtxg@1B#3Ts7IScjZq;ZSMBdmY&0K#qd#xCe-A@Av;iJUH|>-Rz)fTgOv zPW@dso%KB%$L2Vn5!Nviz@}2nWN5OwWf}4e4OSkNz6@#(C--&>F;|+x!nD8`$8YTC zFGrH!Wd+jiFGSm{9o6Zlx1(+LzTmLzVAZi-R2LdBUt7diV0n%5+MPd{9n8Ky%1&<@ zH1Wn|a(4X?%;}ApfV$PG%_{35YB6Df z*I{2;N2IvUvdx_h&};N#u=e4jvRKg_AxW#fQ!|DpQ(EKXP*mAZ^C$Qg_+6P5h>pH* z>n3tY$-M6y3CqIjWR%nE>mj#D7g&PI^VOZaYUVFaU4FYbbe<5ezdSBQ)j+W&x%}gh%KBn zmjW$Wm+_Z4GhUo%QK)@2gKnpeq{j|?#L6}~LQ=-9q>nMV^+t8zd9}5Tq<@B>9;|Y+Z!2v$4!@@qyn!(%xS+or>2G_Rs(Wwkqrz< z3%*)TyzMHWEcSa|U4W~t!oZKVlB!tb7emMO^~-$F zarDXtpcVw96ejYTOy4JtWu|6k=P~$ zqO2`4#UF8%91?Z6U?WZVK`B%>H@_(v)gKB&denpp6tzA_t>`CPtb$Ds?t}{ZrsvdY zk45dyD3rKom^2yf2EXUVQ)yqpn%n)?M+@M9m=arm1r3RGeL>v^T<8zP%S1kN0iCt{ zcd~y&Yf#i^XTdGSx_A8~ENv4`RkKAOHjmcrT@PBQxk^XrG zyq!e{A8%l`z5NTCaU9f_#y?B)olN%G=5?KjrQf@!DNOHj$uV4TOQ5Rek+a^Ts`<;Yy68MXL z)I1Tn7=-7cs}Go-*>&C@w6Z6$*cufdLEGAlN+Q1^Ov`+`Re+}lHP1ZeN-__6RZ}GN zj$!4p^aglZk?340H>twOq2n-I`P#@+>_8GxvC>$k+o%#(VrD<}1@JVDR&BD+s`h{! z)mW~bV@K~S__rC45%ev#5~usr7%xbGA1*+&POXC z1b?Im-zy~Wyk}FZKJkcoj#!tsRE1?I)eCi*^s7lln}@=63yuTU&wW zMDmXp=W@GgdSjhd;C1P?I|Ik!jP|S=H{45wmX{eEec?JhxRem%Tiozr6Slun0i2Fb zIsy_U)HiUT7+&E+KlkD0Lw8NA6*9kwA9OA#@pYy2FBlUOSRyWWSl3N&CFmX9Uov7` ze_XeY3i2Ec-a22vQNr)K_ph0I@7}XSNB$<}Yw;Jl(gAV3f|5wDYO}g-^^I`Ju9=Z7 zi3H@=c%P*%VBcSiyAU&;jWxk}I!~dzNim;a@?;?wOb#4qr*|qLuj^73=|!4Y=9+YL zm0uzRNB1y+BNlVgjG=Fi@|DIJmBI%eb!}>=iT013P^Vu{!loVg=k>CKDuF4byWMTX zS7@_{So}%#Ne}UnA>>cdF3dmTJ~%~Q-?$*%fB4^3&+dL)raMMk=j-g}SG;%p7jn+9 zUYs-jDVz_8TMuFL%M{tuf!fQQ*StI&Zb@#Wy(>WW)F18n7w)J-?2ERg3n{#Qy4J<3 z^lhow-(>ez)Rm8ctF4?!A{V1W$ncbL!mHC5>3J|4Y{%VR zeoeUVGdX(u88U4z-nLLSU@U&|>nOM*q}P`tY;Mf&;~Z4=MuK9hCZ_DHm|z1T@tVYM zM05Z-m@>6yP|0FRU^wnEAk+ETd8iyaKoqQTVE+}C}ZSV*Rt2L z&Lp>;29H(r=xtE3zx>TvO%!T>CAOVy-+&PeK}|A-$WY{kJvb%|71Cr{`Czu&I(jQTWb>3hXfA;~t1((b7BzSrz*FI##SyiYGe^Kaznf{0)37yGXlS*PH6ZKJA76U_dUm8THg zfP@Ng3k=AisKt-pyet(X8Bf+{l(++u;qzp}U0M7EEBx=Bp4$~QZe?^tLTw0?8Sdq* z-cm01I(i;j(Y8?3I!@=X8rzAB2T+Pet>WEis1M_YPWJGISh1BbGrC_>+Hzr&`G|D@ z#JbVPAs2c`CX-Pb{WjCM>DdnZpus;;PMTY+YFvQw>UJ@Rb-8)g9}G>*VJsY>@>j`$bM^UcT1Q}_5~l6B$X3mTOWv@_<80KsX8SeiQ2uKiYDrde%n1Z@ zg3!SQdJ9^Wn$P~e82EvH>I5cT@`Vnn0xmY zHNJ{Xjb}r8^$x{FkJ`6E)Acpu1nk5*a>+Dzr!a4O;#Tn)@YkpZMhp}ps?%|OHcmP7 zQhrdx%>0;iL7f&c;FQPuK`}orLLo?gb>RD`%iJ#M5%3KzT|ev_-#fUe6!I-2Ap6cD zZRl~6c<1UbM@cTTqPE2Eo2)zQjzRP>l0EgiOE^Lul!ofgzY*d>W8I_~KY-7wK5Dua zIL8bTW8JL2R0HsiasVcm>G8ICy`~^o+^SN4r57=lp;;8U)RVfs+NT#`wge*MOG&J8 zWk%k+UZXwfL00HARBdH*K{I%Sf(9g9l1qN6FWbj67qbP+mXom|@jMIzBG2A}3D2ON z75+j!-r?!h{gbfCzpF(4HO;d;l+rHkL}0_HE-JoI0BD&c04@hYNeq%j{ijIOOxP|L zKRW8fAt)u90j2v<0hssbyPU0WquuZ+6YMknRt}MKt_tfKLUxBwFuK%Q)T8sux#$oi z>C+}+Vuub7vx9P2l~y?Cm5^e7@PU-&=ZzV3M4T*1Sj=B(rm?cXajCQza=E`$TvRuh zvl8BY>-(0Un?dN*(yDQCK=j7sQ$ZU`iCX|J55PxwzO3LZI=JLf}229WZy-Mu``&lWtmh|B+;TsQc7egvKA6iAxrip zOB+&A$U5`8Gt%;Yzd!5m`+NPqf4m>&dG2!Vz31L@mvhd&=XnIpbo9ifBxD)s1k1q1 zNGFAmL}1)}80l10kX8|aXr#6)&ead&i8OQdL}L-sAld@C-!;Hf1RWr5ZMg@5w8RC6 zpm0{fXtV_egF{G5l0i&dgMAGHJTM>|k`wKY0AOe}HKb_>E-(aV7=S|u;INLHrTiL- zv_$G#S-JqsG^M_SYhwc3y>Z@{07G|>%-h2o9V~*i(ANURTcAC?vAE!f1FrsP5icAr zPzi|)3k#D#Vf-+`5}06507F7VL^~Mmio*meAq>nAq|3xLAjHEJg$oHr2P+xsYLmk- z?r1-y?>XzBvA7Mq%z`l<-hOC=oFb`iYH9}&NE0;9)g3eqLT=wi7$Y4zz@6N3q&E7k z3CT@|)W(DafaXCOd%I&D5i+Dy2q^{9;~+v!?PqdQ%%75j<_`un|K9!0?=E2zA?x2qN=+z}*|M952lBKJvyMge3ZlNCWO z?t9PJz#NN^{I!xKfXzzkdHdne!ALznR~%XgjRGV#sQ`V^uKtX4 z;a6(xhXP*fu|_M5;V1Qj?_D1-kw?bvIuu3k!GaNzX%f&V+19}>$B%f)WH>Mvv)-HM z@s&TLZ|!mBb>rnjZ;(47M7do$B}6hGZRi%Mz-^1IvHlWA(I;0R+bFt zvIuGXHdl+aSZ>C0bv+-MOF`DYZcc92uT%CcI(?<q6WRATDO1RoK8!_isE}6?{lRF8Jt=Vad#1?H`McgD-7FPxfn3k4LeP`L59r&B zIo2IJ)jPE))j7FC6_|CMi;U^+O>=%I2$uUInDnM3uK#-IP3Cdmn5w225xOg(mWQUe zvviqy1daq_7+qTuI7Gwwu`Qu5d5@avJ%>lHB+egSDrtK6s*o+}k$y_v4X(K_<|Djg?+TA6s5(Lo6iK{5(nA%LW9N9Dmy3DAqn{Yf@boi_&uY5Q9D$t> zh3CsK>H9dh^PH1ns(WU2;1h0Kb4xmcoI?eIYQIm@*#diSj-1@p09 z%y-rfAAEFW`*T;rMrt9ZAuEr-Q#MDr1*Ol_ATIBoRVJt zAV;Mo`}SKxjOUPEL3a1~en(hZE!TjWx%+awMLJV@^Ciw@p<@&WzH*x52hT54N87t^ zXFt@kNN>5L?NjV4i1ox#1;e*$!HJ)5y~`DewXKW0EoM6G7cVchXSOKDeoJDz&v9M9 z6&h1$<_7PeNOAwxHu2w6<62VOJ4J1B*vZ&Vdeq#EHt>W>*ag)+BA+UUM`b?65Orlu z_^yhU9`O-6Z;4!NnR&A}98E#3BQz2IHNLDmyN zk1Tl$c;+GIoTcgKwU4!SiG9MgFcWiY+1pX{r;Q=5lXQnvO>bCO^8m zMh+a=<4}-&AZYp25NneAHP!}7;oH|WoCD9}KZSJkc{CX8-K)IaIXWB_KBLR| z@Y+HLgWFYYrw2dLi3?v^6xTVmV@XHI?7db_%gPxsUFPeHlWmN_>T^fK^A`|P^zRL` znB+VzvILh(VG|rZPKw}6P#&)g4~Ok_l`yjqg8JP*i+4fKo5vOIYslm#tXrgB?j6oWxwN;N zqi0-u(w^}N1U+$jf6AROUQ$*8r~A4iE$Qjrt0x=SM;Bt<-b-=G$J@>*IXrzh*iqmw zKNi(WXO={-tY;Q6mUq9d#QW`u0;=Q^N7e`8i^2rn@!e-{9+p)}3@IO43?CDtwcu2i zoxfRLlRI7F9a`4wlTvt@E!*^sf7;MhA=%<{Tx!_6{Mu>b-Sm{#s~y=2rA#t;lU!#E z_k|SY_FQZYZTxu3kuxRiBZD5obw(~_IhM2MiC?}Bp8YTvUw7@|eO2>Ic79Ly=Ib2( z28;c~-y1Hu;Bl;bNP8zzs?$ELKRx4^iN3|@srnB`>OP%eQ(WS%l#DS}W8$7@;24p$ zSJk*((D(>vTO^3oV_XUzUht>%>^T9~PAQLm+=ZFnHFF^IMrrHurA0pfGfeT4`=`QG z((AaM_U%&g&~q{kj2#trmPZ|SydJsp5~Ay6z17Eh+Uvp!EZJv$j2@?MJ9_?rs!OfD z^Zcs}Mh99>Zk9OFd9bnm&y;!4V9>j<{^41sNFJ#`uX4&*OFy2v z{b2iLr=ml%VR{!-xQ?i^UvSk<+Cl565m3Cx)9XsIsl6j?zL?Z377jUIkAq z;hv@2R=sS`)w~wdJ16ksv^jUUtI~y_ySh)l=3Hj+iWp3~TeDZE_=UTMQ{U^;mdQe;vzonIg6iE@!1#n+VTP_dv0}PeoMRidWzVv{fzYtReksQ zW83yK9g<9l7scPdR`B9eD+h-q{7ll){!q4Z5f$~zLNfKX?a12bC(6g~4fx!Ii66`B zI(9LaMod^MW6=1j=%Mr*@zSqeM-=CtdN5ylNB_Ng_9<+L$+FPIi-H+vJH!yy+&tM;0qcY%9_-#0^K1F|2@S zKn^7_@qm>@YPn+3WC%?yZ5>@*QEgX0Z?|CY-O`f#y*<5fNZkOyCVB^WB5l0`Gy|~S zKm4RbfNw_ydj|quA3^4Ak$T?2Se&+(YcN7a8ptl+-BMDDAh|ov3yYBb&IA8s!bt&t z!uMy!WUiZx>_0#dFteUmQgMbrdh$kT26zJTK@zEnMUl981vyD1DKnB=TpD<^T>}l! zq?(bVG($bfh#};pC4ux5zTuHl06tRvY&RffBqfn{-&2wDu*9MLZ9oz-j24+Y7nhTg zA{T&=l9p5?4JGe<5W5B-D~Y$T&D6K&K*0 ztv~5O4%x);9}M0f_-Y&KkcuS@cK;$N_NF7^%9B5GxX&He9 zJ)9)UgWgO+fZXaoiH?vW%hX6)Fa}7`zcwH_!6tsD!S3i_FnNey_xf~hnH{$>0;`2{P z_E%W`^O-|&pVTiCx|IAc6T1998RU-%T~_j!nL}DmUh$vJ9Q)C(q%{s9EB$?Lm))5E zH|KVFMKFl~^^G(bAP7**Z*#lcpO!STqUSf-eOCtkARk#Jw9$?T87VpB=HenP2Q)iC zn`Rm4ib8{WhI*sWK>3E$^2TA!(81am|3FLtX{3PaZ0K@yw5`5ta!884;6MyXw}bF- z^~3(u?MTZiD3Zvu$tn>0iDS@KBRxYs2nK^e2H+1Ojx$2K;ocq)WMTsCg&=4PL<3`m z;J^g~e-MlZq9VH?$PLE(!|ekT`3^$?V5A^$hjxNrFie{4W(V%GC%hrb?`dxWia~;tu2a6?Y2QW*#tpiXVB?_iSXhiRs1@wBJXF zfsD0_wh06yeu9|DKFIwDfQJ!>pyLq3mMvRow=mGsGO*Co(X((cGcYi7Y-3~NU}M|H z!a%;hKQ=snyu%pj=^2?Aw=ywpWoKeyVkh00*f)}}{5u&CA3-czpkU}49L5h(u)yFf zFyaWPBptC4rVg;A0<q_XzYG7f3xgK&)WqXkI?vwx5}G( z-z_TW+j@qbNXxBg?tA}@1)`t;*iw>lqM@deBcrfOij@*z5X8?$B^{f>PQswxqH|V8 zz->JEXsWg)2MQ}YCrC{~fJR8}aTh@12A8|8wLA_z@dJf_jDhe^6o`Wm1DsqY3#1M$ zSfv^Y?h$NDF5Ge8pyA{)r#qvAuWyay_79H6GYbQH`nl!BHy5J`6?rQ>lk>&Z^&i$v z%GBP^J7p&EruTAIKX&SzvYC#q%UP&+8QN}>pq{m`&fF!C8zg9X%fsDcBC#Y$tiB@1 z_xAmxI?-G-GK24`@&}D93?soy+Xj6?QNGbc=tbSkeBX*`FIMuNzfoA1-BPq;-e{(?>ZJg*L`e4HMTbW`&BKEQ z8Fqt1A9HuqUR?jSUfkQfZp+*Az*TS$D9Du90cvZtQf|^;qxK;W;m`r6WrbnW+lFu> z6~RVW(UsCmk2IzS#4t6j{yO)in=1#VlPy{@Bg0hN=SySyrtOJP$hz3!b1`?`+$+Dh z;B;#U?Rveb@?`1D3cfz^;b_~K%jJYL{M4SJ_V;*$;`I}Gi_@k=s63wtJr!KsnM;H& zZhCWWeUz)N_APuNzb}aqsZtrsd-~Igkxx9^mx0WbQz`gC-h)pL zjP?xP40D)LT$X5j+LE7t(bb=%U}7u?Tslu-^tV*NIR%+{eb7rC_1^QYUMx(FFv!R z*?<1_e8J$#y85d2BJ$ByZw&!8GZ$fpEZGO|oyw5@6R1a#{Jd~ZD?|eSsd2{OC`IXlB8q?mr3q3EAUm~aO z*WSSvx4-&0zAUh>L8FW3^T^^l^R=`ArFMdyEfKo=ng|&S-FlI&Z+?eYXwls^+U6mP z%Pj}r5OE@8=<)GYwGj?go9`*l3Qux_G#rCcCa6A=G^ z>au8{J#Z!1eioubPMfafvT$-lNr}tgnqOj=E&`s z&uM-l(hv5eXz}18-lBXJzrP8ux_%^C0O!%=Cakux#YX&+_rO792X5g~Ig z!srtsRJmNYN|Qo_ax5%H@2^x4EJuhC21SIXaCP1bn6=yogjdZ(sA~#@P7tBtsL}Of zPl10=%>SCiVpnhW98kSBpICdWt^u{gw-geV^JvO0(ETun?|OWGglgp0*G_8f8EZpz zA9w11%39*U=A4|eLp@HYo90Q)@QK%7D~lsSEa!-j^~vIVZoV(QTx)u!>o)vGm>e*- z5WD_Wzi=#-oICu=;8|@o{anyu;?Cav_Lr5zQdXZge>?-477Hlyu^0d5LYV7>`@+Ml z`<(}$T&i4+)|2a$_h`k?)Z4G8bk%+0RA0Z}zLsF*xY%q!gsS?9(BcR6FNQJwQ+(f) z`3NJP1ViQ!k>>*unVL@v)IW|y9#o*Nz2wWj7FAD{VK*OqMOwrpt8&h&U* zfOP_$jgTnvpvU7m5we@FdvqtOM9FsjG3Zz2mx)k{mFSZvO)KqY&9|yODF){Id)ue- z)*rE2-p@ye#9TOmxsjHkr+PD+kXe53%%GvK%e_y&<@;I>mzPS_&FOZl&lU-9 zURX$+CPD*6U>Ho`dHwpnpoxK5e&Tx8+HMRXCflb#g(>qwdaH90;l|n4 zjC&6BcCFD#oGTH`DEQpf^}@*Lj2ZkrLFGglULwSPP@4$RP2hXpzuHazyxDPU;oV(p6c@zG;L2Bw=pP>-j$G z^TT&aK0hxhSE_z;{Tk0syARCM-KbC48lh;p5P|bxBnhe$yEk|RFqs;GCEEfl-{c4} zYl#z}@68jTHBnPSq}#)Lgy*j^4{kg2fw|e8?%ti!nX!v^smo3;>=_AYnlU`^I2R13 z)1TLnn04(7TrQT7#D@-g#%qMadAK900QB&>1J6h62rS$qN^7kaFMA{^cz2yO=G9TE zNN$bvT3b|}%E{HsdS}0GzRdnoF1wI%I}H9Nlf1%{@UkTK{576?4n=#huUu*(oWoe% z?mOFZP(vcx59_T0ZS`IS}e7mDwc|RPglP1^KaW zWpVYjh5L{p<@d@RlagQhl=cjTTo`c_B|@~ecRF#Yo$-6oG~Aaym&DtItp8|4x!0{*~;fCEvjfM(!!X8)JZOlLQb28FqmT zWdI>PJV1;exC4osoMakaGvaQwoHC@4_U|AJ;Eo+W)enk8nuuwpVA8Do_sb8qw!0{({>>tJp z3P&oMJR6ZZnI9&=b2A@OXZ+Q#g~RxN_mk1E0J|j{ellv*Sg_54#@hJpCv|DqZ{<*t z<3KQJuAm`%40V3Vo5nL36B77a5H%*)+tV8;wa7CfgRUhhcT;j0$b-=}1c%W_2cUz2 zTFV^-KqO7@cVM~=U{VMv#?apr0UrOa>kkhJ_WM2we zCo`^CasXe`#Enjr_Ire?)*J&;g)+1P@vqCJ-Fh!=iufICOrX zBmF6q!3~209qLcv^nk=(e*`CwDiKma5Ciy8sLzt!8!Ht_m$=b|w~^sU5D@(wxRKiU z8u$eR=NJU_JObf8&^Dln`&(1@x2EoIP2Jy`Iv{fG`CC)>x2Ep@r<(6?P2Hw~?{7`r z-i!$O9njQ~x&K{&--jTQE`+>?%?xP*0UHCk0YRIj>GC4$#xOwdMREaE z0>tqzAP|r?WC_VZ65oY%aw!{fJq<(&3IYG%lmydv%clUWge&O;lLQLmj|>MVsiY(% zk&uddI5@iD3(oks0c)uMRsPQp>i7}f?yCH@awd`{f!b&4XUP_Y1%(g{$(Db5{axQZSMqK?cG3s`8VM8X)XU%n;g`U|=dG zAt{cMl$S!t%SuSeO74^0Ck76xNJ%24q>+*e;!={NGZT_hi0>CaD2`So*xf_PLPzg= zX~3t-|BFRem<-9B3n{g4-#(!v z6@pXc2k36p!$0sx&VSirn}F`9A8>&{z$TaPjzXe0PKIGY>q?Q@U^7z_lON!JnXSM7 z4`?h-Hxyv>&&Y-)A1~Xq_0kOmCv0|a78ba9Eak7W_z_K}KPge5(s%neE1(J7q}ETx z@^6P*et|~=?!D{ogi@2n$lBDDY=%z8;zXuFX?s`Q0OHg-|k_RT( z-xV~HH_22D=@W?dBo}95qGT9=#kmHc(1tpy{Ge_U-rnv?a?-jwS_+Etiqg6Yy3$gh zo5*P?$|~q8YHCSKYU)UBrq#iqLP+QOHq*NQ2WdAnK(2oOT^>KEqD0nSn1GX(s{Ati zh@atx+S=c34ORI`R)`2-mnbi_PhMVJT0&~0f77af3WFvv09KEf;0V&V0T+4bSfYcz zdpG=k-UxCxQvz0wU?iyWqev!@Xm|ea!QTH>D{f>N=7k0s{*!*O0fxnR;KG3EqNXQk z@qg9rkeii3lE&*+%>T>h--Y}~t^0R# z{oP#uQ49P>z<>9yznkknYJvX<`0w8Jzo)r=$~M5(OjS5cSY3@c!C(hCDHk&fQ$54| zx@1v|!C=340EPl=PWppAd=hJAXYYWZc>y*jX~8}z*oJgPVFOJp^+?AUAkym~Ncu$d1t1Mo8L!1xQej{~<~7%q?$PTEsqck?B= zDM%Zl?7;v*;NC`Zdv3VJ$S@mj4U*g4KLBh$Qjl;CboX~Bxf_A|WM~L!TN1t>xZ^{; z(P6;d4cr2LA^zULP1?z3_eZ;etx`(Tew6?Yjq(C+N#JG(wz2@H0Vq|#VS5J8U)*lL zxN%^A5Wqs(n7|0~ju}D(wFd!MZbgIvI?NA^!-<;#fzvhE9Y}-zfvy1&5VTQeQYwh` zPrNNTc;og@BY%PWXHF7rH{!pVlW7LyZ2cMbGv&`P%yqDv4o(fg&;AT^y9_}UaS*g^ z@MoC7HE|RY zuSNkwjgVjjmSn1d5dUK*{;w1Mg4Qp1h*_XL(BQo!peP&A%Sgs5Ki<@W@DBJ*dif=X z|1#MxIgp$i{TevfatIK+iv+Z_ogIRIY=tP<=pne%RS*OFLAU+1HbDIXLAHGFH~Kwr zgLv}&w;M$=@KRvC$(#0&wuKb}6%rh}0YXW7P=ON^%n&=o4J=A_Ln7qEO$v}Qqygzd zMvy6F1++iT5DF-G{K3v|7!(D?Lh(={bQZb*r9)Xz4wMHKK_yTH^bo3tnxGb_1L}c> zpfTtz^Z}ZM7NJ#O|3Cv{gt5W6VSF$_m?%sdrU+Am>B9EIEMWGqLoiQR04xL+1v>^y zgr&mLVcD=e*gaSktRD6Z)(IPcjl-s3UtlW~a0&(rc8VPoLKH{}MG8#{V+t#ZgA|?= zK@^86j#HeWxI}TCqJW~DqMo9KqK9IP;seD3Fi@d~bHaDQ#o>x@ZMZ4i0qy}0hR47Y z;1}W7;YILjcr*MZd<;GVU#6s{WTQk-ic>068cUgET?Rwd`US@ zIZH{PVx-zmB}%14Wk_X5K0WQ)f1{7s<%{&)YR0R)WXyX)CSb{)IQXa z)TgO4sf(!}QFl_mre2_-q2Z6tnKp;Enzo(xE$u2D3!N~XDxDRb z4_z$XCAuQICv?MfU+L-T`RVu3o6~#KAECcQf0zC#{W$$H11rN`25kl>h7g7`47m)C z7zP-=GBPp>F={Y6Fya``Fy=8fFur13Vq#;GU@~NKXTmdOFqJcPF@0jDWfo-CWOimg z%zTl#l)0UGW-IMhp{?3mUAM+;&DdJCwQuVJ3mc0Riz$mg%W0N;mS-%JtTe1bth%i3 ztjAezur{#1W`ncsX47Uvu^nT}VSB>%mYteinB9=whdq(Kko^VwEC(xxEQbw8I7bFY z4aXQKoKuL?kkgMdnX`nmmve<{2bU%nn(Gu-5my)2w{5)JG`69)C2T9+*0XJe8^Nv1 z?aQ6QUBNxVL&>w3$DAjO=PJ(=o*7(W2V|(lNg&jM0 z=j+vdDJ2iIt>^#4-cIOly8=o4VH{W@_I=*QH2SO9!hq#1jM9l8mzRO@& z$gb>NFLtf+3-ep^ALTFRAK6W}TXDC??(@4J@17Ol6EG2o61XEUC`c=)DCi}aCfF?a zO-NYCR_KIKh0vt%Heo~I!@_rjhea4g)J1|su8VZfRH|C)i}YS;lyru4w+y3&O7coLr4psj%Hqnt%K6HZ zD#9vgl^m7Vs{E?1s@bYzY6!JMYS+}p)OV@7s$W;1(Acfvu5nA_z2+WGAI$>IPg;^% z!CGZn-?WvqqqQIDz;*O>5_DeZvg%svrt7}aRbTOpHvf8!W1$!G(BfJVkT@B zWcI+E+T6@M!~C6vltq+9vn89Qi)Fs$qLr3avel5ah;@kdV;g20C!0K*Z?-zNskUQw zNV{me7JD9hZ~ICI8V4JPTMi43x{end-#W=T#XI#L6h0V!@R>7@v!8Q~3$u%>OX(r1 zL$-(V53RYHx?Xo(a5Hqf;x>!YMx~)XxNEqdcb`J5qEpfDJybnXJtjR>JYM9J^t1IV_TS=v$iFIpHNZEZ5wjB$j_C{(4U7*Q3sMTY z5HuTX9DEB4!yd#|;@AN*)fyra5*IQasur3Nx)f#;RvOL{9uVFdu{YvW#QVc~hi^tw zMxr7gN9~G=jT(>EjLwdM#kj>h#_z@-$G<(If8=&7U94|x+fm7*sYmCJ*&eGtzT^0j z=BCtp2FeKz21Z;E=#?NpZ3!>O;&nVc&>k2s%je*S{Xg=ZIKFJ`6DrG=!8UD|)C z^0L6?vzOP>z0!L!v@(jXY`=2q%C}7S%&w~%SBtWCWF=;;T=TxxpRJ!=eqHGL#T(Q& zLT|jwvB_z^sdzK*7SFB3TkE+2xns92Za3yBva`yl>T$Jl zb=d=n2e}V-J&GsShZ^h}x*N?KUpz5>^0Y~> zsi9f3x$ddz(}&NLo>e_pd|uHa-%{Qx*IL#l*H-pI{zZAaLVIP$zK-fnmCo8O^{)Dt zIxm~L4ZB-<4)k>PTKD$%IrWY8yZ28H_zlbrh7PU{9T}z?P8iuba`DynSJy}Pj24f{ zkJXIpjJHl$P7J+9z5eh9`)2L!@pp{xF23h`pEoHz`EW{as$<%5`t66n534irA6Y(L z`6Tk`{%4KPt+RHsZ|8#Nh+j^B<^GyGFFXHu!EE8xqW|LRw}d6`rQ6Gj%grmcEALms z)@ar)t?yZ{CKwZjiT>bh=MdPAp`?JrfvF+5QG$z#mYND&^jo%2(=yV71%jS|0T@TJ zFfp?M<4V?TtZW>dTwGjCEZn@@oILEDT%4p#V5F2(RCLtTbezl#%$)!6MI_r%j>D9H zv7>B+_yAAyyOAU?p!{JZNo<75wn7vzGWJwdlz^XsMT2;Vl7)(Omy{+oo4G3ue-Jw` zRLtJ8TkBpu2e4EWkZ}t>N=wJdwT+ucP)Jy0&t6$Mc?HFNO5nvDdin;2MwV9AHnxD# zLVS-+Qq{;c`}Zn#^uMavkBa@Q*KY=!t1Ag2*C_tSe|u6te;M)^>0b`RwbwxIlQAN* zy=4VHJO`2|c8HqQbvfzZ9&~VSmhJV!#$9GV$E~O$d8fMR2I}U(da?P#qrJ@1imjyv z9AV1GHP1EKU$%-Yi)xrqkH@p&3i)63w&?jD+#7B2oO<@%<=5g`;Wsf#h5}~~Mu>`E zxI5h769CLzG6MFc#85|Js{M^dotKUbWr>W9~D!t&vSMs;r8n4_V08iFFW@-B(C5mqDbRzcluy3E4Z=Zuu=1r&R z&|2Yc%F_EhiO+%*{Rd9B_?I0m9u7nEje3TE7#nSDsj=Z>T*5r5=m8-f+<#pq? z#AtSw`t8z=jQNIwXP@%nZ5Ebq!za^4pR0TDK}!{ncn*$aosw(GG*TW?-UC(l6d`jG zKALyEW|WcdRy+Yapn9ig61tus@-Ke{pILkz)KARYFC;};mvr49vK|SFhz`8lu=Oc- z#P&Gn1N-D|IANOA>3y7KmwZFUM})r4gxPYHTO=l}?ib~FBcr@$Z$qHn5VwVb+Yvd$ zT=H?xF87{8a|aT|Pj7u9+ZQw~wGDN~Wg*}NFU)1hG^Tr$BYdd7cAMdwIb`B}ac=Rb z;`{P9^0fW_+LM9|9?`%nq8)=jU}%y~XRi&JaZu}gAo3VM}uXJR>T6zY^rU9|8yd#X64 z_H_fdf7hNFtL=Td&Vu<-`{tUmZ~G2fH)V|1%@83j-;0OK?-WMY>OU+`;6r5SoP4D6 z_^RI1o3CQ6zs)enSCn_ablJ^*`FQ6piytcbIck&wZg@-1$qMRS}h=ugu zuL*d!qF16IooG|`)vzl!A?%BF`-QZa%g;+g#8*Lg8Bgk#NJn5PF{zcFUttHPQU9?aIN8_Tj_V&T;ZpKRrNmu>$8Vo;s5JnT$@@1{RC_MpM zR%jp~mMX@Rw}$&Zj@f>%yRZ-w5F&a<*|Q^)&n|w?{P9sNN9#*NH0yfNJl9vY&>m%N z=}$>=S%bc|T?KLvJ~D;$f!h0?600j^2<(5<%Vj7QDAg~KX}SVz@E&~KDd}-eykdGv z-2c^za???nAO`>K!RL89w`HRlyD7|RcPu6w-P70!_rJLo=#EGom~VM<^Xu%er%~I|o)nKgL(JVzRx9+(A03J={MgG^?x-KO zcc|?ib`a8lwb4ZAi8-)9OK!|s+1*#SWHx}Gvz}x(qseTZ zqi?iP>P_>WNInr(EqJRiddF$oy1|PTd(Ty>*}3bD9JS?c=9s+jo(S>P^(-k6n#Glg zke1Ip9VAjLxI~2JPA}`UOry%jUz+e6eV_0JneRZl~wPRr;;RxZfR7b@*p%VVX z`y6N5_$nWr?<>I`IbX+&rv>wA_mfiTLt_O~2B*UOCFXlchaBJ|}&@{*l1m?EyTy#|D2>cB61lBgO;;9WYV`aYpxo-y*#RiW9M z-kcI%>K^pn3ljT%t9ndscE2@njyZIr>p{X-P=nDgPPN;KP@f5Soq(Zl$L~u_vHH?8 zA|%K)uD*UIjBmxY=R=2RJ3$)%Om_)@qcWQbmqHFh^K>HDkC1*UMCkRml{#u*@cK3v zKWX9|>wIw4%B!~)G20h6?>i-ds(3gTnzcO%voArHvQCe~k-+_--esP1PJzJ4OoZ4p zb|jy!mA-%QYUxBY#^m0Ko&G(q zDtDcd)=GNO02he00h5I%5h(ApO6v>5Qw`q0QgwQQw}nt{y$|blSQA;oGbgyu@q`Dk z+-_4I=H~G>Dky%3aX($&IP7u0yocLU;Ol`|m~L zkGuwXyiz*D9ZjtoEz)n^^zHGVrGNA?J6x`q)gb#a?Lo)gfr55{HJaP<@Z(n>au6X+ z3>$u|1B@71*as`yR3g-%8ZJsW`bvlh)n@~9U@syRe|Xk*o$8?p5jv(#gc>_&3eBC3 zi4eoWSn&#dcm@%oK0$;|-S}hE?kv-dK(5L39j%)bpTMl~@DYTPmpqH9@Ewkgqf4^t zYbMa)9*#G4v+d4wMCe+@sk&J&{8GC5{|daoRCP-I&D29++w6upiJz~~DRB86d5>`I z@lT0k>VxMRj_FtTNT}ae;VoLO3wZFge5R&zt|B(M)(bx5bv*$R0l&ZK`JiL(#y<;Q z!V;l_a_Z}X#Tvh}#t%W~7G68=ava#>?;FNXov$MK7?0QhTz`jR*i znh}BDT3Wc~Q!BWHj=1Sn-uq2q)Tg8>p8nLs+i$-}jAx#$Wg2ub{8X3r+uuxszHQ0mdCT!z{>>|+3|l2_};ny82mTf2kZ9)0U~tn)+}cI zRP8SChK&){d-!p_^=tUasM&S`J${w0Wj5|aBRw;zr#Cw+rsYRmW$KG*UgX7#K7aBl zxi0Lv%$1u^WC**t1{L`2#Lw{(jMEyjR;Kd6>pa9kHw3c=W?9083IE|%E_mZd*(5t; zuKV-%Cw^jKlH)xQ;#PlieNC7M-FpGnoBc{P5LlRg6tTMQ0+zMlmv!?(U|8&3zf;y? z%D80PpfoZc#_HI=RAG8iH%`+Hh8;elR-m<#4y3gBi?a&r6bo6a%YgHECJUSCwml8z zJL7O(LhRx8^|cc43KlT^+n6Dhh|p*Yl3;j)z~lI6be_H!|M@Lofdo2e zN^Q83Rm^k4^|h02dKw>h8Lt`(g`ZbA-^a!B=*;r&Ejz7;Bbj{L>i&Skp*4f0q1n-< zT6nLDaK3l-ii0m_u){L}nf{!60o$0l6=;}p-&wA|y~Z?GD>a$Mfati-yw$fa)#cSt zgLkebZK{{Q&{n5|d8t;WyU@xo@v8P=o5FTzY2xLR!NLh|2cZ(#+hNgZj_HbVXRg_3 z^Pb#t_G#er;c5}r=NFxLmOtyyWi^=49fUoU%MTyYKgecu%&3y{<<$Pcn-49xtqy!K zXx;X-OGY-5`(g9qQ0Z*qM0@N**!7|$|NQU<>zCsG<0V})pL4p7ANIemQ4rMp)*$X~ z4#gKvkHLo>H28?Q&kdY|jd!12TZ)?>iV%|dVD9+1H${`#0>L_MHJS9Ft+^UWMcB=ZeyB za_8>YnKCHx8lsiOpG%6px!l+CFcZ2|+xacV?;f<`GS1vs!#lx|-j>@x%@dXC%@cZ$ zf$Mqf+tQj7ZSmIqtx{F!(_b4JNA8*ixkwY*2>WIaq|6B)n0;fLo+^;elrfHByxBGM zG^P#3a3Z>)VYi$2P8&X)@Uv}vGJP+tHim_>>1)%|VS}bm5#=JKzJ@d{n z(Z-yw?Wh$4+m{oG0G}f+kAfE8$=R}(i-?y8MD^8 zsSYnhFn{C%=oybEugA9&P9Lo~yumGo)z^KAxC&l+aaV~5O>)Z3Sii0XWBpv~oXdJ_ z9~kuairub}&}_{5f_nvG?kO~?uQ*<}y=I%WbdGQ!qrPrYXbCVo#yF$jn9vD@wKU`j z^@W#~VE%NNCsqGn@VN?0%VC(D4|U8cy0@Rb@lF>`cw5;maoNx@JjN z_JXDTc?)43Fx8EH*TCGY@Vb4+l4Y|)^Kl%0%kO)z&Xkdnt}6 zr!N})K{)(HDq-HW4rHh|c~MfJ83%|^=ULlg+p~mD{1>a*ZGhT-pk<$m_T46Fj^NEv zfEy9MJW;m_FDAsIoS!%=kBu&?v;)4ge+Pb^o@a3{Bzj`$)Holj&sF)(DEo1BmZ`%B za&xA>4F>TPB?)Cy-W@UY-o2JG{OI|3!Rz{AJ?_d${UEX^xv1VmgjPhHA<)5Dzk&CY zb>mTM7$Ba+jWMt7LgJVGzc3Z^99U%d{qkQ&w4Upu@zDsibLfO1Vw%p?st}ID6Qr|_7U@N6p+{i&doscVh2R~g@~(ZtHyjh10T{{7}FZkg1lq+yJR0&M#nfC zS0amEm#!Kn@Ha> zGm1c+yhO9j_I>IB_{fRKvHy*@GVSetv%YV{mCnSe{2#EdoKO z4XoB)Pz8rpkJdB#dfW*F+u_NqKD(_s!%CKUuJl!7FKP6*?r`Q7&q?-D4o*cWXQ&oG zNv4?0Vo?#Q<(=CeYgCa|JgGqCj9xVyB2EP zcHQVtQhP;@lg4!O z)S1Fo&GF0|6*hYoQ_4ECyzn(u)qT73V_tCb;E&7sGQyo|>b#@WBXYe5Z3^EMCT9hC zQ!(mw4H!GX6e@o5#&*p^xUvYTiz+Zj^fc&{D%&%V;BYhg{ zUw_-``zNiym#6+GKT;*N@%nj7@L@6(Zu2WuQop@9`q%f&|Krb80sA(&U*BXLekI9v zC}2o$E9o;;mnzO`Jbd@%1>)(kw~8T-xk)!T#Zw>K8Hy%u5v+20o>up{RVW;uGE|D>ymx?1Yiv8>}_?3&xO zIobK!Tpy~a(T!asL@TMSygOL1ey-z=tHsK_iZ8n{@maxdg&c}DujxEPs!ooGU;49mK{E-0({g4PHPAL&kbA?1EAho-mxlMP%v zO6!4K_1*fASqi{B4xK`-jk~j(Q9&-sJQ*O zcd;=w$-3X3re^17DytTa_ND!5l+8`+^MrC@Re0h7D#A!w$8{`qUqEJRk$cN3T#15F z+-1z-PKouma-jp=7C;xO?%c)xe4FcD%V2qwD$MShh zUwwq+h{~4BnwHbmy3{{78?51)njkj4EY0JP9?yTF=H?9h*MaV+wgd_rkxV5))2DUO zjI)WogG#q^MJ`a6`dw3WuR6JM;vC2Mc$jN1Lw2^%$^F)>h4iWozA*eH@!Q3>cemiIWZ zRbfnV$l*^QWM#OfB&tjmzjeOG+oxJC{3_33T)|VJw!Lz%>(;*AC6)Vx3j?Rb0kjNR+}!6j+mn*vi=hei%cDi>dbxaqko2dDLeK1eb6$D zOz97}JYSYMz`B3ut;MT`ERq2V4|a~s8$PJ_e<7j%;KZWrWflET+4ti(x^HD;pYipa zw~R|hIa25CI`r6;;c{ZO?^HO8-EC(*;gs9QRdGxg%fl=03+if3RAg+;o6*t^s6nYW zpD_5CudEfDl2>FbDfjWNrjpid5&j8>80>KnSFgJM?n_hqo+X5h#rJLVnlU?ik`nja z(E;*cJnwW+*R7)RblbB~;~?+wR!xb?2rBxw4~mS>U=tkn-j;5EZ`bR<>16FrZCmUm z`%Igq`pjp#juPHn#j5w+@cGm0`}p$3%nd9JFv^L{-RU}LQCx(nPnmRNo~**ikX9XIIK7_ z+jBJ9t~%vpONuq2u~RYRO#l1+EZDia zvy+1%%kbRQjCz}H8Mk(SO}1B!n7oH!5mcqAIs3~V*cb~?GT3HTjh{^esP$lZXMLvY}=RU$s9h+y!chwo;wA_O92 z0^UQ20*7`<_SqQ71H2%u2tt527XBaBz5=X{Wmz`_2o6bbhv4ok9D)-xcyM=jcM0wi z++Bk^!QEYg1$TFN3$n9s&bfOZdGCE|zM7hv?wabF_F3J(IZ&np05?WdkU@+hc&wmpF*q-UwY6H@(`m;Uzg~v%FZEm6qgw(*Je+KRNqpf|qi%0(xMMG2>xPv|3GoZ(BcO`)T@E6r} z#H0U*hy9KYDhNdTG&8r+rIC0d0%kh@bMdr&n3lN%jSO)AK_H5NCJ=AqC;t@Z7cXLF z0^DFt#y}GY0Q4O2y%|u0=F>{mKd!BSNT0x^t3R(4%&m-pn~@pQ{91cU^CYo0(ABkh zGTR1-$f9ip+^PT1Yd#?0kIiq_{Dx0BroRb*d%6LkCZFRzhyD2+U@(0vO;aF}fj$r! z^dD0HyH0s$AE78dZ!h~rrUi<^mw zArMN!N>^Lg5V)J1HL#Qc9ruK5^p_8P^2l>4fX@Bh$baqQ|G>G=epJQ#9|)Z1#Q)~7 z|1^DgKT|;WcPaS23kr1GzkUyYr{wqQ@82nT!V&o^Uq0u<-xByQEn)mSCBN4o|IQMo zzfAfq_?PZw`8y?l=64{% z?{A*@%TmkwcS?Ro0sD7K=>D$gJy$>fsb~LC@)HjE_gdq*R(;k2giQXgE42S9ozJ!4 ze`?JindN_5^IVDkr&^u>k%8stFSPtk_WjG3^has@3oZXm&i$h}{)LwRChPuD9{)ni zf0K9rC`Esv<YvYyfTv1} z5!ikJ@%VtyXiqK!0#gGi{d1@4*ZJx0&mRL&I|B;<*jPV>Vq^qn@87cG@5Sra&MA0| z&zbude$roHVbd`(JR$!5M8*boH)t6F0OqHnV*MvL_MR(@gK}rp!GKAVuBm7>QHz#w z|JU`J9|}n`mL}KtVyiRqW!g!K)w;?7xPgT8B6y7A_+S9v%IKFXvs!84^YZY~hy&>) zXdh&n-`-f(C8Z>_WhZ?Po5!&trHW?8KUQUM?zen-HWJ(1T!_A#%4DoJRrJYtaBnsg zn;`ggAb5DXSN+gNS59UzYQ!EbZ4^Ay)Fhzse9u|UC+GIf>O*0JSW)tWaup|ca)q!_nh+wXjipk9w~vm9K^!eBYS>BI0nRzQ$|@Qu{= z<%2Bd0&`8ly$A`u{odk+%Ud^$pXFfJfqjHep~JWczjjWb?d)gHUVeTHS?pQ=u>Ud4 zd24|t*yCdCqsEq#oV64JFQ=;wM{UD{^Ue!iLJ)lATZu6DjH~R`D98{MxcwIF zL@b+B$1QzH{0XqN!M0lG8k!urS@5+(4?E2^&Vy}-JtxIO(jyyvmnhHW&LBveRO+;S zu9oha!;PUOd|9xYD45T4p@cY#wvfivLJEyxZ{-6$45f7hGY`_GMQ{B2B{vzTn)o^LLL*hmkFm_b%<<44x4 zQc93|bvVBI3oXZuq(K5?7IX++8lXQLu4_*b=rBTc++ja3eA*n9=)3 z+u92vS7M@^9ZUo+C&Lq`r7^X`vUA*GvTVsIW(o@W-5VF;m;m5H2SxxB^ThPzlq`E8 z`Lse21&wk;j!jj2N@|>Lzi>^?7sOTA8-rx|OnEY7D|8{+zQP*jGZ=hjcVWE>W~TM= z`bjw0OK3rN;TQ7l>#n@K+`Ggo-^Zai{Y$sDk(}A$oVA*yJjqW^eVhtkJCzTSC$%aA z>_P9d*^I+pv-NMm1;@@R3P2zSfeS*OLuK0XLSDk0r~7S>&fYw*g#$__CzOmi6Ye+| zOGjVkgOf+=o)4}SeHeg@lvC%D4F4dM3ulRbevmG8yK!(+uM?E*e=J26g)BYc7cCaM zoXwU=1AXd9qK}X|lIi)dkcYn;e!FwfC zg$V0P?-h-^Prz6RhewosXD{E7nseS>tYg)5eAL-m5{k|eRbfV~^fv^n_w*~{3i91K z=|q%Zd=WG9Fu16t$^+Wl9Wfp;kNEDsa$Tpkb1Q@Dww9f08W^%i@^Q?j{V@$kHN0(2+EQ$pJiT zQL|K1mEhhBSkIf*`Po4~;dWljD*Op<(hz9Yo!vY&-g^`G-Nl7_LUJ`H?Ph*q zw<5HdG@JsV9$6TP^2uR41UUbJ`(D1+sqMV>Ux|L~ft;QzHgIxIh|0T?-onKXwdv_( zYM3gV!Q1ChDCp(+m_-hpOPPc48N4W)lI8KnS?Da7$Yet11xN_4n9&AJcuU9idP2v2 zoaawuVXLern;p}BGma}o_GwHc<&AW4cs4}WSBX`Q)Vze5MDl2=3FjSoQim^6by;bI z`)lWf6DVUHw7dd~vq)yE^ctHl!#vQsGStLg^X92;RXY`N%74b!cLu0pRxzEL8|PNp zo=%x{r!EZGH;$VpBRkNWnK(F$%1@XJ^6zOF2kIp$_i^Ks?b-BQ&+jwWW&Nrg4W{O1RU-yu zcelRBHO5IGdn;KQD~P+{U~w>=%DWhxHX`EgEX>_!;oz@GDO_55iI}>J54*5c+H#ZO z{m@b2t&0|+cv&nZf-Uv2{GnHp?akbI3OuvKUmSj zh>xV&NM}%o=A1M?-)zjKjLtsb)K`Q<-9f6e_!P&G@)yON#*=37Vie{QXH`u}xgoDB z1h{~&Q{a=AL3uOn3KeTAf7%sVOj(1})-JN$=MeN8bNRth;AU;sdslHyblT!>8+X0* zFlokhS}=VVrEoy^xLfGB@p!(2aT+E`@v7%dOA{|ixkpz+vy3Q8f~!2^oaPymiKw+bM;^-r zS7}2{#S)0o%)Vsg=F&WTH*=SEeRT(KZQ#~*mwXMnVLp7BfSWL{>tnpC zh1`DPg8fo++y&LX%-(jg?p@%wQdjL!ipmI?+~=D4X?j|(gS_#}ZNj#>8zKD_8!vTyWUK1mA{#`SPSpBHtAuSVOh2UTr?!zU+r`imweY&P97{N zOk0cXqK?~Dj4Q0LtSDTY(VNy2@OG406Py;LZf{I4pPaNSnw%V)`C-I0^~300-9}f} zD+SOYrrcb^fvHL`2Cu@`K8M=Gl-(pp5!WR{3ky?-ec7Q?;RQ_q9|T`|HZnGVIUE_h zZ@96s`6Wje;1WyHi)x}X^p$+eil{m-6IpS3^w7b`JsD?l`aKT|SveTkhcAHigcMWH zg|M7fWE(u5eh*pC(q$_KKZM9Wm4Kl^xSF+mQ_p2t2ly!jG%ai@gswWMv&fQ01+Jmw zS_g`z<=$%;{f8_}V}gat+)>axQ1FMWW9djq0xCcl5-G|-!Dj4`nhPWs$&Wi|_;H!o zmss8`dLm6{>LUcP#~GhW?F~zVNNO>%G_2qbi+RF%ia8h<(%+SYtW8*!TU4dN3`s^`bza*Z`&yA=9$# z+vdokhJVzSF50$N1VN9#p2m-mEy#LoY(8#&R|80=SEEb@CQL8lv9p^=!H!W7M_)z?Zbpb^8OrdO3UE05Xw7DX{D zB7r1k?ZaM&5fc#MJunMg_+YbFK)i_^gLRDuX_p-l#d$x6SFiS5$_j&yCD#Xo>ds4-+y0) zJV!y3PX%MQ@R*7~NhffQ@X(!%*&@Y!+7ahwv2)`-*N}qcx_r5`@UEcp{98?P{qC3c z#G%K$n-S47c34T8WSJh#3+RcRfiYyH4t6XIXI|bhEhkOcXuUVtab{D*9lKaizIMK> z#uc;3Ymp67$XW4M^n8}cc8ylmJyJ!v8l=jHq}0qvs7QJ~-n|-~976eGCQOtJpRjTw z9aMtxuSgALdyq$u>2AQ(-cwugcXsbwu_QyQtN422!h9pF>6{>(lU|j*ipSzE4v-Y1 zV=P=dn`7}6#E<$|yM70c4n|0#(5Iu$-eUaaQP%0}R6K_B10VW_vW|QMgVC58s;2g; z-oZR{TNdj=)bXIPpp3{=fsa&EKcH`Aj2U5GX~L;#D{9lqQ8FeL6h^JjCg*@(qwKt$ zF)3TYtJD}i9~FmSDssP%sW3tHbB)o9^Rzr63G&XT@3p+2Ev}`^EWbuEtoT6vdku>ng$NXygXwSOcvntpIX1 zke!{YNXO_ehOZc6aRIWM9MO8>Un)x7T6MnG6r~2u;Te0sW>p4PmU3Tds?hjSF?=5L zZCh4WUMjw!xRj=bhCl+uKXS0zsfxGUWe=&8`i=NIOC3ta=!^)lPJwJ=mY^XtZQ+sP z7F(IMk`UIIhg*nH!f3PnqAhbP10)QhTwxo#3)HjyrD*0;jd8^&TMOegrgKY-VwI9f z2crb~9f+wKiE14a%ENqNaDtvnKT>TiEu{})ZqrPdsbb_tJxepw3xaFfkb9c1oQni; z^cO9LY=*vJnXzcIt!cctMBhpI#9z`vvet zB)x7VDUJ(uKJqfn33R?+tEVhpQ*U+(VpAGdyi6a70$v01jV~HLPXI_qs4hbUS=3aG zEqk@AV_L1z>Qu>H=*<{^RT3JbOLaxfPHUV=Nc&J=;qFP*Ym$Z0JVmv{=ok!T+d*xa z>BrLp`u2h|{$wusxVNb(iEcaF`!y!^GkeUsl@VR75{jpr>uWu)hBMLiClZQS5RDS4 z*%bLt@R4vB(&3~YhCXTXW9FQ~Z$wZwy5)#t!D zT7C%eTEkO7Rjv{92iR)0$Ej$y!Vt<*+wLk6e~3 zc6^+lWZ7A)50@lpft^7rn3Ubq5i=7jiR;8#rmJ_9BnvE$z~;3a$*if`_TGn;I=}Aj zzVA5Ht1aS|#D1ZgQ^A}JDG&yFOxh9;-u%#M;V*KGeN8Yn^Z8;IWC&a(O9fCc5+I2 zR&fWmVU|Hc3()|Bijwt7V;{w0x1H9#U;*KDHQdJE#Hk3bq z0q*q|fxNjdgUB5yuVZ>Ot)tm$$Kw6aA`#hB3zAE{Li2Cx?qZWV&Ne!jnJtmw@M^2h z-iJqzlFm-m@WR=BCx^ow?N?MHPvHc3xQUf!MGj`4SD404Fk!&vkY0C{R-NscHt8Tn z&a9gb;>@^dZe+^OxleWluJGNj8uf7Q%_gn{R|yQ8L#Rb=d|N8@1O1=~cWcAgL$gkw{G4*;=veDT)WAuX`>EW%TMlHMwn0BsK zOU_Xb9`dSdqM39~l0Fp58)@f5sE8hh=kjdoG42&LmTzAWN9wdIVKTp^B&cPJPEi9x zEpVJ;D(K{@5j;&xcMma#GXx0N6tFsF8_^B+0)!O`C~!hc%LvMQ-hA(O-%AeUkQ=c! zEzB$&0V28(WS($VB!= z%aQ+(`;nck8)u#aGpynich-mF3y_JkE*2~u2do=S87eU)NknDfPu*QRWR35BmeB7R z5*&S1k=|FqvqXO&J zxcWw-36>Mj97=KYw~yb0r${f0flnz9bSLYrWksM-d9`VA9`Lsj!&K`qDOZXND$y+z zT4ZF>Y*%H0efG-Yzc+RbR^pnro-N!zneWUd(dGzM_s+JTE2Ja7T7{w}Cmz)h4h&fJ z*eK)GA4`nPh{2K|21{I)NJPs82=><9vSjo2x;g|wUr;sSS~QSmPxO4+Z&&YIPYU>s z{h1ezghE2~hLelv&@YM#lZdSjZ?RlL{pe%M;`L(_$FIfjmtM%bmP3w1Y<82`f_Li>-k;>5VdG}T zbQi+)(v|nVTJM~v*49m^8}=WDx--|jr`A&&8sFZkaW%U=q~D7@pGeU-=P~LMN_J#8$l!iYovmn+|ZI~ zO6U*ae|NZ_1$Qi+KQN`iCG%TFhr(WMjm>+IfYg9A`$Db1NKtWu+oc0xLuP3K=YX1l zPfC5UgPvS@My)~KZifWnfTWcB#mA6%g?85+?WP4PzJoSKlf9jw=$tT^^JV7umsy#i zZFvBY^Hx^qOwt^$fy|LjahJ%d6rEy{^mEfzS-<^YcQ70FfUtLP%OY9t8Ij-Ih*GT{ zYA^MNYflODhKVx1=U@wId!*n2*%dIH4dk+l_HZK~g&C1_IBEyj}r%3Uk_(8nS`~#yP8*+q!S9HPF(cxhx z*gC{pD&K`w3Qc&UAA9m1 zxZf7Ho9lL$A;4%2c%aZO&34SgBgzogWruY;N=mz;QQst zm+L}YerC%Ko(Vj52Kj>8;ouV>jc*vCO+n;OdA2oMvJc<$73pKIjjACAlca%ELX^RY ze{=bS2k`is&IMNd(ntqG%&ReMM`no8s=ZMyd<7y)y6x1y>`_DmT4`~l+Sl++IAhLk zWjh;830i84)?G|wlZk-Y71-=fzT2AEg~am55QBcw@tZXhK--RtMw7+id(!UogI6Jq z1LPOnw7V>4I9i2iHxM&4kQa4`Z54zs9V1_Qj zddkpx=c2;Ijx+r(D1pQcxoqv(@K) zgnEqOuUK=|!TaUhKhlSd)Kvl_CYtd zkcAY31MB8^*%Oa;A`uJ*CPno6EV#WV0RQ!N>Wlk5UTZ0|i&}3PH%Xo&=LKyq0HihS zs}rBrT1-m%tqTxw|6s`w@FuR;taMBV$9%&cBt5{5yHefX?g-&6E%v%Pp zg7EgT=Y<@z_12^1M>~~hRVgb1IfO){lt4P$gKyI~lnCQA85;1QJxG}$fR*rM;BU(J zCFWr8T7ok^cGjGw9pR+*NY}s!XL*_AVNYX&AkpTPvmLq67Cg^QJtP3f&a!jit%cL# z%7}Ir!;Zzkz;JO~wz#ihCS(z2Zq;#k5prM&`^uk$#0w;UcV;4uy%nueefS4bUae3( zv;z;*5wz)>1&udh?hBZ(fu4LZCH7Tve1)lUt!jKS8M=CcP2QOlUA)`LXjq9DUg>3C z_~xyESBO%Ju5L6oXg+Ew0com`!yK(?Rs0!S27m zA9e4qkg4(2E!KwCanwYC#IM)CV;u1#)+g>FUZfxaPhQN(S%y?RAQS^T@ATpdp^0C?=1b88fMqUXAMLBT_)dWp876&;X{AL~_kD-}^D`@SQz~ zE1(W@%ejY>XQ`j*-2jv2;MwC&WcNGDu&8#Yb&(UNG|V3%pQ8Z1i#!NDO+1I;hcD-7 zQbC+*?wr!h!J}||*VNfltSUk^ zE#_#3UBfSnX9HS-dWD2~*^GL)M|k)7X4SDEt@zikm&;txEM&R*rq&@~`@B8IPYgx) z+F%-AVB{R*`Acq&gP1nL(FQ?$ae+r*-aK_EV>aL1_W*YR(V$a@txZsetMyX{RqTob zDOsBaDcPI`l|PpAm~>&%pi+mK>G2l2;%Y{)2*(9GJHlyw;|69Cj0>8yO!C6D5rMYH zyZVk1VeX{ideLM0cpBtj^Ac2T*gNbB6Zrps^HuYg90Rzo8oxlypQvxNz&cR4Q!JZu z@H4ryyR$DR-z9t4AKQa`Z|Czly*$1IaZ7$=TL!%Y^*}g5c*!-u4SNNNkg^_j-2I}Z z(;bGk!~aFtX*US&CN6}Fm;1{jF!z@hp6V}L65KJ42oWOMX--Q)Tk_2pP2$GRS3-_35Mmxy7G(DMI zkFf-{YREh*KI3GMYCF4$5oK5}8NMzZw3UZxo5@eJ;alr0ox{WN`DHq)4@;jAKV+)vrR^{Ut-#zagXt+G|j}?wS-of3Ga)qKE zy>kO;2_9Ys9Mi1iyThmKU^p0&e3K#ZM~bkL=2H@enEmjo2Y!{rxfg_9v>CXTP@ez$ z>we4+ohKC5TGxX%<*>X`%|$|`|U+LPC!#)6p2H-jlL*$sZzzpE(Pcw7b#A0 zkjI8Vbe@psFKr2wC+(s1H^pdO`%-B+&WClLG$(eR%)@D2a|S$4F_*h2U_7!%UAYge z!k5cJX&Is+_jfF6ec3@3-OW(cOL^1J;j4)9`6lA+NB6H6?w@r#1|V)xD*Ewrhj$Bb zhaa8?t>+teo~*N!bF3lu0}gj9zc(M@g_XS$E2D z8Fp!Hw7VnIvUGcU?ItPRv|SR`(lWaOB?v(7_wsuHURb;>ONS!?)W$8ZxCyoTQBnKFQ5G(ZN4z>wMP%_ZdUv!8%xcmTEW4rX$sjXa2vZxL`CHBm?7Y8( zY&-nS8+J{}#Vg$znyk?WmKPAKcmv(vSisCX(iJ^?Szv|y<(S|E&o2-2WSmk^EQ_U&^ zaOpZ5cm3r4yaoFKPaylTtqZ7qdVu+=vcbv{AHfa2n-A`7@E6-#sDp2kmNZri{_9M%($Ws=D31{g0LJs2N`w;p5JLuxpX*1*;ytY<%6I1sLc&m;t3} zTUzdPfKm(OJf`3Cjax&W!7S}4q(vz0;&Ony=rlfNYs4{cb(_J3Smwc+c;p@!!Eitz zKDw;MIqbYWa&vhBSoSW10KL#?#etpi263jP4G3GoJ+fTzdBx?Kcr4-q{b)kfjAlda zf^K|_>@v7kqk&PgT0KI#hd$O;cw9e1-pD0}e9`{K?6j=4y{%l$8Vf}m>PjI#a07{J zQ=co0#;@^6H_VlZ(6?csg(N}Uq4hp>1@$UB^;*sV7KP8)0?=JIgYEC1|Baws_INcM zh2~qfVo1LQYe{PiS~rG@Z=oez30(1NgC%y6;b;O%vEi}%w|bP)%VuB#EQAb@WEKKa z9S(5rkS^bKyVl|k)ompOsor4?HC^Gkp`U0WAgm}{F}Xdt@u=hqlGgy%^tBQnrWQfX zdPjH?a88lWO3T37#IxbJG@T&}-tX=p9fFtstb&&5jQtYVlG{g~tnCFfTHponD{-!D zS5bJZAnpAAAa+e_MdQZo%+&sV8K=<k~Pt`aXUgJ1KHq5iY5FEgSnp9y~W6;jnx1P7s>9!;Z9j^1cR>FRdM?u6_@XwdPp9 z@D3MPS2KV`<>lh|{LW8`7ri~+_f1Eh22ur`A6yy!S&XKuu7iXDoVk~HIXZJU%FJ8k zZ(IniW~Xd62$y~JVjP5SPmP;pcr?hwg6%L)}AlZN~MS5qUvPhUl)@Xo4pmeDJHSmg<5pt ztw{m05AHP&74_#vi%u#vIPQ^VoaxHI;E0l=Pukap%buU}==-NWeWb0 z+wM+2-+U0Nw=Gc4-L>64Gql+~KCidEAzXB-GHX(*Q7cw1bqjp9=a-3(;0@;;>S@Z7 zcj|jTjgu_e1u{;nEzb$+P8EDM?>9^Tf>oS;wo-Decs%!~(cO_IfBtgO z$rHXY2zZz!?BwJFNq8On>^QzNn~tRa-gbD?7A&`I4z;eWO>Zpq>==>qXn}#54cB*H z7z_NJT1eEjw<>{?4wdW=efvVMGwML!yrSivGhWuf@&c?%VPOv9vcLx&Pv()k%52X^ zHW#;nj4G}y8oq6p|6IkF4lacKW zv&i)h1A_xvG{gASa6mN<2SQ;+akjQ7TXmLpp@RZr%}fX2n92pyzWo;E5q#;J{V``{ zX5HJ8RHgihzHE8!WEA0qSVoa-5pr>9!^jVzDpo%tGf7yTh>TU(5T|M1eRzB(}so=pG*F96o+sblXEV>f%>}_B~L6 z-+Jx2y})u{}inO>%Jt(J(pF>qHl7w7}Lv2 zEW=mz1|{Uea_subv16rc=~DB!rp>}qJqCB zWcKPZ2hBMPhB610WcG8>?52Im%-S5_RK01403q zR&t0JCVUbTEMySPjM~J-YxDmU&eN|*e6h$CtCb;MAVWNeh5`UqHi#D%d=e8atm~v= zVC3qglD~|hus&!?Co<=+6IU%{#SV)ZQ4KE<5IoREh$r^si0c$T@aH@f?z9yA9l0Tq zkjjT5XL_GaoHqd$laMBjC~M^PL0qa1iX8BMojBKU{9EOATAdkNJTrEs7(|^*UP zX+&NlUSV;_d?@@FOu4#`Ok{h;(gq1g3A^IZ;*QcWB$MaFeiI$xeX%=HVsLeh`3YD# zx)O35vf{7Di9c^di9MYR5j!fOwC2Df67ZxE`Hj4U#b4(`W$1bte8I~Rdo4r!c>#>h z)GMC+GB?*hW9J52$xLotUhe-FN$rviPlUFTd2dGEBMx4dj|V{hk>j=S4?+p<;&I8{ zv$}=CzNUiEmP14~HyM9(&Z!lB0Xav-82?{n^4dC?d-~dXRw2e!?hk@Z%9ZJJwM*2F zTjHMjiJnl>a-W?HotUUSOD8@WHp-n4{bt%CDpFILUhILSccevL^a1ySpGYq)FwpI^ ztfa8tgDu}XbmCNb`n&6V+G|+pm4Inv$yn$BS>dUMl6aNFdaaX|Pvl}Bd`0qU$&iV& z+p=WiqoJduHKl(S{-~GT8h(rl%WiWQ^Z8*&*p|f~9}O8L84Ed@#h)kQlknH%3;G2; z!(R5BaY0j#l}t=x!Gar;ovgMb)5RZTcz}D8%*j?(RRi*sMY@;2y5zT$rVsKfE0BriwWn7rz5h~!pH{)Z28()y}l z#rg3Gf%)6n&iUa9(E0hF=jxjkwcSJRnPPJ(B|oKnZ8W#>AH^2DL|bIY9j412{xp3k zt#>(f-hh#4Y*JEQ*R}Eg#9WY^mnCMhnut%ImtiOyJI$zVT(VN`msNBPVXzzT6_o>- zxwV_gZ=+Zhw|^YfQ!`51#v#Q_)l(UK8FG89xQA`v7PhY^E#FXg5!E6U-ugW?2=6NQ zc2o^k6R%L3LmEcihe&ALAh=wQoeeJSvHqx#b=`A;_3i&XqWPhrKmz0h41%VJ4&Aph;~Pwt;jA?Coc=W?wGvx-7!a zYwJ4<9x3lPbyF<0s$Se0Ioqcsv>2wLuz|8`2<`bKm&2%eplT`X`2l;u&dUN&ttK$L!KcA!%8pI(ETLAYIef%Vz@#{D$#Qsbq2*zU1f zBf=qsHH29!ge3u&55gM36)EvC-5n@bXyQmKi3I~!fTU)@-b(@e2qMv>F$u)JD zK~H7c5M@hDv&$=NVN3lj*aMUVZ|idQqKGq5B6X!k0>&V+1K7cII6i%YpF^lb?Vu4d zRfyD@vy>4^adx-G^7WZ0;o+_+2l$krr@pY$IeeMB?ybW2Pc$`8=W2IdXN8nq$4%L4 z?sjn4jL-PdQeCuqn$HcDNw6j;%jHT)8J&xtW~%0lKH3GkpX(FrAZp^P|BV%aeN%Ij zV=u`+)!$UA^R%2Qv`tz60k!DU^{a!n#e>^{Oa=cTMIR8Xpr;niBE|7Sbkr>!b3Y8! z0uR2;1uK~E2-x(2D}HXbu*nlL?`GF~&^MH;e5t=;Qq)nLZpvns7&@P`R=r*O*DUru zxz5dI^aE?QyTo>?%+02(=I{trBStCAdE0J#L7Ur*dLOod7w5Z5@fy={Q)S8IF`3-6 z39=~DhB8JSUm5XAR3E(+t4ncn-(knp;kEwnyVTtf91je4#5y^PcE_tDRBB$L=mtv`R|Z7AZx89hR-gd`fds zDAsS<; zU#FIgvC;`iBgmr3YnmuEPdstagV0_Of$J-m(^+j;ZmMLGh%)~hdvh55z@GgmvE3r` z%pzYtBCxh|S`-)kA(Pd$%u|TJ(hn_=dxK3^eob@+grg2B$BqwT*O!V>M=5;$RDYU~XJsjZ_`cqW& zl32FY2Ri=qz(xU{9C-dy2dV&iOxQg5tm~QRkBy5baU$vucNl)Pd7KVy`PP0#<%a46 z?wVZ&;jCVSaTd^Kyy&JHFGZA3E&>BV`@mD`yy{{B8+v|asTfS8xKl2JJ=_gmOU$7% zf+*X^zY_ako3SZw=KJvIIEawE`fIiToduD?0%fS{Lz4Hd?v?W~7f1Unzweo>uq2T5 z_!w3Jvg&1feaJ=pabgcoYIPnze61o>7M=HLBqWd%Qi|LqLRT9zmh1BAiAq)z>!WfEexsjx7m=Dc`SVwznV8AH&~ahkh#ujuy(ny0yt-SHO}!M_JIvt|76s zUoj?yGFa$2)N0`hD){>gB~Ry_1`VpZPyN{z#(&)Tb8B!BzWI|H%xCB@pFU79W_~fBL)+yvZ_}3!tpY;kZ($g?6rJ~ z%6E)h-e9Sn+$+{s9L*l?U8u)T6>Iz47=$GQ7gQ;kqxiPnf+v!_U)B07TKlUR+M+7V z>!SzF{m&x$KUlhnG)+|?$B*#>(RiVBVYN|yHZNUh%&mSikiRCZ618DWpsMNd^m&Fn zl0aBNtzP|r?OEfL+wU(!RSQ+nFmHTY+Q!j{al6bkgIe0Tid69m zYDo(Zm+Sz7vg*Dp&I0Sd26;!NQqwKeMuqM_&g1x}ASe)d0QLIODp zXDR|YwGD^Hy0(}!_qVE+p_DN{TIS@cu*pzx0*56z4`A+y55#wavIk1=_ACozN!t&z ziravsH3#aUcJ|T7;;?#?l*Hp}dKFEa#xM|Q;x|YjhtsV zw$3`+!Anprh;Afz5?9Gb>?`(dhd%$2fc@^^sGFn9^Q z<(~wzxaadsuPEv{%ugD7Pl<;U|Nk-@h#ZGUjddxT;wgYk$#OP*+o7GLN!CJZ`OTuC zPstU32=0y7qi3=8?Bf?FlXGU18R|Q?f=5|1tpzuOhltL?eay;$0o6u!VeZ`@M>mPi z2`d=%^aqCGlj+#??WQTGNmbaR7O4DcUY#q(Zc+|ITtcFcTjy+w4Sz{t;M8{-I!oGS z{m%p?H8RulWb@Y3g=A|D!NX{&3|#syamUzQ_Gn9*F8===PkKZYL6e)54ZzW_JkAf6j1gU+lRKf4|H?;2vkJxU6d$o=&7m zjaMTGBbwg%(y=2_q@uO{mLg8EPBQVfGA#RP%jK!T*y~J@j;JIOR!OUr9~`}ok*9>4 zB18Xy;LdO$#(g`wFI$#6+lnkkG+*Vzx-@y5blv|Ju_9U%Z-@!Vn`w1jWi-liiK-yurZ8!y)T#*9vdWuIo3INn0J&Wc?OROKKjkEhh7tH-GB z&fU|99MlLYb0>T!xEG@k9(|8Q=kvA?t&1`kPY^uwDCMHcSiRwIi96-D;=6YF2hH21 zsz=p-B#X66mZ3uKC7=8dE#4Ki+#k+8mi!~>wuidS5ZVm0gHf|_91YpAqc}Kh588+}PnSn92s-Eu zqV`XQ{*?|;9!`h%>(0Lxn5a@WPzMSshL_`Mzwh!QhDo3__?p)H-!U7wgPQ=Bu>0jZ z#mI6(ZIQ0XV4{06YHgve&|qwIc6vLVy`Gtfasq83luPbm`XmoT%eN9;R<+-C|2c$m zTo^i^6KpS9Bpso)u>6%`<;R|k5ITrN4H*+Z&i1)2-5E)*y_G*|TBfX{NDq1Rfx`)ZMZQ zaRsnBDjY#0_3;JuCe`|V&J7dOCk7PwJ;EfIbp|X^i@_w6s?1iA>j;Yjb-0~5Z}oZx zWnR;{ksu3H)Dl{v(~t#Qe_1Taw}MX?&7)w-;^}jAHdTX0V~YHWr{JpMe9#4WD}mz_%RD>t#LQDCg>$ zs>zLFm>Xue>*?#m_rvQM<^`55CHs-8l8z$Lft%$}vqRu0TU3$t>gDD+Z;gGY*>`Jd zyKbBm=LqAomgB3SqqS%){PS^|m$LkKh(+B%5YTFlu3*Si?1O0s}9W1wyXgo#I zYyW4E7JeYWAajh-$W2M<_Vfj<_6=^E|M43aq^K*j2M}C@{vbfQr{uDp%iGj8Brfco zdOlVAyj^(P#q<*P30wdA1F7lXg=#-O9T#3ol!(-FSSA(h6j^RESqF`D1?L zTf}P1GW!*Evp=)j+gRkoU!M%WrM`0y1b*#mY4z5e9a+T3ys_MZy*Jw^&1BDx_|g)5 z5Ph>m_nd(y%AyX==^JPF2`rINR>sP{+UN?4mK2K~LWykOhfaMWDT*_*x&8U^Qj1ZSaI~G2BJye zV3}h)sktXrIdTfPt+YJJI(bT%DRB5YLs!|yuDKZ=y;)z1(&y~syN;@DeyNU#60`KW ztKZ*GcU`-^@kFZ|5nHmYmu2vN+_GeTbLC|XO-GDbsb%BSXu5G;d)l#O7n{T~YTilg zQyAGUoi1n2-J*r|weyH}-?L~56=VJOSSlWH*G5a%csS6aJ1KP5^M=!k-yO?QS&_@i zMp%r(cKm~@&L?3ZiG=IqO6H>mM-^|#hs(2F_e zs;b#llYt-B)R1hE%y>jfIfhs$?QWsDB>nk;Z=rSj(GDAyz z&0~<>fuE=>C7LkZ6AALLmFWFwe`)Q%u5UlasH_DeZUn_B@nhkjvnk07B}6xtc~gUW zFF%2bijBQhKNrt z&UO6B{$#_pk#%<+%a4@TRQjR`EC-z)l@yrhPp zwUSs)8285oO*<>INc=yG`a;|$ec0O%3zwD7QqhDwxHR7o#(Le>j(e&Tx-~} zR(sRLdFgoKA@ST4?nvw_^4oMb4T56C$?Ra#so%+AbyFWK zk3zebCg?pOS$y{Q+iX~n^S$?Q%Lh6Rt8ANItZQ4(@1*7MqgS^d>0Mghw6`+WujJmI z0NI8(64HWARFrIx`Q%x3G|~>=4t&TnHJs;H6Ju%*CVtk%mVLz zGp9kA+vi_&xS{&DIBEM(J5GTI>m-+1j^rw(Pit3I&7+~5ANT#LxW#f5Nt=apBuU>k zJ;v?=qiiNp9%QbBP~L_ZxtOEak~<08Cu6^^2yc<2aKtu-0;EZ8h`*tRrv2Yg3X7kl zRGhns#jg@4ezmR|`rH@vVN#cK(SW4TeQixerO{e|=C-DK$Z-EDMe<97y}6mH$~Lps z8Jp!RqLV2&g^1Jn)3i37LLI+FErdC_7 zlg^+C$w_GenQY}p z=<8v!qm>F-8Z?TNBL4^Qr<8srr->U3GpZ&|DOK~qk#L5=Ho*CZbXS;!@M06o1`Wg$ zT^fb(PU?JGf)#F=OCrnh#F5XS7`h@KqR8bN+qwzPWsc>E9H2vK5+RZNf*U zc~~hd&Ao?P6ADP2pgk2fr$Jtl2&hMqcFUoXWj*AAEI`JG%rV57+(gB9BmNW}EZfsl zxVbrfabfP-7#;ki&C44djCrvJzNXpf0qa^(ZY<$y`|+G^qu7m?EjsB3Fv{Fjto;ao z`r@~OJ)RsS_5&C|oFNB54Rh^g-ToN8MfJ<=9JTLo{32#t-%!bf*0OMZ_}V>Ihhgei zq>skSIitON`Mge*VuGcgsT>cHqBGQvxgt|^?**)lEpshZ)^@ZoN#ihI#l1K|$08r3 zl11xW9*{*7q{<@JO$n7TqY^s#< z5FXbXEUK$HW2pQL6d}V%P*XCPR9Bnq3FB9}uF8tO;Vs?Q=R-VxQ2YAi_%Ymd%SMzw zDR$U+#~!;$>u=Ns&hg=J&uPgE=2mci+CbwAYT96SS9q1rA1&o2nM;}?Ea+3$4UHTo zp9xaeg|0jzK-&>0#KsPY<$9Poj*mcGy5&u5XJCg;nf$QBCesrAm?YnA{I{yeu$vhd zBHe!WE^lpmaN^a3J%PrU(7%$Vdnuf;yGGYTXo(#LZtUsfSFjr>8M-htq-IdjBj-8T zysZAgCKnTM1SGzedohhajbUjSufDpPK_QNAWMlJ+f+caU=Z@VKUGXt@Nbb1|KGUbH zlU=nKc_)pW$31BOe<2ktJ!X~&>gvVHPUZhoJ#@ny7~@}DB;#qBNg!~_7t=nBP4KF& zmK{BiXK^<&Ng6qcOVMVoku-509HCdACHvKEq?}ZG6sN2`86ifUJzmuUZqk#m(XDL9 zrUfzIjd$Q)cD+8DQr@hi;F{Q7gQk-|ax-E?!Yi>UA3l(tf6p@`K=iG&LjSDj8$XL_ zAw6*v`nOg<^#x;EGsWN)TGmFft%>|PtKvHAwj0d2qH9L?6_hn<6j_3a-)J9%wqbfzV|Xv4`b(%nqT~ zTtT-GT1smGxO(`}0e=+YPMhE)ajWPSTlFoygGphxAsRvM1y*1`C9i1gBIbWef8xfU zj}Y4(j;510vd{{@HtFY5yMa&VDhS)Q`o%Wsz?x45<1iM(Jr7c{LGKWQcGWNc<|dx* zL>ksZ(a1LJL?jj?$?RJw2&xEPB#ANRO$~h*Zawo17&O;AbUiFnW3To>_5t4J4kFvPqh zpN)?W0!(ytrLU0aIk4#5lG!zAe_)CFvlx}5;wPxdCFU}^>A#@54zX-`zP3^dcDT0E zN~7TrCY70vcDnl?Kr>y@Cin&h8K_LW-gU4B!n+JSJ`E{1abyNwpuGBsePg?VZrJnJB@w~ z3cIG?Xrf*X+3)w7-8w&hdB|f3xwkxq%q5w56-y5H(2E&!Xoot=p*gmJ4{B-G(ps>n z!T{U3mM%D*fT&rTkF3Mxs@t_dpSt|LlC(xPdAJ4{^q$`78P?IiL@Db*$JD|DdM)s7 zgdib3 z)(BsrO}&I5Eh>U#rNI!N-Mr7i#1! zPq@_J2%eGMpAt5Uikcims|P3EE9z0x2JIJj3K&1A|7dWYn!mB;PF*vEs+1OssZuo{ z5te7E(`HG@Ybp>>z5zW^i)t+DeXS!2tP8g0RB>3-7Hb#iopf3L5_Ff0Fdkcz-YGG+ z%!zr#YNdm2?a9cNE;|b$i@u}DQ56SA2ZNarwK!QB11`i@7+e4Mk7+>Sao1Q`Z@`sP zR?eOh@1^2QK=J#T@9+l?Xzu*8&_zWG2u4{LM_B|oSqxbfike`vj*nWC9S#^p92?SR z!42P?IcvKn&mk+J_}^J=P7s({&q&cNTbZ~XxxYU_eJw0gx_i*LrZg06w>d6qvUvv= zk$POrd1RPC@`aefEHaA?d>EFNp|Z8}vTZE?{&Y|71V?>ZBx<+GjvyTovor9ZDO?X~ zBtYG)TH0aLe4J*(Es*|dq%>2wX>vVTa`6r{2D^qYVD2l?61#qVcaq2FFX<6; zx-UZLScbzaz`P3@+?WA9z#M_b)(s3jQNN#h9P`r(m=J zBFLFA6-s`XUa{=^*+m9krLgFw3wd0AiykrS`yzP4y3Jg6&zYeALh@;f_^v2?YCtQg zQN9;%#em#WHT`uF@&GOYkllON8-)UtC-%078iAT&f&qy6-cuqGLT<&Az<^$NHz_c| z*}r(*7aqCIpY_t zaUl=OZ_y=2cfS)1{*e9In=*zF=HIF?Jr!doa-X&Di(m(bv5xa#h7&qXnR9xQ^1om%yYjxF)jfxJ;%^|l}BjGA#;@6o0L~qw^ zZ<3k?47RSL?S=&5fofZ1_L`pU-B9Q;o%4;m`)t*ryj38-ghr9)^hDYsu_+}&tE1+U zmkj%tDyr{=;IuBfC&)KOK0=k5xAhb~6O2PJO+9|TmX$&}6h;^eyxQ<=d{@vDXoo!V zJ%tgLK4>{t^wOB*p_-{G{cU-JO%04@(<#dPzx{0v&N3u%GRqV`UY3tY5orYQ7zQTWx0*oQq<0CzAma%cP- zNZ9#JbU)lDOXn?JJJ~~H!SQs2zR_xwPV);PwIwejJ~tccjKw; z)K%ZNj`{wEyh=ZLin8jK!;|?eH$(acMOd}Qz1EKzdZ}gK_O%d8S23c3s&5``+cFGD z(t97fgaFlb`_GEW1HvVWp z+-WC|+g<^mt2ioMn0+{Q)ZPeGfDtRUoRG%i2+_Z1^8;tZs!i96^z!lKAQu#*x&dVPZbGd+J^PibSg_Ah&vfF(rM2i5s` z0jeI-YyK8rpJD;q*_VhBEvT!!5|k)cNeJEF^U;nNG^5%v{r+zn+i^YPlz(5eBWtwd zTX{EXN3!ysqem;*)Vt$q%WyPSn!%el-6+b!9r(-j+#=b~yXI<3Hn}FY^&Urw;mN8> z7URjNN_Ng}0sq#oO`nz*|7GFJtmdyA6-%~Zwk;z`>*sC_Lg`xmaOYb7XgtfFz8jU4 zeO+OuV@aL$fh)=-2KgFbcmTe%6lpF#YVm;h^|PUUFABC!#jYEEW*U;)$7=;&{?|L96{u;fs-~TyyJIO-@-totG znxepNu5VJg;$U>KT+s4Dhj;n!*5<Sz15(_}&iuq7uun2CLFT zg>@EKfC=g(U<8ery4c!9jm}Q1=QQW#+T~Zi37xdtrCLz!G4|71^THS6 z*7poOG#fn%Y9A|lGKsz;>d`&p^ZPnoP?bg-#c_U}gQ$uj#fZBXL&=o2f%ez)SRfSb zGICH_lFWeLPbQhtxm0i<)gW}cjcX7J=juMm?@OtXx@N0n=0m@iYR0w+@Z8}N2+MO| zz2GwC#e?VvXWBs$isEOEWZ=B_^ZyM!w|MpYT2MPM!CIR!G(s zg)E0&+MGZLcIM>h8fC=X1AE$7!EwX3S1^&)TgI;cslSZKO1*t5jwl%=AMy1@QdVpHummlz{6>$jr&sP1&b5suMQ7sarP)~M~yUn zBS6uiK4(vS$wq7+h(&dFa??1xztagX7sRk3Y2PdGbaFZVc{gH|@s>gjoS|D%e!&e7 zay@%1UdfZWJm>cQv8ZkMTg61qDTXzNDKS4To2F#(Mq=!+ig1lPp5jMTeptzE;ivviNBlA*Y*B5D*3q|yk3<=|o z1QqzcmOzW&d@3d&o%PRik5NMW7jpDlG^7dnG2<0AEwoqPI5*3&OmV%>j7|$1-1oH6 z2&lM{&kE=RV<{!F;Y%DmX`SBNf$it?9`fHK!n{+HIx&i@D zCSUIqJ-YoicIvbFqDs{XU7B9K*jmzx_MSo&VCeTyAS=oJeLR#%ib8~@8>oXpQ!{SA+Eb4a~L6mx( zNWnNJorSNhtKN&DA|}xx#4}}eg@0=tiPck+f6@h`VFO(Hs!=xE{q+Ci<{-Uft^w#$`iDwSwyoU;_H6E|z(&V8xSo0nhdEE7-ppwBH zi|V3O+7j~cf2(p=7e&#Qkc1x%?NW!-UayYA%meos6X=j}iEqEknQ}ZoG6^c!Y zm1>ld)v1SQ(Tx+sm?cG0@^g$bNBA+TZobe0mC)28tZG%n9Ddzsp=GVv8!$XuYOX1_ zHUk#E{aRpV;=L`w3e5M3kiP3H@X(~V8VucX1SN$is>}3_MJUa=dG2eu>l2{m*0~

xO{CFx-`cZ zJPcbG39ElD{!_N_7v1@N`RiT_wI$`;*W+_m&Cv_- zUJCR~rJqkBOUGK4#fzwIDsAS2caT-Yza1NgEhmT{o3Qr^v94<+8H2W0}7tuF=`ve=-p9s0m!5#+G zA$ExOh4lDL%dj#Ygrx>br)$W%-(d~B&Z&5m^>~Nz;YPuud$6y#D)j~(mdxhgG#}W` zQ9A=^2Q~cFC9CK3;<>0*k_v)pbchEVC??0nrebo zlR>x?E|x3H}~i(OiCUm>6rPQRIU zGJMt*^Fjl;U+Q;8{9MJ4hsvI|S#`oc8rJsT5V3p^(O)cah?TF1Jkh8;sM9~1cCm6| zj)kLzsm>m)@7%0C{+FLKti858U+emJc}PZ!piKH5DUDfHnj*6oTiKM>`#ul)jIsW z`nvplG<~X?VgG}p<4jGSfG+L)Mm58`wH@8@d5I-ppU(%l=s$nWz)zwUbJVC7rL0N*BWrZ}#f-k3CMn+NEH0!YD z*$O?f{{ghe6{775>9kQPIX2jwS?kca$P>y0>5qY91v(rVj?D><-Sd=M|cs7MEJ46@qLf*EJyt_Mh-P= zTP0NqHQxpJgTh^RL#0`C5zH@nbZ3pao>V?M_0SR)Y7&w>n~KCj#B& zl>L???Ar!AtFi_|v#Q1npw64}*85Vrs(Qc@ilt=s)Atn$$1@T{1MASb{A9y&>_j!q z-}()*6ZRV-i)|BN2!%$nl(wq+e^E-K(#q zmHiqEK`e|!wB^~@8PO_YFC2>}Pb!8si2RuTi})e?t2ZSx!r?D0BLkg0l!nf-3(b4{ zolTz}Yda4mQfRb6ut$vy;%!BFG18_iwHjn;lx%_bfKLd^JqVQ^N=DDr%--nO9bpl= zB7ZFBf>n0zfidhC1LEa^)muoDYq~hxupKBbY021UIac|O&nrj?A}lK({urnKwC*qd z)4YbN=(hh%7&fm5`6KJN?vojbFFT6mhS$U+<$I;%d)zDlpuZA>+O+iAx&NE2)w@1Y zAf%`GUJ6#ic3}^8Rt25;7Mtkhy^@2s7uPGYCtRjd1xaywm4ZwbBP!@J_wT;kBfUbE z#_RnAXx#Hu+8E$_N}N-vA!dS2rZ2oRz6Upx1x4l}QeJYtTn-eagO+9d+UxV|MZ=TQ zyWd>(P!OfIe8qVg#bwDITD|FiN3r0N;Z?h5TYcasRK*{u#dXOJf03$FyU`3oRw5mQ zlX}JGF~nW>n#|W^)y18IQS*prk{-s>n|3;`=&S2S$``HaFG@})UOP5YQuACl31#wF z_3QH>EPq>w0_ilqaOW|r_{=R=7_IQ%kl2g4?`$B)J z{wNZ(T1~0?)@MulC9fYhl{b}~3+^lKT6hL8YmaSM)_kF7c!m#i$6LXPwfso^WI+@` z;h~{IlNkcTQbSTGg+@3mkp>ETwIk+RGb1S}HNu8_CnJknwId}X)WC|A*_7F>>yf9F zyI$-RSr&5PE-i!)eogAkx5H+Pi)ABI zSB(3gLH>l;99EkM&+H5uWdyv*Dkyf4r4x1vE~G~Z z2XR!mV8h5u-G?=A;L(|J!M6Z=8|0;@iv>oaFR(y}@Et-Q4evd44-q3yUuX6O10x2) z?*Pa>|MR=30NQ6HtPaD7^(sOzLsu)jh+xAFwN3$pd$ALrZrP2(J209q7nG_kJ_eMSD7xZIaFft-W#5~pb1(B0p(+v#Sr^&%1E}i?{&um1Y-9=lfdWQ zfubXplE;V={@fDQd1IH60r!lQ{_5IA-k?Ws6jk8kEF-jc?!M9X&6=q${PxTW(Cu0G zrwIHFZjQI|Gh*v4sa5JJIqSSv$2*2eg7qQ;Y@bLcl?zWYIa#J7Nl`Cs-F_EO3-1p2 z?c+@r2Pf^Uikm1O^YS}{;t$t1vP83nX0blB2Aw65OJ&Vw*82U$prtPIQj)ePVR zH+k3buia>$I@|fqMydtYvrP-I@gL^Y`0xBFCps9jHiXbTL;MisFNk3Hg}Z_&?~x!0 zbN-clPGp(;f#TxZ&U45o_uXTYzmbsOJBBL~fnTsbSZz1S1tl+3bPwtUv@1$jCDJQ? zhF_sRGB3n<_wPG*V9)nKIVtZbPDwkiL{b5?t0=wrELm|g>3=1uGfRdFOD-)RQ$6es z*GI$IG<)7*eOT_Smuu2=-3?K0at923pOYH@DccT4Fkk zdNwY~)AgY{xLhDJmR!+qrV$<N{0-3TUV3kY4g@lTeYfoO4OMNCqt;e79eQKEREz(N(_jDe!qPoKpS`kw z9kD#!YfX>iVhHB1JcLN&ue^!%jUH{{CQAeMzP_L9D$L3;h+`sBM}(ii9Jm?msw6ov z8k04XJcC-GZSuH55L}?;irarI|NK-lM#&lXhMiU%L6%Tex>hq&$egIu6-TY604Z6b zCyq{A>_?_tnfI8W)Dd^2s_=5;K;T)TD}F;$>`gXX@lT$7J+Ju%ma%{wTQS}?`Vst#7KDg zxl#G}yxB3+ung7ed&SLC%DlKFrOP-8olHdZg0xLhJ*~$#BhkY+2iD4tu|FZqk9K&^ z`=&o$8PbYTc1h)B{u}J%rhEQ~kG8**m*F28bh%!^0xJbW!xsINv>nwGP4$iK(7h#j$}EmjhHm~7yi5<^E5lNq>*<+N!T|n zl4r?GJ2oK;lg+s&4U?Ti!L0*`(pAaxRC3?-A|>M&k1e`W*LXtJailfvO4eOvaZj7x zWHh4GQObw&TTF`4Jv!-L2p9^kiiV6diS#}ur?8Ne_BR|w2Yq8Ci1IbO0eufNjZi2v z9Bu9`ZlBA+T1E54%Hp_jAjEz0yULOd+;#`y)c^o7gfJx4DpY{<2sMec9PQ-sHkuW?Z&3RUkI*%*uLPhig;Jd(90m%kcw8g{{<5?QZsTe!ZN~Yuiin zss4!VCXqWs^Vd`T?UQ^5YC~&9+PU#v{asq^VOL>ChH?wvb-QJnIkolF@`S=$~i?`s!^yN_pETR-A<0>RnRwAVI%85@Sid}Wxk3()bj?ePko;cS^2 zrAjn5>hKq;jK2@MxdVe#;H5I9?*FgwhKO#-6Q-Q4hW-!e&Dd|llpFW)Bm3+WZb6sL zURP~Zu~y8;>VR4^}d;nlcF77=nz*PV63fale)KIFCM)!3X&NMTP*z8Xl-F3FH=hsfZ@at`>Z zr@8>o?&jRDt)m>*E}c~c+Yrv=F^J+)94xH7mk62G`!lIhcL3LpiL_N zEyWl9_51G=$Jr*M8ld@1P$qB8d2Y->({N?URr=NF`MX~L$+v4AA3g$S2-coRJJd?m zswT$qo$I%=BD3W$N{$^3z=9$*Nu_(?K-<$cb=F$-TWz>|^ zE}neB=hI?#sXAM<#GjvVJg+O~D=4e!+=;FyP?@ZmtJhCpcfcPWHOV{ij+7{m<2bs( zCO~|f-j7-r1#2Su#PNP7==%y%3@*66&}W+u1MvSN@;=O+;h=17*$Qx?vki%Fs(e=j z^s5MY`+koo6{(7iEU7ID_|AzKas>kS;u~;Ya>hEHJ7lJVqNnz4WTsDJ5L>+eZ-KE+ z_fCVM)4|`OY#wcoR;dR%z*B%XhMi;OlpKjN-z*WfmUo|?ygi0Erp;8;v!jJZf`$%xX19(8OjbXOf%cc zzF8p>ioaC+aM|rM%_-rST}UgT(#2HXb#D!As071RG!)$AtwmGzvdx9#T~GOmlPj*I z3`)pgg*<-m9#TSowd!(FUW7A*s!S4{=beN_ni^*ECB&gOkhfVvi$TkLFru>vq4i; zQ#G8`GK)=aMIXK{C{$+dgXNC{1L;cgu<|)0%j&NUm!-Uut3wSYp#&g`2+trVcexEHwap~QF;xbq>>xjw%>M`L(Ed_oK-E{szYr*$sjVFREPwmX!l z9cdk}km`J!N^b#3n5MJH0DgWPBdwYnbhreh$+X8atl95zJM==CwzKG3Ibv{!1ISH7 zuc{ZeXdQG=&$;u*jtyFB#?&d+T-Z6&dZEWuOw;ZGi)U7tyJIr@mcW#nb*@j&+yY#| zy#)D6=vBJ2N>07Vvs!FP^%nUW;+Yn|mLz<##5ZUU-;cqk(?IwhgU=7b_}=>7GGm?K zoKQPeid62ZF2&z+YQgVJ(L6AWlOH}q_fNB_O?(*u& z+)-}MZkJvw@;D-5-cxZLk8`u3X^5n?e`bW}VaJ6G`Cw?dX5cE|0RI9Z;=CVKB_!QP6RqmwPa=ep9FHk+Qx?_`= zCd4PyW<>l0btrcE3(FUl9gpni3EC#UDRTSJXV4DeI}%MK%&aK!gd%;SeM6T60RyBD zDKWn6YYn>P$SiN?&jZ>y%*fR+1MeWQvpzwf8GZL_6`hd$=uY)bg*t4@V61=co@YJy z%zR3OVI}6?IGY>=ySOS#P@42HhmaZg>Cx~V0ka5km@ig9FcX%LloDJoBb*rA z+bE~nu!y0&Uk3+)O5#19?ncKGxj~n%Cn^xp&@@(%Y#ufbnAEM2ZBOtuJL5o1t8h|OKt;q z-jzvLd7+<1lG}j%;1*Qw-0-IE_V}BYDd${i?Wbmm+6T?`<#CE0Pq>;3PLtesvK!*( z7AZyN<|ANiaBc2fZSD{2IGCqCuZf4D-=?Wk9jjLZI;saRrqm z%#I$x-;fp0IA*?pqhR3KlLUgI;sGiA-YkTCHKz}4OSN_p9I%t~}y4{DMZ5XadK67kKEDW8 z2!{_)dO6onIpe;-+M=|n)Ns9)j&xf#21qe*k81S%k@@vKwvS(gfM8$dr~f0p`)2Po zAili-DZnwQXE9Uw77092xRV>WD9@C3c}gx?o(HT#OD8T97C%wI*aHnpFH4f`nKyn5N0(ugi%SI+Cwr8RiUl6u-Mi@MRi?fc z#gW17qnBe&AmkdShhdus4H|xjN>E7=?=_s$i&o;>;5{ghOj>3K12x)_39=ZtTl_I> zuzC15y3@q-1O!&5YSIPN)7R0X6Io`k$p&~e+}j`{>&|d|QMx9)Bt&t-Uj~LMrVq)W z%deXsu%Z=m(WPVL_&R`o%&_n46|{B`Tnx9u2H<0H0m`vy#2lf& z0!tVBhm}jhuimZ*DM&r9JG?pNK4gLWP1qrS!9tEFr_QMkjrRcz3T*8Ve!Glr{OX1K zB*iL<3QFl{quGqo`Q;vX=e5Gg^)(%jR0aVBvzVsN^<_YCYv7rq>$k-*P35)i3iVM<=?&)NIQ%1}yM#8|8{u)<=aYHZ+<~PXJfqIO|c403i;TAPV zWJ!P#u=;>JF)SlTO^aSf|Mizz(C!X888NX6;|q?80lEZ`d#w`(P=#?^NnpE0XSLyC z3m|WeWVY(VX!UoA?NrI@<8+JOw-SpxyfYW*48Et3SrM$>(LMY0fZepYe-Ex}K+*o? zi29|X3fH3&bA3beq{rK{zrKB+?Ewth4oP5(!ggg(z|%(^PhTK{DghiNF;pCv|9&$W zym$l;oAIIAZ!lJH&%E&iQA8NIkjfWhB|&8+A*Y$o(lcMI++e+zu ztx&b_5BQPE{P?C9_fmEUU&p`(xju108!58(aB*UePJ-`elWA-cauQ;0e9;OBpTx1A zz)0Fq&quYOmg+P;Km8NK`e2HACXM5FUUk3qO=lU45#!Vp1M zEdSU*BCMcIa>YJIaFU0YXg#!Qrc^gWMvQGn0#w&A(pz(8YlH$lY67+zmge2J{-Mv(^W14>)W&P7!ng}9HM3r~GB zXwL&ZQrZ#kJl3IQU(cR4n0^sHc#t=}`5#1so$L#RR5L&bwwv;eaQjP#CIn{FZmU%W z)mXiM;z#*?zfuHJ*I9y`X~$Fan9D+w0j-0)WBTr4gZboCH3Y^l<^#QsBYL`*u6$A6 zNv)mk5$lq84SP)I2dj#T+ju`ThO6S7RDAEc-Tmj!4rVWlkJVXdw=zYZYeIZ5fa6QP z(F?czwV4}==dU;-bEdre4h0>ZNeiJBpLLA9q+4)3lGh}k;MThranW25;(>8uJ$^5v|lOsk8`^hWu7L5jfNelWo1=P}h%^GB5%&D%h2a`sP z4enBXW57$(53iPp!(sJ(>O?1A`vsZp2bW~WmiS^b7f}n^)EQ1zuMt;^_L%_+=u-yu zw}a%k{Y71m^^WLA?uj)Cd~{>?Pf(lsaH1GN-cIOsk9GQ&7X7blB1&MA5MZ`X|^|A!5_J8vt;)C zXw}Q!8hpBe2W*Q*ydZiF#lIi;@yIFWnNGq#hOEoQ53wH-?EvWK+S@Ny8 zoatpc+QM@B7SYTps*RWXztVBdoZ{N)dGs<0m=wj~@iV>RM_W4`S`e57Z(ojoHMs?r`GVpLfQ`^F=aMn4b zFLBA7;<=n{KiqAD$q8_^0sAeXnbYy&Po-D_We7}CNSz$wnwu8fQXj?{qqj#=Or1He zqze=WwoQR}8U5h2tYirNDLvozXu{_OhlV$F>GP8{~sV7rMP|jDK2hsM*)2X;BP55>}oe z?49nowWM?eAGX~?ts4;D){MD)GU1*X83RLN`AKN*W1Jb)nT#(XuL%7aP6_Zif0H<% za!?6bNti6Je2NUJq$I0damFR=QD&C4sRY9!7vX3NEnewHj39{u=_%dl;q}jWhp*X<&6197V-JzOd?0_^-d(i z+>GbW8jrTKi!CO^#b+k!N2#G6$@8$+<40ie+014hH8zBEhvD7>0RMyWOEA}gykg2@ zIKZblpJZpoAV$6jXHIK462`b2!Y;~!8YUb=#>AUGecowQ#@JKYFQCnDKS$;l09&<| z4ok(>OD`Ewi;vj}3>Rr%#|q7g3unG)9Fg7-7saCiW#uV~L1nI!s?d6~WE5t^!`ihb zlYXI;>a~D$ZgF`Esv}a7pLr_&8shRaR2F0+WqCyjXmxQpDhe|a77*+PsB5Cw?1r%a zLgHTic_ZPcB^XQdeE2g)VDsi4Z8z(8i?IK^j5CnmJ94#k-J^0It;n|ZDdk78msQg5 zHbv)c9{ObHbqYuBXg4Gkm=C_h0&*RG&!0Z)AXQ57>h(YiglK~qsD664rTYCI9c1f( zSJ5H~iYS4zd4I}9t ziF0U;4bOrKra<3Ya+ZlmPsYQWHMTQcN+Ub7oMbV(*;yB;2vO|$mv9br_S>57nBFI0ob^5bZcvJ=%6MbyH@Tsp@(#zZp{rc z$$!II(A{UyFKO>^7>#?)xI2bM>c19z4#~V=@$MqR>#N`dHw@DP`v}YKdC}whF;cyr%6G4zQiOGup(_g55U9Oy!K@rG!h7;LCU#*urelIUQ&8NCQ*9bfQSIiYx%aA= zEC*2URj@PN!IuiI7&TeCy>geDzHlr;H8n}voW)5t?I_SU{b*TiSu0uaf<7nia;~o) zV~-hcK2Ni9f$j+Q9(eg-oxmbZa2Ds^qFcTCbL|B#Tx*RmiF-C*#_6tF+Cu40bK<;l zN8{{nO>NZp4D5XD8*tkN#?eQg%PVU5X*J-FRi{d&P1McdC^r9~@ZJ(~T}A%J~5vlPI9eJCNot z+hc3Ta>ybzhtbKtk^Kl{On2$WYC%X!}875&mlIBixp^_dG-`-g4~Pfq#1e z;}qg`W^55vC|oXn6qcwSDFIV&tbFYvRwNVFaPziVzacm|Nk1BlBqftDAfU3m#s

  • W5P}ryv-Pd-)4kWc#N^FJU&2ySMMfjEoZbdemPPIGzV9fJgaW4ouMO zx0`^PDMTuQ9+UgQ9!)TcctHMj%ONC}i187Ek z&}V!MxIhWYXD|h!>VC;&D%ofi{!6lQPaiD={_?Z@xaF)i+Ll73U2y^QRVmJ}Yh5j0 z^=Rrh`7&zo#S7L8U*7G^`n77DF!pYdct*%xPz`+pC789dk{M7`ys0h(f}E|Hct3Xq zIa!z^aX~(++ijluCqC~^Fg!r?+RtIw-f=wHjtwM)ZB;y9CUL4y`YDd)X?TN7v@a&D zj#8mY3|T>#Sl${nmkyq-8iHG8<>umb>v! zZf$*xwtwc*N>7wwis?PQuoRNQDgGf3c2ITbj%grAZ;Trrd=%_yCQy}P{U zUwK=8fsR+Py%y9>oK8|tIT`mSx47wl7q8D3;A>?VGg!xoKpO=SzTJt_%^oymPmA}I zp52KPD#i%2I6^q;+&>Y;_Atj;K#}Y`CoHwqga@qxvVF`7t53zGM^b~dr263!cT;ZX zq;v{Bm-?mZ*h7(*WLM zkLj+*E;NrjJJLOM0e6yZbPa(tojHcuU^}di%Lc-1wt@+af|119ndy4#OY2PWn&Lw1 z{)h(jVeq0(#|fjQnQ3;WafB)YrtzrcB54F0)j#nBhwR_}7f%b6MRl77Z%6%L<#A;z zy^NsOTZ(Z292G z1bxcWyUXt8w;EZGxJ=NwUOhz1>mH4ulcb$fc#aW&cC0t#)sR}mFm(MNomdX8#}2>< z?gP51j_X=>ypMaiNaI^vywRX)yr3P4FjAb`ljH*aVS0ihI+R^7tw9NDfeNirv#x(S z;Om@|TJ-M@s7J#7|FHHJU~w(mzAsL2*B~JT2<{F|2o^y?2<}dBhlXwl5ZppYaEIU; z+}%C6yK7_J_-nGV_CDv_wcmH&yO(eB>%o|FRyR|sYmA!pFW}Pm{`2pK>5Jd)Qu-(@Dq#vqeTO-Y=&dJkh%VY||1`ikP;7MxwD{%lLn~zXF(uD!_b}zJv8ht3Be-3MYppMsw)xms$Q2Avpe2_HJIaOqN^g^ z*q`HL!Sg59`TTUOecc+hXeK%FQ??JO0=&G!;x}!9)MB%Tt>oVRr1XI5<$#_GVl2u zb&zD?J=Y#y7k+jicVvQ!vJ;D?B0oF;LgdeZkDDG(3Q152H@$U8d$28^&ZVO4D$3}V z(3mbg#6j6P<%`(s@I;m71$n<2#0?8=JPd=j~?J zi2q(|V@&h=kJn$2pF1L)r!%YFqx@OxUE>DXY5?djzkT;mL}lpK*N1H?(bo||s9u2k ztt#*yuF?AgK)3(ylSuFN^Nc0+v+G@T{3WC_DB{)iCmh=CBV=6ShqDGZID-5UjSQdo zhU9+k%UuOmS3ZCD=Yp+NMt5lyCiqtX1fRB$GJ`--jyIY@XvzddE6(B}07|#9n?Q@^Vfwa%N z(VD7ITO}V*wch*EvP4aUZrE1W-604AAy+K}okwEoI|B>Spa2fMR(I}dY0|rN@ zX$_V7@*5q0_~bydD_S~%dkUgpWOs?P@EQ!kHBx7U+Q=rH>cqIipuh5<95qC4E4I!u zf?1iO9?LXmd^2@qhn?`*g7BUoH%b=%>R?g$gIjI{Ji0&KTAJj(>DfPM0#@K(#X*`0 zaX;kf9%pi+8FS;VaU&9OV?;;6yA(p?B=>*8j|D|fyZpM}^bhkD2bEm&-+eh^sH^cQ zf2X(INrzW}a6v(QD4&B85%lcslf#dzDUAP!9g_c-mH)KY&LE?L9pXc|e-$p!fc{YS z4pia2cMvs4?HitXJo&uc?&rFT@J@3 zJnZSvIbnuUH-w_h&Gd=Pl_oD;H}yLAwk|}v-!S*ZGeTW^>lZjLJ>e|Tu#1gf`$blJ zCUdB#viS?IcF8E!ZRr}f`_MDh8840yng&h2&F%Nxdhb_vCV5D(sq7i>xfgqs%zr!d zWrI20RmPX43T)wb*~&pp&pSLxSH-bDs^B{gCgI<{3-WsYVKmF1C7mZf?gqaW7&I>? zZAP3&(HPU`9ip~C1vA(~Lph$n5R<+^AWDEy+%cFra{k2}jo>QdJoZUrPf-m{bte6< z7k6YkpESbtFby7!}buK!2P0kfg0{vQBM!lF};t_>%R#_T{Z-ZVXipUghhS zgF%WdObVK1a1)p0r1+h&?y0%N9pnzuouex51yE8@6_T@iUFp$3no6`sr9Gy-w=JM_ z2ZasOdTZ}OZ-ynBy<@87?pudxtDT+il@?Pot#;X0J-9omh*cUL+VMi}yBFiTUn}c+ zU%R>}Eu`C>^Ccp!67nC`x5hmWiI62CF?IVWqeC=TBPS#C;T{a1n8H4?vFam*l!N)Ba8T+ZPXqvLq*5)<@?=wEMsgU= zKB9`}k7iPeYthks2tp@WmGpOi_aDvUKn74qSI&oHtOQ|d-S)ArhJ3CPmVp9Hr}Pe; z=iFp(2K>Lm{NgNMIrg}T zb6WqXnElHn%e>F@{HNg33L+>~{SI3*abN`>Hr@^qObt1UVJ*?n z1Js8>eCqA|_Phf=yA(!rGdiyr$&6%B3v)k_kd$U1sSz8=(EWvRUy{o4p#;oc$Cp2o z@IzS)lnoEU^1c)@O0W1oZ@~8_%Q${XtQXXVrR+|J$@zccT#;1;f_p0P73PA{0F%0< ztS9;j0vSfHh_Qox=_Y9iFK2`76CSBQZTlW%&tUcfOPT#yg1>YQW;xw67Jumf^UY z{qmklw-t4l=}JJwajc!+*C4;whW%WBd3p4L{n#N@xQqJj7c(>qvrlGd6?6G?W6Myn zd*QhS8RLTkT~BL6e@fPIjr8I@o4%;XpIfjd{R0d2Jq&f%VIQXzvE|eH*mjahBmPOs zOYX)9TF<2lV}}Ecq$)2g{n=5!Q02+6pJw0qGYct92cKKXYV!6a{M)s$?a}-5V4>6P zbhAyWiuKKU|5J&{lmxTeIJ3`u^jTx=@}5^ugvcokpN093as{l_t5-)5h&x+!S658s zU%R;qOGIYg1{c*W&irU7VdnLov-xotp}1zHJ{lns>8*1BXi`pYEBNk{S->$@=ZZ*{ zSqBb{EEJp&pH)0hbgm=_H`l4Z@LngVY(G8lke#5PtqirT`sJpeds5mDE728f*!3Zo z+J7;%|3n1IBeUzCP6Ky>K7F)}lD#l~hjOqWe!-*YswYa@$E;aZlZCstH+CIt3Io47 z3M_~n7d*IqhIfhB6MD@&ZU{By;qskhgJ^0MH2zgf<<%u8`R1WY(j>wJg zKVkB)^_wxVQ|0c7a*nXVz-R}RLc?gsV}-)es=!~7GmE&P`>(dhcc|!-jkBDrSUTL) z0wS;IH!>Dqbr36vjdl?IU&G@GJLdf3MykpW;Y_u;M}(7VEwh*!+Nf5n`09KP3_t5I z)ndDMPc(FC3RtJ}=iO#--4lc|g6aQ8{l&-K^pFee)gZVV6 zV&p{PW4bBa)WC8oX4%o#%#+PMD1F=JX=@oRJk zzOaHK*>z8?qtCQDfRUEyx?iG?!6=vSSCHRVqG+Pd*53Z;*wC)^to3IOuTB=$F&!*U zcu9!l3SuXC916Aa)Iy`hcYerBind%w)bx1Hd1}kQIe){@`8{tj&ucY*yeiM8b9{Uu zufDSq$M10!{?rep*Qrmf;}Y$M-$ zfi~NFL3Ff_TH&hn5m4W6?smD)k(vz3cmW_dPvEGFc8_E=9-ZcMPGOUYCthd_a6^`S0zjjhXqWm)Z9zd{K6ywBm2vhVfD^_kPN;=RdF zs+@9a$2t^yM|($&w$`WDHOk(eOs|(2O|Ac0-!l?CqO=Q{?oM1;cyggIC_hMi9UA9W zaemAcy5({8mTL5J3RohV<@M$)R;Z2o*IsCf{>+%COv(Ng;2u`8<{hH9g&S-ub6+Qw z(Y>4F4BXW3q*5Uej>9@N0I+@Xx5xWSwJUdeF6I74><)(NPN3)ev;o^20hA6S`u%m! zaP29_dsRUJo@HCy5Qs0)z_sA_Q6n;Gd5Xf9_@W$x#}GmX9}+gDuVnKLKRi)tZF8hX zn9mkBJkf~^V_qhAW&JU=K22qut)G09Rk=0;VSlgXQl$6xg$cQkX zbNNj~Ue5|w*PYo|Sjxrdm@rVF+B=8_fIf10A||wSL0-@kib%^28FeJQ9-HRb+Bg^U z@;l%s?E`Yrl1}SCb2?E=fj$vK3#&JoXISHioz{PzIJ!P)abm^?EC(e*-O(3OyYx7! zn<-%1&dvRmDXOWBzRx zH%6v}&s=c9$x`}T|7;d2g%v|DAL-Zr;>#>?qUojzKgcWtpH-%|N#tB1aN~n@rS-{1 zr)175?Z6vV+lQi~vu+NLsiW%V?r@`|)VD?^YF$8jXIQIw7C-tstw;6eQTC3qD0zsa z%#3>EvEzet>A8dAgW9gr3J1Tcnf0V`@Mi6U+Kf{(bqFt@ zj?@x}1;at*t7|hUY(ul;d&PUKUn_Cl4JV9hsWo?HG9+RsjN%Q+`mv`pHfKp^W-d8& zrYM2Kg6Y^GH?|^@w^rY2L)QZ|$YOqJ9n3R)WoEu|D-UVSCSiRfDw|4RXWF4n0a24} zP#rM+EF~*s@&{!t5ou;9{PejLl7o*dW#94oCJ>B={oA!`TbT{`>BZH77XWL;mmpt7 zmy%WG%}-FCs1)I+`|S@aH8bI-FQAwyRdf0gcEmcjgqoR>R?rJ6xP5V+;FV_F83Yq5 z69m{je^@wAoMdG6cux|drotM`*7@m6D1d`KR{zD7IWN&+=MO8&jWiuc=l+SHTc09v zRm9yv2tQ2};D>Di`7*hG?FG0Je?octWi;|%`|E8boJK4$t4~jSA-rSAN6jrmNDe!r z?WV>W(fHJb#7CM|h7gWw!ScxHk=1=-6B9%_IlVD*Z#M;4E=HIs0!d$vSyoONBeYcOkC4HUl0Ja0Atara9 z|0G|&SpX_wJFAJXcA6>Hk8z-hc5xe>cBB&eOutNF7$y|$#aj0_G6z;R$nLXj^#~ie z0qYxd_vy%bWsHSUT z?>%06AT_bX)GThktuLB`-szu{?Nv&ea}?U)LbIv_itWJ97ZI%AE`LY4U^sqLS^m^R zWGk!NMGV3~p7{{22^JQc%Y5*RRw~^s+AXUuzEt&$wsNGl8IIUKTTS=FannY>8K{_= zM3Sl})i~ds*o(`cS$OQx1y>2H(ktJz0KZZta4i;1Q4PhVHh<%s-yX5plWeZ&EFF<} zkRUlNRbpZ@oLf`buSpWMl$YOKdCeI3^@!n8?<@EBu#d6493n$=J37z~xi_G!8;ik9 z(K^>E|3lL7yJ&O0o3*?8$JJ(!FMD=9Y=Z2tA>qm9riIPbHWpL1)s^O^+X>Bu7e%`F zGZgnn{EI2WLyv5{XJ^*6U*1UHeA9k=d79)fRQ7b^rW2@=MP&DEkpR3Qvre1X%j}p> z&gR4usHDqAOQM}W_n~}RfI;P4*;}i!;M@|&==%I#SSh$^9eDexLHUay=7}sff=3J$BfqC@xIdc5-s8wPp8ZPt2yA-w0~j`Z(Er2@|5F-CA1%fs!I4Pf^!6 zZOfa6x~DE-BDDHjYkMG`{yUSHTL=&U81CM>go)9nZmpeyKq-;Kr~l1aGPTv%X%2e4 zhder9OC%S4wS-C))A|#8pMwK4~VLz9HV#T4qm0g{OWp-)m2zgEQ4a9EUm8=E8-O-Hu)3Gj&rhqR75^f6acsq+;z2 ze}(`_%;x&b`8aR-HWiXwI&0+S1$Req7$jH_0O^v8B%P|`m|GVpbg4PbEUYmp5P|qx3xUNCO-49bnDka+S zX+n2_vMyqQW!}%BrWt!CD=*8rxPMhJ70dZ8Aqcjy#os4R^h|kPmalN&}aggmS4lz4e&7b>3qbWVOF{6Of}&E%I2A3t~(r4 zH4cgT!A7-8Y|!A1|Kem4s=|n{@ik6do@Rv4lafx|RJujxqQ^Viox-VI=!u#?^60Q5wEwO2%202KnSeMQWk5FNCb(k)h(Tyq{l_7{9mTB(gn|a zTtt6X_E96$M~luZf;Y6FmG6u2K6BzpxltK<>z=~LE(vQAh^tmi38V}j(EjwsO~M+` z1_Ew^t~mqV8a|cx{m4aKsuT>)$N`;wi%dBgRcUJ6JXWj1YcqZk_Co5?;yEqO1~fPQ zuJ5`5!}N*lE2GcPWM6gZ6VgB9MoLzdHYXX?WN=pN)vJbbS4)%$>+k4KlGqB4X*HwI zHOgz;D_lU_Dis}yUK`ndjZ1vC$f(5sef?tB6(;VvhLc$I6!z2TnsMH?AgZcg(xF@2)GElj;T)Y`ElV&l*{f< zN>nL?2u2Js!5Je=|HiH}Jg0-QnQIim@&{LRNyuAmKzl&iEy=9DF3PsI|D8Hqrr`xh zxr5B5cA^?^H7U1rwXIDH-pjNDpA|(moeOSWvDiHxJETU?R5=?G^l?MfLFBCwCyIN# zs4yQsIUJFqy4 zvCyTzMV>?C*WW`XOlJMS$+4y+)SkTZbW?0gjEM@$19c=&!h4HHJ6wUr`g@iFW=NgzOo=MTUiHds+BJe7cN_?gD2P$&V^+w5ZcLp zYz)KTYrXfm_nBM4wFrQV(88GKaYC2Pj}gQk0dA0JeD&K(47hJ7X#(VyxnVeBxJoV2 z4`MqvG?>SHzZDurkcJc4@&Tdw!x_8fxmW*W8c~!0QQz!0_g(PAbuDdK6so zWcGlGYa^dRmDj!Y<#~l&Iev?7a1n6$^&1lEeB{a9z_t|j(;7;P;r(r@6v%&*WH*1; zPciPuC=fk0|ESzRU>+rOW$Ktq3@P#@4UOMY%i1xD*hj`WOMouxWf))h&~tJdQc+_A zw(GTN8Z5Zh=ofCyE$J#IxDF}><8gz^bP8t9DU8CN@p>t6m!AcYKP^Xcox56ifH|U^ zz9mu2Iv|6kcQJ*c%L6* zV~YK=8SS1he1R>7H7toGhR4|wddxHyXW`HAAT7<>636s+3i>!eGs$3{D9qE>LFwBH zyTJ`nn71!PiR&)+md#Qkbapu7qWnLbi*ke4xxi))Q_?B^7fV{Ev6ZZK&L12u^GS3> z@~aDVD@`Nf_lMwG$hOfAWIr3x5B;x~z1)MYy)j@YA3V_}QXEo^?%j?(pSOh0LkWpj zOrxWI$;X_JV0}$%@gwFtcBk}^qHRfGxL~_(XDnsLMzGd08gtZ!iCCkzr;W13&>M#J zzPSl)M6(v#h4EbsBY*GM)On zNf5rJ7)Y@{{8^Lh@#gV7)m*KZ0N!RhQjPyG#F(a@I!M)#KzsG;jWB-VGl$oNvHvRo zn7}6juZ^Og{e|9~Pq1gfN?-pwPJr%+dY@y{9&xtQeu7EMMloded{s8tcz;L_c)c3U zhUlf(WLDto+$>OB?pwpDe&X(olVs*ivV?cf0MU1>)YOSQ`l-r?%NwnHA8-4e_vic_ zU6MH?6DLX+VrQxh#5`I(vGa9=rz2&dD)ZWXG$utfi9l|tq<^F;Orw&19|flIm-%=f z7p|*QO16))^ogz%Z#j^}O9PB`+-X7%pa@{BKknrK@ykD(kj#*n@h_q5+}XwFj@oZy z`n|%XMo1E@zF*YT?G(X9@iP>AMkZkYsg!FJU473NU6URT9!uhGJ3bvl%86$+4+r|w zAgi^W0wQ0+%S`5fMgk68d#gq4-QU?1?N7ioTmQKMBmWo`3*o;pfcLlc+lRG6Q$u#> zcZ~?niIWQfX2r>2hUdh+4XMrgXJ8iP#3_YbX8rHOL{^h0lPz93X5jf-vu_N%eP1a| zd&7SIF2m#%fa0rCzI-M2~XP(hC- z_N2f^P8acOG?WaTVoK@C?=f{A!t}_w4&BZmNP@EB+|MvVX2rd`@0Z z1rhP!^`tWzg-Speb99?*&)1(OuV(`Evdic&FvVU;A|K!3{8a^w&O2p*;^QbvH3kV5T52$SeL88LF*v&0X|`}r*o}Fj zG>UhHy!7rE2X*P4wb@H=x`=oiv*6Q$LPQ+fCkKAF2WWhh$s}yZz&m z%ZJuN3tX_CuRYnG?1uO-;P1R<=_4;Ri9mQ7{9p0G=+$`1is6H9y_gtUvrqR5hWoE# z<8z%UsAl=|3#y8i(_^HDAe%-M8TWW=kDxrE>!?;5BxycVu%+j`4k90T#F=MX3$M8MibQI_nY90ysJKAJ*OzVhpxfwtL`;R z)JAOYN&gT(7i#wGY&`?djlb1oi|x9TbFm-0v+d@6JTkm8nQ$r1fU92g++htx)`rtM z(rk%}BPvleSCNuVOom@w@(Y(7&-9Ds)X~H+6%32AraOu6zcwcU^<9Iz_9V7y3v3$a zwr`-Iq}rtoDtC#Yq)6Vag9MEPxMqWVvvjup(=kpLZ6@R5=*!rio3|!+3_SOQ@!r7$ z&C;9tTIF6<59fWhvf@3+ZSJTc)Ab+&ws?#aG&$CUaXsr&`SNDY8tQioTzpprKmRwW zqgr#4EubnFD+n|=N;dj7wr4Z(e`jfWd4D>TfaP}LJ&!8kUvEe^j|^=C+e@(drnU~R zcpI}HeRM}l@!v{AO$j7hmZ_htey;pE*08oW`gW`L?$qQS`14+D#ye$SLg^xv>3aCT zxNp=o_VyaOsw2hM$~C5zKD#8gWWy)gYJ1||33FknDmfMVV7^eF&77~GT%BMu44wm% zc{+Q>GYVqh?Bkh;J`%aE60CiYWu%vO;TWMjyt5Zd>Hx2;n8YE77m;0z*He4%uSRCh zl5^aRCwGFKriak2+dBp3Q{!Yfync1!>g=}^a~dIY2rU1`qTLjg6xn0@GDJAQW3#5W zW&3~uo32IEecdjvtYAt~yV;(;?&kN)Wq{&`6`}_^i=MK5T@)U|>){w|A7RbQ@UtpNQ zC10j}J4m02C}$9DY_b-4|c9 zS5kJ{$l!F^Gr^531p^gw1Y|?}<+Z(0r}KeEkFLTL?gI0HU5fInBE!eiq)oVUt+t=^ z3e2r{n=!&9Z4N4R3iM~cNgpwdUiGRd%oI1K3{^SZR>p}%9{9Ub3#2w+7k|<^h+hws zWs>045@vk&AKyOk?>Dzb1KD*#)&2*j^V`%&s`7(?A#pkX1FnJM21*aYe|8A21s8~` zDQ#X8)t_o|F4k_Lf$8=L_|S2#-?)$IY1c1;4GHAH=oaj1-wS|H9MQ_x%R+mYliYL1vqgPrI0nlKuy@aP)n-Wt3iE zQw2#O?Y5v|{Hr1Rg0hNxRuti9S2h2aWBx_di-e_&K)th(&_(RA^+A-gP&Xnd{GpOX z+c$c=_~v5HHF8OiAl}Nlcm}-WmD_>hx3QKkyks8DT!U4L^Cj}F+SnbWku|I7%neL6 z3ObM=RvL#NRc6#4!!1q?5@ntARnFSYUh&t#?2EK3N+W%qY%6y^j#(lbTQ3xB%am^66@sKaFkbzrAG2Ib5%FgG?&{4;C1gDsg4oU#M7O62=Zrp zTxVQj#RY8_yWkq_qsh?Eo?)V2<&1HvXY|c*iO2H2Aq1oP3qrNVO5W#glS>q|%HBD3 zQVRqNhaee{G}PR+AvJFDcEV*X!@K@III!b`3c=q=!#IpT4-r)sNHmygb-+7xq*ZOy z5(FUJAS6mP#PYHn4?Xd5qC%le1GWzZ64E5p+I17xPZNX~4(}5O1GFqv?Lr`BCS>k) zLMa?xNEDsHTr`X?%oSSRWRS$Pyw^Z0K{$$aC(-khXy3zs0ZlMse;yH|wUPK!tpCG0 zs(pG96-DxdUewf!%3qS5lT_E-b907KMJzMEFD)eLD$?+^CO@GSU}Kj zP~qyLFK6_Q2rlexJP9K^K<)TuRg2&`XpPwb7Zz19|d7AX@`+Vh?a3%j%h z;Xi^EtMn%VE0(1ise!5FK|(MB7FKB~93wv{b@NC6g07Xdv))l@$d=bfD>hUOqHTwvkFheXuijjD1VT4aa?l$gr4TU zESW!$Hc-6({Q2`V+(*8GPgn#5`2;JTKJSfMD+@vD9Su29#;vH%LVu3>m1<{{cdbCa zCywd|{!kF*Y4EnCMTG-8bS8NrC-o>=Q&UrQ=CawVxhDwvoq*M}qpz~?ZP|O$!f&Xo zrmb%@OL?@|u+V-QJo#r>?U=Kkm6Ke}VBT8K%&PH!K}FW&f`fu|A z#$U)$G(l%Cve2K3=EJ8;i#TK0;31$1I)3pP{izuKiq9iFY3C;y$OP0u+b^WiM-iV= zO7jI-;Ez7Zkd*cdLLqE&R$S zmXhPXxv0um8KlzeL4O?i%JYdwhs~bob^6bUcLq&j@O|ATOELzMfzMyEqFMw|uX`6#P~` z3OxqT2MN!APJ|%O`_jSZ;6A^!DHl0!P!umw8QvQ|6*&ieC}L>XByqc**aEAn&kYJJ zhPf>#y95>&7bn`x2db)*4G7*f-psbCR+r=Hy434eD4d>;t_&hC(5zR9?A@2?YYNWQ zVcm!58->+7;57uqOpPRTmmFKo>kmzu`yQpcLW_qv^NKSPb=O$xOnak*W{ta-QJ}O< zA+`d-1pxD`I$v9XS_HDyr-gMMwwILZ!>Z<9oNpVNgQ0?uJH|!*Xye88I6>h}g$Q7@ zaZ?>-gm&u2q63sidk)!X0bzzRni8f`QK*IP>t>yW|by~Neou}hER+H{=|37 z^7;1tOx-*+{f+vVg3*kUzPpHheYR`SpWga2-a-2kau=N6Z#{eA-lLwop-ivCn#tkE z%&V3zUmo{0v1}Lk{xfnfD2gsfaPptz`ley}vOLO9n_Vi+#1zR-g9}TDV~OUcm0(`M zfh2OZnDkK0U7IWE;H5p~3gMHxxd&sn=Wi`pdb&i5lQw+lYO3n=&mw{rjQ;ZLEzOa2W@ zyAaDZ*AFk`P|s9f=%b!l4TJOM`umz5PRQ@G@)rhF!?ofr-BH=_B>}I;HuLk%wcZu4PjLnXr4y@YEJ#Mpdf!Gb zWUzk~WU>pbdV~9RkwlyusPE`{_RR!%;%_mxzSYZ_LH)Hp+B1VXXE+JK>tX9za-lbR zI$L6UL@nOjXy>_}Az92^sJn75ts&rl`|d`B3VyD$7* zJm=@uhl`}X6qOk#7EeXf;k(2LUB0F${u+DjA@W*@X=mq| zcyd-w^qKSjkrQ5Kx+2f`>j077cT5z!&){zqcb8zqNAe5(T~W9m^OUz#W#Y6QQccMO6Ysad4bzTQo7c;p*VZD z2vv}z2~Q-Q-Ln3^^oYr^Q4bLWD~syJ z7l%zM+%w?mcPkEQ;Q2o-pBB!3hpAb-jiDe&g#%~6PeqIdiq&+M~C(MHi( zzDB`D!CAIsrLD}t^6T>JOm;Jluw+>S%Wfo}P+?ekmohH=&o*CQ? z+=sX$r34j~;iPnl7?Qx1bF+mvmUFyfGARPT}!D9uTK*T215_c-b zrnQUu8XCc6PZ+?qgUXi2P5t1*-B6dJnWGDM%=Y|EkIb4K#Bo1D9CSot24&q7UgF=X z-vmu1l|&dgKej7`wvlrtt?=1W8AddtuTBWnQSn8zmI)Q>%q-7Q8chln>B#^`gfg2# zyyt~N@4+RhK-!_!T3FhWCrzCY?WSS7nDyDbK6vw2{z4m>VDZJYHSpD1g5&EoEuF1O z+?z(bmAOOjDd_F}W2eLWmirC0$feD@gY!3nx?1Z=S8O?{6LQ9Ae6O1U?H?y*Y0Z6nq=`oW?y zg<7lA*X}=;?6Ub%Lu_sbT&EXrb5?eyTc?K8{8A3?BHVFPv`a9l6NcTqnHmr{JBDDa zH~g-UB(i#N@Yca;pgzC;b)Y_~yumy{z`qq@D;@7_dioU>rG zyYJsE)SyFG0V7-7V4AT9NPKF$uhi0HZY7>XOpVIwNh>CDNv<%IWioSqUnH1Y9F0>( zAkf7)T|vc=Xy|0^!(Ko_ma(($;4YSez@L%}F?lS8p%g%=H17VB9bPBQ-;SkqMgOi9 zHk~qth+I-~PfeH_dTw=(e|adSbEl3f;5uF7#zhC;B{mckUZCxrQ0q1s3({ov8#_ls zfj9dGBn@0J(Smtw{O5v)Om}7tvFg2%P zSY>f5kIBf&+K*|acRD>O(Ib26eBY7l90b+ZipX*03{*kCT5R2LzY4z@PMoJ%z2Kt4 zJz6>=I1f3BoNt9~iH#+@!}ik*-<bs%4qU zz~QW4CtUR$eJ5rbGqQaRf+9wsEv5MH9awVS3x7{|oL3vwm-pc>|4zAqSJny3cl8}7 zh*%tL-er{Qv9AY1py8FHd-E^xW6TCZPb1F#L8}8lFobdhX=m@)Z5r=-?OX@}eHBOO z5xSoqOu|EL7-AZmdT>&%>s8f1?0PxFAu+dMUVmf#|KF)Qy-=kA|LwVHE|*%^oxox} z4U`9)9d#)m(yDOuT4eCM*6SuEZ$irZ#XP-hc|_5-d;xsFxvMv;Fp+(0_V1si6RIojYutf>frf#B zetEm0vrRaDTV9{E?OAQxsl7G>H*~6g9ZkvoOpWnltGVag2)Wu%t_L;es`nMEdln2& z2k+{BWNlv9sII@cusx>`(`<~{oo}()@TMp{70oNBDRqU)@ z1Z((4+w&;4=B35X<@o8@ruzR_Hl7uezfSV_UiZu++*`Ra`Xk>c%wug&+4zJkx;ZET zKDSw`GAn=qzz~w7u2^z55PYtdyb~>*SbSM>j<(n|JO>3{1MHTz4z3%-1^s^CE(eax zcFlY|wDhOke~_uLTTs~*FxAUQ;1=pP2httRjeB^%C3KD-X3F-8+P^lvlEAztvo-u<1U=*O)Rr^1HA z&^wxfNcxdiqjC@l2zPGlwoz{Ts}vba?mFUF@xC`eOP=@9qZ2Ufanmf0%->(o?#)5a z(Cysqge$R6B%_$eUQr(5P4B_DD2tq{w@Wvz` z2PZwIVahjB5zOneVpX`Ju6&oG{Z~WMpMwoW=jBPxfN^ znI_w>{(IwS|DkbYcG$5t51>(MAu8jqYK=ZN5kpn#OxZXm@?24M=fCIz&@7Rav|2$# zsPJuS>^CM88F5{&yDYYX1!d+G8#&4NxR*_+8-9u7jTWd%}tzz zVLVN~C97624`HpnzE4ZV>gZJRAhM}7G!Whr6c!%WuF!B^4zu>EEDN1$&VxTUAHmIL z(}20#T;_HweDy2f%B~?>uT_BW%%^K(q#Y|e)& z<_=*z!Vz-nX$7CJXr94Xt3VgnZtxB>uMhwtP|?WI0>Q?>hEw8em7P2 zS8F+oU4@yaY!0;#7eO|cS(|&M`s21VLG*o*Rq#h|iqyaRO&V3hzu>9D;qnL(?GPbE z$0mj?ZO5k0<_cJBO#Bqjsn(`fD2L_F3cFX;MCWAFjgs2cDeB!Ge`{m?UyP{92l8cq= zx^EXNPp+uGG@HnDNqBg|rLfO4@>3 z7>>J@W`|w-oWmpBqR2pEh=aR#tr#FDDSVg}9pVpr#Bp)Xw9pp?<7uuwy8Ejk-V?52 z+o5g@1cGmbhp)w&w$1Nbr#wuo6}vZ`Zx|xM6pnN;SP((bQDO})GN>C`%qa)KNx2q> zHXjKK8sQ4Am<`uXtW~eLmOyc<>4)#5=DzpbCc!$5p+{Zfa4|bWn&!3=2ML-MyS}~X zEUIUJ2R+U@zq;x)@Fw)uJY;|V)xh(R`$;j-(-9^=&?9~S>MZhi%ce`EPx<6Sp`M|m zr&y8RN5?Pw%NG>xjA})2$>bF6;#aP1p`gal61O6#tA-x!Qm$Ise1YDmColubS-4C6 zRj>}syQoEbuaQ9YJ~g%CMmfTdO(CMiv#%4c=soa5BN8nCJ4+;M_qpYFXSbJbOiUA7 zf*cBphzrRh3m6N@Ny@2n6_zq@XGPN+X+=^p$QZT&&N`+ae-#abuhu3w3V4rWIFjxw z_-bna=$0Q};xVRnO<-+Fjef>Zh#UEz=&f8{*;VEJ*wz7hGm!I{QQo4hBk9d{+h-2> z{{i>9&pB_KA|G?3r*N$7+?g;aHgTk55mhFK8Ei6`Eou$F*PP?d3{(f;_0}w!x_p`U zQ{9S@08#BsrJT0piQ8ZTHWB`kUlYN()+KhV3#!R3$}b8h2H z=4!M9%bUAiefcQ?CSTOV&5mqID6l#CFlHnIHUo#{NGx<-!YpQ#HXK+YRe(te!Flm< zwxI_GjM-*JERkb>g`U1MaS7phAjQE6+OaEHbnRS%<_YoP#; zX#UaTA+SzD0mk*UpM5wMV77}s`A6*3!VmzDF5_Gs030p;HIKx5y3eFw_QHz5#BbHF z|KLMJc7sCST-G1V{s}9O1@d$hHyl}FRqhzS_y29zCiQK6;K*?l{^ROf%KDcL-}Ha3 z{_n1xd2b_rrH5^rx33Tzc|0j`^CGv1DZ;;wK97$x^^nRIG&w4WoFa~g@?X0P_W*p} z8Z?<~zBMa0=|5)H(d8HhsO!Jx@7dnlXFXT_zzUz=T?D&tCQPqq+kc>;XCU+eA^Yex zKbnjzzbpiZ?iOU5m3up<;`WRiW#jUm$Brga6vab~XTazG4{L7$700&idn3UuxI+Sg z5Zv8@gb+NqYjD>F8VeS*kpy=V+}+)s;M%ymJFiLhKIfiu_def!@4I6#el=@WcaN?v zYOT5ETJ@g?uln;XUX-;B$L+@R_M7$-I&q3>4pr}X4?FeR5)iz^weCaoY4LS_hS2z zthaN;U5nG%B-Q7jDxNVRab@P$yPLqTbTl{$Rm}P=P{W#`4G65}< z^wHswI(#(}7DNJAYoSCS<2mZ_kwE9SU-}mp4=Cxh=kMW_blT1H7r1^z*ra&&AaHc( zI)@=%d6U`(@gdDM46l^n5Rd)yQ(PVlOu&~G(Pv~7N6&dMB2OW}yb5d) zdiL;glidCnJYVWw0ojjGc$yVC^JS!5<>;?}g@A1?n6Ot@ANYT%wCla^SC3WGC;`Rh24uj&*vC=(KKBj06d?OJ<$QNdy_5+F1&Q4|X57 z9q(JcMh`|$1sGPCcv#-bCv9E-dBbNzRGohfQ&#qF8mc7b?2OruwY4yg6RvbTP;1q= z1GL7wBOa@OC6L6P4ml+m$D$wC>i)U4iN%2*cb-d%YwYb|(XeJe@nNn@Dj{P*hcbJ3 zXMB@qaWNR7cn}pe%%RjgJ3hmXtS;@67$30LW?xb=CT$8tjCBJJ8um<-uGVKH6JOrk zUM^1oAYvk#+V`xix+o4Darv!UXvSvDQoiaM?5X>=d@DTDKW5RWXL}pwb5mj=;u01t zzcQo`7z~erlXl!>ub0FivQ;^+Vq`jDf(xweAyM$AU%3B8OTq8zLAZg!91M3Sse37{Q10V98?YI_r#UA{fIryrCGu z_h~{r6aPY<<0PI&2cwO-6sgXnMd%@8sT$^~EW+PtBWRh)aGzPSB zAA8d8u@hlkEAMlDP*uvu!>tf^BKxQ|{l<9EP<4V<+@}k1EO4s3@ZDJV3Sf(6%x$28 zjO||Gt^sI!GvqcE$8Ys7gHhqBACB4|p3ryr<4)%nJ`87{L24%dIMabZ^Q(9rRaM*S z5r7|Bu459QPPmmWi~;9HGa~9khI}TU7AR6zy}9?4B6`ZRgY|{>KvSzwB!7(ES7bc9 z6OZv4aBX~bQrwDviZ0)O0QwF2E}99 zPCnejaiE+{w{FR3 z@{MFxs?i(P0b!foS+#1x&72&NB&mvE-1c!i+2fa01@hcs1lp~ipBWjRfaYkHCIzdl zQP{!O*ML96aBlZ~=PubiuuCB;AYa?kWRgLGZCC%^4K8_9v>Pzc!Qt$ObY>C9@@Slw z->ABeh;7Vxe%IeOn!q>9_!9$vJ1}G`Lfo;3g4bwN<>+Cg$#B+1`Zj!yZ>rla_~LiE z7oFGnyDABS_WMl^=B;B%QS^(1k-2B!uNZJ1>vF6_Wr;Cw2Sr6B!Ir1A5wTy-dTq6xW8))n{X|AG z!!E}Ghzi~qiy^PEba&`>+#gQqACfRKSf)`sJ4@G-&mqM(=EM1x4y!!BkS}*%A*sZi zM(<8;>VsY%7H+yS59g~3a`ty08wu2R8((rS)}_o%B%yCOa%6TJpK){g8nDs)!bRO` z<_@8D+~~w6Xmxs*GhcMisawYd0+aDn-NDz8|H_g4sOW{1&&pHKL$AF+AVc*=>ft<6 zLvmLEFwjGQywF%MbTF{=nwgWl?JW767UOgqiTf$wy9*l!znAkTkz9XIEAf#hsxMM0 z{JZ_DZJIHd3vn7sfa@x)F@1-g1L+FL>AA8V?haE_ErB?U8 z-&_HlWDP2J`tGDd#XvdEP6CjX95$Y#>>rKdS~Ki*$O)>~b#FTXNX~HNxlEzw{-sUK zllWa;W$nAW_j}OX&+W@SB1j%{%+c~VawgL>eE-cjlCLDwRGsv4!$nqB)K)LA`#`2c zn4y8Y@)4xi6J}v+_xUcEUKh1BLzNWHJf!p%?$uOgZ_mj$- zzQ25b_0|94Z2s02T+v74CJFh>x%X8Nc*(m^>wQ$(Toh7N9y7_3J7@1Np`(Ra38-Je zLz5i1r(pRUtdJR+qtK--(E+D4FRcDuU4xQqmeC5wkTyu{4X(JRyfAYSHf}~{sdjjm z{hRTRL-)!u7|fYK#LHUn<-AD>xw5wQg0{!dqsQ>0Ri12TIoOYe{uTI}g8G*}5hc8g zvghCYbLhoB4d&z#DsyD!87obM=B=Ctiz?w}Lw|ni!mTe7=we5i7wI$ZO7f_;6OBlUOEJJg$;kC=MQfn=9H`m3#V8 z#=tvg=gw{g6cEH`S-j6w$zECEtYuYnQ8bHNX*21Wyh!CCcC&G&`?G&6f9x=~B2N`| zA~H{5p%^c3bD^UC+b!kgl=YCuI2xNMYgoJmtDJEHo5gNb9$%C7$Ay)GL{i!V(_25w z_Q!jshqLjYRZhn^c1zd@f_6(GSF%1+?XTicpPm_o%W7kfrbM^@Ed8oS39WN;UZYWgazXx@FfZz6dk8c$EmV&i-E4a=VzzAeK~u z(?aYhY4Tyz;=-{gaMB9uq3VX<5d(kVxukuQZpgW^J;E|KyoAaIzuH@RbZR_=xz}IX z_rYH(JTkZ^$U5C%cVCw`c@Fs|c|hx!|KMKis-I&DQ4A7KRXh7zkeaInk}P#x@@8h) z<>-?FBSmEnZIjTux8=dysW2Sjr>^!zvcQxfTJuwY(ot^jYGmtcS&tQV35KR%4Ipl1 zO%@(#xH8D($4SrvV8c*Gh73d^cwUo5HZ{JQ;KolT3EVjbbkU~PgqsLir!(q`YZvAA zb2!yzF@hurQ+d@DU++5d*J&984HjNcdi?LeTvCQ1H(^In&r*|?ux|xR5C1@unlw8= z%va(+K{Vc!1{>{DM!Gcn*PsB_QF&^jKC$1 zc=pByssNl3=a>pvB8aq@ERMckOcUXZgfjHCPIfnY=_L~RBO~OB^gLPtG+@zdvc60C zroa<{uZQVCjCJ=vTvhVdpT6oA(SY;+e2pjJdMuZ`C%?HX4R}uYdhzn6qcR)=i5b@{>6zG2ooP^L`>9kklUxQ#kG)G@xinVdh(vhbH;}tR) zu=pujDgS}?1%#SgC>Qdj16Yc7N>+Xf-_d8X;l)+c1wAcqu`m<9jEFsxMca6FEhKyl z9gHCl^j?9*Ay2!4>O`Os{KNGkp*iy+E#m^Bhn&->yq!O|8Y4SSmIm3kIPogDXz3!J zzIv+!uJG9*miK_&(W!*nL6>*&u7e#XO*?>cLdfA0UV#1=SNEniJnkoi-LD=jyQ_MQ zQLtZ0l)jRrtwB*C(D3BYsN1BiUCp;a;UeU43wK)Wpvl`rgj-BJHa}V3Zm{FTX^T+j z@Ht$}JT-4{N#_`5EO#n#e|;Oxn-9+R`NdrZAf$LbSN zB%=GOPACbcpW`ZL1YFK` z>9ikLkX1W>q|oNMxO$I)rwth9VAsm>oWJSY%;EzYdz{4Q_NDOh zv`v~g{S2OA*k_|yC!Wm^ZN@|q72D6cVVse&E_jSGDc770?9HFR*zfK$vC`K)+0oB9 z^{N&!>z$w|ul3L{YY#iKIN3{1+`#2Yk7zHMEVW5wFH=XcIOydL+IhgVZlOwkC-jcYc^0>PWe%QQ zgquVoCA!LCo=Yca+>b79F=>yi`YZK? zSSQ_($DZ(^aJ;~fyjiJe-84@|YwLT5cifbDsX3k^2b%7tySj61$GQyyi-xBUE0=Re z#rw%z7pnJuR{)el^O=tmgmuEIIS6H@$}U^b0_pgc0M&kSH}uKN)atthzIWCKq~xph z0@mh?6|coSCMY6{+^|wUWAUSb9R!c->ak^IhOEpFY^@b{N$;FL3B=Et`=0u(o+hsJ zHSZJsTou=49m~Ctq?afSrMn+&)?CaQ5}LiMU$?Riw>1wolRVg&bbGMruj8w!Y*y5i z3goM-w6u+_s&cT`IQ)qR{#JM%Zpi>{q|~%Ou$d#B(TJ*z)EMqJt0&g%e|OMzk$h@T zyLngDJU4qeXw&ijwH=Xt#QT2I)l=zc2e+|r4sOwW->F=-f)599!QU(@a*C6tqUJp; z6kWpXw^Pwwo|~JwRHt2R4ptc%hul=vp8+>z`Hr<6S5A%OUciV@ym<9@sOUjCdvDWGUfjV}>jo0V*L{Tzro?&Qu2MBQbSO%pCRLE`~QfK9(r`sL^o}mB@B=jXbInz z+g9sLT5MSC4}5>uqVV*XUb8<$^pF4+h;P93@%WO5c<4!|mz#VG!+?q6g5uxcCX{hW z=_X_kX2m?lPxnTI6YJ0wyA#g{-^2Zx4-FaAIavNofCe)z&A|cdy>0N1_FEMb3-kj>x;u^{RX>BpphgCG)_HB$-+Y@URkQL%7pd-ll8f4FAfP;DNY zXS{Ce&+pDpdV8NQW`92tgdHc1iaf$m2B3LwCH`!;y{% z0ty+gKb(mLrO=FGQ@Le`$$i}l!ul6yQfU{V#b05*qzldBFR(k<$XncwYeiMRI8a#+ zoeJWcs2KwoPr5pL5k#B;=Wwl#3-UkB=gJ;nc!a)Ll1Jelhe59-bAe1v%h4mhNsqw# zTMQ|!N^|@x&SSJ11Bk(?v38%`*orcOO>z?hZ$9J{``vt~ zdAo2xo2SeVHrS}tW}(`6SlZR;@yVeTR))?)mRI)9gHggw%Y#ye%b}gtVp6P(t20IF zH(64Lh>G`g6JHVX!2;0gb@ohLd=IFF?Vy8EX8C393%jjzEL^62&js|EUU=?%$WK3? z#E@1ZnC||faPi(Q!lOa`Q>u|l`gbTQIGQ)YlF%QJ+_=4_=Vo}8z6kDC{VW*olN>btgw`AukA($ zSI#*YY0|Y!=K9AK&?KYJBVrw>7MFBNV!4&672bc(2U#fFmY=bR7F|bitTMxrAvlL< z(xyIwqwCduakco>p~nNdmg&VM+**_OJbuJ2jJ>Y#0m{EP(|$sIgU?|X{sB#kCU55b z0al6Vm+MiH)++m5xCJFLs=TIm-%7p{?1{RtAWDx3^fmp9RJgTrZy;X8Fw8%lSE=$Z z`yj{PX7CFJJ{|k)M61bjKylaK$mVR%;)l1` zycV{~qqO9y@xS)MeX@TW|99p?tDtE+9fw!WYY}&4(_-^yBybY#m)fE&o|M!eQU9-*FXNkJi$1UO5CsEyNk-!EY6ei><#fy zs$J>oUrT0n%}zRr!YrAH>{gu=__~(H%9GRJlWp#_Rj4}kjjk!LQPJj}s(62=P6agK z=A_MYtPb{aT5xGlHJ3S|d*|K_c2<61-1YoH7v0>~J7HR=nz7x7dmz+60eF#%+_zT7 zT3euX{Arig7rpuCcAxUTWaUvZoqH4=AS!>xUCAkLhuUwUH+)!e>(eDxQDgFgoY9{4 zzP9+};^3mTW7%cpC9d`!>>jL`s!33})_As{v;Y^>>aFVK+tSAR7VQ`CHJ}>M7oP*e149D@m!Ntv)IOc~#*ce($#Kav&V4$G zjVgQedA!;wM-q`0YH=e>l(GEc+%nbzWuI{p^Ysh^La)rn$oL!tY%%ajwq zH~Ud8soK6m4aBs?dD1v}&y6mdu}B1m_B>TVkVsat=sf{rk&nePZw(oBtC49V+mbB{ zBu67d&14*RO@Y9sk2es&6R}yFxU3R~@`%(NIJe|X(?V+ddLGWDoxg^h%v;C@!7HG- zMR)ma9EO)~;F7+Y-Ubpmnf|>302L21Me+=?Zuu=zNGFZwNJqY9Cz4@e${DkiyK#qK3=V{)N;_O58%J-A(%E_?!t!gy{U9D8M zZ?w=?Wqd4kU(Dh6T)>ri{DtYC*W0l1ZqXgNKle%QQN}V6nkNnkq9-=s!#`k>+T1F7 z#7qxGPUa)A%%X+}YRB#>*08i6m*p|fCaF{mpM4{-|FzsX5H@NT-+odq%7P$3lX8hB zx;k9;A=|x%BWnFgSu*u**oB|Va*-EP_OrrBi|6ZdlH@xOU~ay|b=Q%=a6@^+Z%{Kf zo;t+2tSG=jzw8Zj1}?!U@}xFNyN7WeN9uYzJ${QJ$(V>*2j@F%iy+rg4P%W0{OOC2 z_Dz?zD1+*zLn01%3FRtOm(7Vr_tEQ#M|c%+xRY}Y7o?MqaEBsKaurvCiV} z>s)m&HZ)-j+rVkIa~jCG^TpijxsQ2wTecYLSYfOkqceXQp2l=G@GzN%b6#(RcL3He zQ#*q;u~>O_mPyWS(d9HsF7<1fZub#HuNZI3`JvF+2QS{zV+4@LciRz)-^x#VS#Hb- zX}hF&^a^s;!k3;81Wvl**bgC&t+AIjAa=ENGDAXKsb$t0lCJh=H89r9gG0a5mvQJ^ zt*AY%(s6L*`sfi-b^@+ia%5A{-REn6Y2w%kh-=AVPAPVr|5wvi08UE|dP=e79Otji zr0naW5PhU4fjr1F`;b&<(;TuI5>wprP{SkFaX!ex!Qx_KgaRm27Fn~W=LNnO-CwB2f?FkH5m83pEl1lH59Fox9hQyi3isi*&7mSBW7E<%J;6XC6sO(Mi&|BD& zsXf}>fbPZ(yJA;Y#9P!)*KBOM=q59~5|%nCdK3}%7myg_3+%d3fxw@ z&~m&zzXs*M348KL;7v^q2ktI7A;q-vqOWqkSgzVG(D^qUpk^ zq(co@&~urFz3^+)vzbO9P{c6|CV~llqa+TOmjR=!;FFgltgMtqODm6yn-h$@!^)ADET89#=y1>3!28KUVT?BvcQFu_?3HAqr0RZ3Uze}}81^J_z-{Kx)(F#xXqvbem; zTT1DQ|6c}ORQVDoN1%mHx?**7Z|xdlHRcc-!@+g0hf`KvY^f2@nJ{%hGHWIoHFWgg zY)z0?aRJP+IWzf<1BD-U4E=R+u<=% zV7u84qZ3l?M9zZ7xH#Dfc@}R~(gF6+=o0sNd4 z6s2J}mmjY4R5tZqPZ~{&n^YIBganY400J(!spSdX4D^I@+Fc)Gfd@_9kQ5rec0)#p zs-w_{4d7t?V}RU}qTnSP+c27IDwA1YF%)PEEAv1@CxmMNk&R2V!T2bEaIV5A$Axvm z7(fj-&P(`7#YpSaAfS{hT4qQ@O9*xnwT zk~LttYO)b0LXBbS;>)8SIQ8SL4+>!ptYC2wwqpR}2=2}@vCb(&0i0pO-dpNe0g`}L zre(w{TxJy`38+fZnAw-^sPcS9gnVVq0jtrqx~DVXS0>Wv!zs@)y&=a~lUm(D%N`>d z7t-7)L!2_|=0)_iv~xxY<>Tlx$IQ@0-gL{f7l}Pl2^8*V@~TF~hTvUwSs3#I`g7%& zn-6MjRUanDL~0c0&D#3N;ssb!keo-HdYQ1ow>}EdKjar-hnwL{M8F_%$fKCaFNwhK zr0vT#XooV@i3m9Q9*n@Er(p>`M>p{xxWfwf)@_YsCV5Ifu#>=2LR8jz#SC!RTY8y^ zWPS1npWC5539X(pBT+vUlaltyWga}kA6urTJtQ>F`Lo|yb3K5hTn2EPeKpln|0*zh z=-K^Z{WC;^9%cA5M$^wFd=t}Z4?tIG`2Zk$K!1|* zg!DKy?8mh1I#N$=H$m90;zFS4uJTTCWe012m+ z??;7+)hX4iWnGkI<6vu&k~C_~aMZkat;7{XKZbSeq+0w!_d^_r_Qo5*afby!7M?i$#gfL-${ zUBe0|hW=eZ^X`mE*|yCB6juVg1#&9aw{tW4?9;kGPw%*H#<+wdaPy=9j9T5I4ZQH! zz}odO+6ZnqFR7i?fC3#qpy*@rn^9OGSyj{5&e`ZSwp7JNS&#>)b$k_4U0-b z^JViwu4M*OmK6W|%0>Nq-6O`Y%K~=c=YrsM*vZ@^`oU6Q#|h*zgIBTB?8|bJ3Wfp0 z!#n{IRobw+@m2-JX5C*lA;F*zcf}V`O#(1Ax)q8g+m!Rb`}&0Qukl7wDfvDcRnb#c z-{yS)Uy@l==bSd4@mU1SB&V@C`V`6Ad|g1ROMGy~*fI;4Yn)!3W1sd=t9l?}8(4ft zVq?=?Ms8^XKL_c%Z&7~*gHs2He5FlKQg~&^Ifj8N^WB$2JH$hGnq8rd`iHNFc*F1lKP#rY%N{IJgwR*mnpVpj zu{L0chC?yT0Ka6?&XId?X@Yl)S9}?bfgM+zR})Z z0tI{$I_%ba`J|9c0r-`iA9T@1m0BVM;Kj7Ds-X|Z!<)br_~CO0K;*^&ggQQ|(EEIk z-cw6X09X}h++^Pi(u%`0kEamuX$z?_YzlTA4s~1%#8?s?Il=^@nu6cn%0i{KnH=!| z^*4B57C?8AZqmJgPeN>BamZ)OQqx8#CThOX{vvI7Ufm@(lf~j+EqU-+tACZTxbDyZu;UL$hDF2yi@07l~{_8qxiZ1%oy@@pJz<*{E{2<-fR{AqF*Z9IKY;&t! ziBQm}-uN1FrjQQngt{4fy zRIBx`V&B^b%|Ep~)4kFWeC>=`Zx76g*7c^*dhqRSbjl%TyDB>ElJll7H9q}>nN9Vf zjlFl7UvM_`YpC4`cezMP+X=hgK$Iaso3fwH^@09Eh?t;xt=5(-Y4{Ys#UB`0y63`j z8|EvePL6@Sgj^HlQS>>eKo?RvpwgD~RtFc}0lUi#|C3 znqis|>etj(q9#7W6r+LYP}eAy;(*d3V^y~A##|28Xr&tEOuK>c`W)@jkL>5-2{#ln zR*_^@8(DJtbGcb83q2?F+})_MsTKi0n4oUhJdm{DRTB&n9;9>;*rtUbcM>DeAYn{5 z-uP4eVjn!hzvevfc;A|A!Dy$G)xG^a?{yX+n5AF^rzxrnk-7HYPa}U$96T-G5nzy{ z99nMvd=D|SJlIZ!WhhTupLy@8tX0YDJvjGv!4~d(0+Wg7dP&L%aY#GDPqKgHtuJk9 z?g#?ftrdx+ z!>JWf$fmXTr%Q@cwex`137(idV#N9LBgmqf`1V;;lS>-MIgO zNEH*S==|&DH!a{=xkQJBPVZ)iTx{)zj*R1YnxuQCDnr=*&kYU6 zPXk&qwK!dd1DM=PZU>qigUm~5k*}LKV}$@4uG=X(0leDEo41~MdBblabdlF$+xRMy z_dWvfx2jPN<6)5#nk$2EA@Q4Vs`i!NWu#(oTLu1heTXxwp^F3y8ezH3DD;%2>c9!# zZhp@V?S_m=sh%~{ic2S!C8V^%MIdxZZZ2MbmI4W)Zxm$!X=m#QvZ!l#Q(27+>zs>w zJw?>VHtesI@m()Z&o)Wzv#_J6bzo=gsyt~&;$ke!r_t3PDKsfm*g{k5F z$!zA?QzMMi$2=`txgJz3F!zQFmZ0JmNMXDK-2OD8>aib$msNZ3`zHLoz z%)54oo^dD(DHW?5lGmHaQK{}Y4Kw=cwbP&650ij6D2M@BEpPVKvu$5Y@lEB^va~aQ zs+%?}4}G(QZTiSsDHBn+UsHf%D!i$h_Ac8nFI-}cPiJ}Nhx|j9J}#Zk0oH6+Biq9y z(7DKX?o|2hd-l611BpQ-*8KK0$34scgPp6#^B#SEp~lAS#_Z=83>OCaNcrIWUgaQl z7NdP~_dEi<9Ro$0c3}dDp5>*qCT(?&L@dH1HZ#8Bn(9jp{^4+u8>&BKbN=Aj~YbT+zEoa-pCw&{RccDN5UF3almz$R^pQ=4P4&L6TfTzmI0(l|p;)#aI^ocH-TVGOF zG^Y-1YgU5-vGp>J_non)qxD#mIt;Uq>eytA#yH*av=GaqS=QaU(kr}%!R}CGE9ao2 zd2;DN&nPf)@8t#2#p!$#6ce@K+0=e>J8R4*xW`mZ?TZg;-v(wrRts^4ePw=2`^kvb zYUfStt@>7Ms7vlgacj*qql|It5pwvJtlsL?sZf8OuVAj<)eoG#nOb-3SY1{ghK|;a zUQq~D(t-BzK#67z<4?UoCwMk+vl;m|p=f-nh7?+Nv-ZB`{vB($Xxt56H9`Wjz^vGI zhzup9pF)mph3Hm71fy;Lya>8Lu?Vk+=|oW39;lUk$u6fI`{)(qfpuc01#c6*+}v#N z=jOJ#7t5qq#3kWl1*;XGFZBrN0|E5saxHN$%7c*D_NwFYWdu&M%#0S7T_zjHFzlZ$ zjr%lo)3bJc6GfLM^wk<6h@vO4G-tX4RuZaZ`OuFpxi0j^HnAa?njt_hK?avyv-@~- z%l6U(gDo9>z+6;hvKz>+%vfs_OijsONQU`o-%gx-r8aOG^Go;47MY3Cxxf%jf2nbj zLh}?s=5fxO2O-|BoZW<;K@p*zw`9ojeoozFpB`;zgyvaM{oa-kmgv^(;U82z)kHe; zV!YQa=J9LXAZc6N8P%A-cU^F~x___e(oNLN6KK06yK*_EPYszzu!R&zLeYDv)xKM_ z-sl43~!0VN&iHN<0@BHkG zYEC!Mw+|{|J$abwm9i>@(aO6xHCW2B3nOJQm${`+015xBE_8X1(neqF4CQ zCZgAYhRL&(=eprX>!$lG#$kbU?lonBbS}$%m_;O=tAi^&mW84q`HNx`A$IPm3-|hbNr@R|6yyW$ZvDd86_A2fHw3FO315ieuXI&e7xyKp+b$`9Ol_C^Pxxg)Kvv(^{*Rr1JJxo| zdO>KyAkq(e@&4c8SmD*+ly3Zv zENCr_l%%KcXlpadY5>GUvzMsq$w6P>=)D&VSThuXrpD0|fsVoc9*$Q#jvYe%H2ni7`jxQnZMRB*ROCa&We?g0IsePtBSGB7?6yFqs|aNBkISO8!1w+b zxkoQ?1;4jR(Kh@C^c%gqIUr2SlpA~}CnU0dp4%Y!ZA#bT;`-9fI0+*+>*WMHeUw`W zuuGtP$VF8qHE)}X&iH*Ns{1fAIEhq{G8}W&&o+QtRD5=3Zbp-P2$Y2FzngTJ#B>75 zTE;1rq7*<+ZcL)z)hBYa5k=}GsE?mII27M{@JHzoHMbLCf?Z@Cjq4}@55||7i^V;> z3&q=>6SH2K#ocA?`XHwi?TQW3R8Plq@Zs*c?wZ7OuH8!9cq!1@nRR!obmeMo(e?mM z?qI*IQM+R>IavcpQGDq$sPI7rYr9s)BYa+H)=u zC}HgNR$x6Lo4kROSPbc5eo09Es@*S@$n}t_tRo@vf}%`BOyx@tGUoLQEZwRP856wl zU2R6(NU}a}m~mzO&1_3eoeUTQ>6VFVFb_U=>%D1!^YT|df>fs?Zh6&WQqkbi%Z&F35cHUuVq8E|UKrbHP46E5X}ENcCq|&V zY*X!mq(8-Q#^DcV?M6zOu7lhRsA|nrD*S&HVhKO`N|f5w^H8NY?og`D)Eo{$CM|^L zOru#faGx~fv;Gq6Mt)}pJirwvH+}}1vCpjkt9Y$BePm>1RHy*_8Q5;h4HLdLw&QoJ z_lf@l6~nae4=|;A><^QPA-s~d{r94@lEc4Zjx$}%0Sg3 z-3cxAgu)_nx;;-rxis6U(J5rQU&E3C4_snheSitBh@F+{Y|YirW$1jl?LKxH|=5c@9u}mrra|KK0!uv+=*a1TS$>a$QoK^6h?0peaKpjTH*6osZuAk z{{%%U-HEH1;MAH!^1#Oiw}6$P)V?ibQ3ZnFHhCOE?Z{E(s8RA|8$iP&WDQHsh$Qj*~!Vl@%5mSYJR<a?a%XOKvG{8+2Lbc^gmp=?6~|gaB_y6#H@y= zyy`-I5wTGXk68*v_g@N%dv6j7ihHhtLyLPZgMt5oy4PUP>Lp~_Yu1}YA{^9njL9QN z(QRShK;7&D8urv?wU7i-i|D%qH+@nnj;zO3sdl4x_8)v>DXZ@gOv2>eWvKh8wuh{# zIGxZoiQ}phwMoUJ6Scg`Go#FEaX$U3z27)MRiIp@IHk~SAwI9Zyp|#{Uv5zTp4MxZ z={bxCRJ>MHZ+-cdz31W3N-#ZRF9bzBD|tM1HElaM9&0&^B$(=2I|}^C=MzIi^gvu8a(`VpP#^cuM3*Tm?Q&q|do#s$ z@%tOPsE3}bV`bu}U+(HynhiNq*$6npR_}ZmN=^<({>gEhfc~;(t;gm4LF|v2*1rsB4==&qL%sR}DLOaJ@f`B(w==Cy{Z$ZB zhnQ)gBr~Dx=jdgeILM-FCGJ6K?6CnY7E?MaVYq$zp7V3MysJ_f(3_eq3C~v(RZ?;SR8=Qw~!qB5j*=5;T7c_20w}*Kfjc9{e-sghXF>RWVsS4s(4X|FmF3X2$QNaSL^pKK0=ybyE9{^yboE6+W zfIqEHdax=zYqj`Bl{1Xn+mOZ1S-7UB%2dLYr8%5zr56DnOZg>CK(u#I0y&lB zK-eZEBfzfakrg-80~)&DVar=vW)c`MTv?hpUPaGmJoOO@6b+-d7LiB=yJ^TmfxFA_ zHJH|)bz26Hq_(^@msHeHt6TSv=&m^Cp|Jb|7=JZM?1j%;X@@f#z2+9rXwtSVDvO6j0k)`CV8!Z6QgHY)D<@ zK8Nf!GlLqwuqo+4NJ1eAZu4Z`l{xX&VaZ_80ZFUX@GM&`IPeGH2}<*+#{eKh+xh$= z`Y{L6Uj?&VK3b~~ov8j{7j*buM9dH6?g<&nOA2MxL z9>-%3-hVSto9wdw7!iQVy(EHn^A`O?-kYLA7>U#8LD*{GBXRjBY$JrW7t^SaaSy6b zddo$`Cl4caa`j0Gh=vg)c=NH+=bI*@el;cSSmZSLES1W5U0;RFcp^Z(a(x)5{RA=( zAn)VgJ5kf}UgFmNHVP-6@VHl9?TG?xY*Z0}(DB3VkC39Y{Ji~6+u#X6Y z!AXaMPe7hjZmpxG^3hjkmPMrt3q%qo*X6|Ay!6H6XzHpSz^P738=7@y4HS16zV1?W5Xh_jty{ z;g+oAi`I9BBxs?TK6dPTk<{;-&Vk&a0W2f%*y)$b8D}G$b3p>cYO$PFrRvtV=&N(h z>lZFT9_*GF<*qnntC!ub;OH!Ct^urDo`=P!T<0-v26S_=H%B+SNTRt#bgyC?y<}~K zzh^IhG%W{nygr?@6+%5x@+_JgdGj=1{6cXGZ^YdHq3x~X+S<0h-(3L;6ewQ2#ih9W zrcfwW+}#TVcWoHkDi&v_xK5&aiHxtOJZc82dAK`0Ow{hXH=-YW zCQv=y@T@fO4Xjxn)+{rkw?z}DuY8X)QeH#R>@it4x~#?2mm(4E9Ez}}NV>4~ib)N$ zN{j|XA@{w_0knQ5RR3_5>9Jq$-l@G{Gn(JWXZkx3AraIbnhdTo%!#5hOlJ+^8-?Qf z=n$rY|7Rdc&xr1?2xnT6sYlx+%&*2^w4w6L9lfkt0pz#yw_C(OtNPQiPD(tkri6T~ z(^|O|mXq@AhQ{kQwsemFkbTL21P^`$ar^z@|DFCN-Q`w$<|`BCWeVC!Lm&@?@EseL zvKoo%q~ymn-EYR*fdy;<(3xR03&(VuqV`&~Z#^an%6hB;9&G8*(p6!A9nw`_r!g+U zK3C(fq8jzd@N@A4$je=wKo)XzBcgK%6AE`-k^8<6RcP_Caqnj4BU{Hw!vhn_O1_Ct z{dHO!)YHO!7oNfKzLIroFR+m4U!$Ki8kgtEs8GqkkKuJI^Y*`x8pp?O-pQWa(Oli( z-1vRDZQ~knj>qIRvb^tLpw%E^VF>4J5suuu4Yp$5$hL`! zU!+c;QZrsNUQY)1%LPBB!Z=&s@;3=Ig;ZCSaZ-{mCkdU*PGkGdQfg`bY*gC6M8A1~ z;z9o_qGP9ZU>oa^;qUz$559C$Mrn#0(gQGmHiv72Yz%c~FyFo+_|ijJp$O!5(N+2X z7djK@JNC~pq}rosTLm(WjE1JLR^DH{TzNyFZ<_jBtneTHh+O6yhSM)5)o%x;)@dt$ zjuxvYCTM?MPkYJp*>>vu^A)+$GS#-1giqvE@t$UW_|RPT0p1R4&y{qAuX1rZUO(HL z@V9#p4YZ(|ceg@3Jp2>_uY7P%w+QVyuW7y(Tgg>+o@;X#d{tbw3lw9EmOu za{Uj4F-0`Q?+8bv1niucK5Fk>V=N(U*JP~-BL*THA&nUDGsP6q65FEA)ajlvyOn=g z`02JdUMswwBe-~q?i~~;8C^Ve0%oO= zW)LA?q}MkgW~S%>9-=-U|6VqEQqy>XyAPc0Bq%+NJq>$ClsbCi{3ef{V;Ex?qtjvE zWgov(#ci8%XMc5{@d}lR^VQY^lrKK&cbXdKx0feb*JqD9=qN8F-by4%WJ^m3@KXsO zM*9EsOj}5ck14(-Mw1qQX-N;zUxaV9RL^&cpG|xf<~CKpC~?>4^dt)t?5>9}ImdAN z?MA)yGVLQL>OBkj-Dkav{nAUKj~v@Lq5^+=V>W-psKmq%Hkm;T8GoMMd*KYyqKPMg zgo0QCcbQ-6IL+)Z4(~HthqnX{F~5>44f7^j`aY)|mw#vkPBAToeyt&@@V~W>4?TddfTR94i z+EMEt-65W>l&md|VzxFNB(~->wqcyg{S&6$Nnx5X*w!4CtH;$7bdIsMrK9^!9aJ&R zcwZB&)^dnF3MBQ>`rgjvDkx0VOCfvVtva`@Gcr-8~_i%y3yKpC~6ctDcF?6?+|4|BO`%h3ocHAI#dEGviqA;2Y&Krn3j4G;vqLzZ- z@&{9*hD3)0nFd}eLEf8cJ`_O|#EdH@7SS`=_Ih9ec12Bw#FHXs<6zK*l5u=N$Zxry zA&c%~!mj%_V~~&K-uwt=`Vp{-C^}1nkjkG4%#hf9)G=aTKvuOAJ0-vxO~T;2Go!FA zJbVBAQU7JEsZj0yF$3%pw^rQ?&F4tFZR$A10^V9*E>iM@W;O@zk?S$`TfML_!d!hVPIf`v4+yu=W}aA0SioZ@m%DAxIEq;{@A}2o!=iHB%*|NPDod( zMFZlfb+mTsIa_QUtkag`^-WN0?N-mzOonr1l1ie@i?U}KEo%{G?Ni#VT7-WcsSbdt zqgVz^WVEc7AufrQEXp2bY>`lJrd@hr^RAjMB(|kf|K(WXgTx1v5OPQaegwP_PTX6w zpvQt1XclOe`S!>;`Zj~UR_6dzi18!sZnN&jr!r6B?4&=OV|UXbi;L zF-0NbxZgp9f0zpBvBnok3XOsYIi^TO9QQep|6N3^Nei_6H&{pYX-$ja`(pkKi@ET) z?L#s+VdOzwdrA3o+kl^b|N2M!f0dWi{U6AQMyMWn4n5VRdokOf~Oe zDi{eM^kbT*o4)L?tE|v+)JxTc@;d2V4*}A3p)ot&j;RWz$NerY_X{-WrY8~RQHoUB zai0^p$1oMh@+gJ&cetTPIR$sbm*elI{h(P+g$z(8kUa@7t|5%(m)`;q$|sRrF2_i54FFn?|kzE-h0T6&aOJIs!FZ0V2IJ6i570 zMOR>4v~18TVJd)?O%9O8tL`hStioX%uo*tk%|e~0t&ZXBf%Jx8f_izmS~Fl6;dbx6#UUib%YRDY7sbJpYV^v1 zAt2Wk3hdhq7}lbY;CFVfz)*T!Y7z18_Sk`;-OD%=^`Cp+aIs`MV29r?XvI;2P{L*d zF03TNL*MI4+$SCfM$&szcS_-j;20!62U8JKj9z^1mEsZ^n@&WQPa4TaMWAJvD}UoY zspuZoX~IRG#m-7m@_CqeUv+Fa3Wn!PFv%BS+oCdhhoPdmava zFGTx}H^e#X?SBU&|HC`|XvI~kJ*(8LT{K>$`Y*lmT(+4GxQkG1Hyp|@w61vJS?@{T zfa%esl=wnAmGB~P48rr@3WaoMUGX`RgBj5@lofg> z`%Eym?eTTczFxP~3CqhC*|!HcAr}Hbezxq8~KUuh)YvvZfD*edY`3cw<~W23ERnr1$a}NL3hhtd&32rh<{{eyoQ`i zfsBlra$&S`Tx?;sDoqX}gPQccgxpV^L(9M|T_7zZuWS{q921+AJ@J<`W=J3kWId#~ zpozXF^+*_SE|5EK(*mX`e*4r(jYpfoCjA|V;`wMe0=e@?m)%ji4Ay6>w1a$^2Dz|jL z^lNz>t7yfTPf65&O8@x7{`#%=8xpBT6RA@FJPBkdag!62825fJu|M}h&48$bOUp8lopUXs3`z5{8aM!a0v zdkBJ()~G$(?@FfMV68KbrwXPgDkf5Er!vXQSSriJC?|ayqmHG`;6lxjrk8(hi6axE z`2ST>PKq7Nj-}1vV#twZ_-*(9)4m?XNf*c^3{c0?WV}NC?H((mMGu$AzhihSBZh+( zt@!nmKQ$h8#)|;%K~yAZ`o0&l)Dx5$1gJG{C9#H~?5t1r(R>LWkMfT;h%sF0p747* zSe(SX2)R=7D-UY8=rd3XU%ERas%Bs?mkCLXHm1$_Ce2{39FiFOpXSdMaC)!f>Zz3m6e|EGS)!!b9`FWf)S&o?KAKBEL4EF~< zTbM2GASxE~IhvBpPLSR*Q}#@Z)u+w*yIFfO7Oy`yCadFVDa&fJmBZXpos;l4k#%Nm zv`R%~9eoczoSjh6a5A>^;}fum(u3r>E5o=S^~>x-_P{svHI?Fv>!*)Vzhp4b^^ne8KVNLPLK|=*hM6G$Dd6|NQi?zJ|Q6iW&LP+&>#<6O!Y}n zW=mF!Qx4xv89A)}Sb8W#P!!?FAj8b+GIHh%!wen;vk8z&26t`#6mfO2pQ6N!u<(Ur z=8b~61X3h}$2aYX$=+pkSvvns4A^vf=7X6D5qfu?0;I3=_y~5Dy#+BlJNN{WJ;thX_eT{D zdhF~el#4sROq0Lz?_Xi`w}G(xH6_|ApkE02ll!SmmRznONb2PBhl$8~ic>>=ru_w9RCKK`bWO*#VUrM)|k`rMvcX@tvgMx?2mPCQm!ld~u z^;v3up0CiAdpVou3(xoESNXAP!Y)RK)fjhyf?FBf!qvIKQzs)yu}c0B z{f{e6{3F3%s(#f_*xN496Rs)Ba}8jsOf~6JUFG>fcO(Yg(@{);WwReCAPcKN z_v--C*1~8o@O)d;yvoy60kpq0D=gfUXK`*CAi?wYCr(b1()7p2tt-W%%gpqw?!Gny z%e2Nl-=|?K3%BJ#&rh!PTT4&-0JZk2Y4}!w=@x`|I4yTefZVUzY$^28H+s}4&y)9}@V9!X?QaSVJ zxkHq*{u}1|YBGdF#m=t z8Y7OV;d!3BT*Z1Sm#~gPq&kYW+Da))E2qmW$)AMR*Tl!F+-~+$2w!H=`8|!W&pwi3 z^h2O=7(0Tyu$nPB+&2`yc>dwMJ!bIb7t-kA0<}o($+fShi`?JviX4`V7sz{dl$w_|mu7c2 zMcg^hdUQ~V9#<0M7b|uA#N4K!&gCrs=skh-> z+s;YTANc4^a;>AERsIgR#k11+Il|$=~MY3rw z{Z%X;Q#7E)HLV1pooEZaqvD?;g9i@{$o#??0BN;YNpvTu?Lh?Tyt@Rc zbSv4{&APHlHquqhmbElPwb`@rT=UW9I%9x8MEtZJZVK3)??i3T@nOZauAX?O&D(k# z)Vh~o9_odlPxD{xN$x;XHq|W&b`U{CSWiP7L?Bjg!sV`zX4kbJ-Y%5lHf$5f;#;&6 z$mp#7#2$Nni#8~yROiEmy{Cl^Emm@N#N$Q1$GNa(%UxUICJQt=b0+lG>zY-!bwtX+!qa}D%YEKvM0-e73khS)yF zlJ*>vb?jNcdVEBMFaZ!8z(=l@@&VTY=Up#Hihp=PoCm7i5x;H-DC;9DVq#*P)~6GP#=qUkjQ7;uAjLKuxVk?%p}a?`ciMakguVYA)pygr<) zjuiy*nI4F#AKNQhIcJ9Z3{Jc6YU>6wT(?{2Is`zMHa&Pfh9lVml8@tBQY$Np0K1IK zV3?qfxryc_-I;|=lfGNJPn+JXoyOUG+>NVQo8G0^x#;7Y)@!fp2Ur%T^aJXWf952W z>Rcf`Gmp7mW}=Sb{ERG}7R{Yma;ORj&ok=cmOi1(Bph{}AqNfb#0^V;dcMEg3avD+ zrqT~fJvx<6-8A#wW0{%sY4W-i^=vB}-1#=;0jFg(SYJ;b1(ORt>@C=&Z^k+}pBdHU zv@RT8p1y?B`Yo>=>|FcAwUr&6%ip#V`OH|0_#ZExqt=OjQ2>u$Xq@Y9aud$-WEdQu zyWF<+FZ2Gsk;dUU(*+#=`UdUR_l{W7I@4TLVmA|4hZ0l7BBZT(;H+bTLixlD22QTv@RqJYqg^s`-GY8Qe0Yg*o0=Td zM1bPp1N7rC&{-t+7#3QNIL8D-y4|pZRkI7hk(+P(z_MTVBJXIdd%W7c!k0hu8Y%1s zwm2B8#~BnJ$*TDl46v$Q<}kLYt|t^;EC1h!xz}T{21!SR`_3 zEg1;R_vTGMP%6?5-CwsJ5P2sH++mTIi^x z#!|@Q*=^$2VP&f2Be0ZPP*=#U4&# zPi1>_O<{!03q3xVDv_A?@t3K#^qsQGGpw)Y)DICeo4cu;KFU(_t!^~h8@lG3rqN0e z-8~A{yDcB2aJ}qe@tax4YPvT1LxhVerPiKg8P;^LSZt|8(h};@38Pe8i;Yrm=o?JI-JXS52_lS?R*c#U9IU~3O+0@oS zPeEhXa+-9aBs}@=laF5MrO~WwDgTMFOUAi)FOjaUW7XQ!gW?${fAD6*NIK;WgJ*_M z8*6&h5s_u~odoL;^wQ-rj3qq^6W4?{G{{>5qKFdx#P}6 z=-n}6{lO3Dm2e_sJ;UC?*e%Q6fk-J@=|T08$wEjI@{ZZoxrv&Cif76gB$hlcORU_G zt2-m01~~vNU5ve1G7>eD?C8MMV)?ZM8ED=fL(BnYa<{Rc{8UCuRPzG|ZX{L>@+8<6>lQJ|7uL3?OMq8?y^?Uh>$dmOhx43eX!2tq4>yv zg9h)1-k=>dwB{Fx7|0q$Hx3_tSjs_2XASMQhl>jT!4S63|B=ykTTX?=L^&V0+SGn{e4A1e|(235QwmGN_CEj6{L zcC&wcOv&scCrdFt2CP0|{|D1wzADj>^Hs;j%tIaHRx}S1H6qp-=I6jB*hj-;M0ldl zhlRvmPfS#@D?K2Xme-^e-DmnLtU)$05g2c%Zsk_MWzobg>mOc!-K`|{*k zgl!R-c=pa5E|TA=m4~Z~a7Wr`_J5vUGPhBqEOC;PB^}2B zR(G>AJ0MJwVk9PArFzOIXd3vXXq}yMMzr*JwhRk6c<62f`%h(Z&}Gxv)0SIT&R&!@ zmmJl8=V*j(rUlfH_i(Er2i1fC?{x6PkY)XQzMac`(AWzJ=SM$eDI-B#%(V@fSL}ta zX7d|xxajIpoaw$BJ=jC7|NKGZv983g0S{Ry-Py`iV?|uo(+v62IV)USyRkibQmRK> z@8+oTr`M(4HC;xHd-;>0og>RmrHU%CiQwNxyM$r2c(c4Q75vn}jh&9YtGl)xIu9+a z;Dr(_3nD&EN>UWO=4nWEs+mw4+k&;@gs>u-gCK|fHo;Eb_t&&XuS5`N!dBPCM@IHw*~1xcDfn{3qd0XL3=i=(h)jmCf18I%I0@{Z zc|(-fs@}{=J1gkN(T4jbYgG8`e(q~@61p7_LKpU`ca$k#bI|Yr$1>?U^weugAMOAc z(+yx!*9<#hc*mU4kwaxOI66>HI>E@?{f0{dWk*Juyr1aJ(ih=$95;0UfLrSR&H`OEgJZye} zG|&2^i)5h{n-?tgtz)PjNwl{_^9v$apMZNN(WKr1gnS`%c|{~!GjQ2oYAnyqt5dIn`XJ1#ygrDfBnr~e{WU0oHoiWHTBws-zCOLZ0*MMD}lo>&PB z*tei5R$W=>-K9*5TAYHkZk*KbQo@%avtTn(6OF#w>4MP$B&k7FyXhEvGJdJy!-(Pd zpsCZ@MiHI#B5H0yH!c?*tJR9E0vDh9QmpAy@KtkF&B58V0eE^u{bXm>#T-x;Hg>&f zwFEleR+;P3T`$o3`8$JAthE(>m_zP!2r%9SX$1&79rK2E%Fg)jIJ-1XXZ@*(U{Q1d z!JNQB7^*kUeW2n8-uoA?H%Xjx-&t(`9j)wY>8s0TSiOh{og;s>7Y+%FC3_W6o+$l_ zP4ntkBJ7~@XI-C_I-U?1aTx?eV@9xHG75*kT4@>7Oqtx$O&y+ua+QiWegRJZcvd!E zf0Y?HyPNr2OTK*HMDw-=A#6(;H98;=viM#b-e8ps-> zg8^tLNP(O6oAuwH>k;Z5+}g(|m&PJVyD4o=idmi(8a^2K%=RhpxnvlcWciaU#Lzqf zlW{=wJXE`!zqUQz-F9lVKwC&HG|vjATC$?1#XS@EZqMir!<}mBlW+wgBA)lX%ffet z0>xNQ!37ab_PgtXepGk2Pmc))H=Q2`72)^>$u-j(qHljnD4X3^D2l z21pu?9KUoB5Pb&)Ze8=GQed$h&a|yAD*^91EbOsGLPH%;MS^8v9$b~ECS9K@j5=r7 zi~!%BB<;67{kvP6WVzSPp1<@^7{hxd?yRiS4JKUNKKWZK5CXq=;QQHfVdZA|bMhh8 zj}`L;e+r0takou9nVb7i>LvFWFrW$G=a1;n_;$K@N7~lzx03MokZ$=heH2J_A~;fq zO$>H}Z(szZA0EM64^k;GusX*KxrF#;UJ6lbMuVvAk>5(5#w-G<${al z*LkPb@Pidc-H+0`Uy5Gr1&!I(KeXPyqXz$0t6T*{c_yWm>Aky`XQSFw4PAFG5HSl2ji5RD7&#(I?VE3dYS7ObMf`R3MMJ`ktA z`^c^MWz8zkBV9ei?hdX;;uw1^aFx&d889mZ*PilSXTN5U$|1Oz z2BmhbJ)U$X`jL*Kp)4k#|06Sh`QOBxP=D~4g#$ZFe|-FJe}zLNZ)}6kgwbxZ3$)fG z`PkMVg4PJTmE;S8xr^GiOEO*CJ2bgf8Qs8xRWHqtMGhFHJucrmPes~pRmak0u2iJ` z7`GH?ZVH@L^to+w5q1A#qK=oMq(@!<1@XRV@(I*Jsh6yz!m^|I&~o%Pji zHM6CRX2a9TBS%?%+x|gjj|Ljnx`AX*0H;vTt@_OHZIw;>BM~uI+qiT(3en{o);`)n z!P$L(y}i2_;8KL!%8OS$$cc^K#v)E;nR1T?pcb6#3hR?+<^$<2@aX2%rLm)&v}2Dt z5?j9q2HgpV>&-aJW0gEgw~W=nm9>gf1Ot1;8n?B3Zog^_YPfsj%!z3U()&#>Uz1k{ zRJtm*_B!2P#Q~;M`5&nm+S;w7xAGU*=JuSnu#|a#9imX=)ZuaCd7mj1S~|UGk^HCU zQv8C{S$Qdu;=(;hDtox;hh&GM1E8Pc%vEbQF(v_GaO}S zb+6{o6nduIi8mD`f;0EZh10@;+toCq$G^s860TKgnNNuhuCXWKwY<_H-t*U6tZSMt z8_G4SaL@u!&duMpo`sV{Iq(Z~yOQ=kYIqe!3&1+QfbUU+V->f`5hQ=@q0NK{ory(~ zMdI$JueHY5B!KZ!wl5JuU*Q%j;(WLk9=Ef6z}tp=uu#fD!=TNj_^getD@np)Zx(uU zncwM5;2CS>I_i2I+v;g%*@xwr^zBo{v2 zw`(B;hu)QI^{@C@WFw^Nnj)d0?ydQcAjYP;vFth==CZwj{%_1gRrresPPfA*!t=pC zA||?~VWGFt@>oR6L1Db&tiYY4kT6^)4F+3`aZm)KDWKG)z!gXA$UfpJX_W z9K42b+|~aOW%*NS5Qkb`cZQv}B-Rg_rRzBD6B`-T@Vcfo~$-^G(rmwX)fGQz9^-^l&up zU}J|TK^^hOW1G?l+leDNX3WIJpVQCS!*A5TWVh|PFTqz?B5xL^-1XSiHNwX6mnu7T z)Gr1GZrp$AT^l%PIY@)v&f55tbSgw_+EHDvy=5qCz>kQ}K8Wr;dj^8``HiImDQiXg5aA6LM))bN+BV9BIdDytZ9lLX)NzmzWCRD|=x9nl z7JjAs+32l<5fZ6m{&Zky4phFJfv4+tC$WD?`Rzg-wKsCw7YidDK=2+6V6XC$m-|4d zGAH_?qeCAo7(fGl*}(&DTF7+<_os>GA9|s^>#^h``z><<15yIGj|T<7mzog@D=`;% zBH`#qMgA_G*7nS$U3jHHA!{Kt)_$u%y~?G9#t3a+S6KMvT!f?%#cuE;>ND=iS0p>S zWW`lt!U+YPQGC<4_mz@ceL6D!;T55=zn(P#ro%R|-yHK`xisB+VD)=xdx?%aNzxy4)cz}hg z5KBu}?WELr^Sqqde>NqOy_`|rY!m>#K$5kqZt?pHDC@5mh=xX*LyJ)Pc1g$c%r$TFpg{R0vdwG zaV#l)-pQtqk3p-~65pmti-5kuqj~ajh9u_XvVTYn$Q|(q>BdPUzK#9zJARaW(G+ZB zi=r1CGv(l|v)4|NOEa`JqLil{GyM%OX>p7xe*)E&x+8*mChD$_H0vAaZ_GB#$gyq!Hw&9Hz=B(al*vez}y;knoD`(mv!Hc;GzkSj5HQ}kR?)ha~- zHOTD_QkKh;A3CAw#LYcVo3?3Xbv*q>yDj3_+hT%3@Hk$Aq5Ax-S9(z*7q0N<;PTvI zCk_qH0&JpysYD9?eDkGQ!_?Q5Vl+6al}nSLVUX3&GNUR9FXk=#mw(6jS7TyjIq?w7 zx9k`Uxi5RTvcCo4{a=W;K}FfZm)dfnRdaq7Zghsx6Q>=(q9%*R;DR*EPsjkQ=sw!g zm56fk;zn|Sa~#`~!FBA9NTZt{=-EgeO`I6cKae`$fuu8AIh1f+xO=mNd8|C1zJ5?D z^Wfk!o-x%)=8IF`Msrs;^T_A4{qSZGd~FsAS2f@i)KhC)zJu@FP9GR7K3bd{OA%D# zuVaL&x0HEQ;gqJOCccnT7mcZTeyxq%7T-~3c8Kbv@Xf1pA;x1GYa!k*YdUGqYjN+K ztD~N-cGD3)F^fON^FyD_w{rWF8eP@$iOr_FU`HXH=IP_2G{Z^UVozgR)_mrTA{G!! zQOl3B^%)eV@^oNOg{XeOqjE;;NyIRfXBMwK{og2*Z=w-f?+`6b)09*m%iFL73@?twylwnOxmi zvSZ292K69aCh^iZjOqTM9n&t$S$j{2nm$(hXDX81N+Y+lJ?&Y0ZJu5I2k`?zTjni{ zDq2i&HOl`h7`ywmY~bxwh-t|m=-ijl8m}ij@9;{fq10j;D6?`5GmERKluX&rL!A% z-jevyf)b|d(n*>92P-QXZtk3;N9YP9cjx)$XY>Trkv4-a3)2<4?6mx5|BKv2Uy)WlC6Wt`rmGSE}@!d-p4>1bc z$5lT9Um2R^*;2GfAbrdK1sC5i^P!yThc9SsN)Kr7`kBHuN{=R5JX>>)tO}a7lS__b z0j_~cya^G7&62A6R8@#9o~MbY!*X$dImgLgPnN>*PPStyr|cyvLBc-Tl49e$$+^4j z+>Jq_k6n4?3DZ2>f4#7fK@AZQ%}Pd%JEt&7Sxvs6FjrMg=m2b0ZS-Gm{DusasN2ayr z!-YyEN6^K)OyKl~*+OD%C-rcvAzwo79LM)I4UVe5W@8KFKK;9HN+q)*J}P(b(p%%V zGjcrN7m#Zg2CFA7#!o|Uu6PWD8I|5p7k-w&kIJWvrn5I2iw!Zh+8ChDePwWV`kl~B zbtHIiB=VWs(_gvA^OCkyhE591uUy+BW+s5FNi7@&r;jyal8j?i0FEK@wHsx$+y?{M zQ@e4}Brh|UU)F($1xp=SV}%i!CkWAM zUkbK9PLx;q_!d<{=7sXZC>(EgP2%E?*XBjbaq=9k(!IPy&lv&?I^PprqYYQS2vkB$ z<@_;kcKofecubx z+P52|C0cp@h}7hR31{j9VL!Wa=iwh`HM@4vr}Ar6bI?+*yIz3OmVKgSSIBYEqUgX4 z1{3IxO;h}3Rd_x|>V_2in$<*So6SA&*z93Z0|x@&T39C<-M6}Lw=ZREt7 z()wdi>gO2$IIAND?#qc3qHUEpCt){oo*`Al(rt%Go7pJ)V#gMs-J#pUd${yMtluMn znx5TLgA4e+#6xKKoS?Fol-0r8J+gups#^XI9=e$gzIjrMM3Wzm(OMClgB1f;hIN-@ zPXiV^e{-rGo(JC|y1kwWX3U`WyrXx0U4a{ts<`{fm=5nZ$(_HnJ?>Dyi(NO|`cMSX zIlgie#Jdvd#ztxqXHx7KrWR2#z^=~U%Lvq5e_r%=(Pdj(lE0rGi0m1#h&+)0n2C4C zl&^m=bsVm8@)MrLyw$G`R?6rKo1VF1`l%~mu_NZr~HCg_Pw{%t4yk_xAiDs(i zL@`>FKfmL&dQIau{Wu2iOylpCIc0DAC)yqx7;ze$mT6w9o0UkRrTFfo%L&)FV?xRB z&7}fom5f|fzx{`)ZiINN*#_TSCvf(kO%~GU6X?HXMSK&GU~r8)nSNx|^(~^GeYnTN zoi~Y(f^g-v?x#?PFX@*$esDN@1lFn~V*a^asY4~che%T2**>;)Ekh^{f4a@@5RP+P zT3F=8Q;|?m|GR^Jfx_B|!V=E;q2>}R>!P{2pUEt%o&2#m4h^5PkXGIw`lIJTV-6i3 z(Kl_E)Gce&v~A+lb#f;EW-3{_sA`kNsY~Td{36gEy)=3|Kf96hc5WTi)K)O)p+hsNF72YKOctl=Rf|aCPb$4}QB@*SQ1_&S{0=rlC}SCCQPHasHsRzPAGA^sLH1fjGGnd!RRhjcH{io zDl@V?7V2J_?uDED#yMM@_)A7Ay= zUQh^yTRMm`@8|X0RM+2&=(|ee2JQri(oeC2Al~rz(k~;L`9F)lkc9sz{a_k1SY0y| zWr)FdBXEPj0DCsf+1>^Jz|;IoKNI|atdbZ-t+?oGRrU{J6Xn9BF|B0fRJS`*GxHN}(6{I5?gy!s9>P)6xE{in3TI1O zW%z7$=ffIrY!oli;f;z~`dUjhEr%t^rP8mKa8B|&Je4God}c6jo+$PFf?V-6(fME? z`g?)8(C>du7O)fQcTpzQ#-+2J8c6UpAsAKth_E?6jXX1cJoX8TuHJv~pf} zqG#5dcO`dU;IqZg5)Y}>0g=@Z{QXl=S z#$}8ju371+jre9wX`6cwbJPXfHIIP|0`Ift>!tG!BHiZUn;i#n5jemb@}ugYUX&98 zP!>+lhsJoiZCKY`a)ld^UUnjJl=f~Bby&+spDZlCq@A?2-dHKXT25d9oK9VxHPvzQId zCerM#_@T0q#mmQJ#XW6e8wZ#Aw=EZ@AUxY%1$%Vcz?(Uz`~K7mhAD7@WRDk&X(1Tz z9DHJCwm%gGj&u#*LLBkau7XWTtlcf*G) z{P_t7^SVS{&D*UKiv)Ho7;+?YIA{+j>KF<q<0y0Y<&rcYdzpPl^pS=cgI)nS4ICS1EqyN%U=W# z?E5L-_?LiuBQGITK|`sDioY_~BpNVc;OcIOXh-@g=Fn~Gwm@=Ai1bQ3_fafwqh6rYM3l9kl!wNkQb< zBtP|jK4iWidCt^XXY_cu?T`;)L1388xO6KLDW8;5!c=|+BYj*5XAk_--%jqW#l6~B-8(8s} zGEy|xiPcJ#m@_|-pJYDu$Ylhnt|t}>sl-_n9?7Yt6>w}@F&|j)>iY!A_+iZ_%m`qr znaEFSR?R+b&i2gO3x+B6eNp4DU?fyWjLKa130P%3$ajn=tf;jr&iCc58k+s1QekMxT z@uS{L?^A^T_XC=ZeG|a3oC5LKw!hdo87JXVe@e`Roc_?{`a8St;nrnw3v5od%5~37 zOWBM6tOIQq3NzY`oL>2*cwlu-jPH5y$|0cA^>M^wg+ekUUsZ?{_d!-~q?H{CZ*jjF z_r8is&9v$sH>N7&SMFOCi0E&a^c;ehdE9YBd`kos%AVncmJ!vn(Z{xx8zEj;|9;M# zeCu)m-4mN~I*bj-BNbX-VL(yfcOU3b!Ax`fDK&eU4P z7y%#FvHp9kCSkvt{Qc|pY*jIeZLPd&T;ka*nn@E&(7rd}dBSRgyNGIJbLox~L%Qsx z?f_I-B;lwb7L?=7vi^rOmPS(b4itQ72D|`d*UpXRA1g3{n*cMGyQ2%b{;gaW(ld`-QScQc|~@eH3JuSt^_? zQ^QqzrPMc9ba;!Brb;QFSNChoow8o_XBCl1FWY;G2hS$>dsXR|gVsg3|3FsjYyVshDl!)sDBwWhJ_k6P6tGmv@G}?wV zk)E$xKLYW#?LQ;H#6PYh8AgzT_i738D%nh0WM~*FoHyAJL(N4(5HI7d|O`ReNsY zC0ct9;U^O}k;<4?v0n$&jUbMX!h%LHKVH#7JYV!X=2Cm~8GM^BU@z#GRGS&-Pjn}p zY!r7}8qPPqmo-~^OdB?BD@|tk-)>({9v^cnf)*Wvtn9r;PLhX#NcGPM!N$!f2R$_P zcnRP(FTK+yQY|m)aw&flveV_+Tk^Pa*)~mpEo1#%=~5&!Z*hpHqV1ZA3j$!G&3||im3VYF&}?Jp(<`S zeCbkx6sfve`A?F=3dhlO0@|PYUiew_s2=jteV1QP9G%rlJh1CP7fw+825Md6LsiTU z4Y$k`PN~y=T!b}=!4Riq75+h5mw7#4mA4XL9NZ4JKE&&-J*}tyfVQ8Odp5%psftrs zM5D&rT@?6j3cr}lKvkl|BKZHBTo-Rkcdf8=L7QINK3@I+V{sG<_`?9V=IIjoT`OmE zA8ps#l&aV+F{P?rPkh-|B4Efdm91TaUR5vE#&ak_g13+cv-c24IjVG*dWHXl!44^ zzHObfn~E8c7n9BExgp(opRN8&VBgsrypH~s;iZ~>8)V4vBIR1um2oybxKs}`L-=DP zTzy4n^O8t?aWi^0wROD=@wOIP){lrEV8YSuZNxvE5JSVeZ>$hg>fR$p|Cew4|GdNN z&Y})Q67gxKP3ivlI?l?t_jSKtj%A8%TU7n0k7PsiLoRxj@Glq-}K~Ku5*r^v;Y(tKf0&;He~mAhDo_?L9Wi&(B%3H747Z;V$pBNed{p zqV$HmyC5QgBE{KdzQA4n@keaQ>CMGH>-dq=6Q8d(h(QEKE_4CWm zthpUGq=S2If9dXDKM_mx+N;dkmbl_<%aFVLh=@HqcueUWxx%pND6PnFv*|i)Ko;*2 zV(m76bjk1?OYe&|&bFAIT5>gO6`mc8Yqd8n*PdfhzZ4@4Z;5=rc~=?%_-45;y3ib%Q1M_I{N78Wjs2{)%EDeg5_u}A57-@OTa_M|541Fjw0;PmuC98y zxg^>qRqtE9L~hW?Dpr4Blu@dtT>e*MAF4OLu47$^S3ol5$T&Drezg+6xlpCu3^-c4 ztsd}5*8$orX+A>mmVnxWln|%w7HhG-LyoF}L7qwhEoE1t^ux=TOfa|qwtjibOnY*O zL-XmnYuZJ#dRti;MY@i*AT4=m%ZS6$yg@MtRRl=O=d`$@Xxoi2;dxT=O_GzlVQX(z zvhCqMLN2Ia&THVY%h=h;aIfm7t`%p-7yV}oJM?ydP4(Hg`z|%7Q8S~%LR6(CcsI8p z8jJa~Fy&}C04}!uA;aNUIi5&sWIp`lTr7RLZ{jwU9K>5tcbggu>OF3we8k$uJH2nq zt{y=AerCT3Uo6=Exr1mB)*ACtsH6SK^FfgAZ@3k!fpr19t|-VdB%lsv9=PFtk+t>Q$3B_^C^{0$02*tpN+JPX=EXTg2;o zV`Z8>b?Eo7M@6#hnH61HMwL)n;AX1|v#y?cv0g+{fKWF+0pt8v-0mgjcAnsouYOON zGB|0MoZAxwp)#O}CF`^l@?qVeHO{|MC*QE})3%N(#yR>Kj(ZfQQ#GcUNyVb?`de?| zZ}SNSBKnym#X@SW#flpibI~-uF9@C35-^-N6f!Mw==~dba{rdxokR;zWc&^*CF1R* z$|C>chSPa8i_CHAz|reFjWHMx=rdjfkOIRR4TmWWk4PN)5`}vgxway>{-zqNijS_! z5C=A2rtia~^XEgBAxIb9x zlL+^E^z+Ct7o%=EIx5nWf2B4!BPq6`yF|FRqPZf&T#bh545>)Z`V*yk|E4y$sa#1S zMZ%=0dg<_>(LpGYvuNOw)jLH5sFm!wZ>B8uL)Ei9u0_=g zz0&k6m-Jv;x9sw;4lc(zsikQndKn4lp+0LCdp_x+)p~_efV@@0A9q}D+@r>)amUcM zd0AgwxemNr1X6pIG^4)EwC-anb4C&(bI-XD4F`-9JlL8wvr#dA#}qU3FDn z0CLlgQ>|KR7%$g>2&WXQ!{bo;t#pMyRL-s?ctP&x3$4bI^C4EIr4*p8{IyQn%GCb` zK=1eUbP{^**tdXO;LvNGVVHp@@mX`?3fnp`^lFLLlfM)8>1qibYrnl}W`tq?rgzz6HRDlrfn;KD|P|lB)~un`*Xn zIcZ4j>k(n!0&qo!x@xEOO%1hnD6uElH5!f1>tZAnJ2c+(*0zTAXtQtGU$D(w4H5ww zg%V^Mw9|&B8nrt&WB%ac0gcAmHlzt!y_*K?#14&#Lw~-0s9~`xoSpG8P66hub@{j$ zRV$zqIuSlRJku985xyZ`FSfJkz$P}c{uj`B*!V-jj~kzh@mD25YOfF#;>nYs4j37s zSBsn(TD{wWSK59MNe}id2d<3JYwh7}1F@M^hw#BK9ZK>Ec1`{hlBw+Lju`otc1@`H zp#nPHy9V;a4u8wE^2C598u^(-Cj?_TETq%9`zIBQ7-o|=f#cBhU7mmVuOW#OJ*n(l zjza=V-10z@eBly%F#O6=WcAUtAJSjFXcN4^E1(e?Tl;?k;lo<>BW#6Gi8o^>KrzdqKc~oB zj_y5I(5!9u%G3`lA#)D|ZAg{vho2gjK06KGlOld@K#3_SE3X6`yq~|x-!|wPX1-wE zbbr1QdZqieeF)9vx_$JTS)&VCVbia9bA^y&p~8d;jbhDvNI<{)DIMw-Rx&trKeKHcVLO);@x@ zA@z#b5CfWn7bF+i*PWl&hc@VRAJYCondJd3>{dI=94~c`5X$3k_nT7qF+SBNwEgC? zEz!F_H(fN}s@ls$paG2E(GG%z5H9^$6opU73LVNPZx52?2p^t#g@||YRFD&`K~9KW z7;w9pDg6Ba=(rbW|L`9&mM0l2t(vTY`>y8}qYw&3^5d|algJ%%AGnDLNN2I}-fy{0wHlY*;? zZEB48ZS`P?BP8j~p)aE$pf2y6m37To;+mO?Af(nQt z9z+>_pt-XED>(>pB`PB1`-I~P^Wh~T@!?O6`A&fRDCr-Xr5*M^HOq}6SHSd{K$ZR% z*kuP-tFS)Q)Wb#`pA~i=zD+fvHZuB2Pc@!#sMW)=IAhnwpb<6rN zXDJ4I$Sac|*yQMH<5+-i+PZt@K@q*~M_vdUk#~wHoM6#cOK|s4w|ew2NnQfF`G=+3 z7NuR{oUmi%;gFCY4a37_?;;Nr!r zN1(^6Oggv*`Tk*a{-SL?xi8KQ3Znzj{p!umVTIHnrs2eZWo1?SG1#cPaPdPktZLPtJ*{hM z!9G8<2z=2@g&B{1ZePRA>|x~z^gj~n8{+r00b19YtO|Kd8j=e$7YEd5Xus?%X$J(FsE@j1{PDaS`p4ZOsrG7w6HL0r-*sn_xPpC_vbHJ&(TRi`Qc$;} z0qDg1@t|~9Z^Qy4w|V#i1;;oU$+kXrrJ4y`<@AXMC_wWviDc&=vJXuKMos z#|j-~9pdhHXICGV{XBUi-GImR_24kC4)x>mD`rIALuP>Oy4Dq6n_ulUYxMUA-eGXy z^$h1D*_K|{on@jI&RO~2q@7)8Mk8+q8#l$GiM#MoyTV!er74^YGH|+A48vU1Dxdva#hV7`)`p zA+~qYcPzlYtn`ix)*z(4SBvx9IA}A&_@0xT<^Byh+x^uEn#^9w_{dzyxB_Cs%SN?- z`3COtA3i7eB*N$PDBhjsWv6_bv}{bn+9$>5Pp{iq_0#x`F=_lS>@Loq+}JWqT}9Y5 z{`en)=@+V4hw4}d5Lm@}OEFOOI#zk`MPP;hFZSG@P8x&w97D#1fon=?-_d1sd^NHv zC_c126D}!Bz;DiQFiN4ONm;&C=sgp;x%n28>#)2H$|yg-f9i=&eA@Q`ehjDO1|0@x-EcZKwtgMGfwGpjowaV>50i?l| zR!)aoIbpb$!#vx5xVPM5-xy8`=At3Tll8DFS%ovVJ8@5kMUqi2PTPY&&D*TzE2da7_`DRqjMha<+G8<)S+zc0tvtKcV^r{qJ8D13>oevIkbs-#$*@u_{es|G4bha zQjo`KR5p!={PE|ElRr4RJlw07O^E-2-)5}*1dRMvc8Q04tm4GW`)rk?9pza3DH&hZ zcRDgYPdvml{==W%T7B&L8}2NHS-uwwy?RKFIv=f+i$^9ccxvahDYk%RGL<T^iIkS{f^O& ziTiR-bb4~Y6!)?@f|yHLoZUJ_NxS}e~J< zRcf_w73PEFiR6jdaD+6YO_Fpq>qr&FD7%49aNY57nI{@9yCE_GX~(i=bgagJS-1^= z^iG7i^l8Cy_{j7d^)HYU1;sR#&_m2(sijSP=B`2@euDZ`V6U%QK<%YDDN0fkcEP*| z+?1#j0+T!c#&ZW~c5ctRCk%>6(oZ3(LgXG)!%xA;TfQ8!9@?6yp1^geh8|LLdqRiJ zaomq{R*NCl)3K7))qQ<%lg07XP6_gAigz;ikgvF+XfMCXH%F9!>#1(j@s-J9??)xm z#Qq%<-w*oFBv&0WNzmJ$Nxx%iAKAA%Yr0UG^g>=v6Q3+UlgHjm_QqQsb!yPj@rIVZ zLZ5$!?vea_*+^KYe2W3q@%+t2@uY2FjcvfB;K%zL@u#+t?P^kb8SAzm%lT|~n(81s zuT&M5m|jc3g#JI9;Z^ky&n}E(9jDhr`Q&M(BPRn8*lxx((w#5W6n48{zPjK$JZ=d@ zgM7Wu%gjhO2>i2cA)mS4V1c~PH2YoIHc~Cm=)e@rj* z|NgrXil^^zJly_xSlQY!PxV6G&PYn#o`^hytlsemJo@ZLLq4exrtLgBWv2ob_ZCyI zBZU2+qpJ-(0!PDWQX=_3L<0Jiga0jT&Wy5MSrzZHT*;zj6qY56f9_`fSn{EpIktF> zWuh37WjtE$DgJqb8CK#^K0>_uEn-2TUEG{!0o8P;CJuKp4(7lURufut|D7;Pl}7XB zzlUqq;zejIq4h(%jWtoyhmXv$Eb}ZMb5Ey3E-|AEWy{ST+2CSLxA*MdlxUyIEg zo_RV+x(6heE1tcyXyX>ex~D%>VE74FD^w4*3g}n+?*Y#V=8O4ZO{X4L>yk(RtkSpQ z4j*XNDgS7AAL)eB6K@bIZ+r7&m$8YIKJP_r6ZL%<7Od<%*Zrn&+T?n=TdH7( zPUZYL^9}k-kbj66Z3bQp1WkNG+q)7z%{dTx0n4D;&sZt7__*Tjt3B!c>4Mzj;lXa5 z#7SRKyrh(XoA>AuF;o!Z<1>C{prXGIfABmVF>LWZYo_;~AOd;o5$>#BE6FT9|9NWHu@ ze0cnB@QgRSz>>d(zwEJIkmE6fdgk%$N7(U;JGy=!g?5rF#$!xHhk%*Y1bqrwMLoyN zCp%9sW+UnH1(f6p{FVPjaZ%8;ye67_5 zYk|pC9~H&@A6ecUxSj1PbpXYt4#vgbXPX>Tx8r7xo-JVXa|>04MX+Ym4ecE33OQ!o zCg<%!xS97x7EkdGn3TQ6nc6c5R~0ai8Bwlck?y`ceaLy@rSu=P!Tcz&>xP#=p_l4_di4ijipJ@KX`AYf7|VeeZVw_--OmRCqb!!z&TTv$hJO!}lx^I!}Q$8a~(2 zlHFB&zGkF?+jxZ=8OFFmswq=(4FNiw(KU<;&m|4ws1okTmuITdD z$_=GDj_%da=eug*(-h1e`JoQqDV%CE?~hbVBKvh(oUO!7O#(VSqPWR0Zw@PT*y53V z)YQV0TKZ~LL2^i#onpXJ*3(f+Flos{u|oFz^a$JheWX{OJO-+_0@3jRQkg>g1x6~r z&l$sNEQ&`Jf^_jhf+?)tW3-5W$9=_t;m|?+j`T{WU64qiuhRpOx|M;l3h(%E%+XGJ zjHX{%H#(g8&IaFw8maO9D}MA1RG-CHQRMzQi`zr`{8yN>$ZeRHzU4k3#PTD4g(~o* z4P(#;WmVoE)0>6JuE!Tg1zEV@DX#Yf;bfd5VCaLW*%S8P=!@;hEl=(-#k|R1+65!w zent0Q5h>bKhS7f%9aM^}n#^Xscq8-QA<9D%GmQABiAtJd%^*Wl>_E6&^XizDmYBHbof=T92ah~-K zZ@6J*n(rE6GA&}^Eb(+#Sn;J@%n3{R35eykQR!{UDYDc&^9Jg zPwG)M0mLE1OTV)=aF8Lz?>2?2^WtX@O|5oPh4$iT93A4m6qyO4jdYq3dvV!rn+3Xp zMe6cF;2AmD4NS*O@8QQ>3{p5VRM+@k*Ar6S&Ztn{F6F2kXRngGxH0Hn>%?#BxPAv{| zhy#>ykE-@I4hpD~{*x4kTG$G5gCb-zx_V3)x06i6jm)boaiv%k$}}0EX2#j3S+G*q zt?QS=r)R^)6lHhQ%qAApN)PRb2XUp|T@yePx4b&yk#Rd2+?+KRbony}sPBR5i5b|D zLOE{#=?46dRwkGv5~Lg--U6;yXYXPgYA`0PXNATaFII(V#RG=8Z8UoSAIQ_kK4vvR zZq10Wc)IM(elvt9uc&VI^~t^0zmV3zw`EKk5{KD?0@{t;0%P#y5c#CL7DqNM+0yCP zP%Goq(y;0{Kppp}8bjztKdoTZ=OcAzvD;q%u#`AJHMfmg@5tah=J{h1b=sKK+kMP1 zzsetDc z6|;TGUQQNdenR18F8KOB9P^J^{x=lj>}W7ahhEq!$ERarx~tIV?{&yeUS6TN;CN#6 zc02>AQoecO#)(YQE~|(hmWl3xONjh5@g2q+l9Te{GfzdwUJ} zGV*&n_ezfMb1crdkzdUg9htOz)+4#??&Ed-BHl&yxkB}hc<94a+P;)n&Li+raLOdl z%so~9g0~vBE0PWRw3$ruVH;6tCExbOYwu`>&Vu@w=RoyFdJ0k-QYH(tzH##)2kJF+!>$mCSx%)T1xiT8!QlnU_mCC{77^U8lToS2d8yI`Y_qsP71i>pa^eZH#% zGLL?c-(}3r*m;DN;8gSN!S*qUK6-lbMRdNUE4vj=8&!HH-J#7%&59(`fmxxc{(ED~ znQ|7r&ihcGaTfU!nWe(dZ58DyetJvBvlmbB2rm5a59!Fx$Jp`nK@_P-rticNryeRS z>mu_r*z&BhH{enEFzUOUUcG@hA(Ayq7Qhu&`j`&)5rOS$LCYp zj_vHzDl+pO2Sv^kKMRDN`YgXg(C+DKN0xerlO5LLQ@>Rj7wmK&;#X+8`{!JuZ;*2J z%P#MP_Ma+ZP_(0Xyy{=s_LKD9*QduV;fg{EYX55I3od<9Y!3ISUKMG0R_6WIOAC$9 zm(APqdn<;`nP=0xR72s~+no}4J8~3?LWjfgi7%%0BVbYcV-V~W3GU~YPMm(jR6uV&ZA9PzYFB5bx;0H=Y7 ztIWIyh4V?7{QAvno7N!V*u)!<-3vU%6PFi|Q?BwJv;vnCD*M%olm%(gcT#aX1u>T7 z5(IH(g)i7t?QvMfl;~%QVzx^@{?TRMyoNUfYuI)at)@B^8Nb5tnB>9EI1cLsrE^`C zm{N$rc-s?NdUPO@QeT+%U&5?*6|Xbhb!S3PgN_1p1TE*a@=knrFXdqCWvMsnyJpvh z@R+ih>4jxuo$|B8FP>Yv?0co~78YJzWbxng8m0G>%~YO8OV7aPHUWCBBU!qjpN>en zlD7fwrQcM3ogMjNwYqFz=zTr5AzhM~%jVoo$J>)mYD)-d>th z_$Ro~9oySt>u$<*ShfbO;w)#cYhQdFzYZB$CNSvD0@@O6t6QC2{y1ZkJfd8ujmwpZ zSAyFB%zJQQ8ZPzlmYQ#(v^q&5Z4mb_(ppT|KQt*+(m@zxN-<%DtMA*Fid#czP| zTj@nJjWy>`E!N^CPk?*RF2fRGu~bfpahmY!qY{A`6?8o_Zn@ei=(zIGCtyNDzCosW zM1z#I41|q5WovACJtFj$rHqel(q+K$)@{Q6N^OGqN`6AqrNSKfuEM-}dYR!!otmY! z#tKMHSQ?*p)Ron`4w#5Ql(VdnK&)d~=JjUv2LNhrMoC-AGV_ey&56SqIleK= z$|i+SA8AmmLvm>HqCvX>FoU4$!uT-qt!LH=XG=``78ns1Zn6p4X=nU6b3YBEQw*f9)_G4)TJQs+3-{g!y+bqh6{HLV6)7$OklC%mtjQj+3JXemT0=B zbt5c^BZALr|J$30qQl9iKuSuPb#=B#kc&e#i_6C5n7)_i|PH0hpXk8ZGwTbZ=L1q z@thlS4Tc&_v)?wa*#&teM>_fE%&GaAhN`G(%x}yHJcCTlpQSXdO3DFT%qQNvNKSlr zahl*NJRsNEi@ceAqxx&tsOGok!5lkV#pvb1Pa<_2Du)Em&=<9B}pB#48FLH*^`f$lSQS z>@2L(P*FAWaHpg`_R@0Mx1xTVdBn%jc@!QkyR|jTP2{BjfHB(K!{27;$E3{WtwoD!)^&do!PCg~5FCUj~eeSJiZyIb`CWso21A@rc zZrj*m=9&fw;<1^fW;8)IFK4=U{<)Nn3EQ`gGVt;lsS~ z(q^=)wV{}>NSS>cqK<%Sq*T4?%iESQ%Ii9(^6lW7dW$-aOn^)BkjIOb_5^R@TO*ew zh1PB96@W`POvMp6<+hTvBbL71;Mm?YK7$84P4&fd8T}lmn&LscR?1u~m9;r7tpMIw z?cW4yh*H(6CV^(MMvHXX$QM`E8s9V)UEXkit)Jg2NAmz?dlnBlXt?Xac|G4wZ7qrV zuz^SCy4-}1W3nH7^+xC^&ZCGS=v zi)0ZlZ-RM?esUxqM?CHH&+RtCVxh4X?4yY*t21e)_{i;gucA@@@*jaJVdw}DPHnnb6seG>#=C|(}K<8{4CMJm&d?a z=LPdelfq%=Q7~KGgmVX&u1?B{sq((=>Elu2l=Bpr!=zpZp3t{vU4K`XIOE(0BZRlx zxcr6@b1YEZNK|?sR)SfG>O{}_3}X%h9`#wj4_)K+87){oR?bGZD3pEM5hoQ+hnq~f zO4~by$_z>aD_- zO2x*j=$*kgE<=}JbXZHormAAM1t+Sc&eh=c2a%#hZL*3)=$sysYrkY3sUUyzr+M7Fdd(CWXHWC*gc+8POxT(6h?@&=jJ62K9(oi$8dSvHN zQJ-c`VyjyV{c~YM{+fP+!oBfk_4!b(2-#X*UBiqe`xf`sR$1X#mxCiY+tfP8p0>BrgU}~TCzz1sSkm^i5^wJtX!{6K zeZf7O&V2`QY+Vf+EjGZxBQw&M`-kk|AU4CS87eE%zVda$X1qcQ9m~jP*jZMQC?UCW zmn!KkpL&fUgC~D5swHY`i(H@s)J{L=j2MI_iO}7W? zNLtO1`H80v@N19UiWTgG7eR;h$nMP?b1)QKN4-jMbQS0P!#VHl+q`@8_9@W9gUITB zo2l2X*35nT12g`?sQgXH!@H03$>kcnLbaG1EDsB=C3&3q`<|MHm^n=uGs9o^T}E2k zY4!@^JBoTomVd=uUrKNn`QLt@+;8K%tTjQ4Ye%n=DGFCd< z2_-Lb>E_82ue#`hA(UCFeoEW6_RG-Q8AnOuA{vU7d_dz3**af%8gIR3+IVuZaH-Ac zf_`xZPuTX4W=pENz*B3gVk#!}{SS-fLP-taEr6x^a%Hy!8F2Id%SiRKK&^yj@vx{~ z4b@NQsSQm$sHz?7iOb0Tw4tll3!s7!L9LFi;Ix~P(CY8{^uSO}h@3lyfamY8^KLXS z>h&N>2Q9SML580DsxDvmQ6gBaTiF{aSVV}SeH6uOv6{E%IRxIW_skg%C6=uLEbZjo z90GiG%N@w8`0L0KY^8omm4@#75-z6uhD__T6F01$s-+Jn`(!JF8903p)5Lcii0=hc z=%BQ`(G;Y}5hvKvL0ia89gBk}T$Wc7Z->@e5!gprAJY_QN(p>X7)VU%hv6Vm2K|2S z*0mqe$J8vda>DvBtU7r@s|sU2?9Xi}Yosh!emZj(EcViwErc-l_00HZbLKV8=Sd5o z&RQXEar)+INg_$T2EI@6c@f{(KdHSAVN0MZ?rAP#i*_o6mK{ciuPe=r_Qy{$&7}8V zPLj?%^pAcVG!8$A4$--cpfB`P2N`+oWetV4HXdMpJou5|S`WjN+Ebptq5ouZX~6SnuAj-xS#xF3>FZ%* z1H05{&L^E2+WSh{necwelb|mE zbn|v>|NZh@*;;@0a@D}Hw#LSQWBJ^#OCz0ZP1uFiy;`jvDQWr*499^sn^UxE8KtbU zpQNNU9o5t*Rh@U)d`CyyE35jO$b{KW>QZw_WkYod5RvXWiqdLHHY7y6y(DuAfclOa zuP^oXq_O0#_Zp{Jy3O#H9cZsK7XswA^Oj4)_l4^(lgas=lHGxYqxnEv==7*g)}$H2 za3PurFou?mwq`9h%z$cVepSjCX3RUlaEcyt`Lh5eV$-hgJjPuzV|ASkjTuEPYZI10 znPX$S$ri?}rAzrIbG`beiY;R#yJ5ej zj$mOI>E-;uyu6zp+XlFjVaZvP3z%!ll~8Qbm3AdoE?un=E)5+U6k+cD=GPrIs26>L%|Ew5=`I>>+M1%qznV(A-g$Np82o@v~l*wB6+e3%y#nu3^(z zo{?G0oGW?Tl53=cXZhLtBHhs8d}g>#i@9*bOi(QviN0>?thJJoV+=EtX+>v_{ge%zK3zhOMhDMfR`R?b$ML;{k zPfU4{GSYV~T{434eW7Wgp+Mq}#u^FEplC6rVF#V) zK68*?pF5vWuV21f-6WZ>X^svv+zMhkRM@6f0X8+Y1{@ne(&y(ohE6)?t5$2%?`yGq z`Q1utL;aGd+z+c(myTF!SrF0qyd6@a7ZzIwCl(Y1I@BKH1c5<@*|jOY*`i8^)2rWx zi%lleKb8s#EYr;#S@4`w6fP~OEjqMZzFRm*SFVk-HWoFtptQzvyRp=<4$Y3V1X&Md z$yoSVv$(TQf101})|>2|pFSf~vQBwT-B*99T_!qda@45iUSq8e37;phc6Z;iyq(8A zH?n}#sa`IYiX!~cje72dBU5Jum(nTa+h44k*k*aO-K*I?5Q$C@5%5nh+sK^g9o16q zk(PpfJJ*<&@GUrJnYLV-Yw2}n>NbA_9G=xx|Cp=gSQzcwv(&5Ak^U*@WUc-JD>cA+ zx7#4U@X*8{$w7YMuv>b&rOy2a?`VKE-i!S-nfa<8a-*Bp3Itkd#q;Tm!=ts<=jf^A z^SboTg8V^_q6(=C9|C@~j#APnuX{TH&E&Jj8#&%8FgwHt5q;VgwEjgu&YjOwBeG`K zBvJf=JzuhrU?#OwCiC(e2fO8e!r}L{5-QWlUk2D`(_4Ih(0qi(_1e% zb1V=6bh@$|$(##v_#-moM}4A%0n4tu8{4WncmXdGQtLnHtSfD&DN;~jQ_5-s#IPxk zqEjO!`c_SS5`NU2N$wb(H}Mb)r8Vq&Pzoh9=;Y(+d|q@g`hXl$UiQXO6>~Z+u#Ayv zas+2d+Gu|(=;(F&G#e%kL;4IGj;L(QMtWr9cF6DQor|WaU&QP8O-{eG9i^6fe_K|z z*~m1DofO%)yMI+uudi->tMRQqA7nGGQV#}s+RLZag1*}8rnQ31?Z4}QZbJ&1M;F?f zZcTJDK|1zdbQ(a0_O5A@ZS;*r>|<@Bjdk)iD@lurz#Nc*eRcK<*?y89um$90ueDU@ zY-umGl;qr;Sh#Onu5hF#PAq*iA+}AbD4zQzen!U%&S347uz>uiLY?AaCLR{ zBe4Y&@3ahSpC%stv|9-t*R)${EtN${B~|36rbX%IxALHG9JSMAdzF(i*o`pwDC;T5 z5BRb}#0#<7rbZt;g53@7Ct5!_F zaz_)TlcF+87n?Vb*te}(95Igf3K!z^qzw3{7|MCOt}*6C+=8ETcj+h8gO|>eciG0x zg>0HWcAv!I^L z?ph2k27g+u?iKk!wH0)ux0|1MkJ?I;(x~s!eT+UtMnrz9k+$|lg3CSVSGQs>JGY48 zw^0VtK^#c+Kp-(TF5l8IiUd}Qr5SI-oQGc@zDWkR$4G^b&i5Uz^GXP*F8_hPbs#^s zxM>PDBM##nZdb*3|HHSbJgJ6yykTUY<}LzP$l0s)__evhs>?|qM(om-j1oCzD^sAK z7ilkr0bc-!KUHKi$I0q7xj5IrwNwr83cf8K zwHW3)ngR`6*#bp!n&Xcr{OJ}YFuE}E8-j?PIQF*eiL5niezGp7R>Y7ax9L66)R`jQGfNu zduQS1H2h1POPtOM+bY}6TG0c%;D~#STY@ap$SQGU@@te^ECVC2fd@opf%<{@3rIu- z-D{tF^-H}D-R18qGz^!tx8m&<%f>4x#Yy^)(lL%<5i|orSCNaw6Z_b&15TrJ_LLl% zHavBT*yD0`seb3iqB)wRC5e1?mF9M&Z+a0^$TAfd6Xa;zl>db&?3(aI3qa0O)XmDgqa~#G|c4Hh>o7m;t zg8MjS+(a+b8fsRFHl`yfjA1jKu%4Bit8{7%Vb5*sBJ04+Pix%fMUTwCihPG? z{#KcGt#fsDb9TRU#dX7Vk8lkX$rqtZKT8iyA4&&6{I~Ol$HB&qQo>6lO({eF6P$0|h$57<{Bxt$5(6BHshhTh>6GXBVU z{u%>J;)17v6C?YPHroA1Sj&x- z%p?B($JdduOi_&OXuZ+&vLXZuAxV;}q!~z%#Lv?0JbBSd41TV`9ucmIu8AVZ>Ep8T ze&r>!EbZ#kvG#dB=Cm26$w?-s6cd9rF__2c9I@L;&UtAn+#+4E#3Xoh6XkncX*pyf zmc*4lw)bS$8|FGH|V!sIYfCx3l87?tl{iS^r9^t7Uy}C zRpSvi4eTH4Ur}!tPW;l$HIpdgV%Wx&f!^B}9?)&9ZJ_<(qhV!b;^$r^L#7jw3_dYA zBg23b*L7Y#Qt&&EUJf$wXC%%#LnEX{y=U1{-LKyQPuDsZ;IjyQ zMDTV`=(;gLI~Ctnnl<<<_m=_03D8WNpIw!H)u=GX#mf}uFb^;b=5Q5iXtD{?e>s); zS}3E*Vf~X&=Kj?}?o;!~8oef39BHW>==hi28b>uUltzZ7sJxw(oC*GYy}*IWj!E<| zW1oyi-8)aJ4R#|}+NwJnqifOrQzN76*8WpMBUk1s5gd(&CsiVp8tFc)kI$+^2sF|I zSiMLz(!*IFUss8sX*{4;d2o>;4M>)WhiF42%C_ld!~?WB-j#_*XnP?wKA5ix$%I6$ zDA0n%kAM3QP2e>M;IsL$csN>TBL!O+&UylKt?Doaw8o6XRg5 z#BQ^7A(H%OJGa6ZP;u#CcY;j33Y-dM;d=54JVfMfVmkE5+4d6tg_Ig+IF@qQ9)4T@ z^>bsj&vyMSP#VQMD>JE6bajO-&f~2a6`bl(4DR{(-h7Vjw|Fz!eNb+k_n>~;ZSZ5F z(Y4uc5d)|8J+UL|n7w<6qu2-K;E9Llg}18jr59o4(eR2%|nU3$@J$`jr zT00~(aMho({za=O*=I&&^%O0joNJzr4>j2qtu20sp_0CWY>dc`*5CUrL0g?!hC;9n z!KSy@ukFFzUrq*``1b-=8$0rPoK0E>*p4(!$ooAwKH=5B$!A6Iw2)tn3 z(s6PUn{ni;vP1kESSn13E>SO6aC4SA>`&h5BPvb^RJ~eFuHpDbLy4_s*p}@Btq&mZ ziCwo_Js0_Xii;e9V!fW!KDXfWme7h2g7PUJK*Pz0<91J||9aMU_pF0&*FX`U1EowK zwEeD$;wKk~*Y42yRXCbo^40~c1TPhn#egKye6qO9ac-_#%+oAzw3*=9wM7-W z)$=!hm;#j z1>Ixsd`_4C>bEY0AiiOq^zl^;A+Sq4TF|cRJRhWJl~h6Xn4%UZlGmjJik^P_7LCJI z4Xu1!upNr6o8OjJH%EuUDEfeZ@=*d+LH&)-jS=KV@kK2^q*t-X)ZtCn1ohyh72f9h z-LuTgLsImYE|>lxBDWIs=^ekhA<@63At#FTqtTAIS!YOxU9lakklm;r2R;=TX@F^D zK(dJX2e}%U=*%Sd4#jrkbBhbvfO){tkC9rQUb7}yOl$ccBPiU&_7ja?Bk-8)4c>%# zit&xU6%R{GeW59HpOX4=@0WG#$S=A6pji*OZ9roAZi^_EX3D0=j*J;HNZyJ)PYToZ zOF?9v^$`U*xp3pGSGwGxn@UJd$N0L?l~XNvnG43 zEg;o~KN`ysfc0FxOJ;L_P05wJWl^THxFygou7Tg`{u_19)KE(14dCV=5tcrhJw>`8 z)JLsQA9S-uB6gsGb){?@gDIO|Wca*GL|kw}-PbGZxagG*PR)b0a+uw?%kau1%~;)ymhjyKT*A`=`fwRh zu(C9^sV+2q+eJx!Zz;@YNJYlqo7wZDnvFYJ&%HZMI8ecEd;36tzX-(MrHDmTa0M9@$zx%08&fupvJM4(XQM2qSH{9$k z2yH_Yg;#q^!cOn9urz(&%CO&C8IDqJ&nge{AS~f7Z+&>Zw<)~Q+Zx{NZ4dWjEI!xX zz&FtI)Mt2=@PIcQ-s4>x-ajvn0eIJi2N6BtBXs^lTckD&F}8P8__(((e3IIqcU$LFXO{?@)M(`cdzx2#5AZ+dLA9 z_nwa=dM`%MX1$jq>9kz$cq9uk5ixsjM)DOlvP3aPiWO6&Oi7NED`}Am8apUC5u1`1 zX;ca$Ey~hJ8~OzB(bSHpKUS7UWLghpRV1iXMLHF0q#OI3_80V_;)rZenj^i`t`uiv zt0F~qV19pOmlBQaRk|VvXbh;Vj~t>g6@{`fax}(GWpm_&(jOT{JEFfc;285q%J#?^ zWgv1+*%P^-?2lYh1|wJLHJYE6p&W@^$KP(+*eb^(lgh~`QBFq<%GqcF<(4uUO`>zS zG8Ro$u0%7aFQ)xMZAiHm&8A#XZbWmjFQ%deJ}z2B%ksrXOK1%4ON=h_r9@Zy(xa8W ztf<9jj@D26To_+pezb|!$+slhO8um-INI(ji@IZ6jd9dh9#wo5(J=BEIN_^~uJzfX z>u8Kd|7Ntv(ke*E3e_sN-yrL zd=qz8zJ)t0eYmr-6?ay?gF7qRacAXwxU;eocUDf*ofYOf-C1G&LU&e}_vp?F^8xOx zaJaK#z?~Hn?yRKa&PpcktUQK0D^KFi%4czBWffheWUCFk4L@gVaDT;x`zvnTUkTv; zN)Y!~Lb$)uf%_|6xWCek`zx>E{>tmPzw%w&U)h5@D~EAsGSkSi1jMM8qK+XYxIfm1iH?@ zXaKnV?7z!8=<{G3FM!;Q>!3-v4tfu+gWiklpebZEX(RWMc91k&4SfJtLm$M|&`;oM zXeO?PK7^~G594ZRHm-(#5?4bX!PQVRu7)ng)zDmA4Sf_>L-WAqhDbg+3Gz6uh8E&# z=o7da`e|GZEh4`se;`kiKY|qFn&?xwCi+=i6a5^niI(A-=+n3+`V5o7WRT^!Cb|OG zM9Xna^z*nTx)Rq!pT#xNRk$Yl9IlC0Fd-&FDwz(ZgS?1qqSd%2T7zq%wYVBecT#^u z>X;uhKPL6KCThnu(FR--eTiGgy-J$E(l?W4?f~~=(gJpUjI?r>xId89V80WD{)gJ1I|6p{UC$RBhKT_lg`u5v(8cH7!`gAU(A>B<$MK5HE#pvwje8H zWJS<<#d*zn!#TxsDDiwEND7}0I*T{+`BW%x*hhgkk7>L~!sk=QurNlC0DCA`IOzXE zU=QVr0l5+fOj!XOqHE@N06Xe|LzEwPB0myvoqQ3r>lI)UWkVux;WgkB;ph zTCQs{IaheX8~6l1XwHhw3+8)P4UP?a@fs_=*TV<1C-Qwzulf1bZMEtmQ6X_?UE=3Eh2!N{Ky zOw*DqqzReMG9hPv`9hvhC@h_pQjq1ssyR{xunG>8W{}ka47MN%ejzG!3G4ALRW=Hn zh5os+CQaBb3(di8RdtojKAqBcU8D51gERoWfS^cji5_iEv_~ylqoI& zIZ)}6T|vIj)#>WylUy5Iy|kxYTU=XRJ6yY5dtC>dS*}B_qplOKVZPpV#&ynh!F9=X z)!E{@4s7prO}dHO;7)KSxl`R4?re9iyTD!KE^#k&uXI z?RG2fu(QRz7No?z&TVm)xqIB3oZYldXp1(?*^71pR^aY)R=Bshce;14x#8Xi=dZ%? zp!=}tJi&5tRcahj7 zt`|27&EjUUU)(MZh$k_71}aCJZ!r0+}!$E7orr=UmGw8g7|xFKB^rld*WBj;-4_tCd0;F+Vq z&^G?&^qUmfo?Jcy-=T=TIibBL!MA$a!B6zX-jZ;2iu*n5JU#SX3VvetyAp1_Z;|9?x@`U#7lc;hdCNI6uy>l#QMe z*(4{!9SPzpIgQVdGvypPPcD>~%B6gPyd1qBh`dU!qMlB+$_|ibdA01MLcN?U$$s=` z@FY39W=!s)-c0V|kI7x~dU>O~S?-s&^XH|ln&+avYeF87_sIL@LHP(j4mCOsqm(YC z%O~a2@>wBG9u>#rG2Sg-k*~=&Wg$J?cFHIfuPx zyyv_ZyqCOJz1OQZdM6d47?cDhNl8^Qlx!teDNu^Mol1$YUs>k4tgKWj6$`&osaKkm zR;68WEA;=cvQ}BA^eCH@KDcL_vQycu>{AXZhlOV4m@))8PI;P?5#_vcQMs&)D-+61 zVU>^d8GR;SvMC5ru`3ikYeWmUK-*TbLx5`%~NIt92;cNC)`BwX!KFR0zMSWeq z^}db1&EgGTzi+#5K-%Ej`=zSF+5zER(p?}{+syXL#$oAPu1cz>cl z#h)&p^=J9b{(S!uf3d&JU+%B)SNm-kO+EIXzcBv;{lZ*L1bnL@1vC*#2?IzLib2YR zGJX}mN+<`Z0I3GC2^-e5t!evG_Ls6-{jGjH*C_M~EkX-DC$tG$1p1#05(Mc4=@#g( zJJwWbdI6r1h`(qE{-R;=w~P*BUJifD=b6{8i33HHi`=H#YPMr_5 zm-6|j&X|Mj+e1wz9CHB$9|E{mlLN@p@)g}CN&w3iK(1EiQaG->J=B!Kv2q41GZ4$O zN;_5otdOq1^{knwacJqL+e1zBoHAPHpnX1SRs)=ncEeH9j{b$~^Px}x;RUdEPWxk6 zHybrk;g2G7cQuARoUAO#8&HCB?W11&3$2B%CvHsaOqi;9QuG6$nndt*!Hmuo} zmENy$-j+0*(>48o?SKKz=fFHub5g+hrDnf&9@)%*^ zLLbt3(gJnoF~*i_JRVr9_z%>wg-MbPRscbw*o(e!+xjgy7W8?+8IP3MFyGw!#k zV`u4B{hOs%Yg;VO0(15(%$S$44f*q7*&*DTUl*8Tac+%a?i?GNFBh06YqzQR*m<&3 zm^~M65N^$ZGv+(me#%P=%q00pJwZP5VRMi*N#{6r{4m7_=eQ9mB=I1Q8Y^1h8^;`7*X&*S(w&vK?w13fTtF}lx zf?us&rrCMy{wDQ#wQzqeeGX06YoO1Ea%#aZ)zbDT+I=7Af9Cq}h4RGeynsKRM*R$Y z*t0&ypT@>w8gu>ROkcTnhL4=-6LYnD!`iiM)kjl~*kD|2Fs3xNq5PmRjSa5ba@Dc3 z0jz~^g#NIVs64YlpV**%H14oLpJPk`T(UvgHfXC2`rQWYu|fT9^tr$x8`RSV&$rR~ z!SifTFIx`)e1@$L0Nl6kfg|`g+it)<&3|hClKMy*n+d7f^UmG!qga+!2EAs3xY>40 z%Qx2#&+)<2F-*)44+$8L*-mL~9hq_eRn^9A=K;`90&NGx!L|u4&yE?`y8!0Kf+rTh zuy8A;TOh8p-Moc)ah(>U{oll9F`qLl=F;M>nK2fvE8d%``Ms_4ZL1c>HWo+Cw5!^_ zTmG&V#=92AyLR7<`wjvQYuuh$-aZX5wzV)$wJ=7tFg~^CRo>3Cw^P#o6# ze?f({RLyH$uJ#jcGY@{)3Nf42s@?BU%jK`CutF?l1v|Au9A$+V$_jCf6=D|adNp>i zLd?O#cv~S(unwqgraqe55%tH`{c1g|5F=P2Mz9{&`ux1whgOIctfy7GvO=6-9n(mLQy9nAT4`RX;ApO#U# zM4h){V_OIDL>xT@VPL)0@3QUL-mui{es~ZSEo4&d=(N@KGU%hlGHJ#{Ge}R zEIP92XaD&&#($)>GA@^+--%CPPmu2u5|;zW0~7+50!jhP0jmI204u-&Xa=kXH~|vC z4~PP~0P6u80hehq_wBY@+8lYrBJv)XYKFs2=^0ImUU0Hz2ra)5aC zyfG1w0!RmB0nC7Wz!E?)piHfsu^dnVs0P>ojer(F8$bZafFPg~&<)rC=ml&6Yz6E9 z>;mis8~_{w90i;J3O&#i!VfE%Cy!hp4EyYE;B=mBg3^Z~X3c7DWhH((#&AmA|I7+?r+ z3NQjVui>JG%X2WUA@=794L4Q9vl@&lcd+jP@uoRQ2Bgh6W&(hV@xaA+;9@**F&?-W z4_u4~F2(~F|ZeL}u0$A-1d$WDD-D#KXetXp3WnXXK zXy0t_w{N!(*!S4?+XwAOK#to_+E3fhB1Y|F_AB;l_8ayo3I}H&bHv-PITArq9O;fM zhuM+uSmG#llsU>B752@JYKP6yh-h)NIRuC72s%0)-Hr{8UdI;4R>uy1P8!{TQ8*&>88j2c98kW)PaDHV&WrL-m zzM-k1wV}Pi-Jmpt8`d_gYv^g%v>^H#wl(Z**xj&ClY<~L(}y)V1~Sxes$m4u=QX+5 za2YWUG68b4k!>_Kni`WE(;71ya~kttPPl);FEJ49OAJQ*5<@(Gi6H^M#9+cNF(l%b z7?SWy49WNpeB?P(*c2fz zn%0`WLTXH}nf{T~ntozBM53nSrazKS{3^qa|Bq|NFiDJn@2eanj}l@A7Mp>^W?-=y zSZoFso2?pv$!1`(8N8(#ys8)0Biy)Wl$LlBRZ`R+mvvwnh$)0RavuE0K?0M7HrrO)>S=({??-k$|I0$}w zgT-%e=uCyCLc*C=n97OX^sMQ55{KX6NHD!*YKC!m+4Kr|(Bw9WB-7+Kg-DjE)AVJM zV;VFK60_+o(_3V*>5AzJ$^Cy^Iz#Ax%#@vb4s^Xf0{Tu&$7A|&?itXfz#V3438r)P zUj_XHS4Ge0CD5PYnlb%7dX?)1T?jR$_f}zA#Pnw{U4{2P0yLZA5lI!u2B(_cpYDxUcUw-j_QE&2Vw$8;a2U&Zu# zOn(EP`-Hv|>rC~N+%inNKtIZT7IYrw{4%;OZ;1 zbyKhCpTNi}ha6$#^~)&oAL>u+H~_eu^uiTHgw~0MiASF6N5yd>huS z2_+J8cf$<`U$+N5bt_QO{0De^E`)np5&gQTK@{Rv=~eNA~I(X^uyT0 zSz21iZYz*u6iF`j0q{I@Ec{s0XNq z^UXN2z4)wd(4XRVVw&nq%$a~X6YotxU4vs?!&PH_=!n0KdEVxhqrE(X8q)8-tNSk1 z+&RLqPtzV?v-M4&ze>lNbz-^<^=Z8uw4df7lTUskFovqxvUY- zypHKOnr4P+nt2z`zltR+#e2Ij&0=Zqp#Cl9{~h;p(AT-2!PP?UH0T_fX8wr!Pk8<% z?l*W9a*{t`{?DSmgnA#Ll(1yb9LJyiGMbgy}a?A4UBQ&Ot}e@JG-uqJG-2pSI30faz}3SE-Im zg(p6yjxy%_s)2s7rXJH}s8djzP-kEXCM>~(C8T2hJ$Q8&o*Be5op|PTl_4|@dOzv` z)ZM7BqNe$aag-&RlbJ&Op8i{)Zy*ykU}+n$6<=2wg=hAn?#J`}Shs$xTR+z1+Xi5@ zZcyKi+*?gqhb0fA9!32wmhh^k_oE&_-Hn=-^D6dI7tN#lFQ~g{9_Ae^;T=r>7Sq3_ zZDB6xhbSjeU(kOWwSf91)W{b76)4AmWBMNE{2l5)X_~U)J<1~J0m`EHQD4^|p^U;j zlUU{?mN|)KPU2mocy$!djA~~Nf+pC;`}IeWX+x+5)Gwj_CDq8ElPWW58u*Dh;kPD3 zRF?h@^;xQc$#9ijf;ySDl&z;c|6eSfcbHW*6UK8+a?V|P5tb&ftbi0jngx)RCN8}x zhy|o6C<-bc3d%F|MoG)0;;sY{XGq=|qODZ1x=nP2Wd@AE#B$t0Of zCgt9{>n9^gMv_eSNS0PCZUR>k!}F~N{_7%~K98nWjzHGbE3B7XvKM=KT+Cx9A9nI# zC!hGxqF7r)-5m)O&uqlzM)-L6lmyz*`P=Acomjd=a;!G-Onkzp+WWQVj|^5b`y%;dJ3)PW<^k>tY+LW;3Ih$BMY;@_@+0dBGBk-OWPT zLEMU_w@nyPWtWk{o8moqzA%IQU?u)ABvZr7tYYE5l-d=Vf&XO`{jk{+Yh@VAM&xzK zFjHBZr(E_6E?68PXjj%N>_Ng?6BXG*yPx_EsMQ7w&A|3x3Rng#7EZVL6E^#y-;ezE zkJ}CLzyT@MFXEpU(U}D%(c2_=VfwZk+#8!MYcMvS>?Eb>5_P%{+)tp(Kf*P3N+;H% z%@2M7_MrV{D%oQjF(#5bthEjB9N>B)!mfqm1bT|2*$yACn-7SeN_Pc${Vr}ukcPqW@ccz^1aU@X}5_A=_m)UALw zu;Wb&Z_8Y`tQbn^{YVay15bzhWsjB-SsaAV1>s%?@B{GMaE!$v;l~y~Ly|o#YB4Lm z^}!8f$c>aPNTB4a9YJ4`%jAd4_)v1=hv6RKjP52lnEhfYXAk_~{e}EE zxQ+29!E@n6M%_ZGP@V29{psW-mBLt@2<&eDyfq`zV;nxkYkX zMKCXI-7+>``9Hurp?{3J>>ZxlYwFYPZf55)EmmT5FA1s{@E5@vCe=zJ_JaFqr4Y5I zVrM;)AKbY}Zc^SzN{4}c!CqihtW5^%fhY0UOmgFC^BR`VS}cw=g9m=3ZzGU2pw=uw zvt4``WEV68iM_?rLp?@H^&i3w+^!Be-POfoje}2Er(^NIJ*9h`{JouwV!iZJ7h$GO zbCxsoO2M-ldw1}*FqS>$b=i^W)sx^l@LTLmM?VE##PqQ8wb-dHZTXMtKP~n(Pf4$c zoTH|T#mGEq<)OCs0&fki97>>A9)-=E*nHX;i`T&Pps4J^cxejypMqb8_CDzSYQ(o= z5_Lts58eF}~d#b#o1A>Mn4$SDR^#2cr;gWycC8|!FsqK7iZK7owldy~al7#QYf z#YrnQu~P&74r5tEruvTa%qeE43_7{7+y%_ZTu(!P6{UfoI!;s!!*3;+U)G3?M#)`A z;Ag^;g24@NKe!foD%i-@`kDJhE79~Tfi(iTzqI0ZlN(8OcgMlnuiz$dJ2p39a|1Sa zQMUuNI*7#YhNKFT`tD97T>UA%vbY~yi#!!Bx1PVb*HoaD?_IAFeY=4txi=wc0j48Q z7i$*RQkn`%R5S|i$G4l9cd@)5%g4ZJ;6(5naHf&-LmHOTu$+eFG%TlKISucniG7`4 zGcDT;Pc?~7}1%qnZ=c18;gtF*hOM{XeIvR+!@o5)N?mGW^DnIQuO?s*~SXm z&-#7X;=|0{yT+bIyo>1kh@>1h$Jyq9#TiICiN4J<+gYvK$z#$=1~@f{C~p3mVw-KD&n_B zc(ofI=!VY~ep@dXT$Z^A$1@{O($5&Z`jvRw4-TVO<&mE>n=O7#PtFi~>G*#EQF=Rg zLNbq_-D{-hd*Gub+U>3kvJT(}6G#-n7rK}fiH)&F#6u%mvAI!wruQi?Y8GS@3~MSc^Mt$s zW}XP_IY)oU*?X0o5=|}H(+wv{y#(asZ)V6j*-Ya6=}yAQoURph(>YzYMRTd#dCf}M zp){v=vl_kwYw7ZeWq4gNv#~HjFqTE+`UciG+v^$VS10Paif{EY@x0y&uMHB_=02HC zlbbo}i~dw*f16-17@dN|l@?9i14#gXlUX|ke-3#eEZiaX3d5&?gTO~BEWi1a_8!TR~1fdM9>{f}6qD*{Ruc zH5opb4u2Vh`#0E&d&(Kx7%hRl*g-(uyG2;%#h>1KWVRu*n_MIPc9% z;Bs&-IGj=$V^8s$St2}^E&Kv}&f1xYwc`mCU;P4~AwJQSIfuWIz$suaumeb3$(cFi z+^ajGN%ju>;1|pH5@ToOonP}xVAq$!USJ1s6Zo)1Af@Y(tVc3bZZ7(3SecHBGd7`!)>H>hVMw}fpeT}rJRiF_q|2bc~{ z2>%w0JuiDJ`XeOvVp$Tk1P_2Cv2aCJs0rl-#zv!!5OaS}*z#YIY?9sv*NL26tig_~ z>)S}i23y3M$PIgze;#~=+wK&XqsSQC0W~+@SaoK61@l`X1bg$c4wZEjozZX)}w0%h;62H%%Jk(}q1^(dM%rTMS8`@Od7lX)vd{_g%u+!+FFVM44>JnE&6N6KZLp@C2jp#5Pm?TRGnkaV z40b1XA@MWtZQE+V=S# zbyv`?2j>MT=qPVBLAtr0d?>rat5|!L_X=luhP3Wip%1*M=;OQ;J;K<#b5mXfF9miD zvT|#XePk>7mbldwXtxU|t~7X8d9l&$XeHt`fHw!73g$qP!FrEj`7peyoD$7h^3rTm zz~XiK|2FH+y^4HE1eT(oyY(7D>ShxRiQ%vlubQ_7%@wo2;_s~1j>3cAgZHfD1w6I~ zoj1rQygA!>Y-{l}m?nF7kR6*jna8*3|8w%{qBp_s%Il4;0`DuYH{L)zFqyHRl^zDg zDdn}z6fuP?ZzZEMP4rcZ^|g&RvqE2&7j@3bi{#x#-!R2NiMJQA&^Cb`X5 zL(nvo7aM!-wVny4;-6dSr+~SG6H4v^@|J!CNjKtc1AI7scoxgEk#I_}dxXSx4SZV^ z5Af-y?G+ghEYBLh3+^B`(y%aFUT;*rRdBo08hj^?R{1H4;C~SiF1fS;hW=lAgu{4nrj@d)ImIpP> z5iH!mn&|&Y-`0U2m{Jzoo57qkB>&$QxoJmfFR&nZ%M4Mn4@%!kpu^6hFETp^@VO_b z=LiOK1#Kh?c9Xj1wzQ&8VXZiCESI@8mqYRnHv7Y8V5dKrinr4fw{;u;vB~0xq{?`8 zEjRR@d_wmGH*WWdNkiUqvNMAvx!o7TdvmDu5dLp3JT_S@CsmdcV948)KF>&NGpDJ{ z{zJ^vKzI>&es20c)(raJ$y<;vOFyg292w0_4W$o7f^rrg5cK!c%0F@j(7EwRS2VYR zWvN??TDjpqvmc5i7$6a1Zwf;N-Ma*}MliY_@HYkhWAF#VN5Rh|Gb6bxkziv?_%v_{ z_OYq&V?@4q-s;?;|94pL^39nC;&bF1IG~Pih1>H(=JohX@_nJW?P2EL_(aR=#5c)z z%;L)|wuHBgSC;Qe#an>3t<0sAmWh9h=C@dwL+J?lepGx05{sEP;&01$tK#ylq!N+s zPv)NZTk?G>+Nvadu==yC{5O$jj*l;%`>~gp%M#;G1A=Fazu-sP2JRk)#TGk)VDC$tU1cFbSL%m(TlRXzm7G z-BIA<)Ex%*DLn-q0ndOpDQyLoM)C*vCz1|e6?%n4xmGTK-&6V*SOZK)z7O6|`sVFN zG7bC&c^bXSkK`b@0GtP&M&~K`KX3)dGhSZsWF+yQkN%*qE{jB$Lq8eJClclQIT~yU zZlH7re52@iPXggb0pla4SoqubF%|a74#x_K{qe(kHIOC+)CCUkD)mSyh`b2 zS{dU;3Qu-(fzBOxrW-H%h1?h^-AQi`3Rlddx{(;EXts1bo@8zQm(mN=dXLf^*z5|n z08{Z{ok(6+%AiSv_!Hcy;p5@MT;!m$4a`KI4CX{LaIu8X|3E$j`TgL7l)5;lZ@!D7 zTk!Y50!Ru+@+sQ^B;_O7i<=`SGIfuHw?&6|@LvUUMe;hd3!WW(1f8$pm9TIeyet^f zde~pku|#^RQhK7AS1eqev#+2!3r}?%Ylpxdk=R^@e~vPi((sk&kBw$XPvFbZXAkne zjE3L=nTuYO7Dw(Zx25$Y`o?Csh*b4ovTUIKpw$^3p*HF-Kkr8J z3E=zGs!1%p1AmGc%nPm|Zhv&U27V*k`?)FY0+s})C8AwQ%Yq6t;7eGzg3faIGAtiL zG8LVlX}xfKq(!%;++M)S@)@K06Zzka!tGGsgPW*Z1I?OXqe$KoT}IuH4*RnA4W)0u z&&dAe9YOLaSP%UL@KV@(7s*06Cj^gmVRv(h%ub1(43^KAnTrrjH^0Z?@?D7U;M>t} z4Zj2~1OErkC;PE$gq$e!2_l)@Gk5`;+rj7P+spKSN&GAMycqeDZaqe$Xjiy9xs^w9 z(zOM@&Cb$>e7G9sG{+ie?QkWf)>_hXHMEnTu zK<6*&)@l|%9l<8RXM%gtKZZo-hH9Olmn`V-lb12I zQ@GhBsNV!X(I4B=1K1n`KZMQ4<=xC*fz8fn))Nd~!rCctJNQ00OUr9#2|<4yynwt= z`8SZn_;jYIws$nGMWVLp`4;yH`U~LeL_c`g)df>1EvIM6j;SX}ZV`zs75P~~a|S*c zd|WUnP2GHg!6sTi0j^H;P%PZ9UzZ$({1~`f_p>+_onlBLdiA@Yw^V;;<#|MI)?lG1 z*k8*onSrMA?(sXOJMcdQ{Q!PfZmfQ&{_D?$mykYtyTpQb z70pq!`#5!n!Lj3=@=MEFqYr2N`y_|>1te?vl5^_$xg{s~@*R&^G77(juO)l1l0x#7>i>!LXgJdQjWc~8MucDSbWXK)#~89WbeN2e+LJ+KLq-e4E{_8WbBkkZ-k zJ+yTiow3Mg!M}j-0&9U!BmaQ0>~00gcCD9vu57L4;k=6l%Aw? zF-TnLf9V_X6MTiHn^U~x9e^(ftAo$d+t%=FSXfKltn`Zc@`+&|JK-VFpzk8KD7BV? z|4^66G%q8ehnjgz8X`86i0}aYpfa(_sKe`EPWn@l(!BH`3lbtKsD*_g)S_?3&G-%Y zF|Y-QPfTMCl}SU`#yX+7AQ50-N$C&!&$$fTQB25w+ilou0Kg`1!1!w(fc(c zJ&B|Tmbaie6W#&LL#^V-iE8~Wl2TwBkU8>MP2MJIwWn`gL9&fuwfe)cfakpp;7;Vu zhmV0(&>@>?$D4z0?c?*n54?eX=sZIof(Ga_*8#aGBu)(L!dw7d zMtT@5i)LZkC8|vd=w_`pIEWU1K@*8__$c@e_&P}R>J{K9&}Cy6AvHks^&=oX^jD+f z=9G*bl2J`}(9JA!q;r7GTDXn6E@u7%o&(8U`Vu$+za2*ZHA-1Q{)?1SOS3DPe&9;< zkHVj%6wjLxaB`9F*76eML{Z=}#%5ydJ>u;**3MY)16Ho<`F?N*b;%mzI zK3Ux(kA?UoAW!N{5RYkAlWqjMeStkllN+^L^{(e5K`g{(2qv)}19q{H%oB6@Y8aB2 z;I7ZkGpqvL31rtWA^pTxx(`S$4Nk$yQA)`T(F~5{v*UE|h@id*E))y`x5- z3p&pWhU?KR0zN@$Zum3sx@b-Vk0Vb;-cvA^9j+<;8C(W#2G4`r(P;{Q4{U;@H`s-~ z{YKv&q;xiX4{e=BXDsqr@Gs!Iz*^wb$Uk5#`H(ydZbV)N{wnA^K#O`E?V{ryMDh_9 z+^8Qy6VK>^@UP)R>D5GdJFqmha#HIGrD@3DKyrst{18?^;^b|?s%TE84}XHposaj- z+tkW{7ozkerHeu4SN}_k%wzBsn$EZM);j=S4ps;8OwbyB4GU|LWW^>?SiW^;>WkON=pW2){}#;#^Ncr#`KxBAE|X10Sb9%_xl{`3ZaAu(Jj10OmonIHkmoeiun8unmYmePYksM6LGp zp)1JRG{m+)91D2Q+W_uF?!5FESOp!{zIMDh=vE3|4P1s{jHV`bE@OxI@&91d=!eb& z^dV?~KJyi@azkRn5WVIC=+^JUU|BQ^(=HKcQb0E^wZTEO_zRjyjKfF4cfi*{B2BLV zM}aPPxfrMcqOTtT>7l8nIoM8WY)rM)OE4(AMhOLvcV;A0)9J; z{%e#H`TmQPQcIJ=O+RoY`bXhUQi|uz2sjzTck6Bma#le=%m=P-`@tQQlJWFjI9X2D zgA>(0S)S{W3$Yo3Nvx@WtR9jFVlI0O zL-G>b_1TS`IMC{sD*2YzPODj%Z^~WMpIFJ0yukb>a-GJj zS1-NG;%B@^)e5p(93KR-_5)8=rI}?>i^RW#e6)#_{E9^0@%|NwHx79{IGVvaL6eI7 z5Wm+LZ*J1=Y9;TGcO}E~jp**^>=6t*!5e~QY4IF3kI}b=CcnjzrliF?T7IoF3He~~ zs*#t~-n`&l<^``7^5aNu@q+g^FLIxQt+jmn>nW2*_DAu9-#}jNyvf-A8J#A)-SxuG zC2$AW4g3m!YCXjAA@ZW78wJlxU6K1`m(z@_v z@Lg#36z*Ms2b8X*)@da9!Do=1l+U)*U37e@rEbB?VXY=QbHHDb=YyZ2^eybfkWUe= z;=;W+t^b4kIW*g$Sr+*sEc`%ePvKFk_}_LOvx>xIjpUoO)hPW=6|#5?J~)yX8;ay} zL7iLVx^DEHZTCDpFIWS-qncQ}j7@x{Zqv6iqObd7^C)--`AqSHpCLS0hXwqgC(^F- z4;I2?thv$ML+1-Pe@n_+F8baz_{Z3EeQOli*zg~qKR1x{MCTMd6?_5gDm^r>VzUe5 z{S01%o;-_W29o8B{Sy3l>JDerufYe<&(pM0Ks5b9NZjaL{B!`HN2epb{QyZD`ib{+ z7bJIS-HmiIUMh~YGe}&ErLglU9ze&dhs_@7?2S z_T;=;vK*yVkar~pVt9aA@cX0l2s#bu+d=B)VCTh@j6|?%-*J(%!fzz;jT`=abDfS;mGcGX@`n0=E zctEdoQ53f6vgTIr1hFNG7Z z`M!AD>=X1K!v1=ffAC>U^QVIP<`1T}xmgpNYs{ay}Yha-|rIXRz z0iTIHO}=g7kHlIUE&hPce(H9N+mpHXEn~-%9+thOV4wISO5PKsZh2bF4jM|C3%@0v znUh!r65A)}Kj#zuD0NpL;iTlb-8MJKuIGJ@&NqTVNBqy89>m0&Nn#y!r7dRMe2(S4 zi5)~N?}1N%PXoySnlq2zk=Uyl?X~@E&CWYMl22gS?^Fx)N5}2i+uK50uhXmVl$`v@ z+9y_?tYV!A} z|HxZ`lHUl-kIP^Cp)LIGN;&m; zYtVPQInm-j=-c_SX9MfWfXMMqfOyOwht6F5+>6<43SJ|;tV;AIM~f|fB&ZKEJ9Fsm^UUw6#2UAA=hY_~mqhmFWrm_t4awfPz1wD9mK%rG zs+E${eivKn&KMs>@_RRCO)ZG_lXdG`$y1Ts?=n>lC1+9j1#vp#-H6{@_V};J72lQ8 z1;nObOYAGfUt(ACS2u&Kylm$M74O~=Z{Y6pT;ygRrS3DSPmu8Wm(ORKhEF2QRwR51 zqq1T@tJqiAj9!pm8bn*2`0+L^~+M!luvZ`iI8{P=3)+ zEjB|&%_u5|*Qk4mKHsFYB=X#X^4Iz7=qiF&8SfBEzXxN;ACp#Mh2^iR#xBd>$PKs2 zU#Ug^g|LcXtcLv6R{3p9R75mw4<}=Pq{V#5OUClzu>tgf?}^DTL+yxOkZ+5@E5WOT zTae#@m&cBim!>~$;AP?MuyYXoO!y(>H^CQ>jG%O-#mBJl7#1qSD+|xO6E+u&?Xi*+ z;ZX{_s=f6J=EuTQ^uG%I@5H=Mq14WP=9K^p4-hAgzYXsIZUS#&r-1yTB(?~?7z;nb zM_cSHzxa+?2jc~qg?aLu9g8+LqWA5MK~Uo4y!=K!^J+L&>dH6qA}=!zuOq*Ck#F`! zl`}6|ekoI8xQ_6s9oRDJA@k@^zL%c4I&-b~UnEiGh&d9QRwo6C@ISzd(U(Z-P*?Qt z!+xcRzmuG~htetZr?>n~=1k%+%5Je?R7(7oxdF|S7RO~u+ztk3f|WCW1Fxfb-s1R# zocpelKg8cV=N+Xx_kFvE%J=HqU0?S)_2}69O>dI=K?QZ6Zk3{*soT7Dib_py)h0y^ zYudPein`RgRoxWNp8Mi)m8|lqtm+~4n9W}eR7=&)=B~HZN9t2+yT6*OzEz9VO0_}# zYH!k~5;gMMeXxRhToqSO+Z^}2>Z;zcJK8wgpZ}__)GW1Ftx_A+PIX9L9;lJ5va5=A z?@LkXsj z8>v21S`AcF)oisytx=oRZhPB4o2XGxORq*e2# zDXPmets19T4~dCVpQuUpMq5`6Q8UzhwOp-J+f;_V z16-h17FA6>sYOs|9J*PUUH&ie6z8a&xP)T+d z8>(ii1!{%*S#4MQ)d_hqq8CNgedeFOWW2{YMA;)Ewque zUhPl^)JgS+y4<@m8ptmV4~h1$_Eh$K;(+8D zBd8*f2DJyvOl8}fAqNpF5Uo&f5VerGk-U%~ki`*4SgiovO8VdqNDj0P+_#9gz_-=n zCWuMMB;l`_EmjLsDTJwHs+L;?MqVmG>RIY>E8#2IE2%3HnBo_*-fKo4h;^8Zq3QwZ zG3pIEBc_*uE)g-|v=MmWb%R@j0fPoF1$2E0gLQ+FgII%YgCT<@gDQiMgYJ7zv0Kkq zICEFtByD=AD zw#{i@11gl2k&=;}6quBn6r~Y}CQpqVnlnkGP$lXXsuZr2x0bP%v=;yIRPX|3i{8`2 z<1ViO*vdaTz3984My3+~;`@X;Li$&OdA#r6({I~}d_co8Z2d=w0lh?kOX9Pa?Kg7` zrtues%x&O7E95q|pC$871c1*g?e(!n{5T}zBP8RLUgjzA!BeV1eek#ix%+*cOX5a1 z(Ju=e5N1&;C;QC*z_sBwRYx5AA#USZY5Ogig+hJlH_bHq30&MkSvK4M7cQ!}`XC;|1ebE;x#&-^!v!A9fd11proNKgYLct&%bGN67`^V%8iTv9+Gq!I zAF1;f{e;zBvo~(s@%sy>uNtU`6cSaTD4C*KBdWt52&3vG`h;lb3dM9phgh!!)Ppm~ zuze(#p+VtOsK})ra#PKh9l)qKN#lDF{ud}$fT5qIRtHM6%W7~Q0#1_sH`Nt|b!qlp zDcf+UvlB|S{4?S1bLn!#8WL2CydIxohi%~#M8ujGN;9*u++uZV*(RC6cRjvDE8qHM z@MUKVauW`PCA;j(w|4^6^6|N#P3)5JycsW@!f6Jr`8+m=lb%$i9`UE!zE8(Qi@3Mf zsfQK@-R?Scch%{-h`5fsYrn4elH3ZNDfvdXdRXu!a>SEbyxBGh^bO3q<=vmbWTOQCj$$mNfN^z2NE+_!I75o^pSO=c9S##KRTgxcR-HReA4ykT(2zizEd9{x9DU7l51{%TG5 zY*wAK+2gd!Zj#$Fx5TWE#W;0zT(^U47}#pG6l#rCU8p)tbf|1%+j2geJfpQ#t*>70 zxw;r_y4te0guTbEk6)fXIeE1;ZL)88US-+(w8Xxru8;am`K;SSZ)auDAHX;W&>wB# zEgpK4;ct_7LjixF@`FX@9hwo1(%BA_c??9@x=8Iw{fNLj68iz0_N}vWF z6joBgP+bhW8cA5NH)#p{=AOO+vbcP{d?pIw-NHw}x}jr+kq)-n>bEO#xG^a>P zf{NrykRx?>d$=#qQxXC?0Zt;sH~Iug#ho!hoUwK6K)3IR)WOkM@`XDcN@S=cC1#Mv z@HfXD#t^t+;Az1a8$OpdSJHoHT6OP2;An;?+O^nx&?u5X0SxFhF+4&Ns8kVPL`cxa~g zHr&uKBpe@b8X%jVWHMxo+}YNqx*cyC@Lmsj^|^H-T*KhJ2=F1Y-Sv4hSnnCVV1^&( z-OlJU=Z!rNpzrQ1Jxhp0P`VS3M?v2xE2F7kVI&P1lSiu?aWNY+uSTOK(i+34sy8QA zsV7^Ltk)9PS6qx2ny|0Nprve@xT(rqLBSdfO)XE7Uu1Hw7+yr+nW`P|Ubb9NeNdOS zEu?NczHtt`f=sz6fVz<9NValCO%wM!v*pN=&aJw*CMX{-a*8tLXdR=Ex#;Go70ui) z_KwjKud`g@maEeD2p&&=e8RgkLC^Tn(y$XE;vW3JVG+P@B%cYCW&8kwC?U^ed@|^B zM$hQ*d80>lMUl9LeUZl8e2VZw&%|8P$WtoMNXqKcQ;Wjj+yb-kM9;suR8ps_p3Rh1 z$7gNCVlxZ(B3NAl^oS;pLR|{U3sH}Tin@MPJ?QkOCY~8(`D!O>5CFnNb$ql5FzimK-y+LOYtGO2WPOyjQ6C>| ze6%`CuFt#*1GL6tkYem1*$b?HB|~)f)cE>y?oxS0GKx4tf$P{LRyY6Bv55@3w~wyR z@Gy<8=X8f>5Jj6rOSS%;6-b*kakMjbzm6X2+#XIB7^1DH zgUWQW*Un+QNai9LK3n2qF z4;%8Rz>8Y=V9$#id4l8#DsnFWK%t-<2Pi5?|5EmY9(pu;W2P(^Iloo-Bfp5kXekd! zDrn3tFBOW;tu7VD`fU5c9Y53XL{DCDdcdWu>6z8*mGH_RJb#N3Z~Zw*^Z<;1c{Bn`iLG~(Dc9- z-PZKz8r@cNO2BvonCoBwbXU6>RaR9z8&>)VUk^+w$`kZX-u~qa&M4~U`y1D%^-xg{ z_rU4{hkb_g2F^0y@<8jZwLRySU&rsZyOg1b>Ttiml2}P(6>is}PwS6G9gWrt5(g3| z2x=6_h#B*pF&CC_(^GWaQ#3>1v&-@Z?cPLfg~IW%&G_{5MTlV}UoYf>Hp=iwE;C*X za#jEy7iRU8%cp7_`rVBINE^^cmGQ@7KuGQV{nL3#pB*<)$sWqq&yv7owO zMM1uPQ>bfnIAn`#op%w!hNk;WnvHES&bmdxuil{m$haeHOMD%!1xJF7jV0W=WfsDC zUnpqI6#-5ZCu|*#1PA9W{)cP-BO5pBir^F7%x%k_Xl;Fh@}sxtN3U4YCH@&4?s9k7 z1v++MG)#JATH#mvQxV0=;+KbJ6{_FVjDCULV@+|7zsLb7H zC&t65;Wml1cbxa7m+`;r1e0!Y)ffENVFGGupP9-#-iEd3$(C+2z)P;ixtDRyb;7lG zob`{LuIq%DZgI9({M8FDkgGnrkl zBVdn%-yR2S9tQ#Je;CY|uUjpy>hTYZJ6@F)g*$(1MyeK8xr;laZHl zLFF6r8rM{YpwmUF@kg8zg<%k}nga(ej5+}pM4~n%BHa_gRR!i1L8uk6o5Qi5Q|m;C zO{XLmVyct6@IR14Duq1geKW+g)?Z$MbIsZ`>8TI9fP%2S`NiHgrIQ;>aZKfbottX5 zli`k@n{({!6g6I0KDTIY+sLAcV-w>l22qqWCyJgRYT}^rCpFc?nDaHUlColgyzEgc zf7p(Mdwja=x}%`_n(BT0>yG!Q;HMCb%O9A(W@HmmjQw+L&!#e)XmiZfCd3#Qb&Syd zoi<^2@cXq&n|gU7hDp~pVg11Mwdg}~E8+Q|253E+#VNgQlE;*VS9~#c{ft| zYiilvdXeXKba@wd`J->yJVXH(L1_7hk@CKgLP(tOBQKQ7GmG*%v!cn2s7u!`l}AJ6 zg$V`G8j;6Nbd~$(vQ+jWsV|_VTRG(+F9o=3aWrqtrE4_hE_TJst)ctQUA-xfdanz7 zOl1VAr*PiDUn(Jy`}~z(oofst%yQ%^;plFyAZ$w!@bcqHfqyOM4*$9ThAhftgpwaw z5d4#yU>0nw%ujx-!Kvz}Ec*8V~~~jd?t$%c2UF}Xn%~U7_)>`BZH;@S5e9w z^gNDDG+TV1`-nRP6ZU1y6QY4L3zraiQNtV-(*z|Jn1*plv@iZxKVG0Zr8JqT)I zjxhzLjEW7aN|R_=c}(ih9U0~C_fb9tnWv=B{8n5-2mz?qfRA5N<3x^-$%z9843xCu z;|Yi);$w;mVzDVk1(mq;Bf^}VigLksj*;2G^kWu|*vj#F6Eg*c*<@ydWSrvD0poWt zuVBgv_lMqPzk8DPgjiowKA_7dh8!6eYK6%Ba*PmK3C` z6Rh%^wJDbStmfZUj=3C@Hb848rW~0UQ?w3M-G#ph{ro*0!#03^PB$Gf7Sr4gb=;-5 z(w++fya@>e2K-U%^Aj?rCc*8pR;MmzS0*ivg2_#7nb}!b?=w9LGBUO&5vHaBO$E&j z(Ai*wr5nOEKs7T&rwV7+Xl&8L*i0oGNE=zDvr2aH8lpA8*D~lc=motRQZ-<>Rvs@r zXXj4OoI~W~*h_JoUE8@g3!)YlPN8%pg$ENuPsFf^V_8Jp<`H=%gda%Z=Au{zJBo=s zlR{5~u?y)f!hMU0-jYHw1+e#c=Mk@eC<$ysM2m0)31L`rIL2U>L4|q50SRI6A2x?Y zc$|cAG$GtAqeXZ^F%cgT9AhNQp!qza(T{)>wjqs0_{@(02^?cC%OL1HB8sH23^5#I z2FoDoJfhOi;OCbdmOcZHD zv=-qm#YBLl&=+_W3n<8ZIa%4~xjO+=u`&s5o+EKI97%xH&`TAjHEW=l^D{a7L`(t= z!9-X>B_?%fLM2m0bV4OpMQnmKE{?dHU4I`76DC#+BuP@j>ZqYHYduzim@9pSA=|^( z)p{OYDFrf5llH7uSl*bN4f)z<_mJKFaY$!}Od(!15J}ta=eQ(1352@e+eX8+tZgyF zAMAh8i(=R$8xmH<12*3;y6_r(tcloTuoj@OCZI9#2H2?vII#tA%aF{S+-l%QOTJs1 z#vickQaFtIIET@W`3^cPV$-XJ)#`-Z$T&mfNc3z`w1yQc_sv zl_4&*_~P&2FZgWzL@A~|>{z2;7_@N~B zsIh$x96%IxYrJq~J2crr_x3<^hL>Jgz5&$sXw`i#tpO=Fw5@P%J9HaC?>E#u{$V$e z_yZ{Jkpt-lo9a=^M>V%xA1=CSJ$>i5>>fT}=ytt0cVZtlTj}h(vL4J^*)2P?9@JZz zExR_a+?{xKGu$_^oha9nrMDm-g#3dD_aq;b{KIkgC?BN!L-O~`A2j?UGxsnb#65%b z_jD;vbBD{dtB!7oXplLYP94{tCpD zLWQYiw7MuRA|P`LEanyNbEG-=+Z;%h9xhG7pNVB@`f!d zBu|lfLwt35xQGx#L=Nh>Na90`{{g*D@qOhgCRvnRx4vR@!RpKQg!LW+GAy_s@36vQ zh|3y_H4=j|EV-ZTu*PAO%{q;B90M~fx}WH<`ZCmNsLfi9wH$*pEW4lTu-Ne zW%0bc+EaK*$*%nEjCM(YRXJvHy}Zt{FtgmWwXwGZjm}0{>oL}{bgcsZXM4PutAeh) zB2r~jIs2^Ivn;n9gRV=3U`g#!>2vAVW3K1V`9#nngk>#uVQ9I*nJ}xiPqA28+>*p& z1a^s71>>0#tE$i6;eWT5fth9G|HdpMGt2+}JGBgb)1FekUjlwC(Jbr!6SZjAB;r$* zT5e+5rdiOfNWJvCNzysiWFcMtxS^ z{wCuM6wr~^(fg5rQ~YbdWA)PdnbBj@o5p7q5WoxY4iGp8v8rVq#I}TM;A;%k zBG4eIjH^ljfLax@j%8ZQ*8SC7s5}M0o;z9nWu3^hnW{U|)KkB&df{$d+aees%6jf~p(<-T4nvR@2Cu)u;7k1H3v#)dE1{ zywhc_-CC!?R=uTi9e{UU?K0DD_k(*>i?111NdZv8u{L$mS_!4S^!HigGsNeDCs##sW#Cei^PxV>vHrj5wUVXmQyM%ZWeoy#Z@ipXk=`~Q_f*G+V zP4yjz;vyPxrWtX?73Z!-IU;pPIDpif|_9O3EIaMl~yEp31nIwC8g(&ci;jyNGq`Rae0R+_C+QrxpH2eN3&kiE9ms5$jR|2U8J1fl z`2{!JGLA9WRJTU~_D$}+bnWlls9En4w4&CmSEtNTMjAoJ!Ym{% zj;5ff?d}%oF^g+0ckpjgi{NJw*#bYGpM>Y*bc( zT4`&dh*>3)swZUviVIkG8$*kvXnJAv`)P-}z6T0O>7laK_EH3H$~%8!eyDu?mT+q1 z#0EZsb^@ckZ}-4^9y$EOv;Lg{o5R5W{hgkZmzVcFI_ozz_sy)aHZkDW5cwW=v`}2$ zX8BLE!i|yJL!*iKXaPI<)Y1TeEy&r3eDv`YoKSKy@Ou14V zf9IqsisZ@0&iN}P zlshVCY1&kLZS@k@RgQbv$>}!#*vtrT{%`Y_s+{i4a%H6s-ruATGIqP>W_2wpVLLzD z*sVB?w|tisE=#;`TCMYBE;N%1>Tf19{x2&4;GYXNp6&8?OTAm*h7JFhyqR6}(-M{$ z6@yz?18#iwlCcXR3@?9b5UU|AA-mO(rl0{Jv?+k{3Em1pR9zeZ6Ir))p;XpOUOP4$ zPCL-Ko$R(-H=8zc%g5mVydPvhNiaUrOUaiS7e>WG&nvt_Oyy0N7zPlwe+=dtT4E+xTaGe;vgd$)RoZq z4b1_iza!yP=gLX7ili!-F5dO0_36+FCQ&A5nn7W}Vd^jYPV`yUk!bK~rhOlBpY*wd zOoB{StMy;?J)V?m|I{L{<5gl;jz57~fm+pe^>OuaT^#S=^s%pW>woI|H1of>)?#rZ zTBBGG#D+%4_r+$&PMKb`uJ&6`$^B$Dbyq+%^ZtsjU`AWz`vVbsP-p|Y<(9LouqwD9a{r!RwgJ+Oc zepu=LfhSPBy-kFSy+*5-_UOnVs{M7-+ZL%MUTZeS6{bUR8t=F{YhdbX!@in>Jx6Ox zui&*|cI$(=D8o$7X*$p}3og?vm1O`ozs*FnVO%g%9)8ZdUXpnXeTrzECG6s7gL^GM zr)ru_;{3wiRlxH&-3gY7gCZLxevb1nI}q|X+6kPAGc9LAJ&D)u$pW1YAHy()IjVA5 zbH4?ke@;o~=l5g*!;-MeR3$^PFagU{6dj*oY?>iznzCwKJW1y?n$46pNqaxq$&@!q z4>KBAA5Sy+RNHl7)*N?f2C*XO8jfcwzM|+Fjb}!&BIz2LV`{dd;ToG`hOr{*8lhv_ zgW1n8sN*2NfzcBQu~*cN*1crmqGo*FXpU*`$h`2_YR5VvcS_y zIT|O8*rf?vvGu1l9Wf{h3@x8{MF9^3&TeO~KTCn2LdTAro{D9J46AXNjMF(pT>^-= z0HZk2x3&1zw;ZfLW1^psRxHC_Vuq;}Ha;L%Whxx0lw3rA@E=0P$!Yl{s#SfhYbBm> zNvT>xoh=PKu?7JEqG(=$4b`z8Vby+gNUS~~9>QoAbTo?59P7a7eAO*JZ>V9)f0Qhj?B2Z6kNO5${abZ^$=-VT zsL8>)r*FHrZZoi@x9$_(58`~A=!gL_b6_e#Kciua6VcSyfX=`8h|h_?m<1tIoUqAb zgC}M@zhw!7$p9P|QlskvoRhIbHf%$eF7P8g>Pb*=Qb4=_(zIY7F~;MB1$9W<89lPV zlLujlkw7OHIX#I^SaMQY?FQFFzA5bh&i8tPt%rVVDV|7BFYPJER^o6pjG%e}|d z08eGm?cGYC`!Bmq%$_vSk1EIA6r7Rr+TVU_^^DY@J)cW?&-h^VYy3n7y9z*%} zG-K>QcQM42sHI+Suod(mY9(}4N@9@Z4F?XVtGfhP6(z)vyK|Pgo^b^VS`oF z;&Vb(SkQP&8yUdGgfy|B1LoA#<&Ac^E0wDIz$;a3d!N;7ctT^;b3pYeRIUFR@T*#6 z>~N@>w(al$)X}vEG^wCA1|!LEuVztB!D{(;PK_w-o@y}{>$jSy`wgaCJlV9i7Z6s! zuO+q6<^4K{zBq(u6TNXSU-8a%?nba8zxH7bf+?dW2($phZr>cjTRzsiCj30$lfE3l zjPJYY!{)LL&@-_#Nzc*js5iNXp|9>T&-xK=GG%aicqk($XkXWZdLPEnk*Wf7k&2DT zs8z6$s)>av{)Io!n4%S%qZOK){AsMG)LccaViBcID^$T0ttdvVN>pr=lAHStCR(A4 zTGjatW8Ib3@k*@#|I_|?aXd)@fnH$gop!kFvP>^7U+fdi<%GnPA&boHR9!VSOtkJ# zC2&RG+0N1&Zrop(^S-zG0BcO&b9J_eDSf9^p&!Vp{_E(G>$MnN&QSc;!Rm&N3ncPO zLIB8^N2?m#4NoUx`8Vc~juPiAhQ}CS1ow0`w31_0tP*s!MMJVaMuVzeR^6grRs(j` zv=VmpsFG$Cy%KjdwGw!htrB_FHQkMOJ)uj=HBjbI!>CP0)-^)bz*_!O|o%givz!hDcjbbue99|$arJVqE^C;=~JFJTCZ3JS)Y?=PXvNH~WkDmv&N zo}sb`h9;2>^ZjDIGlGPAf?<#pcCQgIHiJ*^~m81})D z0`v;?8|5xe8EBMW5sZkS1loZ!d@GnJuTNz6Ik*V>7j-%zcCUaePO_7rOm9r)gFxFa zGJ(^mdcJ)q@Buyn$M=;HQ+{E2 zw3@~J>&*WUDG78;9uLzOU_*Qc8v8X^up18k!J8{!%y=_K?W-@JH?xy3R0dk>j;4%4 zra+>vlKM+2$6sd(Y#stc<0*i10_47t;O_MVXcQwqCH}n-f=Dl1Rq!fKRT$qNAaE51 z5W)`!2;v6=gz;rk4jl>q;iiFT91`)%srY|@sv!NuhU_OcDL=6(x95!4Lc7BoF|rK`!h0Q`W{**5+6?k(dAVB=D&s@OgP?8S)$WSO;~w12fyrf#Vw4ev53k zQ@YP1E%cslAjb{U24n(kBgU&4Ie*>QKgd<@Xr(y#gjtAF`V(Oedby!jdu+K8 zhin3~9T{zy<$}-Sj^m z_}_dvvgYmCRPsN#6nsf2d#IDQL5Asd8Nk!IU5}*;6kETG5QQ(0t~Tq)h}j)zy{+c_ zY_p79K|K+JRf7a7hy-o!1vZ)TZ8H>FfE8K-6%`=kwixd)o3&% zbxGtR7M&-xAf6}XO~fY#xwkZt6eBefiDd~f4yEkH)lx}B8-rF1%4j}gSa3z2Y+MS> zX!c}SNcGQXrb)M`Kw!3kyZPM-%^3RHOwO?FioF%8Cm?eR{{hZ~XS%7`Td5_T?lKXo z(W1(54!}0uoDSA#f&U?qOgFh=Oz4du`qTkCxB7g(;QLU$Ah(1(K-|%+JJNmT&~+sG zuAVo(zFc2WlT%5zo1=$dXug zpd=SW|8|~xE7P5>(fw0E2_a`yAPb=@4Hyf-tqnK}p;%h58G%#dqcK4~Ys6)SpA=`) z2m!c2KyV15MuF*=Fh^AV895NaNeg*&?8QF^#;Nw!gSBDb7crmuc9WtDT%#e=yBN7vidZ$Yq(pVB6T!2YF`5E%&Y!~{k!du=Q64#HbkDpI78F)Aa zGE6d4_6TX%w4)&yO3*gsx6J)r6ck((Y(z|?F%%-KElCYSjh2GGh_W%EbZq=?^K7sv z-T*L%BBNqo9rOjIoHObOJsYgIP=>;RE(MgdY$rZu@eV#ZGL)x^y@3{@>bvdBag)IZza44f2@PS8ClYiu09AJHzVS>d@uHx}@KoD>0Z#CWjd%7*R>S3~1v* zEh?($nW0flaeDQ7(sEs0s&z(kMftjwgN2rVLd}iB=RBUI8AX+)9{tD0B!?5Wo?_`J zRvuW6mx)@@lnZyU4l+0&uZDq-$D@zva7L3&M@H1yiwyio?o%T7ZGSbf!&Uq+aHDhTOajOHObj|kO8FWOr%0K~tYt@~8aBmRC*gR%G0(o8*9ujo)S=2W zz0@@~hs0hL=4en=F$?J5Fs34jh~Q3C6;i`c*a&Fq>>>Tq#7OlUV&FF}#FqDeXR`A4 z*O{~9yFCM%-m{@MJ>V1q>Sa*z$dV*6?U0FPs;HC5AnQmIU;;mFmd}Qc@{eO&;06a{ zIS%FypyaP`4#uW~Nf;~4O%rS~UCgbmAC!5!eoY&0hSO^YtvV&ncNuusGeHsPAKyiPvQs%Z?DsFE8r?P}s_i3uqoOj{%muzPfGdo<9hZ5Hsm7#XI! zUf*V8`ONjTt%}5p9j-Qm^f01O3uX4}GCL8>rppF#-eNaNsliUi+NNuG)IJ#{oh2Qg z(NW|{b*DhX(znxJ={(-u2{?+1`AxARwz0xqYYd}t!}1>YX()DFNaTcf#~$REiS2kI&J4Rllkoz+t$o-Gv>e7 zDY{^*PSqvnO1*4oW!)RanpUi?yF%YpUgRx*X#ZR*yG8bt>?`|hmNw;uGEbXjJ#>|V z6T-hulES()>Hi_7B8cU`r1(pf%t&AKet=C=NFn7Ly$JaW9akYZ6db*K@OqiIpE%HY z!|0Q^kb)33D!s6##?IUv7%4KHN0%(|{EHn?Dn|jYVqCO-pinr716uV801dd3Q?h}5 z3`oJk!8uP?$Hb{qhB{=7Fz%*K@Is{Eqai#A3r}UPodeA6C(FCe%Tly!DA9G80D?k@ z0zJz}wmg=^&% zM_(pr^7LEow z>)se_ZYaUk{3~$n_1O7(a^5~2MV=*w`kXOG{AZ}9kynZ&heh2<;?eniBXEJXT3 zQ$_THEkv?|NV!-#*68y2*EQ)7dw5f5wn-H5I9cdi&X8ydz0`Hk1OGe`IaeFO|Q3aOK_WP8ZLJ*>AiLkytwaI?fGM+X0a&2D?0_Q)34NAwIDnzp>pyQ*-`RqcsE7iT8V zqJRHGERSMPhWDuP5mz}L{lMlNCwVG91xtPjPAlI;)fx-G%J?_ba%rY$g9=Bz7mW+Q ztoXdiTj_EhZ2B_N5xRHDeB-3Ula|w50ZKXRq5}U`UlpAC>WsBb)lj|8q%vxC2(sSL zw@i<*;@<7LQ`HuB{eCz_|Cj6;-la1|Lo}DRR$}ilHLBXHzK^L87vx0c39Jitv6#@a zu3MB|4-$r@yUG%4J+u)-QIZjP7EC%3@w+_1PFsZrPsqv|ui~RScC)bXm&C8l5U?u$-yrn`st3de%+x8;8eVnfc-qg4`c0&Yd|{yzexC zX&k&l0z2DKh}yA9dD}Dnx*5N*)9T7%aV=k8sdgvBdEgGY{K654cX#o*UcM<%dO{m$ zQpZDZTL5ARArKpoS2qsCoWaguOy(?$PSn(8 zuh@`<-|C9|8TjXmM5H6zq=5+zoY;G@g8^EIY=*aJt&H%+G%U}`GnYzeU-=$+N4b}q zT4Jry0qZjTskL;57#hV>FXuaKz8N4gSy57mD?H@CvhWOq)n$LNCHX%<@9=11$}6udJB&n%4%0KIni&_9*8 zHFCM;qr`CUe=SV(8+O5s)G=?Px-?@v)w)@jI~FQ?p0}I(^PIUlujx%Gx!33G5Zr$r zNcfXYV4nHlyc%0X-bE@>f03B)PjmOAbYlG3hhbX%a?I%T*vX zBjtBAq4i6)CWWWu|Oer7N!t7ovx1#Ma+)?kZLQ(y(Zi>1=!&9oXy^6#=j|0d;u%&>)#;xGnkhaXc52=N zi2{*=-GxxsoS|6p%?EMvq3VrGS0KxAx0B z$-|aTXY0`wUPo0XHTtR47XQ}$&ZL~0N!qxy4zk?u$-WA&YA)qrWavP755L<{^qe-G zHOKQlJig#H8)L=qyL}L>&PfAskCCWo*H;+u-{-DyUGNEWU$q~K?H5VnawS7k<5xBs z*H!fQIvNTtC2NV=cUPrD>q542Z%e~nT$fVYq&PZ{AQsaNn?En6JW0G9O^F<|t8EQd zKUdfu03NB2sy)4AU(g%_Uk&NZ2y5#7w~>xHL|Wpe%1=tf3OmS-doK{OEvI_ zZ7XWZQO)+`Kl?I}czvOH`mr;7KzD(W7qXiRh9BS=?PPUkNKC)+eV{`mzkXgGWe~@! zQ>j|(DeImhG9Rq#)Wf?WY|1F1Npxr@Rzt6rv(&u#M{PVoGw5*le zgNTL%ZLaNEYMXI2oYsN5j!u)2#JTOnT(QVdv5+Eh>-Hb>0A;I!#67epqpFdZ zn#;8&Zm!29+(nj4W$$CYTkkKW=V=`qrJ`7hijg}=_+e_c!%~(CuMce$+f+r|Yc&E5 znh&J~zI6;CMS|sX`sz>Ts$%HKiV^{kbT z1_w#JZE5P*MbXUn-duPkQQX_-Xw$Pfw9O}-_NU^i&~3pIL>PvYQvQceGeZ;G+jXBl z`z@5OEbQ9v);->&=zI=pSg(lcOO+IFn>H>}sPo?oY& zXg7c=N;!$e#%4leQzF(vR!tw{dn~HmiX@0P=a3Yo!Dtn%GK?L3)>g3O#zl8kqqFqdy zLRZXUcN=!gH1*xEUX#P;H9SzGG>(t|Yk!h{)-60LYZc}7FdvH4_xm&aF3K*p5@8wl zbA^(gd_L#G)1o~f3cw0?p^nQfFI&X{mPGM~;dI+&a6qchepVzzHRCN#6iClzQkG%p zHF!`&y7>DG5fp5j(>J8wuwRx11tieKkVACa{fYo~ju)UL=>@41geplv8tIV9HUHYx z9bi!%F=#1e50CrSHjmzOLgDeL8=lf~I+xiWQ{l?L#}z;JDQdjQfIzRc1K>H z*B!Z|o6C5{)ieveN!Jo+7yH*VOSZT_Z@w&1M%?MP3UD! zoDGZ(oDJxeTnwH6gP|@fLoZ`uYvycD$jHLR%*O`@{a;#m_}%RdjI2zY2@OrmENpp+ zuRD5(2`!9yiPczT8D#B+P0TGMJRMDxJmr*)Jgtm4jfwgBc-*<%ZR~A+%n-WUSlc>r zx$_bm7~2_|aQ)E#!KNoB{7(^QD_-Is6cJi>21a5&XdXvnQ?5TEV*g{(&xn`U+}YWl zi=N)i&5h2DnaqPgTj?o#}+0eTi*wZu8G0^{qBKrTB`QJ4C5AXgP z=l@Fg9}6>cXQ%&r3y%LO^Ph%(0`GhHYZCZLk$gWH;=gh%-~XPYf6_lMvD;4u{-0L@&i_^k#4N0x zO&saPtPPw^L`;nAj7|Ql1TeF({Pzmrp6!!3VH?DNDEjOjl6FemABu?#MRZ72cOqQ! z`71CC^&jR$JeZ%JS7@;%dJ`zX;AmQ#8UA^wVD@sfpM8CqEV|O7sh;6MO$&s3pkyf^ zJj3$bf!upp$0TqzV!{HmfZBNhLSwk!4FgwP-qCOqJ!+Dw{*DF#^q5>|Fhj?ryX$R>KaXctRVfqSkRk%c&1gQsM zeVrmpr>H&!l44cU#7;bDW<) zNU9V1f4W4h4F7G3{;N(CvNHZ~|Iq(mFBvBj2OH=ASU*NWMov}^Mz;Us8eVuqxF@Tu zJ#k(y%8X5tGFv1WlViZXs1p;=$PTThAOD!f4_YEe!u)aBz@j^_K@?K`RVCvHc7Z2&4{7f zXf5S%_)=$Aea;?3<)_}K-XEFBIHbZJ?PE)2qz8%>#i`76G+8Jwb{%1Sv7d&;jEk$K z{paoY*iT>P^+9NuMK30Ysm)PvA^aYT+mm^pU29kseAt{tgP-~E?H!Z))85g^&6;mK@ScST?FYBpmKwXyGsC}?a`k40Zv@`;J*pbeR zhS)%N;I4!w;q}Hlnfbjl#OnC&RU8L1>!;aQq1N$?g*n%Q#TL*5Kggl*(SW|sY<%2@ z>cRV@UZbJxa{nMV;|}ofJVZ8csfUBBrY??=*E1t}o6BzEaOg99cVki=_m1CP@ehzq z>R;FkC+@YVV-E~=noN}M-g+lYuZB#<^Rg1@)S45=hA75d9Ff=gBTnfVU-eUCYle?Y zBQxUW_NT}Ul5Xo96P#C)D0ZfVC-1f|*1j6w*7Lw3aV|D-Tqd4KYfvRjvc`o5x#8yw zS6p64WAVWPdwJf(BW{Dbk_OMeFgU2DW^LB+MzIw)8}?{6Y(3B=VwLTHmZ+CNf1O`fr|CTDj8Le%bdSQgZ&|3`ZmC{b9jbpwS8~*$w*t7~0_Etf41zoo&PH@|}CHTe(t_i^%Htz237Tn$4H}3B4?(Xg$ zTmm=WJy*_Obxxg^ziK?p?yg?F9%l8L)ob(^8Mo6-v#18^?DguG=1Y}7uH41cH%}WB zlWQA%T(mx!5==-5fAc&DR}>sw*GGJ;Pq*K-csJ#gMR$c+U%zxD41w%C9GA3pFQq2( z{*2xJwE(HToZjd04S+t)4uW7ZNViD~@!Db#2dN zI!iepias+7HU?yhHB($`yLLIeR!BsKt5mI1q~5yY*=ni1gO!GxGn3ve+I8E!1*$&C zTrg^`bcv^bNd6{WufU(+_}o7G^s($aez5Nm`pL?ShIeyKqWJ$ldut)XSIJ8OYL29d2AO zilqXXonU3vB8qEaNBc)vj5K0*+n}Xt{-3_%`X8kEAH)Lh1eK)oi+!UHYgvgL^Xq{Cxge9Pv>GgB39Qsll^Lb!io0 zlcwXVh)v0r`-si*R*Da$J7NQG1MgZ*G(D3+7z#TYXZ0 zewtEG0;L<%6S{2O(o08xn@8}u1enqfpjB3)+UO` zbZ3bayNQ-ez6+)2`KNUiTJt#q(2ywWjodQ&B2{iza;Yi{@_<~09c=|GS@9sOrdqI_ zuArB~4Eoi0`_ITU>&K?U3+vX7%_);*Q_b|>GAOKN0qJmT7PE;B4O*B^M)38&2YV}= zbq9J6xqFFp?IoDkL#D=P+emu?+SuBs*Z+|B?|6lv5!;%}GrY3B#Yl_q8n~v)GqU%u zF#mc^i6^4&;?*orhGWN zE_<=>m8tLi>wy0E#+JZa;R?lK?%b4f3U`CKcu-YK+P=ID^)=$#J4#tKr8TsJLU$gC zEIqnDO*QJ#YcgC`7mE@kTy<&yY|`Q`l|_ASJc#&FVr!sMp8nfq#%9FrCuP>KNTb+$f=)@I>==kD|4&zcJyrVTTSQ# zxY);uaenijto%AQW?9}}Us)Ajw(p>%^RxA^!MKVWsx3Rgz z-}hZG+V*o1j;`^8xT{+Q_9EfN`9MBc4WFr;V4exybUKxTw7a2Wa+;~KqSAXK+O=M) zyi5pDHT-ONq2WPL{b65c=v}{@tfG(RyG|Sizw%c@2^(9Hrm+ zYc1er7@00^Lw}QPJbfm>4E&$b~-FUDpuu%QRlf64jnUv^_vjN+hG>d0g1Og(-jJSL1bFBWh<-4kqOXHe+s zxY-&|VJ_4rqk%FsOjUf!uz6e0idVqA1&*UAfE2nrB2K!+b9C2@BG<5exKeO>|co z4Q0>e&aOrvKd751$ITHPDWR2gxX*;0fttX7zW(hHPp(0u|0o$J|6u`zMn}|=6DhwL z=9(Zfh>UH^<*-kTZ0{K+6sdsgA8)&0g<`N3WR++T05~t?5({?*RU{ci0m=*2C~$ z1*zW#oq!gFC2?SlaC4A!64_UgBtQ~KNnC+(5CEi-Vvz_B17!k5(g0Wmcua#_z#&Nm zT9GioAP6AAA{ssmdM>0%G)M%PinD;iF+j*E2B`p85OR`1C?KE^k3ysi;0{7gH1Gwq zg6>nmIRI{uk<_eeI6d%t;Yci*b~qdGReU#rOgS6?>;SnHh$oXtgbM>VKosH_Od^?p zTF`*_ZhRk5qyeA+;wq?-(oY}*A(jJhfD@q9g3#DLnjk^MP5=+E0c2JnU$6sWR=!~b z@)VxL?%@KXCGCa7a|)l^0X_+P)IjgVJ$PVO${sJUD`}4q*p<9T2Sk;!7Y}DDd@cw0 z#O>t*e3JL%K<^6SOa;$c;XlN0(*W=V&z*oA$=fghsnl&8fK>997wAnl2oLID8uSER zr0i(}x8nA!fm`u=GQh3aJ!ha!!k#ivCvJ}u)ImQe1?r#~L;_tT?70K86ZX`BkCL~M z06D4KM1Y)Rtynm9ftyyi3y>sXPXXv6bsGw3FZd!cOC=&79#ZHg9u8l)0u(6+po!ae z1D+)8s{v2q_RRoS3HxGztGInTfVZGUCS0?yMI=0gG{^z0N-!t~ zEKAx)0aT^zlK`rc_CWy6f)=gtNl=5heHtJ|(mo7;D`g)C__Nl3*cdWyiI%cV!dT6( zrQ_Ms@o49Mx%+<@;FS7y{X=WZr={c5&i!-u&qx2^-;nV)w3H`O#{b5F|No8FcmFi? zA6kcuucM|k6EoWKYHhi+bX?lGukVVq2liBQC-RL2@H*10!t&%e90$dR1aK%^X@R5i zjF8Nr50|jAgc_pFtZB^I%w%Xvzci$qVb4m^Y6`X<3Qrno;YbodYe+T(nz1OW3pd1` zT*w1LK8ugKoig=OD&l%@P_^p3MxGZkTEshp;KZ}Vo+kXhGG6fNcedxY@Zi6nyUuJ z``#9sX%tBnPUaw=mNgun+lb*vYWG7WPSqycXq&=a`q+J;N-g(j)s}7a5PV zQ|MS1#VZ~D=P#$&lWAceFs)C)25#b8ri0Jd*T@ryq`%oGir>9|-LuS!36p}7wiT|L zg-HVqiv70G24!J8#Ts%VuQ5A??m1>Pl@4XVoFmUXvzEfun4Q0ry@l?-Iidhmcbtnn7MR9tJ!j%GeQ#c0w5^)gV|0^%`G?xSX zb+%s^4TE32A)zGc#7`c1%F_GCg9GVor;-cW>_71nj7V=Mab~=;C<{9tW7gzt(Pnf>+ESfbLQd>S+9FPrv)IC#p^U}p8NlUVPWZEh!YSz5 zL=Nn}jEJo!0gM!FUk}oecydlUV(B2(01ms%N5{chLO%(^IOOjh7OsfE&fiqA%ox~p zh5ko6g0Y3iOV3R#x+2ZYM;5W+x0Y z!D2^W#F`{amylha9Wg$(;qWwN`;YTzed75AxY(0?S&0T)d(DHV3GneQ+&gPrW^%Dz8zD|q{=G+ z&Di2{N@C5FXb`Wj-;u|nkhv{>l7|L|5E+;wlhc0T9`X+kCR)t>_Dzhzj5!H~Yz&Rt z;itQjqu$6jB0_YB(9Sfeg`D)KeCh*qV?|T1u)30ZX)rR_3EU7XBwUIX7xOAzD4k~uM_%97ew-e<_x|#XY3w8N!PFzTGu@LzcI^Iv$Gv?Ad&7MLzr(tM z>g$8{8}YaQ`|wVTFPh&rWOrlsk9|M{&zcby<_*jLUOCe7(T9Y)$a?z24GcmB@Vrle~EF(28`*|6{0p0}^aH*7bF#%aeA zQuU@W#;wN)dt@(bvsd2A7{&vSR9dPuJoppqgt#T(i z4c+s%$E&Bahreg@$UD2e#}&#ock*(F_^6)0S#TTC3(1c4UgqRn^uCeUYZGGqp@(CK zM~}{q!473jJL;qAyUZUg^Yn|>KDO!lL8sk{NjwYKgshoCqa8JQ?D92W2n>Vv?K8afm0yT_wvgd6*YdvQ@=}U`#)QJ(RT8Ctx zBRyqHNsyP4$79%Z>^~|FD(T#BB?a^-RaYe6B(Ei-j74&}YdRXad(w;9Y%NeZEX80l z(AelI(lXZCAFnK2s8js^o@Z1(&Kdhr`W046K}8%hB4!3bGSZ~trf%~vF*oM|nTs2N zGiuDdGxGAJsmk)WsjC{esS5IhsaqO^CBPC?X`#QRu*!ZvEtPZYa{1(EHAqsmn1Rd) zk72OJeyp0~P*{jVutUw!NRbRQD2YAp$!2o*R2CNo5DAzpm`6v3a4mnYps#E%Z) zp4!+InqcJoDw-|f}83!7Fr4Sh)8oGUoiNHZ3@69-oe zJ6H%(ZWv4ql+9C-BEsNNQQvr2hEjAa9PKm4_d$|;j8jDLMB7|!Ri+oVYuFi4>sHzv zgSJA>ng!G#3?}V30-uAPyh4uh;j+*a#&W75+aQtqRQ)uNvIVQ>gk%&|CaVp+d87eg;}AI5wT0d9Omuy0t(>&FYJ4fGqJYCDoA%Gn7H*z)u)Mp2 zqokW{1gdeqe4VQsTogqoqAXba9AVAnGn>p{B@I$%F0JEfAulbWZ$ao|62^s*vWU<( zw5T&>)NSSC^&FJ$n9%AX<9&}H(gixK_R)B!RR7d@uRuOlf2^h|gG+BDG7n;_dVWy( zoX7ffMceuDqmkv7GGJDFET}@F6@rVD3vC4^6UhpO1LEAz(bu_0Ll32fKn=D6Mg?Nr z&$tJqhfss3215@s1vdqS199i)-lL_5Is?N7RqqFvOOgsZ0dwYy-{X{vQvzA$XWpaq z6+#Iz=_jl_sx%}Obb@bKPufp>W=K4=Na!J`!k-B8$N)$~-&tQ$8W>SXQwVZDj2=5Z zJb4IY*kFhNKf#{@vGB++a1gCOeR4@-p^c!u{OG@8jX=!#vE`!eK!f}MJxFf8Mqd%c zVK#n3p`#5z*8W7^fy(^Jh7QXG!K(*N21%y}IpK>C3K8iGIRnk}leZ12n&2lSSC1N2 zNR%rSaSv0E!p@f))*IIy+a9@|m>#sArykdy<{r+T3g^9V~$0)`8Rk-GR~p+kwyl*@4;t*MZmp z^$zET?}qTtV-s=(o)3)=o)75)HXAY9myR;JtRBs8hkTIMrcM@Mo30DMgy6APWua==)cpopWKf>hChy1K8fCP z3_l(J_njG#nUF-L5X1OA_HcIpt>OQ-roiyl@yZ*KXO7{u~D6_z)niRMb<1^y#O#w4Tf+LTL;=gMFD zk!<5`ebRT%?n>{mg;tg3P<6H#7XAp6igWSh-6>CB7i}Z7@x~Dm%g$kX?Z>KW*&44! zck7hSdTr7{>D?xkLt?e=V`6Qwn~(6{%jj{cjDAf)n!hbu8t?wimJ1c+E;pWEMOGO; zQ-^-X-Imbx9m$-;sS~lX=W50?zPsVU<-R5M$fVTws#wBo0+^Z5tw=T@{*cN`Dd$#b zqR-SFRoOR{dDa!k>|d%!IXgeAG3J+C3c9oOjk?g9m~g*%uZfpVMp_BFAe&gDya2hZ zRv$5*t1wuxwiDg`hHd{tdd4t(Sk*VZctKDRQhCAC6t(H=Y>(Cc0(1VL{}y$j;zGC- zNz;y+yxu37C@`vH)V?Zoq5o*cl^hjHAR;_uY{L~Sg%R*@bK_4!Ui4gf6}=?-%=p_< zfnOW??S)^X0<=$Kq2rsrfHWC!V%(1q*McYzD{zEyScUZFGqJ`>+ij9`+tMm#WP^Ad z$TRyIbI;*|G&L%T&(9Q+IWSuPV-6RN#d>$;lNavV)v`FPsg~rmU9(pq!Yv23%|8_h4(`H5wiJL z=j4a~GU{XU6%x*YntOf@wQiApyzQwsevsLUzom`-a51s%fy-|X zE(^6Q{p`0<(;RP;&qtKunvM7AM;{J52-gCxK08rbxB$g#smp5QDRI*HoE%O`d_J1Z z6oS$~>wsWn;=<8sDHS$ZbNs?kzU7WPsY(-v5S`T%y3F)yDcKtCN{_5~JlsWFqx4P( zkF}8x3AiZ1>REi0G@;>wWCnVPzcV}H4ucdT_)-4|)m0QBdHdwr2XWUdm~ zj>3mT3jYb+p>jOcmbW%%==r-l&vzIXV0`Mwi|W`Xeq7cCzU(m8>kVEtUol^^(;Wpy zlER^~-6MRaEdLR_+}JQFF$fAl>UU&~JYMp`@s62T&yj&Ty139UU{RhDuVkWR_o^|R ziG2qMZ&4o6tM|h{sQwlRNv%0C1da2$AAxPcy$0K8QHY z?`UUWnq@n15G@z18guW2LxEbUm&xwrmEU+0Ukft5mNX)-TP!guSAZnNRDkrM1jkp3 zQofo0j*c|4=SwN9amvODuUfd;^;*^A@cl>XPYpM2|Ez(SrhK}*z9!`QI*DI;U3-7e z=nM=OIdh<*>$9z;Xv7gQb$T_;V)foHSCy^UczkSyHC;?@i{gn|GUE_ElF{LCKT9sk z3m~jc7qEAK`I^yNu*_!?6A|uYV%$=G_4=5+?&IzjJifk6jGu*mC>vZ z%;$V{a=+o!NsgZ(S5Ze-I|fb-seGiyF1j(RbpQ{Jg}L+{pU`j-5yRW&KZPdsW72RS zSXf~$U?=2OrNXdtAb8%aazNGA29k|$Uh;Lyh?NTu8FXu5I2$aJG*ck+x#ZJl=(o1II6s8^lSec!d;<|ti%)t~j#^x_sJN9(uxmu| z5bN+f@EJ9Tnl)m~Bmit0(i;r(HxxwwEa4rxh_(_BP1TcKgv}}-xCkBp%HGQE;yh(W9A`}MFexp|DYbV>YU6yF^z z>B_EbH!%}-g3tV1^GKMr71*Lwj8T;wT=@pZ+8yKy*t`sP;U(kwFsmVO;^{CW#nhof zh$(XQD%8%utNY~=@&m{+i$kqqmZ_F!zh@P}svhW%Yj5yaagm06HF;yYU~2Z=s_c_v z(I=xV!TLX_TQRdMjQAtx^l z(HVDhca@FqlVI`CVaq0;QHf9mRPB2ItV1Z)&C18J#j;rxPC%jF5p1LBkD9U?qs_mL zqS>r1j@|uvQ8mIh851lDMJ2neCY&f6E+7!OgAx+Itu06cXU!U@MV&>d3#bc+)X!YJ>mP>5dxK$gResS{qFn;A5)SJg#Sq~g zazs$#{sV0?9Op2#1$1>`J1oPuRFV5hvR4xfulmp~^-MIATM~@%cgBv|=lsElO~2_o z@5FkwThb$iug?mJgO8OxgyPZLP0M}Tb#@Vyw54RUxmXdE%pG~CxDFkb7r6S$DI2v> z$|*~o3m#QGJnY&v5~W!NPDKNhZdpUo+VZyshxl2g_P0RU{O>FsIC+@pUi91%3iyk+ znG0)Zg=bvglR}jz+-lKxEvqrZpxOjO(&$BI_CRTrZ;C=A3+Uh311}IV!-}dpW4>Wh zd5WxPx2$@h7iAqFS10dB+Z7HBJrP~jVvK2jx<=CGOg{3$g-m{xIoAi6E^$4xg+iT=3s!F${M*sB7$FSaG?}L0QhFQ*BD7+GX{Ox7yw~`sH?wcUBL~$F0@lqbK$ru1xgyB}u!& z(I+do8H<+#n#^Y7nO7%YGAGeS^GG`R`{GKbA_WMKZ^fJDZL3Keoe~X*nZI&yE-(CG zWX$`^wkIWnAs=w!g_c%|NUpSLXVJkrCVfvC2>V)8yza^P)fZjniY`M%ea=LU(da$ z7rgqPkKA^s9?zm4Pk*m8$HR3FwSO9}DHc;ns%i6=AX;~DcorqDQtIpa_lDa&FZqgC zyJz7W*>G)}t~MhY&SkG$Y!0;nnLY#b&+YJ`s{XZrHULf(VV{SOzv4g-5GPSl>nU@u z?Km=@`S6Xr!wOy`m!Y*Mk>7RE{996k(!GBs$JCargw{GhV%C7@cb29uNYpTop z2|f0ty?xDHB(8dwy$H+RZ4c>B9Jq2Tucu3NPqx6-ESA5)g;KVuNl7}MUUzkbrY5xO zHZO(NOAVghYqftz`s<6f{{HrzZqA%eejGEP6(j@j+mExa4w2lS4RW(x8%{?-AjH<1L z!^&Yep?{y(YhNG6tI^=UszFXKi2=n2_NiwK=v^-Xi z8Bi%Q4+$@A3NPLIZ2QtzV|cge#Y@0p=PMiaGq~$m?CS$-Zgfr!)K1VS*mbF*#crX; zI?934%KK@|epWsIHCmUCao+r5!+j5I7X83=4-9G~PjD>Sx@#up{GeAEa&1nu?X)xR zjuRbQ0C9p+p$-+((`(u3aRq;>teOH z7|MJ}NEHW}Wt7teVcei-K_$kk4|BkWOOdv4RW4OoW?0$J|A5w%%;pwF<;#vDQHumw z{6QL;L;a7YzWg$iGl@(_OwN8E8;~;+=CHEeF+%)0){zqD+P+=8gf?xKBsLLE!cy9o zH$z!0pL)7w7lm;(!GWGU2PM~M&!ObPeI!Qn@TEh^tc=RncO}#A>dwclYFC}wuTW*` zXz9=ZL+8z(p1;o)!6$z1RlD?ej9WD|`)7xfvX)KG>dqf2Vd$=^*Nr4u9NUDJr|`s` z!UB`pkaa7QnS2vYBi9%82nEeTg(X6TRYHq1#I(x9AuA3*O>*wcf@V=n30*Lif+4Eg z?G^;1C#2v{Uri`3BERAl3$3?oWO>c=kpzK<6QyW)E3?pax@;=*A`I!*L?g`nr~-xW zX%f|;Z&HzJmHWUt}XrHjV4a`^+J!pBs!VR6p#ZHTIGI zUF*!HZNRmAYTUp^vi%qn9}f1zi9sNO>}+iE*`ISKN5W#KtM0r_PikaX-tts%$*o?@ zJ5-mooJ*tS6-y_4J%48}uWG+-Q*JzXW%uzBiQ?7RlM&tc)?QV>Mq+bOZLPHg(q4C& z9Xh0Q(aNlUAwx|#ab5{P6=EhqRAvz8ptr0n&FZ!wkBmcMI~f1^LOGEH--+p=L{`^? z#<0?@p$&fdHYWC%e_(le!WXO*r3OuP<(ZgyZ4zW!FS2aE7RqD>Wuez8t-bYz)I_$R zl#<$>z%#I5`2OqzfVHpGLFOTn+(EvqwC#Is!nW$Azsm)*(Tjn(Ec3Y{@@aS!8dAYD z?9ceJ5}Bvfz6C5cjs5>Ku8P$lt=;b}?DA8Le8un->4K8{%v@mMN5Xzp?{t{Ua~6j?n2vM@k}c6S`#UB_v#=C@u)7RK)N(dPxPYZ$F21pT|0OCaT1UQ0!A|1N7Dhl|@=r?3rdef} zjQq)NQ6@3fz)JeyqaDdYYf>&iFj_#S6} zc>3njO~(+Wr8efScg`E>b!ANJuTfc2kHJG;13I+}rm%cW(wt;G;3SO#cxynZ_^U&q z;-E~TD*OPG0+%|9Zd_%kTzW&g7;w?$g2(;*Z8h$f1P+5?l{{~AhN-KXBRmrf>#jJ5 z+2P%Ft`}=^%_?Aq7l>?S`czC_Hk)&Gj`lbx zD(Y1@5M*pmRvD~sLK04&{sh8|R^Q_g6JM8J8~F4sG&z1Zo|w^BgZS{E-ay7$7BVCh zqhN*Oji-awc$2K89XBcx$Wc+6-waY-Qe2;zIiZnsXx>9>yMK9;CeY-;k!_Pnr}kp^ zUQ)bVA5J5p{16tMNgYZ1ZC@A9xw34x;+8d-x~<*aT4-)azG~2LX4kW!m!JhzZu-wV z@aBy2hy`e&iLNf+>dT7H=WKGKKzvruqh#z1H8tHPbP#D|JZDZQG=XfvSER13o}sK; zqE4CD%3Pd*R_iee^ynI2KybDikK^fEh-+&LkFFD<__`XM5*v>x;8bRC`o28r#iytq z>NfXvWn^eJ&R_r2%EhTbBFcNoxA!|D2?ZkZGtUESWapa4;*jF>jneXI;^0hF@AoS0 zFL3V|mgAjt$&r;Kjn*Hpjm>T4DeRNo9qnrs@M5C4YIe8E&M7`e;DsNX^Q|_5MkU>b z{lBYMk&|28TfFQYZk35UIT>UatIn&@0{6ak?$p2h`fwXj=z3Meu`i# z2M5pdu8cT}lWBy40KxYOk4Zj@Q%LE~tTbHQ@(3i`<8BYv%1> zzgn6nKE>&a-+bZ>^u~Rig|ZEP#lw)$M|&Ys6Hr|-5CC00jnjW|T%gzx?p~OcCcO);5IwfM#INXh zM^asKwfb#G(+;lRvYe@NiD1}lYkN5&W-%{lJl%V&z!yT-#r6UZrXa5tTFXUmKTHTm z>@eMG5bJpIVA4eq|2Eo*?zJK#T;~0C!m9<>!B^1gC&3~!!3dn&`X%j0m6;`DX3dt@ zxE44!8`w8@&(>>uU#6s1t~6TqADCJdN~%yICeC7LT3JZKyIJCUm-My+ig-Q?8s+9A z;Bc^uA07YDDrJWYW~M2kZv=sr>`NDwzzfMs`;M5iUVl%M77@1nrESy@e zhEdm0i?WJ>&_wfB8UOA)K@L(k7V_*5hMV%MAH^7?2qIUBZt~);D=c6t^@dh|HuEuk z%&DWNI(pot6;U(DI9^NB%9p8vljUIu2Sm02wRPBmFHD# z=h7O{hfYPo5&u-?NwyX?+HS{HwVry6TdVCgZL@tOG!e$@PSvIva8+C08M78mo4Kq^ z5~k11GPu}kUv7$Vouj?%XYAkpVt1-??6svNeokyvw!+e9Im@-cX8Jnq!75c^)0ma} zmQ6vGF~i>MXDAzw3jMJkjh=lexOM8s^f_}l_V+C_5$iY)F1&?B zU|q4}2pKM8Nk!gT!=AKs25-lOdjBD0dtzQ4Z3QEQ=q^M>eryinM@(LP+4+QT5cqVr zp?=~oic%la8Y4>4dfdRwG?u!bIiytR74%41XbQj%1vHf3Aw}B~_x$5(Bnv6mty~ni zy8AXO+c)wMOUC?s;UQDcjW1t>g=$+PiXoD67XS0L%Yd1-$2!1RViab$pi**pQu8(4 zeUX=O+4!!-RkM8zjHHv*>@-tP}tqt2g`$lWw@mLc?GdGC@veG}D7iISm>*_DVbZX>;89x^0T;|Wt3fPoz zEi+Wl?;et;yXljN)Mq&D6{d1y4!7G6&Q3b6=JLwPqO=wBCoe0uQpOY8cyNNt*5tcL zVcM_8YrZctYd$qD$JL#(71FM-{zUl&b>k=TDYZ;c_k=qz zH?!5QEK4m?qjbbdvZLhF56PHP8=hEzGboqy)B+f<#y#5Wjy&kv%GYcz19i=N+G_wz ztMmLFm7GU(BdnI^gqPCDRoQFGT&#|NFHf_57N^D)6t^fp(<)|^zB5t{T?nj@=#p%s zA8(W~xF(C80LfG3D3vEB;9HKv(f|6DB&=~^s%S`)3ro?@K7qpN>l8x&Vq3LUV+Wo^<}c2hnZ$~;f5{JbbvZ(an0>{-Z(J7wU{{Jhyp6hN#T*r#nUm*@hI z8v*N=yDP=a)RSGPQFB!Jt2=`DvmB(`eAau0Hqgmo{W0Z;{|)!_Qs4$pQVTAE;SyIVu(h`dWcIW5Af!?r3y-Grf1AMh8i@zj>rhdkuZ${ojVJ{bX+Ml$qE zEPkopjRnc%=tAoV$GbMi&My4@AFRf+1)>InMZcI09s0wjF?DgAwnMbDj0eTOf}*z#Wr!l=-{O0gRILRNzKyrIz6BY^1? z(?=ypbE4m-pf^MU`Da&989SdWIkL6TxJ%g8&qIqkqOB$Nhr;Ry9iZ-<33xyj_Br!} z3;3fh3@MnBCm{NHETi|u(Ns6Z{}LZ$L5+`*Zwh3UIF*nT8#C)LN&da6S${M>!-t|u z5N0n*#^~Wfb_HAtoxKd;D7vP?qayWoS#4rN?TSB>2g?fb@}|9 zj`l-MS9%P|v%Qxlf5wAt*tA{d=*GqhhW)e7yV+Zj9G&H}5&DX$Yi;(Gwkwr07AQ@$ zQmah{Sl_BpU<4MGB^$0kqSC1GtR}so1$J#(t=wH=n_PX3PkoIXR)>gc-8$P3!rdUm zdz`;g$9c^(_vXpEBbs~>^&Sdg#yAIqiaz?bv%d56dkemH&IYGjFr{%z z)*?Q@`Pe=3#S6A*#Ha{pL+2J{P)F$~IuPgn< z-Weo?&6q*!%mHA0i<}XV#NUTcladU+m`j|*zI1u`Ue;EO}55gisnboLBgYX zvlsZ`sp-FjiqV~AcYuE&Hw6rY>qqF*7Iw@Kv;P$#3lr&dTV`w@q8GSKShkqll**5+ z6A28?-TBf(2JzA|aZ!46hN9tCYaZ{KibfYmjrq<025U2GblB@c{f5$O+pPw3BTX;#P4 zE@bi{N7`dAhW2Uaf}LwZHtV;XDa4E9$Fv%L2S6PDZ=eUBU`oQiw`jHYG$!@rC6oRohqXa1(u2udsNg?GBWONB zQdk-M1&#JDUbyW>rmOBZLH;NJd_C;cAj|nA2%1cGy6RNs5N-A4^Lx1Ov z?}^3IX#gs_rewcsfH2ZzlX|;{jikDnpcS%yv&Ta&+?9WBOy(U;5N15YblQ8X$^-0 z>~7$I$ScgE{!qRVj6F8^2Bxe#-uJl<8Xn`E*mW98?10_WUS_QoHP(M%Xff&(VA{ z@?wuZak|9f>VW-)HFHprAUg47Vxw98QDJItI*{D_nc*`o82-8si@x@}RaN~F&$1?9 zMeM@k(KtC%4<$Nvo3KxRmfLzhpl{2NSvpDvEpD=uHB~RLM=|RUAu{tX9QlqG{&~&k zs6|5ij_=I89(oD$mH8QbboLqvC#4>&WNco*rZh9~0(ow$nX zQ;{B`ohXQ0)1Fmzj%2Fh^=N>Y(6>j^Ct>8oD1%v|-ha4k0px!2b5jI=NRu>)O;Fta z8J`({MA+@HnS>+}QJ`rO<7CehIKK>!Ixt+>vT<9#C@hfZ!EPbGQ=}$^q(R&_l9+n? z8bJ+6WtlQbs1sILt^Is&q2PQAvn9biCXchpnVq%1*iB*OFPjg4Ij#6^ZvSV9tFSx@ zb)z(+jP9tAm`&-##?2YzSlmk_B;IFxT2AsV$51k#~v@7{t7 zsaYy>1M5*6l#JEN{ioK+rHGG#{RMu`eW?8SQ2CF>S6>s1HBech?gygYU_egWN|f)N zQ#0mzC=wW%$<$ujO>E9Oxx08aRgjwc4lu4bxSX4FD^%Q;>wKF#!Zl-E6^oh=iqu+= ziDC|N-XS|Z+O71qn3FtwDWuf8^P0$OgVDYvNJEkpHqCN+)e)4JH|kVDUbqgY0PxYS9Lx;$B6XaeHFr)cv^68qwzy&G=fn7A9)v<`%Brd<{s-B z;Y(35)SV_WX!r#D^mzX8%^VDkj@r7)MySutnu0n5jQ4)ii=&~@h;&U~_I@mlC(IVC zH6NAC4u!N8S>jW6Pb>i=3H|Ado7GDatZAk#jL>k6N<5Unb6VOCrjsb1Y(>}U#NNB% zh2spqv%AkB!Px?`#w6}*Bpz1fWVpSR-I%pT4Nt)K&p*`M`A588{a%M*Q54nHwGS0? zDn+rKb&naQV#jgo?=)Njo4NWJng6&=dg5ecFRK&bTyjKALddyj?6^ma2sHU;O|Rgc z3y7NXOtQ8xC{NN3060#y%4#BB6nNibtNS8nV`Jua#c8pZ!o7n>NDqHZv(}~5GB^E= zoO))AS&h6S-9N$?d^hScYmV6HMlkpg<|BwsNfgc_c0DAe@|n3X*pm)B*pokXJh8D; zVzH|VJ!LHF#H5g2wa9~gTe<>Xv6b$etN{N~cXvA-%&`*~puAjohoo7maWmnWYp6>h z|C+f(K&&viynD&RVmc1-(Zi7;P$^&5de~RpT4}j`Q1x+OuU_cbK8hvsGqkEpgLosWtdn3xIUdC(uoChc16pSd-U!%B_#B^(-Cmh_uD>& z&Did@jFZ!0f3b;QXVjb)rqxfTJ6dzLGjpuo_ zx0H(~m=IC)-UN!KCbNqmU>k512%FxmT?&*>89EK}ZKaO?Y-x|keuy!nS@oS8-@{t% zybn`qhXqO9)LtgA*9$yfu-f2yhN#@ET4CksnJ3a8JMy8#@}(R5u$l!k%VZ&rilg+^`D@3I%7ktJ83E1Fue z=OVJ`7g=^2S90dtb4$EHr$@K{q$&c@YH6OJ8#rr4!M$Z0#K6KZYFXHXWo z%My3R){oVo%73lJPnwB5n>AMY#adRI+-v=3sRq~fPdd5`+1m7&=m~C4plSG-Kpg&Y zObKDWpGV97I2i`$Fx&4I(Ihi>cs1Ioa+P0bqK$>ygJkDLH1t*{> zu8*Kvnf`F7fWR2H)b*U1zGx;T%@qc$g+m$aOS7>1LKEsbp#B(O?Ox zz^#zL29H>kuoi{zO{L4${Dm=NM|g__`BbW;^P=Jv;z)^a!+~AF2!_Xd9Ytmh2!Yjm zKPxpgYbDKige8%Xfh;MK={0>Pi$=HPC5hx`%9$dlJc!3uy>mFOJLe~G8zF3P8Tw^g zXLYAs`IGOrJ&iJtdR{)no4&9n4AU0(TgiFnnxfbErFKlMp8XV><;`hqQueO3vR~S> z^kas9MW$@Hj;~oYRks!tGziVx+0Rvin(sfnS#_eElQ%SX6{64~SYCm$$q;Mc(aWS`B+&i-xrQx6 zrJ}m+!++wv;q|K6rdjX*qGlng$}cu|ND)UB29SW0p#8b0BuLpwarzC&DbXrECIN!- z`zC89?oYi6k+(KhWmcZKj)d*1B!9Opx%E~Vkcx|@qU1aN5eD$5gUR%Uk__~Pq=&@C zfSkmD{85~3;wGYcTLS@T!jKT%5F1ccE`r8(@_n(AMvtsb5;abtnP^*^XJ;>~PE+1@ zd(NvFt*B$KWQLx8`DSXH4V0DnURl0DA#1Q9m-YCDn3I*kV~j(uw}|I_KusXl!ben& ziu4p#^{%?|PVk4h6_`BsDfZ1x1f~-Gk*7}}Ca6CD|03-zpyG(SY+)ooa0m{Kh2X*6 zEkJ_1ySoPW;2wgzySuvuC%Dr%BuL{8H1totZ)V>7Z|1ExGjH`-yLRpBx>fhybE~Vn zZ=Exf54(Pzc(i-ksX8?dEk0rlDE|(7wfogrVBzZQ8Z~v71~s%dC`E#RAw!DJL!RI@ zZ?a3rF}{ADuk=0X^Y*E}YTbcK7WHUXLb~Ueg-H%=Ka9l5)@&B*_)y{t~8(>`$LNl)A;fM+9&c;r6yK?Sh zd-wpfcp&YozKRaSxnh(0P<-VGd#@rWe#!SB)Mu)7q%qM82S9A%uzv6e6v7Rst1*p< zA+6zq=bcQ0U1pVtA=m;l0|~n(P#t~Aohl)&eaH{$BdE(Fn7nVRuLcqWFx$d*(kM*B z{{(~ZhsYk7`Y59cXMa!_AMn5;Sbg~pJ}`s{JIIAi8JC7>oquHZ_Gb}>eRKhU=(_(9 zF15>Ft;?ZoT?zDY4wFSm;7T7D!Z{=>veA1kUk8F~aJ&Ar1{!<1plp4!bpOTSv(J-; zdsB?zq~w4!WKh(0d&MC~ObCW?irKXQ(xUr85fZ~Rp5KA!x~S0wdoexHrc+hPbn@*L zVM-20VSM&kU@?>dq4+KA%YEI|peCMljd3Z)CJ>%zFXSTdrxatI^E)Sir!BQEokQu7 z$K3159ysW12hY5zF@WDtoB<^CzV%dlK>@No>$st?GC>LJq+jTPSi^2t zZh^~zADhJ#9bq;;2H-o1lbNjLQD4CAUatek6k*7cF=5FP$t~B~7AXSkXaC^$aXC3+ z3Z8k1Ce4v~PSf{Qvo;8UIC(Mkp0PpUeU_L`{s1Q|&p$!55DX{upIb13J7^Rx!Z7ze zu)LJeNFtaTgEzSQsW8v8g|NWiuMdoLp@RGWHZdlMRrGG|dK7C%|0B@o#k9|O1g+)NXU@aU&B%H!MSKwCl~p!Xq1 zpgw00t1|GDTQAXvIuzZ4Ac!$*2`XvOQd*Y6G z5E3HpBN{uz4Rl|?$0={1U3=rEJ-`Fsyatgt_a*?*{oJD4aQi`oAiN_O^HvYDTL7M8 z17pSz$^MDiC>{cMZAoRI7ikhjBL?A!V>XT%~-u;=k2M7ziHOqzHp@ZwMBXtLBFp$3ET6DKg( zMF_~chdAV{jkI?K1EjH<;ZpO^hhOfRj!_O9%_E?N^$A>LJ4V>0i&-Ybh37!*2K$JL z`D4wp1i-U?yg)cjC5Ho~8p3RdI}0?~qj?A2>felSHuWIs2q1R%J+gi8W3#%Znj~y` zGlIG1i{+$LgP=FK0AG{Z3)6;txM{&Z!7YJ`?L&v5{3(ZLUU?mjNf3>$&u;B?`Gzp% z9{z4(8wrq_i?AV%t=mSV6Y;Obuhsosp`y6X%+D4vdM!g17U_Vvk1GbxDG}oK-Bh3o zTQ^^Q2Ig+|5leDmOgA5$1ujgi(lL}f3w8tJ+K;gdd*%WmyBBXO)H1H`;}(kPBUPU% zD^9Bl(K?EwS5kUlt1k(we7*Dw#^2`uK8bvM`zDXV5aT$t6+TSNg+_D`!qVseJqno} zj>7|v5X=C?k6ITipb3Pnx+w5CE4dZA5(@Om55<|~7IgjOPYj~-TXVfq4IItu#bI^F zWW(u0!{ntfMBt?pfLUhs@4LMs4b0rv4+%|yU^~_N5@Ts02r~3yf&oIVa{jS(td0Is zc1{Nuu=hX7Va}6hV94@s3vqK34G{&U{)i+6NZL6q)4zv-??u|cAPoCEK58MfqFp?4 z7wCiCB1nQXP*_m-mE#veH!Av2A46E&{am=m1M=5P(HBvzd)TJ~OW4*47TEKGfK94i zbkC4_7&7ywz)?af3gJfFl{Qi*r5*&Qv`g3;V+WXx42CgY6i^!V_kg%E_i~ch;*)xIRk-l>V?=gkmz$NJp(O^z`kG+Zehs1#GDpg)g_J(DllLQoTQx>nRfikO1a?Q zEvRXnKQ?E#aRR?VP(?)`Zag>l_I>_3+sse_AhQmVE&}K+sF!49;Z1~T$CF6p6EV0f z%Jm{$D6=saS@shec_=zXSbSLE+b&;3v?y500=h7p#(mwZdOPm#pM){kOhhYwr4lfy zM=z)}8x-G;H#0SpS?F!Vy}R0XiZLP(5-!jX9Gh9<*U`N;>0A5}uq;c~+8 zoyWzZrOkwNAZYnWYrlW(@`Xt7%6*$!E|iQ?jlQ)?*mVOq5NL!fm{4N==#y zU2DhVv;EmH5o*5q*lBg4S*Y%8Kw z8=0|afGSyFSmIkD!cAB!FzyZ(t2>OJ`};}Yk?q67AmB$cxlsy+Q!eJKflkSR!sMd4 zvRKTE^~|ohn0b;}bF;ew4GGifZ-oHl5ji{sk|>Er$gx(Jf&M@b}b zrm*QFZ2^TITwCJw;#&@Jizf&r|hpK zw2+C}#A3qRLX_+w1-kSN4VuXIypHp!cVWWuZ9SzaUcNk<6pUwyh_kW@zMqY zEQ@0n#;@E@Tm#_`UfKSi#@?*EzE;vQINI~ZjA+dpZ^swo;*eGPMof#^B-wnn7cO6# zMVwcOMUppU5RKIGtyg><)yL&+v9_qeW<3|2QS!qdy1WLZB7q>TxbU0#w}1HTL~B!i z#l_SqLqBPUkts;F;bzT7tyRrN$?RZZaNLM6HWjF7l?LP)T`UF^y|L01C)}-r<-p6k zmo_J@R`aBNt}#!`^MN}_9LyhZtZ>dMXpS5)EcQi zF8=zZyfDFZh;*RxlxI(2BJQ(SYMbiAN=)al)gLtuGFz`XVrCrLs09V@)WexKx_PBsWxK-%%zID zWMiDoGMro6)-Lmi;*(JUJM7LTKd#Zd-&bQKT2eWH?1s>DV%z!~v0u-R&69igwWQ$x zpU(3tBF;!{09PYO1bZpEOyH(3_OQK&t0Ads@CCRp8VpxJM+0XnD1y%3#q1-f2&?{G zLQK|b!P{ND=*y3WxD>T9s_o!u$rJUru1Z%@3yk9F2c8-c??Uyak#Hq6F;bbtD$r(R zcxTECBgi~q$;a`;C8$*@u~7?{SfHEh2N4AMRjE&Uacg`K54US=+46F(hyND$;MpL3}ay9 z<~3khiT)E+@t8|25sTP^UQ0FtT>{gOw0UK^#KA|0!;a!Ak++wofIW&z?H{Y99j&Q$ zHssQd-F86_8@3{xYPb#p0Ic9hIO-uup02N$06o$1FB29hmWxCA_b@a3v^2A#gCq~-mM zwIrosqp2DBYz$Ne(+E3F0x~fgl6@S%MUK~Bc5cEn)(57bhpm?z@wCM+D&~tHF1kD0pD)EC0bMaQa4S)as75G=?#90XD}zm z4VrqFWGJ;&CFe|M7i%sa2|9u+|$S$ma3-qx>+OJeXgrI|c{3kd@t2YaoHLDXy%l_V3`cXltxQ8j!EOavp zSIMzghx^`+7)dFJsNck(3(k8QwFcRGfSS~p-Mw$gFLRK<8AByLW`Q(Kop&EOqE!TE z!Vfi-+B;<@#J&`_c6}s>EtE()yER61fgcX-H*$#c@S^sxJ^z8wm_P!2b4Xjdkrug# z5W0$>>~^WI^+R7RC%D4sV`<%_VF+RbV?Z7jLW43x>xZ;c^j3YHZ;^5gfY*re1`5d? zYRMs}_iI$l3MCQN^r(m^jp#m+O$rw8mbhXCzNaH_|k`dxSbf-R3R9W^J?nXlbTm@uHBcG3{r%ducxgga_W z_#L&=6}~2NW=*s(?;eRGi8u|c!5&Y4@AXM#Q~TyS^N-gxO}=&?lQmIZm$|}fTRJ|) z2SQ{Fy{jaU2zP4vDZ$gK5aYHxDozF50PPjD9I z!Qho^yQKS1{^<9uy1V~aMqbM04W}AQ+IMt+n0hr^v@?=uKhh>?OpJ~bq_8BrrbLf>4Hq}j zBd4v~c3v08JUW7|-+;X^AP_i67py;V{|plF2u$GSGwdK$82|CU8AMPcGQbpu+Wf*+8<4+!7~Qt$)S z-y)c2FRTkhy^rr{L9Xy%Z5V&{ennU?^0!>1zL`Sc5z#*misyp)E%&~E#v0@*mNKZI zq5U|~oMP;fNUbewmk#TXADCMVq(y?f>6_sPH4;Gt(ftizL~4U`pMgiDAXhkuFN*(k za4tsi=L8wicA0V&M7lpo`QzT^T@CW>%3k8yc})zjZN&}NM)qF{&Lt1bC3ia-z06gH z+`x)R^v!tm&wK@OkVDMA<%$zEUTZ69Qz+UJOz#9>H;1Lzbl?-w`t{hM0rA3$27 zlydg@9~k~ALAkF5J^$@bFMLQBn!i81{}!Ui6!1tDblvPLUqAkRPIHM-!YtUOTQIL^ zT#8!ai{^O{S5jc^A`t0M{1q#B6~#XXQKYkfgbdV300AJ1kO$|o^kG6KDj1Hco|CVa z5@a&n-lgnic3k6Z(?;d?0BO@-lHY)MV;&-;5`S z0|{alOpXo_MD%z6mb)F4ivv7zEEwNS!k=(!h(AC)soy~JPYKNR1*u~A*S%=vyb)pf zmfH3r z`mn$c9B0>egx0Oi3yaN*OG_=v;yw* zsm)x86C56Yd5XSFr#gp7RY!}1w3W2JJ`;Te8^_wIyS2yp`n{^JKUhMeE&%E}W53y9 zj!Mg516J)vX-h5Juai6|6GWV@s5IZS(a28ueY;@3Y8s+{1|rUNIzn^fHf~kdEG?#{ z_7ZeYt?RVu;@Y}dxLH`IFqn!C%6FLR@}j4|K3uFTSX+xhQz;txytrghTULEwu*w>t zW24_J!!@E9e0A+AfG0-Dd{KKg+l11ozEVwJZeM;QMyXz1Ryi>TLA;-BdZJKgE5o62 z<9shqb?(04My1{?yV!n&nF-qAjv2Rb1uOBWW&YyJfm^h=`RSmESFWRr#&q2Bds&=5 z2R~DNrAq2TMGHOIzd+a`w1dy!I2x>}=>30roEH6kHAD@MmhvwlI%hN1)kyPCRU zMqITnjKQ-)rksH|yM!|`{u`RLrV1B>Q7K#v;Z8*Tx)2#l`8;R&+sbCi3UN(=Y&zTG z@S8942OlJl;nA%W#li~uCf!e0`V&V(SgAjoof$u$)$`e<-J>G>kb^dPlwx=~?3@OR$Z0w^3sLoYfis4|#Q&`q}9LQrdfOuNmkFp@Y<<_4@{y@<=4L z3Bi2dO}AMshay6-sSfRox=Td71zQNM3yI1CSNYUWnj}vCJpC$su6+$OUAX+nH(}F^ z*h*n5J6j?{a+aT+(K2FNY3)rLpq3X^O$V9PVRlBMlKN+g@X{AnVCP&Ttl zNv*1VCT@CrLRzl^i-b9oVnMX*jfsdnr78x!ip8}l@?x$MgweC;mgxGZuOps?fVl}p zIuqaT<_OvQi5ZIw**2uYB|+&9WAyV(-J}*|t*L9t>~h!^HnN{(GI(lR<{doNist*J zWSLh^nyC0(TYe?1a?qcgR#}Lw1nOl#r|U%AuVSP(RQCq-?th_^Om?U#9<2$T2B|NG zw6+n;ti4aqR!IFi64oHDt>xz~c<6^FT(>IQ(zMm$=#K(IA4dB z>&EB9#3LJ_6av#`FE7s(9|`#|Az{X6KVTgXuBK(DF*SDL4{0QrX-54Wpcl*2#pmu- zi{lk`-|*D%81dvS$5K}lwAk_LUxv}{MwuslS(ay;!TK6I?=j=r>d?LZ{H$%_T3od4 zs60CvtRXzvwPwv;p)O{$nR^NEN|Vy)M>SuEHW73d4ddPIGCG-RuEgpGY{#DM7U;*T z7BP;;j`=+(r;=yJ*(sq&yVp}SR%cwWe$tB>w!W9rTb(@6=q}GrFhkJd)Z7n=;OVrR zGbiTgY@CR@!OHzrthS9MBOt&{jG^CMA6y*-Si3o{`C4j>iE-kBj;F0t0i(OCED@hl zjEI4MKbJSAd&3?d{BGkj< z7WTNT`)+ZsaT|uzi}q1%aGxA59^F2F{k{VAZY6j(-3;Wor5W$Gu6Xz@7X8M>G(^Bc zW|<-3cLBl4Pj=<*lJKkFHm1*Upd*dq%;f}7RY&nxX~hl;k1swOwc_Yo8FV|TiFM-+ zjtn(500UND(sO~Zen+~)sQh$kd7YwqDbq0xRaJqQAUWe|DR@Fo1L@Q5p1KeMj6L<} z6qG7J&G9bCdHOVP&r7u#qqV7x>gcD#YkozYV|4i&EuoE_#lflKUAqDMMy-KA;qAUd zA*u1gQD5h;5^T5w(^7MtKX&%(bDD3(Xh{$+SJ)k|d;P6q;%~uNSYcuFlTZ^)?!B_xPb_J0Ovv;rTPkh7^22RSZMn zOJ{=UWru(g0dp6IE!d)1hbiQ9o&`GApIqrO$pCPh1>(^J6gLf4kW|OsAtQzk? zvEO1O+#!_be_?B7C%EK(s%0uMC~PxHrVcC+Q0Ne13f4tzl@}4b)B06k5R6Jpa_`7j zXP)bmn@M7e+#HG#9w$ajiT<5O;z|6LvQ@UjG(0N#m@r#*;0K-#5gY=d@gyD(?op4g zwR}?qu0@k7XN2EJ^l!UT6$YkpB}bv+OnAY2YR&Zn_5=>$IkUGX{j$rWrBm-52wpfc zsEBG~ml2VF@J4jTf4#5P{Ilps(%5R|IA%L(oAuRhckToanI4%QG3e>)s)Y7~+|0y! z>&)50CPwbzd=0?|35xRwknUs#qPqU_tdo^`mHr5SIV$b+Y2i#d&WMiz**&8p{}Cft zZsG_6vA+2cYRt{q_bx>-UfsNkUx<;hl4=6dMjs$FS!XP7MQT&^XLYE@uO6Ss7Cp2s zDqN(Vo9Iv8XZWhTGc8loU~QV;drq>_xj0O@MVw!8{7<6GxD8;hd2@I+Ns~PeLyT=P zEY0W$@yQ$Fn?o}5Jo=-aIfKuc@V-{5bV_lDx@DdPB6&j#p~ZX(&&G z5}hQJD$Eo26ZIJ}TNWwFUMKaTMVj&JWe>Quc`$&cE_)$rx$o zJRLe*G&E2|_R}8nA!$D+hm5YyVsDIbIIS@`F5DH$dGWdZvdOEgVGfRw!j^7Dvuk#( z2Z`Nlcvox!X4zEsBQt?I9VIBq0plZt*(Rmt-i6Ixkv z_7DQZmmgB~)Q3!@xm8q*AiFmH4ubVYz30JUkEjPJF)>~yL%Wi#-jd^_(MLYc6s+U3 zj=#yA(MxfgW_b!oE#0y(5!2{T$95Uml+ecSQXht00X;u=95C*k+ENF3H1`o@hQu&1 zomYl-oH2BH1qY28pA#`J@j_J&oG8M_0Mk1l1&j+u1LZF9nms3~@OY=T*g;F)jp3b% z1j7-iGF>feQ}7oAK$#ICK8C>yRH)I2%mjMk$j|ty8S^KUwV6gmXCOxN$owI#Fg>awYmy)78iFm`tUoL-GAK%pPy8= zcqkhB)cf$4OTQckZO-G==V%qo6BJyjQ#$5s33VHB^kmnad`J+3Y5?3S#MGmxC8}Bl zExim+m2xz4@a32CZnZBRCIxJ&)v{Uz{H`>o!$EM)vuDmT%^SxChyEifM431~xd*NF ze@t7o?nbqDPg4q=w}<>pA4ES_XSXSDM{mwo0>S|C&%83z87^%E?N~e?-+%dD{+;uu z-$%u}q?JKufxVZ_#;GJy<*WC|*~~uJmfJBAcITa3@6W<+yy4y1%}jdFl&`WVv*slp zpBuLOBLE#82rgkoz0Ew4is$6pA}1MB$_>c}Qw9ehuI(`De8Yjhh@$i#Ta{*Y8`l0F z1XF0`dhoKUpJLX?X`0Xpg(xihIN)<=Ps;uJCb}c@{rdjEE2O*R%a$d>ZoB9b?+BoV zDaQW%wi8YD!*tva%O31^bEF|%WRU4=zXp23qA`3r{29F5J?cV9kF!h8^^VW7r#vZoI=kCm6Ap)3N(Yf+!`JC7&TDGbyUF8EkHzWsSvHyG z>E`JVb5-@_@kQs^*@7PQ`-7RN77Ikhmzx$z9p*I2o#tYXbvH>j=_fNY-xNy5Ca})KQxd$hUrn+v%o-st}=KG6`}*nL=pk5c!(x+;&={IaBnbiM56G z7EpZK%7g|x%19roiPDK^*%dbNLj-$PqFp-in@RYhEAg9IUOX?`sfj$eKk9ocLWF`Z zh|(RWW+p{ap!VQSqmTQk)Hy$lUr+*?MfODw9B*4|n`*M^*zL`?WT4{}$<2(d)xOpT zImxfnT+zYs@klwCzUnmNyAy}WOf2iVcLq)-PF|q$D}f2yiEX;xIvIT~_eJ?i106RD zx3%AnjEI^WY6*2d(Po6))`SafU z7ut(}%NLyc*4i)ns?8P`I&SvA*ZS5rZAq5gYe?E^j5cfBs{fSM)M`N+Qk>J9Z4_s2 z%bsistAD@Kkp@E}(@d%;QZKu2a>$l9713mSPdA^0mQv1Nlb_F0H}PA^>zh=eHidZ` z$XT^nFfQ%vaje(bToF%hYdJny82S0JJCs`Lp6>k2h-~m%4?j}cToH0sbg#}vl-0_f z_k8A(L62T1vWU-_)0s4nR~1g>Aqv?NswX$4-i{<5)m}HgaUki5Z~S_OVd-;O0ZBrX1E>S18btV(3$(PElv=~Go8 zr!8N?BAZ~L*513hW>vL9+qiI+B?ar!yjU51QG<~{)jCm5dnmuVS9hMQ)^uvlUDHKrcb)g!_q+bfMV4|l)uwbXq*?~yMU zE`y(RJKZS;8LS=m<}?_BIvnrfO99^E#m8O{;L4z}tUMv12%&(H;9_apWs@y=?ADiZ zmM+_jCyRw?B209l`?2ax_tC+_=@pg@pZx&aCWW(^nYIpUO7!QG5#f3%fN4pAAopbb zPUKLDG5w%xp9lXG4O_zZUycGZ_t%^}$_7GieG`PXp5gZFO*YlY8A~>An?<(=3FfPm zChIsKmvn07$=Lb>>jz`g`Z`sTW-%;J9lAtbctYshFT(%(nErgy^LTCLRrH#vvSC6Wpkei|!=T&_~f{5+3Me>vJ$nS!=?Xwo3g ze07gp=aY~p=Pu;9*tA;FY;*uzkD3KH`7*Lif!=w3kpjf#KqId z;a!?&QZG*XEMhMn-$ei&HK8@1I>w?dYFvIzseWBfYCwF}s)Qmv3aCGP4iJCPDxxbL zesh4sCiNgEQjj&g&TK6*c`u`VvPIi*8+q=vtDD2{i9CT>uuqLmMh^aXsZ@^wGp{rE z_^{N)2(ON~4Ca`Ot^?t>|7%2Dd@Urwz(=mW;65oJWgh;@8#_cY#1@#|cdkRVK^Q|U za2uXBCX^L-YA2x&R0>jrX$4e~ zH=o1gAjCx}FL?yg0QG@FKtCWM2-XQ;g{S}%fL~}L_?VD}|7A{}2D;!o@ zCj>s3Br&0CVN|_=6Q$0BC4q4=tAr4&HB#874bp~{}Ss+xGoU7*UIuj&k6OP66& zQ?gZs-s5-tY`5B1M!Zc4$yOzL$K%eVcq7Zw(1NTWbbp$Z`fR_+dzIT*&*5$py`&ef z*)f;QS0CI>Vo47vv2BCnPSqi?2`?)?OeQj`b_^YvJaa%(OmGU@ ztT@k%-{)3AF`UgzuAmE#f`pf#3nQ7pxNWh~i#)0?{)SMlo0#C73yGOe$L*xv7GvVi zinCk_!sWdRtu((jKhL&CIY<|DCLAk#=)nHMS8OPHv85s$+Uif!Q<=pj)WXsf7q%pB zm5o;In(y|8lSXV^;OpL7!3&KTmq@2{#>oI<>ipz`@Lkw$^#vGAIFg|7Kpi8TI-)$? zhZY#e6VhG#JZvzP(_1i(6Cp1g0AUL@BhVwrv@h39-}fy9!3tIZt~4$UBZzMn#TPaUej47sFZDGnvSAP^ z%%e&7+vCS|w#&!$7Pam{Zi3H9hw!Mkigq4AALQ?m5cAgn==Zl8y7+Yft)Q-CFb0g+ zkS08yDD|8zsCvf-z7G2`9A+~3OxbsN=ZOs%K-Gf>7I}??j(iMd%enXj;TsBw12aZI z5&HnEtkT?*3Fxk7wo7j7$S|&EgMXzK`~^PbEVx%Pb7Qft4Rnnu#siCs*a;wINgI%S z4M6rq&=VzgwX_|*=lN_Jcly^6qaPX~q(6ylwc}pCwevu>OLMO!EP6pN|61e_lzgH2 z@?qp{Wa-&^^psV!3A-?J?m_lUzXjMbdWw)!>264 z%Kiz&YaTFJGiE!hOLNzf6Id%;kIqQ;`4qDYpECHZ;WplgYpO28LQ9^bs)R^m9<9{)&Cd2sO$sDV3>2{-XEvERHY|&F`?e3F092V6?jf-*VHluP}rWzS+BvVG+@Kqjx zw-|L>uuB4cHjG;K2!&@xO{6g`!NV4HD;W5h{U#h*b{6qM%yvK*Zo$>K?)%miA463P z(^{c#`foeYuYK^T1ixYDnE5YLNVa~%Ko#ZPIv4W?g&eUomi(C*Jr>7C%pb9*Z$iKcfY0LfMsvkj6ZtrGqLa!m+zhJY3U_s zb^d>u_GD{Xyr1iP$jt}H4GU;K5j5XRH!=K~I`jMvmup2j+=QGo%I_=I-Snr^?8p@X zoO%x$lMA__t@Ma)4s0LG_y2yw0DC|fXfx=t}(RK_*%a1 zq1O1iv>u7Z1o~P^YQ!^3!l^zKMK2)qdX?%iI4#IaYevyTh-Fl6a!?L}+pcSL=9*l{ z`-SU-AlYNsC8ygWNjOerw9ZtxpjN_$?>Cv`rU!@<&y8Gc6TU1nu0y`eqg6>>qyv?D zTXKvhN$%(xZ*_7;OO^S`k`jt_wJq_&X|)!zu{q0$l(F@#1eX~Kn~Ni|U#HJ&PR^!g z0VgTSri20xN*0BA3zu0xe_y$^qQ-*x z)@KnzlX#I!8lOR>>?*kYwXlSQYqRV`N}k82LwP=3kNgZJuX`2MEv%Bl=>EY1oRAgi3yjbtN&Pfel2l|wt_305GKYfPT z4}Y0BI4OA3!1_LqATuMtceofN8kl8xoY&yzU;509P(Zzb<$at+{H*Y4$dhm?L92ZL zpcDmq8tTTI4YWyk2iUowhdwxE7-PYz#ZXd^H zbelgKmmSJhRZA7aol3=PGF&TgO!PXGx)9V8|hs-IW&Rj_z^Z<{LvloteP*J0-F6Wtr#=zM5sv*L9PQ7 z?IN3?g&<(d9ikxu{|Q&WQX+M zpTBcX1w;)x@y7HHfo1;zG`m)SU{hy698byo;N1@nQ2DHy3-h$=>2+EN%UeG5IpOocr{B0rrGfki3-oykux=>61^?ue#}|y}@$gO*BRdo^qi+B)65pW+BajOg zvdBVKZ0S8hK=huIpu$fmOBDwh7vc7h$ZoDvq_bgE zz=$~*|El-allFYz>ttWNQfTL;=|-^6CC+|8I6IUv33CryFlrRUo70#06MD6)>Pg(& z$Ki?JJ5&n-9PTcAl3Db9`$sRL`$s=$!F0EX)-r*G@beJ^enJr~UU=v(X|@K~Kh8k6 zs5DIQe%BEPY)djDLo=YUlMqLd!+`2J!MfV>T9wHd!a-w>cGR4Ku0DabKEYXtWy<@RkCLyFyYX8hvte#P3*H5ecl7cIL_}BTu;BQa~P#Cad*CWEXTg1t}m7c*qJ~q-=b%9&!5XI!D__TfYOEY(JgS?s40cGp&t9iEl&deMoENcrxs=PH~;~{a8VI5AI}$`G2h|~eNFiZ zXvOI<@!1q+9FzhoP*b>FxWBCH_bY7$VaITnAhfkgLH2sv-m8}9(eo6C5>Ei<2zGWexN5==YD$w0cni{k`E##i~wB{(*m-an8|+>dl8z zuyv*E{>Nmzhqxt4KcaT$z1+z1CAuDO$&{Z5Yd@C;Ykx(Pf-_^5drE*xG^vPWd ztMlFRPETDD;)5Zt1CCGgt8Tz_XH(CD_oVV~FgK?=_-$_83CRLDY8>Ru#8p!~(!9`? zLcFZ9r(>fh8*6L*RTznZPs!RY8&JmCV@$;PAvi3iar3iIY!R3Lm|@s%>N9mB)Xi}^ z%f_AlXu8}d_cC>?hH{n5>}$2uvdzE2c)HBAnoG$Kj^wQJeK~4N20qoX|A~a4Lq97M zq=C|;l9voujcZjb%4o?@$fA<}4F#`DOEMJ2zbZ-}iCBEp)5}dfs3I`SuFN{BGIUt zvUB}!z))b)&iY|DB!V3Oa_YUXXoyD?DCHQ7n5l4veT{Rzgb(^O%E{Z;86Opp4o;2y z2lQ$~rgk0i0~*1Z!`pU%sgYm*8&qj9459`sUxXDTniBkRPR&=z%`6zz54PP|liIix ztIaI2+`!XF-NaTgheler;dmJHTL7iY1~$QL=RsRqB|Ir7vF6^U>HmR7n?IVQ_h^-{ zq@4U4J?FqLrklUM$`<0{zl$MOthg*9R-9vkX8Ct{ELUt6t;zo@)LX^~nVu4v&Jg;H ztZx<+H~v)0cy-W{cs zC#fXl6sX8Z`iyT~1inn>-}Bz&(Aj>{rWz+!UW#atO5!T0!Zwfne~=0qKdB67CUwdtw^XK58gighL&Y29z9PUi+(jEI3D5!X+o?KS(Nu9ca zL0LVrLPkyf|3Ok2O^sc;q?Np!-h$3p|4)fm*0bQ~>|11;J7m9Vl&NrDI7-u(4t`sav4GIs0E z`7CZHEkoqypLxuX^A((j?HCLnlg7au_CM>d)<6Zq2K@8hMCM2@wDMBO_wOB%trJtt zASOscFCN;5-iFO%%AbU9+{Ug9H<1qf3#YW9uy|N`&Abo=Er$jXl%IJo}Ygz=u4d2Z+Xe*OLnw}3V#0r zYdG-1mxut!*ro!|+_CY++?J*;0TSy){{g{6u$K2koZuaXQ%%4g~6T2%wE8?i`co{dA@r4Z_CQ=dg<=qO~0v3u6__jPyqJ*+=lGvxyPxP!VKCq-^x_K1BSb6U1o4M0Pvkwwryp4*qyng zJ?+pWBij0(s%iHpGnrt#qCLlDjBl> zM$YtXj#LCv*V-4Ri`|)A?E>I;!cJ-GH#E~GZjkPZn7Q>A1dw>IR-Z_jL zQkj70ChTtvB_7$$k8X_%Q!4*Wk`4PCP02ElAAW%-ZyLr8v5W)DPtDR(@zriir;dv2 zpCm5>>7=ADZgJAgdvfi!geNP`od7}cz|VltNM2%1{v!sx*o&Q~x^G3dtkvPxLUMnM zbuj0>)0PIC$V&b*$?3*V$78-@Jz`!eO9O#k{kzIvAYO#l;)&iv>94DSrVozXFZZik zQ}GV|U#|-@$u}X#htfPE9S^_$Ym$6FC&E0goGRIM*sy{c| zD_bL#H_cgHA(5I_ta=ik-{|?b`fL(Bn!EQly4o~up9=1)mMZbe?&M=uXFQsF^q!ul zZaz138oJ*@1AcQqH`E&5-A?rQuP(DZJ(?T#p8kObbTEvIRPWO@?*<>G z6v$fXO0V<3++NkDwmi^gax28-I}-SHNqWtTNn)57<-_CI!{3Nnck($VUi7@*lKCl#G=eX^XX>cs+(XZ@ zjWTb_DDGyL>Lx`q8FPk#?);j#siAaPb#MTjPWjMp$Y@A>MgTpctG{BJ!!B#xVM z+eGkGMd-p?8ci9yIndh4VYJr_kFDp*`MTVxn`qC`QCMG3mYh*PGNprzZu$XjsBjjW zMG6_?@+QFMI3^e0eOPgnh?mi9? zI7_pU3~6jQnBwX*7T!?h(VL#3#5>C!>*X{OciO}D7jX#lsSJcH8cZbhmeAEia5F8P~1uHCZ$!aCiGY`+1@-M=V>Ml1+E z^ef`s2ET7rSR}g94!r48^0mTDh-A#^lJnJAiV^9#K9`HhpsUz?R|!rcE?S^?l@=Q` z%eiH4RTw17(TdrVh-2d7x(UxCm@s+^)v5s-68T5v4OA_BzKS{Wv9}?XX7|PQl#FMa zJB?STGnbxP_$(+Q(X<1YW>d36dTn10$w@`1eS>Uf#$LX-oR@+2omTr%h?_6K1s;lxd z;oBdIfMXopjat7ZeSl@dt}8SGEn{)^?53HMEAKg4env4hn50&%P&2xZMP$YN{0l4Zaa`CbX>nSd9Y~Jc zotd^DIt%?`N`L-5>e!Axf0C~6`Ic-PQj>X{F1JD4P$P2u7+fQgmSztnp!~xhtemfi zPV|5-T+fwzuQ9;#n>u>aR*b)`aAu@8jfrseR;PyiwW{U zPLJHfMEE4a{GkZOuPX1AOspLB(Unc;mWc7&Ok(A1B8trw=|@5~6^fSP-a>JAhvF^nPH+tlArPz-_fnu}&=x3e!2<<~OG?#E=?ywj#vu0OZs^Y@$V2Zv#^9+LVIKblYjE zM-p074QDUL+7^qVPm3Q(IKE4uczOMKI^vh)+xvK72n(;vtErm-I?FPIn@m_y|X_h9= z>a^9$-Q+U$^5|UsXVkfRry~4LSPjo?oc>OHmo&b<^Q}bS3l+yIU)*)?`V)I7-yCl(T@n}L9Bfs#tLlV@ z{~|J>Jum(u!Ma93T%-7P=raSKb${$HoP&Ezsg8h47MjQ&CYoOe?y;)`vGb?dbyC>1 zrkgC+?NtGcCaISU*MK*rB(*c9QKWnK&)d6ixIgHs@^&pSJhAKhNj`~jk+#0C zbo1thxtfei1$;8dMk-HQkwF3Y5jTO42ZNhdhYKzAMq_GoW;&%XjZ#yZ6nzW~|pI z_uo5bc<-QFi>IZ&3dhELle5z@wGWvMmJ{OPpM-`zU42~*?I$HNhfS2v$^d**mY(L7 zqvvUGl1w-W%FHv)ze#e!Y7KarZ=G;7NUA6Zz8>e#zgnk^WmiQ;JF0Q3F&g}@dS4i@;l0v@^93u>;ii-_d9lu6Hk`QCM z!!B)-h$)J;$>Og>W@1;(AB(Vkn%~K<=}5Gm?r zPFffFr}AaEWgGTU4cq#}#fT$Um#JLT=F9~G8dzI6{qgX~3~<~UW61;$ZY=PZRj3`bhr|~4+V8~C-LuaTQg5q~gJ+l2 zK7f^)wS{m`5XHFrf@?0g`;$v9LihfM$M(G(9+SV3 zcE#h!`|$1YOPkT{f&q|^T@qMS;o=zK?WX{us=d$-Isa3!xQl+G*Hu1Q=YW+ES)2Td zpvNGIB#(@6k2XOhZ&5%nL3C_uH_kTkhAbj~)zqp9eD}UxdI~Z@K6j7yml9o+Lo4$r zX;1)&C%W^mz@m76-1(@5#(3`i;pu@PJ%=Sc>_Xw|Jyls>gRbWT$nfrepIpdo(w34W zG(cBx?5GB%JV_&)xH8QBpY-sXtBA!q^deo|yeR?_-1qn^pgq-N!rl~JY8Nza5BYy+ z+!m?#Te5r9i5 zvW@qiR3d0kk`Az4QQ3q7?xSb#Yfje0hUGTbTZWG6ui|-nn}Qa3dg4d&Tgskz`_*%< zpct0X@SugGc(EYhDVKt}(Ejj(6i8#^QJ9>mIVqk++nz$s78=tAAJwm^+Miv<+L zD_eGME9yVSoK3n66J^PEh-8%&txyqB^Uq3B|bAk_majkQ8Mz4?s$< z4n!5%Qc+DN_tKkbTNJ(FB9=j>^O;R1QnM0x1!#p5SE^e@JKql#c3i&g|I6s6jDi%00&5h*Z8}k!L+rwq z-|NJpjpNFygv=}1GVCi6d@3X8Z-@s}M4Sq#1hw%FZsWOahX1%y=kTq5AM#@1Tc}ER znTAN%)hinoY?iU1%lbWS8!T$)s%D(0o5k!FpnSEsnKR+#V(1|!7GQ!T-*8pB?es1$ zRh&TTf#8>-;e~*W-J52YmX>q(LlHblp;_IYjJ=4JRj)5evPMrOMwEIH(dQEu;wN%N zP3l0MEzvm>rh6!mlQuY#uwe1^x8qH1%Pfc}+Zq)jhz*64Ge<#f%|(0rc`HIril5?Y zeG*GQv=Coj^6hcnXfdS|Wi<(9^^1JMna_RUa)LzE>n^~p%sf}@0AtA;>wTmH_`@H; zRlE=2_koA}ZT6>>?Qfm=>YVeOH(axS8}By62Vx7Ozp2fUfYtxhuXm}VG=uy2MyroJ zDtp50%D$riMeH_%6(q`toUM@NVT5-B5biZ=VKd$vd?9>DiFecEx%McV{v?Px-R$ht z;OvxaN?A`x;y>Y&(BqTnIr);JlAx=S!vnXLAGP`y0;7b)l*0!LzNumx^X{oFd)^Hb z`}LxtJuSvtlQyxGvF;&!wSMhgceHp=8yj$Tt7HzIrz|P1qP_5Ou=2lNE%$(WMr=+} zyGAj$dN&hrFm!DBrre@yu~9hNky;0pYlQJ#lzGBpe$THxX(#tRhP-I;sB|2jqnAcO z2nF@{R<0ZdgJ|(@=`cK2FO58UQJt)V=p$2}Hntw9r3qIL$kK$V2c%bWRc6eT4bn?t zDIG{QK*DNOB_V09~u#z^UK6*dht{FlA*i0PrYy$6iHc=gNvW?OGfqsRTx@kgXU7>YnX$xcP8soiiNWZQdg7Y=A3`G^L z*v@}4cK0j(Iy_O+WF)9RxUtij6D|;TvHD0nGRK0ErnAfEX~GJRcs$c#EJ7m2EZng| zN}`aVjJ)>6K|VEgylcar%utXU1vC_9gtfK(fC z>1}o=b(O3H)xe*oifzs{(y_C*_1rylf*8B8J$zQM1SoE>q#zzEPE+XS*HXuh39=EJ z^3K}>=F0L=M{jGWV8H6%mvd+VW5#FcVD(Dn<*dkHesA>d=hagUFgCVY6js4)0T1)Q z{T%OA5aVO3#QU>--nYk6JW&B|F8q?B`1;{uYnRj>H+UkFy7B6XtJ-UqL?V*%@#;}7 zo?&xcpyL}+-$1B%yIQsxsjmFB0(iBz5#wUz-+S~cZk){6 z>%45}Qk`@r?P&-4X&1++`D0P0X$RXcb|N1BdTi3IY?Yy)6A(ob~S- zg70D)`5q5S;*(l$J&~lbr`>$7;roz8~kY<=1?~5S{O2NY4Yk>@biptY432`;zyz6=HZeT<(5Mek)vxHzMLnmV-rOqdb*o8 z_ZO;`LX{YDy1=SpOWfc*H!hrzW$wocoy>g^qukFow%UHh{LQ4OX1@{si|M~8EePLQ z@O?AKb_#pE6j(ERVz_tpD)J=RC@%Vc2%xvgkLC!5+31Hk{(d?# z8L;=Ywf>V?B$cI-*|lZ-^;Y7qg#X~puY?DX4+sMLX&#k5OkNM~$R@udJ*Cu^`S39XktqjD{}!<&9lCgMGkw422= zBf?ed3DCok*SXSAxh=@DyR8m6*8NeuW{tvC1N8+{Xb?I|I~P9z1viNfO;}Xmd4edU zt?VDG=8=09RnoXIt(^q&$Bt6wha;D~$3y1lUYlLG_x^R=W3$+}OPLz5TH|VR{xA=K z%Eu_~7mWZgmP#1YGE3U?F^lKoxO^5Q;!hBrPD^)nxP$3tPh`C3kIV?X(m;aYw4 zqg+My(EN1{j=iO}3hJF+C6NkNPb7b z@LA!-H_gWm{|6cMMdDv{o6eHLbA{${19G`eL;P~3a6SfezrUc%KWF-{WNZ+qoDN1Wh}DXvEXP6T%5hw& zes|X2E_pS@bdO#$%eg@%1qJ*!ryT0hzp$hQ)W1BJrNDbfK=qV1dif<)I6Xu(F+lRa zq8T9kU&)Y+Dpb$kPO?Y8{r@k&xrg-e%y!W(DKx&Y-FceMEX}C&IqH>l{{OoSPBn;4 zHHiQ3Jb3;CCx1?pRcr%XV5l<5NuMQ+;SirO#(f-XW&8Ts1q5fNjC!WbG;LUPo30k) zl&&R!tu#FVM3BD6%WLe)J7;5EkMuc;^7wpLYf>ong-!13&F9^Q=Thw?IcQ5j?fSKT8kvGZzisb*JLSvJ?ZoKcPBmrRN+IB z<{yV-FN*(3))xX7GajjTsiZwa{H*1s+}IN5wWCSr!(W7v{X-i2&KG&pnqp-VP=7wB z;W$G~v$baGe>z9gB}K;+?a*5)w9xGWz5uVngpt$#<}~j0O4NP)-Hl4^=LhBx4|Da; z=@ChPvET1Y zzn?;ycBn|==tQ^0ho1@oWE)+UJ@W6K>QjL^3p39bLZP+-O*`6tOlFJO7c% zvg-dqrm!QSqVr0z1m^RumkZbeqYuzNK%5wnqniKr6?0UmgxHN-A(bCND|sNRc04?K zitEf$N1=1WaK$gl`$wO&`&$jF7etDWyAyw6bM^c~FE*EA@Y}<#!K1F2iOR4TCO|CL z;n6e6wx7MEmzST)i<7S|AJdvG73e+B)q7q%()@k_&-B#oCb$yqHk7S(yF{~v|76Sa zwVSC=M7a+J?ZMJ2wLejOOsD(NOG%ne{RGV*|H~hrBujd`)h{n!&`K?@GWqNLcGLMB zgH;k%d8jGVr76RS?CdqZ^ueZeU0&tzZw*V3q4@akPP?ntX2G0;Hm*)K|`u{x9W@Qf~9B;)yjrf0bUfdU7wjMCI?O1+l8{eXvrC9hC*F$ZYcBJT@GHPn#c>1y-t(}y5 z7_eeHBW=bawzJsx9nxl!H#Y!9^VM0@zwPXYLu%N^bNX)c<5gB0@U~u!zEkNdBf>rv zJ<^BABe^Os`KM#HZmA$r5y(nz$o4A_6pcd1@bZA@)?};)c>zx1;2G}~O<5mNKmMul zTBGVQJzS|`oRIAHje;cS#a2KpGGmm9x7qr1CbmsW*aMc$)NZXN?AxRUPDP!)O3$58 zfQOYCd{i^dm9llA)jrYl*mQJMFFJqU#F>Fr{aj>T{DO*qACPJK-}%*eJ0Z;F#q zhZ&TonbzBwaJ$Bb+cd;lzVIt?wvLC*^;%#BtLoLGfZvVs29T)8kGNP=k)N=64qxLL zYJA`#Ov!^G=>l=_cjQ;z_>j>AS99ahg!P(>i{lYCMkt>eRqIp=sKC2Fn@c}+(pY-; z@IaTQVwEK>#+rCdSt5%!{xL%Xdq?((J!V`k4}WmsZ=4KS>_%x)vb|+|H~RUfSKJgm zKLgyP#2*H(${uoyKen=C?YlnvqzTVI4 z!$i&9Y-M9HWoMs1;#Ls|O1~16#j5|Q$NW2n&IS_25qt(zJmqa+t(?exQ5ULr zhz;*+f17L207=KgR~^V;hGecVn<}cbmf`umcJ~|b zW!5T}xjA9>*-tX|S}Se3h#%-5_&lsh{dE?}sKpDgVb#;pZ+)uQQn%U~dQ=795h!KS@M z{pZs(%%qQ3&D!Ry;xE)Y_|x$CmK@Sv)Gm?xkk~$%+LFXTbYXLoZfwg}13|3b)OEr2 zzws&}D03xZ#}9fGq$Oj+dH#-%@qdOKz7)qv_-R0fkFh8A7JHABJBkV&XyMxhLNWO>yG8Mk=MUEKweoUtelC1zxIv;-1BbUjj!Fc(M!pEC@11ra~zHLTfj4; zmF6*tZ>VG?TzR~It6{9y8Fj`Gzl;*S6%YMw7BoAbn>d%rPRbM7;Kr3GG*vQZ+3G7J2RQ&X%{ zI-XR)<-0@YM&QSh8;#0`If6`pm^fj67GyXP1l<3+Sb6A3xpHFc5Z$$#E2ExA zTTMR4CO2SCq!?*Clrr#Mo(klboQTyJ4L=UZwmx)bq}^%IY`|zd@0d^eK7^8RbcdPv zndk_#5vj()R{Zx>NcX#3*PX|A-ir2fF53-(z66{`bQHbn&w~_YF>-zx>+X(SJ^7ZI zXH8<18i`#t`LK^3lV%Rd8TqD6_J;ZB=R~~cs}c0wY;99(gfr=r4chILmEc3sG~)B` z$XEqV8QL7oDTKoEZzU|TOGYBcO%1+?3{6M$I5UZeC8;J6F2i|l=5t=HLzRe~v#ou) zYzPD0{%lqIQ+2l|-Ur9`&vJta-G$idcF74(kXyl1t#2 zVPV~M4v}Pa^tT%t`BmofI~7P7`^u~UpRdKTqRXyZ*KXIU&ZxVQr$^$hV6}$~YkSWz?$}7TMC<04#M`6 zGUe9YCOC?^73-!|V`l$lE{S1me4Fs)0pp^DHL_A)W?f{M#02`)# zk=HQViiW+qIaRS#BsD}(BPrcCDj-b)81eQFoN6g?kwacc zIw12Rs5>qQc-nb4^m}dw{(Xm`N|h`&NTlG(Lns^j(%15zHVckpvg%j#cd=>2%Xke; zw(^aGdr^j5?nR4BYVEzEx1k^iE~+lhUsru2<4!HyJ`f_fR&FjBRve`)2b{DAqIjWo z8yA>(jy5Nl}8={#s%86BX z;9=;VG(>wq_L628l^YQ@b(~CsS$|5)BRRWCX&Nli%mVt_Cp%Sp5m~0n{YFajRpngj zya00WdNT53?~s9}#h9RMIj&DXj(}&BasaO%IYWrD#K2JW+6%xS87wQsx7kLdz}Bru zG2K0J{cwjjhHSmak989(zIq3}1XK=_=ITEEl1HkFAGSPQ&uwq2g2E{m;J{|vaPxM{ z;Y~{GQZo|DJA1fI^d;?1o1d?jt!kGw;)qJ4w1;e%-~xFK9H)Ag@*uj_5;DXLVT${J z14Obr>yFA=)A`S;`-bLgzRqtG?me7UD^xk(DW3`O0*k8?jy{Q{WUL2zndK=gBoU=Ej;Vl!E*WT58QHJ)VE*w)Kt5nY zKPAI&t5))aFFof&sf3>Fh|s5=WTEeBd;=Mt^K_Sb9uOAuiVoroJ&p|{V>wpH3nNnQ z`z0*Z(ifW<9{XOvB-C*DP8pnP!z3vX=*a={L4(Lk0dA&Qu0OBBvs{O+3X=s^{XIt- zme7q@*{UG)a9-W>@o~y@+3=Ryv68{svR;9yBDE(w{A>R7_9{@uaR(*n#<+vDEp~Pi zDRL@#@ip64Jl9DFG3*=LJaz4QZ<9N@PXeeDl9?^sA$2IaVD zn(zR%bnJ1JN%z|T3uz}h2ua4_{KP}qaspjAiG3Cf`@Yy}e3}4eR0|9{3I-6-JX>^WNGecjT=NWjS$_15 zqucdT#LR@rg{b`3@Cu2NtNfrT>;9{R7-09)qmo8Nc49W4i$_vP-HX2zc;w$+rPE`% zF(IM?PA{W1dyDBO$tE4!K#g7$Gcyi)@@_1GJMCQbD^>Hn1X11}fb$&>I zQ!og)L7tkXpQ%sTE*RtrurqP27nq~aPum-&j9W|-%A}4HuT7fizl6?A>^j~ccP)?( zCRXSCeiT#b@S#8jO3z%8@yigAAu8a!rKF>z#VJ2i##pT62F{6tRh03;P zz;0mGiU39~q4R#WHR7H?-|ww|-VchW+fjXXUO!VvY<-w%JbK-^ro~<7JTV|HmWug6 zAdHGZF}Bc=`YL|ApTXlhd1~o8V{PF)3w~OhP1N`X zqAW7S24HPtY?rQYkZPEkPF>b9X>ekT;z4oLHk?(!IBrau!q)~joUSQ zKXv#0R@o5IHhl*zb2W1Xf8LyFn8WXj*^Ss$w6?p}^lRO9RIg(ikeW@}W2tGmO}BB&=Ela1k3*_z)+H3At10L4>TAnfaSx= znnp!O(UYzAUG}mln+t^tK@@RA=G-tkX0B_`0=|q~Kd&Ka0k?pSU7G?H0w?EOf*RV- zD#XUA9XZ?;8|llw?=ypAVMElYHe2{X;8LLDp1V+^F~{P<#(uTZJYn^$9^>R&L6$$< zf(+;W)-t<$)6spq(;3r=eahL#jtY1C&{b1nmP1hpSU%nl?036YEcBbwN&h$;(zRQH z#B>ccU7%c-aN6`)ZGGV_>-t5g-(^|#D7y}ETyR*qehVU!*Jy&n;8e+^+@f zQ8z?DnBX3M$*ED;ek${^ndeX3*<9xEd!Rn^fo}mK*;Z0CmE@HU>Ty%?Q?Q)asRSWd zQEz5%=3MQn)r!@w$kFvG{v4vaw>ziGELJ^U9Y*>qCtAIhv?nKC%9$$~5sj$1e-$Kn z*Lthq?{dR%4Q1zJ8w6zQ3Y3Q58tOsIAm5cwhYmr!00op))r}S{xEAi7TXBv4u3mXrgD*IG|>D6=hnE~+KiY%5yzL=x21q`p_)JgvCDJ5 zg!_^}X~YJIYHcS6^#;PNxY(SqXdw7+aVn*#+pA&Jkl7JY@5#115H9Rdz3bq(4rzi+FGODVdd6BCu&VGYJn zX1DM6rcMVt;wNeE*F*vuZjt7or@(VRJHeaKNt5)zx8jiNoQvAKRdss=#i(nzJJ9%W z{%#=%ox+{b)){bnC$-6Rrcss}u6e>#5yN-twpLVG!dF)jSp``L8i#0J`f0xuxkKFt z9uf8|`iZ7)^G=RV-JfG3+r{S|-@S}KR_&Q{M;ER5hw#;jWad1-$-0Faj#T=XdZIVY z>RdrR=fvPtU60r;uiXenl^gM5e8P_U2tQVXiQcZ`AIsZl^b@!Y)2GtYAFSjQGPjQvWAQN zj34BM#LX2(?_$8lF^)QWWI{9CrO0m!#pZ~3xHd5&ExC52P+XuDhfFQ&4DCsxt8Hh+U-vvinuyzeP5Zv$UOU82Nch;5lkqvy zM5QOQ_m|GhJHeNH)^@%vK1SY2;7G&Cxyd;?H<-~-yiS}Ban79UjB6Cv?!_*#B@Et; zWNoX1m3KG)9E&;&E+YH@3UTDZdaTaW);YF7SC5gcwu>VUWqv5{A2b!FI8>OxM>Mfx zEKcaDi%X3~=?}+n0$g#ZCd;9h!uroKa@}zg0Yov0k7xm8X*+hqr~AldbkN(-t7hr95DWAwpc6P&<3@PyVP3(G&$ z!B)Q3vT&dzTer)rHr@`(A9Am1q1|X1>(-rCmgXQFy=}<|gnUg??2ox&<}qtk`fBtO zQqy&2U7P*27KOCZZCWnzFx1V_yc0@%$x|Ino1|M$pbIy2k~bxegzi?GmNh9@<_HhP zOLeMS9l@B1Re!k$W<(RNB-=Ccmi4hNN0*USyeF@C&t;NG!&Z|}>~wBp3R!M08)#;K zDY7BxnOSTbXtV!PU4JoIrm=axvl#^FX?K~`~E2bO^1!2XEiT8Awy1?Vi zpnOrFzWY!YDa<+!Dq6NWlHb${otXbLF(0=oW-!LlDPWo)VEP&dm)>sNqI`AMOk-@d&^#F_OrqUfaXC=peQl-RuEE9#BfN zlEIGSxoqgI8wbPG4-~UQ!7S$Y*^>HB&An+R)oCW7-}MqL3>5oc4Gu|P66iNn+0{(* zLFMQt3>P?Ae{hz>*cUd}#FT`#6e~5x;CPQN)a?|Ywe3DqyzhT4@IKA4ilUQQc0vQv zmI@`YDvJ9y!7LDc?4P23JGu+^X}pMCI$#+mFQT!Te+Y9%)N}}0(!Vi|I@V;UKz}$= zFpN!j+49N`=Z4<0%$o=OK{yFy>UoY+4Q!S)o${#<7i>I+ef%;tE;HL!@eqr!Yq@&Z zA+?m#Hnm{Mel;o_R(fm`thU$H=vc`qR=vX6T!SRXB&E?glCu>1;`&n4`J{!C&(-Ip zb@pX=#dP~?((5sWB?iQND{nxdBDA`SKYUfFSDm6*^ICOMc#~Flp5Er@Fl{%fq>Oqt zv64=Vvw)&U`B-I*%e@Y7OVs4XvGZTFM={q1Pn zNS01a%jm;MmV!&@K|Dc9NFUwXM4N&`%S_7;1PRXZ)DJFZdh3@qavb?XoSMUPdwV1^ zNE+9KNIyR~oUV6nb8potPoLQlat*)DuSh+|^Vs#1Jd1%_?ob`$X>I}!fbj{CUODH= zUu=15Kfqa{Oz@;Ej*|iTp+O&`@mP$>W}}zwm(JZBfr=~j#Y#k;a&bQV`_Vf`2I2~; zTr{MhDBuKhfBa_Tth5)Qh+M<$O$A}4G8BFEoK6hMjr<%)(M{<&{}vgFR$WyUVLaDV z+bvj|xzF1-Udk*!J~$Y%W=!(>^R@n+nNG1d*0_-pi-FNoIXO3Cf<*c64yCzag${Dx zgVnIKuA|w0o4M_-6wqvmDpVbgBB zcSN?b#7@GvS9TpCSSPv9N&KH(U0J?3R1JpXIyFANN?Cd*-};0`=Vu6Q2#-*R8L?zg zB_BTPPzY{11|<)^=!50M@8QE|7H|~TKxFR zQm8vH>6Xzv=z6&L1C^bXH}Kc)hPAiy)0U<%3$7Z{M=^Wd#X&{4YD*f|8n1bvBPyFX zJPVlDn91|lg=1-}UVdTl$IiFjQae-Jrhi?%?u~;(6wF7% zf@ZuUL^%=PW0CiIG4VbkK;mv>we6~U5n_2+9tprmoz{(cxV+((33zxH%=(;Pv zHLj!E2mYETMa-v?t+XXA35SV{{AMtHrS!QxiylhcxlFZA^{mWGFB;SCuX&p1j97c~3?5_PMX+X9ImJeXH>|`;ndk?gG+R3~%=B!)YSLEYrmD)5R#b z!M{F=Wy|IuTCx>OMJhy!rAW&Ny2{>Qi=eonzI%-aB~+uvI5!N?`}Z-O}B1i*D z#hnzox$GHmw&%wMU0&()d)9tmW}6v{k{#WYj+PQ3S#aE|KA(~(@I2p}%*v~6J)>Rj zHZ7Bk6yH80wK^CxqI&o3cK<3T^~Htf;pRb^E1B$iByqw@=7JTq3|7ueDRETKgd?07 zR*xxqFiO_+o4hAu3oT@nwLChGtax+RXJZE4-u-m8zP-6oMnCC-(k>I(WBql-DPY%+ zYAaY}s?(nmHTzi2wtUlJhE6Gm7UfK|8VsgaE@ir@%kCdM&EomgMQjlQD}!j1EMcU98tm`i%f8 z@37D7jBbs3%aYzRZJDH=SwSJ~-ljW2PFHaWSDprC+oZo656IDT^na@G3r*ftwzqwI zv7xu3y)n+mxfJf%7Vfj`*^NM#@|Dc?B1P)W>^T}pLM!lp86u1an@&A57Jvxk=6Blq zkCfo*z-h#6=uGU!TOcXG3~xg8*VG(R5rPqPjmmDaWmJACuxYDr!RdoQV>*Z``59A| z<2U+iYseoG?@3JteJhH)i4i^U!GqoDm45q`VU=QpKWZ2_NXoevTf^Wr4-K5q{4Fpw zRv8xPQ2x_y267ZXo^czz!NYA3$LX&gT7j6PdEz7D?;KiDo%MY)2vGKrmGqNqe|KfV z=-I~DWPFw0#1BgUh4`60&so_KD?i#X00I)z&NN^VI7f`0{5ZKVDS8KQCmkT);7;um zFGt7<=LS?)+xf z`=VpVe3ElMv*;u#t`{k(IZYT56# zxLTO|RI%ZkxUc9^BY^9;>C4 z8_KsQP1B6;Rj2;CO5%WR81sb~;|)_pO%CLoH7(A@7W4Y7d1G$MG>@U*q>Y&JOl@B? z(;h6heA*e&5?7C)H`8ltxonG=1)Erp!>!gEjCKIs>tbnblGpDq38CKi6Ry?can{?$ z-I6zZGnYw0&=`{KNxL8AQf~Yj$!9MBLCZ?u#*I``NdQU&SSK(7i9VsV49bxQ4}@;y z^(^*0Y-v~U_(ai)`9vC3mEm@7{tM6;UKC5M#J?< z;>qtzqfV$m)IRpKo`#elJohMEn1yUC{6Hv67rfVPQr1M8hd=8lgkeaHKCd&&nL4Nz zyy3^bZ^KqNA&(c4+>8oHqw9A2_DZMO;F|Lf*L*43n2YRy9+qITRr620pNP-u{rYd&1}yrxMp@-8*d4Di0V< z3mLu0prDKj2FR~tbDir?rB{8qKc3CCnWPpc^6`Y{X?_474=HzijC<>S_!Rw!oond+ z451S_q^4k_wNJEdq-tNE(oY6NIv&*0e&!*Gc$YQV%LTx_N)hz0&mJLqM!&p74n2gK zZ&r5q`nw28Cu5c0&8?qr9wn#3ayH|0vKdN6n7|d)rlF06cgDA-sS2BORd@Q?PZuWM zO?~f5grAYDPAzTL0^%;sjB~HsALd$Tbes^oTcjOq;@Ir@yeU?ib7c6V)+OfP_2u@A zbekmsvNp@kNk=<%M3*7P*nQ|0PuX;j#u`^n-EP^i?bV4`)3NI z?;<(H3mGnOa}Hc743dFFI!x%;4Yzo_cTwC$7}~W`?fRrqyKnZVJ_8cJebet_t`N+# z?GG4F{ouB<9&zb(Y&g5STC2yO#7BDAqAPs((QMNy*Y)yCwl?Ei4d=qGtUOK?C=DeXx8sr8RvBCa8+P$X(`!^jM$r{Y09jO?`Y_KoA*3O`K?3RU271nAud3qb5w8xJo*Mwa`-iY-2#@aS@9VHU zHsTsgDW2i=%A0}BB|kQHsf~w+`TNpL-H+qF6m*v5OH?MSd74pPu!))G87zqz^YZHY zqlH&qzXGE~9Kg(h&TM~tHk<}wfw#Lo>AeDj8BhFKZUR}lJwW?qTeJi7tmr5;x|je< zqr;5ZoCROU5MuWozigIN!>+O^d%Ri|)T4pCsVI;jWh;i$v~Mi9Q8yf6*5m567S87? z`IGNV@si^r2TSt9{qvSjJ_68Un!!+rlBrxTgFt)!Oc;BUT=Hz7&aR>8;f_e zd8sR1C=qt^JA64!PE+6avSeu*i)!eDsxmv=(~Rn0X-UP_nvPAX74Kri&HOpJzAnBr>vtV+ zjjmj`IreaW4`67gZ%bTES|nT?xKEynDmaE*(Yvc4nO%u`*N2a7k3uY&Io)NV^elgU z@JJ&h5gU5pou-|#q2$>=g6ApPG9b?^q7=Voso(V8J0-?ezlrQTDMt4>OM{a8fcf`# zj&g{B4@YZgMusn_%w!9{u6h#+xe8Y;0ulHJ@RzYnez`b3%J;Gp!UEFGnK#I9yr9g7 zGm-G1M%OMFb-yfTT0ayW`9Rk{K4)TQQh!3$ju<6mXk7nj|1H!Xgvzl`(#DtG%u`<9 z)(?aItE!MpapbqN*}YkxZ9)%l62n7rUfX9ZeJFGN3#yZ_^jRvAFa8T_WXGT+tNtlf zHAXX`E3Jo$vBQCb@!I6t7NePTyo*Ogz1g+W2)&|E6QxLVf6(g(!Sx^*9@gvsK5?)4 zG1$zG;icLzs0#_Dd6O_vaB6?`NJ1?ksr1Z8LYk&hXf(5r@YEJka`RH8qCbePSHSnx zgGkufJM})cT5Dlcf3qlX<$i3Mlr!G4v#?gw2UZQt@Sj@Sepn}^*akd4c@T)nh%MQ5 zkq32eNSl}N+3f9wz!igsS<+_Wb;eE2-RHZ{;$}JD)W4Wb&`vN7V)q580^aWfkAZ7# zjO`yDgfaRd^NeqLo6I6}<){!Ur*H05{S2{2jrI;`Z#BM`x!03?U*U9ou{OX+JH-+4 z_Ws>N?SqF+QqWs{L3xk2!dgV6SJf=l@j8kbuQu&beHve=4CC3?UnycJVtoHmP*70& zXDIPttD?^9)a_K`548j}Jb91`P92b}(o0Jv#B3OEO!XuM4=eYHKsb58IAZR7sY@ zerUX}woiY^_}V~KGEy>WMv}vxneDY^Eq7;GFB&JGSw-~Pu$nMhGPxA=gUbG=ETvg> zSW8pnuxqpb_#A&A7qTCvE#YT0&W}?46INUQXa1%HpH0)(kgaj74PtBMsx3(>+xq1} zof!@BkD~jd;E2&%HO)zIDK)zjM~_IXcg8ctJ2b@~RGQ(Sy?P%!v$IHvNH+P!74aH$ zN{DzV5^G811AU<)1-h@0?=iVnq%CUac94BtJ|o);qCNK_5C84`*uI+`vwZc zWJ$ncfsW$(Rb|_&4{~#KdE!t*iLN_{w=-kAqd<_<&--#tFBTS`pI6$WPqK?a-h}(B ze<;upE}pQpP$GUr9+EQI@u10e5;3eIp^zp}|_aZ2-rmz3<(|HJJbH@H_+o-hNurIzlZ>UFa zM-z{-J&)g@)gb#EVEg|dd_cG44gYK1s2z4;=n*g%+X<`u(W~8PEBty5ipWWzvuctm z$f5`tP;tXDgj&Yr7GN^US_NoFAn|hdKw5{?tvypx=9QD`cmBFb^reBVKw+&wWDk{( zY#)`*3_e|N*gjot82rkcDEA@)e`{4&@llb@B1ehGp3-c}Tl$`oY%;?{nrE<3RXo;3|&@9 zQ6G&Tjb~LhD{avg&nV6)`igB8`O&D&vTZ0=t8K+c;hjTkD!3Q3h16Zk+C_w&o7=QS zX0k|iSSj+3fFAuUa((iAh>RFnyvax(bKlsS+$27m!&DI}LPd=;DryF=7p_G*JY;yu z?-s8YubGqFo!Zgqvm8lNR_Cp_3f27}Y{~ z$jUE*bQG`wmswPr?Jrs@D&5wxig}}JU|q1QYDAB2WY@w;YF=D}&P=H;ij=ryrUUuZ zuhxxeO4lOyuqtU3&ZebIXeZ(3A554)4oqW|Nv^t&LGr>a7s(ROXIbXEDB z>SB#;jScf2ZY}yn=d&Sm_WLpeN1I_Gq9)nM2J#K791cadaaSw-q}aU?X=Sf-%{#x{ zr5pTdhMKk8qA+?+%&_4nLnVhSS2Zt(X$|v%Q4J>&AAbfP5owLn2DeG6O0{6h&4#B5 z7>qDM0w_#|(r;L#iCr|4cr6hg5o!iV-tdyuCPQKYu+#&xR=-wHET35|JKW5xoC%dx zG>NWx02KK)1AVe6Q2~{44=Sc<63BGtDbi3tyiIq zKz8(+Sd@L@6Vp(K<~l9?Jl`xI5?&+S8hS&pm|z9o8vH|t@_M-1d*kQHrQZ|TnQxJI z@Y}Yn{vVFR-JPd`0rUGI@ixG6S_I+p;!=TS91#5b^768leLZFc zY3&4hwijSEJ=pYnox8vXz>8pYfBCwC?hY+cm@a~DNlwU$f|vmXISCqM1}ww^l$Y)| zBSRd|nkYg1AB3D5ZzhDFA$bsQh75I}O2hnM>%q|w;3x!@gmNap1(cU10#8LTi!=rm z@5iS?Kz)~&GbWOBwK%Q_K@Dw_m#+Yi7M!8#f%b+~5G&|Y$%lTZpn{2jigw0d&QD$U zIQnMN5KxVLnO9Mqe?W!jnawBbi~ibu;@jJ#x1f)@oG|yZP>OxR9I%ijP+o(df>sa1 zgWW*#8`39a(_PgU-JAaza(ZD~T=U<^ujdruunN2cVPvSn9uZ{JG`v#ozq7smq9(ty z;3@7xNRTlPdp^#?Ttp&q#X-bjrHt@uiKmf{!%!~q;PBu?y9(k9n8r|Wp@`SxPb5%N zxe{D4HF!uHh@d7Ap>?3VOTQTx0Sj)z{~xBv zD!d#>o^jy_w=nlL_s!$7bJ>de_;vj2z|LVS;6vb;5J`LtfehjIG4$%I`7zCi@HY{{ zXXx)4-_m>GAkqU!E@DL;QEG+1&>kFd(5TF10)#4rH){K8vjZ)YEwZd^wj8z?a8bQO z1`gqh2B=}uaLv2uWny`Xl&A$GEhw)9me_%zk+oReQ%+r`)Uw6gIENtCi5zdmZ z^cHTh_$oVxF^QCNX|Kg!C5%bO@)-Po(w%yw`cX&4dPEw1c= z?#olAoA3kx@&s#>sfJK@_J>ePSr*-(jR9sd!u;|$(}drZx3p*S9K|HxS+}@vS%wom zYsb;YqBO?EOv(-9htzYqI>!-BLpjm>k@!O}L((JDEJt}$<3r;b@8!4D_WrjV@wT+A z=th@TL&TNd{Tjq;n0DCGigziu=u)|^{xj`8-8eL&F#7~U)C=yz8gyFN*VxzjN7%-2 zO?68zh-Bx{a3?5#FhA|s*+KZ3nsTSq_E{=7&8&s_*Q4=9u323otV<6zPi$gq#T$sL zXn$zEha*guL8={y7gaC&nn5>t1Pj~o9e3LuWgTUaQ(N#|c%u@Ab(BT4m-nlOMG@xa zDg6QHr-db=xTlsxi2!gRd62ySG2+2Ymy;j=$}i0`)12noRx3^v#*%0fh)3}6F(f2A zFsKc6YGMu7Fn7iLq&%w)MgJJ}%yOlN+XZ#Lu~T2X)bG!w7u)+L-}uR&o+?k*4z<3q zWB&(68T=nj)H&DL^G?eD_uhi?E=J)1MTD>6MR?>} z@(txIk@y-?^egEEnvPHRZy>ZjsF$vX?%z~&X**-OvKwuUVEsYr4v31Iio8CS;67@d zvZ8LZlj{l%UwxR*%}`ZNF4)x-!%`q_ST=*uypRjV1wXd8=*roDaRdnz5%dQa3~!-H zzfbR)?keso@*6uq+dh=k4(K%En-los`2D`f>9%CH2<-%3hiA4YR~k#hKgv4rBD_jE zP$b~RPA|@u#I|U@VaVPOKLzewqz%mrj_#K4hz>@#ON&0Dy+GX^xug=mNpeI09WnIr z@}nsdhQkFaqDm$QqtB&9`P9^R2R=z-SK^b&kYvDQiVELYmGAW$&*t@4*CnJ>qm&en zIe9wJkG`#Q$Y=b4i@wEkVwQnkZ3*z!B@GytNKk)8x)SFkb&7TT-3SBs{avK+_xxcG zr4FSY_cTL&6LP38o|X!_j;x){Q8?rW8IZ zM7l2V*0pA{oqc1q05a5`%%Zgv%Cw%$kB1Vu9OA&6D>-Ed!yv6;5bV&=#=qL%sEmI7 z^xVV0;w!%{E5G&^JJ0k=KfKR;lH#tGHEub~2DdZOd|_$6+|)jx&J-Uh<5<1rmmXY} z9+)amJ?n~7+2As^rvCgiK7UnD`K5CgwKJy51r&|!XA@mpb6x!DwhoF0&OJRkkO&=P zI{bdE4s(fMbF0L>sw4Qyw029D2CSL*!epn0)tNE(%H%{1 znqw;li~HPt{SYZRqhv3X^L;Oy_$J6I39{oFsV*pLcc`^4sH&_1tyUDPL$6DMHR^|( zm?!wNM71fykf9IK8!2887uQ9m zCF%}Tn`1B~>kg=R@_X`IXLk&!JRwIKVbtFliY1T33C1Gif7><`$!*{B_*DDRfZWDMgVaqWL1D%6zcASK#+2P zjbac=S?W38gHx;zg4SlmHcj>1_42j2WD$N(NiHWvs&OW%i|xcNB!#@Mh%cyw!_*?~ z@xiJ5nE_OclOt!}=yJ|-j`%39H++-atQ$`S70yj4^K`0aylCH3;&c_`8wg zr0tJ@9g&2D?_iPxGflt=MCcK7dW7$s9Ab+wdRIC0MGKm6*HW3Uf$0*&i9!LGs31$oN18qxa;w;EXuGa|mbax@fH7^dPN zDsml$Bbpkz~#I<3*5sDn4O3x;SRiL0`35r;x;58SppV)+((;()>j6~)ulr)!7kfb(LFjP<~ ze=DiIFKJA@#25Thh_;tlGK(`vLC47lB}Sg=Xp&$!!E6R}jOpZunr`A`GB@o86)(vx zLjEuJ=+Ag~emfJvf>ykD#0H^@)qvW6VJP|Ct5JsxRwbw+|bva_r&ApNCYaPPsjQ8XWBuXe?V8Bn17K?*2M8)aqBVa z9P41T^=CQ;yWw%)Ul)2AM(ubbV?WKUHqT}G3)?V+|f{0<_~K3 z`+!DOXfM1!c&R*cs-Gf*ak>TsyXPwMG32Tc0wD$HKK#^XD+B`JvqlkkHX0j z-|)Yfr~8u%W`6-^Ea9WZg|B;6D`=rRy-@WFSP@i8HH6akh|kYsS90uh1{;!;pc zc=K83k$uF4?E%}$c@!Vn5a&(19{Kj52?S-(mR=_;GSIemGG-_Ba)KEltRxLSwie!U zl!tk+-Nr=T08>K_PD2DJ%lBXsxn{DQ@0amtJ2L| zt#f%OMH691Vo?${A*rv^WS{PQmBI!mpXA}c->1#_(`rdbZ&l}+$mir+-4x)>{qL$q zHTZVTE@NV2pQmga;x+p2G7L$sqGwoZ-!;`IZ8>_8Z$xknY?vJt4X%eC&n?WorA*j8 z;igPIqo%h#Wu{a;r>2ws_2X+Q)g@~F>l+Lyrr;6a*EE;ft?oCyb3n=K8~5XmnD>3J zqNbZP&9iGgx`980mujuUoeh=hhX4bBL`CHX_5=PhP}oAJ8%o_oR1 z9{nBKM|A*Y(l|MboM{&P0*vP`l5sPT{V_dI@{~ykb~!D? zL-?lJ6K>Q9GEjzMr?4zVHLk1hL!CWcSp*7CWH(K9{XO}0#y#z0av`(($sqI4;%<*U zQ2`fot!DQ^-5hh)Q=N@a$tv#qf8wNoonRcLkJHnG_dCO*WUcO0@YB?18vpvID|3#n z&rRfc83+oh+x@=dmBz?)4_5BbjLPnNwcMib!P>&_Y2DiDao_6d`6)J<)jc^;(BwY| zwwz4Q(vI;!qigv@t#d&Kz0Yi?XrQ?(b**dmFTlUZYT_IQJhghC$qiFH=-#TsC+Z+( zPS)(Z&v~ny(e^He;~gU@$(9Xbvok+G!hvU>bmuIBs;3cc-VcY`>{qkO1lUz+nmK&F z+TvIHvl?w_HT6x(74s(8bMh5S=*Fk%pwZ55glSX~zgq1au8>v5Fh&$Tuf-qNoJtMj zKV*)ly=Rhww3yl+1Gswm>XpVDpiu{2q{sWzO~5ELEM7u=lw*#V0U!Ctmg~W7M-MdzBbO>!KP6!n1++1Zd}=h(Iy^5GEtz0SsC1V z=SQ-1_MV?X)n5OxP$)}21{kfe%PD#M_AC{3P{?SFpuagOpM4#SUCV1(L-Q%q** zG7s{n-NxAaWORda_FscdJ#Ir}9TULm>=3}{T;wQpR+^-L#|tR-I?9K<8jVVQqb$<2 zHoxX2uzi{PokNxtddT)t%Qv-_nk4#?@58XUQ~%Rbzv-e_*3qh4{Elc%x?9YYa(Ts2 zv!m0vKK)Zoxf*JRf1-~(Mex7?fq(lC82`B&f#*=)t{T(q-VXft=lTTNLX(GjubI5O zlXEZowDZxL;p`VLf4|rl$kAE=FTm$0Bme~9f0SZ4`XwAC-v6rd4do==OEhiZG+fi5 zNF0S#!0II4t2m8!wAEL&B^jmc*Us5J%?;-^!wup#z>VRy!HwWH*50!rT?I@NX}vY* z&jv=pLw1yEyL+1v8kx0a+G8;!7B#w+d}OGFqj9{%^PE1sk>LtQbQr1Bc@7+J+t0Gb zqnUKHIneTG{tA0dZ_wmQz_{#*xU%Ruz#~}&oVmdSs0CWZyG}=(iS+P@1^IUm0Dhur z27*Z825I9Syq6%XvtZoEJDl~ex;g?-06U119Y$j&Vkv_-Tpb-+j(Co<_&q0^gNUad zD{-A&Q)6pyp^>4Cd4fN+uDb!CNYQzfeDH3hfF(tat5Bu+O8?1?rX*C+*Vu?zsd}7a^C#@GnwDFSw@BOEuTDR_)72wZSva+$mSN zRHmoZ@w)bFvumQ0-`hPIBEq}tswcinuNSL>I`F8s z{K9D7wKH9bXKHy{CNI5|y4fw?4slY7j|0(3R&{xAw2R10?p9^neu9BhuiOJ&{`qyH zvte6JSDj~_V~$7jBYzrn>Ny(b%2@UD3cB#x>mLit`n z`6cCx|EY_gI^tsLS#6e`7k<8<5w@Q>h!NHhk|+dG*o{^?$`CS;cLckyEyw^tx4W&p z?UZ0~v5Hl8ezPg)g){0LdD%Q_`tg->z#ewk9CjLW@4mKroCtUCO(QneSSN;v2Ywf; z?=5P$8ht2**UlcQ9Y)FFj%~TD__we=o^)H zsAem37C`D7mUk}hTFGQL!%qh^6CtgpgWI9Z(&c96+9=CJHq&_pTHZtNYDeujhg>tt z{X+(rqh5F2AlFah!2h%0x_ocofY;1Q5s#-0hVn!Zx{|sRBfsJWean4@G;vsA$M4ua z0-MCW1DuIXAYCgo$8%lru4ngU^^rYeb{uo7rx9HbUa`_S)#KmmU1b?fdHf5AO~g&+ zy3W4H^5q}*?7RnZn)O5h(7W07bLu>8fq5^sV~&}VcRmwB;M{G6KIuI30edSm1-(~R zjG2{wHzllPk8Y?k_bI!9wmGGVl4;jpUU?k>5+EKo)S-nSFk(m`DDwaOs~6_*Fyt?EjFKG;?|EUocYS~jVk&N44vInfq81WRcs za=~I(_oJmcs*G#(uj8LzDPBBo8jHkQWvC{j#6=2;t?~APC(p;Z3+b)#PKqV5Tdp2>K(c~_wqU^z@e=Nob>>uVR%;b|+gBDLQ|7evarrxPZ ziY}02nl2*jxJ7skswCXklm4+QP4U_5#;P>pJuSMLI*cr1j?V4hS?W8brn9_Na;Dxm z2@#M{`#6b6jwL;|PN=|nmgw69Va zZ1oT=zSd&4Eh4g0*>xI*600pj^mwt)xh+FFG1{f6vHvSnd{3(>(78o*KD=_MObp(r zN;e#r_zlul_<(b^gfrHzI`Rm(E0`Vyqi+>*N~W($XQH_>Tet%Rt~)>j5v#8f2W!v6 zyFyD3iL1iuMAQvq`PvimHXtj}2hIV6dNX+(PgyojQQ*ftovkvdg$`7uH6Kr6Q?mF_ zZDgx33Cvr0^aqLH3<$4vBwHD#fs&wgBD#D~w`e0x3;JiDB>!-BMBc?$oIjApD94|R z5D>lnP>QGtUW7p6w@%7dEFzW>#fV=yvi#9i$K$AA_X8+r5=Jam(CNyWOkjj}mBda2 ztSzZd(Nzekvo)9hZpUs3El1ASw{+G&=o2W2-Mt2q40{g6!Qaz^ip@`kPE}7mrD^gux02eMhsrqk}sAr)S-u|u4oXW6BhnP0rMe7n1 z9(JgaQ&~=s5>5 zc5qn-MLDR9eR?jsG<@~L2?I4A%41NceIy$&>LoB3gUO<*zatq!QwZq8o(-x19Z+>1 zN68x0B^|``eeb<81NRPjYFM>FgmKf}vlqoyW(^FCK_eYUdHot9)VOAd%sq+*=M-<+ zl?09HKUOlWDU~$m1MO~u7}naJZwd;(WS68Iy=S0k$ZewUA(zsO9gT+_U5hl(RC2$L zcDi0HSFvIHf5V6o`iLC`IPj`-k&gEU<|WoqxKXl_Km>^IkvLMi@%RX8BaHpryMG~T z<={l^4!F;HVQb}gLtk2`sf&?E@)pL21ca6X(O86Gt{G8uv!d z6eQLh-HinHj_3W-`yNU?*xgb6^a?(K;MD)^_Yfbncn(xhou>++bl}uG3PQEUHEVfi zapPejfDf}3v`ABFh+s0d-@CpR@hC9$JNqXYa4Q%o6OujvFogY&slT0#ZW{F3@_YXN z@9}DAE@rVN=xP?o?tBz%hI=&C=SBla1&J2nxIR7KK-PCGbhU+x{$2N*MhGQlW6DOM zF1Mb1VIp(E{s2jnJI+m{1!jr1Lo-?&&a2IXv2FE_3W9UVt>zgLF89LztO_576(>L1 zDv#@!2W-6K}rN zOydvln&v3uXisI*7PAU#Y7kvm*FE)$^x$ZVv{S|?Xs#Sby$lZ!IK9Q$JQEx{_!_`)F444L_v zY9t}?s2`3M4Ex=v5fOKp1N{i&eipB>_O=!z^c}5HTr=oPlR{$sxE+27gZA~R5nnUe zjY@;`=Yyt}xp&VOu>#cvOu@RnhT9-&5xUAhNu#p|bWR}Be?lXpTGu~oCMy^G&Ny0# zQ2{j?GG0KkQu72VX|PgAKbLt3Dimbhxb7!k80Q|60{F4^7hqdMg3|_Wz^E@>z_?O< z1pe1C3<;1`rG6&&u8?0O9Aql6V~czX^36aD)G{#8jIzJNMWH>2&u_{N=m)X6szx9U zLnv2ZklbUCVWa*&r5%%ttQurY(9a%yB%H>A9{cCYO-xP<<~3#Df?6g|EdyG1+iBRS zP!mr%17dc=X#|kv=umkf;r>+5yhxaJJ+74|80-9Nt@FaFK*#9SEQF1S(y9%7{5^ng~eR<;fJTbt>$ z!uH?4$UDHdf5^rid^4N4MP7EhycKwX9}{IJ_&U^2+NLlroLzL6UF}A?B0jU`8})at zFIAto8&$i#|6X@}LIcik=tT;a%S_L{iA6qBv_x4S{oe4H6}n5PObR(>#U6k^iL(Rr z3YAaQXQUsj{(^g?Pvvh5{F`xq&^}RZi~Az=i2j2A#Cz~ivYBhAbW)xy{+C-R3y{@I z>O3vU^oeksAUxSW(z*AfT;4FS6?{D6J^DO3KSG$`7eu;Oy(fP2cOUJDuobZSLd6>S z_AwA+D8QJZDMjiG%TT~s3&(t*TL}0fITL1Di1mrtJGq`^m|=T}T`+s-E=4^fd+&?fPV$_h`HaK98g4UxxNu;GeD;~%I>k@{3tR>$CrL0C&q;u&Mgc$=#~dau4Qekl3c=B3<4x7}#nbTA4*SMGI^-R27V8s??LM}{zJPUn8D5~zyRGn5)0{f(}; za9y@df=&AyjjXpbHl9Nf>67=(Gc3Pb-k0DiyU5os;e=qGUo3MZvsCQO{9!sS+zaXn z_|xg__nOR>pe&JHPM64cz!w;E;9NK9HE7@k8t)y$AyQQR7JpPD;R(!N$L>9R@^1;ZfV|)W?>WHahQHO4I z^7)}yt7g+!7VS7b7h&i@+6K+@ILIB-D`{^o4{c7O_#uA8|YjTDTZ?_f;YR&60x2 zJkBSszL=JM!UfG8&I8Up&MQu^&l0^j=cS(Q%5I?{QWR1s(?CoGAP*cHp+UmY6Ba^p z6`(uda?sVNasfS&#S^?cmsfZLypPSp@snvq7AesxLdza*SPwKP!qbsR)Vsk$zPl<@ z4EF+_h&sPmJ^{O2yFf44Pl`C)2mKk#2ZsmVIF4CH3H&#t5$%)iz=HyUKri4=guh^G zu5g8MA9gD_A}l8a3P^9;go7spf_%|FP<3FN!rlH&+v48{-srr*uehShqZTxcSS|ko zI{3ead%Vj^6FT_yL=P40@)?xu6z%dD60dnH{NZp$FtR60L*BqmMfLO6O4%C%JEU!i z^j*8eN0Xw?%3R9vE(^VqBCt#4r~_PpT!&_D4W{k#`AfP)@kI1X-pYI);O?BwX&6tz z8bYy)#Nwl|3w$Cl|75-43@G|af6^hBb{CMxWv~1LrBw(sQI0QzY)ovv*D0RPkc!Xj zh(BgiO{0!8DrZ(DB6v-ZAiLgvl~tR6xA-?|R+k5#w%%@$yyAoPl}a|?Zl&Pg2;zP}g5NjDW%zn9fQNFP~|OCZ%?0?Z_Rs+5vMgC;SkRHj0&D!HhX zy+Ft&NvD)aDj_Es|0HQhMUR&RFDYKQKSvcubXxgWuZ>bSrCKU+&iSa!;y0}72inc5e0?VWmfatR8JZ?uLxc-6RO59xJoy-zW|~Cp3%&Nv%jhtNP)$#u^26pw6G0&q9a!QQweCz?c|$ik&mn5k z6SDrS|G~tqKkp6BS*b~$KEaH(zy04ZlR;c!>Dm)Co^lY!tBJS8z2Y_Q*^MUkiI+OE zHSSY;Gq`&p+DhqffIgB3)Wg`8k*%r=z5?E0ZXm4Z(eJzmJO?t)!`V0#Pz;9KOC|px zdoMn)%`Ynyl&vmAb(z&=Uc7i-F4+HJm{5j}`iu;7Y!28=1|9=a_51Uwg_jF718UK` z4Erxkd((98fdHI}WxthPt%YXL=IV0pBC%(A0Nb^S6++`?V*ruv%ER&%0VEa4wH0S@ z^UBQfk?AI9P_0?jO^Y^FS^)sn`Zn>jTqB&N%P$AinEAokyh7C!U1!4)EIPO?mqjUP63lf9@4efbvoF}kb77YX|{Udm=~R(r17C{GPshn&P<3L-uGSn@Mngxds985h0~w?W=7 z9{a{}@j>nE^?>$UWDhP`;KE- z$soj4C?@jV45(NvRDV&q`AzNSDNaHqfSqd4IAxCK6lWK@oJ6UZ;=Eudq7*{{j|-p^ z;3e;`azNz+Oa_=MQ8=RV1x^N(9}l_6H>#YMc|tz|z{_UmA5b%R>EwSszjG1NY)v8` zBayD|dy($|I;JzJLp!kwvxWOz@ zGuStuB!2r_LXJLT?V|X1w#nc;;u4-50(|FHgvY}?!~D>9?$_+E`OQb+zvVpSc>M*Z zXOw%oJ1-g~`T_NKs@L?6Sr1n}YMy+k$2`YHiqnH7j7P1s(Vo?O!BEo&9wW=0RZzD2 z(}PgeI{Ph|dS=mqww{BJJauLi=f`YJ4B<>|=gw8pm-*_t+vI&@yggJq@6~+KAUdIJ z-()_{3yGq8;4AItpgRp7REE>lEcQXiJMVYAb_!kB(Ic@Pyzqg|2*Vh|X4i&Zc+ZpZ zXS`=4H-Mgxvymsj5YOqzJ-`9gL);$L-uhOrXG87{_UUTntTSoHTs-(W!Z`C8`>MHM zh&y<=&+vAuXCwTabmg$~aOJXd-{NtK8}m9r_@SCpXA1&eRnW~#61LA6%J>9QC~ILq zodoz+oWNWhVPU=m(*f^b%aCl)K}E9P!JKZXI<$zrsnuv+0ic3TQmejg=Y#*h^))#fiGp09*D(DwSk_ym29 z-U?X$B`(5pik~ml2-he5Nr)6R(pEq?;xdP}PrM>A>GEs7xkkZ#NwTxKsbKSwY#=!6 z={S{9=Hxk^k`dK==cPyZI+{@Anerm@Tfd}L5}HCL6XV2vhIredRrbhEmg0Zi6u*t# zqCa-Y9!BBA*H;&_V>vws|G5^4aI_1`ccDqpS2Csbsd3E}`Q8u`&C?2?Vd5v}bmXNF z(o{mA54`ThvabQbIk@pr=E*(UwhS|}H9)uTCOnX~FF+8IBhud}?MJ(b2R z<_3EQzntU|dVtzvIb~?ti=`xn!sUM+@>`x0ZrC@A!=Spoh<+FIvaO)H-V zYBW}d#;4%ipMNm=!_u~Ze?EI}nusfXD)pe5lVkp#JmH?y5mhHu52EW>?*7=gYv59A z{1VxHWy~0!T;hPy7l{hkcv$d@a_9ZSW6dHy-+u9QBAyNj!G6y^<3PRSWF{xzj&n*8emDe#5psLFvr zHU@=HxeuaNp3~gxbV^fyDdXD^KI8rnxmxoEjWgAIa7tC5Dux$o=WCA*{g(fv{yy(t zNA{Cye49W2nrzpfIr&bn_Eq&|z?GH7^c`E{@tYPSMkB_{+FGQykZ0NSs@|2d{RasX z;yua%=%s3x_vK<2qcy<_GB{#qGbZ@f< z_ZPZ;7#>pX5Z>vVhP_kQ5#Flza1rl)12WeUUdh*EU#d|Ayg8=~)@}K(+QWxCKa;Lq z-s7(6o9dtHyF~j88DlSxy`M)qBfH)UW5&D0)5h2Tm4`e@Iy=2Pvo(GeXUzI&Pug}@ z95phO2VXuf(7Ac7Usq^D#qNIbE79D{nkqCKdfMBlS?QFO4<_ebIht0qFJC}7+GqK; z+%2f7=Z&>Al@hmBJ5^g%oH?qNQm6CZpe(bqos=t*&_}M-n^lB63lNL-wpyjGg^stl zRD|BLiI9xpay*kfT>A#z*`3%apwD&=`y%vI5~oiZIjsUWrO}y=ua=8}XiqNH!sTYJ zpqr_puww+;7=s<ctpD1#~(qT^>Msw6|snP*!j;=5~4HAHYX^vcZq6`2NI%d#fIavMP>%pk2oiZ``H4L9^+`SR z*MIEP|D+6;8bbBQ;W`4afLlfRgkD9dBJ<3@PT-yWT}ROtcoD8uDpwA(sJyAd@uvKP zL|%mZB>zbCMF_ip$v5IB)+5Q8cxn0%l>H+=6RwyZu)BgQ5A?CES#%gbAenZS_rq8w zaD0M6Z?;u2rJ=zTPHL;xa)+C6nzWm^o7~rtMEi$U`BAN1{TZ7>VLA z=f@vdKqi=uNLfZ;QAW)p(vXXz%1G<7Pqd2h|B}p4Xw(|C=kbHN+*@wi&W+sH4$d%& z+XX%vXfyS^qz3%gBWp{7OS?l@LtdwM|5}=bWe>XC7d0ZFGRgTMJ4ppi392GOv)%=% zp|FOqGyp5<1=N5Q77+M#h|v-TYV@2leyjJ`-uk={^k#j7XkY>!IYuhY6M1i9dnXuj zahZo(Rj4O!GfiCXM>@Jh%~*5Rgf(X=MxwglSk8oklb~6&L|j_=Me%|(Y02wfESV#< zM*vUer36YC3Q+knrp05<_lhQNgK7s~+MVPRg4zXD z@m!$l?2t}DT((x=wE^}TY03wb>pW0~A=dsS!CcaRAXkLi23QTJ);(-GCq!pH0%gpKtY~9*j70NrA z)bI4(BWI-W1k2s0SHo+pPl}R_W<%j%uLH7i|5Zsya5SFyy z1vYIvu{1Iz{GOUSO=I7QF_!GV{8)#uQyFA)7+00R;z*@~ojQ7G|2mM0!?qjIf_(8$ z2TL8QF1rHEE}1R%@T^trj@1o$**ele?IIC(0hY{ksvoQc5u+Z?zO(Jy5CQk#jSI_q zQs#mV<_ezCS%%9sYIIM|F>r%%zAroQHF(wNy+zSB3MVw4#;iO~7G#2yqgPh=6e~`% zI0=UgJ5DUUI;W2AMmVY`2h8*DUf1pMYvj!YdyN9v^K_Rrx4AwVra=hPyKq{L z=7~JpigdR`B)NgV;4G{R(-hoIq){8)Jo}nUv>jsofX>CT0Slv+k-r9QiesQrs|FZ) zM7lBB3T*6DuJ;08d2-DojIt5iLhx&h1|wBjEvyFP0vp}ZD)<2Sdd-Rnj=2RT2lS;T zy7tZm?ly7L>d*>wmr5xj*en%w5STML%JV8z{oUb{<$D7r`hJg-6ZUdA#Gvqj+YqAe* zH^T<}4*;z=SJup89BwzoUOWvWB?!%8A9TT{j!t+K!o`GR&Et})huv~V`q6+R{U+0> zCfU&we&sr!cblCS^)B**czt-gY0`22iP$romte@hDRq_Ra=jJGv#N7z%fhZn`!cID zr7W;uqH2xz=~ogwl=nv=ui3RJs%N)%kI#gU(n&o+9qec^-{&>Wgs(7-3{dNcHXPQA zZ(=Px@tHSvk+!@)tbZ057lPxgM=jQX$Et_>^aKFwTs2PeoV3*i?|>Y#%LV6v9`eKX zdG3nroOpznMz4SF$m3qlO^jM|mar~AZ&Zss{GbE8E@f3jjY%xwo;*=CD!kH2kB}x6 zV|0ux_@Kiq;l4}8aZ9Dn%sseLO;1#XI`NFuoA??}tC@K0kH0Y(t}B*a8Lv&1JO09A z?=7ssfv~-xux@0?n)Gxyji1$YPg2Nluow;ig0ms#)|`X*a7T!%d86?rQjY_tK5!*Z zbQ=*T-;2dUHiS-)M?5?U;h|()mrYN*B~IMyv;aKeHx{LbSSKbKj>3~yX{dv5Gjh$R zutG)NS4fEKc@9dn-;sGwc^>}JrS8?M0)o?fb!C46Np7Bx9(R{3PRzU?BHwbyTJv-pA-z@gE+|2* z-S3{APjTWNVRyD|gN^BNX&&~Q%$tw<71V!G`hZIT9Zm}@Cax&f$8;~>+XOH;tKuTyws7D>JEFaApt#DeEb=_2jgkoXWS`82XV=odHwV^yXH2KLH_6fFB-Z=JTsp?*a^km+8#w#WVVU{P zP}@rz{ZO@`B_8|0a--WTLwF+B5{0p0{G$V`4#xEoCyc>rH35;W=9x1A$XAVkOq~F1 zoxn$}{hRZRAufN|_L9Yyi9e_Dt%Z&W)QL~tyI=rDt76>iIH zGy98bfc}zKg}9xsOwRq*a5u$a?=~%BCM}3oI~`&oEhqToSys^dFQyUZ%I~WJP79J) z{tB7=$?2W_M$h8m7lrC~O1?>NWck|zk7`=o;rR2HxTML&@gyr_KQ0f7mFX#BIL_wY z`)H?(Y_d1Dn&jv5UEKRLK=(z^#zH0aqO`4G?dHInNG<5x8Ic0 z$`_&7bvhQ}j?lT+ z0|gZo5fq3B!$eYyCnhv13>yd#MJ-Gs784K^u@x-ZC>*JRjF3<+lmH485|J9s+}_G@ zugt=qCg^rv(mbzpo*K)rWA}WzSgkjo2BaT*-!ty#KPmU$Hq?FXO^_M49}dPXU**qT zQjGZmz#zUvpg!Mnj@x`wZ!wa;d6qxz#oo8MGOI9O_yOH~m@oUS=X)$mJvEmZkzRK> zR?WJ{w+|rtrc)ueCEaBINc)^q8kd(7fQqDk0*&~wE ze~cf^-FhBK%2_BWXQAZ$kRRsUq?`wmORRofCrR;9QqBO$^%uqJ5BGo{_9&r~8?8)o zo8{@ZF{*5+vg!YS8{_|_XJuXkZ=-&q>TEM_8k3eSrJj^VQgWrVmeT&B-<_o7N$DZw zHYxq343aWT%19}rrHqv_LCO><)1tkR!UhXWrLKhQg%q$E9HQc z5-CT+K2QEHexH_dE-WgaGA7-#{Papvs)n|m41dcQ(yL3!l9FTj|NdQHN)u~qddnZj zoZeQ-jZ(TuiCaDCy=;H!eWlzjWk|>$E+t>e7^^pZoRmpY3ZzVzGE>SNDf6W)lCmWH zz5JrzKgh3=vOfGhKWw-DqWXV(t&x`kn-xiw@?;l$n9~2)JA4wS<9~++# zpAw%Ie<40QJ}z{=G83F1{hYHNGRhH+~>q52nRCow;Y(}KR-pUlAra7jfrhS?+SnRB@R*!%g-_SDNU3m&L>SWpj1v)lRcr*h$-&6yI) zP7CFg_rgX0o*n+47nX$=^;s1D`z_NjZ=3w=%G;NBFz>MZ90L#MmC8?9-uak`1+mKZ zCvRJ=+qOA$585^rYy!WfHxfPCHW&Tko$IxQKODLh8sLL1sLiGJdhZ5B|9&iK zi=@&m+|$TdKTJd0I<)CrH1!t4x7Zr&h0G9iu0*GJ!|AC#I*t8-f=~Ohx}7o59l%fh zQG(-DCgOmzkjGBPD7r(DoaGM|T!hY_DJQaD>Bt#s3z6@P{PWNmXgdRzAb;Nbv+x~n zlVC4zulAyJg z(e_@j5Uk-AhQ#j+{%(wHdwBSmx2rK|gL6z^0)Wu#=4C1HXVM8m36^`@u7`EevrbSOgY;s-X~XJg+kDZ18z(J_DAZr$lXz zoba~`mVqbyxnMpx03;IplcJ#p^K}l%67YD46N!Nh8XIs@Xh@+Ug@zPSahTe}a1Mu@ zHG(c%ZBX?qZF>_Xcv z=vmOOhN#}#hMhgrR9h8`HqxLMS@hR3v-!-U)}Dbr5&Tj;Y*DQ;aO6&_mFqQCzpBy)hEF!rGrLFyT^#_#l%T2(Yu{itNi8K z)?0>ET07k4^FT9aLq%Deds$O^Sx34$u7)n8_V3{sAI6@cw0#5lH}EqV#y_V1QIuS* zXy>bOAp4^;2Kg$`8<8I$W{)EBK!NTKtihr1XMsNhucnv%U`1Ltoz1i*^sBXbx$@$@7G+NlfmBlMNmSYU})xZ(k*zZzpfB&@AfjAtraJq+g%dOIMD}oyKs6 z=JUvQyNczmEIR`8vPV5Ed0-7OwuV({aTDuh4Y-LNM00hfwiSQAPpgTnpozqx_VS2Y z<#yLvx4X?Mo}5)8by(vaX|*c&p8TNlt<_qIWaS*yl`awfiS8^|o*U+$iAZWM3&BEg zLvW4K!E>zKTXdIUTVeMm_0EQYs=xk zjnC^qXET<=dQx(Fc&dMg7Zp6Fr$?ujqRiJsvWm{y9L6|L*P7d$eehaEH`^1A^AVa~ zM)C}r{|fzA=&tDBuAUcE&3V{7QqjBxeH^^quVnOGq55xNrW&AOhuwem93|(3d&qto z;Zr%i9QTGZ3XQj4P&)_9chgrf+A?*d-e1%kK0fijXMV@%{_a*+ZSE&ZdpAILVZ5b` z;(Kz%_pHQB>?GSe>(oNGC1bxNv{o(2fo|l<*)_6-QNQQOX)tmlwr!;?(eAYMM(7%+ zRc}25JH6en1!sDlMRR-RafLTT@>+d&|&JAN(D9lF*MZ_PO}EBV!y+tFOR=;C<>bIc4c6Ch4hF=u0#z z*n=KG+aT=hjh?`NQ8PdojXJuu*mFL(O3^<9egYQ5&jIr^C)hKmN;=KJw*G$h5v9A> zQz&|NgImzE1wC8P^EvWEksqoYCm&8bI7xeIRoa|YO9Vdwi{a-$t9%uEvZa?|i=3mn zqo=#Jb^1W}v9#(DEQX&0)`62n{BYht=a*I@o`(;7R!4{;kSOKs@o zH)XZz>`e6ZwE01JJJ4P>dHYzi+zwRI*pvJb&i1vq1#|;HLR&5Lp9S}UOK95{>_XdB z@V^4LdlIEVj*crRQuKzajJLyIEi0YAf>FNiQ~mK(J|6fd@=^6_P{g`!j9$XA=<|My3I7%`Bj673QTC?K z*k@NM`X54%2Un9_&$0(SqvtoTA*Z;{LV6`w1Qvj$TB|oN|2Y2dj$~!9O>l>xy^(Q4 zbXSL11Qvj*;cX-zqt(005mZhO<@k3K75zEuJ_^Rbd`^a=IDdBGPRa?^t4I8-r7tAi z0?nl!96=q$F*IKt;!3axEC5BDf34n0gZGJCduUP4{I>Ad|U)4`5FGTeZcLaBd`oZnMsc&3}bHRLY07xw9$t|eFyx)an z7tM|S)&3TtPx&7Tz65_?i22|Ea1+>6en+Rs9q3+96Zz)i@AKfNop7ym&-?54dq2ERRRoXtsN-t1OFif*Sa6kMHkuL%Jfb)a1ifR3H zr$gqC8aZjTp{s)}&~^d&nb=%OcL%SUKBw}U`kBO!(vI5ZpVZm+sJ9(xlmMHF^_EOG8 zm+Hw!@?kk^VJ;a%YsZ5HVfN5g`^g*c>%CiK=D?qW{p73QNugI_b7!x%;O`Z^Z2bQg zBmJD&8H3F2p`>!^au51Q$LRe`@5nAsm0f#l`;=STR&w$a_#umVZ_K^yC8DLKFS#g4 zr`7kI5Z=`LxIf&Jn}s)>96OS>BWXJgda?H9Tu+aKn3q?%^$%f0&v3)t%Zl*eJg2vE zuOW8ciTpS8h*kb%=y7^CcOQhdG7q4k6?m7Pm*m{2t8%qhL-z$N{E9fYx9OXRgszOe zsk=_b)lc;VqrtI?-h6K?Rs-}{-QT`_Zj?Ci|29SxuF!Y)(W}l6zZ)?YUL*4U&D#|10@Kw8s4&qe+EH!!w(&TIKEQ6h5P#f zy}!#S;`;2%+fBc5R?z2YID@vh?pA7*WFEzry{iT9_9hAcF)}LmWw~E#?XzGOoc7*i zq4PbptuY+(tyhP+_!|6H(cPx#?@;s_gA=u_--KSSKxcQbEw~VE1=d$+I0e?n!;gax zXvRz1q8><3;?Hy3`|jr{{R2v;1?+nFXsv$@9^QszC+K^XPTQi|(vx~J@l)If+b}L0 z8?Bk;PRz?I&>3iGhs+!Le83&3{`WGOg|~=}D|HuhkLu{$rO;KO$0KtHY)q>hFoW5w zu5JAVI^+IA_$`opjahzHY3FM=ZGu+dOpP}rYw2uCoIFhqRNRHmCD2!6a|S+qLir+j z4r|Y`Liwb=;&l@-ZpBB?OZBsCFt_40=xf0O{ggbceH~nY{8(se+{>!$|$X?q4v zA=sH#&qHTWTLPYkLoZG*IH#bk{&w_!7W|Cbe}ctmbCKx|_JRLpNUIHt;VgyI6}o~} z4WN&L8^CwL6G+CP&p`*!DX=DZIMqN;hS-C=`A#{m^-LC+shkL-j@%CJgntlv9k>e_ z>%E?-n?yrPI~Phj9l&|ud^-!!xu5}Ofs0alI{m=%oD!@$3cWiV%T0_cUD}SN?KtHa{1bT+$=peIaoUf+Y}4ooB>b3xl++s zIt$DMkI-X1FdJ+Rennq40$+gsJD8d3DA*hNa%Oh2jY;J@%b**j^!EJ;bX)jDg_EWj z5NW}qir#88l&c4V2bA`=G1rT%XDVLSPaBc{jg1Yoy?_nhBlAyu)l*lctf`vBzv2u# z%jKta#WB(`Av$2TU=6SXIG)<^XdAB_@u%{;z|RFuh}pU?K+g(MC6jo2f9UyaW?>$v zbZ6ze&r@4QtLw1PMtB(`!vB#2c19TKt2UmYhaj^8FYU3}Lw)7##bb8;W4=Mm_+iY}|z?M?)q!*7MuGMkY)@K2}@BNwnaz<}Q6eX@Ktz*Pj zk>7we4(|yuo3``Nqw+h^xrf@{5UYMP(6J)1|Y(-{;UC|&Jz?q4c z+9R_Uw0VQLb=Vigt8%AsS^JUKz)_&h74^a2fseo+4c!qOP6R#<|MhS$(0HB{(&_=b zcl1Y|9O4YJdkV7|;QyLnA-EG<2a?YtZ!=#N&}+f-wB2Rr3mQ*GPC*X^lX&SYbQNlg zp}T{9QfJjd_+O%P2DlVl60Tp{mqz{;BL6Haq7T>={s!pQ$WKHY`%YvNy{Cu`cE$*q z+^vOVG0_4YIZHO)2fYM-Uuc_Gnf;)Mh^h)cMTX&g64XVT%}9N)_T7qC^fM+jRHS~x zcm*Sy!Sm$dUSyJ`;N3``Cl6O+a5e)EaMq|7EcG|CBbL#25=o1OIfp?$w?)^c}7)m>(-nSZ!itcG|k!-%&IJ7n7iWZ`o9`Y% zn@F0iijf@K3eFxy@1&xPLUDonoQ?uLo%E@Kv)SsQwy&Z;2@U7KL*P_!xvS4}8YnvJ zT)o|A>%HDN2dA3f4?Fc+WR;a;_9$%*DvG?)TUFj~hn{R&HFNd*d-dGeI{WSdY+Itw zv}v^*YzwEp%KPhSbtJSzYx}~P=Z@8E1HXNU`aL2q)V4sqgl#L8j+9`J>qHd&GJWd} zwBtC+iL9qqzk%E$a+q(->bKf@I8y~1>r)qJo%6hAUFR9K-1(!fYo(nj&J@A%j()oB zsC=Xl?4{`5kIXEG?>ag&1e?0g3cd~9$bAhxLPyRZNn58gZJ&p}9BpSbN+W-z_w&x> zx|SV{ioQ-w?5wKs@9-(V6A0%f=Q3T(&NaH0RX&mgdn%gm6kQh$-O$#@siis7*@;f2 z&pKb~t^vIS$v7HPwEa2sQSifvdUypk9FP1$B%4I^38&;m;arI5r_AM%GTjTDW|~)> z34Cg=Z6b!Z5C2U#qR0DvAUeH% zU?=dTqI(Qns_0jSe?iglz~|u9N9HcYU_X)#z&N!z(1W1+B6$=Jd~d2^T3zUCsC^$S zgF`RwpP}!Co&ffMGYNc5F@m*Ddul&|F2SAvnL@CL+D*`JLw^n40^R|i5xM2Gwc56W zPl5M=pCH*1nsK@RqQ{4zH)78|@Hm`5plt}PS|hm){*}i21~ z`vkS^>?rM>1S{+uDeYH=a{>BBJ4bL{ursB!dlxte%tzbZcD`tpW@il=p9H7utRcS? zJW6ejVp?4|?_*n2B&UJHt$*nKW-R=``b0UhCn{|{hM&C!U^{xm+mUan#gooDG!S+E zOmH*u^T9n}0%X*ljkLMgIUf0|(SXnWC^is3PCa7p66B8{^9FPWByEg!1fz=SZ)n@} zE3nf=rYjoW12f>)X4LiZ%r@j_QOg?f_R{Jq`og#FOuO#z;eOiUTW>0O4SL=|rWyM2 zr*ji+SHNeL`8HOE(U)C`b#3gS=VNFjoo8uv0-4`}HbU^8JIY2f{a%T$mMKQQh4V6f z**LroyaDV<+g;Et(2xs$1^yHM6#5zreJgqxmrw70Drh{O|XNPmc1)S|0J>kk!4R z;2Px1h?xn*kIh#_Ai2nA9l1}zv6-`!wsuaLcbAz8h$Z(=Im&GV-lDx5qjwPR_bL6fs2|t~JgMj&1D7iLmEm7dbUg4mIQ5aa zOEK7wWCJixZ4UGx=)OoEg#+K4s+d+6`WkBA2g~5li~DEjd!Z+QJ>X0NA5)BAt<#>` zkDyDiCqSkUETVQ3^xM#1gSUWpz-L5mIc=@B?ch`3ec&fZwuEL}?!V~qA?S_RvkyED z=MQKbLaWwDZi9a%^fKtV_+%CIqu{IHwY05G+X`fEgnohAeCWI3r-6(mI0ZJPb{aSw zyqQ)X&~FwNTFV))w*YKMTSguEmRd&StfMWn@6QA`BR?P9113Ogp`CF%uJPd2XkhGq z6rIeYQ;!(91oj!Om8nTSD_itxY+N$ zLv1tk;2Gy8_$%NOy}pfsVQ8}vZe#Uh_{ccV!Z|_hZ$W0q!4K{z@MW~wdAtt10qjZb zF6b7t$_2jy{|SEzItN4FiXJTY>BVn_>DB*?{Qv?7AT4{mbA~16flp^XQ_@v1^?5=zN1bZN1Up>)>Me zHmg9pJK=1BK1ADS^g#0UT?98r*-wVtHvDqct1O@1{Rx$71 z=OC-VWA-Ch9z02_Cy+l6&D!zCfuF)>PF?)(_lM8w_J{9=qAG~+6x&nWb6I1kR#;S-N0{B4~+Makp&$$6fK zWbkZc3H*iH*4YJTD77y_J7_2c$AF6&du2su0v_nCPe`22Jhf;E-O_ze+p3JI;CaR6 z;qwzg^EZ|8bJ5d_R-Jf4(pEW<%e_~GUp;&_vV>y06}C zon1;tIz#uPwi9$Q^ruLUgHDHTOYNU%bsSDLs}0WKl-~3kAybW3&A>s_?z2d3CiHn~ zUqZuG@c#(E6?6k?1L$8tKVxlBI`Wydf!fEEPW7rdE0ItS&T>;r@Bs8YrQOT8%U3A6 z?ZMM<&O^^e@~?{i9z`z#-vO6Uo30osgDwS|A#aeG4mJQMQ#%G5W zWCr|Rskb#gRo>f3?LMuQvFq$qMsqLtHPQJz_SddBFLqAC+V8OKfVT4U8Ou@l^NG6g z+A7kDzQ#i5pr={t0-qpUP=A6`73DOgSOO;tnWNCv6y2M#swK0wnZ6!F^H3}-Q4BnM zTi-@VMIVhim2s*mN8i6A8Io1zRn@TsHIYB6wBH4p%5eJGIK4EYoqn$TBU zYMT*1CGcA-N`BXQ=^n}`9w7$ypm~?|f9MUhyc1(7!B^GcR{{GXIU?-$0_)-ev3HtC zu#)Pxx=KrIpC*!3=5BBXoZFGiq_0dQchG7xGIPLH)F#9An=4}puz3Yz{1|=~_&)Xw zvyzN=q#dSSd~jFn^#ryWS$b2njys15Z%)&dJ26TQFj~}@_=jC(KOm7oj()#Yne?Q;|Df3 zBKaiz-gthdqU5EuC|R3>W+-}5I7yYfaXrj*NtEfm>0@umKz_=qh_|> zYR;5+Sj%d9ji|W5C%G4h)eFS)1?EEObNFpSxQo?-qoba~NZZ+6jGR--?5tBvBZ|`4 zW!z&(4guNY%r_c`at8i_9C(@>s2Qd=cD5x-n-Rmih-z|?NG?E9<==!q0?BUBG58Cy zd>`}@_+3(a!F*QVX+4u`FR9rThncTlx>}jj1mnuF`&#Nxd|rQrT8rhA7)v&iy;7Wc zXq#o~iq6b%W`!v*^#?~3 z(@sHuuKLrCLH`Td%Jc+VAbAfsMBjU(ww0Gyn}gpWzW~~{I*!d{@UMbjRWa>GM%M&9 z#ds%Ey8=vue?5{N>FXr?ZRpH}(-zNI&UtF@M1CqgZo^CG!6)hcCL|luRwbK3H-pX% zw!%LL-4H#NUk^)egT5B}4)p9-OizR6O+M-A)ZPi_S+uRzci^DmdNeeLZVuf-|6X3? zcSBbPub@?DY|h2zLCo@8M*1DK*cL2;GXUHKmQhmsr z!!$G3n;T3=$^W|$diMw_wvF4Mue4-a;41Mdchf+N8( z;P}D!j2P`s0cU`7z=hy4aMj>@9=_Mz0B!|$fP29MV9DUY59GT?!7@e90jq*_!A4-) zAtUblmDdG~gT01~eDHz)V(&YktSFkctGZ`y-#at6c3E}_OOPy?1#u+_3aBIj5k*i? zau5Vz0re#)f*_(INiv9lh=_@xC`bks6_Fg3oO6y}P3?&6%KMq#_dEajkEhQ*)jjD> zKiyOHbkFRJ^@v~-!4`t;1Um_K6YSBdbJONlAHhL_BLpW3P8XadxPTAb)LJR{o#0x* z&F!D++QIrsaIfHD!IOgL1+V&OTkShGZ*Mz-v4U9ybMng0c0R$vf=PnOf)xZS3s&ps zAE&lpeZfY8PYAXWY%kckW9Jr6+0O{}671W_Up`Q9u;2*6v4WEXrwPvN!fj;F5}YTv zSa7A_cY^D?w0)|Ty;X3h;C{iQf~N&9cInW(QwRhd!Fa)(f&~Rjb?K5+GE_mZs$ea_ z`ht%MwqPt3YA=`~*h8?d;2^GEWUrSVqkj-J`#D$Mx%_u>$lm+r z825)!NsA~xs$Y`X9zQ<#D)A3vhChrseuJ@p7<0*)YO#0&`Zc(58T~G5j#QZ-%b(0; zmYm}Fl;=;`ypZot+5Ax8Pgvwg`uq6%oFGT=-^Z9gge6&Rq;S+929seHEQPhO8&0Ez z@t6-wV^yq=EieW9;xL?yvv4V{#oc&XSt_ThrJhp*)o3+c%~M~i&FY}Ks2!cC3+r;a zhHj+W>F4x7Jz7uaYta9#aB82`wbPZGr7I6gSAOk=vXyRqh%fVvVDN^rQ#x(go0N8c zI-BB{Nqldw5$Ia9%O<+|z0&!j#7>=VtYCqdyEJOi5Urn|wSDpZBzrr#fw zzDN7*rBs|s;3fWl5RrdAI?8(%=W-?)pq!FQkPK z;&WQeOlj~VK5Cg^;=h8te;=+@A1=mV4D`lC%mL5K_bmHjBYX_{VSDTV1LPZ)1Mz80 zfmd)K4uscnB#wf?cmhwr5Il=#VJKe0OEApu8ZcaiR0u{WPkHdB%Ahj9NR>%tf>A1) z$_ArVUX>Tds6wg`j8#dhE{sztsw*r|-Bov3$lm`sSfqNYUa(m8RefQp>aY64GBr#M zgXQW?^(L%Plhp=TsiWL$F6+{|G+fn{byc{gtLy5h^f)~ZwUuJMg_hmiZjPnwmUc_L z&2DYC#?p3MyDi>scd@%*vfb70ig(!E?e18{{xLKF%Q_D_P4Sr1-$lIY#d`OsXT3+g z@#=$Ui)cG_D%v|bNL?gFVI8L2lv~G8UdpRuDL>`c8R%BJRmV{wDx@<~5h|kNsTdX0 z2~>hg=uA|SO6ts1no8>|luXGwE0v)#I+4mzIh~CvPz9ZxDpEzAgYKfcbWW;FmGv!D zm8$AoRE?_X+|-1c=sf->g>_zPMXhu`YC~;we(FFSbOGu}9rdmBG(D{gQdjD#3sHCK zt_#z%^sFvIy{We@N-xk0x)}ANe!4gfpaHrB4WxlOiC(2wbxC@iUe~2)2o2G<(J&gO zOVbD%p>L;=G*TziXd12Wps_Som!a`AUYDhbG*OqMNi<29r^z%~SD>jhRo_X|Xqv7_ z(`mY{L^EiHzKdqkOnopnyc@j&*(FKFMUp*>-%T{Ezs3y z5iQcyX$dXSHE0`Pv6itx;A}F-|9N_J$?YA9X!i zN9**1w1GD0`m~8Q>4#_wZP5?Y4%(p`&=ESKAED!PTsNeXbW%5>({x%tN@wYuevCVB zQ}JIQo(u6JUSuzJ4X?5HuoaI3lg|gs{q^@<2otR0YA&)!4hab~C#f zcye_pG=-+X z-SiH<1C{ArdKaqDd-NVurT6K5xQ9NZ58+<=m_CO4Xco#sAf2-?5NcN*!Mz zlonrGi2Ig}jj=H=Ziy`ct-01*P@yZKE1<&_!xh;N|7Ut1`@nyC-#@)C=zWRO`wIJN z3)_aa{L{z&>0|$)K8AKX*7LELN0rw1T8}_>C;6q^!xMQqo|AhF#d zuZry+d7W){-fpnil*k)myGDkH?G_m-wtJ)pC|=u#v1?=iW4Fj_jNShRBg3WUT_Pg_ zX5I{#85uA$Dqv=Gz|5F{k+A_I;{rw|1dL1!7mbS@xsVtVPyK>WaOiOk&gpLJ_#6^6)-Y8U}SE< z$frSH`7B^&Uck)f0W)6&%*+p%Sr9PtWx&XyfRV)kBTE8CmIjP03m91uFtRdW7g8?Il0!9u8j2sCVITkQ-JYeKRz{tsfky8O9X97mf28^5w7&#v>av@;k zQozXNfRQT!BUgjIaxIk^2U3}FFqIicr848_fSLWm$WdYBv@mkf?)N1o3*8bd-A1>C zknXHILs+Ni6o}|K?iWc)FK<5u$pG9s?QmJpC=iM{kebF0%}Y;8;1W zTdZ7GZYz(K*UD$*w+dLd`ZeP-IwP~|sd^=QFgH=eU&s5T&RwH!e|?LB!4^gRxhdVA z*MJpo`ELL#XcYwahW%21H{MFHGFh3eELK)4(SP?HZ~N=-D#!;hR-Bd5vaOJ1tgsca z9Lu#lD{7GyW5rtje3!*_>&++W@1v|ct%~4TcUyM@@w#NlqNnOO4X8oRikNKXd*^e@FOZfM8>OkJrxA zpX)F5e7!(_sTb-+da+(|vo@BaPt{ZT=+pEx|A|aJgOC1!X79{r_$?pZuZMs1;t+q+ zqu!(*!r9J%Gk?E7*t=vuzc=uH_ETyWya;`vAG`$pVF0|$*YztfNWL!mIt+$4_$nU? z!(cd!fHz?zjN)s442*?wFdinrM0krmz}qkxrodEq2d2Th><`|98Sp;Lgb(0D_=vs3 zCol_U!yK3kpTcMCD?W!WU_LB>FJU1pV$ZPzmclYv4l7_Ke8qm`8(0P3!gugJtcD-h ztNaLSVI8c84X_b5v5(mTTVWe)haK<}{LCI_7wm>Tuow2hemKDX=MWr*BXAUs!Erdj z-slvZhBI&$&cS)O02kpBT!t%f6|QkNM)iQIryf-G)kErG)j&O>8mdO>QT3Q=teU9D z)f1|zYNnd27OJIcrCO^ts;z3Lo>c8s2lbTds5+^q)kL*XZBm=n7PVDvQ`^-J^^^Kp z?NqzeZna14Rr}O_bwC|dhty&1s3YpAcGWR;T%AxS)hTsaol$4iIdxuLP#4uDby;0e zSJgFkLH^VBT3g!IA#HS6NAv@_o_mT$Q{i9y1*Xi|ogWjk&>CJkJ-m16h?Rtm)N&jq>w<`GGZMD`~ z>#X(G25Y0W$=Ymfv9?;nH1HYp1o#+HLKz_FDU_{ni2NpmoSPY#p(VTF0#8 z)(PvRb;>$zow3eZ=dAPA1?!@9$+~P^v94Oz?5G`Q?lzT86;svRW9~KgnQErGsbOlG zTIPOJ+te|2%>$;MdC=5151EHe1M`S!Xd0PE&10sqX<{BXPnf2rnQ6|cC8yS$+M0Ie zNz>kRFi)9|rjvQvbT(Z~is@>)neOHp^Q?J}QxDVA^fJB8^X3K9$Gm9znttXb)87m* zFPnkp6*I`ZYF;z1o5AJ{GsFxv!_06q!n|olno(x78Dqwpab~=kU?!Tk%p~)+nQY!O zGtB#Druo2pXg)F@n@`LvGuzDZzx`@HGxN;n<_k05EHGc1g=UdiY?hd%W|>)TR+yFM zEAzGa#;h{mn(xf_X0`djtT8{DwPu}JZ#I~XW|P@$wwSGEo7rx5n4iqgW~bR@cAGtB zui0nzn*-*cIb;r-Bj%_%W{#T^=A=1qE|`nvlDTZIn5*Vm7{X|#n5pI+GtInfrkhjd zv^itWnsd%G&a=*Q&cB=6bzZ})lk1-Fm; zqTAPf$?fkBa9?%@y05r{+*jS#+}GW~?r3+6JJucNj&~=x6WzDmN$%V3WOs@?)qTgE z=DzDrci(g0cW1gExF5P7xgWcqxU<~Z?w9UDcagi;UE(fvm$}Q`uibClZ{6?Q@7>kz z5AGWGM|Z8e&Ry?rbboetxqIAw?g96Zd(1uIo^nsSXWX;yIrqGK!M*5Saxc4A-D@6r z=qXQomS=k*ZPEe2G)mE!Xlyh?G%lJk8XrxFW{PHx zW{GBvCPuSGvqy78b4G88=8EQy=85Kw=8NW!7Ko0Cj*X6sj*m`=PK>@4ofLgLIypKe zIyL%Ebei0KmbrbIWACjdDE6Q-bN-gD!SQ{azMtd!2Hi+M3Y&Bj{WxrqXu3^z(w$&C zN4ytchaRGbz%D&fkA&S4+4o4?+ADEupTw>G61NWMIeIP}ln8OyDr=QPkQsPoJGO&K zcB~zXC1sAiROsi>UfgezOldqS^X;dc{>~VsoGH$iDzo#Ib6%B_S@&i#-#(S2{Yi*G z7RbXfzcwqN(HsF5uy^L4aQlIxuOv4^a{fJTn`TXntcjI18PcrDB5ShBnnYQnAi}Md#BEnb`Cm&augZf`_o{nAtLmyc zSgMYy1GY2N844k1t}_>mbKE)3$5Zw+^}~ND#-@$1|9{8V|CL^f{=ul&<9FiWZ=>NTj)T8Oz#F5> z|7+3kdbH!XIFjS{jZyJ#Rv*6hNL3!b?x@Sk<3gZ2F0txp$ckgUXpRZ2I4*LpeVBXd z<9@&VC3dO~Y2&6B>t*obyo_GFm*8dcGJ9FPtX`s*&CBlP@N#;$c)7gXULG&6m(R=Z z74UBL3VMaS!Z(e!{cav_DMAjpe<cC~zlpvp+?DQE5`$OWGzxFvIK0W- z;%;+y{1T5T6J?f|eB|FoBG?*R!)@3W+d^r45<9@{*b$$DGS~x$LscA&a0?rr|PD9 z!t<)PdI1Kg7gc|FMZK(Eg~94|H3Wvs-Sbgugkoj({V6C$Ln~Qsx#@r@QyC3 zOTZVpq^=4JCE~A@h`&xoZ|ki|*7tDG&R}Q2EcRLZEM~RO+vhRSzGz>>Y$2u#vxi;| zy^1+PuZM(p$+$9H zHe43J^6#JF*WtUuci}hT%HhhmDtvGFUi>y(JzO2X3)c$Q!tcZN!}W1>xIwr9{t#{y zZiH*XkB6J%kKwlAwzx6E!+zZ4G;^BcW~Zgo2DduxoD}@Y>E?99LmX$v;9-ulU*Z{# zv*+=utK3JGaT~kOsixipZ>Q=VeKk5-ElGX8g-4?^<&H~ZY!xh-bHfsZau5o%M*-F} zrFs1nPCm|LRWL=YUz#73=5uKqC;us%B3OibO>r#F;jRpp;bY#1_i=Eki8aB(kvLMG zvRMgD?L<49o!!o1=d^FJbJ@A=Ja%3?pPk<>VBcyNv?vE@3CxCGAr7 zZTKUu#dWwIH{eFxgqv{-ZpCf59e3bQ_%rUrUAPT~+M zzMwDaOZu|DqOa;}e`lG+Rk4)JG+6TA3K?YXCkrPH**RIv+^t;GqToN5R)SNQSuMvp zu>vOtDspn6D%=Ae)Z|3afKv=Kghs3nn{bMQ7MwCd8&2`i1yUdZo`vTiGxX+^m9I_( zi5P>ikd3d=M96_TF(>4dr($NWA;_I~$kl9Q*S_ zP@aAI5pE;@`LFWovFmmDI;cx=u1n4|bt$XL^0t1Bw5rQv8B1zpON~OT?;3%TdWBiN zJq;15mm~FxO1a1$IcwcCUwjub*d$9xYV?y)HGRY zT887_6doVE!=sE!QtNx9*7tE-Itw*9DqZ1`iC?4Ys$FpR)&DQY7E+@UejTx%T=#H& z3CLWg!Zvu<^<@g{V^J=}U*C?efSYhpK~-Qbd`2v3V_SF$2`@%?2@5X~*1e6v5q4Z@ zbx$~oIt`tMKs++<1u;DO8p3Tq%ozjOc?>oO@;RS6UqUjE#EwBl=Y(?}TC#@d4;@%7 z42I`e9n63}9Q$X(aE|qxV4Sr5r_%PHaRmPv=1C9uTzbG4(gWs84_F{Q;7jQN3puhM zgGC(OPrzc1@K<07$MX<;#~LRKtY=-58@98SDGYmAmAG(})kOw4!7)COM*!>zd4%*d zfIotS%Kj_^Jm5dK1rNIa^6r7}c%K|NN}h7mzqSZ86JC>~*VVnDMUsAP5vUIpuP;+@ zm)t#%zrLLU?TmFM^Di%SR&sB<;QIZSm&!Oh^?Y*6nIr|juJ~6H|B7ejJrl$af%qX5 zKcvMES>lIm@k8vrbx@p3*DsocK!5}Y9^8XFgIjQScXxLuxVzin65QS0-8Hzo`yI0P z{@#7Qd+w>a|D38@_drdtR`*(~m;Ac>8RmI<@XmP!o}`qXr1+j92|W6dxwe9E@XvW^ zHv)8e;Cg~^21z_fG@hiq?=pus0-j#UHHHCaasZBqq`Q_!8fdK0&8lG^zY3)Iu0bWR z!}A3|m%}_%Q-#C657-$1v$u^EK7ZrO(>Jaj@Oq@S-kISMg&l1!?4Bv7s5DO@XEF(W zX%=}-`NReB-cGeg?_qx0iZJGf`&!y~dSgU$Vsdl>sfbX3pc zc9-Iv>gE-c>fNhPD>*{a20m_zESiCP&V%l9! z08E2sl<=P$jTH}2irzeK@*KVAwH$p5*yE@W9W>uQ$7n+gds8!qmw4Bd#|gd!+%LkO z>{?3>cDi%m+~yLB^+GSF6l$B_M26L`meiw6C6!DJkGtw%Y<{T_KXb2$*c7Xf{QXHM zWj#PAWm8ZmWus3=^*6DO>IOwcNhgcjkp1w!YUwtm&TfEhkownA${P{pi20)RW}Py> z%lmlKR82D?OzLB%A1W4E)yt}rHZeKdtMQB}6y}WlD%OS7%WRW2Q=q2nB?3(9P-4i< zB;WJlPA3#?_97Y}NvI)WZ`J2bNQE!`vMVZX;Qevov@dN&ca|3=lw;GVzA~60K1n3Q zgzl78S5Xu%mXCrR#dEgiPr$85jT>TuoHED<$9|f44kWD)5yn#NQ3$Uaebp3abez60 z<#?RlaJm?~@Zp?cGP{2AiZh}xQeD?Z&!sPkRG?e=Mds$)!fkum5L1IjRYwVT%?;@u z7x_nZ41=nsm3Jr{6`0BQF-a%&qQvp&kQ}I(QPV_6^>>49XBu`Ymu%Op0_u5Jv`?%Y zeIN7KCb70ht#=#K8`B#um&aD9m+wzLfc{H6vvTsXbzY zaI8~YDB6&}KEaE~;zJTdBL$95fj0^*kg(m~;(qQgfYZw{tgpe;!=8Ixx76SM;! z3=lLHus@5@d4xnsD;E#97>wiWN8nOj{n+E}|CWrA{240KHq*9v$*K55(sKp$Vao9+ zHpy0mlG4bR-}CC>eMeQ9&=IvvKPa)SExjIz9OmNZ)dh7N)q_^xgpNvyD;|FYty~j1 za1mBKY6q>r5IS&eXlxg(jE8Ist%%{^6Ks> zcFgAH`(;v=+a)+21y4jWdYT&o^eK?6vpk;qiiJg8wd#`jF_nX26WexPb8NarE{~jV zurw5za4u=mpcG3XH}XDJp_u$HbU-G`bnv3orvo8LS;Yg1F&Rr2uZM|u=t52k~1*VK4Msgzd5R=7i_vs%}QO5CAc!rF?-TBwX>#jJSxw$4; z7r9f6J|AZg*riHL8nZr*$!@>0+uq~2?8y9}Fnv*Q5NPbCZJWe#$xAKcGecc;=|XJR zepOET{VVzP8ZGH?Y~qY|I<0Wvn%4CoI{C=U1MQNG9cEW4d#!Zv3`O2a8SDC|ixNOC z;up$M5o^WV;r`lGqw>Y6?n>eviLq?b+V|Jexv+sYL5C?hBK5|(HlO(KGxz2fr+F)h z^;EClt=WZQ>PL-byHbe4af}hFVi^HZSEdd8jnm1pO`b8VD-;ciQ{Tf?jAdu-NF^7M zrm3&pwjp1K#h+3dpnQ)pxyY@G%X-P0TAM#@C)B0iS@NJk`e=WQ@c7=rkT|fJ?p*#g z{u0s%#!T-edQ0Opy@$>d>hKA5IQ16Lrs5R!+IXa*_uZdAa5{&W+K)H- zr%iZDrjA_KARfCuF<~s;des&!h(F)jEt#{djlPo6^c|d}diHwi#;%N=^xY>M`Th1> zcY@zV4OpNLK#stdujk$pZWnrlBySN4*lYSZu`i8%EwC0swehsEM>k4sm>V1$WAASO za26MEI*QYk6MLC{wT_RM9;dh)Th;_X21ERqz;){KjLb6niUi}G^+SpQa`4qX<3HRV z2@-U|>o0L6@JK}7S$tBlkiiH)r142aKJtTZ+4%ovV_P%M*25AHLP~j9LT==pl}viK zOQz6zLSc&?Rj`2gQH+uws=Q1f(Mpa`KNXJ((PHE@!xj=$rl0$Xl##d_&AwMo78At) zC+Y6x!nT71cmdc*#%DV{;zb0RyRo(wSz6Ltm`_z3pEZV@*6xzy1lxew*A{hxeUnpJ zC9@JoF;W!2A^^0%BCu(s$>j!(lkI1uSdJBhCk}~&7}H0qY#bi&$YZ5BuCxY1h0&gP zn6sxcj1w5m(@oMQ&woW%2yam{pozD{Q?lB*74i?H3NJhpN%Z_>PV97!7=8}1^U{g$LmMa9oNw$TlKknkI_fB z(IhS^GQ!(g7tp}@EQD?hU1h7FvBt5Cy* z*q(}{VqZwwI37RcnuI5AU6!k46#K6ywmaxtURGkV%$_09fo-Ta&*aKaO(#23VbmDS z9=Z)y=*4o0f2Y$l%L{w zx*z%k;HIKc%UaJBSbX(VoRMCV_4s8&;m3O&u{o*0O&JQE`ZbA=1cw=4?HvN9XlvS; z`8#iaSR?=dK#7dpE=a2PVT2JQ0&0pqL~kMca}5Qa$ciGxiQxtZ6GDGo+C?XTxxNq_ z>_e>5w^1mok5zz*P)3J%Dtz3O(=95EBe#mzQu@E1u2-@F`i_VG9!Oq#8pW_|% zXo1chp2SX3j;+1DX#X1CBqKumF)P8RtR;d8LX3`tPs%^zgZVq~>Mtl^U_>M^j2|eN zPSK$KFg`rAdyRbi>390-0OjfVx~AS4b%*nKbFaTBEgc)9U$exqM$;2#KTnPjzj2^> zc*2du^~xhW#T$GnSH}#&VmBYQOY38%ytR1u>?^Et#8wBc>7;lwl@?Wn%jW_@;lq#a44oD$&i)vtedl&2x$ z9D41Xw*qxSSH0bE|7mIor>&8&TScCY`+$~!`gY79b2urfOnlexu|8esS5lg*7<2N< zt~Rb^l-bvUNh;TF8$++lj}e(D;?l9c+}~}*K!+Qy8{&x8c&~~r5%(M%=Z|(ES)<^z zN*4sT@d=KE#+%KHW{;7lg>V?{L^{^6P}2(I)6p{OJS}oWO2csr=$p|6Cm#-iPEz*J zk9}S1eBS|+>4lhnDcJI>D1ZR{RQK@5-47COY~lbg(06%qAn~kobDH~e3!T4$XLkQg z)8zG#v{&>FA%M^In&UIxfVn-Hh*jh!KZ=*<1*3CiC}(@WUMAW7xJ2B^hVZO*jP)98 zq%Qt=hBgPFlU!w_Ve^W(Y9qq&glP0UW~4w&Z(6k$EPzFLT%EH`wq@{zQl2yY>`W4Q zQU^B*S>}_!>!#2*6}f))_{Cb7hRrX@0&R9%T_oS&0x;4=m0fx}Ka{svJK7oscio+W zQsgYv^5jUIX;`^;0*vx%&^B~L{oUU9OpWS;&5@~sZUTnIW(=WOP9=n+g=0YqIl|=% zAvy;${X z^sz!S5V>}(NR-z3BoPz1s|IPfT)6nN*A?_Kv*)5X|U-a7EM~nfjzA)?A$7_*+7(U_5vB zzJ09L40{G~WH%Usj=Z>Fs8<~I_-?t!V)3v9Hb#*gqO+8_aUvXP&u`V^bSre0L^rA$12JSU>itOGfS?2Gic~H<^|ZT; zPBhIuI?BOWPll^H^=1{H)mrt1c@JsQW!MZ)-(tyaN61$qVeH@q*RWCtZWg5@eEDZ? zM}Bpv$;007EqZ(nOnZLMaT<&mO5EdpK^lSSF*ZMKtfjmf+HKymd64D20?8=Q=dbOt zL!J`*zH4aU61Fclur@3%Juqjl^(AHV5fMH89)vHK*s1 zetMY*yLRUTX5oD)HgD#1^z+%tqchMIz~ugo>xC%F=YFJJBVFo*PK?#U=J{F|z`Jh9 zCzPJbvcaSKUc^y*mS~Kdnze{b>Xa{-@pz~v4Q$SBtZwCEmU#(rl1UR#_bA{~vs2XR zmdmt36|}sd%x75z$A%yUqj^$FL-Cp2W4QLnSbFgvd^45k5c(TJh3JdO;{}&T`_M? zSMRkI(fsy@?7llTmY#4(>Z~?0Q7{gN^I?0cLP~QMk4g~eNY3!;z3=hg=zEgcT`&qu z#iudB1-lXEC6Zi(g5k3u3fdzmkM2w0bmnO!kmf$Zd{Q#rYdglD&$K!S3-8$e?TQvU zIi&Jwwp^6q;zDb(!ktB_EG0Ou#pvguD*@v-Hw>;1-T`;sY;g902a;C0g9KQzw1}c^ zO^El(HebEk+?=)`w4RVH8hdm%FR}ZTQCTgPf{N!*OnvK`$%jy zN$3vYx?F&x-!}9I5V1*@ahwg$$I?>#W=rl>=&}mCPaqakjP)?hl+lK&X$~d5j7_x6 zP&82NVyuAamTCgwV)dFxd6S+)t=NFcWtX;lk=g(%C9y2 z;AD{&x}WZUH&=y0H6GGt=J00aQi74YR#{Y8HVf;_wt&)e>nVB#@3!D?9$B zXKb+RP0?I^)+Rv&a$7I=jCGji6gvk+>xd#8k@OCWSS7m{gDi?kffIlv5kDH_I{Ud; za^7KA#t9;rc(|R&49N3m*C?{+%fHJ;^$k zq33Jp>fFGIBgBK<2B9QQ!VY>dI(n%nCy80=+TxfoNu_%uK@%_6+9&P`v2jlNmf_Nr z_G}czNIjUqR$ojU4tapHm%}3+BIfcS<7b9}Kt8n;RjZx22e*S~=hpLE|D-K+Z8zPk zLIVu<$BE7xe1KE$p!luRF7~;i%3apkP2Gmdq>l5tK!8|nn3S-)O-L9xJHZYd*qp)` zyCelRvKaei1tN>2qW>)o=|pHtDHuz}aX0?=_1GBZNq$5dT-|Lo#t=pfj{S#*U%c-% zGZgPb_d9Wif6mG+m}-{<6B|t(`aQibRC?Ws^>WWV*Hcv@#o0_78zObgEa7p6E_r3JDq=b4THqC#Q+5Uu1kRJ?8KGJE471dx4kX-ZcZ0p~ zx+->aw+sPS$*JCa#W;8+BL5r?u+`Bk0mSv5yi`QHy|&J_`#_AdO>zH++Vb(=mH#-bZkE3MDGl4@n@>h*#4K8J zPt`5PN;rly&hZUJ{f>GkCd~IxlOs4`c)ZU1+%bap1Cyac)x5qU5?!VV;RJyRLj$fd zX%qIJl6sGe<5;4pvSI^_8m!4j=D|Faa@G0#AFRD6UA}!_Is2yVYFwM|*5|w4Q)O?{ z6mFm(DF;DYkap0E2%hiN8~jetlzb2NBZlm*Xl)LE&!YrNkJ0dBT>06Kk3sevB-Dws z>s3?2hayXBV0BF5fKXIq?)h%5sno{pSKJXg_P9bLS!$0aIy5;}H-bLF(&h3KUz(x< z9G@)VX(&-j``W>c4ScZOheMOY4lnNxbl6ESx016TI#jj zrG>HJF@~(Gl2XcI$^a+Vh0ySqnc7J=h{Y0kGl5B~O`CakUPp$i8^Qvs#jUvO=bx^M!%Ciu#h+2Z1&A6{<+k%ujtmG z+0BpZ?nhIP$vS3NRFF2aPrr)}o-TQY0Z>bub+7tjf7RIjRqj;fb<~!ftpb_6VpPsh zf5o(&_e8xXhg1}2gL(Dmuv%C2@1S>3*l<2PUXg*G z{$rMhvgmI@l8+7SS)}@&W%W6}jcXD{HPnf~j$WK3Cy}Mv_GgM?mSmJu&f$ad-ISzq z*IUa`BNF!C>=8;&v8IR|mWvyw(fFmfT`p|bvq+oK?Mt6w1BFX}u>n1=J`$E9dBbP6c{cOgcM-QR8^C||hJ`X)SLbROV;+7`j0c|5JZ z2QRy8@keh;vyp@7*WT{n*tb9%?|vfd(x*rlQ{ek>5XD`3^sS_!FV@X|iP|g=lCSD2 zZYm^>v`vE(o0zF)^8p|!Ee6xFtAX>HC?3c0BBy-tvI(uX9Hm$Wo#J$3_YBa%u2NxMD=| z_t4rNjHjCtjuf%?Ca*uS3SazQ3&XU!2^TVHQ8srhzT1AOyDEcjy~~lI-RVxh$bKnc zk}1E^IUk9$Upv1iC)$_CXB=Pm?u{|`qV#(eQ9%tdgCF&K=fXXy=ObB@r;yLWRI)$? zghI^C2>Iel*HRT~XG_50I@9U>?rN9$TA1lOTj{3|=>R?qjU&7p@gXhUx+zx7<8upd z?w3#3sxVG4(E1j7wsto9+U9>qOC1v!XaFrP4elR`ot;|F*-D>UT;EPxPuotLTGn32 z?yW&dT#Q;w-@?$&2$z>|9P(+PbFtcDOqFhQ<~g_@_;6__)S;9QcX= zaT;+eUVS5DAr~8cSr-X8T^Cbb7Cn3}PIf0&Cvz)v&@i}8=4KYQtWF&G+Ip5c`m7-O zt(h7h_m7C3DF;416)hzb4J|$=G`o$S0jmt3z~4$BjsxGw&d!RJn%dFPk;;*t%F@P= znwEuyg_?$rnvRYVBtdEGY+OT|4+7Mj17(KZ2#9I*!+?C zGY}|Ie`&CaYulLW>v782*z2=X|KFPbCm!McZ}@@!-!KO5{~6@}RhIuxy8i!~uD=!m z&=ScBS|R>fV>$n`MuV1r4tz(@3j9Cc3F!XW2~=@uRB-_`OzOC}^s2aYbc`T^mI>6v zz<>*&rw4I#463+{w178?SrwOonfXohjRLUXGSbt6IEFU~x;I${kR}~~4n#4&nWdw7 zqv$}ge^DSUW&i+}k>PC=CICo_@lBTbZ9LjH7noTCw`HOaK^}Kx%IT(bCbr*j1@F&-F zxJ-X)zyNp~nVue$m_G@B%QHR8n+`MJt$=_x_drPok&MiL*Mj*i6QG`ddYRq=Wqzvx z^IIn9Y5tHbZz=wh3Ff!N)6>wuy+A@Nv~TKkZ!UuB0O|t4<-fnwan*7Eb)iB354=DZ z8Un^vUj7<4F% z$QKw~1s`ZIVvNtcd_Et*z&>|r!`j99zB`0~fCblwfcWnF)e{WtoyYp8-~V&4GyLPt zTNsQW=0Crnu>OhkPwQKjK>2t}+*^wNdzgRte`$kK{2%U(`g_{EO_;Z-^3NoBn;w5` zf+Xl@-loGp6X9(Nyn+88*#FT0A^i>F|6uzcQ2%QzP@zB^2;G061cLQne?hGv1iwM| z4-bOnn-pluy-|N76VwAL9|(YdgYXS~Z?OBrGl1d-0qq}z{RORm6&3)p_vZ@o51{^s zn!hFXpNq?Xt}Af?OrTbo{{;pZXz6Ge{ssgsXysv|Wuf~YQE>!1%nXTtv3Kp@fW=0P z?tQcvf|dat8YD~q*ORX!TU(I*Fi_rvz67{Jk-9zn9r8$E&_xu%haa$UgQ;SIjNU0` zH#Opu;X>|_1^oPQFzAv|6!`)y{m8IJ?S`=Y?I!z0oMXn`?sf?P7_)<;N7Ug%f|CA4 zVQ93rI)tdfAwJk8nQfzSn!4P4J}W%;b;XSwnI`5$jOGnCE4!)b zSq7wxMHPI{^1S6h|CrNp; z-BWdnL;TI6VC?00+S7+gsGd!@EB77VBUhlulZ;&TU1#N&ZA0mB@-)W7ydt13-1_q8 zKs86PG!2<%?Jj!9uS?&=kd9Ln++>x9bTcJ0UOlcHm!;UvdE7K)7%I%Ee>?H(PZ^F* zZWys|7?;!~tT1O5@Aj3c2CmR2lQ1M)RWSLwqZ|oA;b0`cgs}{Yu|{AUUj_r)UPN|3 zc_i991jP;Gkw65#u=b0OCaa+v=i(T+dyb3jsvby{&6!dV{6Zwn;=v=&9fu5!#^{?_ zZzfk2fS|*`rnBpXU9Mr#4~A?nf4=~G5#6;1p!hYQ zn&>9(5;)I0)3U><@tATr5B^he@vL7|tXickjH-tTc5 zPbjtiMUT_uxli7agwfx9pWPBf_sH(ie$$O$d4p_%G=yWig6OfpcEvibBSy}Yr2y`R zv;ATQCH@~szM_*b1bSCjA>Jg^Yi#=(%#r^%%3hc<_L_EM4l#*nJQO;CW$ zfbhU!G1-|ZjRX~jg3il$yf&Sjm1*uV= zG(~mGxKr?ygzP69Uc>?{hNwl}7!r*~|L9*})dWP`vc4`P(vQik(g+N3(V1y}4w*>D zy1C5_gXTy*Mq$)Gs^_Z=99^$ps5$N@83I z9hNc+eq09~3hNVx1d-f3EXnK)#66WgzCB`wAOT)c<1coV{t}2T zU}00?6Lw@?@e@vaUy|RoM140AH2yB`J&M4ZB9duqM0dqx*W%!7fxw!O$77jiJiayw zvna?Qxko7n(Gq9Cy~_(X^`Q~o1!KhbCEVbLW&Xk~&RtbbleVLtX(>7r*71<9_`SF;2IaedW5RYlm}X zz4urhe-cody**BB1a8N1#o-c-{gaa)j)!SnWSWce3hjZwR$PjgTBSlvZ>Pqg~I zint`NW}aa+$5rrn+hlsCCjrit{GNqN7+HpAzR2F;6@^{OIFnJ#4Xk$tiuHC;)fMdJ5+POR$gi&He;q1$Q1%4Y3^H@np&TmiJ|dlp0(^Yp0)foW6LQn zUk~mw9h{!8lVSi%*VT~Ag%}&OIw5meX(gZ%>uw<21za=Ir<%q+p`X2PcqAt{_u7oOu0&nn9*|qg%(Kh(K?msh0`uT9 z)+XN{+dqWE^1OnMG-Cbu>;-G;nNQC%HVJP8gXL#pC*~^d@_>A@pAIegD(CbdyuMHD zm!FOV^pJ6SfC4eT`RQMQ9z6ezv0mTr^UKFU1$wACJrH+Jalr#$g3hiaee*pj*q?RR z_i;W;zA8CA^mR@}KuL0aXMavSyV3IR*Dwk_%)m^6ZKi#DMI8dNR(gd_WAy4#^(|48(x!jE4eWw9@k1 z9EE|cnobWM>-&#>`KPG=W)Oj`l1>ktpdR1+QxK!*^q{f6?+Ow_2ELS@U2$|y-9k#P z5wN>QoL#MSPC0&-T%%-nuRFVP^v!Q0V1LG1-#-Nj5V5-_oL#ARPOZTMTSc87sMhzJ zKo${zt+GxJ66^bHAd5)AR$iwESP%p1`3iigJ-e#&%WtD(e>Pv=xBM*W3DQ#qSpWr{ zcXoB$IaLQ5jEdd8>0ivV`1<~mU%n+M2z93i2aq15q$kKK21xHKuvOgYfe|F&n{SB- ze0f0L+7FtX%FWlL1-4$GIzP02zqksUobm*hM16HPN5evb=T0s15Ah@?E?+-*aFwEd zF2N7VA(f_TE&8>eRllM21O7jYwk)EV=@IClo35E&7b0g%q6RVJ?v}WQH#sS9>NEL| zZ##w%Ve~7PQWn^?EBWTwEqfpMNy$N5AN6SoVFKyXM$@2c(JN*!QDXydYc3U^=S!u1y|74Tn_v#sNt??3qgu!iO~`A@7+c`Y-VEKwJ6fR=?ayD*&$j3|Nts3R$2iYS@c2H^g+ z#Z69Eo1uz8_*B5JQB*LhslRe~{1e#>c&iFY!^hb8<7BpfLd*Nk-m%#4T7&|lIM-Ge z-KIhLCkcOxIyv$D%kVrq<$w_b(?$x>I!GGy>CH=L@)q58g6EUG4U|<%{=ZV7)94p7 zFrDaH^!X_%`GLzC{_HbPv`})SfSVei_$|M`X;=Q`M4q^c9>Hk|)tRBmR!iJgo43HS zYK>VVNh$L*qw&A$wRt8GwSYMtXc=E^QNO5CM(C+6Zj&?_SoWdTkupGlfo#`}A#X8@ddn3Le*7QnA9I=-cB7i_ys zQ4}P8PEU?{XOg*vKvVw+_)o>eJ86i)!TlIER3A_ND%*eg(aZ2w5Px6oe|bG+ZHEc| zDM0OagaUvsz`uy#Ag(w8JBn{ImSMwCmFnzVaezqci22_TlIg1>4(VA8v^*vTsA0*2 z0&P)w3)GcdFb3RuTU!ik?O*P%o00!80Hq1d;S~lkQg^VZyfWVRuP!^LZf~ z!ClklCjTmB&WK3f_;`7L$Xb?Y*UU8+7tt$SVtW$2;E3Vh1EB8jsdk0_lxldv@n5JGe+gzVS(u!?*{JKcsBctnk&)|4 zBaGhZbvak(5C{I3zv8mVGByL8o1+j_uX#Kd`8WDYgIM)OVjf^wwL$oQ63 zFW$L-6=7trkP``Qp?2kMQi5g=+bsEl=MNzSVZ=8)-2B0Vx1i#`HSXrhG7CrypL#5% z=dJ8bTB0veeF>u&@YcE3wlP<~f8H4EqIK?f6nF3cJn#2izw;J3gvRPepyE`4>alt) z(namz8Ro6IXz*Gwab*C5volivP4IdB=g2LKZsm4o=D47j=oT)pH-nu(Iw9}o^#OX#{)2p^K}5rCm;f8by# zEM?rbawODP~KXZ;vu1AF;kuiXxaxV9Kv%uOs=?R0Ih+>Toe zp*@1SPgbNArAS|q#kZ3uPoh_gOQKm#PCSRYJvc#dX6iH_$H}a8#Cs*Dzhg%IOpJkNL~S5G4>n#DxlTL&MN{H^`H+@ zwANW6EWF7T%Se+q&cN#{)pECGgU{Oe5+05E)$+Mm z7n_vX_$C^{FSNm_@~H`W<&{#W8nck&;F46)w(a?5EQKWs%l&6yP5Fh4Rz%9T^T`oM z>w*9i>Y771HXdq8*il8)c|K#(8{CB8RH?FX>ff(2E~2sbAfVA|FT(mZX%|o<)#WV2 zd0XVyRt>FG)x$3=AtTxjFUJn%kmhE-t;|{qY0el9+z0vJ*dDfa^J(&UbN&!paN>jC zoXJ`Suoz3kZP>;sWA)RxF+l37swKvIcQ~?M2RK^CCG=+gR;8)Ws6EQCruDeUBSd+K z#c#=dP!qkgYSHg#h`&rhZJ>!rM;_a;N^e-X_spCPjBm&_=0rL7WRNT{AHz8q#9=RN zk5bi;W2(LHI*2n_a!s`?Qq`@2`DT@V&?|IpuYCZ6CZD1BJG~=qcQ8$D`jaG}d(SjU zyOj`0HQFoi9#KfV$ zOZH2~wj>Rm-(?p5vYbPAJq^xUY_C^L5 zzCbnRnW6qniQS=elT1=%stXN$Bu)l(B$CHZoSeJG60%LUJm6q;hWEKDX)JB!6#5I^ zeI(Mw#Vz^fVs5ENP+QOq(;Z_o_d$yJrD~^4MOWM9?l16#ds{bI^`X4M$a1;C)Pd8E za(P}yd@LSTznn?CmyaWYD#6w8!nslfSft>_85&(oXE1@bl(levdAQ=Bz8oFMbe`wy z#*1q=XpOF8Hz-Ys^?uaLNB$S)3!|-wtX9ekL8;lx8T)N6{JABZ!XnKen~xWt4lh1Q z;rO_L54yYrG+tnGs+utsQE7G=J}fPkB$-c~a9`kB7gP2v+I(5Dd8Pv&ygPO)WR?NH zklUIvvHdbf>5(tWE>I^YAdp+y5xMG}*#=JF_*vitMP`EGR4v`P#y$F;{VFMd^K#q} zTcD@QaKnlI+LW~bdBCfi_Jp4H#H9sJC9GO@dhNZsf3*Ph`I;6c8*X9KJ(6cLR*ad9 zzNDo|uL37L@9{PwdG=xs)pG^X*8)ktEj)YYf>lRvqckbBuf=l`1)&zQDcN(^NqEh^ z9w9kWs5zK~aS3;uGDoU+0EQ8<)vu3k`kd)yqf7-r%-Ibhpoq`#gJHSKnVyJX z0PIc0ezB`Gw{pApI|~@Ak4_(&-}`*{GIj6P8f(iYxsK+Bi!%fxuTrxXJByZ7S4UfN zS(yR&(VB6Pk@f>3y<)L`%BkOJ(8%f=hd`NiWJSM{ftr?@ftv0Y5Mdw_>^^3mEf zlAs@P3kDrYuRLWwdDzb_wO#@{fEGJocb_?QgE{n-loRC|)&px&i5*>+7HKXMnBg0Z zY)m{0hsTtG6zq|?hYEV2XWBn2KEq`QHwQnbvQc64KHhd|?^$x6Qs{UB-FxwC=rP_N zsXNRs91)aQ3KHdU(|j8Uc$G}poF77J(^x!{mJp+5NyY*NN9T*jyo6 z=@&-X6K<6 z)KaeMDH?4m)%&I{O)_O^o89R*`S#d}3vlslD8>MUzSeYs$EhsG<3$1KQy*-EYp}zI zGWctUy#{mUFBY-o4bn~zVcz!BIjx2TSiim)6GRURYNHJZl8tFO zt2ieUJ5#209wTMG{?rbksRB$De$<6kns>>BgKkkZ@*iim6yh4%_lQS*R6aQ}G>$+f z0@6*Cs})RP#2Py@PSMd!P2x>?x9~^DP>9q^WtSewX3jy1U)0*Dyc}1%ZC5`H8Q;fD z(RCR&4F0m5LmyKQnG`XKEH(2R_uyG__Bo25JBp8T5Or)Kn(9=b#Z0U8twl!9CV#wG z7*Cago*!(@!8{7OpJJOokEWo@yPu+unz@^DC15+0)bu-Y^?Z1~L7i_)auU|ff3_Ap zPFg=QomHF}(wy0T)p0ilyO8ZC#?uts9}au6_IxmRdF?BI<|W}0sW51HC14OTt4qE{ zzV<9!I??u=WX8OXc*$vCKH!Zd41f5^wNGMldP}?#cEss9DW@m;Y{Ah^`f~Nr)!^4%khnC}be z)DAH9dtP)O9OfgSEPHD+f z%Noj74rrU`nwXpDTWHrN^A30Ha91suF%%i}i0vrIFXCBdz1#?rXUmU;7M2z&)sZzG zoW{0aBO553EuYtH-HW`8Q|y>VN#1u=x~(8y7Ktr>)r{zNOLrcx0Y?s9Q4NfiRQ4qw z&<0P;aGB}+_WWW?Pa9u(2K>g6UUvrUbFd;?`O?gCFWRJ)xXIufpH;09o`! z6fatCK`$>qqR1UT$V6G5r^=*Qb}$EI>pXq3x1^{hM^}_7-0eYh!>Rwib=TWugNfWj z1jCT9H_}s@3QabEr647}krug0eS@;w7;FnoJ~uKpTIN{XG=@X&>H)@m&Hay%f?W#c*(WygDTi zvn91wRkyalH=zV~x%pF5r5g%i3n>ddi>zg5m8>Q7#2Q|qY30h|5L%UANttP77VB^v ze~{i#TB_~K+HexR;lAMa7ivZXZ>cI#v_yYynd!mD6ZSE9*^& z5+_Dg(8z}dmW{-!sLgbZRDf$9?D{+UC=<8@W;WU;T>5wstC}GzeV`a+l$ualls`V& zUfKAHkYHphkIcTq-m_2yp8NrTJ&AaC@%!$cAcfepcwet9IfuHes~jFRP$>ltOFm^+ zLpCMfFmEyPk)HLFf&WHl$^^wV2Bf*{Z-E?Q#}oa1y%Y0d@O+H@%-iZVEr9uqsQ>^ajt zB9`_@ulyY#qIxHoUA#whiLK1#`9fx>Od1?GuCv6isD}C$-zA&Q&C=$+)af)voD#_GxC{(2Zpo(iMnP~nMwLs09MEY39bfv**IiBmj9nRr$> zsQWt8oBoKqYoa!GcH=ItI%d0yM`1)`#}o#b{G}ugrPMvkIF=hc& z+m4rFv3ypyML3l9#0&^&V8U5)|AU+u(LmWUw9Cu|I{OSf zg!>EDJQ8CJ){m{BSVL#XIvdo}LHc_djegYg?I-(}T9@p`AMR`8b5dsWT4bdSnFa~* zWh;24lA(b`97NKn2jTbh@KyUR-HQI(0?C4P(kv?>_ck~s9oH7fEqqIR>Y&39y9l_4 zgA$21_oiqLQ7T<4iuEL`5*CWgFxZAA4nq(^h&1-|^hg#&fONvjf%*-VvI|9+yCu$0 zCvB)&%020uryaTS^7J`6`?^YIPM!5DNR|h>=!PDklg|thM^S(rQoMi(z}#$cfpfzS zqPZ_4>Uk4s5-a{>)7Nd0;f@+5V5gW{xJEXUaeCmjXdVriL33CG4My}?fqwaF{q)`t zM0tmjzb@KuQdKZ!qI`7f>ipD}9c19irWT zX(5nfRxOlNE6T(InWxNh>*%D=y!E5$utbw=vgtlWj3bKVRw^$HsoF3t*CvkrCcjU= zCwGH;tt%`LHVIBH4VNPRRae9|t$yHf{mEw~(v$>HOxLUvO6x!i%OpX|X|!y_Zo#fg zmkhCPV-GZr5T*mw~9gPDm!kO}U1a*GEYrLqqO5_2*Xn~{ z^Lys{m6eIm(^URAMs&T;!d>FuPK)CBDZEal6(?vg0J-F&*JEIHy;@H5@GeuA3SgzC-SmZd0WqiR~)kf;s#H0zNOTO-@KfV&+_ zm)fSaJkYdJYe?L}%S1oQp2)Uakcn~jMX9tpAb-14+@VUYasuq^vCLFs9BZk3t^C{N z5j>EOx1U!x_Bhsmx0jXz+>SVR5@oo9e@hxW$9eGsBX%p-yO&>IPnJmhz&j`j;FsK* zHTXy>&N?fY4;;^4nSMXqAEjSm?6lJtC2z>L=m#Z#HYD?YrRt>v_GVnstQaoq&5MI6 z6Gj~rDEleDyjKsHOC@0TV8|tCmA(p0_AS7&+CiJ&SWo8M>aig=i>|_N5I1zs4_|&@?h(C$)~DMn*sUl1qW!b@!T0{&EHcpPns8v30Cql|IK^ zg+=O+kz!jcPrgbio=prYxvuN_9R)^)R4eZcziJ?(aS`*QL`K6cUN%EmbD^7L(2Swk z*TIkZko*0Siv!jILP`GASe~ZtGpl?1g56+y8l73Qo0cv1q`oF(=A2W zHwVOKi(=@nUwbqI4d*`xE_<_Fo?XgImkGLK4Eq#SpOUGcP~l77*lEizo{RX3$uAzR zGAadC{>XCWZiO+(``xcaRDR8qng~wsrj#2b7=U|Qx8W=6GOGh6$9rWP5*Qx-<#TG@ z3%~~5ucF+Kwj_Zqe>s$GY)W?&SjsWdXv>iT%!G5sPod2_+1U~3U3%RzOXK3O?^&Yc z*`J`TFdPB`HX8-)#3e*RPI}cTEG*>Y1XNV=*NFhHTIWo}&QmV-CZ3ift`CRm6jA4* zYG5w&jHl;P7@zTM^@L)HIIDS$ybow=>VwteWQI=GX%Pzgnl62~#%k%WFZ*L^W26IQB&Tkp)?Aj|mDc*3 zW2K8}Z1@Ia`%|(ss#*>fOqUK>4A^#{plbR)GV5a9BpMl-3A&0k(<@Z;C8kjoaeVLG zw^`I(WK)k~RHdj;&(cv6m*GUTp9Y~FFp*5( zdlt!V$v6%$ZgN; zooQKFina&W# z9h2Q8DS?yyk!Yo)B^;IAERGvd92vte9g#>TO^S@j&X$qfkC8L3P5n3*;BuLrPhOjP zI_@N;&*OBBeM`x7t4P2sBB*6DI(1xo3Rj$>P2p40)DWXi(nLoqmnO;M;*?awL|O~- z*jSW29T9}woGFZlZ4S>S%G?}!j;EfV$|@{-9!{dltXz5i+aD*4n)U5#Sbyv?^QPt$XmdSsk7BdjoBOlelerPax!zo!C!5`IE{A{>nPWyF~* z^<>qE49(nx)Da~kQ!0M!P4XuF zEJ>D@v@MBG`rVWzO8R+1W=;XEfAPu;<;yuQcZp|U>Y|UoFt5bDg8oDJe{9B<<44Vk z`{d(i+$Th=UdVgdSv+R)RJkf+(qz>XflQU7$c&gIa9N6Mfe`Wi*5@NDXW}0cAnD-D zGz~6aK1nGi_=NoFqh=H!v?oMlOv;Z>OiDsLk5WvW5ud}eI8Q_e|1U3l7w)+6-OT z+XP;Soz72>E#`}3{ql(7EUrF_OPi9KoG~GOO6sVM6EiY|xsy{fN=TGCD?U+(+< z)K+$wk!|s0V!qX3Mx-Iber*1DWjxKXP)iCmmR8LjWaaYZ+(_|WN#ln`NCeG4ecyis*@B(lVmBk+Pp%xbSjzM&bO# zDRqP2Da#m}o}Qi*H!*$**SP0f<6_g>ad!BDlK&a+M86=M?4R&VcJwU; zmm7BrsQ{XdM`AuOn7|EilMYLB6l4GN9L3nDKT$Lc&B6QUH_W*`v06_<4WHMZXvEO_%)b;cNIBzJ{;i>o2&j z{g+&y4qwC9|9h7rUNKcMfA|`{hOgmk_!_>3ui8oq|F;cNIBzJ{;iYxw&A^&*7K z=1-8|k7KN6rHp+yG?ld|&65}|fdqeX#7u5Tv^|Nz6q6)cN#YgX zlIRHXQiw-IlI6dX=t%OiqFkb*xkZW}(qB-K%dnP4d7aS;&~eHEMk`tWAfqE_e?%0c zRg50P=t#+iA}!ibq(vKwv}i+-mWT0(HWX>mh9WK6P^3j0inM4$krr)8>8LRM)l9c6 zMr*?Q>0f?oB4#r>j_MY%kkKPRCqz^;Ix&oYB(sA^Cx!KoW^+Z|#9a z<99GRi_seyJ&n=yZ=X3;nEtA;wKQS>njj{PD_8!-V^;w0^? z=Vi3aplR8Fek0?^!N^?Ff=eJ3=xfG&E3vSa4z&*4c9c!vti*UL>lH{j>a~ok4Sfxe zBw&<|Gyqn%MiY4Gn3=3WUmMZ?Rr)>8Ir~rQK{anCHtdP6J)2aqU05WE0+|7+dE`Y< z^xLUM(umPEj8hG*WJ;KPQTmYVCFC{CsQeo3D??NX(|;{wn4pC~7DK9@twKkq0k2^m zmDYkDr(_E=vmTY2jh-sTZ)N=gDP#Mf)-<6{fTw4XeE57h#%*X*-KZQJ^B1+gLGp#3 zNwhMr&~`hsL@P$ExTseJvWm^MN`9G7mSVlR(p+=cNISDq6IN+t5{=B3YuQ?jD8GJP zu}yg!v0oe8MHAy~L)pZ}+nJ}FOiL3RZD;lnB{WL1#NE?)6~40bHfBvH^C0w@N%2Ez0KTUHMW^@gt;v(LWQx}V6_MpI*ZP1*EQu-8e4T1p&dN4Nbb%2J;%BP5;gEf}OLUmrwzV{vXIJUW7BC7ka`IjjG8Y*e z&25%8y>$xX2Rq|l^4g-xkoZbkl$aaV8cof@V!htjs1v3MuUQ*REjlN(FdHpxrfi|g z*l2At3uO)FCY{MDyf7<&`tmlL(AwY>Y!;nhHDDL|HjFe_gm#^|)o8WqnuJwOjOc{< zOUveB)XW;~=C&qVqg61PgtZ1^qakcAYNM&K#nyzW);6KZXlZZ30u81n%rb(Z5nNb4 zM-YOGx0za;LZ)$wple-4XAQ|R1-ZXgCC1)F_iWZ#tY+*EW(!*$(?haeVj5%`v5HmK zN}XXgV%4U$wWgM~hVVt9bc3j>&MaWRZCDDW&Dw6W3QamYH7aHzMPE_#V)I$NwGZUHmT4KjwFX{t5p8^zZp6pg)sA16hI$ z&uFp{vQp5m$X*3qCR+!(OV&krnOF7*^e3`spudn?@Z4gRTXLHDcX z5?(b=wTsA9KUNLkY3e^zk3fGC3CWSmBi9mHq(hCTRCSa(n#j~K>P*m6)cK$b)ISA% zKz#)CTk8J>`jq-K=y%k=27OL_p781m>bs!-U40+@AFCgN{)74x(2v!RL4T_L6!a7I zXP}>|;aLsQoWhga+nO_=|3&kA&<{0#AiU;LbS&YbQPwcA#JE~N{R;p?hcBHCN)q!qMHKNq3+ELn7PLwW{2cumoA4tqtJGPh8DBsb%gB_j0 zzUVGSqD+cT!d^y2j{==c_a*HoitONy6Gel$VHFV?o#qxYr`fDqL&^=hRc2Dx(qJ{= zWJeKhX+?=Z5^-t*uz{SYB?|91%r=Cb6#9-69oFXXo)8mib2wFyR93k_AW0Gjk2i)` ziI!nBj>NCgnN7sNN)s!staQ=a4)L;b6Dzl|atA99vho5eZ?>*!T|*wTa*&psl9e&6 zOk!m!A)zXr77s&??B%u>|TR?5vnaoAR}Oxk=W5Fl1xUEF=Q+m zM^e~dR|?-S@9X-IUYMnZ>R8DCrkXw#*CKzlAftImH`zkAlU-yVIYj!%adMiRBkz-| zDJM%+9Tp6D0zOt8Wq4Z)6G1o_Vg4({mo~3{Uvkyo2}iJK43DKfoWub&(&C$z=&B zi)3%ecFNAkuF8}60ePOhR9+^(peR->R9F@36jv12mFda~Wb3`kbIO~z?ndN9v_~9N zjZ;lm6{%LMwy4giuBskJ3X!hJzNoCI(^2=-Ds_T7Sv^5rtKO*YQ=e5o(oEM>YU(uI zn!TELHBY1E(S^~~(d(l7q94X+V&=q@#FWRh#B7b(h1gCHyiQ&Wd_-mevw@;OANTvf z>)dC+=YiLG4u}kV#771C_}Bpb*}_DWkwnJkrI1;JPcW|*^Ge9_fPvJYt_AurCL^&J zi3id#5`j5=m{WqaN-)QOIr-py9lX@rbTk&T;(>JZD8Rb`ytUwc9lWoD_b|@03|huw zb{u%(QKtlYNGe9t!8sjcC4ml73M>H10!K*&>ZPcwP*Ph?1Z`lY}}2(o%tR z&?V4f0Z;}VD$rhvx*DiOpEMJ*;;?Q!>J;dn3Z!GS1bQq0%Ajop>ZPcwfm+Ot6?e(j zOp(?s!ORkAWf#qoPGMak= zZuGd}rJrLT)TRdP`*pI6a)4Iw(*pT?Ay5W`9wMW?Xz9_?BTph8xa`0oZd%|FuK*$gX?)b+ulQIX zDPZAYS3W&pAtS-H5L~0UoIpO88>r%52#n?OL4P)Q1gj9Ndjt{|^3gyXv`jz*jsTK@ zF~HbB9iIXS7|TF=3UhDul&z zsT9w<5D~i|=_Baz5%jP?4-1zEya40_%uj(@$f|^_iEJ0qKpb?82a@2WWatI|!B&0P z^HJE#f_)$5C!w7QOhG#fdXJN0@+mZ+TJq4K6dIKN)t*WUyzoc8#lvPNV6zh>3bH#P zyA!fIA-fZDI$_z5z~2e3PVjevvlDZIk(WgEm2_M9pBqK6@ih_;nf;L251IY&(Q3%; zhm3y6ID)6gaO3MC2(Hi zCjgVto`QO6V1PtI_5h!VeJ7(H6ZqedI{>-=%1=aJCXj_FiTX-R24j)NA=O|4^J^dD zycD+jC2)qXd`VjQ5{=El+sH(>$(w;Laxie7^a31CQ4gM;`U7SBT%7y`u>Gq*8QP10 z@<11|$FKNh7^?}~=2rxE^7Wt%sMnxw0dFf{3iOgVel|Gf1bX>mjLc`!9zxnfNV^Sb zM)s1uR~jh@m6RP0|{MW5_+YXHDR-UgjqdoRx8HZfDX(Yhm$oL zF+DnbcaSz7(y%j<4{3V76x<8Y|0?R`XxD(Q#VU26>jO>vD$qL6deqH;0drSFqgK#1 z)ONsu)t$(M3MO?C8O<+4U5~nf(1@Q4YJT80QA_rutDVO_u3;bl2L11|RaZbtJ#0wr z*or)$f}ZQK>)V*SADncz)IPmI`@l9qS&IT6z>@pHaT{xoW`3y$X9H>j9H2` zozNpDq{n==MvQ>l zSpO2Ut{4G5%zmptH!*AXAOdKN>v<#kR|9L9J$n#uJ-mfQLr+*V^peRqUA;J6y~wG( z$f>-Dw$%!_n|f7ql47uSC4n4gMC|MDbeC4Ztd( z5&TW4b>PvXZUzjXjVwOPpj{L+%jercn*j^p0Gv1vkp*+zog_qSWlb0j#hZ9`AyjUaWK&mOdO7 z{d)MX6)TRF_WUCfg&CDB%ETDyV!D;1e=)RJ9{6D>@@Y)=N)gq;ycpcY;y@`oCzMl* zJ{^m89Z7&?ZX+^&4efU#G7dv3<)KlgWm3<>j`!KQZUYecycK;;oQqf~&)t@0Ji?53 zSccLgW(_z&YtYxi&df37z1v~4Z{y8F%0rml!`9P51HBa8R6dV9F`C9Xo~`LVY6#`M z&3e}$`e`hiKnF8hgmiL64k~30?h+Wmnz!NII<&L^9n~Yl7@%Ei;5X3hA-FyO*EKx- zzX@B^Ap5Rhdpa-WieL_>C+OcWgPx)zENAfGe#p*~1}nV7PMcQB)Oy^lsHWmPYC$^h z*OVJO{8!|%;C@8z-%6ZpKjO~Wu7jtzf$jQs*secdD@POh#2HWXv}7YK;~vfYhiK$i zOF5vGo&9{~f!NUbPeCgcpgC#Cr(IGMP|xfSdB!ApM=3>}m=R5|Wk=vwOs+1FqIo=ju^lS4=%E{>!V`uXYyCl4S%Erj*?LZH(2iOlB0(ya?zzOiDqdpCsm2gq2FH5)z z+>}7+yO@)OdO&JlC7ixitk>kBek9>3A#32eHA?gsqSgQj;v7bc;5rTjX?|4mUBd&z zEyFWIf-Z|8%NWB@s4Ev?6c}oBc?^Zd$rQR4T^5C*TtcDIWw>tiHV+scH$O5wYkq2Y zY#@-^XS6aXjl4l)R589nqt}qve3?NBK27-g%@-N+K<@>TB?S3XK?AzV=F1dAdg_RT zpx#VRLlI~ON&^dwGa1Sy6w*BbMG_K>B@BA-QUu#Apj$%ig(3Nr4r@0(`r|MxfG&Dq zUDH)VH{bwm1~!AH*wu8CVK4SZvCg=JA=vJNjJ`1YOZyJlJ#*B$j3q727MWn8T5Tnb~~?4(Kv#!fcFH}V^&GgKmeDy4X0Xu8W#DIpkR z3ygCZg8a`zi@4K<#bDu|K#*^qbS8r_YR29vLNN?lAJ(SvLXm*@O3)P!#qgKgp;)cN zUdw@Pn6m>2#wNu9T{1%`UP12-YafO`C_?}!$ul)*Q=9}%aSZe^ zrehXEA7UBMwHS9&g!VR+pTu^MzmNj)TCOW%VB?e*bIZf#5AlonC8+nGY#Ucm=qim> z6gY$340$xSv2&HmkS^hzaW{h$>&7>9sT5%`EHKc#ND(~86v6ZM{J9IFNW$~|H4=u- zelRzSIu4y*F((A;>)7XYT>{%Lt-lgqy3Gud4UJoZIS%`$IAb*7d@eD(H)QALn}&M^ z2hIXTFuwEP(>&=+hu<5dbKico`69*8c>7I;P~HHY7v2upKFEKU;rTrCeBKD2`+2ZG z(2?GeMPXRbk;f1`m(SfRLi@&f2zysAYW|{ofYUv@%-75Y}J7{?I;|I z>5d|_i-y{vGtiCu0L41o2Pn>T%oCwgGMt0&C?vadEYPJgD4Q=+1Y@&9gSKWU#zXlw z_)PHpy;Isho|@F`vv9&b1y`}pzatd|iUJa&n5lS)#IjGRM<~mcuaPmzD&;aFu+OI_ zu+NDnu}^t(==TTt|KJ}$N}6l};bj@JJff84%L+-H%qM$95*3+>Y_dsFq_{+Wp!kjA zH{2w}2g;YY$;vs(m$~mNYn9F150yrxk^8Z7jk1N?tu!kw+#YqLI+EL~eoNiQ{daZ0 z`WM_!HJrx8y-7Ik0be-u#HZ~BHnUH(h;|#W19Uba%_h*h*cj371@Kg*Jq+{#$AFW- z8Q>iFr=xxkxFX@YRNs z%k@|5c7wW7f3E($Iy{BfU#LG-|8Cu8P`&kM>rd2qK^>?+S>IP@Cvr%>U;p8XW03H$ z{?5uM^xUsM2>J*{`d3!h%m%ls-dn%14*sogueaBG>gN2XMX7>)r-QI>b8yOa$_*rv zeXk*&eJf!E;wqW*`m<}{3|xC z@JO%&TUTty)q{E~$~{02Yf+k(+og++qi1<}(_LHx%PZ+ObzuL8gz%5}Pw?LRDSRPk zzECn>L@-}y;EP!#TJciIBXRJ^cgZN_Yw*ih=9h8G8f6VhgVnMuE5HA+QOA}($g4nPiW|~Sw zST0EYl<)lzICm=Hm#q_lIOlca(ElOo2}Awg1YIVO^JnlC0NAmvn6;T+3^yd*s4mD; zjmXPYXTLO8U;Q?qc)Do4k0Ml@`UidXN33jp*>T(4y`{39cMDIc2o8@ zf{kMx)ciGbh12YHJDdBH+xOycIP&)75zKVU+3KAbuHC9 z_jDaJNvwEm^V3(d3Tz(I!}6cgR>j_?ani7Znt+I5=q7VCP=7hPk#H_Vq^g7=R3s%x_MzWJsr+xyUb*EQYyMCuuE&BQ8? zTyxNK5#x+W?g^+*IwaR~P)jKC$dVdEratUe|qAK18|B z^@K?qD!W;Ez%}SAu*`Gq^i43=F>MdK<-Xb2H6++3xF7jWTNb!>V~^!*r{a#zxX1ZQ z%>(WUzA{UnI||k)#2#JXq&!)!eXxK?SGo>@7JF)3N4#FC)Jk+eO1$-ck*SfUaUF;ht#;vq3J?6SB$C!pE-EsBkcPIIZ zEw|jIz6#4acbWHw<(|6&@q?K3Ra5V`_$_*OHCB8;BhB)d(a+p<-gm{Qv+{IbRu%Oi zJvFUoXneNntufHtU_Rk)LS%-{j<1eJ>C(-j1+0nGkJd4C7goW&n(oNmPIu(C5ACix z9lN_lQ z!%CaHwbm;4R$r90mRi-iip4++i%%96Rs$?~-12~0(rThswOSeNa&PywTfOccpWV9A zy~pRVZeezKgWAEmlUfP(uY*>*DQ(@y=!4Ar4)=bnlEr8@KCNGhY-k zx|`B8+q7P>9&sN+zuw*Jby@q}N4jn2&WCmm{pP%Lj(-`af?u+#-gZVazoHT>^w$fZ-8Y5*h z(7x@~4_#Y)J=PoSd@)~G?@*d%Hb_Gb@$IqRXZC+c?QebJzUm3Z!K z@-RAT$o@1RwqBu`$Jc9%bKms#+mhUOkx7Ok`KWE2d%$;Mt%{DWjiIA!6B#{*(E_6< zhtFE)_a&L@+)t5dFM0^H?eQD~ecE#pDr@Qv8 z-znuH@kDnspE5hIof))q>j7rHjceyPyVvigId=U%=|r=LrMp8v+a1Yw7)2wymCBzG6x9?Vi2jlUC3kpd5%oyd)<4)yOnLf=Zt@W?U3i3zueaAzUr^kRzTbRwxgc+e1|CQud$u* zT=A}g z3c3ordmXd8in@FBPx@|1C{CMao+P?bnNL`*ZmYR z9LlKTy~(kk#gcfR67R??M>!7BI0yg1P|Szrlkk{#^bTc!@XYKuO0%)!1k1)OOFK?e zTFSI$mT9xYPJLLGcAV|%-as4|yEbo7hUY!U<*scTG>)rXJ2oWP>|MKj1=M#NlBw@D zq~ZyLo{oL4cQ>Tdle_+jbl)jtr=uHMeHeb4Y*#(c;Mtp!k8&=VX7kopfgVH`|q+({T#G&z`B^U%RGrrhl6~ zp>vLZhdsHo#Ba8~-?by*LNQDU$?h(9`WBo+3&wa&zJw6-Q0QH|3E4oou~Yd zC3;=wyZ&U+YuML?|3lu_$3=Bri|+F=Uwnn&NC-tj2^opy8sHKfM{2kR&di(<3NwQx zh9I@ZT5AYV0^-GCB4DjGKFc+hTH`gAYb~*s=cQijwboK=xjvuQ8e*;W`lIM2Jj?TE zt+77CgSXZ?=L}~?jW+G;KbQSmYp=8R-fOSD_u6ZJFf#}0O;|gyZmgkg?S)ppVdL7t zMVlJ7tQ}sopkdqEQJ{CMy#c$&RJ2~gaXQ-EuzT(8MfHHk5eGyZg+NrRRoO*1>>#~OHf#t2W4YvYyt@XG@ zywN~wL{DQ;0Co|uZt}r_M!9Kq>p|R^w|3y!q4fySeT`+f7iwHUyY%L!w%VPIRcqo} z`*B~?O1t;gfyTu^UqJeet&Pio9)z-St;1x!qm8w&?%dE@a(!)JbFjX#KCm?yd|eD| z2dmz#?ipZ?G_Jupf@c%(8*mC}9as6mz%GRkt19r@M5NoI=%g^H-y1ZpNB`5fiTn@j z4M69PHMwsbAi5jrws_njv?Z!*TxZ}wTVmtRz@Zn`6F&v{ZRtd35HQe3 z_1(%^Ke?-^*obr+ovqp$8b<>+gFT@C9T+1x1HN(zPg||yjW;IuFnB6#YsT|eZP}{) z76xN_yTu6eNTJ7DV%pY$XTv>1FYXyui<3K8^pI^EaDKIICVDH<6*XiD+gC@mB)k#T znB0;C{lA0u7_I;%Wm*p%`JP^`Cs4Mvj2_3 z)k7`4?K2w20u8Ne8u>tTYjE{Q%i;Fy)z?~%wdb$&ww!1$SbekQRQtS&f|j$bUFr_M zvgLfc3wyr36!m$be)XM}OYMH;gsYxyl~Zl_iM2>Or8cpaE8%BVbp@yWLzA)PYWu>b zn3n5rTx&{bxz%2y_|;XXTE^g%L2?=rg8aI%rlg>`eJRb^VPz&_z3nU1(=_ajfkT#z znzXM}{cT8-_SJe1Nhjq&JR`RU6rYA3qrFWzUn_nI=W<&Et{v?g6|8WSTAEVVm|Lw) z8Ns;rEsBNUssWtrptXI6dOJZk22J@*E8BM~w-ZeT!DO&8M4;(#m}WlxpAKR2s~BWoeT?n7iUy)54&=HMyxKIJdnQ ze@%eC{l#?O{^IG|U!r-Qxsn;^8(%5(jjvDBH@-5=4d!O{jJd`9b(T-x=6asK%~clt zbaXcJNB^(r-?1wC2HGO}z8St-JeOs#&oah}*h?&#EoN`9JoYsRezt{ugH^Cy>>c)b zwg^1fQ8)c2`7MoyeIi8!rzRGRnHnARV8}~l@ zXYN0^E9?*Aa`6@Rk=P}EmraOA#Gi74cuIVavxp<&@3=?BTLyufYRE7=#XV`D%O;EIG43tXG*c?qW%{(Kh1+9kv8?9}makbl z_*ly~E!+9WEN@%(@t?B%z;crRjO9Jc1>R}-56dn7bC!>yto)bpKPh}`bX@c!d|Pxv z^ke+`=u6Qb@S9>@jd`2j7IQO}<9{BT9GlF)7n>5B&JV;s9s4x@o7k+_EdCK88Y%EdSVBtSvrC{Ihv(M4nyvnGL%1uw2o?>3pbklTJVfu{eGi-tBZ%i}U=S|tB zZ1#dF-;~c5nj9tvd(l*2DqvM6r^&@$GQDW3Vv9`GrfQfk9NPgi341vm-(D}p0a#T? z21sKCQoNKXrAX;grZiK^lN?f^BuVonuT&{j1AmFMT&j~AAhlUqCvAXyn}OacZI^aQ zd!&8R0qKx*R5~u5l+H-!q>Iv!G$LJ-Zc2BY%xQGSI1`*n&QxcHbB5F9oCmxa(spOI zGv8T&-v=|lW`3Q%^%oV^TTKx1*uO(~mR*LBPw#x2#YQ05O=YGsHrrHTs$dS&64Mek zhjB2A=+{cv3}#}iOa>@poX-aF0)Q&U6|MwWA>@`7`QplCpOpaVGGB7p0$&=@2vt5? z*Y(xTdT8mI{>bZ4b;TH=6WXc=eR(~g zZrDzYcfuH8|8%JRt<|wfjd6_h&)A;})H0|mmg!PsO*c)B*07TXvrSYMRcZR}?jKj(f z`!<#5`7V?@e1l=*`heJ*{c!1F`6B!KAz~`8JxBI)WM6z-JP`2=?Y?hZq>FWOy!lE$ zJt+QIz4Yz4m%V9oZPeFMcEi_6v=(cAS(}5meLF*GL*AwS5$_8BHSbFQO?)Ol59Ph{z$a>J z(7nboa%@&ZU8#FVlGY{NB(UR@c(< z1OCeLL;h;LPb)v_UqWp=?q7c2bs25%q`wZ^i)}1F<8KJbJm+uL_gDEv|GM%a|Az7r z|K{>*{;lOV{oBj$_;-1ke~;Jb-{+0-AMhsl4|$XPN5j?*ZSLt~Z7qrP!}p6L?W-&z z*7)f6JMUpn_gjl1*CZ(GEl}sOnVcIAJoo|^R*c7RQDQM ztj!xaVje}Vf7*Top1rQ{IJCD3-rbJ7*4u~GS4|JCm67Y}{q`S`*|<)4k5%M{<~{OHR21O+)0g+2s+bqjFH$zh^`5P8QQ7ml`K9wunlB3Nol)mY z6{VrRxKiQQ{JZyR#lld(sXBYFSJZ^#u)8GTNAO|t%{}Iv5FOViZ{P$ z{%?#$=g=<*jYf|${KZV$U-y2+Ag~F#M_EMoC|@uhGyaU*N;fE-bc3>+ZcxtB4a#rn z2IaD)CCbXrqkEC_bT9I2x)=Ek-HZH|?nQow_aZ_v-irvCcrPM6jrSr#Hr|T}IdG!w zV%?Ls2aW>fa`+t!9W{=njunoTj@9;IN5IkM*yz~e*yh;bC~)is*z4Hu=ykXphaJc4 z!;s^I|^8Z`?^XS3D!W#|rVj3QBUUl2uQ(H~S__*IEkgTnh10ps>Bj!8T*7cSDPJtF4AM zLwk2ai%&oZK(5t}-K66Z(D5<)E*k^uu>mg=0uN_t{2kLQ2qK%wo?!--!*bz#{VcOH z3+PnDVwnUXj=3N_!ej{XY(9iXStW=45#07|5Y8yK8n=PM)+CrDy?a)xu^dw>_uYnSruE%57;MNKOa( z0>K5;o%A1{470n6Z{*}b3zmc4>xu`YUC@GNXxEOe z4*)%YH!sB(ava4sr1`}+P!a(47s5E`76t7DAnABR6ED?aKT%&nZ3x-pQlT`2acd zM!>rvDMf0a*5(qW0dSPkkh9Nuf^@qJ?!|YWaGr9W4bxu-n1(t#&pR(UuQ;!28tUO* zeB?Q=J8$W=548gL&g(eJ3ZNd?H=6#=8SXqOulRy9TgoHIcNRbo4>;#JUD8ZvsnhRV z=&UIobS`zSaIPfF20L}Gb_PHaNN~0}H_jfFDxF)f4?)g0=ML;i=Wgd-=YHo5s1?T0 z+3P$kZ;`h-kI6ga-SS>}zuYSymXFCN9f&CL-e8KII z^4x`P$vr=((Cw8R?n-wxgeA@l_i_kz&Qf=tyP>$>-3&D@2K$;nyUV@Ky}`ZNz16)P z_`BSDa;n|?+y~r;+(#iCcb{~hk(Rj6xi7kh+#}8mkaW#`bM`^^9Vrpql2MM46XY0a zxtt`Y${BKo`Lr>PmK{xooa1SF*F$m8DuW`059SV0ga9Gs;kS@?dowI zjI>nn8kGpj_&6^ixQ@8`&~{w?uG1K6H2MP9fa`*5&^7EDb=^SyUAJB1)DCT2!9Ti1 zcNES_cf9jTabNar1R71SJ9nZx#hvcXbOq_2xLKO%o>`NI-qvIDWO;HucDYU7=$Y#& z0?kk7#(9DaJZn5b&wAho zJ)1loo=)KI^mKW;Jw2X-VBbleBc47_zvr}PAjjdk;2HD`dq$r*?74yd4}C7$E@*Sx zGfsU1de4tnye0Hg6!_A*`QrR2S_@zPFSLVN#_H(K9Dnnh<*sKOfHij=gbffjL)Z#o zJA_>j_CVMN;Q)j~5RO7Po_ioch1_Rv*_S>$rUKCU zJb+oD={XL-s!L1OrD^%b6dKb*X=yqd%h>?3BH}oeM#xn`qwTsh4OCr1`La~`S(7rg zI!Py;K9tY)CqQllMC$T!kgU@|r)NlySIlpA~lxp)*%#+sqGpI*CR|$**)42S?>aXDuBg0 zJtNz4FJ14^Klh7Czub?BRhta6MLvSJ450S@{Sevy2kNAsU)r2W3!i(Dc_^+2=mY4# z&-nfY9d9aM(*zG``YG% zY%RiH-P13jF4q8V>iE#Nv+jiVRiqAg$-=Zz6|`r~PPFG60Jl{bhdM-i*m^oEN|#r^ zHldF3_Pf@%S&8acXrReSQR8%gOn{m8yVfQ>%*s=MY)Iodbp5NYrLzhFr0{mnny=_P z%d2a11Yq7-l}dZDjkBtCGM9w+*R16LbpQe5FHUMk}*b1;6U>Crih_xf@KJh)q z>b~~*us+UwZ+rSv*QAftBXSPw<79QbBjP{H*J{2*7vD91?zjFwD1JbDKC!+Zw`M-f zxMqddulc6R#BjUUVmkx7+Xrv}Xd^(3TJM;y9$sxT$g(HcC+BdSJ$!$x%|C5#tmCD&(`s@`Kb3#nlG|V>R`{GOt%+I`gi+0UB9V1 z+g%ZMqV}VGMZ_4JC+8xSD+Tb|m*VH1=-2Mqf1R@?w*`L+BW$aYI zwj1Iui1z~Q2j~Sj3~&tK1Y@cF5T8=vtjdRcsYfQ^@pVc*%6nePi+tN9fGaBhD!_Gs zTb}^N6ge7b@}~2O{?pB>Y=G%;;dvv<71|PPNw!p5hHZu|+m>%Du+4+uvX#QKA3~{Z zA@FJ_EVZq$t+cJS1%NKKwb?e>w%E2kHT2YwZ3kkE70R}o@ZL|=KA!n_rfomSTWE8A zs@~QM;jrzPF6_t8dfxp>UwXrXNbh!-O7Cz;q<1(xPH%5Wq4zdSqtE!J(Pw=BhTheX zLvLxwqxUmBOYdjMr#Ca$>CFtY>75ME{nhK^xCBo5)a+sQ8OENfWbCmM3OrQ}umoWF zB=3IkR2@LWL*#1)0Q-AtgYukVj!579U>PcWCSy2bG$P!1e0hkzt>X=6F=t!e?air5*IBfLhjZAvm#?$nk zjT!&nz(``&=Xr(NqXMYaV4aC0UV*H!gNWcD2I}gK3_}MN&v1*uMBbWFodUT z@-$f}Nt2^W08XMqE2q_rH;4Q-=nEsii~ljW^`G)TXQ})z_+j>>vC-Jbo=5M=ilToM zeT)^;n?sTS64ZBcd^%KKg!14A`91t$X5f#2tYj*a0yz>1tNmfU$vEpZD)%;Ge5(wz zv$?t)XIaA3(^GS;=cneTC0Nf}FIg{5<)`x2v(_uttJdq*TNK7f2L7T(6#rfRyHNM{ z`R@bg2mB8h&mZ6qFoFLe|3lF1UqKrKw5gw&sWnlc*^gOt^iM#)c$je;xPH33^Rh>w zc0Xfj82~dr2D0y)##swk$$l&4a;*4(M3>#;p) zpqEnr{q&h^ms&sSHTJ}qRkq4g*Fg>$^C`hP7kCX*8z7!bZjBvoS$M&@F$!H@K3uq?IM;-FhZ_t5a3ynp_EU^P~#equ!7>$DYYQ0 zW)iT5)KsV|mE=ND@`b|`GfJkqAU!oh(J^5Rb(~U9I;#3jshZS}%3Ygw2ecg1bh?*5 zD1-R^Pa>xB{Dl0}B*>AE`5-OEp-)7cE}|3s`QcWpS3*EU&RC^!6!h^dF-Cz#fbKF#1E5MDLe+{7>?6 zl>lV`wdCc}={qJ1>9Y(4s^_D3ud+4ti35&Fx_r58DZVQul#c^%^lh+c9{ds2Pqn2| zZTP-ZGg&$#OBcz~jb!O2vUCesdK6iDG+25AizP|e21ac#P#d12y77HOsJT-2lceKn z(wbv+As)}FRL%AI6sWGG|7+qm@(YO4(Y~F;T>jO zI@?otwQ6tZc^ztRXuQ8vUp!1}{+!;rS6^`KAUj370(@UGi%VrJ<_JMa%=uVrTw?4I zgqTxti5SCEO3ePaL`XZLq{pSlrN{Qfr9f&A#Oas^a%B>p88;KT7-G(22$$^rW0WsJ z*DnZ`ZQHi_FWYs>wr$(CZJbl~DciQqQ?{$Rp11GYb7$txtkqxoOLwlw6_J6xBV%Rm z9T~afw=2e!l?9bD@T_&DtI(Z|Z52_MVv_3U(-<|nfoy9U1H`oST6b+cPMag~3y@X5 z8?m<(6j8L%Xh+h97=U!pJGk7iL$m_CcF~7wBH=;Y;Y(`bx6n3#XR$j_U&QKl(SB3; zV;?PrJ49x6vft={Jy0Yy#+=fOsv^$l61C!TZOtM^APy7sVcTokRDPGx$KX&<^>G4= z*TxV;ccTxCWCRjKM}pR&P-4qpf-{dH#RDruFAxoh2acHU!w;7bCp2j*dMO!65~MK9 zl7$`~iW5fHkHC$r2FOQ`kqE*CYP~d=uI1PH-PC;xNa#sthI4!zxiX|THu8I1!5x@6 zv5sX|!yc45VIQKZhd5U2u)y};2Qk^9VJhr2(!m|DOpkut07OQP*67#GwM9C|=Dcs< z6n5S3cLMRg2d{w{zxlqr>l(L5u7i{Kd=MX|h`*3ng?2ttGG7m7MKHd0URihjr|+)o zHNJeme4n8F^8{x0UtvGMpQr>z5rZZtK1^@8!;2AvXI_~v#>@L_J}3=v+giUN_Bf&a z&l%oudD=xJ?3d>3E7_WI@10={uhUCge0gq5e;L-(Y+wv%#UOa#PdlGa<%eR_Q zb!K10*-a^W6kmk>CsJQk&6Sg-#nuBu*qm2NI+L1H~c3w9%#u&bY4&&PX-qIDVWPq)H?TMjCh_K z-X>~A?8lLYT@V@;3#1LyQu%-ouw~V$Ui$oJR>m=s7|M`uPbb)>BGdq~eY6gm>d+O7 zC-92x0_+q_zPu1tsh#>z>8~78`yx`wEMyV|`TCNMP*SO+(jl0XFtS7YUS&AhA`SwG z>)`A?^z#OycSFp<$D%iFpH&9%M-&!2^aB6|nC3f?4*&4C0b~ZOA{dcK_o9@?AzLav zGAeON1j()$v)*72)gDL)@P0Ka>yQhxZX3~YB<^4)Q1(!D(HrFhEjMwk2z;cKq!8Uh zvZ$OM$*43KwkJ@=NFWLk<~YWl6iO>8qLI`lxwL$b_>HAH*m@dA*4Yee-qH15!T|QC0E_S!DyiNk5kdST1(?b~ zUT75v|GV0)=Lf$f-u5l9ZRD(x^I_xR6BNZ4R5c91j3ZmtY4SVe1u@~&AU@M_I0X_S zYR#~U9qjx?9P+f3PJUmM#?eOPLaYa#yTAa9xew3;4g-ihIk)D4E0r@KmP?#YCMP>& z%>yot-L9{}DBv_(a3V#^Hb!JilAm=~`ys=Te7sK!>nqTA9~$$YSx7pOIo?dm29@es z@GJu81=cM_|G1yn8lMfN&krzVM42v-d$NV;3bSmEa)_nGC_IWhrB8$drcrlNU8X|< z(AD?+7yLaP zx$L#m@iHpEga`T9npCAFnK}O)C3L(Z!9RG7(#)3PU(Yt#HrxYrNXbUB`y*!(p53k={~)F%t{-^y=avd zOlEu5+0z2qZLKg2KbrF4F#}Ti8v%r z)rasilp}=b*5^1vu!i~_P2jT=5bt5n{4O}}q3&X}XVV6W8?cA3$v*H0H@S;ub~g_h zK>aY~EAadwmgy2?AFM;nQTc;>xZFXe=t%*i-$-3G0d2_K{bu8yncvqMFt0?H{sksQ z=Ej%8B>qTz5NYVcy(f+zwsyGF5(rh`amL?p571WvkzY`j+fwXB&6|h%Lwe}u1?I;N zo3MXZ5=jHTbYQ+=6EgchqsD185*w3mOeZ6K>{wgy(PQ6nfR1-xH7Ji_&-V zdpStpx$9NH;~ULLYlLQNb`;mH11CpbQBR9|ot=gA0yuh<0??&3f}848PDK&veBf{F zCaEt-r%@p^(uX+Su3rSO@`8W8=RkoBp$z!+#-o0r-#RB8SBJD>8(?6ey)lF4WW@@I ztSj0k5cy}Vg1MAwfIQeBTYHWu!njZ#z4FY5nSq{K(y$8>4A4THY7e*#fQ&Xm+(Ydg zeuLkj^+CRf4QTaFL4fWa)Hxr7%)l@Top+P=+6iee_~4#0VrvQZTL+2a4dPZTO@Ln{ z+ru^j`K$JReW%o6zX+hs^7l}72D?JrgEC<5PSV5~P!C{MK6jIS0KH)Mv-C1T3qW+L z2XIe(C*H6R)@h6I5uy`-PD2A%NqRsquMqj9vx#P28wfi!WKDTe5K5ap$}o>!LgXuAOGs*0-nj0{9GimVaX+G}asqK)DNH?303lzt z0n#?mN7UZ61=_Y~H;_{s#~#dXbwAN4lGwIY!8NC$i4eM+q9+*{>zHRXO}Fk82H?^(m$Jhm4$YnASV_r@Kd({ z^OSJn{8**Dsg!RS(QC?eq4!vpEV)vZ-`IR5vmv}x{NW~f!q=3YBCpOA2G3MK7BRdL z@H-N8KIu1&r|O}62L>CPJYs~u&w1O-kvI}2sXp@Ku;Mi`eve9gy+jlee%xOV5!lq; z#s}>qi@uD~1Iuj$bGsvk;4WN62FKC+gJ`hNYLSxp z0^Xl6{+vMgj=BG#Ke$<&q7)`PY25owCl^s1VLA0S+XV8-)chyj%>uhEKg1PnoeMes z;YBDlm@D%sC)>atwmMi9N*#N>)qt@tE6)3oY@K?Gxs)ijGQiS3&=pv|@X?NE?>pFI zUu=B_%(7a2*_YH&Nir^2&5d*#d=k_y0ih>$s8DrQC;uGn5Q zh81D?7H&U4z$Cr`i@W@mk0XHx)gAUn%u$M`>H@DL9{vE+992FKn(U9D>WaKDJ;6QQ zyx5?6)ZMx#eny(tP54* zjckmx;L*mGigRRlWI!qV9^Tgh^2xmUHBO2mZ?cJ%8%e=m@a2PJ>na9uX#{Y*oAO!2lb28@SowFm<#@yNS9$r&hRsps^z0!QohIs z%D#W<4NgBBOn+@;9??fnWFxdAT5S4I{HkoRv2-DTHqtqiYlmcd2h}flTxll?baA`( zSC{l9YoxyHhwb1io8vJmzmTau#in@19qt$9UhZHafMgC;#KInRWNsVlj6x;haL7ZV zPrd&yD)XevcHsT`4QwYdGo2uv9z`b%^G>WrM%Ze}E@z~OhDnM!hY_h^-6guo676W7 zdV*~&k+npQm?>=KB6CrXaOpO=rD*guZ4&kOM#_oE{$!z6m8d()mVBiEC4xduxl}{s zOAq-p#Jnf0sfCVt86`Ae z;KsP12u<_J_NW-v;y7SutN|=>X7fqz$qZ*VG`*$P4c>0wj_a<^gXgFGooVwP->XXH za{1if&h5Y3E&C!Nx-ehxUN9nlDT)YD_7S{B_mj)Ajp*1N29h3uct*LwuBX5yMW*u+ufY&A~U^U5}Ca3!v>ZW zImd!!NBqi!;&rw5?X`#b!gCl8Mn#wu+rpYvIYCHoBiz5hxVNPr|E!E_`uHP zTG$8v0GK^cY$wD6$5S|E3-(9Nfv%&(SQljVzp*Y#+fG0F0e0yj=CUm;#5~2JQtdl~ zm=>Q+4qUUShk1$adj<03HGp~n?d^fZ1D9vB$nl#!>1`GC(0~We1@qp8N09P^DD|p! zF4)2RP}_}%M1V9xI~AJ+?;Y8dO|%HVr9mT}3z}o@5Td}&;oY5tGzVjXciq!wNBqo< zaC=<-|G0Mp2&B6UEGAgI(F&d|#d}lj~d*Q)}i_q%rc_=qjK@0a# zwD2H!?FWP>rNA%e_wMio*s(Y?92=fV>mcb66Dpb@bm2X)c$?h|HjGW%@Ls^O*l#$E z6)+*cG$Z#B_#k;_$wn#rgsBDSznT6?Hw85Q-Axm1@`mO@DkVmtc2k8bKOc9i%%rK~ zz`lGMc{R~*>HuAT3haiKI#u7?o$;yvNVmo0j`I{6vi+w1~7MiPh1vG=T(w3n~Whhq2-9+`cR z^ZZSrU|2ap73=;MxGx}1sfp@)TEqaYiFhXCNkkj&O?9HJNAivM<&uc|S1YR52NP(b zeQJJRUows<)Zwj7=xb4`z9NoE6L@|w0mKE2PPi8KTQ>?zMn)u=j#$U`CJ34D*>Y0G#!f(0<1B#4WuyA9J--HHIkPbHw z5>@P_(~l9S!c^7d#<9}V&>&aW2uqcj3Bv;763VG)@@yk{ zbt~{pSA*9|*}_9T+{)Va{#-}Ty1zta1xApzPkL*%7H2mV(#?oK&QckG} zGEskc2D!mCU?OuSLIvW%6*_oD8;KI0WZ;gr8^~*~b4#x`R~X6T)4rlTgS}Y5 zG&je^yeuSaZdB*Z%9XH=ESfnB7A0pcpL-Cha4FWVD z$Q_6hnDmzH0r*sB*DI0@qaxq{uANH}^f)j-wEg5TPQ>DcNI^cJwhj`T&T>kvO-6S)NvLIWRM?8A_k;ik-GaWbT?Y=Gt$qjIOXo#VY2JvC0h~qFYvluufIE|Vx9@b+JxAQfZQ{2t1HY0J zc3`K;G=Fp5-&x4;LlR#U+2A)56wuqpfcL%b;oscvZTM(dgicD%g0AU!zKyeS^UV4{ zc58*X<)6;nGCRi^{TPpIvfxPu&^qRwG4>3Ur>KY8pSk3iZ1+=TDDsG=&A**iM&k)7 zOXz|=CsYUD%RWVfo%(2|+x2q)<3G(r^aEo{U$m~TRa^melb+flLY*jsdgzxORm}!2 z4MR!7;FwTCec?{Be}ir#Tt%k*qd=sO?ZPk%PoPG8K*60-XUU>o{DAu5qlxmG*KK~yS z+gM>65;u>s&Jp4U{z5U3KgHfidRVbUZgzl9}YZ!?=ijGn6UqzQ6RA$3(v_ z175VK=}Srr7lPD;XKRWtYE6TD;>9f7kedml(2yxV)%1shEP?kOY3crg!RP+sg!wSJ z!4+~!BVdmx@YAV*5jN>m+=R7&e)*0BGXuf-~G>$nMF88TAczxQklE&FB}&=36dhohuc4y_~%Vy`jDG zD4LqPc#->Y+-Qjm+?L3-dk zs@v47Fb1Hz5|KWn7Y`{-UYI`c&nXlrL%G6E(jYUzgk%c%q2ws<2V;v)t~D_%kuJzD z=K&jm@#Mcp&8kr8uwmt4@^n!ibL;jX0B%5hPGv@46-TpbmN^a>5T6(>coz>69krg& zeU>rvk+Yt7_l>+Jb_3zDvmG@F%p%7aZ;vR6p_E2e@NQChP<`qH!O3hAFZxeB;?tgU=U-ffsZWbTr!gj1PNg*7QwYqc zCWlhOv}f>Uj53~4o#~ad8K8$p(ci8_p4u(sho$5LmQ8@ve&uzvvAr!*`YSq1H@SbD zmkG~krr=zp*qyO2UL>zgrEgk!uctgm&bEF^<8^O0-+Tb)9kQKYdlClU&sZH-r`JTU zlj^Tj@1uHxJ+)O6l!4vE*8x^yF9I3EK%vbK2%o4_pN&$}kmxg!i!ce)AepSa;wY); zMzzL8_@%b}!cq#U6)h=LUUQn-F`D9*jQeos!4;S$#y?^f zs{48=!QGEM0`tIP*j_wHL0+o;tRQvb@9Q-Rie!$XbIX(@{uSc9c<#E3Z#gH~djU;K zXk*OQ3i29DT*FDJcj_~v;lZAUi=Qj;PtFptuk=}-=zYRru)Mxa>-sB$WT}JP`lRWx z+9Yehe=M(FEA)FV8d$&vn-EAh8VnE)YnGgT@B(% zU%nE0VwW!qSn-+!)@cyEc*yL9=E3;z4QG&2mLV^T?qgfX_=6#ZiCDoNAS_lPbK+Zq z4sj8r!44mvr8X6Lka&J($QU`(R8yg<_(`0t-hcs`A zJAVy0&U;HP7v&}7LuVUi<3O&%K6w|Y5Y|c*NDNSB2mEnFX$E=$I_SV-aqk_2Jc%SG zJxa&Dr$M|!xjl|=0Hw^qAgWTm8aRe5pbX?Un3al%Bkv_UMI5>qAFxUJ&>Zflh9ai~B(30G<|b*b!7ZY7Coro>o+TcZh0iYZd8<61M#+B!c*$HSpmR;dUQ* z62RRHD`;<#5#8<`KsifdRyGf@t|r-CSNnVSLFrm@unM=T1)~j8f%SRU#sM+!z#BP; zQxU43RI>~{?Hf`5$pQ!2ijIdQB+-{*P}j78;(U2Eit`06gUFbL$; z9wJG2Fb|DbEHe0m+{1{Fx`a(Bg9{aNpUQ87^S~6k{ujmT6h^Qb6s5{P_;@JS^c^>$ zzg8*C`=U`|V(^kA#sQhV)VV@8BNf13NFNp=3ZA%55I;$bAqtSeM!GvpCB?fTt~JP~d@lcA6hWNzA?{zo z9gMSg;5>GQebD|MN$AMa?;z!P)!r!*F=X`EtX6m z#BAB=H}r3o5P)U+P6P(6i;Nh_PCW}cPt|uzBg)58v@XX5`yOEIXgN4cZ#uXi;gaB{PhF%js3 zsm1BR*hS(#vX~~!KPi&)@np$+WV#+#+AQ%V$wwyiYqEaie-F91C2A6R50O2^_@jmr z&9-GLJX1ZJJz;COkE`2in7@P0weC3_b?GZE+iEzjd)Y@iQCHZH^&NGsx5dyLx9I(j zpw9UIQ#8ar@_}1pJ^AkNQ^Z)}Jo$Hj1&7!dXl3a*xa~Ltaj$*Y2WzGIm{iy+_O;@r zSxxc>;jsCY>xU8Q52O4+*Xq}l1ig26f<%2DLh0d;T7VM{pS~%-u?NM>&7|f4>j~UU z4(4SQi$2qb^W4n@`2b@&e2)$@z-j4blzo771wMY03E+fE@YmGiuw^fiH%!8h6L1&4 zm)LPL$~Qpz3?C0*0^H5sjFJwJ#(zV`PZDdIP>;Qq6L=bV99Hfnnukf`;SzWndK{7i z?#6FMt&N8}nF069H

    rtk=xO{8(SF3pXFF3OTy*3R&jYPdVlmX`0bIY1;k|d2*L{4V_19W9mxpVI}G3 zn9`;kW(>|Pfi#vd|8blzYV()Uq>IX-ts5E70Y-u_eHtvk%8K_R{ijjVYzZ1%f=VNg zlHYsC3In7|aPb~}q}yQ`a)FuE3D^>v(+Rv)nHz9QN{59a>upzB z)L=MR)GZWct|VjPlJXd*Ns!yv^1P|GjJgfIZgaEC)bhNmwhX5Y{np23(vzU#6ulhS zb)nGIB0=Df2}?Zuzn;d^w5g&Ej_9jZy0x&7 zDH7y&3c}=gjouWcLu^6tQjn`5qod>9cvZpQSk25OhyKl(bV%pXcnzsJ822x^QhuaG zZDU(1Q)mWO1~BaKX|$a0U7~%Qh$`lqoVYZry+yAk3SwNwF{Xx%2RVa<)L zFZQ8_R;8i_lZzV)P<5l>9eR_EX<>o&FQo7Bq#V&R@v1VtJbZ3D+zCi#85cGsrlxhd zAUV3hT!FvETv755!b)W%)m)X!hRwAX3SF=@L_~kFSWxVpKdQx9SXf zu$Jsj%oOz`wnFk@kH5PGC@1oQO3&F^Nn9R&MOvMPClow;V$+!ajZ8l{GUZb?zhm_k z+_F^tC+Ay1SS_|-2{BcIdP>F<>nCGA$L#_7jj;Q3uxC$oKj$Ne@StbDb$b;qJdQ<<%1%`z^lQB8-oG<6BkG_IvO zrQK)+tW}_k60oU%DKqcY<&4Wq(?Q!b^5xblNY{9H*&6mOnXd2*aw`Epc9 z9_5%k(p)+7BDFVU#^{Ii+C(3%ojDdzU98j7Jaoc6Gk zg7Z_JeQC})xe~I^&@W->xm*`YYPsiGzQNe5@^>k0uLuGX(=%qTn3Ur3Q|f*Bnfb;N zK$j#V3Zhr49y$7{oR{+CO@);?1X3*a# zjLfi|k(_@<{w4ma0=5?P(I8!pSTyLP%h1q-f+g;*!nPLw(4c}P|DuZtO$1ubYNlY< z^j^+eG|JVWRLXWW)RiPU@AFC^!Wbiw!pE2}lG0sPxX}4GW}lhxMwdyR3}M5BD~r>x zXTxPV*loCzFnpIyMwU_9=rSK-S_g;H&!S0TIZjarU4orGNRfDaH$g#`B4@lH3HwC< zo)%J%Z3AIBW>&9BmNRAOEJ^z+hB}``ZvZQa+mb*}W~+%YL2{|VF+p*8gefNp*^)y~ ziEM+eEymN(Y(sxG$k7mcNZXQWOOZP?xh3Ci*0IVkpZYoMN4m8N>=xi+F0qO{ADnAI zDXHKVl}pmKitQHmfN}o@h%`xGGesGyX*?&(+A?dEg6o*LO44{r;3M;0Renl&FlAhm zK^fU@Xe}XpPyUp8YXngf+~+<@f!j5+qk!Jb+ejAG%fO_N>V#qxhPW&0q>?%&_kd37 zm$^&&aZ9{sI!bia$2V%Am#9uA;$ftuT#b}j#%+OM(yk^-E8M*lWjQqJ zt|e7XmRXoOH=dBGYT46dbH z&G4GNtY|HXVI|i@VUoD4V=dp%l%^%qpkZCyOuVKASq=KC_b&Y&MK{-Or8|bGrBF@z z`YU?AXjDOquo_YG_mHKdN#?TtIpdT69j!cd6X3Cgy+XiOigMxlROgMeJ>yF-eGc9Q z_6H^>(qcp5$HUwM9G?Q?!ubP77wti~=Y0BPvTAX%CYSXDiH7-d?4!|K6=Sry6kRI3 zDd`%@e_RQ2+jM38($-{eNxn3EUn6#l$wOXgyddcqw`f- zU(&LuZgSI-xU{bBSk{i7gNW#+AZZwXbVWR{Y|{#@e@cl zR3r#)ga|4E0S00OH$Opy;6{P~N|2x;5}=6dNrdD{1m#(Pa3`pH80a+$`j`lbLxjjC zN?;KJn8orW!tyMDz7vGH6I4D7G#dq-N`w?ngw!HJ3?W8r5+#6=_(6yT%;IY)kf!kxrI8}_;3N0sBK7DK`|*;R^@vZp2~E0*O}dFpx=Bnv2~IwVPCf}w zK8a6?lgJk%mCr>iU=3Q*?KdIrH!<$BAvmrhI<6Bs;>2^|2XM&==1`ExCnJ@EB4>{o zb$$&%t(Qa2kZn45VY$842BmgbKfEIB;ix8ki4A3G%)*?aXCP*eugu+V#!AlI$ zBMj#z4(At(brFPh5ruUThIJ8#brFbl5s7sXiggi-6(b5KP7G0u9LyZir!ip zT4;#H784NmYnJHA-~*Q$*s3WO$GCXjMx{L#$GVusX0dH1|Q9rQ3-Nth3mot> zsUeLi=1ooO5|@95u@#PF+tG;04|nwb2FOT1G?b;E4#TQWz)ks_8?ex>osnxntHBPL z+%>mi>`zW4(v)J=KOMX2ZI)!sThmgocLX=*F1^FXZ6q}qZ%Xogtb~asp)va&NWn>= zf7=s%H>Q0HXZ~ZUZc`9{+4eaJ@WIUQ)vg?1Ww<$5JDcuac2U(39cZjHQbOa+PZg_a zqCagp9le@qo`6zL^69F|%W+e=jP_!alEq2GTPe5y?Y%^$;J#B(uzpp&UzCKZjAE?3 zl}$!L`TCO9+x5r_|2*^55rIn#?Y)t*>t9KKJqR`e)gT9KRnqx>0e`Yfd? z+s`JM6j|qA&hHtgz>&~%`S6YJ=3%OJX)ExwkEWh3G2Y>A{LsRGyf-LftIsG9{{-6t z$x(<~v{y1A`|y%)nUH9Q#qzB9iYycy0srw~?5b6197@>oPn+PGb=h4|p1L}cd#(2O zcpp{2PuF7yXiN5GSKp)Sw(zz8m{6Hno z{$gXT+WauawetADQ1dm}A2KpMmxp$OX>VV+SGC#tN6{1XK~pHhIg~xj_~E?qRxx*W z-C3nv zhm7vt5??LQ^Z2XQ{sWaI>t0!ta)2c@ME36B>UM>f>JGMFpv1SXtg9IV{fbUmYN^U? zlcbEn*i5?GQig1$q>R3{q3y5==Ca#SbH_@nFY!A0`}#!N%djC_wnp7v zI8hmXTa>STdsItfU1QONMlmxrD!MtwgzNW^YI?D093q93?h2r%srE6*jhJ5`M3k>_ zePX}=H%&j)ee`UhlX#3q=DnQ85$1?{lf3TyUummmAzT)LYPfv%l%{t7m%{VZw$C^j z@otr@LjnT-2i@>uZ_Mk9lovXh!xN-Clj%Ni^R1S3Musz{^N-SoKYS8=zMX8QOAppU z3;$-$TS*;y&!DYoeA@lKb#w}^DJ~{^q*@?5eR%J>k{c1dPr1#_9KL^pwt~s`7`kyS zc3s!!8sj|2>vsE2JXr#V>noNg4(R81Bm4M@eobZnx!chZIIkl<+l<+;<$z?s*5s@G zIs$qhT_4|X@ciA6r89 zFw@^yWg-NX%t_W(pah zp4*wSu?gOXnXJ_?mDNvcz09}sZacIWmZOe`asNq23Veq4Qr=}=J+t@e);{HvV_!Hr z*OT<;R>IsfId{{1Zq5qTRx<&CtJ{l*pB1T6B?23V?B4|UaAR>_?c!^mTc`+CF7VRv zYppgT<3gy?{8$1jrFUU-sgU0pm{=)}-XcehHP>BN`TQ!KGNP}T&gF4450m~&{qON( z*Nb7raroJ+qzi^bU9K$pur-ZHy>GVH+RJEj z5E|$$JN5(k%`DgdMJ!{^Py4Q-cWykd#39_zxLNGk_`bX=po%}Oa&|^fcuWkhJFX#q z(#Y2XeDY5kE{8{q5&h`Q4)ffXn^wNLoMp$ zl{Lh>piJ(u4r5u+Rn)C-nZLO%L`np?o4cE9*r__)+@@r|yDKZDT&)%(q~o5kZ#?0A zi%=jJCI1mp{$)=}LM?_AD=k~Jm=}@-5cV~M`L)cND4lDbYk&%Tx6ov6hxHSSgnf{P zGLPw7NPl(&2tQRykJQlpy8-k_8r|%|%Bk5+!G9?-QxKWYt_Ln#I&;K-CiqZ(Yg~4? zCLK3ByKizh92BaXU(2?uvr`{k9AtY-06e#;3nnri!sSnr&p=O><7;?iv61J+&-qT3 z`-Sh94)k<&@Pn40-drjLbqhZn_6C{=Tdp@37>jD`XLz@vCGuK-A3qgc>>_7cJB{RP zt6$#!E{^NCrX%pZ9_)%ajBr^Av4U(gv!_#aQ}~Zol6h{r=y{txcw@Dzt*v)@Nhsj| z9F2GoTRhWRyue5euAO>XW!?TNnLy;LEqNhdq0x4jb@m^6vNaMxOr^fR{~8x^wAE(x zZb~0{CrkI!`_c{I^@RbE#W@zBK|wIJ^s= z2cStPe2Y-6-RAyj<7%_)v#&lL_eI}kkGJ^W@pX}Xigk9qt^I^@@mfcDuwSl^!RuO1 zTghsns?oLW_MOWn<49iB%i%}y=L$g{yF6R_suVq+$3nm2mAYp*1^8&U%f1Pvzp` z3uWq;+QSxd`TYT&ekr1SWh$@tOHy&y3uz0-g8xK^rY%fLPS^MkG@(c0;TLnDGxxzo!NFtg0uw^BvZc zB^+ys6Jty`vOOHp3=NONHmo3Q>A)@|a|nsWG$e6W7#U#pA@$iCMY&$PzV6V-ix?k1 z@S3jcXpyIN=Z1e@JIGj@H22F+`%goLo6lY?nlkzyU1qOim$;zlrT5${=M9;d)Ia{# z){?Y~n+7hOCQkIed@pp(AoW+e=ptNm14D z@`)=b0#BBG$7v~Eh;akBa$(qXxSO7IVOkz{>8F%UaW@tM$Y%d(B~DNr+4q82q1Odu zfmsvOGq3=0#&bc`c!vB!3K*w?HLxB<(_q8K$qE{$GKN|~8f3TFl#M@5Y!9Rfp-n%@ z(M(9xD%nN3_`QpBVQy;pU#^7I-^}oXlvkI#MxZ7m7-}x@VLU~G1^7J$lvhw5_ zoxTQhTWpsBD#q>q#G6Z|`nONu-0+baUKTQ}`uzrNlBI_^-O@lW7J6*HHR#hz4%`;J zr3%KLCb;d3t6JF@U0Tr(XIZD*eBDON!l`2|OGS^ZYg_;ET-%Hnr|VE>oZ)YiI2d+a z#mldm*Rr(&1O(#gEj@pY5}zBNT)G1`k%$xSUCtf{!lkF4{VaV~UxW|B9!3<-`8nvj z-EuwWeCE=2T6)w3HqBg&fR)Ej%)d()VYq`jL^Ju>|D=0zpfmXQELZHWKH@R^moA=3 zb=$ptr>?YiYpT_yzdlssidRWAQ*zm4yQ`Mdo4;Ec7O!s`yPgj|#(tGtrfu!wycu6I zZao~kOpVc}7h%wla+V{3_eY=YboX4pzR=w}nuP5q)rnhv*W>r9Y2B`;k0>;)wJy4h*{UsLyw)jPn=|lE&;99nt@7PlYRPhX z?Wi5%ysY;8a6YDFP>*jW>0ou`Un`{y_3=`#W#AgSoBEr5>4(3Ax|#ZCNerLs`1*w1 z#IoJ6J=Ppy;OI&fJyN38jcdA@wF9+Y)VF1+y33}XWP;=N9q*#?>??)sUSfUYPrfM| z2i6w9>FD2+R;94)nc9gV=^6I-6fD2+OLOg&HbIy4F@;!u&swtO&|H1oE&V(B!!`oL zEynbz%)fU55^@&FzJTD+d%PCbC(eiGcTDH?uPyZFqZizJ5$Z@-pW0Q7oXBmWO^=&# zBazB3>XkCx-wi8KZm`Eq+!G%Q{7HMV<_<-~ZQMgF$&rb31@*o_9X3?>QiF;sLBps8 z>(Ds1Ig??4(E|%XZ)AX-2tTNa<}ZUv;FVD$DA|A3T{QUw=Q~H_nS(W7yP4Cn#`2M^ z5ZIDh9&p8QBp9dcr%WMCCM<_6B`j#HR7@|xXHG=;g9(UeGA5&-4Sd+r0abVfzYjyL z;AyxPtfWkZ{Jee{35l12Xsr#-gUR}0ub=z3ZOvZ4)y1-V#*uWa5O*wa#nE*zxb(rE_c4H5h9x3Pkz|#bV$6Y z6qeXZETppsj(?>e>(wo3e2w1M)$JF|9lmHpXtXnkqF@%RWT-OnKfvX?aV5vt|#oD6i+dQ>|?z;BJVT+$n^b%tn&83YVSX5g?4` zqL6T!N+!KDg&>yzYXnc0piIhXbefKAL8%kAlt8Faj)SFvlZmC3k(H?>YDhMWO}o9m zJ*V`#?(~?4_#Tx8ORbIh<6@;yP^!cr@bY+Y;6&cN=BxYhGkyT?&&&4r=7meyw}1R( zKD0!!T21R!rdQATT%?pY;T2cKXtle$ltE1Q-Eubc&W0-^4#z+3GF{E~Biq^A?2R>E z&IjCj#uV;dg5QM3nDncUg2hjFw<*t^9U`?y;BMKQ)!xQ#^`7JtVZzUFn#W}Df3L?( zPm0{mzj=JVqPC7)*C$nVFC#rWuoxKqUArzn6oQA!F!Q9*Msq3>f6rm^j;|4Q_suIS ze5K)Syj9llDY#{Yu4;e2b3E@zWsl%DuC(PS?`Ka~eII*N&J`!M4|t<*R||ZuUH%Hp z$rTF770h4iegM_YmvN0&!{_SlXim2b7k>;ZxZA+4{|hwW$o&BiV`^vO?BZlXOGz&$Q)MrC6=N@J zV{Q`?0e*l7kB6;;?GGCw4_g~MXC4ne5SHW{->P(U$m7h%`IG<|NnDv`mZ|w#pq|C{`VFcl8+W9VWkYHDn6V*1}|fQ6m=|4j{e zVc?p6*D>Z0F zLUAh+tSi=u282g_3mf+x1fH`5a$Bmiz`A_%H&P0uoj@kv&dz$Gz}wMDi5n!)ktjK} z|FH3_=FAdXb{hu>-NZxd}-U65OF^sV+ySVX>YTudRTNJ&d*EjGjTi}_9xi)$9q}v!~%Cl z;qpOHKtpE8VqswXwP;6>O}krmf2y*RPP0Q>f=yk~Sv8lC;ZJ#|gO-HlAgBpnV_^H$agMRW-n0MKkN2u4BZ5 zsSQEhll7p_fxHfy*yDM@+C z#2S}5U{nvIAyNg(0W>iPQ}?G7OyCpXX5GqNKMYLrRl|@4c5FiOz5Ri(awbEjM z0tHlLu@JE+BA_6GR6tOY0)j?l6A_eZhzN+$y3iY#;lW&II{Is#dAvXJ+`RYw&bOTJ zBsp)ko5L;<{K`f2*P81KtBw2A!`=^GfBaT-Cc*iFDP^{;LBme-onqUWy>ohB?=?-d zzeMPm^X>Ou*ZqB|!<1n|k?cYI5(Y#lPx7_5ZMA6qduwE?cdHY$_XuP2Co7ZR?)UDu z8)1!nI^t;%yYq*gWp8=7kGEEmZ0IR+;BUGcapISOH0%?eFgIU3z%{$1eqKJ8) z4194evGen`Pr_aA#8oC$CR?qn`m)MB+WzV3H@vI87qi$2wlOsf)=xig_x;f~{`!hK zr&!q0%{0n1)n$9Dfjmlata!Wl*a+=LtzxS}VwP`~X*SR712bcHe>YzK>imX$d47O< zo@!Z;^3us5dC|VjvhX3p5X<8k~?o& z7iZ@99Q4V!%HJxZGi+Gn|9EQj=9M!FLPNG<)0x@i!+Xe0Ohh?{Ab~1@*ng(jYX3`KeuBth+gZnjC z6lDpKkwS6_MJD-6lPjX{Y z<7oMo&?5Ch6H6YgC}aNqr5R%x$r%Y$n{ZIlTXDR+QglMneQnECBhjdId8j%(P4u3m zP`a)EKyTvjErXz%ccZ*%w9>dk*%qA8_I+6_s;p>GGlYJ&TKl`)lo7L)XqZrE;7cF+i zei_Bvb~j@v=GJ!xwWn%LYdJLwYI~R`SwAslcKhrE-&cMt|EMnRwyfSRW+lpOE(qON zB&=h~+*d{acGs~x<*93hIRgf4HT&t)62DMhW~3N@l@lXMH?5{D8*b& zfHlXm$f^C}!WpX#0-)-}2bQqSS{93h*QH4um-VfGYfJHL*qS();+6b(sVU)xy}~w# z85BIQfiS~*dYI;0ey-%-5QKg{sZ&so3F4`ha> zhkg;YezW`i&i!}yCm)u3jIPxdfa^*mjr|)EPHZe>6mSaEK801$%0G&Xnid41whQ{u z&BE5MpUQZ?B?C8eJm2+nDSiB7aH?n0qoClkmycSdR5nKTby}5?2AujwM^~113Jcq} zcT{(`{3>Z^ip|I}yz+LNVWXka(B}Q3*rQvyPu(AS%&eHRdCb_;*rY42y|L4}@|>u- zWzMan6Q+GpPqd|Jtxhu?H)?iwhoAVZ_=vv^``6I%!19fe0pG2yyA%6fibD#+-NL;< zrBGQO?pe6WfrGM9W@tkjb_k(&(deet}sU2%K1ow(Uy&@jpDiih0 z%DQXavNcIme8W;Rl;63G|F-6zd5$%%@IOX-B>8pZun%tz6snLCo^J z!VYiiusBgc->I>&`}D(Ar6xzB1Jz}BgeJ%4{a(qA$_Wm=h5b8DJWA{mSA;z*)oRoX zWz0JzA07DS;e=a?QPLnjAksh!MnDhWo zC<53y?JKd+FO0(#)17%7u}~uPm)0C5cnHOQ1PB0OE8;Vp=STw+Qp#V66@Hv4l_E4u z95SJ<_;HBb5H6o9kV>$Cz=?qTI5ZBXDM^K5`oy@dT+!r72#+4bi4;%z$L>s?Ok5^T zH+p$7Wh%gDsx@7x!GsbTV=_87p)lm%6-=LIH3e{)*zSj}E2}v`F$Y06kW53!G!Qih z5E=kXNHLQhCYckK&O$$)f8>8-IgR-qCz@4vjVO>1d4B&|I2e@{$`(uM;KUl4x@$E#42>fc_zT5+ zT|V>`Q0>a6l5rSJ z!t+Q}Y$NupUl=9hVnF}^Hy#4Qcpms1TNuLg5CGKoi(oauVH6nWmjvKqhESA*y@T;g z9uP`}5q*q`fciclDjC+VDMUpP{aQhoo~|DY3;+logK*=)01WEK0s{!FUjrB*!TNc? z02$Jc8N;af@ldjU9xy<`^#%-3aka-VT))5|fZ+UsAU+Qeq~QF55U$r?5ZlG;%?E~2 z@fbqJ)a|wfF0M8?%cnn4G809&6P$)Pa1nTz-h>}Q<9uGuO0M%Qo7=}>v))s_f z?V{H&5Q^sNF(8Yc)0ax}3)6A)mN zH+QgfvjTAecU0LVt?k^*T|jJ-cE)bz66U6kX68adXs&K9=EnADUa4Dp3en`XI315E zKXKwzG0hB54^5NMc?{cHb}4vpcYC;?;Ua-u%FDT#=#bg5MKC{{`-9F`nLL~=JaT4D zC}uYn@w@+c9Tk2ZD*9eV|?jqUOKvw`N8 zH7bMcOE=qQD-YEjqUz5VYaWwqkvPG}8Ifs;{ME0{x_>zsIyCPLd<>msYp*&K{!Hl2 z)|qql$tNl7$?cTc9_);!#MU+80~$673XrVoOL{I`=03RrF+4Dd!j4 z`O7H1T_)`XJT_&rzziK;i)Jrg;ZH2uf~5RC^N!8svV{yA4vOLdqx5jO@Ofv45{OJqcB;yy0exst% zeyokzzTkE~=x_9)rl;NV^XUFt&ooeVMAMAKJA*BU><-qUjUhDrcCf<5<7mN1gpg51 zvS$*SzDBh>LS?JY`|;(`pq*LamqQCnr}Ii$B_&s7ct zkGDN@o<8I0EA*d#ko=hQ>CU_>ghr6thQv1V(>RA*i+?lK0uP`+p@G%%xNjhE9RoBEWw=5k~am6^-=Vg*N%b#s)J5`qF za~HO)I}F*3jw!yef9H;CxJ#8u2rX1Xhj=nY1<~gL z&M{p1^Cyv{m5r%K7lp`z(=C6@Q5ua&gY$Q}NT(!?vCT8gUa%E$zfoAhV9c2sXye(O zr9GI9=r&O-!_lfCDIG8lC*HCIKPK(V0(*Vsz3TYM6Wm#j^)PYw)4^+D*2?ea1ovmV z)~r%OXsk$_z+lO_6g=E<``jTLUcMPxi$xa+d}$K_dc&xvi#&976yMq(n!z{JaGi&x zfAn0`w-=|*-s_GFkQ*UxU+XeQfWuLqYhRU6LPV11%1dGp6{(e+Qg^~-&kSDseGduY zIaOt14*F|ktx^|01(}{OjnVggW@S|PHKL$ilt?wWUV`}TuZ65O3IlbP0gsV*=wL_spN#0v$*qhW6 zcwc)?XBC+kxyZ|v6cYTw_%nm;Qai@trgmqf`}lDcGEy){gnPwfk@^Ni{Bs7gOT*7; zeeVY=%So$CEzR*M(v4M6*-r)r^V2JW)6&I8;R{I&{*nAJ+DF=4#E_t zbU91L?D(~_)!geyb84z(nmoY&%@&#F6_$j-rRBWCU*KUV>6*R zC{M7zJxCDzArX&|Wee1AoyZ758m>o8#h-8RV6(KLoS~R6oX)ZfNFlLeWr)_IjLOC$ z9E2tT*iC--EdJk!bvphxS@Y)s{&2&)U+&B@C#Nl_kL@biYg$~~Lk2fualiN{p`Z&6Y z{lrb|)G6snjT!m5EiOEpEKjQ0v5FCr;Gu86f>NTo_`*o-2%4t9t>Zvx+1AZcwk>Z; zX7b)aKR{qrACKR8X6CNZl3mvp` z^VGNrb9yH>2W}hop-jwzEWMJ)Q5AnHur-0RH1c#} z@5}pcsds~=1=&;;xmkYc(dUoHM6}^YEK5f?TjSaeHLBR#z9mG8=1n-eIB%!vZ6EA) zTRP;cF2QNwenfA1I;0;4RHR>eOLQWwZy=DgG zC@(oZrV~eEFjnUj5ku5CoHOa+;~;{k?}}vC>vrDqyaMG^JGA0d%KXss=8;dcYkDVp z6;j0O)%$#or&_}1G{z46@L_j=)-38?QL&KH&1QnZ^H=%1-wvDpgok2{Un@mULvBxg+u}nPY=hfE|x(_{=1ERU`lol>GEkumS zPFc2|(slD3Sx@8)a|<8sGhd9?)F^F7hwd%*;L~*Ss-C)psD@FC3-++Y?VpnJo|=vr z@gjw)@#U_h=L|3{f5CC&=E~4ieow(yYJ|%tle6N*E^OeTCtSloY7H78BI#(*e9hOb zq9gBFzkU%ql5+my;tHQk$?$>Vbp9wk&V<#x>LWPdzV8KNstr>14@2W3Hv9}A&B!l3Ntn0dn7>Toon8~C7ne)Uj_pFKs2 zcV&}iNL?S!>8ZLZykZ(AK5|}Js1!5O_XmWZRC8=Ov=sR~nGTq>s)clXHe!FldH*Oq zNJ|oaJLN62d*akx)!Cf6p)rG~7~ zrt|9TPjyWx$oujg@Tzct9;-|mcKI) zD;lF}I-$0oz5-w7NfotM9O+Z_9iKjTjVc&zkaDBr(OY&aTYjPYpsLrr8Sgc7lxC1G zna&Rvh{-llaPQIP^T*-XRUd{cpGdos*_;kzRpVkFu4?~u2(Y#;0h#l7+h^^am4xiE zB+&}bFK%opAWMu95e1hYu>Fvd?5p|FTBK$t$1Yl|N=%XAS(GkR$0QhLTmJb29`D!` z8m90!T5|jMnTBPjA#xWomJt(Dr6&Zt=4B&N`b~jZpCT11>hrsf%&`bf{ZY)D9)t_? zz1Wsg!hIhrd=45jtYGh)4`ljwn&e!_HkTgY%xlI%3-c0wSG%+T`rR~&G z^L+a$w}TqoarT7%$46Cu;^V9WsxILf@3}U^SFvOY$&h4L7hgRz$MaL-TW&_bNB^FU zNwxeVn^9KpITIafbC&bE%n6d8HLsg}qDcSga#K140fiCdQy4!{*C>$qbCokq>2sde%kwEG<#8kr zrEov5(7dP6*+}w{Ua|J?z9_7>MQiOzS8H8m_25w=!-OQ-* zqqel|_sJcf5!NjB?1$Jc!8LK2*e7jP>pQY(?(j9D>Z0Z8d)D!;_4*qX`Ve~);34iD zbFDSmhdO6}uG_x|g62N;+#`CtbBbW;#QU=@WX%KSXK^nD$8|OR=@@ zlhz-wzjK>6HY)ry)9`rk(SxlfO|92`ONcpYtGjb|ps_6Gn7_tHt`R%49(fAi#Q#)=NLHp>)IPOZ2Dnz;>*?FS5M;WaM_z%hu)7|4N~o`nwV5hm#B9$EG}LA-u0k^Dr&ML(p3_4y^D_j5)E6 z^C-F!K5^jtK6uO}hSS^m5dV|0^T&JZp)cy@WLlZJXJsKmDBoqRn;)6Lk4*A6^Hc}9 zSE#^mePOA6&qYx)1o+8$- zYCY;H|1)tHf7yp3r4hrmN zuFNH+X<&3J;kF$k*1nkNd@rz8p=l#9Ky2HZ#Etj~bWed%?uBPoghZ1x^RG%&A_)^O z(&y%i-sAY81qh9=<&SXtV~g2`t2|XCh#I3`E05KNE`hakt$94CSrh{zS6snqUb=M{ zb~I9|xuU-L%JNybC`(U6Ry(*4tf$%~C98Fub3gAa_qI-0O8xPVxR{=H2pC@J^zHqS z{Cq352-99r;Jas5Uln=CJnd7ye&lEhJJW1L@H8^Jm&@0F(kO{a!&Waf#H)s|&WHDH zw=K*VHl;B6D)He>%n77zdFI}0qwzu_&BR2eV>(zT6CU-x8C6Cq|p-xL-L7U_1R2rr8 zzCs4-qKVoG+V3U|UQv%E;$Kzzn0TRk6}mspo^^k#AkQ@uE@F44ToE!b+rQ^1+TQ=A zFI$jaTtw;vBXiQ+y}>SZySz6dV?)_Z0qC82+mdx$NDW#}$GK-H#V-6YF8DS9I;-I+ zawAcW1V0j!Yr|-@an+4+we-}OB5}<>4q3i>!bbi{L)=_sPZ?WtL{u)Ogu&D0O~2*@ zoil15PflW02K!?fN%njLCTQy)G-JLg4S^tfO$XzZ`X_GfOC1MQF7SolQ7`rFUM><0 zlnt_pe)5nLWgB3OmSlMF0MDSftNQeiI@Rj$%;8t~nfTU`CV~wz%wq zFE!D%euxT<@nNm%X*VceacA)1*Y}z)%Li2_nuJ?+R~|o5Y{EO}HN^Dkr*j)HbZ`8q zjHiZO);}squXmZO`M`2q9_QTzrMsp2b9`%f5|$TFaJ>>y71QO(3b{S9+n|@Q{uC=L03gA0k(l(Fa#g^0{MCN-7!Iv#t)F zA02oceZIOt4r)!w`j5HidQyQ+KJ1)aJa>~1$3Jt=(`QcRY|6%#=4=Y)X4b}Hj$R;L z*gV9=4gqoVLiEwtR2|&_PaOyhq;fHLa05YMvlMXK+||+D#njvtaPTR+IGU=NyXmq4 zEK#uI(*O7pm5D?gVfHbgj0_yz#P^Q~5{G%|0 z{YK$y1tF0CRPcI&S4I0rLs-4tCVzFu4plUL5KvTi zpzM%;Nq}YfuOb3TjNOdw94+r8-L{O9levSashhQ<14#E;DBx_hhP8l#xtp;W@CXP3 zTYUUmH&_M#OY%PrgT|($tN>yc61uBqSV>_ib=hPb%*?&a&Cu8+%ss44%~hqu&>)_FN(IDz;ZOifMc=;-vI5Fm#eWMpLYpg^JSfB=QM1Ihs?a0e$4zCl-4 zR}T#3_zMIm(_bK*dXO7zY-}7I9Ssc)0Y!l9ZlTu$KHA#aKrKSN0O4lp3?4o)C^ z3xo^E@fIi;NPh<>Aod0k5fMEw1gL}?#Kpypjg9q8u0K!+(3p2{0gv1O>pSc~_1@y^ z>&wW<=;Gp{2LUv_#mUJD1OkbPi2>>ZEqMzB3^d9uU_jqnSXfv%fp!H0?R*Cm3TS(S zsHiAV2te`;8X6jwmX=CNN_sA^4+PK;!T~ha4MIXfKzjl$aswY9AJAfe=C?qAu6G9* zc=9jofHHRg9SVF0pe*hf_O+rFKSy@?C zRTT<_nwy&&85sfX33Q2DpuiaV3oweIcL3s{H`v+P0UZ`7+8sc%L+=1`hTg#mwCNo{ zfq?hT8vsKD{R?mp=uR*oP@t0U01PDL4h|sh4nR%F9e_!I+(1oDt*NQ$?d=Uz190;O zKR-X9A_19q0L=@zK~YgrKtKR!I^fO??Ck6c3JMk$7QhXlZtno>6XXVceSM&*0IhCN zS62suKNd^^k5$d&?oNz8Uv_<8^A!r z-T?&~{4c=M&|BQ}fDbDxD?}}z7*N1^-2n#1*xJjP zV(&aTz#>zX9g4<&z2f>;{6A|vHZ^w>H`v)5! zD`2q)0m5R|Zm!DaF5-^%PL2++1vd|{48Gnp|M#Bx-KIJxgqK4|=%4L#eJnloC&$f} z+YO&i_N26fIi4_e8-(4L36Uww3CkhLy{rPWh<^ZgRB$}tg6vae)+Cl-pVGOzmrL}j zGfvc)aZk-&ewEdImy#g+sCsN*++*gV@7PZ=~LR%h>e$Ea!*F$sy9!#W?(x z6Vp(cqu|2SfDdOjS= zy5vCUs-CcQo#Eob^jLL@i@^zHIp5Y4`ocN-&(KDnuA#_3^h76z1@zx`kZQA?S$|5f zt&<@ZyB_9XQz@M34_{S;_%ZM8`@vn@cT=dR?#?s0xF6KW$y>jZz-(?btR8H&F@`3h z!xx%i_&%)5a8q0+zwOl(v4EM?s5?pf$LP;XVJnL?4&=|&R`XM&qDhL*2h5i{=W(h0 zZO21q9z!;`O&6iy>^%d%_2a{b*nV9r{3M41{VrB&E=D$JS6lIVhA-O|k+)j(J=YXI zTk_FEKlW37cmLJv!!YZKj*-T>aEWZul?pws;Kj1Y)H-wR62=L=bTyS~aX*L;x0>xm zFu$+B2AT?;)x79v7s8haT`M6HL;zn6rT*$kSQ?`FEK~z>SbWsKA`xM@5^~RzE-D=# z>bMt|)$2%^gSFTaOD)_jiYIBPRk6E&nq%I$Ca%cJoVFYyipRR2^?`81q0xAXA~;d_ zvZs|PEIRG)hLDa1lb+ zm4?tU5zrp2ub?76XDG;N*AS{C&GhQ?a^gAr80v?w@y1=zi}2G1ho3$Yh87l?q7uXo z!xXnBP&d)<2__1au@*5q(G2l-&fd4#I$@|3DC(8yoC*A$y%BH=uav^U3cr`>Q_j4P zJvFPqp8T9ND1$Da(*meQ^Msmaco!wCm8VEBT#t-3XGJG7wuv)V^-d~?kL@YAxl4I?`lX<~arOIr zu%z!~|J+_e@y{<_w%5I0=dTgG7=D;%_Qx!|R&^*@-+stmNrG{zj^B9h*5arc1@?6hUz)wjUz=q2$l|Y|B}&)zIcAZL;GWsR5R+ z2D(CJLhG;FgdeDW->~*{YHuUxOQ^6TpvN=Je@P{9GRFO}smbJOtGnn;{G)ag)vtpL zjXnf)^avTn}a+8z@pYa~5m(s#EcE#XT>GY9Q* zqKwR11OIdVLvr6CL-;vu0$0)2Z-TxHjh-cbq+tdqC*FEYYp()NGN#A2%H_~SSo$36 zOb!C7?@`HzvY5hEgg0q~7_;G`8Jm(1V*1vBN+~h1+=s$16R(EqP3r7=P>9IiwM8AZ z%23T$KO3amIA-Np(AiUq^&)pgA#kJ_O?#Ox(=plSOP$A#kE&+r|CSg7>m`4oL@Qmr zlM=;Jiiv)lu~_Y z94Wi2NQX0Bgb;?~q?zN&!DeBeF6pCQ)wN4q#ivNBgb%k3>li6tKH4>Ey&Of&i>Obb zzeE=wxM$c&qP&|+ah!+A(XXl&?T7vP-Em=noQLsGs`}aG&WiHHDwkR|4`@9mdf>b#PQL?j6Bdqt@N;tYn z#RB*OCcNuAANgm=3p80SZZ968efZ?i@H>)hr|+@^w-+1;i1Cv?j|)mdJ$M7ujo4PF zMCfXLrx5X*-g#RsaQpOe-fR9x)$2o4LIl2SB4hovi3AreuFs|?n`HLHA5$uSF!b!K z7S8>MyD{;KDU9Zme0bHFK}c-$$JFG;Y@xL;^OENGq0mQ2`QlT_lb;j@iH3#S^>A4JMYygx`3zT9Ev;6l?j)?IhRI;>H%vHbXXugLZ{^aILa$EFj4L^mNs>!G;n0626$ZhNCxK^!?BqMT0iAt*X z1-=h&96D`L2`|SkS!;XQOBgSeFk#LW-(}HhL23KZ)=G#_S2x|Wm<#&#YorbFFLgRJ zqwtPjL=*Y^N^G&54uv*)d_^Btth$FN)j0)iEc$rrKa_u4{+2xNT!oy`=OrowvZu&% z@L7*e^i@x&mf$PclQiPRYo&8Cn~LPa&#r%|ButbtModK$Bm6QlOMMg=X5l|Z#$L6JprVH1O%O0Xd5!Gveb1o% zsS+ys<^39yitqW$lPBN&XF~AKL(tz`#TeODIteUQ)jt{LUWh82K|#Nof7F>y0?$uL zo|FMc>rF$eFekqFkyRskiEMJ<5#hw87qz65yz~@C&t`wx$&V4N0seGMZ`%C9cY=lvGR-dDFOvC24<9MAc!`|&#>N>4L zO!j-Izm(GGpJWcaTlRL4zu@lHWLewE@=bv(lHW$Ecr5srvi$5>ke=^fbP6e2T*`LW zm|nsQL2%Em33B*#{6#B|b)!SuI#LP9=EYa=xDNi(lMnhdt(N^^qbl;+ALqypr-JCf ze%u5p9h3&As*+|lRlITep?S84IFd4jSq z{QEC+VBD`biM0%CnFK2ELG7RIL9J;DNrYBk5(<)@TTzR?TtG~~jV%d!#3gaT0Yz0i zc74%NEtL5>qLERI`QyDs$u{tbO|lOo^|t}jMY6ntC)uy%C?0iYVaPxEF6Pkoy~if0 za_P(P0porVYU0>28=kw-MgaC$qiN`it!l>Mbw9HP+1VoUJRuFE?*6g2k$HsTA z=a%M4EQ}i~3QdPWd%g15Ma!ymN!rd0OwXVBi}@|rM{oFF4U);6=X|T3NKb9r>+^Ne zU*adF_2tGORdd3y=H>&tXUELGLCzKGy4=SSN*=ez%Zo0{Rf$PQk6tOIN_+mJ^T*E7 z+QHzvBO?>*iLg;)miRY9PA`TyQC)q{_uUc&63FW3Hlt*LH`1!ZhEM)Gki9=E>IvG> z>u6;{K2|g2nIvZ3Maw9>=B4Y+U&&chR?Fjp>GG);O{!fQ&;^cSYw~+e*4lzmXUXRH z@8vd=`v1_MdcULOdsXAV|2X!1%u*qQuB4E5+0n5w6IfYNs0}lBLsqO8jQS_K0zFP@ zi5f25_wLoMnu@-S<$p*+1Zfi3U!%Ap9Xu$a3oAfv*GMgCe@W4^K~k&QYusony@2qm zLE#KjXPnQ|1nal34kQ9U3xM~coL&cw|~)1v7wZhMxLukEU@&l6hX!yMY5 zBNwfa_D*toc|^%R*F8Jn;*0(R4Od^X+_ACo?@%yfDR1e-!v4zvNXq+fJJ$5kB~~9x zemELvIxE$#?yuHO?>9KSE6>Qt5j7s0A9&GM%un;Sj*C$Vp6zu4M)CMi-6o4={@ZwF zYa6|9&50Tmz=;v{Xa!;Ne4FI4rxokrlyVk_`Gtkg)_+!4%5oj$Gn_VTM0QD4txw|U zc+G!Ij?0D4H%qFY;O@s+PD99F^wsvM2YH3{ndO#J)8rZA1Mh6wN;Ch1MdzQWnaArQLE93 z8C6WmVa15Z4(=3yI~Xo3E%&yeHg6PUVpZ)b%tQXj93->xRC&sHgO@DcQ03Ee-4CJn zO%g$Y-RaRAEgA(=hFZ8|tV!;Q90b{zOyA6ul;ex@y=~VlGrxH!gq5fzUCAyS54_94 zL>7`1pc>0E<@=ap`htB-JFUQnT|Qq#wx>A4hDzQ;>(V-(JCANrBzrxvu3bX5T5|+m z>9dinO=0qC^SRSP&BQy3#}Uqd;-%EFPZ>4jrm=Zqrxu*yIoT>rc8MJ;N}nUW8D&3d zEv3vNrS+81+THZqh#7qct15YZI@~zEkr;~cn_9DFd#du1ut!XdzK6x?fG?NOk|uA2JWC%Mbc+JaX#TKC=nCzN8cR5wemG_i(_J?ew zNN6PZ(^+ME;6i#mL3v&n!?&`c_;&lw@A1q}R4Tlgx)NqgkVWCv#<}iKRDMl$Q$Yk# z*Sn_RU}st2Xn`{l2xV8XsWIL5=L(41sR5eRhCOi z2AQ_8#ob*sb{?s2wdBW@DlSrz)stCHZ9Y+9;Uour?e<45^W~EIocImZ49Us(`}S?Q z|7#Zk`UR{KZmQ(}MHE^Rk7!|JWAhy9*~`9Bo1K7`rNx<2>n^I8HhTy=P9Pl$ALX-C zkJ4zTLLI+f#_tR)MV8YXH#i>{P!}45)7x11i^~Ny!;gXEit#UA+$ZMQ1>u*Lb|DF< zbG!Pfgd^IY?2)^?vVzwj&YSZTRe!~t$d&EMlP{LByFzV&AAf%@YAo43c7=85em)PV z$N12IahP8{d_l1*R#erK5d5pUlhATfykq6MS!IbYoOSj&U9<$5==C{d z2F|mr*65%E6Oj%{wFxcG_rH&WwdVOJ?JJ@5i;uSk_k6-%1?{NKI>XvWg<<$+TLdrEf}C z>PK_o+YxMFF_|uk#5!LOQI>l#p2ZK(%7Cb~_o9>XY!{_Wv~pr#KKVi^sbb$VMU>pX z&}Nv^;a;z=2lMu;Cs(ZG!3>J*eU>Hz6s`@R$sUXJqH@|{dWdAN7xWvUC$xo+e(+_Z^TDpQe&_~;tTQoL6|axp zkN&7412zx49)+tCIN$)EAcwmVM8t%M^D*V2=R})7$K=;;Q(-fLBtFj*I`~c&azPHF zW2UO5K02Xj8O-_9t&aH%+n&oE{w&FQ*@7@8k+?>vD6yviuI1`LG3lO1dx$5VX8JjH zr_jiu`n0T23q(~1gytfvJAqavTp>O{p_Xh?LCHE@#@}2|(!Y-06W=G2hW}FT6Y5ib zn<;Ty>_4LyruN6&beG;ocq1mNO(`*@%rbp*@Wzb!3gHR4D1)gkl0&2@k%LCqgEX0J z^J2UVb|}h$Fd@tXPD7S%&BHffcif(EIn%$ig5)h%_+TlfF3{ug(*NDF3T%}9%dx5-+v?B`!U)@WhBgO!tYDPDXgDp0 zm6B`ECerehHy)Hsd3@aNHDw%*wcgGZ=l|#6$VH(i_s>biAEoK1daCq?S{WU0lGkfK zC}J@(`<+#L{Q2CY@9*b+y2<~h@Bx0u{A}8vXk#009gB0)pRs9qOT$t1cyQ?^UtX*J z)*RM&yjoXlgKtD$wh@4kM6(Hh5B!BM8_vQkO&QKq`vDpluILGT=lFRLf;{p#4I22q zMmWNxMw$xTdu>59qZu_IJswjQTxX>ue#^dOy+!LNV{`H5$NDW>1#~N=pvtAelUE7; ziDK5a!Xt5OU*1aiXS|*0RVy66fFm0UOZ?B4`qya-F=JPA*eM9Mr<%%|q8dz3pMoVF z!Qkto8xrQOrY_b_ZjLUX>mvtjPaV}AtYLri1%h0k;J7)f0ec+goXgv*ZBk%M!u~3$epOJg_8OuxELJ5U}Ni2E=gi=>JQf>~V53qNSrU{c78Tp+jYEZ%N>yV3vsxfg?7c4S!{dvq%Ju9>DkEx@)Gm16=YFUA z75dxlduLnq=XNK?jdp9gKFxl!iCn4Eo96sUSZh5lSGwyv`&>KW%LfzBu8w>h5e=+t zOPl)~w|=)rUYh#$xd_&t_!>;x&l$`tGUWWJ`gk;0bKoECvcaUdxmKj%6PNdL*j9;D zDpAE}7@xUo`b{Uar{MTQcHXDs4|dFQTQW~Fyz>Pal$fb(mA;|(0C&&7?mzWW9hZc~ z*$!0GnOjcTD1BqOhn#2oEuc^B|8JrD{nS_pZxrka?k=s#045!Vn1 z73Tw8;pvWFY2rtWLY-J+ZE38;LSoNF&K|aXbw)q|>T~c`vVMp+MG3EZc|- zUcpL|W(EZaFDxQ)WW_4zpesmoI7?0{wCW%rCjX@NB>}!D?L_cNr@pkKE{L_nwt$pr z$ezW~6q{0M53yV{ylyCKIL#pP)e>^3t@(a*khwWv>pwN!Y#4JZJhehJrYgZuJ7 zhxE0Lz3uUT$F!)LjEWj;OtXXkhcV55eF*B`gZg^I?Ei64b8-9~)DYk-5*Ls)2PY4R zhZ78f@@K;XVEx;K@a^mXm{5ffGq*`Y(c<4yN-v+;sy)_ z2b2rM3GDDed0@tZ2QWF{YdAQr@1wzX~N2q!1ZUIAv0gA=fD>|iip*?72NX<){WhZB|tkP4Wz>sTPj!vnK%JV1z@9f)Oz zz>Fu%DspfEUpz3=2%Ou3g#f8MoIu7u=y1dXp>g05427?28L11P{zi1F%DY3l1O_mNPHVM*mpde;wMtZUflF_0Jr4 zJ>@AH+nfJSQ=u4ev=TU3$->SJbWTnvh>HiT58KeSbOmvsv5C5x!nS&Wo4{7FvD58- z@bx83J}eIQBpRCxaN^I}RMf%J4mgsD#-`?GZm$7i2X?aAU^6Fh2$TM%ys+8jdP2Er zAK1imGphh)yquL+g;B>*Avin!@wpcUJi!qQUOzpIWYVFxBc$x>syoY zpOX-v-R&OubypU@+p-4E=<)n(R%+C;wj*DAw)$<<1(&H}CG4Z#h&v*Y6+HLHkFs3J zqbS&99=QA^?n!ad-`#Q13Q8UD4v%XB!*N%JBVly;p zKb@Th|NcbI|64u0~d?2%l_wai$8~mFv4Gxy$1GvoK}9Tv@a520vEg%JSIHPM|YQ0 z+RKSBq_8MC$S-LQpQ8vi2h8z>`CW9FhP8KLadUER&6my`Ngp`)q8}%e3e~UK`cTbG zd@yw@emw$DF}hbD!&)5q6DckKja!A{&=dDU*6~9g**t5_5jMAsZAL*{+olhm>y0e) zEsTbr4t{R>M3iTw4 zUm1p6CBBq1Z3{en@E{f}iJrZ9`|O_NsZ6HWJ$jKPBuu;qoGK2Zz_bJqi zyKl0bXqiJoV({aJwisU>Fe+yv(Sm}&dEfh7AKo`_H&Sl)+$^ot+r-i}rZQ~_-+h?T zZSEX3U7~R|8PZ{WNZKeK2;U~+QAvS4bD1-Te1X%vr1q7T+1S2M44qlJpbl5fB$g+- zWa5Y_(C3T#0O!CX-9A0;AINk*ao<&m1dyeOX{>X5164}LY~80Hlj9w;*LFwi(^@`v zxBSk|X;6kQ|8CLCzd>mu(DD63O*prZbtqI`P^+~kJzLOrK;Hp~NIpTHYd#AuV_BP`%oq%U+xFyBjtNsOYth!#tT4y2C{#E@VO;tTZt z8b%V~9Vqy`{?YgG=OqM~LtOqK?4-s#CHvrD&Y z`onMEV8g)Keig#y`po*+d(nHbaT59bv(cD;hqt?(xls<{jMiLtIeV!XPuqL0aKDni z)cigkM)a3K_A8S$?nUNjLw$}_>7QJ;ZPwhn4yRT~o^GYL#Mn=A*(8JIi3PrUX_iH9 zhoqJ1^U$TK@hv%8KG4c_{KjFQLTQMhw-%X6+%I>pAT#lC@sl=T59VTMYb+#|@m; zvdKS0Cy{+33^bc(zC<1NMY-pN9kieB#nrAB#Em!+ z61F{iNN4fm)k{TzG}%XL@7!2}ALMqrY-fL#jyEP??RM>6HxpE2k>{07cgZBoA9CG= z=&66CeXAN7I;BHUl(^<1*ZrfLX_!&?o^t3ULW(H_qb7Z|^yRKCz z6`#YA;f5|x!n1c&a5V89!W*@p((pc_W)Re36HX&V?T+=Xhc<=Id6HA@Pm(7Q_LRFY zXUP8;p3+ibU{Z@^EY89@Um5Aws9Q=Up(jS8*yC=SVfYa+w&>(N>+p6y>b>|gVyw+Y zfkDK9_&=Im8d5uFS2#_`rKso|4LVBr5H0q!-Y4ioLCPU&5BAxA+1p-f>mGbrJt%SV zdAq}V5Sh3vSenY`yz#}BsLB3M;_0)U8cgSkb75x}ndT<+^EYdz%UzvVtg`~2JX{v5 z3xwbO@i-?w&((M}|3PO_DcFDUclm)-r>D=y69fBVRnTY8ved!!hG$@=uPV~3Kdq&H&!P2UocgrM?=urB~jKvd}z|j z1tQ-vP7-{zrudgru$X^q=BxYRFh^8w6zilgugZRs53cIau0vtNAxb0AbZ;>0H_e@u zt`WAEKFT{AzF5DM_jdsC>v5>d6U2Cy3)@uhl%PY_n!@A}DZ75M#|(R4h7 zpp%iS*e0cX;L~cgQ`*lVcE^mAq;d^rbys7QoN>D52Lo36RwMIvBc_Hg;UXiFEo3A{ zX-_`k3`qpoMZg_AQmN&Xs!K$6nK{Nbf-@PW<4m`N>l@Nx3jIY3h2SMRsr4gZIhx63qDT3%< zD(7)wsAAs-57Q?wG{h&duMQv)!>9s*dBLCH64B!k)U!!bbBJOTHL2B1 zWWGs3_vEQ#U#^alCvP({zjv7lD+V4RWZ zIlH*tGmbZ7FjFNqi|5@(Ckq^W!3@F6YEMOZ^h=XPP+vdTvUA{dHL_wmrkCii$fJ(1 zk@ulPL5;;Ed@hu%tz;Xr9zxuPMSX9}LYKyROMdg0^Djl?Y+h{7|6D|X%8f=8mag>j zRW85D&1c}F*IV!r5f*$EjnoHUG`~@cj4h0e$kA>3m1mE+loxkJAx2#?1~&kSpieA3 zK8E>gMfTS>Lk-DlayGm#)#H-|SjIx%?Q-~I70136eEYo;&%7s|0h)RIrM?4m^0nZk z)zn<&p6cdt&AZ9gmPyHZ)h{bwC>Bx46t74?(Y`!Ng;8U_rJHBIDlI+nhj zk8#@hVjG_fc9!~0qX~jqaG3k!I26>R$4F99!9p7R1`9tL2GIxFg^X#r$jKCD1YLw8)3CQW;1%6L5VGO-N&e+rdL3xV1;Uk`)B6V;zLI z+b^o3yC?-l+qpYD`si|f)u+u4FczrNyNQcs}fmN)xJScevu^d}TLA;lzAbRmgjHD5EfGp^?(O_YKO z{0W=IM{Hz-ecTkD6rREUs8@u+R8qpdbA59qv#HGjwGEI)4XvJe4dDf0q*}y@uF_~W z(oNr^CNa$=`D}fmdrBtbiCexzy5bp=LK_WZ&o;;QahlNGmV>uN^SUiKqf^qv4T77a zf0_D}M{QnhQsmg5c*NGz!AigJ}uC2Bwh5FAs`58u$bEf_w{mB zhqx)O!FvM%TomN?%Luk#SUz4@(Y%3??zpUNi=K5cOH+?~@mBX*hbZlZF8z-qEp@*g zgnBo{u&s_vd2uDG4~t2D4XgNSmDwPQ@ny0uSCrZ0xugjVbJ(!d%>L^I8l+(qqU7mi z()-+0cB~~dj^mk6Co@MS*|GCf@fES_=!{OL8a1x8oS3a1zQX7Gh4RG@PDx_mNB@s{ zTk#(8$nlhq{2x#D&UP(#sYat+gul%deNQz^)osxG9Q!HOkM0j;^q5EjlNv#xH2w<& z+;{Q9TS`dgVy*XVEQiISti?4#W=XI=uU=ROnMqS3!w-=ibfms`5yHYwO7()o^!^@# zKYjz>2=iveat|jjOd~*kG{`<}S`tpDC<__WgFK_NJj|bqY0N%)fZ-r&$V0R&f)Uk9R)Dw5X@I{?J@Yr<#Xc!f;muNejeB_%)bQe3e$>q)ee zqqKG-v9`E;H}r~?ChC!PT!~iGjI#+pJ1UYGN{kEoVSNtsjEB<9|7q>3qvGh6eQ|dQ z5@dh`NN{&|3mz=^4DJ%#-62>4!QDN$I|PT|&fpq6LEgYQ=R5bydF$P~*1PjZt?JrU zyQ-^q?=>^sRX_08W19@J!K8SBRUrq_%*EqxJ3PNh5LP=Lzu!Gxd!1ajojmH)8-Wqu z?>g}s4JXZTrP{O+`LsvBS*bZ?LgfJ6CGt9f@pp$3XT8mOWw-Ok08V?Ubi>ME(v5x; zpM=)ix|UYF2HzG) zY*N5^O7wAp-28$9ju&C^1?i6uB^8gS1wuZ*HQK#*T-v$Hb?PS?+ym^7nslNpxk}l} z=NtMOJ|4MmYHy}E_vy?M&Dye;H{Y6Urs%94Sll#WKg>d&DC*3Rbt!bMzyr{VzUqZ;0*J$q`rg8^2ZwaT0LjSNq5wl;>*Yb+dlnSBCalv zRTRaBOA|tb>)^*0_f~s>NUa)T@1AxzCc_W)58L>3@0Z+;7BIcG_AQ;r8;n3-+P>bb z^$UI6BzV})r)$4iXVSd{$9RKn+bwPuXxbhIQ|aDUXrC83C%P>C+-ui){9SH_J6mQ%yVXm*9zNH(=>jexyALUxn`unYSt^Ch1FU z3Emv8F8RE^Tt8L!BEKD&!6(-xZ1q-yz39H$tZjP7H)hmzA5;oOQoKEcOmqF z@AS*AX-T<`+dX=Q<^5eNS803IVPAc_-Bv!6chy4#tUjyHZ55NyV`5wdr{{eH*J{JB z%@RwE_NuEX%g5QKnR>O=pI5&$xV+6a56gTSjxN+AxES?X8-DnDhDx9raSM4~)p%nF zI(i4cN#}Wd2fu09TDz*~LBzFV_yH|UdNjJU5cd-Bi3UFWI@D%@X7ZEJTJjexW&WB| z3@UpO#)k03Mko|O9DZCVjHoagQZ`AfL>MM2N<}7Z1v&7<3+zlIbai#1)9o4ZV?bp#H>-qJ{0$^ zGQ5Rvg`T-ND3sI?n4g?qu&(~R*rZ*CXoU`>(o#G+KXN%)CzBFC%eZ(|9g!<4*&>rb z^;V;4NSX7q8a@Y3vYOw3P}U>z@9Z6Jx9put=OuO%Vl(N(s1x)P(M2U(#}3P%WSQDB zsOHDtw43;NM=;{!KmUy64Y8(L=8?;H?ntl-C!V?gsaK1rS5C-qH{ct5&vTtgb0F>V zns1ZT!f{L3tfD1~Cj6SdY)q(JXz1NgquIN`o_Mc8HG15kpc+3CV*fKCE%!xVj0xjW zY}0bS#W@=beo-9;vg47Vn9e-3$y3gg4@)3|mDz)4^OZ7$ zk~ttX={5A5*KF*Y#w}mt^SCt;fMOWpX9;WT=12^IuR4%QBmH|eXoi^(R8XX|>4RM* z)RZC>g71V1M33{naQoP&4Y$-fTB;uzX2(d z@#`Y$N9u@RbHkL836>C9gvD`hhQNXsv+dU$=6&7Drzz3bt<>Ji2zv3|6Q(3qSZSWXQ#8S^4*8^VFj7 zrO393Z#^G@B{jeMFh~TLExp1$N6)@q!(XuevcH+Ri3r=NQH&vb-Dip!GeXXv&Vw&N z_Z7I4=9tuY)fi0W5h_|t5{6}><;#Q63z)VPSAzRYMZN?0Zk2#ug+tR#pS5OrW3 z*ruk};+0ed$3ipbx3FnMT~1kZQM2FDN%`gUjinNLF~%Xr4>%Wz zYZ~HEak2I{vpiO5PGdib7#VW?&3Q;=O1^03GffG_4sKU(ihCm`pDR?@tnXS%q!GG}DLd33NO_G7N3RR^AG5y0^lox-uS zB-xI4DYv=b@_bR5ia> znd7BznKJ=oKdM!mFSfe&XbTIq%{dv2k*e>t*g(IJD!K~TV&>T*lE9^<%76V?x>8Z* z4Kl}@+SkhsK>8X(L?R*WfbAzq>oWP@b0#a~t%X)1>&K&MrWaJ^%X zwpJ7bu-BBeebnHanK3@t-*eCwI3la5K>sqa-IivIzKMSRjg6nB4;}GWqMvjI@rm54 zL?_yp#8@@H{?d=zx4H=I%kh>&>;+fi2UzwNYox0^M; z_ho6y%T(1=Oh~eQx??9gNc3S9eHVIPS*|Xx$<5YURd*BPJm*{4w~&_939?#^CGr(= zD>PCid2DH_Jk*tGQpy$){hkU|lz3sH+>Q6WA%V=b49LQ&NJuzLXV{GUa@@FTeLTAW zhpj?fhf$UTzEMR-V?S)rs{~cHB6-#?&^KeU-DW6J9+Fmw*7Kv#swrkimd9*;2b+Bj zEaviuik!Izzf&+%g5`OJ3#}If_XLB}C26S6y=scSEcNtYv3yA#{C-WQk%1!Ajp-=% zJ=Q05bV5t<2iux#<1gA7swolMj(%99GjBg?SMAKWmu|7BhI3h(H_?u4f};^xID(qm zr_~8SRd>;}@Yj->2Iwh?NlL9B`cHPWci$_%1lc=X&RGMK7x(uv`IPt;$ZcdlZ_D1j*iC(_QMriuVW)FbfK8 zf?7)v4T$5hb&zo-GAaBupkCn+g<T(L<0%lkasy zmecjk)0;qb-N$4e7v**{Ki_EAupgVNF_3z96ldd_tLVD|6$3n@qSM$O zn&`BXjk=P=br1!3SBzD9S$&lmFIKdtJ4V8H2plws0n&NibRFSCdu2JCz30Jy7id({ zWuX}sm>5gh4^v!-!pz?;T2YD3_&xBBLMS?RD~=yJ+=Y@xS!?ON_e|H4sCC<_Z?OOe zXO4AyV_s2fZ%c(GW?g?(z)E+(ijSpwj>nlXgf)|moAjCOuYPo{@H%()x5r|AUSpg3K^t;$j!{GdI)r9Mx z+%f{=rMh23V9STb=|^seFdP!j&)Iiyim>osi7gvu^8wLQ#EwK%Gi8{oNFOlt3+jiD zGNlV5E*4rpwxcijy)jd^ws2{oIRdb5K_xnZX^;FxN8)%`E#+J;bvBQx-q%T3h)bf= z62Dj>WCjpyUW)WziKaDBC^pq?<@%C}IT*5HiDPeQfSsFNI1VchEBTL?{EL;NJ`j|s zLSDsw_~v~O>*Y^!E}xUL8_1fPBCCiV_0BYG@8Ndq&1HfE=M6EiXQpC*f}8Dd(5+@P zQovkJbLLwp&omN9W0+_UK@k_^@TCYtiUxE(_abS3>XhD+Qo1HA?l*|-gL5gnM1I7X&r97&~!cBtOxQlew zQtCaE?TG|jFWO9K^$J#dXMPdyO1iw95z)31SRQ2@+OP~^tZ8+5R5}PX59WXKy*eaE z^-Iyk#ax^lr9OP4$4M8WH%K_GG%b%X{A|27=IR%%5O|gs<%56~rZHk#73_>`R24!V z!%W=k()o1d*;>kQmVkM&!Ao+>jJRgsPbA-D}@e zQ_WA#vRn9w?t-9y^%8mp!kmg4VTC53o!}V2l9-Xa=nwEkyE@bBL{~bPW|h&pbEhy8 zE^{J~;d#?MHi|3PKAzK`mloGFpqELQ|B!?|OyMx({oUhJ#%6xt*(qV=ou3`&SCp$@ zoN64TGdLus_tSbrFqmV)Hd%0B#zK7Z?H0h5tnYrm?>lDi@Z&3|=0yPjh(Bt@>q5|$ zp$2g|sO{zar*hdNlJeAfF0Zx0QG%v)mozaUn(>%K4OOQ6408AV@x$pj<4qdGcP69a z`Z%LiriHjkxJMy6lGjl`&<`VR50;5N@dQNKlL^}GmjErxmp@l<>-x#RuZ*66BhyW) zdw=|xH~;o+9zzLTjY@ZnC`@!rpF!#EFy{jpCC}l^O}bwfwVvs&6N<~lj?B#UW>D{i zJE?~Ci3|SlwDa>o5d%3wevi1>Em&HPxNt2VqLspj*zSPAitolc4`?JBH zhvFu*Y~vYwa=FuOW^X5H@^W*>X#(e&3E-Vc;B))Q4XHOU{beaDm0oBL2sA*Cij+<8 zVTC!`8QL3i`b0pxe?@I-OFge^R4*~$xj)a5RADkEHX z+G@x*5nZ-P*W7jK#jxWY>jK@1tc+}ZTA_WRR5xr^@IV%oV>gY8;$>R+*X=M0#(uP4 ze!;G6>5+6t@3`YfKhtfYy8$b9`>RDeDElLpT9R7eSgVxm*uiH3a2vE=)JVd0_tcuR zty$I#P!Kw8?NU=M$x7#~v;xB2VFYM}$`6%4zK%3k&A&C+LEDa($y?x42&p( zA`Bw1q7NgXd@UR<-BBp&9Tdjg3Ms$Jjm3)>6_tnEsD67r6jn(rOM7-#ciW0jSg@wA zj00q$g}aRR%Z%~W{TP~MMNwq2Y(b?BHiF{dz+ z_Zms&+?|GvE&N3F-%#Ft4o5fIX<;WK-X+yZkvA+SQDDWrD0G?Qk-p;l#kZNH88S(1 zwS8^>+hbqed4$7f3(J+`y0g*qBwY>_JVR3AvK%tmDqv@ea;#u+jo^J}dUF4`;KgkZ z^gazc#ND@F$Ku;2zd~z9@DlSBrTf>lNP2{*)KOe2K659)xrrZ!ssteF4)K@X9|^$Y8Ywuu3QX8Y#AiM9za~h0A?aMYkVX7?OVT4 z5)}Au2Te8K$_vr9*K>OB42`V za5z!~4#!Gf&V*Kr+SLs%Nd;^sXP{X4dMUT|N*gDs?HGE;mr5$;r&I&g{`Z0JYlnwR zjy+w7OzN5dUt}@OP&2_d>GpUUgi9}_G|qJy=Pk9de$Kv(1@RzorUa%>*O0(2_7Zj& z`PxkRc8xIhLveRHpb7u(e4Pm;4qg1R-=LEI@ysCs%Olws5CXdn6-)e~!PEZ$gwGhP z6D}mq)SrnspJY6)R{3)L=(zc4wZ@uN=tpIK zSE*tub277+l;PwJnm8%vLBr@Nu`jrHs?YQMi1KS#uYLUFrmBJg<85Q>ko}M=v?EztRr2@b30ye}bILdG3!q6s+bvS9Y|(qiEQ^}` z269bxw(ZqYmDP3=x_TwUqS~aSx}-@M5%beO#PK4){lzBN-)l$N$6_7t(71?*WHGNV zF|VR7qx$ki*|Ml6vDrOXoFi;s#$smoR14CBJOP?%zNQ2dXep?e;V_KtP({AU!jvc+ zU~6i}=ElXPnHA%Y-}n|=O`5t*O>`#i3*UZYYd(*O6yDIKvAf%yJ6x}#!5|ys$MwRV z)=e52hrRIS6GM-^zw#^h8?}-uPaHTHitCY!y@AX>Tq+XNRRSe2)I6^G^YmVr%?qF+ zqy_nHS#{rTfpUxn`Qa#a{hByTeA8zJkH2nCZzya)fSfrI0&pi}Y-?;+pq`~D><0V((VvdtgLQzFL2f{k?5 zi51%xA0&0WuAv>JYVroZWfW(9oZ_nts!}M&mbK9=Lkd+E46SUyz2mDM%57hbL)>ElM4Lq1;O-drBmj_lC@h(Lkb5BvG-aPjNkf zz+0*B;CzQ*%FTfNH;VKW{*?O$ohCIW4|V z47As#K<{cptFebvq9bmhXpKP}FHmkA#=5^)`_qqx*Pu}xIh|qqZLzc8ciP(?b>G{k zG3#2X%gEbOZxiW!V71;zLk);RRsS>+Q@f!Bf+A5x-WzcO0zpA7bcY%^@EP$W_Ue$&<)68NCOpdA18(FbLYczH_d4 zp9(`Bw+FkRrj^dvUOI1VxM-3lm4B4;K*aN5Q~p3Jbai@|-mQH`9<)IogC=%{iALS8 zV!Tg5`_Mi4-QnyJ$P(YaT1h|2Pg04FA;$3`7A7-_v>c-#(TXaSWF&V&ceC97=*m{A z2jN2DGJVObF$D93Tit8&M)qLryN}`n<^|#f;$?=TEqEnG&}HKyY-jX)E9cLJQ^gIT zoiKBoA)$AQZj#Gl$Jjd}J5W5reMOZtTc29}$t##IB$;aAFi+l|*+_GnW!mf#bJNa2 z^(^9abjl3oFBrYAW3YLj3Mp9Bx6-hqQ{?Zmc7Ct(v38b&^Vnw2d}Xq($RqwhXP2{< z;%C_ntXFDvOw3H=3C|L{t$>YNFmE@mqPT>KGg0L&Q;X=ek``1Bv`W z=L`I~0oAIU6+t$a^{nUv(n|@eMPc`!9Qp#W<)F@luzvH6VIHi4zph-{y&EBgJ4Q$h zv)tF!YheDsp3s~;f+ERAm)Ra<~e?23&@csE!7OlmKdsRNGPMlL~=dd($I_CWPiEop|3j8;!o_s+@jtZ94W z@@m6W`OICdg+lLc$?S~Hxc49$zrw5BH45(43t3oRMozg_`W2flXDNfTfO`%m>PF&$ zN@CJ7pT=ADDa(8fh6?A_m0N_{rUS(E**$V2&3nJQ;GeKy^vkHNmqoK|I}SSz711r6 zSHxqeEwm_ecL*Okyi&cY$NP)bK>N+=tyvTG-~VY)x61<@3GJ}94x1;ockkG!8{%9rl@N4_d zdFEDeHKRSaLo*!s-6EN54*G~?>U|^aOG&_J?XsZN2N4Db7^xQRmMh>{)858TK?GNB zI9JvNfh-?&5L*VVo|b1s-Upjh+r%hNwy0rFTD-uucr$2M9W1|rM9SNeb0&3R6`5M` zVXIhVe4mC>CVVHg15FWZ;v_gy)ECJi`Bb?q;MoL9cCPn7&EZkrC~hU5{~i|i($h3c zNDx*+@%`SyP0w&qHD1y{i;H0YMvPvBKp6Q~;YJM8oprBzA}FKc!ydn>u)x>ule1>C zisUQ*+}Tmyjs+ZbcTJ6SJedjXT)ekiN=0z^G*dvEJvvlU{2ww0*u!zrU&^V{LXh8$ z*%Exqv0hMD_!>grVg>8hW;G@n9}THNlwdB0w1Q{Wj;>zMB|cEcQ4s~KOm8BK6U|iI z;Mq=-=2MO$5$(O_J!fL@YNrGpS{_=;bN0N%9YMYct$&r`vCh_cFcH5rwaeoa?uEeJ zE2_@pzkvJN6DlX6R=MgGy}MjC{HH5j>W<%7s7uzCJoMv(L##rAuS6}&DMozhnW&R7 zgKtD84R_Big1H9gWAUA{Y>o^Q_ zZ;R~sMMjHfii9p%n|xs7H2{j*8H5R|qji%Ftt;i#+cMFz;(C1*QZLltwv#sEQde5D z8rT-dS?GefDsVIY;gXFnqugiar{nM#NxO&}sh>B&Z|AGB!_@elXfZk;?_?4YtQ!&zb4gFN>`8Z}r78W;uoYO4^P+zVIKocK(td_B^j@jbB8l z2XXZt;~g83+wq$$e9Sb_pBhctk7kG-*`hwV-xY*e#%`f$dh_j#E=P-Fu6xr%;H~(9 z)=ta~xr6CUfrH|uY!WaAv_w2JZoc(at$Q zN?PoZZ_Yr_Yt#$Omj2*#KU&Tmg7A@E_zqpDRrSc#f}_z!!d*Szj#^S5{u@Ck)Llth1Op1=z%zShs`ij8yiK{6Z+}wBVJ7O76DU)|#quZ_O41QBSsH3!Ow8Dq-m>_b568qMkq6jLh9InX z$+P1j2T@jE5wb+h;O7VgW4LuO4!X@7munAfwJTo`*_A@OnUm|FVB}l6O8qt}fL}s~ zLXADG;-|@pmj_903*Qi-Pl$J8Y2k`1);J(@NOLD4tiHc_^8$UWb%ZL zpaq{>>c^e1oEsLDCW09yQ~~XAe$TCddy7xrjEiqlR#QM}m$>G5xSfkDOdvlc%wVFZ zie~UwCsJJU`QVgkw1B|bR`K9%XJZ>x(cW$XKVu9^w;3Gx4pBECo&L+-@xePScb!De zJgxE_%f@>rDhYOF>Vo-+ciL$m3r1unY&yq&o%OYM7+gbth6{1F#_LrM#mr*%bHj>3 zCB;!d8*re-`(zx~W+pq>7o1HsWCmnqC*pslaL(kQ*qmO8eZD+(M8(iO0^7H;;HprG za3l$N%5|c5vXU-v#JAuwZM%FwULHc;ax%&n!O3ehHHVQ95kx#q#UD zzk^YW57<*PE};bqxMhuTQeMB}t((Hs>%2bR3lY`1oy13_X2L?GZV5*{ zCr(3&P=*@(1dWAQ7{N;TsypS3tOG2+bE5mpK%(pOT=E=wg$Y!Cc~R{6_KeQq8L@XZ??e~}i(*&i2%)O;&Q!_46k&OEqp3r7lw}?uB0epG zK82Bl9uMMizR>gfeU{*)kHr-D_LLH9dgI#IE7R!77!zxV$($cSegoG`oO=l8gz%7#ZOwUYlpyR`<>eEx4Q$s zKd&kd$K|Fu!gEiLE*a`V&x9S|W;6z*zz||4Nh7bk>bzQr5}tU!P2h7$E;NxfsQgnU zSQwptLuui8A0#&@UK+=OURAwX!6FFPV zUk(ORSj8=yD3nVM)jtl!h%L5jpKRXU^l)@ z360h!#|mR;2Mmo^yAaZpOc5ypm~6Phg+mch_owVZOn}qk>xA}%fUo&(6q#kPVs(e) z_Cxhz!eh#@@t^U#OnN2on+O3(Iio(aMp@{#Fg73_iF35^7N@gbvFj}IDwxR0xj32% zXzfrn{LHz)?oaS4_NX}OcJ_T8b}zPQcbsi$rC7k*^B815Ov6&g-Y# zY#C`EY&8-B@j9=~rB@Y)NmXAL))&1D(3hAsM!6;pfldQuT&7)QoRT>zdgPNDZ&eys zT4vG(jrG?Dk7U96QMZLJ$`FrSQpZm;#qSnVmn@~Wrrup=HBTgOp|77v9*5ZuP6MyD zQu>?wcukki?42H;K| zIZh-DD?&%CWFk%@kB2jDz{hDzaC^DmCMx$b3OMxHcKuYnmp}U%Bdxtr} z>hSN*re#EyLnK_i+KC8_7`}d*?i)C=zfRFs#Dp1zyl;1uScP)QjS(Bsk_~-5Gih{d zww$h=c4z?;ov=m0pIN>smcz3zNzAH5skN5P8&T8ezn7CEP%H9kXA`?rMrNIeuk3Bw zcweW>QDQv-TeW?M7!mT8(xgbosoTSqqe@qepn@xNa~gX%0pzKFH4&(Ah@mM#XN$9M zD9T0e#pM(7K*+@aEiQ?9b#)C=Y5gMoj)#y?(wJb%`%DtHY4tJ|Y=7`$Teq&S>3&fG z(^=4{b=K?U(nfyXz0XKWWYUjU`ALUqca?(u+YR(w187sYE68KOG2l)DXzr`^=(pTR zi!^QArJ!OC0Y&0*)$;k#!E)sD&Lp5^Hj%WwT&9*)aJ^PD-k6WB&!^PHzL~H&B?rJ_ zh787=%_e8RsE9nFc{ye{2iJ`DZ=*Y zoQAPQ1=_fPKp%PnU?~{4jb~<@1${2#YL^{YO#dPeCQ8BK$2wKS;|DFzQkaY^_unB1 zo^Vo|q<}A#t3h5m#B9rXvnwY!k&oaGpY>Ig-$PX|gOOt{1QiV$ZRgXu0X!OvepuSGllEY;01;vXXtQ>Qd62*dMUE z8P?pWutl|9{Ef7)Nw;o>L8o-J#wNQhpe>41ynUv<$Y*LdiOK`xL~zA!=w~U|Z6B2W zc^v~WTHHibwH4Pq`*eL{3XHcCw@X-7iF}mHk}ir=O%4#n&4pPBrA8^aq!_Rruv^Mt zi8iEK>fJ=9R|Xg2>L|0zsOTQQ8#=Ve*Df^C$SD|{66Rt>e~>JPUJm?mu_EZuf9mC^ z^A0yAz1Z!tV@zJ?==Sw5(qFST6;dn2ZjQ%GMQjD{+F7r!H-$*=B{u5skdHsx{&1Y; z0F$}k7>`m&3C*8Kb9bl5((L+2ItagWwtzFW$-3oW824>syvm*$(1pvVxm<|5tfY~r zQ402bfg$nX(^!fZ9!B6+EJ<8K*A5E7+a$p(m(EYF_`Lgy*#UXovv;773h?Cmfj^2I zrDb|UE{{B<<8#mNaK`K+lGC9PH%-h4c;b)W_yv>4z?bx1ANNEh);VLHiTmH)CbxkZ z=0TA3GjnNo2au}!J2hi>OJg1&jgTM;zmOpW8xF+a zYG}t`^4#6q5dbOl7N8VUk(Z==QgG#UwYIZ{K(+u}t*vYvd0ho)o=tcm{F9i82Jo!n zWGO(Ssh|XKvbD9cG>0@1XXIgIVPIjS2befOYSCS69V`JXjGQ!(DII_&yebfgo_|aT zITD~Tb8@odWnzNBJutekG1@wqGO<9=8JL(^nOIpFAQ}vgZZ=Mat_(JgR1km9ftYLl zWoF~Z_#6|Xv8^?exh4|}BQw*#9Q~^<{t1WX$+4l4t+SH=4Kt9#h|>_r#Q@>~F*C5R zfLIwIpdZW(Ko%emGY<&F!D{p`M|S@uz`uEd3_x75K{5d0cp>ORKxbo+g8+@Fvz3** zxgFpMhDgc590C;t0U8H9otx1=MxNq?NF*IVAQuRl5kLZH{)Cf5!}QPO{Qt)cxn}?O z>_9H`Khwhx(cx8qG@&tZ6Nexx2}1BD*ch0(7?`=$n3;K5Sb3j#c3x&?ex^S(A&UZH zDh7c{hd`(Q4^01y=6^A@bx?yW6+v|yOB-7k8xcD@NJ9a`r!@S--?Py_b@-W{uH1jg z%Ku)T4DA#Y{@&yZP9cavJV(VaS2wC)o|4uR!WXaM9 z@*5F8B}Tc`~MdJAiP;PfNzu;U7L!LH7T0CTL;o=J1F4 z^YD}TUq=6zMerFZA^g1b@#)a$iTuAKc-Aw1(zAUc)=%V*nV+M2cKPi5nLIl( zd{X}Rz_XdelMMJoo&$f5`I&p3-sTOYZs}=NLH3QOt%z2f_h}zv=3?fCAQVA>m>^pi z4Kp(hL=Cdl{WltFPj|xKGOqBK-{&)W4(-{m~Oa3~BuH zhYW(S@}~@v^#71S@PhvI!OX$I`KOG9jT_R?=!VPS`W4ENYkjl^qd?FAq{yPAYg|8CRKBH5M-?ZAV7__5Uj+frgjkQMH>@az&~+j zWW)hF{H&~!?2wyNL` Q)9T_xdHq^KQ4;0<09|N4qW}N^ diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 5089ce3c7f..cb61d4aae6 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -188,6 +188,12 @@ private: bool _dsm_vcc_ctl; + /** + * System armed + */ + + bool _system_armed; + /** * Trampoline to the worker task */ @@ -355,7 +361,8 @@ PX4IO::PX4IO() : _battery_amp_bias(0), _battery_mamphour_total(0), _battery_last_timestamp(0), - _dsm_vcc_ctl(false) + _dsm_vcc_ctl(false), + _system_armed(false) { /* we need this potentially before it could be set in task_main */ g_dev = this; @@ -672,6 +679,17 @@ PX4IO::task_main() */ if (fds[3].revents & POLLIN) { parameter_update_s pupdate; + int32_t dsm_bind_param; + + // See if bind parameter has been set, and reset it to 0 + param_get(param_find("RC_DSM_BIND"), &dsm_bind_param); + if (dsm_bind_param) { + if (((dsm_bind_param == 1) || (dsm_bind_param == 2)) && !_system_armed) { + ioctl(nullptr, DSM_BIND_START, dsm_bind_param == 1 ? 3 : 7); + } + dsm_bind_param = 0; + param_set(param_find("RC_DSM_BIND"), &dsm_bind_param); + } /* copy to reset the notification */ orb_copy(ORB_ID(parameter_update), _t_param, &pupdate); @@ -737,6 +755,8 @@ PX4IO::io_set_arming_state() uint16_t set = 0; uint16_t clear = 0; + _system_armed = vstatus.flag_system_armed; + if (armed.armed && !armed.lockdown) { set |= PX4IO_P_SETUP_ARMING_FMU_ARMED; } else { @@ -1448,6 +1468,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); + usleep(50000); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); break; case DSM_BIND_STOP: @@ -1695,30 +1717,12 @@ bind(int argc, char *argv[]) else errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]); - /* Open console directly to grab CTRL-C signal */ - int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY); - if (!console) - errx(1, "failed opening console"); - warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1."); - warnx("Press CTRL-C or 'c' when done."); g_dev->ioctl(nullptr, DSM_BIND_START, pulses); - for (;;) { - usleep(500000L); - /* Check if user wants to quit */ - char c; - if (read(console, &c, 1) == 1) { - if (c == 0x03 || c == 0x63) { - warnx("Done\n"); - g_dev->ioctl(nullptr, DSM_BIND_STOP, 0); - g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0); - close(console); - exit(0); - } - } - } + exit(0); + } void diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 133cda8d65..bd431c9ebd 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -156,6 +156,7 @@ PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ +PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */ /* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f)); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index f7b41b1207..42268b9715 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -257,8 +257,6 @@ private: float battery_voltage_scaling; - int rc_rl1_DSM_VCC_control; - } _parameters; /**< local copies of interesting parameters */ struct { @@ -308,8 +306,6 @@ private: param_t battery_voltage_scaling; - param_t rc_rl1_DSM_VCC_control; - } _parameter_handles; /**< handles for interesting parameters */ @@ -544,9 +540,6 @@ Sensors::Sensors() : _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); - /* DSM VCC relay control */ - _parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC"); - /* fetch initial parameter values */ parameters_update(); } @@ -738,11 +731,6 @@ Sensors::parameters_update() warnx("Failed updating voltage scaling param"); } - /* relay 1 DSM VCC control */ - if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) { - warnx("Failed updating relay 1 DSM VCC control"); - } - return OK; } From 35ec651cee89081ceaca63a1641541d8ed0a1467 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 18:07:25 -0400 Subject: [PATCH 70/88] Remove unused IOCTLs --- src/drivers/drv_pwm_output.h | 5 +---- src/drivers/px4io/px4io.cpp | 6 ------ 2 files changed, 1 insertion(+), 10 deletions(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 52a6674031..ec9d4ca098 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -118,11 +118,8 @@ ORB_DECLARE(output_pwm); /** start DSM bind */ #define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7) -/** stop DSM bind */ -#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8) - /** Power up DSM receiver */ -#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9) +#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8) /** set a single servo to a specific value */ #define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index cb61d4aae6..10ab10ef31 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1472,12 +1472,6 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); break; - case DSM_BIND_STOP: - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); - usleep(500000); - break; - case DSM_BIND_POWER_UP: io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); break; From 0b935550439a17856f5218fdcd6be8b864cfd346 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 21:16:55 -0400 Subject: [PATCH 71/88] Tell mavlink about bind results --- src/drivers/px4io/px4io.cpp | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 10ab10ef31..960ac06ff4 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -577,9 +577,11 @@ void PX4IO::task_main() { hrt_abstime last_poll_time = 0; + int mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0); log("starting"); + /* * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. @@ -679,16 +681,24 @@ PX4IO::task_main() */ if (fds[3].revents & POLLIN) { parameter_update_s pupdate; - int32_t dsm_bind_param; + int32_t dsm_bind_val; + param_t dsm_bind_param; // See if bind parameter has been set, and reset it to 0 - param_get(param_find("RC_DSM_BIND"), &dsm_bind_param); - if (dsm_bind_param) { - if (((dsm_bind_param == 1) || (dsm_bind_param == 2)) && !_system_armed) { - ioctl(nullptr, DSM_BIND_START, dsm_bind_param == 1 ? 3 : 7); + param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val); + if (dsm_bind_val) { + if (!_system_armed) { + if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) { + mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x'); + ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7); + } else { + mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected"); + } + } else { + mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected"); } - dsm_bind_param = 0; - param_set(param_find("RC_DSM_BIND"), &dsm_bind_param); + dsm_bind_val = 0; + param_set(dsm_bind_param, &dsm_bind_val); } /* copy to reset the notification */ From 518e95ce44ca586a930609fabf551f12001a7b52 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 21:49:49 +0200 Subject: [PATCH 72/88] Hotfix: Fixed Windows execution of sdlog2 dump script --- Tools/sdlog2_dump.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index ebc04f4d03..838da9c489 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -105,7 +105,7 @@ class SDLog2Parser: for msg_name, show_fields in self.__msg_filter: self.__msg_filter_map[msg_name] = show_fields first_data_msg = True - f = open(fn, "r") + f = open(fn, "rb") bytes_read = 0 while True: chunk = f.read(self.BLOCK_SIZE) From d3d9d059c0c0780541d9dfd9c44b1f521298f5b6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 22:03:57 +0200 Subject: [PATCH 73/88] First stab at Python 2 and 3 compatibilty --- Tools/sdlog2_dump.py | 72 +++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 71 insertions(+), 1 deletion(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 838da9c489..0ffb381766 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -21,6 +21,17 @@ __version__ = "1.2" import struct, sys +from pypreprocessor import pypreprocessor + +#exclude +if sys.version[:3].split('.')[0] == '2': + pypreprocessor.defines.append('python2') +if sys.version[:3].split('.')[0] == '3': + pypreprocessor.defines.append('python3') + +pypreprocessor.parse() +#endexclude + class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -65,7 +76,11 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - self.__buffer = "" # buffer for input binary data + #ifdef python2 + self.__buffer = "" # buffer, python2 + #else + self.__buffer = bytearray() # buffer for input binary data + #endif self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -114,15 +129,24 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: + #ifdef python2 head1 = ord(self.__buffer[self.__ptr]) head2 = ord(self.__buffer[self.__ptr+1]) + #else + head1 = self.__buffer[self.__ptr] + head2 = self.__buffer[self.__ptr+1] + #endif if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + #ifdef python2 msg_type = ord(self.__buffer[self.__ptr+2]) + #else + msg_type = self.__buffer[self.__ptr+2] + #endif if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -170,7 +194,11 @@ class SDLog2Parser: if self.__file != None: print >> self.__file, self.__csv_delim.join(self.__csv_columns) else: + #ifdef python2 print self.__csv_delim.join(self.__csv_columns) + #else + print(self.__csv_delim.join(self.__csv_columns)) + #endif def __printCSVRow(self): s = [] @@ -185,16 +213,26 @@ class SDLog2Parser: if self.__file != None: print >> self.__file, self.__csv_delim.join(s) else: + #ifdef python2 print self.__csv_delim.join(s) + #else + print(self.__csv_delim.join(s)) + #endif def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] + #ifdef python2 msg_name = data[2].strip("\0") msg_format = data[3].strip("\0") msg_labels = data[4].strip("\0").split(",") + #else + msg_name = str(data[2], 'ascii').strip("\0") + msg_format = str(data[3], 'ascii').strip("\0") + msg_labels = str(data[4], 'ascii').strip("\0").split(",") + #endif # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -211,8 +249,13 @@ class SDLog2Parser: self.__msg_names.append(msg_name) if self.__debug_out: if self.__filterMsg(msg_name) != None: + #ifdef python2 print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) + #else + print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( + msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) + #endif self.__ptr += self.MSG_FORMAT_PACKET_LEN def __parseMsg(self, msg_descr): @@ -223,7 +266,11 @@ class SDLog2Parser: show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif if type(data[i]) is str: data[i] = data[i].strip("\0") m = msg_mults[i] @@ -231,14 +278,26 @@ class SDLog2Parser: data[i] = data[i] * m if self.__debug_out: s = [] + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif label = msg_labels[i] if show_fields == "*" or label in show_fields: s.append(label + "=" + str(data[i])) + #ifdef python2 print "MSG %s: %s" % (msg_name, ", ".join(s)) + #else + print("MSG %s: %s" % (msg_name, ", ".join(s))) + #endif else: # update CSV data buffer + #ifdef python2 for i in xrange(len(data)): + #else + for i in range(len(data)): + #endif label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "_" + label] = data[i] @@ -250,6 +309,7 @@ class SDLog2Parser: def _main(): if len(sys.argv) < 2: + #ifdef python2 print "Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" print "\t-v\tUse plain debug output instead of CSV.\n" print "\t-e\tRecover from errors.\n" @@ -258,6 +318,16 @@ def _main(): print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" print "\t-fPrint to file instead of stdout" + #else + print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") + print("\t-v\tUse plain debug output instead of CSV.\n") + print("\t-e\tRecover from errors.\n") + print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n") + print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n") + print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") + print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") + print("\t-fPrint to file instead of stdout") + #endif return fn = sys.argv[1] debug_out = False From 487497d66eab5846f133ed2da1a1f72356c24668 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 12 Aug 2013 23:50:29 +0200 Subject: [PATCH 74/88] Added Python 2 / 3 Windows / Linux / Mac OS converter script. So much for cross-platform / version agnostic --- Tools/README.txt | 13 +++++++ Tools/sdlog2_dump.py | 86 +++++--------------------------------------- 2 files changed, 22 insertions(+), 77 deletions(-) create mode 100644 Tools/README.txt diff --git a/Tools/README.txt b/Tools/README.txt new file mode 100644 index 0000000000..abeb9a4c71 --- /dev/null +++ b/Tools/README.txt @@ -0,0 +1,13 @@ +====== PX4 LOG CONVERSION ====== + +On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight). + +There are two conversion scripts in this ZIP file: + +logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored. + +sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run: + +python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n "" + +Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux. \ No newline at end of file diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 0ffb381766..bb109d6f3f 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -1,6 +1,8 @@ #!/usr/bin/env python -"""Dump binary log generated by sdlog2 or APM as CSV +from __future__ import print_function + +"""Dump binary log generated by PX4's sdlog2 or APM as CSV Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] @@ -21,17 +23,6 @@ __version__ = "1.2" import struct, sys -from pypreprocessor import pypreprocessor - -#exclude -if sys.version[:3].split('.')[0] == '2': - pypreprocessor.defines.append('python2') -if sys.version[:3].split('.')[0] == '3': - pypreprocessor.defines.append('python3') - -pypreprocessor.parse() -#endexclude - class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -76,11 +67,7 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - #ifdef python2 - self.__buffer = "" # buffer, python2 - #else - self.__buffer = bytearray() # buffer for input binary data - #endif + self.__buffer = "" # buffer for input binary data self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -129,24 +116,15 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: - #ifdef python2 head1 = ord(self.__buffer[self.__ptr]) head2 = ord(self.__buffer[self.__ptr+1]) - #else - head1 = self.__buffer[self.__ptr] - head2 = self.__buffer[self.__ptr+1] - #endif if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - #ifdef python2 msg_type = ord(self.__buffer[self.__ptr+2]) - #else - msg_type = self.__buffer[self.__ptr+2] - #endif if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -192,13 +170,9 @@ class SDLog2Parser: self.__csv_columns.append(full_label) self.__csv_data[full_label] = None if self.__file != None: - print >> self.__file, self.__csv_delim.join(self.__csv_columns) + print(self.__csv_delim.join(self.__csv_columns), file=self.__file) else: - #ifdef python2 - print self.__csv_delim.join(self.__csv_columns) - #else print(self.__csv_delim.join(self.__csv_columns)) - #endif def __printCSVRow(self): s = [] @@ -211,28 +185,18 @@ class SDLog2Parser: s.append(v) if self.__file != None: - print >> self.__file, self.__csv_delim.join(s) + print(self.__csv_delim.join(s), file=self.__file) else: - #ifdef python2 - print self.__csv_delim.join(s) - #else print(self.__csv_delim.join(s)) - #endif def __parseMsgDescr(self): data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] - #ifdef python2 - msg_name = data[2].strip("\0") - msg_format = data[3].strip("\0") - msg_labels = data[4].strip("\0").split(",") - #else - msg_name = str(data[2], 'ascii').strip("\0") - msg_format = str(data[3], 'ascii').strip("\0") - msg_labels = str(data[4], 'ascii').strip("\0").split(",") - #endif + msg_name = str(data[2]).strip("\0") + msg_format = str(data[3]).strip("\0") + msg_labels = str(data[4]).strip("\0").split(",") # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -249,13 +213,8 @@ class SDLog2Parser: self.__msg_names.append(msg_name) if self.__debug_out: if self.__filterMsg(msg_name) != None: - #ifdef python2 - print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( - msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults) - #else print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) - #endif self.__ptr += self.MSG_FORMAT_PACKET_LEN def __parseMsg(self, msg_descr): @@ -266,11 +225,7 @@ class SDLog2Parser: show_fields = self.__filterMsg(msg_name) if (show_fields != None): data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif if type(data[i]) is str: data[i] = data[i].strip("\0") m = msg_mults[i] @@ -278,26 +233,14 @@ class SDLog2Parser: data[i] = data[i] * m if self.__debug_out: s = [] - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif label = msg_labels[i] if show_fields == "*" or label in show_fields: s.append(label + "=" + str(data[i])) - #ifdef python2 - print "MSG %s: %s" % (msg_name, ", ".join(s)) - #else print("MSG %s: %s" % (msg_name, ", ".join(s))) - #endif else: # update CSV data buffer - #ifdef python2 - for i in xrange(len(data)): - #else for i in range(len(data)): - #endif label = msg_labels[i] if label in show_fields: self.__csv_data[msg_name + "_" + label] = data[i] @@ -309,16 +252,6 @@ class SDLog2Parser: def _main(): if len(sys.argv) < 2: - #ifdef python2 - print "Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n" - print "\t-v\tUse plain debug output instead of CSV.\n" - print "\t-e\tRecover from errors.\n" - print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n" - print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n" - print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed." - print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n" - print "\t-fPrint to file instead of stdout" - #else print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") print("\t-v\tUse plain debug output instead of CSV.\n") print("\t-e\tRecover from errors.\n") @@ -327,7 +260,6 @@ def _main(): print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") print("\t-fPrint to file instead of stdout") - #endif return fn = sys.argv[1] debug_out = False From c4498ce9a3525bafd2d1c70f7e16812d14d51206 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 10 Aug 2013 12:39:58 -0700 Subject: [PATCH 75/88] Add a 'menuconfig' target that makes it possible to use the NuttX menuconfig tool on the PX4 config files. --- Makefile | 28 +++++++++++++++++++++++++++- 1 file changed, 27 insertions(+), 1 deletion(-) diff --git a/Makefile b/Makefile index c02a986cdd..dc69b0ae8b 100644 --- a/Makefile +++ b/Makefile @@ -148,7 +148,7 @@ $(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) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)/nuttx-configs/$(board) .) + $(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) export @@ -156,6 +156,32 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@ $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board)) +# +# The user can run the NuttX 'menuconfig' tool for a single board configuration with +# make BOARDS= menuconfig +# +ifeq ($(MAKECMDGOALS),menuconfig) +ifneq ($(words $(BOARDS)),1) +$(error BOARDS must specify exactly one board for the menuconfig goal) +endif +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) (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 + @$(ECHO) %% Saving configuration file + $(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig +else +menuconfig: + @$(ECHO) "" + @$(ECHO) "The menuconfig goal must be invoked without any other goal being specified" + @$(ECHO) "" +endif + $(NUTTX_SRC): @$(ECHO) "" @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." From 5e2d67617369474406d86d4eae5ba9a24d5cbb9f Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 21:57:11 -0700 Subject: [PATCH 76/88] Remove our depdenency on CONFIG_ARCH_BOARD_* coming from --- makefiles/board_px4fmu-v1.mk | 1 + makefiles/board_px4io-v1.mk | 1 + makefiles/firmware.mk | 4 ++++ 3 files changed, 6 insertions(+) diff --git a/makefiles/board_px4fmu-v1.mk b/makefiles/board_px4fmu-v1.mk index 8370696446..4d692e31ab 100644 --- a/makefiles/board_px4fmu-v1.mk +++ b/makefiles/board_px4fmu-v1.mk @@ -6,5 +6,6 @@ # Configure the toolchain # CONFIG_ARCH = CORTEXM4F +CONFIG_BOARD = PX4FMU_V1 include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/board_px4io-v1.mk b/makefiles/board_px4io-v1.mk index b0eb2dae79..1872a4124f 100644 --- a/makefiles/board_px4io-v1.mk +++ b/makefiles/board_px4io-v1.mk @@ -6,5 +6,6 @@ # Configure the toolchain # CONFIG_ARCH = CORTEXM3 +CONFIG_BOARD = PX4IO_V1 include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 3ad13088b0..0d742c37dc 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -154,6 +154,10 @@ $(error Config $(CONFIG) references board $(BOARD), but no board definition file endif export BOARD include $(BOARD_FILE) +ifeq ($(CONFIG_BOARD),) +$(error Board config for $(BOARD) does not define CONFIG_BOARD) +endif +EXTRADEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) $(info % BOARD = $(BOARD)) # From 60275e1ae65633dfc03f6353b7796ed540975803 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 21:59:10 -0700 Subject: [PATCH 77/88] Clean the FMUv1 config through menuconfig. --- nuttx-configs/px4fmu-v1/nsh/defconfig | 32 ++++++++++++++++----------- 1 file changed, 19 insertions(+), 13 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index d338161296..a7a6725c65 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -73,17 +73,16 @@ CONFIG_ARCH="arm" # CONFIG_ARCH_CHIP_LPC31XX is not set # CONFIG_ARCH_CHIP_LPC43XX is not set # CONFIG_ARCH_CHIP_NUC1XX is not set -# CONFIG_ARCH_CHIP_SAM3U is not set +# CONFIG_ARCH_CHIP_SAM34 is not set CONFIG_ARCH_CHIP_STM32=y # CONFIG_ARCH_CHIP_STR71X is not set CONFIG_ARCH_CORTEXM4=y -CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FAMILY="armv7-m" CONFIG_ARCH_CHIP="stm32" CONFIG_ARMV7M_USEBASEPRI=y CONFIG_ARCH_HAVE_CMNVECTOR=y CONFIG_ARMV7M_CMNVECTOR=y -CONFIG_ARMV7M_STACKCHECK=y +CONFIG_ARCH_HAVE_FPU=y CONFIG_ARCH_FPU=y CONFIG_ARCH_HAVE_MPU=y # CONFIG_ARMV7M_MPU is not set @@ -93,10 +92,8 @@ CONFIG_ARCH_HAVE_MPU=y # # CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y +CONFIG_ARMV7M_STACKCHECK=y CONFIG_SERIAL_TERMIOS=y -CONFIG_SERIAL_DISABLE_REORDERING=y -CONFIG_SERIAL_IFLOWCONTROL=y -CONFIG_SERIAL_OFLOWCONTROL=y # # STM32 Configuration Options @@ -248,6 +245,7 @@ CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y # CONFIG_STM32_FORCEPOWER is not set # CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set # CONFIG_STM32_CCMEXCLUDE is not set +CONFIG_STM32_DMACAPABLE=y # CONFIG_STM32_TIM4_PWM is not set # CONFIG_STM32_TIM5_PWM is not set # CONFIG_STM32_TIM9_PWM is not set @@ -275,6 +273,7 @@ CONFIG_UART5_RXDMA=y CONFIG_USART6_RXDMA=y # CONFIG_USART7_RXDMA is not set # CONFIG_USART8_RXDMA is not set +CONFIG_SERIAL_DISABLE_REORDERING=y CONFIG_STM32_USART_SINGLEWIRE=y # @@ -342,15 +341,12 @@ CONFIG_BOOT_RUNFROMFLASH=y # # Board Selection # -CONFIG_ARCH_BOARD_PX4FMU_V1=y -# CONFIG_ARCH_BOARD_CUSTOM is not set -CONFIG_ARCH_BOARD="px4fmu-v1" +CONFIG_ARCH_BOARD_CUSTOM=y +CONFIG_ARCH_BOARD="" # # Common Board Options # -CONFIG_ARCH_HAVE_LEDS=y -# CONFIG_ARCH_LEDS is not set CONFIG_NSH_MMCSDMINOR=0 CONFIG_NSH_MMCSDSLOTNO=0 CONFIG_NSH_MMCSDSPIPORTNO=3 @@ -358,8 +354,6 @@ CONFIG_NSH_MMCSDSPIPORTNO=3 # # Board-Specific Options # -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y # # RTOS Features @@ -497,6 +491,8 @@ CONFIG_USART1_BAUD=57600 CONFIG_USART1_BITS=8 CONFIG_USART1_PARITY=0 CONFIG_USART1_2STOP=0 +# CONFIG_USART1_IFLOWCONTROL is not set +# CONFIG_USART1_OFLOWCONTROL is not set # # USART2 Configuration @@ -507,6 +503,8 @@ CONFIG_USART2_BAUD=57600 CONFIG_USART2_BITS=8 CONFIG_USART2_PARITY=0 CONFIG_USART2_2STOP=0 +CONFIG_USART2_IFLOWCONTROL=y +CONFIG_USART2_OFLOWCONTROL=y # # UART5 Configuration @@ -517,6 +515,8 @@ CONFIG_UART5_BAUD=57600 CONFIG_UART5_BITS=8 CONFIG_UART5_PARITY=0 CONFIG_UART5_2STOP=0 +# CONFIG_UART5_IFLOWCONTROL is not set +# CONFIG_UART5_OFLOWCONTROL is not set # # USART6 Configuration @@ -527,6 +527,10 @@ CONFIG_USART6_BAUD=57600 CONFIG_USART6_BITS=8 CONFIG_USART6_PARITY=0 CONFIG_USART6_2STOP=0 +# CONFIG_USART6_IFLOWCONTROL is not set +# CONFIG_USART6_OFLOWCONTROL is not set +CONFIG_SERIAL_IFLOWCONTROL=y +CONFIG_SERIAL_OFLOWCONTROL=y CONFIG_USBDEV=y # @@ -559,6 +563,7 @@ CONFIG_CDCACM_EPBULKIN_FSSIZE=64 CONFIG_CDCACM_EPBULKIN_HSSIZE=512 CONFIG_CDCACM_NWRREQS=4 CONFIG_CDCACM_NRDREQS=4 +CONFIG_CDCACM_BULKIN_REQLEN=96 CONFIG_CDCACM_RXBUFSIZE=256 CONFIG_CDCACM_TXBUFSIZE=256 CONFIG_CDCACM_VENDORID=0x26ac @@ -747,6 +752,7 @@ CONFIG_EXAMPLES_CDCACM=y # CONFIG_EXAMPLES_MM is not set # CONFIG_EXAMPLES_MODBUS is not set CONFIG_EXAMPLES_MOUNT=y +# CONFIG_EXAMPLES_NRF24L01TERM is not set CONFIG_EXAMPLES_NSH=y # CONFIG_EXAMPLES_NULL is not set # CONFIG_EXAMPLES_NX is not set From b3d2efc90af671f13f8f473230e3af6e8d91153c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:26:05 +0200 Subject: [PATCH 78/88] WIP --- Tools/sdlog2_dump.py | 21 +++++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index bb109d6f3f..8746a99479 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -23,6 +23,11 @@ __version__ = "1.2" import struct, sys +if sys.hexversion >= 0x030000F0: + runningPython3 = True +else: + runningPython3 = False + class SDLog2Parser: BLOCK_SIZE = 8192 MSG_HEADER_LEN = 3 @@ -67,7 +72,7 @@ class SDLog2Parser: self.__msg_descrs = {} # message descriptions by message type map self.__msg_labels = {} # message labels by message name map self.__msg_names = [] # message names in the same order as FORMAT messages - self.__buffer = "" # buffer for input binary data + self.__buffer = bytearray() # buffer for input binary data self.__ptr = 0 # read pointer in buffer self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" self.__csv_data = {} # current values for all columns @@ -116,15 +121,15 @@ class SDLog2Parser: self.__buffer = self.__buffer[self.__ptr:] + chunk self.__ptr = 0 while self.__bytesLeft() >= self.MSG_HEADER_LEN: - head1 = ord(self.__buffer[self.__ptr]) - head2 = ord(self.__buffer[self.__ptr+1]) + head1 = self.__buffer[self.__ptr] + head2 = self.__buffer[self.__ptr+1] if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): if self.__correct_errors: self.__ptr += 1 continue else: raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - msg_type = ord(self.__buffer[self.__ptr+2]) + msg_type = self.__buffer[self.__ptr+2] if msg_type == self.MSG_TYPE_FORMAT: # parse FORMAT message if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: @@ -190,8 +195,12 @@ class SDLog2Parser: print(self.__csv_delim.join(s)) def __parseMsgDescr(self): - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + if runningPython3: + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + else: + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) msg_type = data[0] + print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] msg_name = str(data[2]).strip("\0") @@ -224,7 +233,7 @@ class SDLog2Parser: self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): - data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + data = list(struct.unpack(msg_struct, str(bytearray(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))) for i in range(len(data)): if type(data[i]) is str: data[i] = data[i].strip("\0") From da9d9781f999361009b2c7b8e9b18d0d500c072c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:33:32 +0200 Subject: [PATCH 79/88] Final version of log conversion script, runs with Python 2 or 3 on Windows, Linux and MacOS. Tested on Mac with 2 and 3 --- Tools/sdlog2_dump.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index 8746a99479..a376e03d39 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -198,14 +198,19 @@ class SDLog2Parser: if runningPython3: data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) else: - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) msg_type = data[0] print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] - msg_name = str(data[2]).strip("\0") - msg_format = str(data[3]).strip("\0") - msg_labels = str(data[4]).strip("\0").split(",") + if runningPython3: + msg_name = str(data[2], 'ascii').strip("\0") + msg_format = str(data[3], 'ascii').strip("\0") + msg_labels = str(data[4], 'ascii').strip("\0").split(",") + else: + msg_name = str(data[2]).strip("\0") + msg_format = str(data[3]).strip("\0") + msg_labels = str(data[4]).strip("\0").split(",") # Convert msg_format to struct.unpack format string msg_struct = "" msg_mults = [] @@ -233,7 +238,10 @@ class SDLog2Parser: self.__csv_updated = False show_fields = self.__filterMsg(msg_name) if (show_fields != None): - data = list(struct.unpack(msg_struct, str(bytearray(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))) + if runningPython3: + data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + else: + data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))) for i in range(len(data)): if type(data[i]) is str: data[i] = data[i].strip("\0") From 0025e9ca909d4e1c8bc63841cd0e61265a328e30 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 07:57:39 +0200 Subject: [PATCH 80/88] Hotfix: Copy a current version of the log conversion tools to each log directory --- ROMFS/px4fmu_common/logging/log_converter.zip | Bin 0 -> 10090 bytes ROMFS/px4fmu_common/logging/logconv.m | 586 ------------------ src/modules/sdlog2/sdlog2.c | 9 + 3 files changed, 9 insertions(+), 586 deletions(-) create mode 100644 ROMFS/px4fmu_common/logging/log_converter.zip delete mode 100644 ROMFS/px4fmu_common/logging/logconv.m diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/log_converter.zip new file mode 100644 index 0000000000000000000000000000000000000000..2641e671068b1ea6867fc6b9fef17ba3889e5262 GIT binary patch literal 10090 zcmaKS1B@ojw(Zw8rfu7{ZQHhuX}hQ0)1J0%ThlhDZS!mU&VOF=-pM`h-t1JWDydpY zB`cM^_FhV|VBlx~000`W!HXbT$i5Zh1rGp7vj6~y06c)JnVq90i=mmjy%U3zx4Ie( z04#n8M&-RFQlKy6sw( zG~pu#ZZL^zi-Eb!LWHX6>euI$RCE!QjQp~R$j&O?*6o#77o+p_ZL7QXci*f!N9y&Y z@0!)D95}<`EyTjeE9&~QL_}j0Gttop;sZ2T=E^BMY%_P$XYvXFemW1bDGf7mZ2Ey{ zhOx^yz0b#YY3XrtfCU-t=;L8`}0fQ z0kH+{Iq$iiOg57utEd3t(=2q!I(nPqVDGFn%lg->oA<$80BZnGHUowU{X5qx3NXKj zOmQ$2B!AsUyrE)yhcRXT z%&j@4j1v0v6G0Tj7vK#&UfN~0EHA^BT|G-$pJgTT(qD8FTS$8BGYkXZ#ul*A$-1~d zLfT!i(8=gTzA$ce`M$_HJ-j}-roVm6A+ZX;t|9mf2=em=5O#3~z$I8#?~(?`WVb+B ze!qzbDDT(2-ZK1U0F_qC7{J||>elns4{501`*j1vVZYlOz5||g0y~e3ODXifo`8DO z2M4`^2Sic69}0zE8y0)9XaQ@1_aQ8+~J-M}htv&+EuNn$}>BA5s=#8F#B z@5{g;JQQA{7*U~Th7)?IAP2m0IyD zL5x06`$&i{gCH*{qW<=xpL@B&$SLcAzC>)e+pH3E!#hT-E!3LAzlwIsjP5OnB`eKD zzk!=d>BqT1VF!k&l}gM{MF&f$6LsZ7fbX#x?S{8l@78e-2&S?@Dh(vjK>sF}-yf?- zY0E?Q)$(-^meu)#dV8z}-BM&eg#CKQ2(oVb3x79HtfNx*5WIbzG>geIQFc)GhE%}? z#SD3mKv&HsQ$%{4a#Yh zTgJNHY<|a8dCidNXlxyVN8rK9ehQgci?4%uc!rLtt+HU_oXd77avzU4W$Q#Eq^V-3 zCzqD9`~9CImM76$ODSX}e5z@gr%j7b%Ce3FI5X`}Hccxo)`<9P47L2T1xV3Fj=N;C z^W(%a74c-!3(6JOCK4#;-+)?P@=Nbyb93`dp+Vf_=;HQYSbw&L$nV3^sKLcSaznr{VKuf(JjKG|_7l2W=r^xwcQ%sOi-erU`}4JGFj zd#iy~xmUaHWl3b~>&xn6omlia^Wzu3_X#vy#1SLpD20$ySUFA==zHUa_n%i274ytZ zY~wvPoNO@2A70xb#Wz{-olpjsyC*St2d^KrtTOC6D_q2(Z%;}B^s2l0{$5521HIA+s!pL@wl2T2`l z60XBS$_40u6m%6E6T&V;O;8c0vvCyM8Z$)aEFL1$iuA|c+v)8qMqzs0jMcxY*{dzZ z*049%tkhK;;_`bMd+6d^;+XgC3oy>apRba|EFIqmXb=3>r=Tq8<7Sq!W!O}{41$xB z_)X2^7qtmBk3iq7>qFS|fZep-W#7!+es7(1)*`5+^HXh@zX~%>9euyrye<~su9%`{ z&BFh(yRoGr1?aY^(aF4RAmiabv>s?Z1!Q{VYC&b4JAL#;mF2RT8Fi+WC6v0t5G@dl z$*sT&pwD4bm7tiSUyw>3DsfAuXZ_*-J(sQ{CGl20j>kf<$sPgW&ytY16HQ~7Vos>} zPclUcRV;a6J*VLP#$oUU0?x?{L2ylG3+#tC(reS?LJ^K{kNBAVi$nWo4p)F;v@dh7 zq=AK>(yvVJb{klDEUO*g&|=+Z>|DE#C@4$wSp;?wvp6~T zmubruoz6>y0T(!8>X{usQ65S(PBfY58gXxi*(*HODYLx|^#*ZJAr0BvVKE}SGY8`2 z$*59M6$9|N*Y)${FT(S*(Fkqy3g2{h6upsjDL6%Hb2$h+o#3a_8 zW5$>oof(=#fE?bNLv`lVmb>|l;B@$iVACEPZ3R|LwRaxn*mAVnXjoY@54Q)Id z#Wf#p&c1%51)tfd){y*1qQY-TK3T|) z@4&5_%hTZ(lWF(}(u@pEsC94mUfy{AXE%fPE1}0pgXpEBSCNAaZ&H`57uVW&Xxqp< zf+IsG(S`{BTAkxMVAtz>Wm53?4!<;}W}xe^^yTyK7Do(Wm{ytw9>;E|JF-g7FYXw2RM;iT8nQy{2{BpP%!8p41Q8|L zJ3Sm6PS%s|l-0hTQ|=>EZ9IGV(?exFUi|@G#VRz9Pcx6nAM2r1ze)_p~mpK zJUELKr9!LGl#ndv!l}VXdm4y(qWB?g^pLOM~xp|cMsBcp}}?wjnH^eiEh=z zJ?h+Nw|mv@b(~8p;Qb@F)1X-v)t)FCRjqPj(2fxSMrfCiDb987R)bBS3O9QlYA1`$ zACJs0@Ca!iFx-7?P&axdl((zMITHY~Eeq%w^BR;|oPkF9rM@5C%BU%^s8E3~8+z4; zoJTIq24e-C%#48(MM8ZgkJbEshPAvuwg*)?Z|K^3bS=Ab8jsjK4;SgV;cBjap01lM z!@G+rY{xdf*lqeYI&@{YW=$9|XWhs?gBT(^o`*n!<$Qw(TCAIlm-vEG`oH>xBM45k z7l*@v8WRA}w*UZO{_2;%>c!O2!Gpp6U($st3rYokV9ORQlI!BUG4* z$e7Qn0!c)_jT!e`4Lx?!FF6fcEH-iJ4W*(uBtaM7uT!VK&)&*2s6RzgQ3?lmh+M`b za~D@<6@SBrjhmcBTSuUM7EHI7+;p&U8HCv_Vk496ehM2#&!l>}1~b9PI!Sk8u3OTi z^9MxJ=BbC(>rl4odTsB|(L=%rOH9on7o$ZvB)7I&$(`jETyQ2C&zoEaL4Q`uX2XCW zXL6v6B4OOn%gx}_;foW?RorV@GDm_Xw;2JCgi$-<@pC+r2{=4>@Ew}Rz@*eGmi!x>#S#qx-Nc$fH#R>8h$hQ1i1u=Xb z`I7IFU(;-$E0vohz4Ys3vI}5ieG{@5<=-I8N(~&1kPgXUY|XisY4nsqv`>-ldFnKX zjF~`WkisNN0PCCxD;X~^(s7G!xyJ!YXFv33N#zpzG~3^tqnbktdPTdA;N~f|bbGr>e_Ld?7Y3i!D8%B3 z1P9|*#P+^ogbCS5C;T{isSs?hc%$|H$+Qz`x?y-wB)(8PT&yM^loSY-wX>~ zlz3V$nAE%FSB80dAaY7s2JY6H1-C|?^jCo=t3-R2kZ;(cL5Y?RO4KI;a>=fEyE1hV zxGN|4PXOxyJbWBDZ#cLKm61K_t-RFctY|1ZOe>j!#ECc6*{Y0@tI>RH2Pmlc?n$bp z*DD{9NJm1c>JL#h`nZc`4@kbQx?gY~Af*?q;nD1?*QubsFy6ufdJl6&2KrZ+pMAWI z82Og3YjZH4OWuJK68JS~&D^%soNLOp(Hgb+5HyKVQJ|5yEOc&0r!5cirM}-TM(v2S zgYSc|m-!U~$kY!Quh?gILMwIaN?4gl5zCCQv^I$DUywvQeP?XF}T| zs`RxC46_U*UCkA(bba`UH@~lrT2aERs6{%J3zZqw^tsx%sP9h0%fK0RTyVG*?2#Z9 z8NgmFsD~;YU1(C)dVKbY39|7jF#(R!* zVEqck;f3y$ zPq#$+%GYuw+;SDZ?kn9fm_8$5cfD$-b(*&=+TyWV#;wK)BMS%zh~V`3K@)PM52FNT zei7(6`C3dJQ?OrsZ$aSt?(@aH@%d%>xq0i#dA+ z2P|L7hL?QHq0hY9$unIyGd~m1vcHe;b5npcQaH-#VbSKCYnRR51++$8J)`zk`u>27 zSE;y**q1=pEc@($!6Y&3_wUMzw0+*pu-2u;tB&?xgv!({;U8Q-S&YKCKX$Z=1V?z5 zoVvLdBh}mDB2ECc-y?WyIT~^fX?QVu5#|ogM}Y|VDHHZE5RVknp9?>!p7Csp#4+Zr ztu2ZSOR_T)*mE>Rr&n!zE(t76`l3|HzS|D`m|Tqy5sa3h)`(&=mCGE5)+BABEgDFK z6jXu6G|Gu+J`vFjgyg{)0LuAcJYf(~+Ycy)$MxIgT$GV~{aHru{PsC-p4hihA``kg za``hg!If?StdxNHnYH~A0b39jsXwgmaet5{;;X?}BcAiMTIJ(CWZ#E^$zK_L&>(5w zXM?_HpsbNEcKJO<8JmQ@9^lm}j}cPgYVdSJzUIN)R4Jt-NUqXH^L zpF0oyYtk^YF;gU__$me0og+0m=rRkJ30WwMDv6@68IFMrnhQ0BPKruNui~*M2>vzs z%83aZVW#}3ESlg8vMgB9os_#7InrmPuHHZLs(%-6Jax)d4(bs&nm?el&C0 zYB?<9!QK`UrGou@j@}j0zw1%rz1vK`$x5zDeu8~^eio4!oTlEkJ-?jY7}?fp9D%<2 zAt}Vq{TT(?YiYo73*GbGE6&#zgN{A!g*ND#Hk_Prv#2o0hG1!q`MU^ev+jO+&tBy1 zHU=)E2@UhFSZUNw%hQu!bwn$oNBEuMzP5t;i3S%4mXnZ6LtUgknXVleaPjN`AnLm$ z_XxIAH4WGeY@R9SGQYT1rn&vMU<6PcD%$4Rf?jiT69^9cp{2wMkjD^TTq?caRDB|O zbgXCQ_hgXc5_JISrxy%qyhpxd&8>i>0_PbqhBVnem~ADP~6% zu3qRZNfBF^4qgx+dFWsqb@`G_{ex0pl#*Ivj;aO^;DDP)J)fMUd}-GHO@p(C<}BBk zw@@IwEoA~kn5?bA*4`NM5Wzs# zTzhNS{Nm?59WphXr7Nu8K4&Yv=icCe^Jm9q_M_YGJi{9 zKsC%Kq>Vq?{rB%1QIqa$;DAZDu#0fN#ln|bf7}M%m70;9mylm?=!obzW_~OL+DH`% z^OEjUev+91$y;wo*g%x4o@1Cgk!$LKZS@w}bFG1|uUv1K$glv_k`}`XmZ%CC2YMl_SMymA&)bwIvarb!^z3 z`Kwt7B@c5bpZYn=Fk&t@es1zVj>&;(vrxn(q*@5cnv&KZ+pt2NkT?alfJXDtW?vKjxkrR(SD8e$(X~Iwf0X2Qo+Be_#DJM?#Q*I4(e7 zFkm}zw^G7=xA2Q^YkF*Do%_XtmvZ~+=)n2So`Mpo)fHGLKOI3h>NTGcvv9#(F`J~C zBz$}oyfY2{dxM3eZMJMAox_Y{6lmxu+DfMvPczfQxFZbpe0{uVdz%O5%5+opZ7O@g zgl;PemN#$37#Wk~9y><^LRZ_wqG5cJHl2Grr6qGHBihRPDdNpRc6^#rod1cJJ*}h3 z+sqXK|1B}wLG-(pw28t!?`1-myQ|44XP1} z#@6|PeUeg8ie_aJ*1OQAp*P!29JZOyJnP(xb0aHq=E~c;gkwE5%Exjy>)7x!-b@|^ zBt4(4#En>98?p4@=n!d(7X@8U2A3WM9!@#c$0SY1u&S3odhC;(%_k|6XfY)p=b=>g z?|DeAZM~Bpf(;#su?~jO?r*vhtyGPf$f`mp!9!uDkXNuX!f$4;!bpCC7?A6FeJtZ2 z%pteXUp>^?X05Qvo6IpJW}>bCj6JhfB^Y=x5)Z}#U-z9aPl7+y*=B?o6mNrt#~Asz zZ|KB$Z|J4($d@QFHwc~xo#%@SmQd}Ler?GYh2I-Y=|;NypCP+%?HVg+AZO+_=GCU7 zR!3Ys3X5$Et$C!c#37h`qRVTG?Yf1&nRJF`n~hE$-{Mb;K)^u$0n(Aeij<|8zlrQ= zJf6nt2cl52b6~t$b!LB2YrI4hr1c%$PF&8wClq@9Gg=>?yw zMceeRet#3wlPBg6fBD{RD(o>xfXGkA<7FA;QpX!Pg+_zkI0y+dR}P57OAO(}pV07+ z^4l4)-(;2{Y351o8b9-`DGaPIvLr7C$>k_^IB?s798BFqR3-?MHneEuh+yKBB$*t| z>q!0Hqt+Izq}sQ!HJL17BV{}(FBmqjUZ%9n5jHtQUQckUm7-aXAZKnHELT&HqIpFT zxyn5|VoOzfgBH%x&gbs5i)6qJ!QJE#1Hx+dJ}V`L>Q{RsjZ%9xp7S-kDu9(Xri1+n zD@d%`WS$VDtH2jXXdFMkVd%#oe-AxE*Nyim;-HRVc5ffP-x?_Pa2mTv6o0Y{28NPYKeEyWlrL@qe6MPKS0M^0yo-vZ{#}YpqM!D;Q z;qBp@t;u=9_BE%p{#8Ca(l0CU;(PNX6on#e4*~88%Tr5Tfm)O4zhgf(Z(h`3^c=98 z|5gn{58-q53*c(G%?~2b+hq!hqh5?+0l*7JQrf!7p?EEY_b1SvDv5y1L0Iz?8y2ruk7gE{@~=#elW z*Jf8I3+To5+Nl%{T#e%wxVQVvXJ3oJ&MW!*FOEiOVXqiWNt7X@_4g2h4{AMx2#KNP zgsMh&wbCQAVjNDziDO64!WGnq1iWb5-cf+Y3tbC($X&r)q3LHnwntFBkf?Cr+X3D|_qavXT^191{}l z+&6Tqh+nr_s;F;5?imwYn=|3asC*Mtx}Cuhs-e}VW_>fIP%1pCvabD85reeKI|GXM zx^T2pM8@l4R~?Ly(5*hW7BwJD`P#lMT^H#Thlap+wx_V;^M1bdom$BxARH!XI4u_R zjs9eSyKbMA;6Ux>0y%2n?V<}wU-{dw-?h#C93x$&ht~G5Md`E=tcqvZhavhSBw#i& z=XcH!-9QD~ppEoO_nWrj**MDBwd!aJspN5~qEN@00)SA-itP@TOJMg<*g@c+r5vhP zS?oA%qz$KK^eYRe$(1vqhE!#<|RG%$z5-xXpSfcCisWW zy`*Ccll5Fe&e0L)h!Cih48L_|sJwI}lssNa22BHekg33ID_SH$ok}8dRHKBKn7hSm zIAr(|fLduM^+2&91}jtDu*OX1GuuIz)g!uzj?gn@n@s3oXh<`byz^HAN~gTi+P-OH zTbUlh0a(-XL(`B*oZr|OirrHaoNXYDR>q_OWzJi4E1th-O}D^Ai|ZI_?YkQzK}y66 zYQ$mr&W)!tdnGHkZ@Z=$P$j<|DCUm1swXX*XvG!9jwu-5(hPhF@mID;S%ya;zam49 z#qU2l7k<8GS7zPaA?+<_i}%U&Y6r(p0OWX?1q#0k=FWGYATjU+?C8=-wYvI$`j)<} z+wDyW&4G?5c6Dk&R!Q{<&KwyOt`50m)QKMfPWeMLx*= zA~T1n_bd=lk(M>=0f6u@_`1cK7@Z*IsB{l&HZow8L^$fXgLCvIDqbK|KRwq#UswvA zgKp0y5{KeONKu`>A110Tq8X#^?iGueuccU*4W(T|AJo=-=Wq*5u`&axvw{31aHt7KRJh14QYYYd zmr-OH;}wc?S5ZY*4#+Y`L6Vcfh=#}x6&%qw2Wu1(kAsCu0jj$27)r%kU!BqL@3)si z-H$E9cnajt*tV~R^rVD$bB`do-NYtc!yiqWrEmu4;O8?o0O7d4bEDmKlTBF0h#8HL z7Oo3H_pjb^HG>B)cv*1g?IYW5?sp1ZQ)vnr^MCaGX2lwCEOJyduN63QxL??6k0woW zOeMq3MPZv?qocsvBj#qzH4{CN6`;4gO2Q1~Hupb3z1*ffGl>06(<`{|#BO;L9rN)V zc<6J^Y#}a8az<Tb#M;9v@9_lzj$FbiE$ICDR%!WyAPif00$ZesseDHQ}qU=mp|b_nl>h{aZWd1?>Q*aTCh66Hnj$TuYLYqvW}|-yqCLf34W|%|H^st&*8guL&zDGrEoYw(xqpby=cz% z>^MHDEUO3h#Qk35$QG}o)Ae_u@^fKK!I60kM3laZ;l;G~F{~|Kx8fCL#z&8gw}i|; zF2X@EA^Ak^1beqeh2-oP2X<@kX*6#;joPHKX`o93Lc z+49RBYc@Qb?gS_s%UnD0X~>vIaQ}rVy1nMzcTM(*N$d9h1^9op_CMY5q6M_D8@GS$ zKPq4V0PNpdyNbB5n7lZHo0r?aitS^X|6iYwx{9vj8WWoTOzrbe$^;^}&71_UysEQ= zygcDfYsLlXJ!IK9{67jrU;dN|(H&Hn+tZ%B+SRXcBiq|`yj@1FUVZ_e-fIK~-#9ds z-DZ)0rYIeOQvOPoFipy+V9{}R%BjNSmOAF+aG%<50{bI#CaX17jBDA0W+hI|N?t-_ zqEf%pEL{xQnlF!%c86|<@ zi8L%JZC){%iU$gQZ^RIRrBK&6gfLB8+ZU?lj@@Ml)IA3g&WTAJ&RL4dvVjUdSp7y^GCibJDgk!R@wRpQSAp0zF$ni z=4eHF5|eVQ~raL9Xle2=2Q7?O=T@r2#)Er9hrV&o5`vu6XJ3o6y!;~7+mME znqd`D{zDoNP(rZ($zq1}*Lns3{ACfKDCnQne>a>#{2#;Fe>0o?JLZ43ef}M@@2{Ed y-K{vUV{kpDae>~GxtosB8}+5H#l;vhu; literal 0 HcmV?d00001 diff --git a/ROMFS/px4fmu_common/logging/logconv.m b/ROMFS/px4fmu_common/logging/logconv.m deleted file mode 100644 index 3750ddae2a..0000000000 --- a/ROMFS/px4fmu_common/logging/logconv.m +++ /dev/null @@ -1,586 +0,0 @@ -% This Matlab Script can be used to import the binary logged values of the -% PX4FMU into data that can be plotted and analyzed. - -%% ************************************************************************ -% PX4LOG_PLOTSCRIPT: Main function -% ************************************************************************ -function PX4Log_Plotscript - -% Clear everything -clc -clear all -close all - -% ************************************************************************ -% SETTINGS -% ************************************************************************ - -% Set the path to your sysvector.bin file here -filePath = 'sysvector.bin'; - -% Set the minimum and maximum times to plot here [in seconds] -mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] -maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] - -%Determine which data to plot. Not completely implemented yet. -bDisplayGPS=true; - -%conversion factors -fconv_gpsalt=1E-3; %[mm] to [m] -fconv_gpslatlong=1E-7; %[gps_raw_position_unit] to [deg] -fconv_timestamp=1E-6; % [microseconds] to [seconds] - -% ************************************************************************ -% Import the PX4 logs -% ************************************************************************ -ImportPX4LogData(); - -%Translate min and max plot times to indices -time=double(sysvector.timestamp) .*fconv_timestamp; -mintime_log=time(1); %The minimum time/timestamp found in the log -maxtime_log=time(end); %The maximum time/timestamp found in the log -CurTime=mintime_log; %The current time at which to draw the aircraft position - -[imintime,imaxtime]=FindMinMaxTimeIndices(); - -% ************************************************************************ -% PLOT & GUI SETUP -% ************************************************************************ -NrFigures=5; -NrAxes=10; -h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively -h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively -h.pathpoints=[]; % Temporary initiliazation of path points - -% Setup the GUI to control the plots -InitControlGUI(); -% Setup the plotting-GUI (figures, axes) itself. -InitPlotGUI(); - -% ************************************************************************ -% DRAW EVERYTHING -% ************************************************************************ -DrawRawData(); -DrawCurrentAircraftState(); - -%% ************************************************************************ -% *** END OF MAIN SCRIPT *** -% NESTED FUNCTION DEFINTIONS FROM HERE ON -% ************************************************************************ - - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -function ImportPX4LogData() - % Work around a Matlab bug (not related to PX4) - % where timestamps from 1.1.1970 do not allow to - % read the file's size - if ismac - system('touch -t 201212121212.12 sysvector.bin'); - end - - % ************************************************************************ - % RETRIEVE SYSTEM VECTOR - % ************************************************************************* - % //All measurements in NED frame - % - % uint64_t timestamp; //[us] - % float gyro[3]; //[rad/s] - % float accel[3]; //[m/s^2] - % float mag[3]; //[gauss] - % float baro; //pressure [millibar] - % float baro_alt; //altitude above MSL [meter] - % float baro_temp; //[degree celcius] - % float control[4]; //roll, pitch, yaw [-1..1], thrust [0..1] - % float actuators[8]; //motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512) - % float vbat; //battery voltage in [volt] - % float bat_current - current drawn from battery at this time instant - % float bat_discharged - discharged energy in mAh - % float adc[4]; //remaining auxiliary ADC ports [volt] - % float local_position[3]; //tangent plane mapping into x,y,z [m] - % int32_t gps_raw_position[3]; //latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter] - % float attitude[3]; //pitch, roll, yaw [rad] - % float rotMatrix[9]; //unitvectors - % float actuator_control[4]; //unitvector - % float optical_flow[4]; //roll, pitch, yaw [-1..1], thrust [0..1] - % float diff_pressure; - pressure difference in millibar - % float ind_airspeed; - % float true_airspeed; - - % Definition of the logged values - logFormat{1} = struct('name', 'timestamp', 'bytes', 8, 'array', 1, 'precision', 'uint64', 'machineformat', 'ieee-le.l64'); - logFormat{2} = struct('name', 'gyro', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{3} = struct('name', 'accel', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{4} = struct('name', 'mag', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{5} = struct('name', 'baro', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{6} = struct('name', 'baro_alt', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{7} = struct('name', 'baro_temp', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{8} = struct('name', 'control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{9} = struct('name', 'actuators', 'bytes', 4, 'array', 8, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{10} = struct('name', 'vbat', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{11} = struct('name', 'bat_current', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{12} = struct('name', 'bat_discharged', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{13} = struct('name', 'adc', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{14} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{15} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le'); - logFormat{16} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le'); - - % First get length of one line - columns = length(logFormat); - lineLength = 0; - - for i=1:columns - lineLength = lineLength + logFormat{i}.bytes * logFormat{i}.array; - end - - - if exist(filePath, 'file') - - fileInfo = dir(filePath); - fileSize = fileInfo.bytes; - - elements = int64(fileSize./(lineLength)); - - fid = fopen(filePath, 'r'); - offset = 0; - for i=1:columns - % using fread with a skip speeds up the import drastically, do not - % import the values one after the other - sysvector.(genvarname(logFormat{i}.name)) = transpose(fread(... - fid, ... - [logFormat{i}.array, elements], [num2str(logFormat{i}.array),'*',logFormat{i}.precision,'=>',logFormat{i}.precision], ... - lineLength - logFormat{i}.bytes*logFormat{i}.array, ... - logFormat{i}.machineformat) ... - ); - offset = offset + logFormat{i}.bytes*logFormat{i}.array; - fseek(fid, offset,'bof'); - end - - % shot the flight time - time_us = sysvector.timestamp(end) - sysvector.timestamp(1); - time_s = time_us*1e-6; - time_m = time_s/60; - - % close the logfile - fclose(fid); - - disp(['end log2matlab conversion' char(10)]); - else - disp(['file: ' filePath ' does not exist' char(10)]); - end -end - -%% ************************************************************************ -% INITCONTROLGUI (nested function) -% ************************************************************************ -%Setup central control GUI components to control current time where data is shown -function InitControlGUI() - %********************************************************************** - % GUI size definitions - %********************************************************************** - dxy=5; %margins - %Panel: Plotctrl - dlabels=120; - dsliders=200; - dedits=80; - hslider=20; - - hpanel1=40; %panel1 - hpanel2=220;%panel2 - hpanel3=3*hslider+4*dxy+3*dxy;%panel3. - - width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width - height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height - - %********************************************************************** - % Create GUI - %********************************************************************** - h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); - h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); - h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); - h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); - - %%Control GUI-elements - %Slider: Current time - h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... - 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); - temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); - set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); - h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... - 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); - - %Slider: MaxTime - h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %Slider: MinTime - h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %%Current data/state GUI-elements (Multiline-edit-box) - h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... - 'HorizontalAlignment','left','parent',h.aircraftstatepanel); - - h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... - 'HorizontalAlignment','left','parent',h.guistatepanel); - -end - -%% ************************************************************************ -% INITPLOTGUI (nested function) -% ************************************************************************ -function InitPlotGUI() - - % Setup handles to lines and text - h.markertext=[]; - templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array - h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively - h.markerline(1:NrAxes)=0.0; - - % Setup all other figures and axes for plotting - % PLOT WINDOW 1: GPS POSITION - h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); - h.axes(1)=axes(); - set(h.axes(1),'Parent',h.figures(2)); - - % PLOT WINDOW 2: IMU, baro altitude - h.figures(3)=figure('Name', 'IMU / Baro Altitude'); - h.axes(2)=subplot(4,1,1); - h.axes(3)=subplot(4,1,2); - h.axes(4)=subplot(4,1,3); - h.axes(5)=subplot(4,1,4); - set(h.axes(2:5),'Parent',h.figures(3)); - - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); - h.axes(6)=subplot(4,1,1); - h.axes(7)=subplot(4,1,2); - h.axes(8)=subplot(4,1,3); - h.axes(9)=subplot(4,1,4); - set(h.axes(6:9),'Parent',h.figures(4)); - - % PLOT WINDOW 4: LOG STATS - h.figures(5) = figure('Name', 'Log Statistics'); - h.axes(10)=subplot(1,1,1); - set(h.axes(10:10),'Parent',h.figures(5)); - -end - -%% ************************************************************************ -% DRAWRAWDATA (nested function) -% ************************************************************************ -%Draws the raw data from the sysvector, but does not add any -%marker-lines or so -function DrawRawData() - % ************************************************************************ - % PLOT WINDOW 1: GPS POSITION & GUI - % ************************************************************************ - figure(h.figures(2)); - % Only plot GPS data if available - if (sum(double(sysvector.gps_raw_position(imintime:imaxtime,1)))>0) && (bDisplayGPS) - %Draw data - plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:imaxtime,1))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:imaxtime,2))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:imaxtime,3))*fconv_gpsalt,'r.'); - title(h.axes(1),'GPS Position Data(if available)'); - xlabel(h.axes(1),'Latitude [deg]'); - ylabel(h.axes(1),'Longitude [deg]'); - zlabel(h.axes(1),'Altitude above MSL [m]'); - grid on - - %Reset path - h.pathpoints=0; - end - - % ************************************************************************ - % PLOT WINDOW 2: IMU, baro altitude - % ************************************************************************ - figure(h.figures(3)); - plot(h.axes(2),time(imintime:imaxtime),sysvector.mag(imintime:imaxtime,:)); - title(h.axes(2),'Magnetometers [Gauss]'); - legend(h.axes(2),'x','y','z'); - plot(h.axes(3),time(imintime:imaxtime),sysvector.accel(imintime:imaxtime,:)); - title(h.axes(3),'Accelerometers [m/s²]'); - legend(h.axes(3),'x','y','z'); - plot(h.axes(4),time(imintime:imaxtime),sysvector.gyro(imintime:imaxtime,:)); - title(h.axes(4),'Gyroscopes [rad/s]'); - legend(h.axes(4),'x','y','z'); - plot(h.axes(5),time(imintime:imaxtime),sysvector.baro_alt(imintime:imaxtime),'color','blue'); - if(bDisplayGPS) - hold on; - plot(h.axes(5),time(imintime:imaxtime),double(sysvector.gps_raw_position(imintime:imaxtime,3)).*fconv_gpsalt,'color','red'); - hold off - legend('Barometric Altitude [m]','GPS Altitude [m]'); - else - legend('Barometric Altitude [m]'); - end - title(h.axes(5),'Altitude above MSL [m]'); - - % ************************************************************************ - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - % ************************************************************************ - figure(h.figures(4)); - %Attitude Estimate - plot(h.axes(6),time(imintime:imaxtime), sysvector.attitude(imintime:imaxtime,:).*180./3.14159); - title(h.axes(6),'Estimated attitude [deg]'); - legend(h.axes(6),'roll','pitch','yaw'); - %Actuator Controls - plot(h.axes(7),time(imintime:imaxtime), sysvector.actuator_control(imintime:imaxtime,:)); - title(h.axes(7),'Actuator control [-]'); - legend(h.axes(7),'0','1','2','3'); - %Actuator Controls - plot(h.axes(8),time(imintime:imaxtime), sysvector.actuators(imintime:imaxtime,1:8)); - title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); - legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); - set(h.axes(8), 'YLim',[800 2200]); - %Airspeeds - plot(h.axes(9),time(imintime:imaxtime), sysvector.ind_airspeed(imintime:imaxtime)); - hold on - plot(h.axes(9),time(imintime:imaxtime), sysvector.true_airspeed(imintime:imaxtime)); - hold off - %add GPS total airspeed here - title(h.axes(9),'Airspeed [m/s]'); - legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); - %calculate time differences and plot them - intervals = zeros(0,imaxtime - imintime); - for k = imintime+1:imaxtime - intervals(k) = time(k) - time(k-1); - end - plot(h.axes(10), time(imintime:imaxtime), intervals); - - %Set same timescale for all plots - for i=2:NrAxes - set(h.axes(i),'XLim',[mintime maxtime]); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% DRAWCURRENTAIRCRAFTSTATE(nested function) -% ************************************************************************ -function DrawCurrentAircraftState() - %find current data index - i=find(time>=CurTime,1,'first'); - - %********************************************************************** - % Current aircraft state label update - %********************************************************************** - acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong),'°, ',... - 'lon=',num2str(double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong),'°, ',... - 'alt=',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]']; - acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.mag(i,1)),... - ', y=',num2str(sysvector.mag(i,2)),... - ', z=',num2str(sysvector.mag(i,3)),']']; - acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.accel(i,1)),... - ', y=',num2str(sysvector.accel(i,2)),... - ', z=',num2str(sysvector.accel(i,3)),']']; - acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.gyro(i,1)),... - ', y=',num2str(sysvector.gyro(i,2)),... - ', z=',num2str(sysvector.gyro(i,3)),']']; - acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.baro_alt(i)),'m, GPS: ',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]']; - acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.attitude(i,1).*180./3.14159),... - ', Pitch=',num2str(sysvector.attitude(i,2).*180./3.14159),... - ', Yaw=',num2str(sysvector.attitude(i,3).*180./3.14159),']']; - acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); - for j=1:4 - acstate{7,:}=[acstate{7,:},num2str(sysvector.actuator_control(i,j)),',']; - end - acstate{7,:}=[acstate{7,:},']']; - acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); - for j=1:8 - acstate{8,:}=[acstate{8,:},num2str(sysvector.actuators(i,j)),',']; - end - acstate{8,:}=[acstate{8,:},']']; - acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.ind_airspeed(i)),', TAS: ',num2str(sysvector.true_airspeed(i)),']']; - - set(h.edits.AircraftState,'String',acstate); - - %********************************************************************** - % GPS Plot Update - %********************************************************************** - %Plot traveled path, and and time. - figure(h.figures(2)); - hold on; - if(CurTime>mintime+1) %the +1 is only a small bugfix - h.pathline=plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:i,1))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:i,2))*fconv_gpslatlong, ... - double(sysvector.gps_raw_position(imintime:i,3))*fconv_gpsalt,'b','LineWidth',2); - end; - hold off - %Plot current position - newpoint=[double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong double(sysvector.gps_raw_position(i,3))*fconv_gpsalt]; - if(numel(h.pathpoints)<=3) %empty path - h.pathpoints(1,1:3)=newpoint; - else %Not empty, append new point - h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; - end - axes(h.axes(1)); - line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); - - - % Plot current time (small label next to current gps position) - textdesc=strcat(' t=',num2str(time(i)),'s'); - if(isvalidhandle(h.markertext)) - delete(h.markertext); %delete old text - end - h.markertext=text(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong,double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong,... - double(sysvector.gps_raw_position(i,3))*fconv_gpsalt,textdesc); - set(h.edits.CurTime,'String',CurTime); - - %********************************************************************** - % Plot the lines showing the current time in the 2-d plots - %********************************************************************** - for i=2:NrAxes - if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end - ylims=get(h.axes(i),'YLim'); - h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); - set(h.markerline(i),'parent',h.axes(i)); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% MINMAXTIME CALLBACK (nested function) -% ************************************************************************ -function minmaxtime_callback(hObj,event) %#ok - new_mintime=get(h.sliders.MinTime,'Value'); - new_maxtime=get(h.sliders.MaxTime,'Value'); - - %Safety checks: - bErr=false; - %1: mintime must be < maxtime - if((new_mintime>maxtime) || (new_maxtimeCurTime) - set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); - mintime=new_mintime; - CurTime=mintime; - bErr=true; - end - %3: MaxTime must be >CurTime - if(new_maxtime - %find current time - if(hObj==h.sliders.CurTime) - CurTime=get(h.sliders.CurTime,'Value'); - elseif (hObj==h.edits.CurTime) - temp=str2num(get(h.edits.CurTime,'String')); - if(tempmintime) - CurTime=temp; - else - %Error - set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); - end - else - %Error - set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); - end - - set(h.sliders.CurTime,'Value',CurTime); - set(h.edits.CurTime,'String',num2str(CurTime)); - - %Redraw time markers, but don't have to redraw the whole raw data - DrawCurrentAircraftState(); -end - -%% ************************************************************************ -% FINDMINMAXINDICES (nested function) -% ************************************************************************ -function [idxmin,idxmax] = FindMinMaxTimeIndices() - for i=1:size(sysvector.timestamp,1) - if time(i)>=mintime; idxmin=i; break; end - end - for i=1:size(sysvector.timestamp,1) - if maxtime==0; idxmax=size(sysvector.timestamp,1); break; end - if time(i)>=maxtime; idxmax=i; break; end - end - mintime=time(idxmin); - maxtime=time(idxmax); -end - -%% ************************************************************************ -% ISVALIDHANDLE (nested function) -% ************************************************************************ -function isvalid = isvalidhandle(handle) - if(exist(varname(handle))>0 && length(ishandle(handle))>0) - if(ishandle(handle)>0) - if(handle>0.0) - isvalid=true; - return; - end - end - end - isvalid=false; -end - -%% ************************************************************************ -% JUST SOME SMALL HELPER FUNCTIONS (nested function) -% ************************************************************************ -function out = varname(var) - out = inputname(1); -end - -%This is the end of the matlab file / the main function -end diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 3713e0b306..0da8ec568e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -604,6 +604,15 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "unable to create logging folder, exiting."); } + const char *converter_in = "/etc/logging/log_converter.zip"; + char* converter_out = malloc(200); + sprintf(converter_out, "%s/log_converter.zip", folder_path); + + if (file_copy(converter_in, converter_out)) { + errx(1, "unable to copy conversion scripts, exiting."); + } + free(converter_out); + /* only print logging path, important to find log file later */ warnx("logging to directory: %s", folder_path); From 53b373dd829baec5858212ab966cb4f74d219b59 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 08:50:40 +0200 Subject: [PATCH 81/88] Minor fixes to log conversion scripts --- Tools/logconv.m | 4 ++-- Tools/sdlog2_dump.py | 1 - 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/Tools/logconv.m b/Tools/logconv.m index f2ae6e5f37..c416b8095e 100644 --- a/Tools/logconv.m +++ b/Tools/logconv.m @@ -111,9 +111,9 @@ function ImportPX4LogData() time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); time_s = uint64(time_us*1e-6); time_m = uint64(time_s/60); - time_s = time_s - time_m * 60 + time_s = time_s - time_m * 60; - disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]); + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); disp(['logfile conversion finished.' char(10)]); else diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py index a376e03d39..7fefc5908f 100644 --- a/Tools/sdlog2_dump.py +++ b/Tools/sdlog2_dump.py @@ -200,7 +200,6 @@ class SDLog2Parser: else: data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) msg_type = data[0] - print(msg_type) if msg_type != self.MSG_TYPE_FORMAT: msg_length = data[1] if runningPython3: From 8c1f7a3706a15b5df2749f8ea076e457cd796f5f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 08:52:03 +0200 Subject: [PATCH 82/88] Hotfix: Updated log converter --- ROMFS/px4fmu_common/logging/log_converter.zip | Bin 10090 -> 10087 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/log_converter.zip index 2641e671068b1ea6867fc6b9fef17ba3889e5262..7cb837e5666f51eca7ed803dfef4581f01bec1f3 100644 GIT binary patch delta 7944 zcmZYE<3k<(-^cNj*TTZ`a-Hmxy|`?*YPD>)aI&#nC)+lc>twrS+pg>T{atr1-1yvk zfBt~S>v^QGuK-q(g@gYL002G!u*J~Cuv&r)Tu=c3Hg*629q@k406+**&m!elu)5w2X=!B!XvE3{K+cITC+t(;^Z@NaG()^>XXB{^xd|Z`x$d-=>Siy6KP1r zP&m6zAdY_A3USNJ?PGjgf-Kpnw8rn55frSXo!vRG6ny4X2)o{tF>mP!9wUqcsPVLpeDnSs!cKWEEsJ!V4tsIZ66z&Vm4*`bwn&S7wVxd*^1R}-Q_P9}Z#bX$tM z@yz(kO_anMXDP0F@s4Dk1@86%LB(HzEAOd-^5m|klYZ_`Ga@YW+SPsU7$7x1c2{&oWxW0`GPl^F(xak#nf5!~nB-@fQ|yq$h|^6|V`i)`|D4agc-oETq6vKwEA-PJC8 z49zwyIvpUedpQ#>y_{>i$17R@ckdpKWKC32k2kF^?UWtglYal6XZpR}{X2=bs?T-% zjat$1yME?K=9jk>F@?DHg>%qzmSumt?s-b&<_wJ;ha^pBVf#h`9{Mmubsl|KG5sn& zAkJQ9E4zI!VF6ucl&&VAhX(<;PTjFfH5nCfM^xm!y%RB;k6sia1>7wFLlWe3ELFI6 z_2h>O+u1xGW+)79DhEl^uR;Q@P>Nor3t#$$1IXx`VD3fCxjN12b0fM33T;#?{dvB1 zD~leFeQnf$22&s}W9TrTdLxJte7;$Z7evv0w^J|<_Ma*jvat5B@XRXF;up2o_j zv~5gZ;J$=nE5xCa3GI@Qf1^A4k$m##>$ zWwbqO?yz081bNauthLaMcGR-T;30+`VX6wVPqV0gtP^DOs_?Pk-&`Cznh6EB!33%+ zy-E@fKe$1F--wh&h-hSMz;Z)My;q*y(i^=4+S(j%@fb^yAL`hI4oMiEkQzNQm(HET zP>X{3tI$`Bt}W=)UFa%>idtlX$SqV~r2-mXCGb^v7lWS7+LUU5DGB&9XidD{I*kdR z$$YmQiqQ=7EPg7nRLPXKqV4Tw)ESh6#t857!CR)`Ix=W5jpC0!{s6{-Y2LecL?Ie1k!6 z4|aE!b%~d{gD$de76m^D9a7uhhJ!iQr)%sOT&Gi!Y$Y>)pfR3|wp2rAw1o4X9FDDH zz&lza+AT9?^DCf>^IO9V#|m(2t7n}D#3NS?19gHGjo9sW)(&AT(w!XyB25HX=^v** z6e^o(E~wxkwh`FtDGt&KSI0268HaXbTUPhMpH>jm^RG)9Ui@N^E>XC-;121a;7gXx zd&$_{jGd1}dL>KIp*f7BX_mK*7^D^ekB80GY^6O)FV%1Wco?%i_%=&28u?g>RtOo0 z8>hxPynk5Ra-`Ii9|4tk`1z&cmqNdB)Seid`F5*{rQAH9jHkE>L`|3H*Y?vQ-CprA zd?lgP?KJs{exglaPr)(iVIEJCLJ%G6AyV>^Xl6NpUzuSp!dlMU4k z&0R&EwXrJd5}p$N?AjJ$nP@r&FTxKTIX!tMRXb=7h0)q8pqeuk@RthO`$C5n5eivq zCj4&vl606l(3hW3Pa3UtZRDA~mkV1@KPBMCl{Sam_Oz7#Xm3DmtO=-??GtWHdB0iK zmYtLFXtgc#W?d(d$$SZIf|-Hr8r?Wp)0l4Mubj&>8kGrB4puOFleOrAQRQEauGIP; zvf{p>{4|+fWsd?uN0Ug`X>@IWe*bb>Z2VVjWX5o41|^+UDwWCWii$Ch%7Z=it5sY~ z$79YuGs+G@cK6!}`N@&JMvd^fQC5-%M9p}j>Gvw`S?0oe+W2}}e@EatB@0Jmfy7Vr z?>}v@ZN{}RV=DN7WKTy;U^t+SYEj~@@}+1MVGhS!o~ybR4!;{AF}Kf@kG>0bOT3Sm zjI{oC=duWL`Bxx*ecsR(4$5Qd*~1cPX3f1CZ}i8aawjjbFc$G3l{^yW`=vzWfek^MSK9TuEHu$S(Wja** zAsFXrV6k)F!tRNxS*Il4_RM%I%(PB!O#nY@B9p0+{}A4w`*u*wOB}V=?bB7tMvC-c zYu1DKqr?k2aktQcaXx0wFAofU>fh^f`%ob z?4uYC*NPl^8GZIJaO+hwPITvF^=RpPgq8AXqaxpHXR`(;A8MzHBMuP#8brg-mAVrM z%&0wZ>ekw$dBCz@nP$b&ebre-!fuwltVDLz81WHMS;QK`1-UZ zAY%7$ceCZiW)|EV+cR1gaN6FwzBWMO!&jx}M(p{ErQh7i`_kd8{gLPXrDXxBhY(}7 z_XWlF>)pnEsS7&gL>Ws57M&8}xmasHY$gMG!#2taxKk9KdbM=usQtDx!~oR8M5dBz z(k~KCYl0)KKKT<3r>8cUkL{}_HExF@^(D2>?t;d}#t>^%tqyEix5;W(H~|pk$PWrZ zI6F3iOYYTkn`m{L)pJ{lWS}59lB?&df^=i02tT6b{ODgZqkKPcpW+Mqifcxj1d240 z9Tcqx)6oHRFZ&El1xFpX0@@P;7L*3b?5r<^*g3g|S{_eY+8!bK9$#Tr(zW5E`=ndv zG1fD`+`3=R^SE=(xqa}D*Cz_;WSb?H_u2tbKp!%xJYRo4O_D+vZH4D{8?mvhCG&c5#zi zC#?HboM!)op3Y=;?33nFH+Hh3_Y}SqXwdlS!PlLE6oh{fN&6u`_@@u(N%+4B!}zaZ zB>yoCkF~rI9UcH+W(oix|6`bc1Y>Mx>&k5NAHD?shc9(ks8a~w)>)R$p6WV*DBRb` zSX5aB)0`p>Cv`}JEQbnW6(6eHpRv5^@E$zZesK38TT-j0?JUE>x6ImaO3KBbM{=m$ zE#Ico=Mr|b=rJ1YY`a7NHo4M#Fbm8)@nlDG=Cx!w<_?d`&l>CpimkofCLn<#+YKi> zs?k?am!U^1F>eK!hZFI!Qj95eXB_BX>(4QujHbZRB*dQ^{;ODCKFM zyQ?Q%m7CbL%q+$H?&1SE7F|UbzV;Mqa;x#OjsICQraRZU<#7|4l};X=n#tbEJSvr% z)qI}r9;(2v)2IheXsh{{e1lGWF7F`C--Lv-{eHl%ouaPS64D)PN?(H&DiY|~l} zvM4Akg?Hj4B35e#UWcV#g>gv~U3n=eH$&^u=rDGKC1}8YB!z`4t1Kt6A zuEuMsfdydgd0g^EvTVOv6%?i?T@9dy;f$yraS5TJaC4Ji&(BC$M)+ZNu^gFXwGa4) zwey%Mxx)$l#i1wCm|nSZGRpaZC#(rvQ&wlYIs~St7wLr4QYd1x&1@{wFSb^h_rxWc=uc zcHgCCC73)|Z>v_qls*o`*QttbFy`Ajsj`Acg>Va^fH77~HWj_iRtU@FhgN2gQ*>c!ll zD|uRG)~Lc%^DA^LjPpcPc%QAgUKMdphQ>A(5C#H~X76R)1@gTxm$hUZM(MFsJ6uS? z^xyWVj{y8ywCOy9w;EcX*v-Cm&L7G9zaKR;4c;6>PJ1l_Z00TVm=EE{a(`fqV3kNl zGo)?oHBNB3#HO|!YSPF{n0)q)*KO&k=xM~DI(#Q(m*QIIHerxfTmsm!veQZWC{JTg z$;;hx>}gbIK5<|%gfU91Rmm3mX`cmw6PYaH5N>;l)IIfNYMvO@o-Kd5BSj?C5QTRv z8S2n6ZLaTHWQb59txGM`M}DUOBYR`~;PY4K@W@EWgs+CxV38k}An$is+%Z9=XG$g# zEnfNZJ#kJShQ4A*Rpz6*QIlMxiH*qzo|P_o%w$al^T~b%HzRUNq;HUk! z4d;hc(DF|2Zi*iIpf}@rLGPpKm+=s7T+^*qL(D11THA0LcMQePA2kosKJyD#gJ53e zgJIf{dzzwHYqevot>OYr({5NQ)nMJ5yCS+i_N1l)^Kq~#E&@b%d|#sT_`K8z<;m7R z*~R+pid82>sW~w$t;%td0@HL$zGu zWJ?=aGlw5rQzRNQ=!mTlEfuZyWnpEK31uN~xb7UqeFx_4nKw~a;Hv8js(_2Q(|$c; zgj+7wrvn%KzMv1@!TTEB8c8Xs5|Du52H6gtbVo1H6hwed2_6R!$m1p0LW48K zVWKD#5KI9gT3hL9R`$zkrcCq*J79Dwa)>0oqHtZf?d9i81Bq?HG|2l6aVBhE8fn*MwDSmA|*i%BOK9geWF+ts2c-4`P z;88L|oXO^UARL`_oC-@@{cC4MEb^i^wo^#jDO1MiptlLW#&~+LHjJ6MK3LD|3!^x1_kI828q>lv9FMRV8uTEYENrq#xvax7`$-Bdp>PzJjN)3T7b16DzDpNzRk)aoS_QmKGs2&BV^zMf z`h2p$xLBoLy>8U)BZcrxjCXS1T0PVrE3tQV4Mw07!%(kiHmXL4Tl9EOY&+c=IvYeR zEEeWEbc^sIoj#|0@|OE!Fmui=BUuaMi?KV>(x5VXNF)$HQ@&7T?1#COE-&iQCZR+{ z4IAJ+<7R3c7}wwze)D0a9Bd8=!-MqiVLsa<$0Ik7A=+lIXsu<>UJX)nCw;`0_NSc1 z1dr+xoJf-f=H7t_RnFW7a7I&MbEnsk+hm(OeK<6<#hRji3-w7dBy82UbUU@5STq*2 zY>oehQ#i`7-R7OM+o*rq{dJR%TY}Y%2SXg+Ymigc{9cObz<9?(k+NHb8a8 z1qltA=Tb_#rBFADlM(Ix)3YEsX1^>@P6~>NmOe@zzlyYIJ)1M1C6W`lYs(v7f>%xG z$kG^wf_1`JwpU>V?v6W=ow@E)5fIBS&B zdGlLyrbOo2_x(9EzA-Rp_6}@$*>Vx5_(t*~sFW+NqzluX;XiH_eiT?%Nb0Uz>r7C> zi2r8b{^DcxRn{+)pQdYd$xYE$k^MZyS5mzskN^;}A@=zmeg@(p*EWgw=G+~R+0}$( zF<$=itw5#Nx~zD|fheCv(eK6vOqBmeS$Y@j`9WkqfBoS zuc@qx)%>O*j{{vlM(5%CxhnJ{6N9tzP zcqPNY45Hagpg6Zd>5G)`s54d$rnvDpKiM$wnO|;)`tl^c4`+*iOs#voq@s=L5V1Hz zkg;M>LcfRIHD^(ZzJ~?x-r9zZ`6iRs*wx8bhT>Y#4wo~Drz{bP(PI?3$3o}-st9DP zHtZPEZD;@Z!s_s%io|$#sG6(=CC=L@+rL_o{p_`I=vIi9gM-VePUuxPV}VgS>x#P@ z-~Ykt`(F3>GwoI7Z!8i|_qnb?B>nP@<30nUSx+M7y?L?L;P62(N&R_orEtd$6Zm7o zVwRD=$>qM^!+3lE(%A-cWc&C&Q@ zW{-voHAB9T=_fBe(W>?t9Ww4cOJV_Ay87*Jd9G!-$kX}kSah5G<+Om`hqr`0!Cwrk zoXB}ME(m7eNi6fgS08hi#|S8#LaqqH=sb%s71KBA2H|hGL{wGXAVhA}v*A`kd;8wR z3v3pkP&5CHT-?{GG$uJ6P<~O%;~3j-K%9yq1Zbp+wIzxz^|LUXQEVgS(~UPmE>gJ~ zmH1XUCW&%JYG;n05vRz<&&|}2@r;zgrgO;*sY&3XmH9|;1_jf|p#HAgMmkPbHBf0VKXE>?tYUY&!${BE6n$s#&gbF{#`X};iD!ksZ z4HC2qI0MANVf@JA#!}UfzcAiBI}O%yq^JOxCI zlRgNcOrNG_z5hLYyWP(iop2v0X#eu}O^oy0cdUBwCGGiEA8gMl1SYkK=iVxa;f-1K zn%;FHbOwN(jK_P;E&<9PC-;FT)&tX^&L&AVs$Fg2Xhb+%r6j#{Qv({ZZCzL;q z*4P)AKpnUq0So`QFZ@mW>q$m&jN0^cGK+|B^azQ59zK3+K#`i=C3Qta(BWpACb8d` z-43>==CNQW1MD-wWNVk3v&o0e0dg!EK5!Hj&TSv>ZxxPTzRY_8(xo)z{-Ym_SmJ|! zv4}f?C;x<@Je|oea!vi&n8C{<68<_*wW=zpaxNg(Q0S4&ij&}7aS*#4>V59iGPt`t z*gSab$aY^GuN>-aeSp0<$f@{MD8@UrLU$?Iy+bM0^(P_ybwGQ)Lwq1dd-S{OOu~**CN&qj1_HIxJbDE@pO z-m01RPMu8qY8!m|rd0bk!(Pxnz0hW;*yKyl=^FFMbY;vZyARdK9lw25c0;u4klD;U zY9xZ_uS{Vcwz}N5CWj*MKK~w4Rj=hn1D{ZwqaqIm)`pyUtT)K}IEcYEEy`Y$*tm(j znCr!F+}rI;bDT4B-z@p~^278cN@SF|bIblxr|UzZ$iU5HqWv(W+mlRVL&58+VnWiF zqNd_%Qp+t|r^>EY)*ql5jg>ElgJyA_TuCh4+%V%Vpu6fkPnur4h|K)7_V-~w6&zZ^ z=?Umpx|9Mp0|}vQgO1sM&1YV;|1zM?NlMI1`nZ-}30+wsr>WH`3{{vN87QhmFS<=o z>4Cgzgz}_UIDN2#(8^n?Xvl1Pb=>`|Sqs=5zrs5zr@dW7vd@u%kJ9fIg^rC1?1mLrNc)=(jJTCJ8 zIf=^U)_)hj-t_mF3)PZ(_^D^w#AHT{Sf4|V()#ktc=WjT{TQVf=~Z}e61B;d delta 7942 zcmV+hANk@6aWAK2mstW4MU?f-i&w*002oc000gE8~}4009K`0RR956aWAKy&C;*+qUxO`mbOW1hrSiOWeL; z3zi3@O}Z6p+N?<*_7)q0B2%_rWlGbBQ)Afw{_aSMq$o;%P1a&U;MhFg@$PuMFLCej zw{=;3dz-LtDch2KSFJNP8pTDnAwdw=Rb9{^Aju}rii+e#!YUYLQI+5{&-2deO-=wk zEOsQ#R%AsPEy9W}$?c9@{`UMyNy;SvW+W@f>E#6pOY-vSKO+Lq=tCK<=&@W?&I^`6 zahmVQkML`M3Y7m%ZVt8!_@MZ)Buknmo1~%z{$zyJX^P)ABu~SH0ioM^MY6ie>xv|-tZ29-S&ZyW1$<6KPJorIOwwkJeUCRqv;Hg zq=l7#RZ&NkPs&{hV=?}puIVRmF~4nG|}JA~)e;W1~as2NMx>XO^gGaz_f)O1AC zlJ>w~g#a6kqBJZ^a&`6wZ0<5FN?M5dFW$U+`Acy1`uB5~`~A@mGd>F14Sqg9Jv)CN zyg7dhkY}yoBZ7>bwg+c?@P~h?!B_9zUz}cl2bZTWe>uOFbiV(=247vj|M2n}HS^-d z^YZAs^1J7yrzTzh_wroM9F6b=>fo>eI-#P3%Ctjq4I-DLJnUI%% zN+=sbl~6Y1TnS}E-k3Q2X@M_#_u~%^`NIMEl|z1QL;m8QK@gSOfO{Y`8{acV(Z%3k zGqx#LL7b%Es9^MFAxEoZLlFdHNL`L{2N{5aRHsJL&5D9XRUo{f1q9+WVBv zTjd0~+asGWcaclOTks=JauQ?^;v)ADLRiW5O>9B}1TMZ>Q&J+0tiUJ$K|!AK#$DTl zZ|gYbyLh{U$W;{KZae|Pau}mX!Z5PQ;Jgg0&?b>rh<`|0&mO250%4v(tfxqSM3S_T z(Ym56tvAdNZ4W~g;hWvSfPgd@DH;p_cbl++gK+iJl&jKnQAd^y?IZQ521=}ILL*8E zv8P$fMWoJ`JRLEu)Y=|#9s<}rx!N9)M?|uUkrJRjxl5`wdGd`%=%*Y)C5Fw6#CXKg zq^xk7h?Z@$1)~M6oHZE&H(;NCs59HOW%D?z?=G5eVQGUL9(Ff1=?0pw9aJ=AR zQqyX2pETt{^p6hBYj7$+S5jPraV)Zn(4IE_fbo4!Wz%H z_iD7)a%m17+Agm>(4r5Dq;KIQOVY|AN~(_}Nz+lP?_x$0>k;x;cuk3aY+?gqmQyxX zbA9sU?&*_>n5k1B8;LvNwuvuADM;F&*`&*^B<4Kq?%9?CpPrDT-g!~Rs)QLvWY7`0&&IZnS%e}Dt8As*dQJ>-#nGB!;3slmQadI4O$ z;@`}-bnM%Topj{D!^l&tfsLIxH&$aB`)5=?Zk_Fs9BVl%clykJn+E=)UaV8D^>0)6 zY&K6LCvpYB@C?&`&~aB!{Z`OO#FL>Rc~kC5PV9~q-^@qyj+23a!vdP86Q0^>tAl1^TVtieHg)rVY@Zm1+YII`tGWpkN@wS2 zG8-{rMwWf-3^3R=1fkz&cZS^YG)l9Q$`PX+)Z6Q<2zj7v`H~4au%$A{iOfLfp-p;V zW;jOX0j2Uco~apQxptxf!O#xVZ9-10=?d~F#e*%Iov&C`GFpzMls*n!S%jHySt%AT zL+_DcO~V|2lB4B#tn)U|m*M!oB&Wk8ZfcP4g@dU+EsLVOrC}cm(}~L{ADA>YqVZua zik{Tv5Gz8#jr43><4=hfc<{-w`c!RH)s3z-wXWB&s^uF!cVTv08tocoz~eqI&yVZa zB#hPP^nY2x#$6^SqQE&ZNNX?|jU8;ICcfHce(k-pwyKr#blq0FG2dQFc7DX$fN9P0 zF#0&Q6Eo52_IndcIBL(xaVtw7NbVLxqCbqEsu+JQo-|WNCe1C=NRz~-bdxPJi++5c zEV`9{k?~cII%Yq#Z4C|C)j&mXDzk-8o`hwTBu^$&7)|oAH$U{;<$~-D8tBg+g07mj z3jKKx`n1f`q#Ap^MagaXZn^%RIDb!ydojO9US@1di^^QQ%G##e^k0!4TXjr8%++rV zOxUJQE6da3gWfhmC#zTOs<0|{?({lt{H6VW8tW!<7Xt>DkkZC|HG^VUg;FqRNAblg z8S)F=@tz>|-g~MaN99x2Ilj5X7o|d}(K;-k0OAQx)8&U>c_lTL(6&?grmThTEV&B)Kh(G3R0;?WavH(5;Z#tm@g z_8M|hlQ1QV;n*&Xn;SYzc6L68-Bf2m@(tNM+)+A$_yg61k6GkOzwZ#LVX9Mq++&ws z*Jnc|wPL%85dsZr>JyBPDosjkQ^d#c?EB?$%Kxc%H&9BNP6dO0`1!C=#R(22K$q4pr75f6Hs z5X?euSJQ0UffW|3Ew-O$dPQk}W&g~jMgUgi`t`+mfZp)!>BaeC&J2emnVDAy+j(`r zJC8m1bY8jcK=#aDiq+=&Lgd_eBXaKfbFYsGYlxs8=3j6_vWI@JTIaCxy!z6sl7hh*Tz7G2kN#Sp{4bbXh}xg|MulPK?l1 ziB0cQNqmW4`E?d-C>f?vR!cxNkc^vIF~fvL9*3q`;J!9CaB0kSC#`#T&2`7kxH{sY z&cvwm3L0#I`IFxqDpuTmHvG?y7p)EzqBujbgkcO@IvUg_r$E?>Ck8U>L6(9K;#Lk^ zLmh*-v4#7{)Yu^A=Cl2Oc=Pp1^MrzI)3XR1iIH@zA-+{P>ha>Ob+9+p*95`G@y-I9 zX03M;R;;&7LV@Ywf*)n`3w!0{Ruh1GzaiprYG^( z5T45bB;IBS&tuNuO$P1V4Qy-^dDjS~le`P^Kse>G)1_PcE1%cGC%#TL@2T)4`1QY-O00;m!feS;w8a8ez7XScVW&i*Q z02}~pZ)am~ZgwsVZBT+Xr(x4KP!lZbz;v zPJfM|z3Wi>B{{K)(CMD$La4I9o&(~2@5nYj<>YefwlCC~P9dhg^$oBv=hQieJ?a@I znms&1U_?qQFhN!{!=>(+cAKCRZUmmqyW09K$ePw@)`gk%ZEFS+sx|A;EprBby!J-? zy<}aqXiTh4%Qeo@&<-I4DzR(1p{X@t5PxfE$_*{8^^${qb@&npc-6vh-W7NJc#eB( z7A!T6`743%D~2T>-K3*|Y97_mF?>Q3wOiwuzT$}S-xeD$Vk$A5jY$)`XX)sIRSsw% z_6*>qz__BZ%d&C>GU$WtUt15rO1$6+1Vx>~@)P_=Ima1rtttcX3ZP>*);&d7ntx?& z5rPc@8YnBZ(4xO(Wnu+39mLgKs&q+(fB`0J9f2vTOj(SI z$cYreC(54`MM}sHLunJe=1%n1TnlqBLnS4g$4|gV$Z{(OuhtH{xZIVb)vfYOtFR(t zs%>r3l}xK3ifLp`WVAwy+u`!Un18E^A3Rdp0`norUT3b-!oC2q;{dkgg|t-Ek_S`& zx~<5hB-p7cA6?J-26O9n2exu&MSCf>IS(XZ<#uBix~v;qgz+MzG=*9mfjlLI!;UGb z)oQWzP{4^$RFR%jRyqLWIXYFLB_gTS&~5uxH@+(BpJ6+rK8CoJ%KDBE?3CncOXg~17r$yRwvP7EQeVRzOxSv);s4XW$sP#v(N1@(M!c&EMgSb74b;icgvUe57om*>6vwP0G1Xi5p?{KOULyOygN4G0 zb6jtQRUmVg1mhdwWd3uGv1UHrQsZHtLd2(A+5ou`GRRM*(Gvb$p4JIO za`1h0O^fFx@|VyDA*Lf(4U<<#Y5m^{Sd}z67ljm8Uz3wDsI*9K1fgzocvV(y1*o(R zPbn!>d)+cIlC_Z`;A{h{L|k5@pg|Wq(}m?(rA+pmt%4{ z9QU!Pmk#HfaX24lS(u6If<;8j$+{^j;Xyo6C|sd$QtbS|(ggH383yns2;Vls$Yw>d ztw|D^ZPLHEQVHPU0xtq92xn%RkXB5Hzz+tI1M)kL>hMu%G=Y3SyhR3<55ZD4Qq8So zb2HU^m~3vPntzXy&4(GhXts|sxzS1o)k%)D+N3j?^e0!RJ<=Ob`WKx^PbHo1ZQ(t2%~z{n7Zc*E=1@#w?!YaFb`9fH8{neAp4uA|8+q%03=m!fVU(*QPo1)0{ls z&dJx?Ir(NgC*SVo`Vl3W?3Ok_JVGtK0 z^ckL31zTBSX0po6E0{UomA0D1nTlv>_lNs#OUlkCMLqXBHJ7@yd1P}99s7};ZbN)n zNn%d)JAd5*=gBss@?Y5xSLKb9ZZPKNTo20PfLB`_@TycQ@9P!v;sq&7rx~RRCtXiE zUwjYIXi1j+Dbu}7A9hs9R*x$iw(C3_Y}hrn!-maBRlHhc1@IGK5?0>py#rPc0pe6<_JZnbqM4-4K zNyEs*Ber-ZEWVjITqYbEsVM!-D!Ro}czzX)_iSqZBM(ERCp=-kXtY+dC8&yIop=u`JN< zi+-P_-lX=j@uproXw@2rjia}j+73u7f+X;+gG`Sisq;9*0|IDn4G={2*YA~>RewAt z6lG?AlU1(^v#MK=SKXq_>gI53quXTZg?^UiXPeE}bi?43i(^95Y9145_sN8GC!=$M zBtqXtt@f&c>K`>wnlf8}h|K#8Ycj2~mZvPrn_`PHyqeT+hG9_O!9>xoQLtaLV82$u zeuoA79Tn_%T(IBk!XooV7MaV>7k{J-K~%NkhQT@vVCVf;?zW2~yB`~vqW;*V-!1xm zNWYKh_c8r`O~2nL8Oa6!LXNV(q`S1@M^h)Q=S>@MBz`OR2m4c#_E`sf<1P>M6=2G8-bXV{kJiaSFNIH`BK zji*z;fz#@j>(TRBq)G%|1awRee}%5%{;NjBvDm+eV3xmD_@P(4s`9I9W5dCa*AFvU zBzFZP*z)-X2pWBT#R&F+et&jcA9LLNi6Mcyr8RkaJjPZMZ3|Z64<^}sY9bz0+dx^? zi&TY4Dg_Py3SS#F!)f!de$YHRBB@_G%QL3wx>uu7Z!iJb?~XcW6HHO|ep)Ff{~0B| zjB^Xb(~wG__=KhTAl8Y?tA^d^G3)o5I8f8TT7u^XvIDv={F%p?eSb2K(1j=AdKP(h zd!1J|=rsS)P}~2h#mB)*KKXm__dtmfL2U&DcM3YMDXJ5$nttGI$!O2!CdN^|LAJoL- z3|ti&Kh~nqkw%Wpj$v4n$&@$*uB1ZLqRgg&Q7&vA3Vtteh<~keLDS%I18~N=zD8ap zSv6H8f4>`e;HyD^*p59u^lbj2HQI+6pr-O)*~p1l8P{ITMyL=J!M+~^!&vo$KtvRt zgj0&Vw=EDe7Uj*3MH!0F3!<@ufB9K!^Cko0RQ@Z25-DWP=EswuH1-0exfdv{y+AqK z3zVb1KsnwElz-Q|B{l|$TYF3KbaK~{gQbjv zigCci@lPGF*r!ijVkLKsg0G&-Z!b~sfv4Y@HiTAKz*K4Q%}%F5$Wq%`lus5Tta+IS zJMW{&yFyBM?BP`dA0KqFg0B;Qg;DQqxR_fH=^82?dwYe3-UB@B= zYD(+#aRt5dPHTbOn5%X0xTVmJCym;ziY7>t%1ESyZ?2*MK&IDg;23g%y~Ks&fWv1@ z6L_eN%6}_}YBy(y%pJ;SB&O_5Mm%wbryLW|+W<{X-Dz&z!BQ)(`Iw*gbzH}!(IB1) zf{R-8M{l+;Y0;3L=H@rYKmtfgJ!zVRO-YCcO&pb(DzXfLV?NNg6o?+MQjrjevqpGC zb!Pg828PuDDNx{+@EJ(L= ze*Sx>``4d$GC$)Pm-2FW`w!K;12)4R^Kb6gcm2WD`22meP2PxCJ?1=e^GTP_Y0v@u zeT_K}pTz@2DL|i_u(KIU)A;JQ+0EOY=YMH)9riBaR5#ir%I{;@^VTHqNTQ4ZnoyPy zelH3Tb(%nL4W@y zF6bLKVcSIif=^$JZu|&YlW4J$J3x+gQd1RCe}9{05)VvD7K#O(gg?h!WdpN7MUDywmGV<^I$ubS zY3}MOJ>$8j2lUC-33ooB&uh8ZgT9r9y*bAZbnuOm?+oV5WR*99o*khtvhoW!d^r^G zy(G(Lj6`6^Bct0u2*KF#IJE?V(|Be%pyLp1-Q&AJ?$ z^t&0h`$Nfkcf$3+ahkRvqmpqHws*TMOS?Wkydl6Q^g;qkl^(O zPRUTM77t!IN{}*DG^D*>x_12F)=uN`Y;n_Be{jlTC%EW$d*h#HB7dgV>;V)*#UK6Q znrI})9Ls@vqfPT?c`q(h8x>g_`Pr$;`^c{)Y*NiSA-A5Xe?3V#V&6TJaMAE}`ivrN z*Z55oHn8Tto`ARwYvBd5!Ia9#2@%LeZTiDA%2a>+sdL^x{n#0tp7(y9Jn?i5p2$lk zZs-qNEilmRwVijm=YQy{sIl_Cj>g(Hokg%LTYhpVeR40A8cOzn4oUNjI~Q$wU$3Rx zXgfnO9TkX=X9l6?q#6=pBK{D+0-y-)pJ{FXay6ci@eq89@dY>)L%$j}ZYdW409|GP00{sX00000 w009610HlGy3;+OZZ)am~ZgwthRa6B411OsZlkp}x0W6a&Cp89PCIA2c03YQ>G5`Po From b6676f6cb8306fb99274f8e0a784d8846928d920 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 12 Aug 2013 23:54:35 -0700 Subject: [PATCH 83/88] NuttX is confused when it doesn't know what board it's building for - since we don't tell it in the config anymore, we need to pass it a hint. --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index dc69b0ae8b..778395cee9 100644 --- a/Makefile +++ b/Makefile @@ -151,7 +151,7 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(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) export + $(Q) make -r -j1 -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)) From cd928b64f38100e91b7ee927a4b37dc58078a844 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 Aug 2013 09:10:47 +0200 Subject: [PATCH 84/88] Fixed log conversion scripts copy operation. Each log comes now with the required conversion tools. Eats up only 10 KB flash for the good cause. --- .../logging/{log_converter.zip => conv.zip} | Bin src/modules/sdlog2/sdlog2.c | 8 ++++---- 2 files changed, 4 insertions(+), 4 deletions(-) rename ROMFS/px4fmu_common/logging/{log_converter.zip => conv.zip} (100%) diff --git a/ROMFS/px4fmu_common/logging/log_converter.zip b/ROMFS/px4fmu_common/logging/conv.zip similarity index 100% rename from ROMFS/px4fmu_common/logging/log_converter.zip rename to ROMFS/px4fmu_common/logging/conv.zip diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 0da8ec568e..ba7cdd91cf 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -604,9 +604,9 @@ int sdlog2_thread_main(int argc, char *argv[]) errx(1, "unable to create logging folder, exiting."); } - const char *converter_in = "/etc/logging/log_converter.zip"; - char* converter_out = malloc(200); - sprintf(converter_out, "%s/log_converter.zip", folder_path); + const char *converter_in = "/etc/logging/conv.zip"; + char* converter_out = malloc(150); + sprintf(converter_out, "%s/conv.zip", folder_path); if (file_copy(converter_in, converter_out)) { errx(1, "unable to copy conversion scripts, exiting."); @@ -1265,7 +1265,7 @@ int file_copy(const char *file_old, const char *file_new) fclose(source); fclose(target); - return ret; + return OK; } void handle_command(struct vehicle_command_s *cmd) From 56d355414cbfef92b39af6830932e7f1487b03b9 Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 13 Aug 2013 00:34:11 -0700 Subject: [PATCH 85/88] Fix handling of board config files. Treat CONFIG_BOARD like CONFIG_ARCH in the toolchain configuration. --- makefiles/firmware.mk | 5 +---- makefiles/module.mk | 3 ++- makefiles/toolchain_gnu-arm-eabi.mk | 7 +++++++ 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 0d742c37dc..ecff77db9a 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -153,11 +153,8 @@ ifeq ($(BOARD_FILE),) $(error Config $(CONFIG) references board $(BOARD), but no board definition file found) endif export BOARD +export BOARD_FILE include $(BOARD_FILE) -ifeq ($(CONFIG_BOARD),) -$(error Board config for $(BOARD) does not define CONFIG_BOARD) -endif -EXTRADEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) $(info % BOARD = $(BOARD)) # diff --git a/makefiles/module.mk b/makefiles/module.mk index 9e4cbafc9c..9c1a828cc2 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -98,6 +98,7 @@ # # CONFIG # BOARD +# BOARD_FILE # MODULE_WORK_DIR # MODULE_OBJ # MODULE_MK @@ -117,7 +118,7 @@ $(info %% MODULE_MK = $(MODULE_MK)) # # Get the board/toolchain config # -include $(PX4_MK_DIR)/board_$(BOARD).mk +include $(BOARD_FILE) # # Get the module's config diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 3f4d3371ac..9fd2dd516d 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -85,6 +85,13 @@ ifeq ($(ARCHCPUFLAGS),) $(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3) endif +# Set the board flags +# +ifeq ($(CONFIG_BOARD),) +$(error Board config does not define CONFIG_BOARD) +endif +ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) + # optimisation flags # ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ From de749a3602423f5ee6ca56f3cf2dfff04e31ec6d Mon Sep 17 00:00:00 2001 From: px4dev Date: Tue, 13 Aug 2013 00:34:41 -0700 Subject: [PATCH 86/88] Stop expecting CONFIG_HRT_anything since we aren't baking it into the NuttX config anymore. --- nuttx-configs/px4fmu-v1/include/board.h | 12 ++++------- nuttx-configs/px4io-v1/include/board.h | 12 ++++------- nuttx-configs/px4io-v1/nsh/defconfig | 22 --------------------- src/drivers/stm32/drv_hrt.c | 20 +++++++++---------- src/drivers/stm32/tone_alarm/tone_alarm.cpp | 4 ---- src/systemcmds/tests/test_hrt.c | 2 +- 6 files changed, 19 insertions(+), 53 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h index 5529d50972..839631b3a2 100644 --- a/nuttx-configs/px4fmu-v1/include/board.h +++ b/nuttx-configs/px4fmu-v1/include/board.h @@ -158,10 +158,8 @@ /* High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ /* LED definitions ******************************************************************/ /* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any @@ -241,10 +239,8 @@ * * PPM input is handled by the HRT timer. */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ -# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) -#endif +#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */ +#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10) /* * CAN diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h index 668602ea89..6503a94cd0 100755 --- a/nuttx-configs/px4io-v1/include/board.h +++ b/nuttx-configs/px4io-v1/include/board.h @@ -118,10 +118,8 @@ /* * High-resolution timer */ -#ifdef CONFIG_HRT_TIMER -# define HRT_TIMER 1 /* use timer1 for the HRT */ -# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ -#endif +#define HRT_TIMER 1 /* use timer1 for the HRT */ +#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */ /* * PPM @@ -130,10 +128,8 @@ * * Pin is PA8, timer 1, channel 1 */ -#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM) -# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ -# define GPIO_PPM_IN GPIO_TIM1_CH1IN -#endif +#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */ +#define GPIO_PPM_IN GPIO_TIM1_CH1IN /************************************************************************************ * Public Data diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig index 5256722333..3785e03678 100755 --- a/nuttx-configs/px4io-v1/nsh/defconfig +++ b/nuttx-configs/px4io-v1/nsh/defconfig @@ -200,28 +200,6 @@ SERIAL_HAVE_CONSOLE_DMA=y CONFIG_USART2_RXDMA=n CONFIG_USART3_RXDMA=y -# -# PX4IO specific driver settings -# -# CONFIG_HRT_TIMER -# Enables the high-resolution timer. The board definition must -# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/ -# compare channels to be used. -# CONFIG_HRT_PPM -# Enables R/C PPM input using the HRT. The board definition must -# set HRT_PPM_CHANNEL to the timer capture/compare channel to be -# used, and define GPIO_PPM_IN to configure the appropriate timer -# GPIO. -# CONFIG_PWM_SERVO -# Enables the PWM servo driver. The driver configuration must be -# supplied by the board support at initialisation time. -# Note that USART2 must be disabled on the PX4 board for this to -# be available. -# -# -CONFIG_HRT_TIMER=y -CONFIG_HRT_PPM=y - # # General build options # diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c index 7ef3db970e..83a1a1abbb 100644 --- a/src/drivers/stm32/drv_hrt.c +++ b/src/drivers/stm32/drv_hrt.c @@ -70,7 +70,7 @@ #include "stm32_gpio.h" #include "stm32_tim.h" -#ifdef CONFIG_HRT_TIMER +#ifdef HRT_TIMER /* HRT configuration */ #if HRT_TIMER == 1 @@ -155,7 +155,7 @@ # error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11 # endif #else -# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y +# error HRT_TIMER must be a value between 1 and 11 #endif /* @@ -275,7 +275,7 @@ static void hrt_call_invoke(void); /* * Specific registers and bits used by PPM sub-functions */ -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it. * @@ -326,7 +326,7 @@ static void hrt_call_invoke(void); # define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */ # define CCER_PPM_FLIP GTIM_CCER_CC4P # else -# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set +# error HRT_PPM_CHANNEL must be a value between 1 and 4 # endif /* @@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status); # define CCMR1_PPM 0 # define CCMR2_PPM 0 # define CCER_PPM 0 -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Initialise the timer we are going to use. @@ -424,7 +424,7 @@ hrt_tim_init(void) up_enable_irq(HRT_TIMER_VECTOR); } -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* * Handle the PPM decoder state machine. */ @@ -526,7 +526,7 @@ error: ppm_decoded_channels = 0; } -#endif /* CONFIG_HRT_PPM */ +#endif /* HRT_PPM_CHANNEL */ /* * Handle the compare interupt by calling the callout dispatcher @@ -546,7 +546,7 @@ hrt_tim_isr(int irq, void *context) /* ack the interrupts we just read */ rSR = ~status; -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* was this a PPM edge? */ if (status & (SR_INT_PPM | SR_OVF_PPM)) { @@ -686,7 +686,7 @@ hrt_init(void) sq_init(&callout_queue); hrt_tim_init(); -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL /* configure the PPM input pin */ stm32_configgpio(GPIO_PPM_IN); #endif @@ -907,4 +907,4 @@ hrt_latency_update(void) } -#endif /* CONFIG_HRT_TIMER */ +#endif /* HRT_TIMER */ diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 167ef30a8e..2284be84de 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -117,10 +117,6 @@ #include -#ifndef CONFIG_HRT_TIMER -# error This driver requires CONFIG_HRT_TIMER -#endif - /* Tone alarm configuration */ #if TONE_ALARM_TIMER == 2 # define TONE_ALARM_BASE STM32_TIM2_BASE diff --git a/src/systemcmds/tests/test_hrt.c b/src/systemcmds/tests/test_hrt.c index f21dd115b4..f6e540401f 100644 --- a/src/systemcmds/tests/test_hrt.c +++ b/src/systemcmds/tests/test_hrt.c @@ -94,7 +94,7 @@ extern uint16_t ppm_pulse_history[]; int test_ppm(int argc, char *argv[]) { -#ifdef CONFIG_HRT_PPM +#ifdef HRT_PPM_CHANNEL unsigned i; printf("channels: %u\n", ppm_decoded_channels); From 50e3bb28c90bb2cb93f9f0a549cf9c4838973e1c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 14 Aug 2013 14:56:27 +0200 Subject: [PATCH 87/88] Fixed power attribute on FMU, contributed by Tridge --- nuttx-configs/px4fmu-v1/nsh/defconfig | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index d338161296..9f088c37a2 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -534,9 +534,10 @@ CONFIG_USBDEV=y # # CONFIG_USBDEV_ISOCHRONOUS is not set # CONFIG_USBDEV_DUALSPEED is not set -CONFIG_USBDEV_SELFPOWERED=y -# CONFIG_USBDEV_BUSPOWERED is not set +# CONFIG_USBDEV_SELFPOWERED is not set +CONFIG_USBDEV_BUSPOWERED=y CONFIG_USBDEV_MAXPOWER=500 +# CONFIG_USBDEV_REMOTEWAKEUP is not set # CONFIG_USBDEV_DMA is not set # CONFIG_USBDEV_TRACE is not set From 3a21cacdbbf507f47a45035af7fda04ac787f9b0 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 14 Aug 2013 16:00:35 +0200 Subject: [PATCH 88/88] Fix bug where IO was in override mode for copter (workaround was to disconnect and reconnect Rx --- src/modules/px4iofirmware/controls.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 43d96fb067..fbd82a4c6d 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -300,6 +300,8 @@ controls_tick() { } else { r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } + } else { + r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } }