From dadd8703b422523d88b02effe48e76152bcb2fce Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 28 Jun 2013 08:42:05 +0200 Subject: [PATCH 01/44] Initial non-tested code for reading from the ESC. --- .../hott_telemetry/hott_telemetry_main.c | 44 +++++++++++++ src/drivers/hott_telemetry/messages.c | 28 ++++++++- src/drivers/hott_telemetry/messages.h | 62 ++++++++++++++----- 3 files changed, 117 insertions(+), 17 deletions(-) diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c index 1d2bdd92ee..2c954e41e5 100644 --- a/src/drivers/hott_telemetry/hott_telemetry_main.c +++ b/src/drivers/hott_telemetry/hott_telemetry_main.c @@ -149,6 +149,29 @@ recv_req_id(int uart, uint8_t *id) return OK; } +int +recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t id) +{ + usleep(100000); + + static const int timeout_ms = 200; + struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + + int i = 0; + if (poll(fds, 1, timeout_ms) > 0) { + while (true) { + read(uart, &buffer[i], sizeof(buffer[i])); + + if (&buffer[i] == STOP_BYTE) { + *size = ++i; + id = &buffer[1]; + return OK; + } + } + } + return ERROR; +} + int send_data(int uart, uint8_t *buffer, size_t size) { @@ -218,6 +241,7 @@ hott_telemetry_thread_main(int argc, char *argv[]) bool connected = true; while (!thread_should_exit) { + // Listen for and serve poll from the receiver. if (recv_req_id(uart, &id) == OK) { if (!connected) { connected = true; @@ -242,6 +266,26 @@ hott_telemetry_thread_main(int argc, char *argv[]) connected = false; warnx("syncing"); } + + // Poll the next HoTT devices. + // TODO(sjwilks): Currently there is only one but if there would be more we would round-robin + // calling one for every loop iteration. + build_esc_request(&buffer, &size); + send_data(uart, buffer, size); + + // Listen for a response. + recv_data(uart, &buffer, &size, &id); + + for (size_t i = 0; i < size; i++) { + warnx("%d", buffer[i]); + } + + // Determine which moduel sent it and process accordingly. + if (id == ESC_SENSOR_ID) { + extract_esc_message(buffer); + } else { + warnx("Unknown sensor ID received: %d", id); + } } warnx("exiting"); diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c index d2634ef41a..149c4d3675 100644 --- a/src/drivers/hott_telemetry/messages.c +++ b/src/drivers/hott_telemetry/messages.c @@ -73,6 +73,31 @@ messages_init(void) airspeed_sub = orb_subscribe(ORB_ID(airspeed)); } +void +build_esc_request(uint8_t *buffer, size_t *size) +{ + struct esc_module_poll_msg msg; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.mode = BINARY_MODE_REQUEST_ID; + msg.id = ESC_SENSOR_ID; + + memcpy(&msg, buffer, size); +} + +void +extract_esc_message(const uint8_t *buffer) +{ + struct esc_module_msg msg; + size_t size = sizeof(msg); + memset(&msg, 0, size); + memcpy(buffer, &msg, size); + + // Publish it. + +} + void build_eam_response(uint8_t *buffer, size_t *size) { @@ -92,7 +117,7 @@ build_eam_response(uint8_t *buffer, size_t *size) msg.start = START_BYTE; msg.eam_sensor_id = EAM_SENSOR_ID; - msg.sensor_id = EAM_SENSOR_TEXT_ID; + msg.sensor_text_id = EAM_SENSOR_TEXT_ID; msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; @@ -111,7 +136,6 @@ build_eam_response(uint8_t *buffer, size_t *size) uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s); msg.speed_L = (uint8_t)speed & 0xff; msg.speed_H = (uint8_t)(speed >> 8) & 0xff; - msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h index e6d5cc7239..e1a4262a1c 100644 --- a/src/drivers/hott_telemetry/messages.h +++ b/src/drivers/hott_telemetry/messages.h @@ -60,19 +60,47 @@ #define STOP_BYTE 0x7d #define TEMP_ZERO_CELSIUS 0x14 +#define ESC_SENSOR_ID 0x8e + +/* The ESC Module poll message. */ +struct esc_module_poll_msg { + uint8_t mode; + uint8_t id; +}; + +/* The Electric Air Module message. */ +struct esc_module_msg { + uint8_t start; /**< Start byte */ + uint8_t sensor_id; + uint8_t warning; + uint8_t sensor_text_id; + uint8_t alarm_inverse1; + uint8_t alarm_inverse2; + uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ + uint8_t temperature2; + uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ + uint8_t current_H; + uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ + uint8_t rpm_H; + uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ + uint8_t speed_H; + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ +}; + /* Electric Air Module (EAM) constants. */ #define EAM_SENSOR_ID 0x8e #define EAM_SENSOR_TEXT_ID 0xe0 /* The Electric Air Module message. */ struct eam_module_msg { - uint8_t start; /**< Start byte */ + uint8_t start; /**< Start byte */ uint8_t eam_sensor_id; /**< EAM sensor */ uint8_t warning; - uint8_t sensor_id; /**< Sensor ID, why different? */ + uint8_t sensor_text_id; uint8_t alarm_inverse1; uint8_t alarm_inverse2; - uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ + uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ uint8_t cell2_L; uint8_t cell3_L; uint8_t cell4_L; @@ -92,9 +120,9 @@ struct eam_module_msg { uint8_t batt2_voltage_H; uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ uint8_t temperature2; - uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ + uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ uint8_t altitude_H; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ + uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ uint8_t current_H; uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ uint8_t main_voltage_H; @@ -103,21 +131,21 @@ struct eam_module_msg { uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ uint8_t climbrate_H; uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ + uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ uint8_t rpm_H; uint8_t electric_min; /**< Flight time in minutes. */ uint8_t electric_sec; /**< Flight time in seconds. */ - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ + uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ }; /** * The maximum buffer size required to store a HoTT message. */ -#define MESSAGE_BUFFER_SIZE sizeof(union { \ - struct eam_module_msg eam; \ +#define EAM_MESSAGE_BUFFER_SIZE sizeof(union { \ + struct eam_module_msg eam; \ }) /* GPS sensor constants. */ @@ -129,9 +157,9 @@ struct eam_module_msg { * Struct based on: https://code.google.com/p/diy-hott-gps/downloads */ struct gps_module_msg { - uint8_t start; /**< Start byte */ - uint8_t sensor_id; /**< GPS sensor ID*/ - uint8_t warning; /**< Byte 3: 0…= warning beeps */ + uint8_t start; /**< Start byte */ + uint8_t sensor_id; /**< GPS sensor ID*/ + uint8_t warning; /**< Byte 3: 0…= warning beeps */ uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ @@ -183,10 +211,14 @@ struct gps_module_msg { * The maximum buffer size required to store a HoTT message. */ #define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct gps_module_msg gps; \ + struct gps_module_msg gps; \ }) +#define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE + void messages_init(void); +void build_esc_request(uint8_t *buffer, size_t *size); +void extract_esc_message(const uint8_t *buffer); void build_eam_response(uint8_t *buffer, size_t *size); void build_gps_response(uint8_t *buffer, size_t *size); float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); From 6d2f14e125062be623c710c4b739c46be44d0adf Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 4 Jul 2013 08:33:19 +0200 Subject: [PATCH 02/44] Refactoring of the hott telemetry driver and added functionality to read from a HoTT sensor. --- makefiles/config_px4fmu_default.mk | 3 +- .../hott_telemetry/hott_telemetry_main.c | 344 ------------------ src/drivers/hott_telemetry/messages.c | 268 -------------- src/drivers/hott_telemetry/messages.h | 228 ------------ src/drivers/hott_telemetry/module.mk | 41 --- 5 files changed, 2 insertions(+), 882 deletions(-) delete mode 100644 src/drivers/hott_telemetry/hott_telemetry_main.c delete mode 100644 src/drivers/hott_telemetry/messages.c delete mode 100644 src/drivers/hott_telemetry/messages.h delete mode 100644 src/drivers/hott_telemetry/module.mk diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 43288537cb..0d9ca60c16 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -27,7 +27,8 @@ MODULES += drivers/ms5611 MODULES += drivers/mb12xx MODULES += drivers/gps MODULES += drivers/hil -MODULES += drivers/hott_telemetry +MODULES += drivers/hott/hott_telemetry +MODULES += drivers/hott/hott_sensors MODULES += drivers/blinkm MODULES += drivers/mkblctrl MODULES += drivers/md25 diff --git a/src/drivers/hott_telemetry/hott_telemetry_main.c b/src/drivers/hott_telemetry/hott_telemetry_main.c deleted file mode 100644 index 2c954e41e5..0000000000 --- a/src/drivers/hott_telemetry/hott_telemetry_main.c +++ /dev/null @@ -1,344 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Simon Wilks - * - * 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 hott_telemetry_main.c - * @author Simon Wilks - * - * Graupner HoTT Telemetry implementation. - * - * The HoTT receiver polls each device at a regular interval at which point - * a data packet can be returned if necessary. - * - * TODO: Add support for at least the vario and GPS sensor data. - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "messages.h" - -static int thread_should_exit = false; /**< Deamon exit flag */ -static int thread_running = false; /**< Deamon status flag */ -static int deamon_task; /**< Handle of deamon task / thread */ -static const char daemon_name[] = "hott_telemetry"; -static const char commandline_usage[] = "usage: hott_telemetry start|status|stop [-d ]"; - -/** - * Deamon management function. - */ -__EXPORT int hott_telemetry_main(int argc, char *argv[]); - -/** - * Mainloop of daemon. - */ -int hott_telemetry_thread_main(int argc, char *argv[]); - -static int recv_req_id(int uart, uint8_t *id); -static int send_data(int uart, uint8_t *buffer, size_t size); - -static int -open_uart(const char *device, struct termios *uart_config_original) -{ - /* baud rate */ - static const speed_t speed = B19200; - - /* open uart */ - const int uart = open(device, O_RDWR | O_NOCTTY); - - if (uart < 0) { - err(1, "Error opening port: %s", device); - } - - /* Back up the original uart configuration to restore it after exit */ - int termios_state; - if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - close(uart); - err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state); - } - - /* Fill the struct for the new configuration */ - struct termios uart_config; - tcgetattr(uart, &uart_config); - - /* Clear ONLCR flag (which appends a CR for every LF) */ - uart_config.c_oflag &= ~ONLCR; - - /* Set baud rate */ - if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - close(uart); - err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", - device, termios_state); - } - - if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - close(uart); - err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device); - } - - /* Activate single wire mode */ - ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); - - return uart; -} - -int -recv_req_id(int uart, uint8_t *id) -{ - static const int timeout_ms = 1000; // TODO make it a define - struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; - - uint8_t mode; - - if (poll(fds, 1, timeout_ms) > 0) { - /* Get the mode: binary or text */ - read(uart, &mode, sizeof(mode)); - - /* if we have a binary mode request */ - if (mode != BINARY_MODE_REQUEST_ID) { - return ERROR; - } - - /* Read the device ID being polled */ - read(uart, id, sizeof(*id)); - } else { - warnx("UART timeout on TX/RX port"); - return ERROR; - } - - return OK; -} - -int -recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t id) -{ - usleep(100000); - - static const int timeout_ms = 200; - struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; - - int i = 0; - if (poll(fds, 1, timeout_ms) > 0) { - while (true) { - read(uart, &buffer[i], sizeof(buffer[i])); - - if (&buffer[i] == STOP_BYTE) { - *size = ++i; - id = &buffer[1]; - return OK; - } - } - } - return ERROR; -} - -int -send_data(int uart, uint8_t *buffer, size_t size) -{ - usleep(POST_READ_DELAY_IN_USECS); - - uint16_t checksum = 0; - - for (size_t i = 0; i < size; i++) { - if (i == size - 1) { - /* Set the checksum: the first uint8_t is taken as the checksum. */ - buffer[i] = checksum & 0xff; - - } else { - checksum += buffer[i]; - } - - write(uart, &buffer[i], sizeof(buffer[i])); - - /* Sleep before sending the next byte. */ - usleep(POST_WRITE_DELAY_IN_USECS); - } - - /* A hack the reads out what was written so the next read from the receiver doesn't get it. */ - /* TODO: Fix this!! */ - uint8_t dummy[size]; - read(uart, &dummy, size); - - return OK; -} - -int -hott_telemetry_thread_main(int argc, char *argv[]) -{ - warnx("starting"); - - thread_running = true; - - const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ - - /* read commandline arguments */ - for (int i = 0; i < argc && argv[i]; i++) { - if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set - if (argc > i + 1) { - device = argv[i + 1]; - - } else { - thread_running = false; - errx(1, "missing parameter to -d\n%s", commandline_usage); - } - } - } - - /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ - struct termios uart_config_original; - const int uart = open_uart(device, &uart_config_original); - - if (uart < 0) { - errx(1, "Failed opening HoTT UART, exiting."); - thread_running = false; - } - - messages_init(); - - uint8_t buffer[MESSAGE_BUFFER_SIZE]; - size_t size = 0; - uint8_t id = 0; - bool connected = true; - - while (!thread_should_exit) { - // Listen for and serve poll from the receiver. - if (recv_req_id(uart, &id) == OK) { - if (!connected) { - connected = true; - warnx("OK"); - } - - switch (id) { - case EAM_SENSOR_ID: - build_eam_response(buffer, &size); - break; - - case GPS_SENSOR_ID: - build_gps_response(buffer, &size); - break; - - default: - continue; // Not a module we support. - } - - send_data(uart, buffer, size); - } else { - connected = false; - warnx("syncing"); - } - - // Poll the next HoTT devices. - // TODO(sjwilks): Currently there is only one but if there would be more we would round-robin - // calling one for every loop iteration. - build_esc_request(&buffer, &size); - send_data(uart, buffer, size); - - // Listen for a response. - recv_data(uart, &buffer, &size, &id); - - for (size_t i = 0; i < size; i++) { - warnx("%d", buffer[i]); - } - - // Determine which moduel sent it and process accordingly. - if (id == ESC_SENSOR_ID) { - extract_esc_message(buffer); - } else { - warnx("Unknown sensor ID received: %d", id); - } - } - - warnx("exiting"); - - close(uart); - - thread_running = false; - - return 0; -} - -/** - * Process command line arguments and tart the daemon. - */ -int -hott_telemetry_main(int argc, char *argv[]) -{ - if (argc < 1) { - errx(1, "missing command\n%s", commandline_usage); - } - - if (!strcmp(argv[1], "start")) { - - if (thread_running) { - warnx("deamon already running"); - exit(0); - } - - thread_should_exit = false; - deamon_task = task_spawn(daemon_name, - SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 40, - 2048, - hott_telemetry_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); - exit(0); - } - - if (!strcmp(argv[1], "stop")) { - thread_should_exit = true; - exit(0); - } - - if (!strcmp(argv[1], "status")) { - if (thread_running) { - warnx("daemon is running"); - - } else { - warnx("daemon not started"); - } - - exit(0); - } - - errx(1, "unrecognized command\n%s", commandline_usage); -} diff --git a/src/drivers/hott_telemetry/messages.c b/src/drivers/hott_telemetry/messages.c deleted file mode 100644 index 149c4d3675..0000000000 --- a/src/drivers/hott_telemetry/messages.c +++ /dev/null @@ -1,268 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: @author Simon Wilks - * - * 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 messages.c - * - */ - -#include "messages.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -/* The board is very roughly 5 deg warmer than the surrounding air */ -#define BOARD_TEMP_OFFSET_DEG 5 - -static int battery_sub = -1; -static int gps_sub = -1; -static int home_sub = -1; -static int sensor_sub = -1; -static int airspeed_sub = -1; - -static bool home_position_set = false; -static double home_lat = 0.0d; -static double home_lon = 0.0d; - -void -messages_init(void) -{ - battery_sub = orb_subscribe(ORB_ID(battery_status)); - gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); - home_sub = orb_subscribe(ORB_ID(home_position)); - sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); - airspeed_sub = orb_subscribe(ORB_ID(airspeed)); -} - -void -build_esc_request(uint8_t *buffer, size_t *size) -{ - struct esc_module_poll_msg msg; - *size = sizeof(msg); - memset(&msg, 0, *size); - - msg.mode = BINARY_MODE_REQUEST_ID; - msg.id = ESC_SENSOR_ID; - - memcpy(&msg, buffer, size); -} - -void -extract_esc_message(const uint8_t *buffer) -{ - struct esc_module_msg msg; - size_t size = sizeof(msg); - memset(&msg, 0, size); - memcpy(buffer, &msg, size); - - // Publish it. - -} - -void -build_eam_response(uint8_t *buffer, size_t *size) -{ - /* get a local copy of the current sensor values */ - struct sensor_combined_s raw; - memset(&raw, 0, sizeof(raw)); - orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); - - /* get a local copy of the battery data */ - struct battery_status_s battery; - memset(&battery, 0, sizeof(battery)); - orb_copy(ORB_ID(battery_status), battery_sub, &battery); - - struct eam_module_msg msg; - *size = sizeof(msg); - memset(&msg, 0, *size); - - msg.start = START_BYTE; - msg.eam_sensor_id = EAM_SENSOR_ID; - msg.sensor_text_id = EAM_SENSOR_TEXT_ID; - - msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); - msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; - - msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10); - - uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500); - msg.altitude_L = (uint8_t)alt & 0xff; - msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; - - /* get a local copy of the airspeed data */ - struct airspeed_s airspeed; - memset(&airspeed, 0, sizeof(airspeed)); - orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed); - - uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s); - msg.speed_L = (uint8_t)speed & 0xff; - msg.speed_H = (uint8_t)(speed >> 8) & 0xff; - - msg.stop = STOP_BYTE; - memcpy(buffer, &msg, *size); -} - -void -build_gps_response(uint8_t *buffer, size_t *size) -{ - /* get a local copy of the current sensor values */ - struct sensor_combined_s raw; - memset(&raw, 0, sizeof(raw)); - orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); - - /* get a local copy of the battery data */ - struct vehicle_gps_position_s gps; - memset(&gps, 0, sizeof(gps)); - orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); - - struct gps_module_msg msg = { 0 }; - *size = sizeof(msg); - memset(&msg, 0, *size); - - msg.start = START_BYTE; - msg.sensor_id = GPS_SENSOR_ID; - msg.sensor_text_id = GPS_SENSOR_TEXT_ID; - - msg.gps_num_sat = gps.satellites_visible; - - /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */ - msg.gps_fix_char = (uint8_t)(gps.fix_type + 48); - msg.gps_fix = (uint8_t)(gps.fix_type + 48); - - /* No point collecting more data if we don't have a 3D fix yet */ - if (gps.fix_type > 2) { - /* Current flight direction */ - msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); - - /* GPS speed */ - uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); - msg.gps_speed_L = (uint8_t)speed & 0xff; - msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; - - /* Get latitude in degrees, minutes and seconds */ - double lat = ((double)(gps.lat))*1e-7d; - - /* Set the N or S specifier */ - msg.latitude_ns = 0; - if (lat < 0) { - msg.latitude_ns = 1; - lat = abs(lat); - } - - int deg; - int min; - int sec; - convert_to_degrees_minutes_seconds(lat, °, &min, &sec); - - uint16_t lat_min = (uint16_t)(deg * 100 + min); - msg.latitude_min_L = (uint8_t)lat_min & 0xff; - msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff; - uint16_t lat_sec = (uint16_t)(sec); - msg.latitude_sec_L = (uint8_t)lat_sec & 0xff; - msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff; - - /* Get longitude in degrees, minutes and seconds */ - double lon = ((double)(gps.lon))*1e-7d; - - /* Set the E or W specifier */ - msg.longitude_ew = 0; - if (lon < 0) { - msg.longitude_ew = 1; - lon = abs(lon); - } - - convert_to_degrees_minutes_seconds(lon, °, &min, &sec); - - uint16_t lon_min = (uint16_t)(deg * 100 + min); - msg.longitude_min_L = (uint8_t)lon_min & 0xff; - msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff; - uint16_t lon_sec = (uint16_t)(sec); - msg.longitude_sec_L = (uint8_t)lon_sec & 0xff; - msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; - - /* Altitude */ - uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f); - msg.altitude_L = (uint8_t)alt & 0xff; - msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; - - /* Get any (and probably only ever one) home_sub postion report */ - bool updated; - orb_check(home_sub, &updated); - if (updated) { - /* get a local copy of the home position data */ - struct home_position_s home; - memset(&home, 0, sizeof(home)); - orb_copy(ORB_ID(home_position), home_sub, &home); - - home_lat = ((double)(home.lat))*1e-7d; - home_lon = ((double)(home.lon))*1e-7d; - home_position_set = true; - } - - /* Distance from home */ - if (home_position_set) { - uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); - - msg.distance_L = (uint8_t)dist & 0xff; - msg.distance_H = (uint8_t)(dist >> 8) & 0xff; - - /* Direction back to home */ - uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F); - msg.home_direction = (uint8_t)bearing >> 1; - } - } - - msg.stop = STOP_BYTE; - memcpy(buffer, &msg, *size); -} - -void -convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec) -{ - *deg = (int)val; - - double delta = val - *deg; - const double min_d = delta * 60.0d; - *min = (int)min_d; - delta = min_d - *min; - *sec = (int)(delta * 10000.0d); -} diff --git a/src/drivers/hott_telemetry/messages.h b/src/drivers/hott_telemetry/messages.h deleted file mode 100644 index e1a4262a1c..0000000000 --- a/src/drivers/hott_telemetry/messages.h +++ /dev/null @@ -1,228 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Simon Wilks - * - * 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 messages.h - * @author Simon Wilks - * - * Graupner HoTT Telemetry message generation. - * - */ -#ifndef MESSAGES_H_ -#define MESSAGES_H - -#include - -/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request. - * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting - * the message after the read which takes some milliseconds. - */ -#define POST_READ_DELAY_IN_USECS 4000 -/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower - * values can be used in practise though. - */ -#define POST_WRITE_DELAY_IN_USECS 2000 - -// Protocol constants. -#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request. -#define START_BYTE 0x7c -#define STOP_BYTE 0x7d -#define TEMP_ZERO_CELSIUS 0x14 - -#define ESC_SENSOR_ID 0x8e - -/* The ESC Module poll message. */ -struct esc_module_poll_msg { - uint8_t mode; - uint8_t id; -}; - -/* The Electric Air Module message. */ -struct esc_module_msg { - uint8_t start; /**< Start byte */ - uint8_t sensor_id; - uint8_t warning; - uint8_t sensor_text_id; - uint8_t alarm_inverse1; - uint8_t alarm_inverse2; - uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ - uint8_t temperature2; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ - uint8_t current_H; - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ - uint8_t rpm_H; - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ - uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ -}; - -/* Electric Air Module (EAM) constants. */ -#define EAM_SENSOR_ID 0x8e -#define EAM_SENSOR_TEXT_ID 0xe0 - -/* The Electric Air Module message. */ -struct eam_module_msg { - uint8_t start; /**< Start byte */ - uint8_t eam_sensor_id; /**< EAM sensor */ - uint8_t warning; - uint8_t sensor_text_id; - uint8_t alarm_inverse1; - uint8_t alarm_inverse2; - uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ - uint8_t cell2_L; - uint8_t cell3_L; - uint8_t cell4_L; - uint8_t cell5_L; - uint8_t cell6_L; - uint8_t cell7_L; - uint8_t cell1_H; - uint8_t cell2_H; - uint8_t cell3_H; - uint8_t cell4_H; - uint8_t cell5_H; - uint8_t cell6_H; - uint8_t cell7_H; - uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */ - uint8_t batt1_voltage_H; - uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */ - uint8_t batt2_voltage_H; - uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ - uint8_t temperature2; - uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ - uint8_t altitude_H; - uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ - uint8_t current_H; - uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ - uint8_t main_voltage_H; - uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */ - uint8_t battery_capacity_H; - uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ - uint8_t climbrate_H; - uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ - uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ - uint8_t rpm_H; - uint8_t electric_min; /**< Flight time in minutes. */ - uint8_t electric_sec; /**< Flight time in seconds. */ - uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ - uint8_t speed_H; - uint8_t stop; /**< Stop byte */ - uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ -}; - -/** - * The maximum buffer size required to store a HoTT message. - */ -#define EAM_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct eam_module_msg eam; \ -}) - -/* GPS sensor constants. */ -#define GPS_SENSOR_ID 0x8A -#define GPS_SENSOR_TEXT_ID 0xA0 - -/** - * The GPS sensor message - * Struct based on: https://code.google.com/p/diy-hott-gps/downloads - */ -struct gps_module_msg { - uint8_t start; /**< Start byte */ - uint8_t sensor_id; /**< GPS sensor ID*/ - uint8_t warning; /**< Byte 3: 0…= warning beeps */ - uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ - uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ - uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ - uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ - uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */ - uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */ - - uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */ - uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */ - uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */ - uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */ - uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ - - uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ - uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ - uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ - uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ - uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ - - uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ - uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ - uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ - uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ - uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ - uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ - uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ - uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ - uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ - uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */ - uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ - uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ - uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ - uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */ - uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ - uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */ - uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ - uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */ - uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ - uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ - uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ - uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */ - uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */ - uint8_t version; /**< Byte 43: 00 version number */ - uint8_t stop; /**< Byte 44: 0x7D Ende byte */ - uint8_t checksum; /**< Byte 45: Parity Byte */ -}; - -/** - * The maximum buffer size required to store a HoTT message. - */ -#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct gps_module_msg gps; \ -}) - -#define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE - -void messages_init(void); -void build_esc_request(uint8_t *buffer, size_t *size); -void extract_esc_message(const uint8_t *buffer); -void build_eam_response(uint8_t *buffer, size_t *size); -void build_gps_response(uint8_t *buffer, size_t *size); -float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); -void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); - - -#endif /* MESSAGES_H_ */ diff --git a/src/drivers/hott_telemetry/module.mk b/src/drivers/hott_telemetry/module.mk deleted file mode 100644 index def1d59e9b..0000000000 --- a/src/drivers/hott_telemetry/module.mk +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################ -# -# 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. -# -############################################################################ - -# -# Graupner HoTT Telemetry application. -# - -MODULE_COMMAND = hott_telemetry - -SRCS = hott_telemetry_main.c \ - messages.c From 49aca1ae5ba240fc9ae695e58ca392b8d61c939e Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 4 Jul 2013 08:50:34 +0200 Subject: [PATCH 03/44] Add in missing files. --- src/drivers/hott/comms.c | 106 +++++++ src/drivers/hott/comms.h | 58 ++++ src/drivers/hott/hott_sensors/hott_sensors.c | 232 ++++++++++++++ src/drivers/hott/hott_sensors/module.mk | 42 +++ .../hott/hott_telemetry/hott_telemetry.c | 287 ++++++++++++++++++ src/drivers/hott/hott_telemetry/module.mk | 42 +++ src/drivers/hott/messages.c | 271 +++++++++++++++++ src/drivers/hott/messages.h | 268 ++++++++++++++++ 8 files changed, 1306 insertions(+) create mode 100644 src/drivers/hott/comms.c create mode 100644 src/drivers/hott/comms.h create mode 100644 src/drivers/hott/hott_sensors/hott_sensors.c create mode 100644 src/drivers/hott/hott_sensors/module.mk create mode 100644 src/drivers/hott/hott_telemetry/hott_telemetry.c create mode 100644 src/drivers/hott/hott_telemetry/module.mk create mode 100644 src/drivers/hott/messages.c create mode 100644 src/drivers/hott/messages.h diff --git a/src/drivers/hott/comms.c b/src/drivers/hott/comms.c new file mode 100644 index 0000000000..4a7d3c8451 --- /dev/null +++ b/src/drivers/hott/comms.c @@ -0,0 +1,106 @@ +/**************************************************************************** + * + * 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 comms.c + * @author Simon Wilks + * + */ + +#include "comms.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +int +open_uart(const char *device, struct termios *uart_config_original) +{ + /* baud rate */ + static const speed_t speed = B19200; + + /* open uart */ + const int uart = open(device, O_RDWR | O_NOCTTY); + + if (uart < 0) { + err(1, "Error opening port: %s", device); + } + + /* Back up the original uart configuration to restore it after exit */ + int termios_state; + if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { + close(uart); + err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state); + } + + /* Fill the struct for the new configuration */ + struct termios uart_config; + tcgetattr(uart, &uart_config); + + /* Clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* Set baud rate */ + if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { + close(uart); + err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", + device, termios_state); + } + + if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { + close(uart); + err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device); + } + + /* Activate single wire mode */ + ioctl(uart, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED); + + return uart; +} + + + + + + + + + + diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h new file mode 100644 index 0000000000..a1173631dd --- /dev/null +++ b/src/drivers/hott/comms.h @@ -0,0 +1,58 @@ +/**************************************************************************** + * + * 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 comms.h + * @author Simon Wilks + * + */ + + +#ifndef COMMS_H_ +#define COMMS_H + +#include + +int open_uart(const char *device, struct termios *uart_config_original); + +#endif /* COMMS_H_ */ + + + + + + + + + + diff --git a/src/drivers/hott/hott_sensors/hott_sensors.c b/src/drivers/hott/hott_sensors/hott_sensors.c new file mode 100644 index 0000000000..dc10685b47 --- /dev/null +++ b/src/drivers/hott/hott_sensors/hott_sensors.c @@ -0,0 +1,232 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Simon Wilks + * + * 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 hott_sensors.c + * @author Simon Wilks + * + * Graupner HoTT sensor driver implementation. + * + * Poll any sensors connected to the PX4 via the telemetry wire. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "../comms.h" +#include "../messages.h" + +static int thread_should_exit = false; /**< Deamon exit flag */ +static int thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static const char daemon_name[] = "hott_sensors"; +static const char commandline_usage[] = "usage: hott_sensor start|status|stop [-d ]"; + +/** + * Deamon management function. + */ +__EXPORT int hott_sensors_main(int argc, char *argv[]); + +/** + * Mainloop of daemon. + */ +int hott_sensors_thread_main(int argc, char *argv[]); + +static int recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id); +static int send_poll(int uart, uint8_t *buffer, size_t size); + +int +send_poll(int uart, uint8_t *buffer, size_t size) +{ + for (size_t i = 0; i < size; i++) { + write(uart, &buffer[i], sizeof(buffer[i])); + + /* Sleep before sending the next byte. */ + usleep(POST_WRITE_DELAY_IN_USECS); + } + + /* A hack the reads out what was written so the next read from the receiver doesn't get it. */ + /* TODO: Fix this!! */ + uint8_t dummy[size]; + read(uart, &dummy, size); + + return OK; +} + +int +recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) +{ + usleep(5000); + + static const int timeout_ms = 1000; + struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + + + // XXX should this poll be inside the while loop??? + if (poll(fds, 1, timeout_ms) > 0) { + int i = 0; + bool stop_byte_read = false; + while (true) { + read(uart, &buffer[i], sizeof(buffer[i])); + //printf("[%d]: %d\n", i, buffer[i]); + + if (stop_byte_read) { + // XXX process checksum + *size = ++i; + return OK; + } + // XXX can some other field not have the STOP BYTE value? + if (buffer[i] == STOP_BYTE) { + *id = buffer[1]; + stop_byte_read = true; + } + i++; + } + } + return ERROR; +} + +int +hott_sensors_thread_main(int argc, char *argv[]) +{ + warnx("starting"); + + thread_running = true; + + const char *device = "/dev/ttyS2"; /**< Default telemetry port: USART5 */ + + /* read commandline arguments */ + for (int i = 0; i < argc && argv[i]; i++) { + if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set + if (argc > i + 1) { + device = argv[i + 1]; + + } else { + thread_running = false; + errx(1, "missing parameter to -d\n%s", commandline_usage); + } + } + } + + /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ + struct termios uart_config_original; + const int uart = open_uart(device, &uart_config_original); + + if (uart < 0) { + errx(1, "Failed opening HoTT UART, exiting."); + thread_running = false; + } + + uint8_t buffer[MESSAGE_BUFFER_SIZE]; + size_t size = 0; + uint8_t id = 0; + bool connected = true; + while (!thread_should_exit) { + // Currently we only support a General Air Module sensor. + build_gam_request(&buffer, &size); + send_poll(uart, buffer, size); + recv_data(uart, &buffer, &size, &id); + + // Determine which moduel sent it and process accordingly. + if (id == GAM_SENSOR_ID) { + //warnx("extract"); + extract_gam_message(buffer); + } else { + warnx("Unknown sensor ID received: %d", id); + } + } + + warnx("exiting"); + + close(uart); + + thread_running = false; + + return 0; +} + +/** + * Process command line arguments and start the daemon. + */ +int +hott_sensors_main(int argc, char *argv[]) +{ + if (argc < 1) { + errx(1, "missing command\n%s", commandline_usage); + } + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + warnx("deamon already running"); + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn(daemon_name, + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 40, + 2048, + hott_sensors_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + warnx("daemon is running"); + + } else { + warnx("daemon not started"); + } + + exit(0); + } + + errx(1, "unrecognized command\n%s", commandline_usage); +} diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk new file mode 100644 index 0000000000..ca65d3de22 --- /dev/null +++ b/src/drivers/hott/hott_sensors/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. +# +############################################################################ + +# +# Graupner HoTT Sensors application. +# + +MODULE_COMMAND = hott_sensors + +SRCS = hott_sensors.c \ + ../messages.c \ + ../comms.c diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.c b/src/drivers/hott/hott_telemetry/hott_telemetry.c new file mode 100644 index 0000000000..fc80ac4d23 --- /dev/null +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.c @@ -0,0 +1,287 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Simon Wilks + * + * 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 hott_telemetry_main.c + * @author Simon Wilks + * + * Graupner HoTT Telemetry implementation. + * + * The HoTT receiver polls each device at a regular interval at which point + * a data packet can be returned if necessary. + * + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "../comms.h" +#include "../messages.h" + +static int thread_should_exit = false; /**< Deamon exit flag */ +static int thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static const char daemon_name[] = "hott_telemetry"; +static const char commandline_usage[] = "usage: hott_telemetry start|status|stop [-d ]"; + +/** + * Deamon management function. + */ +__EXPORT int hott_telemetry_main(int argc, char *argv[]); + +/** + * Mainloop of daemon. + */ +int hott_telemetry_thread_main(int argc, char *argv[]); + +static int recv_req_id(int uart, uint8_t *id); +static int send_data(int uart, uint8_t *buffer, size_t size); + +int +recv_req_id(int uart, uint8_t *id) +{ + static const int timeout_ms = 1000; // TODO make it a define + struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + + uint8_t mode; + + if (poll(fds, 1, timeout_ms) > 0) { + /* Get the mode: binary or text */ + read(uart, &mode, sizeof(mode)); + + /* if we have a binary mode request */ + if (mode != BINARY_MODE_REQUEST_ID) { + return ERROR; + } + + /* Read the device ID being polled */ + read(uart, id, sizeof(*id)); + } else { + warnx("UART timeout on TX/RX port"); + return ERROR; + } + + return OK; +} + +int +recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) +{ + usleep(5000); + + static const int timeout_ms = 1000; + struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + + + // XXX should this poll be inside the while loop??? + if (poll(fds, 1, timeout_ms) > 0) { + int i = 0; + bool stop_byte_read = false; + while (true) { + read(uart, &buffer[i], sizeof(buffer[i])); + //printf("[%d]: %d\n", i, buffer[i]); + + if (stop_byte_read) { + // process checksum + *size = ++i; + return OK; + } + // XXX can some other field not have the STOP BYTE value? + if (buffer[i] == STOP_BYTE) { + *id = buffer[1]; + stop_byte_read = true; + } + i++; + } + } + return ERROR; +} + +int +send_data(int uart, uint8_t *buffer, size_t size) +{ + usleep(POST_READ_DELAY_IN_USECS); + + uint16_t checksum = 0; + for (size_t i = 0; i < size; i++) { + if (i == size - 1) { + /* Set the checksum: the first uint8_t is taken as the checksum. */ + buffer[i] = checksum & 0xff; + + } else { + checksum += buffer[i]; + } + + write(uart, &buffer[i], sizeof(buffer[i])); + + /* Sleep before sending the next byte. */ + usleep(POST_WRITE_DELAY_IN_USECS); + } + + /* A hack the reads out what was written so the next read from the receiver doesn't get it. */ + /* TODO: Fix this!! */ + uint8_t dummy[size]; + read(uart, &dummy, size); + + return OK; +} + +int +hott_telemetry_thread_main(int argc, char *argv[]) +{ + warnx("starting"); + + thread_running = true; + + const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ + + /* read commandline arguments */ + for (int i = 0; i < argc && argv[i]; i++) { + if (strcmp(argv[i], "-d") == 0 || strcmp(argv[i], "--device") == 0) { //device set + if (argc > i + 1) { + device = argv[i + 1]; + + } else { + thread_running = false; + errx(1, "missing parameter to -d\n%s", commandline_usage); + } + } + } + + /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ + struct termios uart_config_original; + const int uart = open_uart(device, &uart_config_original); + + if (uart < 0) { + errx(1, "Failed opening HoTT UART, exiting."); + thread_running = false; + } + + messages_init(); + + uint8_t buffer[MESSAGE_BUFFER_SIZE]; + size_t size = 0; + uint8_t id = 0; + bool connected = true; + while (!thread_should_exit) { + // Listen for and serve poll from the receiver. + if (recv_req_id(uart, &id) == OK) { + if (!connected) { + connected = true; + warnx("OK"); + } + + switch (id) { + case EAM_SENSOR_ID: + build_eam_response(buffer, &size); + break; + + case GPS_SENSOR_ID: + build_gps_response(buffer, &size); + break; + + default: + continue; // Not a module we support. + } + + send_data(uart, buffer, size); + } else { + connected = false; + warnx("syncing"); + } + } + + warnx("exiting"); + + close(uart); + + thread_running = false; + + return 0; +} + +/** + * Process command line arguments and start the daemon. + */ +int +hott_telemetry_main(int argc, char *argv[]) +{ + if (argc < 1) { + errx(1, "missing command\n%s", commandline_usage); + } + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + warnx("deamon already running"); + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn(daemon_name, + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 40, + 2048, + hott_telemetry_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + warnx("daemon is running"); + + } else { + warnx("daemon not started"); + } + + exit(0); + } + + errx(1, "unrecognized command\n%s", commandline_usage); +} diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk new file mode 100644 index 0000000000..7673d7e775 --- /dev/null +++ b/src/drivers/hott/hott_telemetry/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. +# +############################################################################ + +# +# Graupner HoTT Telemetry applications. +# + +MODULE_COMMAND = hott_telemetry + +SRCS = hott_telemetry.c \ + ../messages.c \ + ../comms.c diff --git a/src/drivers/hott/messages.c b/src/drivers/hott/messages.c new file mode 100644 index 0000000000..1a29b7e73d --- /dev/null +++ b/src/drivers/hott/messages.c @@ -0,0 +1,271 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Author: @author Simon Wilks + * + * 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 messages.c + * + */ + +#include "messages.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* The board is very roughly 5 deg warmer than the surrounding air */ +#define BOARD_TEMP_OFFSET_DEG 5 + +static int battery_sub = -1; +static int gps_sub = -1; +static int home_sub = -1; +static int sensor_sub = -1; +static int airspeed_sub = -1; + +static bool home_position_set = false; +static double home_lat = 0.0d; +static double home_lon = 0.0d; + +void +messages_init(void) +{ + battery_sub = orb_subscribe(ORB_ID(battery_status)); + gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + home_sub = orb_subscribe(ORB_ID(home_position)); + sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + airspeed_sub = orb_subscribe(ORB_ID(airspeed)); +} + +void +build_gam_request(uint8_t *buffer, size_t *size) +{ + struct gam_module_poll_msg msg; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.mode = BINARY_MODE_REQUEST_ID; + msg.id = GAM_SENSOR_ID; + + memcpy(buffer, &msg, *size); +} + +void +extract_gam_message(const uint8_t *buffer) +{ + struct gam_module_msg msg; + size_t size = sizeof(msg); + memset(&msg, 0, size); + memcpy(&msg, buffer, size); + + // Publish it. + uint16_t rpm = ((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10; + uint8_t temp = msg.temperature2 + 20; + float current = ((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1f; + printf("RPM: %d TEMP: %d A: %2.1f\n", rpm, temp, current); +} + +void +build_eam_response(uint8_t *buffer, size_t *size) +{ + /* get a local copy of the current sensor values */ + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + + /* get a local copy of the battery data */ + struct battery_status_s battery; + memset(&battery, 0, sizeof(battery)); + orb_copy(ORB_ID(battery_status), battery_sub, &battery); + + struct eam_module_msg msg; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.start = START_BYTE; + msg.eam_sensor_id = EAM_SENSOR_ID; + msg.sensor_text_id = EAM_SENSOR_TEXT_ID; + + msg.temperature1 = (uint8_t)(raw.baro_temp_celcius - 20); + msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; + + msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10); + + uint16_t alt = (uint16_t)(raw.baro_alt_meter + 500); + msg.altitude_L = (uint8_t)alt & 0xff; + msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + + /* get a local copy of the airspeed data */ + struct airspeed_s airspeed; + memset(&airspeed, 0, sizeof(airspeed)); + orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed); + + uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s); + msg.speed_L = (uint8_t)speed & 0xff; + msg.speed_H = (uint8_t)(speed >> 8) & 0xff; + + msg.stop = STOP_BYTE; + memcpy(buffer, &msg, *size); +} + +void +build_gps_response(uint8_t *buffer, size_t *size) +{ + /* get a local copy of the current sensor values */ + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + + /* get a local copy of the battery data */ + struct vehicle_gps_position_s gps; + memset(&gps, 0, sizeof(gps)); + orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); + + struct gps_module_msg msg = { 0 }; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.start = START_BYTE; + msg.sensor_id = GPS_SENSOR_ID; + msg.sensor_text_id = GPS_SENSOR_TEXT_ID; + + msg.gps_num_sat = gps.satellites_visible; + + /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */ + msg.gps_fix_char = (uint8_t)(gps.fix_type + 48); + msg.gps_fix = (uint8_t)(gps.fix_type + 48); + + /* No point collecting more data if we don't have a 3D fix yet */ + if (gps.fix_type > 2) { + /* Current flight direction */ + msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); + + /* GPS speed */ + uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); + msg.gps_speed_L = (uint8_t)speed & 0xff; + msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; + + /* Get latitude in degrees, minutes and seconds */ + double lat = ((double)(gps.lat))*1e-7d; + + /* Set the N or S specifier */ + msg.latitude_ns = 0; + if (lat < 0) { + msg.latitude_ns = 1; + lat = abs(lat); + } + + int deg; + int min; + int sec; + convert_to_degrees_minutes_seconds(lat, °, &min, &sec); + + uint16_t lat_min = (uint16_t)(deg * 100 + min); + msg.latitude_min_L = (uint8_t)lat_min & 0xff; + msg.latitude_min_H = (uint8_t)(lat_min >> 8) & 0xff; + uint16_t lat_sec = (uint16_t)(sec); + msg.latitude_sec_L = (uint8_t)lat_sec & 0xff; + msg.latitude_sec_H = (uint8_t)(lat_sec >> 8) & 0xff; + + /* Get longitude in degrees, minutes and seconds */ + double lon = ((double)(gps.lon))*1e-7d; + + /* Set the E or W specifier */ + msg.longitude_ew = 0; + if (lon < 0) { + msg.longitude_ew = 1; + lon = abs(lon); + } + + convert_to_degrees_minutes_seconds(lon, °, &min, &sec); + + uint16_t lon_min = (uint16_t)(deg * 100 + min); + msg.longitude_min_L = (uint8_t)lon_min & 0xff; + msg.longitude_min_H = (uint8_t)(lon_min >> 8) & 0xff; + uint16_t lon_sec = (uint16_t)(sec); + msg.longitude_sec_L = (uint8_t)lon_sec & 0xff; + msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; + + /* Altitude */ + uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f); + msg.altitude_L = (uint8_t)alt & 0xff; + msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + + /* Get any (and probably only ever one) home_sub postion report */ + bool updated; + orb_check(home_sub, &updated); + if (updated) { + /* get a local copy of the home position data */ + struct home_position_s home; + memset(&home, 0, sizeof(home)); + orb_copy(ORB_ID(home_position), home_sub, &home); + + home_lat = ((double)(home.lat))*1e-7d; + home_lon = ((double)(home.lon))*1e-7d; + home_position_set = true; + } + + /* Distance from home */ + if (home_position_set) { + uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); + + msg.distance_L = (uint8_t)dist & 0xff; + msg.distance_H = (uint8_t)(dist >> 8) & 0xff; + + /* Direction back to home */ + uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F); + msg.home_direction = (uint8_t)bearing >> 1; + } + } + + msg.stop = STOP_BYTE; + memcpy(buffer, &msg, *size); +} + +void +convert_to_degrees_minutes_seconds(double val, int *deg, int *min, int *sec) +{ + *deg = (int)val; + + double delta = val - *deg; + const double min_d = delta * 60.0d; + *min = (int)min_d; + delta = min_d - *min; + *sec = (int)(delta * 10000.0d); +} diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h new file mode 100644 index 0000000000..ecfad8569e --- /dev/null +++ b/src/drivers/hott/messages.h @@ -0,0 +1,268 @@ +/**************************************************************************** + * + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Author: Simon Wilks + * + * 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 messages.h + * @author Simon Wilks + * + * Graupner HoTT Telemetry message generation. + * + */ +#ifndef MESSAGES_H_ +#define MESSAGES_H + +#include + +/* The HoTT receiver demands a minimum 5ms period of silence after delivering its request. + * Note that the value specified here is lower than 5000 (5ms) as time is lost constucting + * the message after the read which takes some milliseconds. + */ +#define POST_READ_DELAY_IN_USECS 4000 +/* A pause of 3ms is required between each uint8_t sent back to the HoTT receiver. Much lower + * values can be used in practise though. + */ +#define POST_WRITE_DELAY_IN_USECS 2000 + +// Protocol constants. +#define BINARY_MODE_REQUEST_ID 0x80 // Binary mode request. +#define START_BYTE 0x7c +#define STOP_BYTE 0x7d +#define TEMP_ZERO_CELSIUS 0x14 + +/* The GAM Module poll message. */ +struct gam_module_poll_msg { + uint8_t mode; + uint8_t id; +}; + +/* Electric Air Module (EAM) constants. */ +#define EAM_SENSOR_ID 0x8e +#define EAM_SENSOR_TEXT_ID 0xe0 + +/* The Electric Air Module message. */ +struct eam_module_msg { + uint8_t start; /**< Start byte */ + uint8_t eam_sensor_id; /**< EAM sensor */ + uint8_t warning; + uint8_t sensor_text_id; + uint8_t alarm_inverse1; + uint8_t alarm_inverse2; + uint8_t cell1_L; /**< Lipo cell voltages. Not supported. */ + uint8_t cell2_L; + uint8_t cell3_L; + uint8_t cell4_L; + uint8_t cell5_L; + uint8_t cell6_L; + uint8_t cell7_L; + uint8_t cell1_H; + uint8_t cell2_H; + uint8_t cell3_H; + uint8_t cell4_H; + uint8_t cell5_H; + uint8_t cell6_H; + uint8_t cell7_H; + uint8_t batt1_voltage_L; /**< Battery 1 voltage, lower 8-bits in steps of 0.02V */ + uint8_t batt1_voltage_H; + uint8_t batt2_voltage_L; /**< Battery 2 voltage, lower 8-bits in steps of 0.02V */ + uint8_t batt2_voltage_H; + uint8_t temperature1; /**< Temperature sensor 1. 20 = 0 degrees */ + uint8_t temperature2; + uint8_t altitude_L; /**< Attitude (meters) lower 8-bits. 500 = 0 meters */ + uint8_t altitude_H; + uint8_t current_L; /**< Current (mAh) lower 8-bits in steps of 0.1V */ + uint8_t current_H; + uint8_t main_voltage_L; /**< Main power voltage lower 8-bits in steps of 0.1V */ + uint8_t main_voltage_H; + uint8_t battery_capacity_L; /**< Used battery capacity in steps of 10mAh */ + uint8_t battery_capacity_H; + uint8_t climbrate_L; /**< Climb rate in 0.01m/s. 0m/s = 30000 */ + uint8_t climbrate_H; + uint8_t climbrate_3s; /**< Climb rate in m/3sec. 0m/3sec = 120 */ + uint8_t rpm_L; /**< RPM Lower 8-bits In steps of 10 U/min */ + uint8_t rpm_H; + uint8_t electric_min; /**< Flight time in minutes. */ + uint8_t electric_sec; /**< Flight time in seconds. */ + uint8_t speed_L; /**< Airspeed in km/h in steps of 1 km/h */ + uint8_t speed_H; + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ +}; + +/** + * The maximum buffer size required to store an Electric Air Module message. + */ +#define EAM_MESSAGE_BUFFER_SIZE sizeof(union { \ + struct eam_module_msg eam; \ +}) + + +/* General Air Module (GAM) constants. */ +#define GAM_SENSOR_ID 0x8d +#define GAM_SENSOR_TEXT_ID 0xd0 + +struct gam_module_msg { + uint8_t start_byte; // start byte constant value 0x7c + uint8_t gam_sensor_id; // EAM sensort id. constat value 0x8d + uint8_t warning_beeps; // 1=A 2=B ... 0x1a=Z 0 = no alarm + uint8_t sensor_id; // constant value 0xd0 + uint8_t alarm_invers1; // alarm bitmask. Value is displayed inverted + uint8_t alarm_invers2; // alarm bitmask. Value is displayed inverted + uint8_t cell1; // cell 1 voltage lower value. 0.02V steps, 124=2.48V + uint8_t cell2; + uint8_t cell3; + uint8_t cell4; + uint8_t cell5; + uint8_t cell6; + uint8_t batt1_L; // battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V + uint8_t batt1_H; + uint8_t batt2_L; // battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V + uint8_t batt2_H; + uint8_t temperature1; // temperature 1. offset of 20. a value of 20 = 0°C + uint8_t temperature2; // temperature 2. offset of 20. a value of 20 = 0°C + uint8_t fuel_procent; // Fuel capacity in %. Values 0--100 + // graphical display ranges: 0-25% 50% 75% 100% + uint8_t fuel_ml_L; // Fuel in ml scale. Full = 65535! + uint8_t fuel_ml_H; // + uint8_t rpm_L; // RPM in 10 RPM steps. 300 = 3000rpm + uint8_t rpm_H; // + uint8_t altitude_L; // altitude in meters. offset of 500, 500 = 0m + uint8_t altitude_H; // + uint8_t climbrate_L; // climb rate in 0.01m/s. Value of 30000 = 0.00 m/s + uint8_t climbrate_H; // + uint8_t climbrate3s; // climb rate in m/3sec. Value of 120 = 0m/3sec + uint8_t current_L; // current in 0.1A steps + uint8_t current_H; // + uint8_t main_voltage_L; // Main power voltage using 0.1V steps + uint8_t main_voltage_H; // + uint8_t batt_cap_L; // used battery capacity in 10mAh steps + uint8_t batt_cap_H; // + uint8_t speed_L; // (air?) speed in km/h(?) we are using ground speed here per default + uint8_t speed_H; // + uint8_t min_cell_volt; // minimum cell voltage in 2mV steps. 124 = 2,48V + uint8_t min_cell_volt_num; // number of the cell with the lowest voltage + uint8_t rpm2_L; // RPM in 10 RPM steps. 300 = 3000rpm + uint8_t rpm2_H; // + uint8_t general_error_number; // Voice error == 12. TODO: more docu + uint8_t pressure; // Pressure up to 16bar. 0,1bar scale. 20 = 2bar + uint8_t version; // version number TODO: more info? + uint8_t stop; // stop byte + uint8_t checksum; // checksum +}; + +/** + * The maximum buffer size required to store a General Air Module message. + */ +#define GAM_MESSAGE_BUFFER_SIZE sizeof(union { \ + struct gam_module_msg gam; \ +}) + + +/* GPS sensor constants. */ +#define GPS_SENSOR_ID 0x8a +#define GPS_SENSOR_TEXT_ID 0xa0 + +/** + * The GPS sensor message + * Struct based on: https://code.google.com/p/diy-hott-gps/downloads + */ +struct gps_module_msg { + uint8_t start; /**< Start byte */ + uint8_t sensor_id; /**< GPS sensor ID*/ + uint8_t warning; /**< Byte 3: 0…= warning beeps */ + uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ + uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ + uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ + uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ + uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */ + uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */ + + uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */ + uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */ + uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */ + uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */ + uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ + + uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ + uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ + uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ + uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ + uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ + + uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ + uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ + uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ + uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ + uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ + uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ + uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ + uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ + uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ + uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */ + uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ + uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ + uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ + uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */ + uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ + uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */ + uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ + uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */ + uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ + uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ + uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ + uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */ + uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */ + uint8_t version; /**< Byte 43: 00 version number */ + uint8_t stop; /**< Byte 44: 0x7D Ende byte */ + uint8_t checksum; /**< Byte 45: Parity Byte */ +}; + +/** + * The maximum buffer size required to store a HoTT message. + */ +#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ + struct gps_module_msg gps; \ +}) + +#define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE + +void messages_init(void); +void build_gam_request(uint8_t *buffer, size_t *size); +void extract_gam_message(const uint8_t *buffer); +void build_eam_response(uint8_t *buffer, size_t *size); +void build_gps_response(uint8_t *buffer, size_t *size); +float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); +void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); + + +#endif /* MESSAGES_H_ */ From 86adaeb3e8f28c92005a38b7c71e12111efe8694 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 6 Jul 2013 15:02:34 +0200 Subject: [PATCH 04/44] More cleanups --- src/drivers/hott/comms.c | 9 ++++--- src/drivers/hott/comms.h | 4 +-- src/drivers/hott/hott_sensors/hott_sensors.c | 26 ++++++++---------- .../hott/hott_telemetry/hott_telemetry.c | 7 ++--- src/drivers/hott/messages.c | 27 +++++++++++++++++-- src/drivers/hott/messages.h | 5 ++-- 6 files changed, 47 insertions(+), 31 deletions(-) diff --git a/src/drivers/hott/comms.c b/src/drivers/hott/comms.c index 4a7d3c8451..a2de87407d 100644 --- a/src/drivers/hott/comms.c +++ b/src/drivers/hott/comms.c @@ -41,17 +41,17 @@ #include #include -#include #include #include #include #include -#include #include #include +#include +#include int -open_uart(const char *device, struct termios *uart_config_original) +open_uart(const char *device) { /* baud rate */ static const speed_t speed = B19200; @@ -65,7 +65,8 @@ open_uart(const char *device, struct termios *uart_config_original) /* Back up the original uart configuration to restore it after exit */ int termios_state; - if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { + struct termios uart_config_original; + if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) { close(uart); err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state); } diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h index a1173631dd..4954a309e2 100644 --- a/src/drivers/hott/comms.h +++ b/src/drivers/hott/comms.h @@ -41,9 +41,7 @@ #ifndef COMMS_H_ #define COMMS_H -#include - -int open_uart(const char *device, struct termios *uart_config_original); +int open_uart(const char *device); #endif /* COMMS_H_ */ diff --git a/src/drivers/hott/hott_sensors/hott_sensors.c b/src/drivers/hott/hott_sensors/hott_sensors.c index dc10685b47..41ca0c92f8 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.c +++ b/src/drivers/hott/hott_sensors/hott_sensors.c @@ -47,7 +47,6 @@ #include #include #include -#include #include #include #include @@ -60,7 +59,7 @@ static int thread_should_exit = false; /**< Deamon exit flag */ static int thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ static const char daemon_name[] = "hott_sensors"; -static const char commandline_usage[] = "usage: hott_sensor start|status|stop [-d ]"; +static const char commandline_usage[] = "usage: hott_sensors start|status|stop [-d ]"; /** * Deamon management function. @@ -96,8 +95,6 @@ send_poll(int uart, uint8_t *buffer, size_t size) int recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) { - usleep(5000); - static const int timeout_ms = 1000; struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; @@ -108,7 +105,6 @@ recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) bool stop_byte_read = false; while (true) { read(uart, &buffer[i], sizeof(buffer[i])); - //printf("[%d]: %d\n", i, buffer[i]); if (stop_byte_read) { // XXX process checksum @@ -149,37 +145,37 @@ hott_sensors_thread_main(int argc, char *argv[]) } /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ - struct termios uart_config_original; - const int uart = open_uart(device, &uart_config_original); - + const int uart = open_uart(device); if (uart < 0) { errx(1, "Failed opening HoTT UART, exiting."); thread_running = false; } + pub_messages_init(); + uint8_t buffer[MESSAGE_BUFFER_SIZE]; size_t size = 0; uint8_t id = 0; - bool connected = true; while (!thread_should_exit) { // Currently we only support a General Air Module sensor. build_gam_request(&buffer, &size); send_poll(uart, buffer, size); + + // The sensor will need a little time before it starts sending. + usleep(5000); + recv_data(uart, &buffer, &size, &id); // Determine which moduel sent it and process accordingly. if (id == GAM_SENSOR_ID) { - //warnx("extract"); - extract_gam_message(buffer); + publish_gam_message(buffer); } else { - warnx("Unknown sensor ID received: %d", id); - } + warnx("Unknown sensor ID: %d", id); + } } warnx("exiting"); - close(uart); - thread_running = false; return 0; diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.c b/src/drivers/hott/hott_telemetry/hott_telemetry.c index fc80ac4d23..c87810b42f 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.c +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.c @@ -49,7 +49,6 @@ #include #include #include -#include #include #include #include @@ -189,15 +188,13 @@ hott_telemetry_thread_main(int argc, char *argv[]) } /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ - struct termios uart_config_original; - const int uart = open_uart(device, &uart_config_original); - + const int uart = open_uart(device); if (uart < 0) { errx(1, "Failed opening HoTT UART, exiting."); thread_running = false; } - messages_init(); + sub_messages_init(); uint8_t buffer[MESSAGE_BUFFER_SIZE]; size_t size = 0; diff --git a/src/drivers/hott/messages.c b/src/drivers/hott/messages.c index 1a29b7e73d..ba2f6212da 100644 --- a/src/drivers/hott/messages.c +++ b/src/drivers/hott/messages.c @@ -58,19 +58,31 @@ static int gps_sub = -1; static int home_sub = -1; static int sensor_sub = -1; static int airspeed_sub = -1; +static int esc_sub = -1; + +//orb_advert_t _esc_pub; +//struct esc_s _esc; + static bool home_position_set = false; static double home_lat = 0.0d; static double home_lon = 0.0d; void -messages_init(void) +sub_messages_init(void) { battery_sub = orb_subscribe(ORB_ID(battery_status)); gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); home_sub = orb_subscribe(ORB_ID(home_position)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); airspeed_sub = orb_subscribe(ORB_ID(airspeed)); + //esc_sub = orb_subscribe(ORB_ID(esc)); +} + +void +pub_messages_init(void) +{ + //esc_pub = orb_subscribe(ORB_ID(esc)); } void @@ -87,17 +99,28 @@ build_gam_request(uint8_t *buffer, size_t *size) } void -extract_gam_message(const uint8_t *buffer) +publish_gam_message(const uint8_t *buffer) { struct gam_module_msg msg; size_t size = sizeof(msg); memset(&msg, 0, size); memcpy(&msg, buffer, size); + /* announce the esc if needed, just publish else */ +// if (esc_pub > 0) { +// orb_publish(ORB_ID(airspeed), _esc_pub, &_esc); +// +// } else { +// _esc_pub = orb_advertise(ORB_ID(esc), &_esc); +// } + // Publish it. uint16_t rpm = ((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10; + //_esc.rpm = rpm; uint8_t temp = msg.temperature2 + 20; + //_esc.temperature = temp; float current = ((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1f; + //_esc.current = current; printf("RPM: %d TEMP: %d A: %2.1f\n", rpm, temp, current); } diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h index ecfad8569e..dce90f273c 100644 --- a/src/drivers/hott/messages.h +++ b/src/drivers/hott/messages.h @@ -256,9 +256,10 @@ struct gps_module_msg { #define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE -void messages_init(void); +void sub_messages_init(void); +void pub_messages_init(void); void build_gam_request(uint8_t *buffer, size_t *size); -void extract_gam_message(const uint8_t *buffer); +void publish_gam_message(const uint8_t *buffer); void build_eam_response(uint8_t *buffer, size_t *size); void build_gps_response(uint8_t *buffer, size_t *size); float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); From dc600e7d65df3d91fc1dabac33b6e264ef9185df Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 10 Jul 2013 20:58:47 +0200 Subject: [PATCH 05/44] 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 06/44] 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 07/44] 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 b500cce31ef4ec3c68a5c98e90e3e6dbe10d6722 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 13 Jul 2013 01:08:06 +0200 Subject: [PATCH 08/44] Major refactor of HoTT drivers and finished sensor read implementation. --- src/drivers/hott/{comms.c => comms.cpp} | 0 .../{hott_sensors.c => hott_sensors.cpp} | 40 +++-- src/drivers/hott/hott_sensors/module.mk | 6 +- .../{hott_telemetry.c => hott_telemetry.cpp} | 33 +++-- src/drivers/hott/hott_telemetry/module.mk | 6 +- src/drivers/hott/{messages.c => messages.cpp} | 140 +++++++++++------- src/drivers/hott/messages.h | 34 +---- src/modules/uORB/topics/esc_status.h | 3 +- 8 files changed, 153 insertions(+), 109 deletions(-) rename src/drivers/hott/{comms.c => comms.cpp} (100%) rename src/drivers/hott/hott_sensors/{hott_sensors.c => hott_sensors.cpp} (88%) rename src/drivers/hott/hott_telemetry/{hott_telemetry.c => hott_telemetry.cpp} (91%) rename src/drivers/hott/{messages.c => messages.cpp} (66%) diff --git a/src/drivers/hott/comms.c b/src/drivers/hott/comms.cpp similarity index 100% rename from src/drivers/hott/comms.c rename to src/drivers/hott/comms.cpp diff --git a/src/drivers/hott/hott_sensors/hott_sensors.c b/src/drivers/hott/hott_sensors/hott_sensors.cpp similarity index 88% rename from src/drivers/hott/hott_sensors/hott_sensors.c rename to src/drivers/hott/hott_sensors/hott_sensors.cpp index 41ca0c92f8..ad7e74e62d 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.c +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -55,6 +55,14 @@ #include "../comms.h" #include "../messages.h" +#define DEFAULT_UART "/dev/ttyS2"; /**< USART5 */ + +/* Oddly, ERROR is not defined for C++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + static int thread_should_exit = false; /**< Deamon exit flag */ static int thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ @@ -64,7 +72,7 @@ static const char commandline_usage[] = "usage: hott_sensors start|status|stop [ /** * Deamon management function. */ -__EXPORT int hott_sensors_main(int argc, char *argv[]); +extern "C" __EXPORT int hott_sensors_main(int argc, char *argv[]); /** * Mainloop of daemon. @@ -96,11 +104,13 @@ int recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) { static const int timeout_ms = 1000; - struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; - + + struct pollfd fds; + fds.fd = uart; + fds.events = POLLIN; // XXX should this poll be inside the while loop??? - if (poll(fds, 1, timeout_ms) > 0) { + if (poll(&fds, 1, timeout_ms) > 0) { int i = 0; bool stop_byte_read = false; while (true) { @@ -129,7 +139,7 @@ hott_sensors_thread_main(int argc, char *argv[]) thread_running = true; - const char *device = "/dev/ttyS2"; /**< Default telemetry port: USART5 */ + const char *device = DEFAULT_UART; /* read commandline arguments */ for (int i = 0; i < argc && argv[i]; i++) { @@ -151,20 +161,20 @@ hott_sensors_thread_main(int argc, char *argv[]) thread_running = false; } - pub_messages_init(); + init_pub_messages(); - uint8_t buffer[MESSAGE_BUFFER_SIZE]; + uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE]; size_t size = 0; uint8_t id = 0; while (!thread_should_exit) { // Currently we only support a General Air Module sensor. - build_gam_request(&buffer, &size); + build_gam_request(&buffer[0], &size); send_poll(uart, buffer, size); // The sensor will need a little time before it starts sending. usleep(5000); - recv_data(uart, &buffer, &size, &id); + recv_data(uart, &buffer[0], &size, &id); // Determine which moduel sent it and process accordingly. if (id == GAM_SENSOR_ID) { @@ -199,12 +209,12 @@ hott_sensors_main(int argc, char *argv[]) } thread_should_exit = false; - deamon_task = task_spawn(daemon_name, - SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 40, - 2048, - hott_sensors_thread_main, - (argv) ? (const char **)&argv[2] : (const char **)NULL); + deamon_task = task_spawn_cmd(daemon_name, + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 40, + 2048, + hott_sensors_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); } diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk index ca65d3de22..b5f5762ba7 100644 --- a/src/drivers/hott/hott_sensors/module.mk +++ b/src/drivers/hott/hott_sensors/module.mk @@ -37,6 +37,6 @@ MODULE_COMMAND = hott_sensors -SRCS = hott_sensors.c \ - ../messages.c \ - ../comms.c +SRCS = hott_sensors.cpp \ + ../messages.cpp \ + ../comms.cpp diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.c b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp similarity index 91% rename from src/drivers/hott/hott_telemetry/hott_telemetry.c rename to src/drivers/hott/hott_telemetry/hott_telemetry.cpp index a88f357f6b..1c68e06b1e 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.c +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp @@ -57,6 +57,14 @@ #include "../comms.h" #include "../messages.h" +#define DEFAULT_UART "/dev/ttyS1"; /**< USART2 */ + +/* Oddly, ERROR is not defined for C++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + static int thread_should_exit = false; /**< Deamon exit flag */ static int thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ @@ -66,7 +74,7 @@ static const char commandline_usage[] = "usage: hott_telemetry start|status|stop /** * Deamon management function. */ -__EXPORT int hott_telemetry_main(int argc, char *argv[]); +extern "C" __EXPORT int hott_telemetry_main(int argc, char *argv[]); /** * Mainloop of daemon. @@ -80,11 +88,14 @@ int recv_req_id(int uart, uint8_t *id) { static const int timeout_ms = 1000; // TODO make it a define - struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; uint8_t mode; + + struct pollfd fds; + fds.fd = uart; + fds.events = POLLIN; - if (poll(fds, 1, timeout_ms) > 0) { + if (poll(&fds, 1, timeout_ms) > 0) { /* Get the mode: binary or text */ read(uart, &mode, sizeof(mode)); @@ -109,11 +120,13 @@ recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) usleep(5000); static const int timeout_ms = 1000; - struct pollfd fds[] = { { .fd = uart, .events = POLLIN } }; + struct pollfd fds; + fds.fd = uart; + fds.events = POLLIN; // XXX should this poll be inside the while loop??? - if (poll(fds, 1, timeout_ms) > 0) { + if (poll(&fds, 1, timeout_ms) > 0) { int i = 0; bool stop_byte_read = false; while (true) { @@ -172,7 +185,7 @@ hott_telemetry_thread_main(int argc, char *argv[]) thread_running = true; - const char *device = "/dev/ttyS1"; /**< Default telemetry port: USART2 */ + const char *device = DEFAULT_UART; /* read commandline arguments */ for (int i = 0; i < argc && argv[i]; i++) { @@ -194,9 +207,9 @@ hott_telemetry_thread_main(int argc, char *argv[]) thread_running = false; } - sub_messages_init(); + init_sub_messages(); - uint8_t buffer[MESSAGE_BUFFER_SIZE]; + uint8_t buffer[MAX_MESSAGE_BUFFER_SIZE]; size_t size = 0; uint8_t id = 0; bool connected = true; @@ -212,7 +225,9 @@ hott_telemetry_thread_main(int argc, char *argv[]) case EAM_SENSOR_ID: build_eam_response(buffer, &size); break; - + case GAM_SENSOR_ID: + build_gam_response(buffer, &size); + break; case GPS_SENSOR_ID: build_gps_response(buffer, &size); break; diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk index 7673d7e775..b19cbd14cf 100644 --- a/src/drivers/hott/hott_telemetry/module.mk +++ b/src/drivers/hott/hott_telemetry/module.mk @@ -37,6 +37,6 @@ MODULE_COMMAND = hott_telemetry -SRCS = hott_telemetry.c \ - ../messages.c \ - ../comms.c +SRCS = hott_telemetry.cpp \ + ../messages.cpp \ + ../comms.cpp diff --git a/src/drivers/hott/messages.c b/src/drivers/hott/messages.cpp similarity index 66% rename from src/drivers/hott/messages.c rename to src/drivers/hott/messages.cpp index 36d5fe942f..004322a2d7 100644 --- a/src/drivers/hott/messages.c +++ b/src/drivers/hott/messages.cpp @@ -46,6 +46,7 @@ #include #include #include +#include #include #include #include @@ -53,36 +54,37 @@ /* The board is very roughly 5 deg warmer than the surrounding air */ #define BOARD_TEMP_OFFSET_DEG 5 -static int battery_sub = -1; -static int gps_sub = -1; -static int home_sub = -1; -static int sensor_sub = -1; -static int airspeed_sub = -1; -static int esc_sub = -1; +static int _battery_sub = -1; +static int _gps_sub = -1; +static int _home_sub = -1; +static int _sensor_sub = -1; +static int _airspeed_sub = -1; +static int _esc_sub = -1; -//orb_advert_t _esc_pub; -//struct esc_s _esc; +orb_advert_t _esc_pub; +struct esc_status_s _esc; -static bool home_position_set = false; -static double home_lat = 0.0d; -static double home_lon = 0.0d; +static bool _home_position_set = false; +static double _home_lat = 0.0d; +static double _home_lon = 0.0d; void -sub_messages_init(void) +init_sub_messages(void) { - battery_sub = orb_subscribe(ORB_ID(battery_status)); - gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); - home_sub = orb_subscribe(ORB_ID(home_position)); - sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); - airspeed_sub = orb_subscribe(ORB_ID(airspeed)); - //esc_sub = orb_subscribe(ORB_ID(esc)); + _battery_sub = orb_subscribe(ORB_ID(battery_status)); + _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + _home_sub = orb_subscribe(ORB_ID(home_position)); + _sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); + _esc_sub = orb_subscribe(ORB_ID(esc_status)); } void -pub_messages_init(void) +init_pub_messages(void) { - //esc_pub = orb_subscribe(ORB_ID(esc)); + memset(&_esc, 0, sizeof(_esc)); + _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc); } void @@ -107,21 +109,22 @@ publish_gam_message(const uint8_t *buffer) memcpy(&msg, buffer, size); /* announce the esc if needed, just publish else */ -// if (esc_pub > 0) { -// orb_publish(ORB_ID(airspeed), _esc_pub, &_esc); -// -// } else { -// _esc_pub = orb_advertise(ORB_ID(esc), &_esc); -// } + if (_esc_pub > 0) { + orb_publish(ORB_ID(esc_status), _esc_pub, &_esc); + } else { + _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc); + } // Publish it. - uint16_t rpm = ((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10; - //_esc.rpm = rpm; - uint8_t temp = msg.temperature2 + 20; - //_esc.temperature = temp; - float current = ((msg.current_H << 8) | (msg.current_L & 0xff)) * 0.1f; - //_esc.current = current; - printf("RPM: %d TEMP: %d A: %2.1f\n", rpm, temp, current); + _esc.esc_count = 1; + _esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM; + + _esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT; + _esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10; + _esc.esc[0].esc_temperature = msg.temperature1 - 20; + _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)); + _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff)); + //printf("T: %d\n", _esc.esc[0].esc_temperature); } void @@ -130,12 +133,12 @@ build_eam_response(uint8_t *buffer, size_t *size) /* get a local copy of the current sensor values */ struct sensor_combined_s raw; memset(&raw, 0, sizeof(raw)); - orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw); /* get a local copy of the battery data */ struct battery_status_s battery; memset(&battery, 0, sizeof(battery)); - orb_copy(ORB_ID(battery_status), battery_sub, &battery); + orb_copy(ORB_ID(battery_status), _battery_sub, &battery); struct eam_module_msg msg; *size = sizeof(msg); @@ -145,7 +148,7 @@ build_eam_response(uint8_t *buffer, size_t *size) msg.eam_sensor_id = EAM_SENSOR_ID; msg.sensor_text_id = EAM_SENSOR_TEXT_ID; - msg.temperature1 = (uint8_t)(raw.baro_temp_celcius - 20); + msg.temperature1 = (uint8_t)(raw.baro_temp_celcius + 20); msg.temperature2 = msg.temperature1 - BOARD_TEMP_OFFSET_DEG; msg.main_voltage_L = (uint8_t)(battery.voltage_v * 10); @@ -157,7 +160,7 @@ build_eam_response(uint8_t *buffer, size_t *size) /* get a local copy of the airspeed data */ struct airspeed_s airspeed; memset(&airspeed, 0, sizeof(airspeed)); - orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed); + orb_copy(ORB_ID(airspeed), _airspeed_sub, &airspeed); uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f); msg.speed_L = (uint8_t)speed & 0xff; @@ -167,20 +170,55 @@ build_eam_response(uint8_t *buffer, size_t *size) memcpy(buffer, &msg, *size); } +void +build_gam_response(uint8_t *buffer, size_t *size) +{ + /* get a local copy of the ESC Status values */ + struct esc_status_s esc; + memset(&esc, 0, sizeof(esc)); + orb_copy(ORB_ID(esc_status), _esc_sub, &esc); + + struct gam_module_msg msg; + *size = sizeof(msg); + memset(&msg, 0, *size); + + msg.start = START_BYTE; + msg.gam_sensor_id = GAM_SENSOR_ID; + msg.sensor_text_id = GAM_SENSOR_TEXT_ID; + + msg.temperature1 = (uint8_t)(esc.esc[0].esc_temperature + 20); + msg.temperature2 = 20; // 0 deg. C. + + uint16_t voltage = (uint16_t)(esc.esc[0].esc_voltage); + msg.main_voltage_L = (uint8_t)voltage & 0xff; + msg.main_voltage_H = (uint8_t)(voltage >> 8) & 0xff; + + uint16_t current = (uint16_t)(esc.esc[0].esc_current); + msg.current_L = (uint8_t)current & 0xff; + msg.current_H = (uint8_t)(current >> 8) & 0xff; + + uint16_t rpm = (uint16_t)(esc.esc[0].esc_rpm * 0.1f); + msg.rpm_L = (uint8_t)rpm & 0xff; + msg.rpm_H = (uint8_t)(rpm >> 8) & 0xff; + + msg.stop = STOP_BYTE; + memcpy(buffer, &msg, *size); +} + void build_gps_response(uint8_t *buffer, size_t *size) { /* get a local copy of the current sensor values */ struct sensor_combined_s raw; memset(&raw, 0, sizeof(raw)); - orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw); /* get a local copy of the battery data */ struct vehicle_gps_position_s gps; memset(&gps, 0, sizeof(gps)); - orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps); + orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &gps); - struct gps_module_msg msg = { 0 }; + struct gps_module_msg msg; *size = sizeof(msg); memset(&msg, 0, *size); @@ -200,7 +238,7 @@ build_gps_response(uint8_t *buffer, size_t *size) msg.flight_direction = (uint8_t)(gps.cog_rad * M_RAD_TO_DEG_F); /* GPS speed */ - uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6); + uint16_t speed = (uint16_t)(gps.vel_m_s * 3.6f); msg.gps_speed_L = (uint8_t)speed & 0xff; msg.gps_speed_H = (uint8_t)(speed >> 8) & 0xff; @@ -246,33 +284,33 @@ build_gps_response(uint8_t *buffer, size_t *size) msg.longitude_sec_H = (uint8_t)(lon_sec >> 8) & 0xff; /* Altitude */ - uint16_t alt = (uint16_t)(gps.alt*1e-3 + 500.0f); + uint16_t alt = (uint16_t)(gps.alt*1e-3f + 500.0f); msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; - /* Get any (and probably only ever one) home_sub postion report */ + /* Get any (and probably only ever one) _home_sub postion report */ bool updated; - orb_check(home_sub, &updated); + orb_check(_home_sub, &updated); if (updated) { /* get a local copy of the home position data */ struct home_position_s home; memset(&home, 0, sizeof(home)); - orb_copy(ORB_ID(home_position), home_sub, &home); + orb_copy(ORB_ID(home_position), _home_sub, &home); - home_lat = ((double)(home.lat))*1e-7d; - home_lon = ((double)(home.lon))*1e-7d; - home_position_set = true; + _home_lat = ((double)(home.lat))*1e-7d; + _home_lon = ((double)(home.lon))*1e-7d; + _home_position_set = true; } /* Distance from home */ - if (home_position_set) { - uint16_t dist = (uint16_t)get_distance_to_next_waypoint(home_lat, home_lon, lat, lon); + if (_home_position_set) { + uint16_t dist = (uint16_t)get_distance_to_next_waypoint(_home_lat, _home_lon, lat, lon); msg.distance_L = (uint8_t)dist & 0xff; msg.distance_H = (uint8_t)(dist >> 8) & 0xff; /* Direction back to home */ - uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(home_lat, home_lon, lat, lon) * M_RAD_TO_DEG_F); + uint16_t bearing = (uint16_t)(get_bearing_to_next_waypoint(_home_lat, _home_lon, lat, lon) * M_RAD_TO_DEG_F); msg.home_direction = (uint8_t)bearing >> 1; } } diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h index dce90f273c..451bee91ce 100644 --- a/src/drivers/hott/messages.h +++ b/src/drivers/hott/messages.h @@ -119,23 +119,16 @@ struct eam_module_msg { uint8_t checksum; /**< Lower 8-bits of all bytes summed. */ }; -/** - * The maximum buffer size required to store an Electric Air Module message. - */ -#define EAM_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct eam_module_msg eam; \ -}) - /* General Air Module (GAM) constants. */ #define GAM_SENSOR_ID 0x8d #define GAM_SENSOR_TEXT_ID 0xd0 struct gam_module_msg { - uint8_t start_byte; // start byte constant value 0x7c + uint8_t start; // start byte constant value 0x7c uint8_t gam_sensor_id; // EAM sensort id. constat value 0x8d uint8_t warning_beeps; // 1=A 2=B ... 0x1a=Z 0 = no alarm - uint8_t sensor_id; // constant value 0xd0 + uint8_t sensor_text_id; // constant value 0xd0 uint8_t alarm_invers1; // alarm bitmask. Value is displayed inverted uint8_t alarm_invers2; // alarm bitmask. Value is displayed inverted uint8_t cell1; // cell 1 voltage lower value. 0.02V steps, 124=2.48V @@ -180,14 +173,6 @@ struct gam_module_msg { uint8_t checksum; // checksum }; -/** - * The maximum buffer size required to store a General Air Module message. - */ -#define GAM_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct gam_module_msg gam; \ -}) - - /* GPS sensor constants. */ #define GPS_SENSOR_ID 0x8a #define GPS_SENSOR_TEXT_ID 0xa0 @@ -247,20 +232,15 @@ struct gps_module_msg { uint8_t checksum; /**< Byte 45: Parity Byte */ }; -/** - * The maximum buffer size required to store a HoTT message. - */ -#define GPS_MESSAGE_BUFFER_SIZE sizeof(union { \ - struct gps_module_msg gps; \ -}) +// The maximum size of a message. +#define MAX_MESSAGE_BUFFER_SIZE 45 -#define MESSAGE_BUFFER_SIZE GPS_MESSAGE_BUFFER_SIZE - -void sub_messages_init(void); -void pub_messages_init(void); +void init_sub_messages(void); +void init_pub_messages(void); void build_gam_request(uint8_t *buffer, size_t *size); void publish_gam_message(const uint8_t *buffer); void build_eam_response(uint8_t *buffer, size_t *size); +void build_gam_response(uint8_t *buffer, size_t *size); void build_gps_response(uint8_t *buffer, size_t *size); float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next); void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec); diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h index e67a39e1e8..00cf59b28f 100644 --- a/src/modules/uORB/topics/esc_status.h +++ b/src/modules/uORB/topics/esc_status.h @@ -63,7 +63,8 @@ enum ESC_VENDOR { ESC_VENDOR_GENERIC = 0, /**< generic ESC */ - ESC_VENDOR_MIKROKOPTER /**< Mikrokopter */ + ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */ + ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */ }; enum ESC_CONNECTION_TYPE { From fa29694f0ba85c0b140dc460be14a5205da9c093 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 13 Jul 2013 01:12:47 +0200 Subject: [PATCH 09/44] Whitespace cleanup --- src/drivers/hott/comms.cpp | 10 ---------- src/drivers/hott/comms.h | 10 ---------- src/drivers/hott/messages.cpp | 1 - 3 files changed, 21 deletions(-) diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp index a2de87407d..1da1c5c180 100644 --- a/src/drivers/hott/comms.cpp +++ b/src/drivers/hott/comms.cpp @@ -95,13 +95,3 @@ open_uart(const char *device) return uart; } - - - - - - - - - - diff --git a/src/drivers/hott/comms.h b/src/drivers/hott/comms.h index 4954a309e2..f5608122fc 100644 --- a/src/drivers/hott/comms.h +++ b/src/drivers/hott/comms.h @@ -44,13 +44,3 @@ int open_uart(const char *device); #endif /* COMMS_H_ */ - - - - - - - - - - diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp index 004322a2d7..c5d73ab11d 100644 --- a/src/drivers/hott/messages.cpp +++ b/src/drivers/hott/messages.cpp @@ -124,7 +124,6 @@ publish_gam_message(const uint8_t *buffer) _esc.esc[0].esc_temperature = msg.temperature1 - 20; _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff)); _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff)); - //printf("T: %d\n", _esc.esc[0].esc_temperature); } void From 9aa25c5671b6966111dd75687945a8a0b3c8fa19 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 13 Jul 2013 22:18:52 +0200 Subject: [PATCH 10/44] Remove unused code. --- src/drivers/hott/comms.cpp | 5 --- .../hott/hott_sensors/hott_sensors.cpp | 2 +- .../hott/hott_telemetry/hott_telemetry.cpp | 37 +------------------ src/drivers/hott/messages.cpp | 3 +- 4 files changed, 3 insertions(+), 44 deletions(-) diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp index 1da1c5c180..cb8bbba37e 100644 --- a/src/drivers/hott/comms.cpp +++ b/src/drivers/hott/comms.cpp @@ -40,15 +40,10 @@ #include "comms.h" #include -#include -#include #include -#include #include #include -#include #include -#include int open_uart(const char *device) diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp index ad7e74e62d..ada7f9fb77 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.cpp +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -55,7 +55,7 @@ #include "../comms.h" #include "../messages.h" -#define DEFAULT_UART "/dev/ttyS2"; /**< USART5 */ +#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */ /* Oddly, ERROR is not defined for C++ */ #ifdef ERROR diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp index 1c68e06b1e..042d9f8162 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp @@ -57,7 +57,7 @@ #include "../comms.h" #include "../messages.h" -#define DEFAULT_UART "/dev/ttyS1"; /**< USART2 */ +#define DEFAULT_UART "/dev/ttyS0"; /**< USART1 */ /* Oddly, ERROR is not defined for C++ */ #ifdef ERROR @@ -114,41 +114,6 @@ recv_req_id(int uart, uint8_t *id) return OK; } -int -recv_data(int uart, uint8_t *buffer, size_t *size, uint8_t *id) -{ - usleep(5000); - - static const int timeout_ms = 1000; - - struct pollfd fds; - fds.fd = uart; - fds.events = POLLIN; - - // XXX should this poll be inside the while loop??? - if (poll(&fds, 1, timeout_ms) > 0) { - int i = 0; - bool stop_byte_read = false; - while (true) { - read(uart, &buffer[i], sizeof(buffer[i])); - //printf("[%d]: %d\n", i, buffer[i]); - - if (stop_byte_read) { - // process checksum - *size = ++i; - return OK; - } - // XXX can some other field not have the STOP BYTE value? - if (buffer[i] == STOP_BYTE) { - *id = buffer[1]; - stop_byte_read = true; - } - i++; - } - } - return ERROR; -} - int send_data(int uart, uint8_t *buffer, size_t size) { diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp index c5d73ab11d..57c2563394 100644 --- a/src/drivers/hott/messages.cpp +++ b/src/drivers/hott/messages.cpp @@ -61,10 +61,9 @@ static int _sensor_sub = -1; static int _airspeed_sub = -1; static int _esc_sub = -1; -orb_advert_t _esc_pub; +static orb_advert_t _esc_pub; struct esc_status_s _esc; - static bool _home_position_set = false; static double _home_lat = 0.0d; static double _home_lon = 0.0d; From 6b631afaef65ba874373b1dd1652f02a7f6e3612 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 14 Jul 2013 00:04:17 +0200 Subject: [PATCH 11/44] Reduce the max stack size needed. --- src/drivers/hott/hott_sensors/hott_sensors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp index ada7f9fb77..e322c6349e 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.cpp +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -212,7 +212,7 @@ hott_sensors_main(int argc, char *argv[]) deamon_task = task_spawn_cmd(daemon_name, SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 2048, + 1024, hott_sensors_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); exit(0); From 7fe2aa27974f93810727b0a59658ed760c6ad591 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 14 Jul 2013 11:22:20 +0200 Subject: [PATCH 12/44] 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 13/44] 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 0b47ed86e04bb1930507a74a745ea0b0259dc31f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 15 Jul 2013 13:58:43 +0200 Subject: [PATCH 14/44] Implemented new, simple system boot config and sane default value system based on two parameters evaluated at boot time --- .../init.d/{rc.FMU_quad_x => rc.1_fmu_quad_x} | 35 ++++- .../init.d/{rc.IO_QUAD => rc.2_fmu_io_quad_x} | 29 ++++- .../{rc.PX4IO => rc.30_fmu_io_camflyer} | 25 +++- .../px4fmu_common/init.d/rc.31_fmu_io_phantom | 120 ++++++++++++++++++ .../init.d/{rc.PX4IOAR => rc.fmu_ardrone} | 0 ...AR_PX4FLOW_example => rc.fmu_ardrone_flow} | 0 ROMFS/px4fmu_common/init.d/rcS | 24 ++++ src/modules/systemlib/module.mk | 3 +- src/modules/systemlib/system_params.c | 47 +++++++ src/systemcmds/param/param.c | 73 ++++++++++- 10 files changed, 335 insertions(+), 21 deletions(-) rename ROMFS/px4fmu_common/init.d/{rc.FMU_quad_x => rc.1_fmu_quad_x} (70%) rename ROMFS/px4fmu_common/init.d/{rc.IO_QUAD => rc.2_fmu_io_quad_x} (84%) rename ROMFS/px4fmu_common/init.d/{rc.PX4IO => rc.30_fmu_io_camflyer} (84%) create mode 100644 ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom rename ROMFS/px4fmu_common/init.d/{rc.PX4IOAR => rc.fmu_ardrone} (100%) rename ROMFS/px4fmu_common/init.d/{rc.PX4IOAR_PX4FLOW_example => rc.fmu_ardrone_flow} (100%) create mode 100644 src/modules/systemlib/system_params.c diff --git a/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x similarity index 70% rename from ROMFS/px4fmu_common/init.d/rc.FMU_quad_x rename to ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x index 980197d68e..a72a2a2396 100644 --- a/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x +++ b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x @@ -3,10 +3,8 @@ # Flight startup script for PX4FMU with PWM outputs. # -# Disable the USB interface +# disable USB and autostart set USB no - -# Disable autostarting other apps set MODE custom echo "[init] doing PX4FMU Quad startup..." @@ -25,7 +23,16 @@ 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 +fi + # # Force some key parameters to sane values # MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor @@ -48,6 +55,11 @@ sh /etc/init.d/rc.sensors # Start the commander. # commander start + +# +# Start GPS interface (depends on orb) +# +gps start # # Start the attitude estimator @@ -57,11 +69,22 @@ attitude_estimator_ekf start echo "[init] starting PWM output" fmu mode_pwm mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix +pwm -u 400 -m 0xff # # Start attitude control # multirotor_att_control start + +# +# Start logging +# +sdlog2 start -r 50 -a -b 14 -echo "[init] startup done, exiting" -exit \ No newline at end of file +# +# Start system state +# +if blinkm start +then + blinkm systemstate +fi diff --git a/ROMFS/px4fmu_common/init.d/rc.IO_QUAD b/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x similarity index 84% rename from ROMFS/px4fmu_common/init.d/rc.IO_QUAD rename to ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x index 5f2de0d7e0..8fa87442ba 100644 --- a/ROMFS/px4fmu_common/init.d/rc.IO_QUAD +++ b/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x @@ -1,8 +1,11 @@ #!nsh +# +# Flight startup script for PX4FMU+PX4IO +# -# Disable USB and autostart +# disable USB and autostart set USB no -set MODE quad +set MODE custom # # Start the ORB (first app to start) @@ -18,6 +21,15 @@ 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 +fi # # Force some key parameters to sane values @@ -68,6 +80,11 @@ 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) @@ -88,20 +105,18 @@ attitude_estimator_ekf start # Load mixer and start controllers (depends on px4io) # mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix +pwm -u 400 -m 0xff multirotor_att_control start # # Start logging # -#sdlog start -s 4 +sdlog2 start -r 50 -a -b 14 # # Start system state # if blinkm start then - echo "using BlinkM for state indication" blinkm systemstate -else - echo "no BlinkM found, OK." -fi \ No newline at end of file +fi diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IO b/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer similarity index 84% rename from ROMFS/px4fmu_common/init.d/rc.PX4IO rename to ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer index 925a5703e7..e04aafe54c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.PX4IO +++ b/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer @@ -1,8 +1,11 @@ #!nsh +# +# Flight startup script for PX4FMU+PX4IO +# -# Disable USB and autostart +# disable USB and autostart set USB no -set MODE camflyer +set MODE custom # # Start the ORB (first app to start) @@ -18,6 +21,15 @@ 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 +fi # # Force some key parameters to sane values @@ -68,6 +80,10 @@ px4io start # Allow PX4IO to recover from midair restarts. # this is very unlikely, but quite safe and robust. px4io recovery + +# +# Set actuator limit to 100 Hz update (50 Hz PWM) +px4io limit 100 # # Start the sensors (depends on orb, px4io) @@ -93,15 +109,12 @@ control_demo start # # Start logging # -#sdlog start -s 4 +sdlog2 start -r 50 -a -b 14 # # Start system state # if blinkm start then - echo "using BlinkM for state indication" blinkm systemstate -else - echo "no BlinkM found, OK." fi diff --git a/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom b/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom new file mode 100644 index 0000000000..e04aafe54c --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom @@ -0,0 +1,120 @@ +#!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 +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 1 + +# +# 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 + +# +# Set actuator limit to 100 Hz update (50 Hz PWM) +px4io limit 100 + +# +# 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) +# +kalman_demo start + +# +# Load mixer and start controllers (depends on px4io) +# +mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix +control_demo start + +# +# Start logging +# +sdlog2 start -r 50 -a -b 14 + +# +# Start system state +# +if blinkm start +then + blinkm systemstate +fi diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IOAR b/ROMFS/px4fmu_common/init.d/rc.fmu_ardrone similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.PX4IOAR rename to ROMFS/px4fmu_common/init.d/rc.fmu_ardrone diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example b/ROMFS/px4fmu_common/init.d/rc.fmu_ardrone_flow similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.PX4IOAR_PX4FLOW_example rename to ROMFS/px4fmu_common/init.d/rc.fmu_ardrone_flow diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 22dec87cb0..06c1c2492a 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -24,6 +24,30 @@ else tone_alarm 2 fi +# +# Check if auto-setup from one of the standard scripts is wanted +# SYS_AUTOSTART = 0 means no autostart (default) +# +if param compare SYS_AUTOSTART 1 +then + sh /etc/init.d/rc.1_fmu_quad_x +fi + +if param compare SYS_AUTOSTART 2 +then + sh /etc/init.d/rc.2_fmu_io_quad_x +fi + +if param compare SYS_AUTOSTART 30 +then + sh /etc/init.d/rc.30_fmu_io_camflyer +fi + +if param compare SYS_AUTOSTART 31 +then + sh /etc/init.d/rc.31_fmu_io_phantom +fi + # # Look for an init script on the microSD card. # diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index fd0289c9a4..b470c12271 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -47,4 +47,5 @@ SRCS = err.c \ pid/pid.c \ geo/geo.c \ systemlib.c \ - airspeed.c + airspeed.c \ + system_params.c diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c new file mode 100644 index 0000000000..75be090f80 --- /dev/null +++ b/src/modules/systemlib/system_params.c @@ -0,0 +1,47 @@ +/**************************************************************************** + * + * 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 system_params.c + * + * System wide parameters + */ + +#include +#include + +// Auto-start script with index #n +PARAM_DEFINE_INT32(SYS_AUTOSTART, 0); + +// Automatically configure default values +PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 60e61d07b6..c3fedb958b 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -63,6 +63,7 @@ static void do_import(const char* param_file_name); static void do_show(const char* search_string); static void do_show_print(void *arg, param_t param); static void do_set(const char* name, const char* val); +static void do_compare(const char* name, const char* val); int param_main(int argc, char *argv[]) @@ -117,9 +118,17 @@ param_main(int argc, char *argv[]) errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'"); } } + + if (!strcmp(argv[1], "compare")) { + if (argc >= 4) { + do_compare(argv[2], argv[3]); + } else { + errx(1, "not enough arguments.\nTry 'param compare PARAM_NAME 3'"); + } + } } - errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'select' or 'save'"); + errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'"); } static void @@ -295,3 +304,65 @@ do_set(const char* name, const char* val) 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)) { + printf("curr: %d: ", i); + + /* convert string */ + char* end; + int j = strtol(val,&end,10); + if (i == j) { + ret = 0; + } + + } + + break; + + case PARAM_TYPE_FLOAT: + if (!param_get(param, &f)) { + printf("curr: %4.4f: ", (double)f); + + /* convert string */ + char* end; + float g = strtod(val,&end); + if (fabsf(f - g) < 1e-7f) { + 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 17338ca61aa8a58c92ae621de94240ddd22f28a2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 15 Jul 2013 13:59:23 +0200 Subject: [PATCH 15/44] Removed unneccesary casts in airspeed calculation to double precision --- src/modules/systemlib/airspeed.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/systemlib/airspeed.c b/src/modules/systemlib/airspeed.c index 15bb833a99..e01cc4ddaa 100644 --- a/src/modules/systemlib/airspeed.c +++ b/src/modules/systemlib/airspeed.c @@ -62,7 +62,7 @@ float calc_indicated_airspeed(float differential_pressure) if (differential_pressure > 0) { return sqrtf((2.0f*differential_pressure) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); } else { - return -sqrtf((2.0f*fabs(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); + return -sqrtf((2.0f*fabsf(differential_pressure)) / CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C); } } @@ -106,6 +106,6 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp return sqrtf((2.0f*(pressure_difference)) / density); } else { - return -sqrtf((2.0f*fabs(pressure_difference)) / density); + return -sqrtf((2.0f*fabsf(pressure_difference)) / density); } } From c46efd3a7b71f725fcc2887d4a40a90864629c02 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 15 Jul 2013 14:03:39 +0200 Subject: [PATCH 16/44] Added saving of default values once loaded --- ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x | 1 + ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x | 1 + ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer | 1 + ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom | 1 + 4 files changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x index a72a2a2396..a9ab1a32e1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x +++ b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x @@ -31,6 +31,7 @@ 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 # diff --git a/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x b/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x index 8fa87442ba..200f49d1b0 100644 --- a/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x +++ b/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x @@ -29,6 +29,7 @@ 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 # diff --git a/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer b/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer index e04aafe54c..5090b98a42 100644 --- a/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer @@ -29,6 +29,7 @@ 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 # diff --git a/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom b/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom index e04aafe54c..5090b98a42 100644 --- a/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom +++ b/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom @@ -29,6 +29,7 @@ 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 # From eb2a9ded6965ef876b578d23916c5b1204cba44d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 15 Jul 2013 14:17:42 +0200 Subject: [PATCH 17/44] Only printing value if equal --- src/systemcmds/param/param.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index c3fedb958b..40a9297a77 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -327,12 +327,12 @@ do_compare(const char* name, const char* val) switch (param_type(param)) { case PARAM_TYPE_INT32: if (!param_get(param, &i)) { - printf("curr: %d: ", i); /* convert string */ char* end; int j = strtol(val,&end,10); if (i == j) { + printf(" %d: ", i); ret = 0; } @@ -342,12 +342,12 @@ do_compare(const char* name, const char* val) case PARAM_TYPE_FLOAT: if (!param_get(param, &f)) { - printf("curr: %4.4f: ", (double)f); /* convert string */ char* end; - float g = strtod(val,&end); + float g = strtod(val, &end); if (fabsf(f - g) < 1e-7f) { + printf(" %4.4f: ", (double)f); ret = 0; } } From 47dd3fdae1d626a28c273946d45ea8c79fb4b76f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 15 Jul 2013 14:35:20 +0200 Subject: [PATCH 18/44] Added default params for F330 --- ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x index a9ab1a32e1..58a970eba5 100644 --- a/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x +++ b/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x @@ -30,6 +30,22 @@ fi if param compare SYS_AUTOCONFIG 1 then # Set all params here, then disable autoconfig + param set MC_ATTRATE_P 0.14 + param set MC_ATTRATE_I 0 + param set MC_ATTRATE_D 0.006 + param set MC_ATT_P 5.5 + param set MC_ATT_I 0 + param set MC_ATT_D 0 + param set MC_YAWPOS_D 0 + param set MC_YAWPOS_I 0 + param set MC_YAWPOS_P 0.6 + param set MC_YAWRATE_D 0 + param set MC_YAWRATE_I 0 + param set MC_YAWRATE_P 0.08 + param set RC_SCALE_PITCH 1 + param set RC_SCALE_ROLL 1 + param set RC_SCALE_YAW 3 + param set SYS_AUTOCONFIG 0 param save /fs/microsd/params fi From 7380cebb6752b954a43801d5508a7babcadad558 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 16 Jul 2013 08:08:55 +0200 Subject: [PATCH 19/44] Cleanup comments and make them more consistent between messages. --- src/drivers/hott/messages.h | 166 ++++++++++++++++++------------------ 1 file changed, 83 insertions(+), 83 deletions(-) diff --git a/src/drivers/hott/messages.h b/src/drivers/hott/messages.h index 451bee91ce..224f8fc56d 100644 --- a/src/drivers/hott/messages.h +++ b/src/drivers/hott/messages.h @@ -72,8 +72,8 @@ struct gam_module_poll_msg { /* The Electric Air Module message. */ struct eam_module_msg { - uint8_t start; /**< Start byte */ - uint8_t eam_sensor_id; /**< EAM sensor */ + uint8_t start; /**< Start byte */ + uint8_t eam_sensor_id; /**< EAM sensor */ uint8_t warning; uint8_t sensor_text_id; uint8_t alarm_inverse1; @@ -125,52 +125,52 @@ struct eam_module_msg { #define GAM_SENSOR_TEXT_ID 0xd0 struct gam_module_msg { - uint8_t start; // start byte constant value 0x7c - uint8_t gam_sensor_id; // EAM sensort id. constat value 0x8d - uint8_t warning_beeps; // 1=A 2=B ... 0x1a=Z 0 = no alarm - uint8_t sensor_text_id; // constant value 0xd0 - uint8_t alarm_invers1; // alarm bitmask. Value is displayed inverted - uint8_t alarm_invers2; // alarm bitmask. Value is displayed inverted - uint8_t cell1; // cell 1 voltage lower value. 0.02V steps, 124=2.48V + uint8_t start; /**< Start byte */ + uint8_t gam_sensor_id; /**< GAM sensor id */ + uint8_t warning_beeps; + uint8_t sensor_text_id; + uint8_t alarm_invers1; + uint8_t alarm_invers2; + uint8_t cell1; /**< Lipo cell voltages. Not supported. */ uint8_t cell2; uint8_t cell3; uint8_t cell4; uint8_t cell5; uint8_t cell6; - uint8_t batt1_L; // battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V + uint8_t batt1_L; /**< Battery 1 voltage LSB value. 0.1V steps. 50 = 5.5V */ uint8_t batt1_H; - uint8_t batt2_L; // battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V + uint8_t batt2_L; /**< Battery 2 voltage LSB value. 0.1V steps. 50 = 5.5V */ uint8_t batt2_H; - uint8_t temperature1; // temperature 1. offset of 20. a value of 20 = 0°C - uint8_t temperature2; // temperature 2. offset of 20. a value of 20 = 0°C - uint8_t fuel_procent; // Fuel capacity in %. Values 0--100 - // graphical display ranges: 0-25% 50% 75% 100% - uint8_t fuel_ml_L; // Fuel in ml scale. Full = 65535! - uint8_t fuel_ml_H; // - uint8_t rpm_L; // RPM in 10 RPM steps. 300 = 3000rpm - uint8_t rpm_H; // - uint8_t altitude_L; // altitude in meters. offset of 500, 500 = 0m - uint8_t altitude_H; // - uint8_t climbrate_L; // climb rate in 0.01m/s. Value of 30000 = 0.00 m/s - uint8_t climbrate_H; // - uint8_t climbrate3s; // climb rate in m/3sec. Value of 120 = 0m/3sec - uint8_t current_L; // current in 0.1A steps - uint8_t current_H; // - uint8_t main_voltage_L; // Main power voltage using 0.1V steps - uint8_t main_voltage_H; // - uint8_t batt_cap_L; // used battery capacity in 10mAh steps - uint8_t batt_cap_H; // - uint8_t speed_L; // (air?) speed in km/h(?) we are using ground speed here per default - uint8_t speed_H; // - uint8_t min_cell_volt; // minimum cell voltage in 2mV steps. 124 = 2,48V - uint8_t min_cell_volt_num; // number of the cell with the lowest voltage - uint8_t rpm2_L; // RPM in 10 RPM steps. 300 = 3000rpm - uint8_t rpm2_H; // - uint8_t general_error_number; // Voice error == 12. TODO: more docu - uint8_t pressure; // Pressure up to 16bar. 0,1bar scale. 20 = 2bar - uint8_t version; // version number TODO: more info? - uint8_t stop; // stop byte - uint8_t checksum; // checksum + uint8_t temperature1; /**< Temperature 1. offset of 20. a value of 20 = 0°C */ + uint8_t temperature2; /**< Temperature 2. offset of 20. a value of 20 = 0°C */ + uint8_t fuel_procent; /**< Fuel capacity in %. Values 0 - 100 */ + /**< Graphical display ranges: 0 25% 50% 75% 100% */ + uint8_t fuel_ml_L; /**< Fuel in ml scale. Full = 65535 */ + uint8_t fuel_ml_H; + uint8_t rpm_L; /**< RPM in 10 RPM steps. 300 = 3000rpm */ + uint8_t rpm_H; + uint8_t altitude_L; /**< Altitude in meters. offset of 500, 500 = 0m */ + uint8_t altitude_H; + uint8_t climbrate_L; /**< Climb rate in 0.01m/s. Value of 30000 = 0.00 m/s */ + uint8_t climbrate_H; + uint8_t climbrate3s; /**< Climb rate in m/3sec. Value of 120 = 0m/3sec */ + uint8_t current_L; /**< Current in 0.1A steps */ + uint8_t current_H; + uint8_t main_voltage_L; /**< Main power voltage using 0.1V steps */ + uint8_t main_voltage_H; + uint8_t batt_cap_L; /**< Used battery capacity in 10mAh steps */ + uint8_t batt_cap_H; + uint8_t speed_L; /**< Speed in km/h */ + uint8_t speed_H; + uint8_t min_cell_volt; /**< Minimum cell voltage in 2mV steps. 124 = 2,48V */ + uint8_t min_cell_volt_num; /**< Number of the cell with the lowest voltage */ + uint8_t rpm2_L; /**< RPM in 10 RPM steps. 300 = 3000rpm */ + uint8_t rpm2_H; + uint8_t general_error_number; /**< Voice error == 12. TODO: more docu */ + uint8_t pressure; /**< Pressure up to 16bar. 0,1bar scale. 20 = 2bar */ + uint8_t version; + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed */ }; /* GPS sensor constants. */ @@ -184,52 +184,52 @@ struct gam_module_msg { struct gps_module_msg { uint8_t start; /**< Start byte */ uint8_t sensor_id; /**< GPS sensor ID*/ - uint8_t warning; /**< Byte 3: 0…= warning beeps */ + uint8_t warning; /**< 0…= warning beeps */ uint8_t sensor_text_id; /**< GPS Sensor text mode ID */ - uint8_t alarm_inverse1; /**< Byte 5: 01 inverse status */ - uint8_t alarm_inverse2; /**< Byte 6: 00 inverse status status 1 = no GPS Signal */ - uint8_t flight_direction; /**< Byte 7: 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ - uint8_t gps_speed_L; /**< Byte 8: 8 = /GPS speed low byte 8km/h */ - uint8_t gps_speed_H; /**< Byte 9: 0 = /GPS speed high byte */ + uint8_t alarm_inverse1; /**< 01 inverse status */ + uint8_t alarm_inverse2; /**< 00 inverse status status 1 = no GPS Signal */ + uint8_t flight_direction; /**< 119 = Flightdir./dir. 1 = 2°; 0° (North), 9 0° (East), 180° (South), 270° (West) */ + uint8_t gps_speed_L; /**< 8 = /GPS speed low byte 8km/h */ + uint8_t gps_speed_H; /**< 0 = /GPS speed high byte */ - uint8_t latitude_ns; /**< Byte 10: 000 = N = 48°39’988 */ - uint8_t latitude_min_L; /**< Byte 11: 231 0xE7 = 0x12E7 = 4839 */ - uint8_t latitude_min_H; /**< Byte 12: 018 18 = 0x12 */ - uint8_t latitude_sec_L; /**< Byte 13: 171 220 = 0xDC = 0x03DC =0988 */ - uint8_t latitude_sec_H; /**< Byte 14: 016 3 = 0x03 */ + uint8_t latitude_ns; /**< 000 = N = 48°39’988 */ + uint8_t latitude_min_L; /**< 231 0xE7 = 0x12E7 = 4839 */ + uint8_t latitude_min_H; /**< 018 18 = 0x12 */ + uint8_t latitude_sec_L; /**< 171 220 = 0xDC = 0x03DC =0988 */ + uint8_t latitude_sec_H; /**< 016 3 = 0x03 */ - uint8_t longitude_ew; /**< Byte 15: 000 = E= 9° 25’9360 */ - uint8_t longitude_min_L; /**< Byte 16: 150 157 = 0x9D = 0x039D = 0925 */ - uint8_t longitude_min_H; /**< Byte 17: 003 3 = 0x03 */ - uint8_t longitude_sec_L; /**< Byte 18: 056 144 = 0x90 0x2490 = 9360*/ - uint8_t longitude_sec_H; /**< Byte 19: 004 36 = 0x24 */ + uint8_t longitude_ew; /**< 000 = E= 9° 25’9360 */ + uint8_t longitude_min_L; /**< 150 157 = 0x9D = 0x039D = 0925 */ + uint8_t longitude_min_H; /**< 003 3 = 0x03 */ + uint8_t longitude_sec_L; /**< 056 144 = 0x90 0x2490 = 9360 */ + uint8_t longitude_sec_H; /**< 004 36 = 0x24 */ - uint8_t distance_L; /**< Byte 20: 027 123 = /distance low byte 6 = 6 m */ - uint8_t distance_H; /**< Byte 21: 036 35 = /distance high byte */ - uint8_t altitude_L; /**< Byte 22: 243 244 = /Altitude low byte 500 = 0m */ - uint8_t altitude_H; /**< Byte 23: 001 1 = /Altitude high byte */ - uint8_t resolution_L; /**< Byte 24: 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ - uint8_t resolution_H; /**< Byte 25: 117 = High Byte m/s resolution 0.01m */ - uint8_t unknown1; /**< Byte 26: 120 = 0m/3s */ - uint8_t gps_num_sat; /**< Byte 27: GPS.Satellites (number of satelites) (1 byte) */ - uint8_t gps_fix_char; /**< Byte 28: GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ - uint8_t home_direction; /**< Byte 29: HomeDirection (direction from starting point to Model position) (1 byte) */ - uint8_t angle_x_direction; /**< Byte 30: angle x-direction (1 byte) */ - uint8_t angle_y_direction; /**< Byte 31: angle y-direction (1 byte) */ - uint8_t angle_z_direction; /**< Byte 32: angle z-direction (1 byte) */ - uint8_t gyro_x_L; /**< Byte 33: gyro x low byte (2 bytes) */ - uint8_t gyro_x_H; /**< Byte 34: gyro x high byte */ - uint8_t gyro_y_L; /**< Byte 35: gyro y low byte (2 bytes) */ - uint8_t gyro_y_H; /**< Byte 36: gyro y high byte */ - uint8_t gyro_z_L; /**< Byte 37: gyro z low byte (2 bytes) */ - uint8_t gyro_z_H; /**< Byte 38: gyro z high byte */ - uint8_t vibration; /**< Byte 39: vibration (1 bytes) */ - uint8_t ascii4; /**< Byte 40: 00 ASCII Free Character [4] */ - uint8_t ascii5; /**< Byte 41: 00 ASCII Free Character [5] */ - uint8_t gps_fix; /**< Byte 42: 00 ASCII Free Character [6], we use it for GPS FIX */ - uint8_t version; /**< Byte 43: 00 version number */ - uint8_t stop; /**< Byte 44: 0x7D Ende byte */ - uint8_t checksum; /**< Byte 45: Parity Byte */ + uint8_t distance_L; /**< 027 123 = /distance low byte 6 = 6 m */ + uint8_t distance_H; /**< 036 35 = /distance high byte */ + uint8_t altitude_L; /**< 243 244 = /Altitude low byte 500 = 0m */ + uint8_t altitude_H; /**< 001 1 = /Altitude high byte */ + uint8_t resolution_L; /**< 48 = Low Byte m/s resolution 0.01m 48 = 30000 = 0.00m/s (1=0.01m/s) */ + uint8_t resolution_H; /**< 117 = High Byte m/s resolution 0.01m */ + uint8_t unknown1; /**< 120 = 0m/3s */ + uint8_t gps_num_sat; /**< GPS.Satellites (number of satelites) (1 byte) */ + uint8_t gps_fix_char; /**< GPS.FixChar. (GPS fix character. display, if DGPS, 2D oder 3D) (1 byte) */ + uint8_t home_direction; /**< HomeDirection (direction from starting point to Model position) (1 byte) */ + uint8_t angle_x_direction; /**< angle x-direction (1 byte) */ + uint8_t angle_y_direction; /**< angle y-direction (1 byte) */ + uint8_t angle_z_direction; /**< angle z-direction (1 byte) */ + uint8_t gyro_x_L; /**< gyro x low byte (2 bytes) */ + uint8_t gyro_x_H; /**< gyro x high byte */ + uint8_t gyro_y_L; /**< gyro y low byte (2 bytes) */ + uint8_t gyro_y_H; /**< gyro y high byte */ + uint8_t gyro_z_L; /**< gyro z low byte (2 bytes) */ + uint8_t gyro_z_H; /**< gyro z high byte */ + uint8_t vibration; /**< vibration (1 bytes) */ + uint8_t ascii4; /**< 00 ASCII Free Character [4] */ + uint8_t ascii5; /**< 00 ASCII Free Character [5] */ + uint8_t gps_fix; /**< 00 ASCII Free Character [6], we use it for GPS FIX */ + uint8_t version; + uint8_t stop; /**< Stop byte */ + uint8_t checksum; /**< Lower 8-bits of all bytes summed */ }; // The maximum size of a message. From 1d883ad4c6e5b45cf8133c0d954d6a1155969890 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 16 Jul 2013 08:10:38 +0200 Subject: [PATCH 20/44] Hotfix: Fixed RC calibration --- src/modules/commander/commander.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index 928d9b85e0..8e5e367120 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -282,7 +282,7 @@ void tune_error(void) void do_rc_calibration(int status_pub, struct vehicle_status_s *status) { - if (current_status.offboard_control_signal_lost) { + if (current_status.rc_signal_lost) { mavlink_log_critical(mavlink_fd, "TRIM CAL: ABORT. No RC signal."); return; } From 0cd8f2d35b30b5081083ae830409a9090a02c6bc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 10:01:03 +0200 Subject: [PATCH 21/44] HOTFIX: Fix startup order --- ROMFS/px4fmu_common/init.d/rcS | 56 +++++++++++++++++++++------------- 1 file changed, 34 insertions(+), 22 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 22dec87cb0..bbd86a4744 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -7,7 +7,6 @@ # can change this to prevent automatic startup of the flight script. # set MODE autostart -set USB autoconnect # # Try to mount the microSD card. @@ -42,31 +41,44 @@ then sh /fs/microsd/etc/rc.txt fi -# -# Check for USB host -# -if [ $USB != autoconnect ] -then - echo "[init] not connecting USB" -else - if sercon - then - echo "[init] USB interface connected" - else - if [ -f /dev/ttyACM0 ] - echo "[init] NSH via USB" - then - else - echo "[init] No USB connected" - fi - fi -fi - # if this is an APM build then there will be a rc.APM script # from an EXTERNAL_SCRIPTS build option if [ -f /etc/init.d/rc.APM ] then - echo Running rc.APM + if sercon + then + echo "[init] USB interface connected" + fi + + echo "Running rc.APM" # if APM startup is successful then nsh will exit sh /etc/init.d/rc.APM fi + +if [ $MODE == autostart ] +then + +# +# Start the ORB (first app to start) +# +uorb start + +# +# Load microSD params +# +if ramtron start +then + param select /ramtron/params + if [ -f /ramtron/params ] + then + param load /ramtron/params + fi +else + param select /fs/microsd/params + if [ -f /fs/microsd/params ] + then + param load /fs/microsd/params + fi +fi + +fi From 8d1abf4aa441e1c6c886e8af6ecaab2c3ca6e255 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 13:16:34 +0200 Subject: [PATCH 22/44] Lunchtime HOTFIX: Bring back USB console to operational, allow single-USB connection operation via QGC --- ROMFS/px4fmu_common/init.d/rc.sensors | 13 +++---- ROMFS/px4fmu_common/init.d/rc.usb | 27 +++++++++++++- src/drivers/boards/px4fmu/px4fmu_init.c | 2 +- src/drivers/hmc5883/hmc5883.cpp | 3 +- src/drivers/mpu6000/mpu6000.cpp | 3 +- src/drivers/ms5611/ms5611.cpp | 3 +- src/modules/mavlink/mavlink.c | 47 ++++++++++++------------- 7 files changed, 62 insertions(+), 36 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 62c7184b85..5cf1ff3835 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -34,9 +34,10 @@ fi # ALWAYS start this task before the # preflight_check. # -sensors start - -# -# Check sensors - run AFTER 'sensors start' -# -preflight_check \ No newline at end of file +if sensors start +then + # + # Check sensors - run AFTER 'sensors start' + # + preflight_check +fi \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 31af3991a4..9868219946 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -5,8 +5,33 @@ echo "Starting MAVLink on this USB console" +# Stop tone alarm +tone_alarm stop + # Tell MAVLink that this link is "fast" -mavlink start -b 230400 -d /dev/console +if mavlink stop +then + echo "stopped other MAVLink instance" +fi +mavlink start -b 230400 -d /dev/ttyACM0 + +# Start the commander +commander start + +# Start sensors +sh /etc/init.d/rc.sensors + +# Start one of the estimators +if attitude_estimator_ekf start +then + echo "estimating attitude" +fi + +# Start GPS +if gps start +then + echo "GPS started" +fi echo "MAVLink started, exiting shell.." diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c index 212a92cfa8..36af2298c2 100644 --- a/src/drivers/boards/px4fmu/px4fmu_init.c +++ b/src/drivers/boards/px4fmu/px4fmu_init.c @@ -194,7 +194,7 @@ __EXPORT int nsh_archinitialize(void) /* initial LED state */ drv_led_start(); led_off(LED_AMBER); - led_on(LED_BLUE); + led_off(LED_BLUE); /* Configure SPI-based devices */ diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 59e90d86c1..ac3bdc1325 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1221,7 +1221,8 @@ start() int fd; if (g_dev != nullptr) - errx(1, "already started"); + /* if already started, the still command succeeded */ + errx(0, "already started"); /* create the driver, attempt expansion bus first */ g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION); diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 2208425369..8d9054a387 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1063,7 +1063,8 @@ start() int fd; if (g_dev != nullptr) - errx(1, "already started"); + /* if already started, the still command succeeded */ + errx(0, "already started"); /* create the driver */ g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU); diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 59ab5936ee..c13b65d5ae 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -969,7 +969,8 @@ start() int fd; if (g_dev != nullptr) - errx(1, "already started"); + /* if already started, the still command succeeded */ + errx(0, "already started"); /* create the driver */ g_dev = new MS5611(MS5611_BUS); diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 7c1c4b1751..919d01561c 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -420,12 +420,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf case 921600: speed = B921600; break; default: - fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); + warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud); return -EINVAL; } /* open uart */ - printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud); + warnx("UART is %s, baudrate is %d\n", uart_name, baud); uart = open(uart_name, O_RDWR | O_NOCTTY); /* Try to set baud rate */ @@ -433,37 +433,35 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf int termios_state; *is_usb = false; - /* make some wild guesses including that USB serial is indicated by either /dev/ttyACM0 or /dev/console */ - if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/console") != OK) { - /* Back up the original uart configuration to restore it after exit */ - if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); - close(uart); - return -1; - } + /* Back up the original uart configuration to restore it after exit */ + if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { + warnx("ERROR get termios config %s: %d\n", uart_name, termios_state); + close(uart); + return -1; + } - /* Fill the struct for the new configuration */ - tcgetattr(uart, &uart_config); + /* Fill the struct for the new configuration */ + tcgetattr(uart, &uart_config); - /* Clear ONLCR flag (which appends a CR for every LF) */ - uart_config.c_oflag &= ~ONLCR; + /* Clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* USB serial is indicated by /dev/ttyACM0*/ + if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) { /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); + warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); close(uart); return -1; } + } - if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); - close(uart); - return -1; - } - - } else { - *is_usb = true; + if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { + warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); + close(uart); + return -1; } return uart; @@ -751,8 +749,7 @@ int mavlink_thread_main(int argc, char *argv[]) pthread_join(uorb_receive_thread, NULL); /* Reset the UART flags to original state */ - if (!usb_uart) - tcsetattr(uart, TCSANOW, &uart_config_original); + tcsetattr(uart, TCSANOW, &uart_config_original); thread_running = false; From 7bf2edc3bf9f04d52c6bd9a64d383acbc2071a00 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 14:01:42 +0200 Subject: [PATCH 23/44] Script cleanup, WIP on mavlink logging --- .../init.d/{rc.1_fmu_quad_x => 01_fmu_quad_x} | 0 .../{rc.2_fmu_io_quad_x => 02_io_quad_x} | 0 .../init.d/{rc.fmu_ardrone => 08_ardrone} | 0 .../{rc.fmu_ardrone_flow => 09_ardrone_flow} | 0 .../{rc.30_fmu_io_camflyer => 30_io_camflyer} | 0 .../{rc.31_fmu_io_phantom => 31_io_phantom} | 0 ROMFS/px4fmu_common/init.d/rcS | 63 ++++++++++++------- src/modules/mavlink/mavlink_log.c | 11 ++++ 8 files changed, 50 insertions(+), 24 deletions(-) rename ROMFS/px4fmu_common/init.d/{rc.1_fmu_quad_x => 01_fmu_quad_x} (100%) rename ROMFS/px4fmu_common/init.d/{rc.2_fmu_io_quad_x => 02_io_quad_x} (100%) rename ROMFS/px4fmu_common/init.d/{rc.fmu_ardrone => 08_ardrone} (100%) rename ROMFS/px4fmu_common/init.d/{rc.fmu_ardrone_flow => 09_ardrone_flow} (100%) rename ROMFS/px4fmu_common/init.d/{rc.30_fmu_io_camflyer => 30_io_camflyer} (100%) rename ROMFS/px4fmu_common/init.d/{rc.31_fmu_io_phantom => 31_io_phantom} (100%) diff --git a/ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x b/ROMFS/px4fmu_common/init.d/01_fmu_quad_x similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.1_fmu_quad_x rename to ROMFS/px4fmu_common/init.d/01_fmu_quad_x diff --git a/ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.2_fmu_io_quad_x rename to ROMFS/px4fmu_common/init.d/02_io_quad_x diff --git a/ROMFS/px4fmu_common/init.d/rc.fmu_ardrone b/ROMFS/px4fmu_common/init.d/08_ardrone similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.fmu_ardrone rename to ROMFS/px4fmu_common/init.d/08_ardrone diff --git a/ROMFS/px4fmu_common/init.d/rc.fmu_ardrone_flow b/ROMFS/px4fmu_common/init.d/09_ardrone_flow similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.fmu_ardrone_flow rename to ROMFS/px4fmu_common/init.d/09_ardrone_flow diff --git a/ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer b/ROMFS/px4fmu_common/init.d/30_io_camflyer similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.30_fmu_io_camflyer rename to ROMFS/px4fmu_common/init.d/30_io_camflyer diff --git a/ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom b/ROMFS/px4fmu_common/init.d/31_io_phantom similarity index 100% rename from ROMFS/px4fmu_common/init.d/rc.31_fmu_io_phantom rename to ROMFS/px4fmu_common/init.d/31_io_phantom diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index ee7e840505..b22591f3c3 100755 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -23,30 +23,6 @@ else tone_alarm 2 fi -# -# Check if auto-setup from one of the standard scripts is wanted -# SYS_AUTOSTART = 0 means no autostart (default) -# -if param compare SYS_AUTOSTART 1 -then - sh /etc/init.d/rc.1_fmu_quad_x -fi - -if param compare SYS_AUTOSTART 2 -then - sh /etc/init.d/rc.2_fmu_io_quad_x -fi - -if param compare SYS_AUTOSTART 30 -then - sh /etc/init.d/rc.30_fmu_io_camflyer -fi - -if param compare SYS_AUTOSTART 31 -then - sh /etc/init.d/rc.31_fmu_io_phantom -fi - # # Look for an init script on the microSD card. # @@ -106,3 +82,42 @@ else fi fi + +# +# Check if auto-setup from one of the standard scripts is wanted +# SYS_AUTOSTART = 0 means no autostart (default) +# +if param compare SYS_AUTOSTART 1 +then + sh /etc/init.d/01_fmu_quad_x +fi + +if param compare SYS_AUTOSTART 2 +then + sh /etc/init.d/02_io_quad_x +fi + +if param compare SYS_AUTOSTART 8 +then + sh /etc/init.d/08_ardrone +fi + +if param compare SYS_AUTOSTART 9 +then + sh /etc/init.d/09_ardrone_flow +fi + +if param compare SYS_AUTOSTART 10 +then + sh /etc/init.d/10_io_f330 +fi + +if param compare SYS_AUTOSTART 30 +then + sh /etc/init.d/30_io_camflyer +fi + +if param compare SYS_AUTOSTART 31 +then + sh /etc/init.d/31_io_phantom +fi diff --git a/src/modules/mavlink/mavlink_log.c b/src/modules/mavlink/mavlink_log.c index d9416a08b9..1921958568 100644 --- a/src/modules/mavlink/mavlink_log.c +++ b/src/modules/mavlink/mavlink_log.c @@ -41,16 +41,20 @@ #include #include +#include #include #include +static FILE* text_recorder_fd = NULL; + void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size) { lb->size = size; lb->start = 0; lb->count = 0; lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage)); + text_recorder_fd = fopen("/fs/microsd/text_recorder.txt", "w"); } int mavlink_logbuffer_is_full(struct mavlink_logbuffer *lb) @@ -82,6 +86,13 @@ int mavlink_logbuffer_read(struct mavlink_logbuffer *lb, struct mavlink_logmessa memcpy(elem, &(lb->elems[lb->start]), sizeof(struct mavlink_logmessage)); lb->start = (lb->start + 1) % lb->size; --lb->count; + + if (text_recorder_fd) { + fwrite(elem->text, 1, strnlen(elem->text, 50), text_recorder_fd); + fputc("\n", text_recorder_fd); + fsync(text_recorder_fd); + } + return 0; } else { From a5c8d8c5f20584f32acaa03e69681a13799fff6d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 14:24:32 +0200 Subject: [PATCH 24/44] Robustified accel cal --- src/modules/commander/accelerometer_calibration.c | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c index 48a36ac268..dc653a079d 100644 --- a/src/modules/commander/accelerometer_calibration.c +++ b/src/modules/commander/accelerometer_calibration.c @@ -283,6 +283,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { hrt_abstime t = t_start; hrt_abstime t_prev = t_start; hrt_abstime t_still = 0; + + unsigned poll_errcount = 0; + while (true) { /* wait blocking for new data */ int poll_ret = poll(fds, 1, 1000); @@ -327,12 +330,14 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { } } } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "ERROR: poll failure"); - return -3; + poll_errcount++; } if (t > t_timeout) { - mavlink_log_info(mavlink_fd, "ERROR: timeout"); + poll_errcount++; + } + + if (poll_errcount > 1000) { + mavlink_log_info(mavlink_fd, "ERROR: failed reading accel"); return -1; } } From e19d2e94ec5c38c2800a7001a2a04102734012d4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 15:20:36 +0200 Subject: [PATCH 25/44] Hotfix: Ensured there are never two filters running at the same time if auto-magic happens via USB link --- ROMFS/px4fmu_common/init.d/rc.usb | 11 +++++++++-- src/modules/att_pos_estimator_ekf/kalman_main.cpp | 3 ++- .../attitude_estimator_ekf_main.cpp | 6 ++++-- .../attitude_estimator_so3_comp_main.cpp | 6 ++++-- 4 files changed, 19 insertions(+), 7 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 9868219946..147521fd11 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -22,9 +22,16 @@ commander start sh /etc/init.d/rc.sensors # Start one of the estimators -if attitude_estimator_ekf start +if attitude_estimator_ekf status then - echo "estimating attitude" + echo "multicopter att filter running" +else + if att_pos_estimator_ekf status + then + echo "fixedwing att filter running" + else + attitude_estimator_ekf start + fi fi # Start GPS diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp index 4befdc8795..372b2d162c 100644 --- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp +++ b/src/modules/att_pos_estimator_ekf/kalman_main.cpp @@ -121,12 +121,13 @@ int att_pos_estimator_ekf_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { warnx("is running\n"); + exit(0); } else { warnx("not started\n"); + exit(1); } - exit(0); } usage("unrecognized command"); 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 d8b40ac3b5..1eff60e88f 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -139,10 +139,12 @@ int attitude_estimator_ekf_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tattitude_estimator_ekf app is running\n"); + warnx("running"); + exit(0); } else { - printf("\tattitude_estimator_ekf app not started\n"); + warnx("not started"); + exit(1); } exit(0); diff --git a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp index 3ca50fb39c..107c2dfb12 100755 --- a/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp +++ b/src/modules/attitude_estimator_so3_comp/attitude_estimator_so3_comp_main.cpp @@ -139,10 +139,12 @@ int attitude_estimator_so3_comp_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tattitude_estimator_so3_comp app is running\n"); + warnx("running"); + exit(0); } else { - printf("\tattitude_estimator_so3_comp app not started\n"); + warnx("not started"); + exit(1); } exit(0); From f93fbbae238e0d3c303a3553322dfa6a8cc277f2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 15:26:14 +0200 Subject: [PATCH 26/44] Make preflight check optional --- ROMFS/px4fmu_common/init.d/rc.sensors | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 5cf1ff3835..73f40c5039 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -39,5 +39,5 @@ then # # Check sensors - run AFTER 'sensors start' # - preflight_check + preflight_check & fi \ No newline at end of file From 798075c90d0bf1d271ce9758f1649f160b7373ec Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 15:50:07 +0200 Subject: [PATCH 27/44] Work around orb_check fail in sensors app --- src/modules/sensors/sensors.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index ae5a55109a..be87c752d5 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -1141,10 +1141,13 @@ Sensors::ppm_poll() { /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */ - bool rc_updated; - orb_check(_rc_sub, &rc_updated); + struct pollfd fds[1]; + fds[0].fd = _rc_sub; + fds[0].events = POLLIN; + /* check non-blocking for new data */ + int poll_ret = poll(fds, 1, 0); - if (rc_updated) { + if (poll_ret > 0) { struct rc_input_values rc_input; orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); From da54659b5e2c883c504cc48b82a03504cdaae6af Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 15:55:06 +0200 Subject: [PATCH 28/44] Removed wrong dependency check --- src/modules/sensors/sensors.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index be87c752d5..e4fb7416fb 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -139,14 +139,12 @@ public: private: static const unsigned _rc_max_chan_count = RC_CHANNELS_MAX; /**< maximum number of r/c channels we handle */ -#if CONFIG_HRT_PPM hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */ /** * Gather and publish PPM input data. */ void ppm_poll(); -#endif /* XXX should not be here - should be own driver */ int _fd_adc; /**< ADC driver handle */ @@ -397,9 +395,7 @@ Sensors *g_sensors; } Sensors::Sensors() : -#ifdef CONFIG_HRT_PPM _ppm_last_valid(0), -#endif _fd_adc(-1), _last_adc(0), @@ -1135,7 +1131,6 @@ Sensors::adc_poll(struct sensor_combined_s &raw) } } -#if CONFIG_HRT_PPM void Sensors::ppm_poll() { @@ -1335,7 +1330,6 @@ Sensors::ppm_poll() } } -#endif void Sensors::task_main_trampoline(int argc, char *argv[]) @@ -1448,10 +1442,8 @@ Sensors::task_main() if (_publishing) orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw); -#ifdef CONFIG_HRT_PPM /* Look for new r/c input data */ ppm_poll(); -#endif perf_end(_loop_perf); } From 7106565e94ab683b3b9d4b6182bb123e018cbb8b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 16:17:47 +0200 Subject: [PATCH 29/44] Simplified USB startup script --- ROMFS/px4fmu_common/init.d/rc.usb | 40 +++++++++++++++++-------------- 1 file changed, 22 insertions(+), 18 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 147521fd11..c89932bb5d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -15,29 +15,33 @@ then fi mavlink start -b 230400 -d /dev/ttyACM0 -# Start the commander -commander start - -# Start sensors -sh /etc/init.d/rc.sensors - -# Start one of the estimators -if attitude_estimator_ekf status +if [ $MODE == autostart ] then - echo "multicopter att filter running" -else - if att_pos_estimator_ekf status + + # Start the commander + commander start + + # Start sensors + sh /etc/init.d/rc.sensors + + # Start one of the estimators + if attitude_estimator_ekf status then - echo "fixedwing att filter running" + echo "multicopter att filter running" else - attitude_estimator_ekf start + if att_pos_estimator_ekf status + then + echo "fixedwing att filter running" + else + attitude_estimator_ekf start + fi fi -fi -# Start GPS -if gps start -then - echo "GPS started" + # Start GPS + if gps start + then + echo "GPS started" + fi fi echo "MAVLink started, exiting shell.." From 56805e8378b4c3a23e274e0815d1e11413895533 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 18 Jul 2013 22:49:04 +0200 Subject: [PATCH 30/44] First community review version of autostart --- ROMFS/px4fmu_common/init.d/02_io_quad_x | 2 +- ROMFS/px4fmu_common/init.d/10_io_f330 | 139 ++++++++++++++++++++++++ 2 files changed, 140 insertions(+), 1 deletion(-) create mode 100644 ROMFS/px4fmu_common/init.d/10_io_f330 diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x index 200f49d1b0..131abf8c4e 100644 --- a/ROMFS/px4fmu_common/init.d/02_io_quad_x +++ b/ROMFS/px4fmu_common/init.d/02_io_quad_x @@ -105,7 +105,7 @@ attitude_estimator_ekf start # # Load mixer and start controllers (depends on px4io) # -mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix +mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix pwm -u 400 -m 0xff multirotor_att_control start diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330 new file mode 100644 index 0000000000..4107fab4fa --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/10_io_f330 @@ -0,0 +1,139 @@ +#!nsh +# +# Flight startup script for PX4FMU+PX4IO +# + +# disable USB and autostart +set USB no +set MODE custom + +# +# 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 set MC_ATTRATE_D 0.007 + param set MC_ATTRATE_I 0.0 + param set MC_ATTRATE_P 0.13 + 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_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_YAWRATE_D 0.0 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_P 0.2 + + 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 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) +# +mavlink start +usleep 5000 + +# +# Start PX4IO interface (depends on orb, commander) +# +px4io start +pwm -u 400 -m 0xff + +# +# 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 + +# +# This sets a PWM right after startup (regardless of safety button) +# +px4io idle 900 900 900 900 + +# +# The values are for spinning motors when armed using DJI ESCs +# +px4io min 1200 1200 1200 1200 + +# +# Upper limits could be higher, this is on the safe side +# +px4io max 1800 1800 1800 1800 + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# 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) +# +mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix +multirotor_att_control start + +# +# Start logging +# +sdlog2 start -r 20 -a -b 14 + +# +# Start system state +# +if blinkm start +then + blinkm systemstate +fi From 2c31961bb02522543e2f23bca2c21a7aef7669c7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 19 Jul 2013 08:09:35 +0200 Subject: [PATCH 31/44] Minor change to make USB startup more resilient --- 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 ae5a55109a..f7f0a1f48f 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -1488,7 +1488,7 @@ int sensors_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (sensors::g_sensors != nullptr) - errx(1, "sensors task already running"); + errx(0, "sensors task already running"); sensors::g_sensors = new Sensors; From 4d88b56e38cfcef91890ec3baec16fbda41cee75 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 19 Jul 2013 08:14:44 +0200 Subject: [PATCH 32/44] Handle case of non-present leds in preflight check --- src/systemcmds/preflight_check/preflight_check.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c index 7752ffe674..d1dd85d479 100644 --- a/src/systemcmds/preflight_check/preflight_check.c +++ b/src/systemcmds/preflight_check/preflight_check.c @@ -135,6 +135,7 @@ int preflight_check_main(int argc, char *argv[]) close(fd); fd = open(BARO_DEVICE_PATH, 0); + close(fd); /* ---- RC CALIBRATION ---- */ @@ -251,6 +252,11 @@ system_eval: int buzzer = open("/dev/tone_alarm", O_WRONLY); int leds = open(LED_DEVICE_PATH, 0); + if (leds < 0) { + close(buzzer); + errx(1, "failed to open leds, aborting"); + } + /* flip blue led into alternating amber */ led_off(leds, LED_BLUE); led_off(leds, LED_AMBER); From 0f19de53119e5d89b2520f6906ab50fc9d3a3b28 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 21 Jul 2013 11:27:52 +0200 Subject: [PATCH 33/44] 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 34/44] 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 35/44] 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 36/44] 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 37/44] 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 38/44] 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 f4fc3bbd571ce99b707d326a206159a6eab49547 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Jul 2013 14:10:37 +0200 Subject: [PATCH 39/44] 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 zcmajGWl&z-vNihP?(VL^-5r8kfZ#5{T?4EKcPGK!CAfQVcXtc!!S&X=_u2QH^VL`P zcGapmd-ZIo{xN^_9HTV`A~_xcMO6U`8XE+H2Z6*)UK3E1QN&DMCARu*_D!HcAd}i} z)KDnA%p80g>|6ruYyxcTNoi12@a&wjTx?2Qd`W#!EKuz1oJluOt&r@TNxz^ufPef! z|3i>LAdstto13+Rl`D&vz1<&OgQQg+Y`@EDVBqHsKV05;#V#nSt ze0Pfxsu7cs>S}Xx3S)STmZY?s8m2n8$%Ta<7c(JYqDGR5FVOnNG8I}ogS9SV!UtxA z8owgeMz-{TMZn+N_%Hu`?k*=QYQSg*h(QxC;Y(jxX(id$U#WA5l8{k|(iGv5w~S1X zZ6sPN=LT}ai_F!~b1CJG@f_vL_b#m+I-8qpq{|^Lt#))O%?4Dc65fVN1SvEdY}OuELY2-<_Qvn@NEP7S760%|_$X^C zU}%Y$X!}R-e6n9}HY?Wt7Pi1oo+7@*1%97HW8IGNw$Sb+1H=fEJ@_bbjpcygPCgK+p3=2^~^wSA5W z7i7bmM~Pbs#N0S9aM^II)W^9A;%A1c?c#@epa)1IsUqaGBH(C@s7o7<@888x%K?`r z(db&>cL}&Hh%(0p)~?!6C;hR;A~ubrMkdgq@joqt)miejhWoNJ>8x1dI{afGng?lC z^3#v!`|AWSZ&4^mV0C4>-~DNqjpdkXRs!Z5)8cLF1LXUIQf)UHx3PN}W)D*o3~>!D z)fq6|KQ`5_rU(Xj_fq#x`<}Dp`(Mgjez&X&guYlJOOaS_+g?>bdP-v=`W;wpM^=5S z)#h)Nt9jV%t+0D}{D#{VOiS^N1s%n>fAMP+vZ;$=4Vo#uZ~xEZC}Vn_M!j3a=puQ> z@XIh|mjlA8OI)9xeeshP*ec~9CgmU1p@F~^;AG9GH&0|pcrj7rl0?C>U3v#I#Pt_| z5p{U6I3l4jR3Y#uxRI-v$ZIrJiuNb%r*NVsn2IleNv1hDg&)J=6M2XG`rFG^V&PxMsXl_@D3y( zei4owwxI+!$4f1J#YJISkTM`aN>aO&z1~~eGPUTrB!bklOMHwm=H%3(G3QgaiR0BN ztte{qIAk2HKB$^uMq_U@|WjnY<;WvpjrNlYcEyjgYhHHwUg2lrcUQ}V3?Dsdgwg0m9$j4q}F-!(= zLqJo3Y`FkOZHkKJqw2i8KcV;cCN{B!bDLyPGTDcUtwRJ=a}|v*5_gXexgHSEPm+B` zrwaVjwZ>WoM_tp?E{}QQD59x+mbYMHVoanI%=}k=g$?u6+E6O3uA-SqNs3_NE=QqR zSs8{E))`|C-@JpByo-73XW$}P6Q}lgugkhUo(QV$o5h2(SVug%qt3^%Az5UWmlhMu z1((xv&S}8c%&O_RTUYrdx&@$p^YOXWpqh2?d1I@ItL+X=*_+MUlXhzIn}BtjZ+>8^>QcE;L=PiqItk^Fc8;yUi4xVsy`dM~v#Kh^Ake?> zb$EFAfA0090|ZjwG;xj3<2|QD^^Ue|Ln(ohg}P^QndS1#&V%uOe10{<<;E)VXQ{)5 zY`#R9;|u0f+QV4VKJgVLn3BGH#KCnnouPsPlROU%?l9C9?6|pJ{WEEeZ;kf&c>%_` zGfJ)_yXddE-`&Y>HQC4ha1?L#$4-V@t*qtsAEB&`%H2C)GOg&8!krKbUrnL&a5ZR<;h zrbXwSP}D^m&tMysKp+ZR)yO{IK>c*!jYH?-=498Wc}-ur#M9IBg2Z+1 z%tpSKEwdbG*9^1L?3_?)(r7%Wx9*6(wpe3u9%-m-kMvYqdN(oXR5;C8IOID;R%(bs zm2poR&?|)$#Y3oH3%ccj_1iFXFRohqgfw1%N`IF<7cvAn3zXDz5t5UAGFh>ZXvTqc%krE}esjanG$$avMBWL;cy{8TC3!S8C4dsPOy;qWDyA2q3BLvhDqJ?j8 zsigo2BK5UfEL7NuI94KVn0zs|>QT&Gqwac{2%*SYMc}N&C^o$tN-vdfWBO(<*1@n? zwu}&eV(4V?^@p87A@8ZT2r57L`i*uHvjc}&vtD5jAyi6k*J8x7{DD^(*5{34_XWqA!%7ukeI@d45&1xzJVhQ5$!qO{(CKBsNWnk1 zqFjMAGr=M~n#C_4X=el^DPZ04kBluJf5rQY(n`<5M48Hs=ERUPHc8tS$y$70{B=cq zu7YV*pRWGqhIUkyTiqzL17q^oJ9&b2^bl7m6U7+Ys-1dMxd!U0i|GwU5Z}I<^;Q8u zHS~7BE-@$hQ0&b4fZy8X|LI?RbGSzTk`^i|3FlBf`s_JEToiKXF+OX7$nnIR z{ao!e#yIL9!Fj|rT;ZojXsp)>sklA37G;i5@0?Y&w+k6d4#MDHvi|uhEPdmYZ{Y${ z@YtMj&Y~kU|7nvFz22`;6OyyTmpB&q<@%$@bJ9Ii-vH{GDgO`d12n#a4&H94V9o{ll9=eDx%inB z+5r1D#e>x!CkD>o4^dI~XuIW=uRLcad>PERMsGELtL>KYPP(i8m)}zO&x~Y%$v8W^ zpt&KQx7TK`rgjC7rQ-?IJl}Ql9D&4YmQ72L^%h1G%KBrdOvkwOQm=gwxVG9~X0+OF znIK~#uwI_T-=Z%zeZhN~b2sKQh*y5O{+k0~oPy@m!UPW+@xQF3FI<^{XLo_XYz5*o)Grj}Ll=K};y&P8jv= z1)Ds3Rl_e?$UF`+Y^whknTfcFRx@9@#QVu_-(Z7#Y~xti#2i#Naxrps(aPtv1)R6A zKybfu@@3XQ%cxK9cQm*7uFHwF((jgcFjvAQzGI@FGu&RPMICnU_9YvD%>$!~sxw=G zuh#;Ti3Bw}?dI*=Hg<^{$goE|qlvz)oxUSHPlB&plstk3B8DFM_L#rydD+!X3AXT> z+k?DvtvZO&t%<^8cpu1Tlf;Ck)eKR?4ganClz<2}4Y5L}b(>sb9GoS)bB9ZbnFQ@mpq9U1$)*8)NxlppC^E^L8+ z7Y07wENMXyMb<(_Os zae&&{_HrgosKDIUrTs9M=)I3FwK6t=W2W-EaW1_LCMxQqC~G|^b;ql?&HaZp^S3o# zB>GptBS|sh*8idXK5Y6~GPgNtixab^3|@PBGj)MzkMX3tLuXp&!fBW!@(O*XV#!r9Ki=vwpVk&J!l5^=gW+rzi7_LaCU~btheN$KM4Wl zc^`Td4rUNVTizsEz*n}aS}Dk%5s{b#!K{YNj!wkjE&J;k6Yv7Iw)EX@R3#xUUL;3N z&8|FD#(r|y5CZLZ^FgLdt>UGIOm)yo2oI08P@%c?;9hx-hK2+#?>T$&xInVE@*fKT zaz1r@%;tdig?{cW{AZA2jCe82Oh|SGnq%JIR5#6aXr*s{ULREJMl^ck*PrH5D!-PK zW{B+9$=5MWG!#8D<|=g?upFiFDye^xMJDijSHt}IEJ1D6TiEa#`8}?Fk;O~26mJ!o5_t4NPTyKEyOZc}3+Btv6 zq;0=CKo6k=?!6(fxD9+k&x~YweswBtWtDe5_CXm`PUptZH>Tl3BAW9NZXa=ox*Gc) zScQH8hlBDP2D8PDOw3>9)Hh}~zvL7_EhN|2Jo2P%^7Hks|9o-~b_UdOHD8A_AOYzc zg-pE*5g8B4grca;tuX$A6>SAe_m$v&8a?GvfMfoyEC5-I=00KC`}PYA3OCDA55H8R zPCWK^YH>5Da?1V(%h-6|U4H1z%lMuY?})I#I5_2g6&I+PL^I8J#1#3Y<(9G18k5mq zsW-HWen`b`aSS~OvY2EqfB5r^0aPU6DU;+wm|k!}44gWetU6)5e2SN1m_{1}JNhr1 z%+OLki>@%jd{Q@zN4hTT;U7uU6e20Q)>2?X<3DH9eP+ZEFtRa)NA!rH_)Eva; zx2PDQAjM!G)yZX*!C8>eFY0t+WWS_24ayj-lAnGJaEWTz$SOryo`*hB0m+0u*Uu$n zqFkT2{7Bmrt-6ta(Q=my6vO6m*9jo_-jbK1B{vL|OsJqwVRG5pcLm;bULxbke90Mg z^y9WMp%IZRKt=AB}BlBwbSm+fFM$OstFiEg^>vnXg2OdO{CR%D6GGHXvo`?snz#9sLuTr znl9zvLrvMFzCtJk>*L5k)42x`+G|||A*yAe9Dol(@2z3w8x1W%0ApMdZ63sIagPH# z10=OFAqQQd>24BvPj5InimgLL?#0jCs@%I)(p3_yn}$|WUC;tC7PUrp1V|W*`qsG# z%0wU;Uc`hnbyoYtvA|7Vn-K_k`W2QQPTa$#_FNHxU&2wd9{NH~eQ2d}QR+SwE2W4+ zS^O5E?dee77`#ahbVT__%nj@+IvDl!LR{a^-^L40zNY^)XOttQm(wCk^UPPJBUvN} z$16uiiWkrOJTCy1g>Jz}uMiM7nqXU=Nu!OE?vJ8`e&oTWryrXg8h6RCdIKV-z#xY> z;S*@R&S#8lfgssg!dxwu^7%79)5zb}-G{RHT1%%;sf{><)2jX>m zdO;XS{n7CWjFrtf$l5ZePdcCukYB-Wdt7 z2xydfSYab!DjBYX&Pw6hEpEiki^@L3c=0MNc}Q{e9tYAPzK)<@KK64hsR7mWFRslL z+q$SF;QbnS^MsmX6LKd)BQ5kYq`>D&9^qv|o_Ow_60Yi9azD&8Z}H_iC^kKG z{}N*xpxA{rr;#hTMuG39j6a}F1g@cv{d6+OOI(SlEEgjUsg_DglP#@oS3jQxYxsA8HI2x2{M z9`tf4St#l{=$8(aUUWoastt9N{i)H;%*Yt*>R;vMz2xXe34?adxShYKj!vAI=e~E zBpr;GH33#K0`|O6+-1HHNQcTBjLYE)Kj>Fx`td}ptHw>zV3{n+PkI2@6gE2Pbgux> z4)c7gez7Ts<}25OWayU+CG6}!tm+{*E+br5sT~$w?9$9{jByJ_z6;hhu$$d;(=R5c zBAR-4tBE&+A@aVUwNy1Fr{6Ws&3wAjFAj4GVZ$^-)AxnDrO~g5{&s!MZ55z{py+vn zaAbP1Zv$nAu%p5SdfXj&wkwr7psXA%oX2AEo>yy$6cZ*Hc=O$>tdWFAN zPHoAjC&T6WW%-k1FAM@`I9@pzu96%aQ6yg=F^?`$gqN@0heBCw;X7OQjR%QB?=`nJ zG_W^9!R-Yd6aMyRL~p>)6xANl983q@h5Z&CKYawWaXt?YG0?Km=B_uK6^(C){Nu=X zr6&5sE*Wv9$iivi^@jY~FWho~0(K4ax#CxLKV1Pw1k0yfVU#a;c%>Qvqb#mo2@qm2 z#-wOkknH3^L2pN5=5WubS(fy)YJZ(X<#Xm<>f)*auNShdkF~Y9t&hjP{l1}QvhIuy z;N?80`(vklq*=7<|xGc_j`}qhu$b_i<$LURmu0JwvQRf3m+Q*O@g1_!P^+W3&{h3?KVmlcLdWOHzp0 z%E`Cl6$NGe%*3kJ4*=Ty?i?-40dtdQ!6K|48D|L3oV0`YMx5i{L^M24AMSp9&`x&$%6d zG`nT`+}tOWf73&!A54`vm8XX$W?4K-MWlsvhMCUud2Z!Q)Lw~ve9q?jJQi8QkPM}0 zPaz#IeA`8;g`n=oQJb-J#(|6>PEAZrR%(x3kDaR|z!v=`aR!=EeJo{ACsWZHQ30tH zVNl3Jh`S!27{`EpitCOv)a;9}X zuSy;Q2r)?!&U<|jZrOjIN0%yY@jn#>_f>K&r7J1xoGB8DNVIU33ojN~T9*sAU@_cB zzaUQ>hy_Ey>niPw1cTo z2|`=Qg6R+>&wRvwwe}3PF~b-Jc)qElBugcne-ukpqdfpa z0t&8q9>w>L?yOU8FkZEeFj-2^t*zwXbqeqPOwe5QdyhJ2B1xSuKBb(Hme}!*N!k(1 zP+SfDU5M+nLH2~75CW%XIaZ?*9TE_y%$a#l(`m_PANA!~WU3{G&Sd?s1KjeqjjRN+ zzV6nqkc{?5{6cw!f+`FFOEfpf*vm8YIuh0Oijay<-EjC)$+T^({ zK7Kf%W(5CRIAvGXyj{s`Q#7BSa_6aqAD4@I5i9p;j9i`+ABdjswfo ze)Pbh<r;CjH;yBc7^6Ynu)x7BE*}<>#smm6l0P|nXZj*jvsre z5m|7V$XSkqz+%FlC6oOp7Y|^smS1S4sVpltll7tJZY$AaJJoCM3ir-0sYpTEz8TYD zYrh#0@5rY-CFUyH$-Aag+L+NvW-5e8r0)s#8t%PHt%QOqgmr&5hjqnfk$o_x{M=Gq(Pn;Fo z)rA`gRfRsAjP`pHb)q?rRHdIsL)g%YBs`Q?se!R=kFEh<6~MIO=XSDvip9Div{y%E zYoR*lsXmZg2v@qMKJQNXj(5^0)yp^Jf}G%=MlG(Z^LV zKkHi8VNyeMdeCQAcFZLQMo>?;u+mjfpCJpQoM(=9_JLSvR2(N%TZ9CCdYTKcI0r*? zcYP0i!|ul|YF!Dh{{=dc(GOo_eg0iV!V``*-epl$MwM}0YX^WIwM{Lr5mIg!6O-Is z?zQ5yKa)VkderJT1Ds`8 zd06g9UR*sWnK*Cn;N2(T>52)eaW4kLe0?g#4DMqZS1}}~cPAk~%I9K{N+U{lz{Na? zO_9+%PsrsdjsnGFpiAHu~~R!e?_&~K7?U;4iYF_fgH`1D+Uxre^t$l*erCW3Bxw5SlR!r zAv|0b`=E_JB-K)8Gtl35D>VQ|HSB$1FEwUZk5S*!)BwY);OX1YGnYz10C&|>!6D?- zYu_8>jwB$>xt9iLXCjOBsyL|zLwPhI+==^!1aQx(zzQL{N6FeQYPXAJ4SmJd#yY{; zCZMQ8BCY9IMmf!fGkSUt*zsx^fp+4Y@M3b6xDQ%BzN)wsdAq%MaqPbIdDf)+-sb)= z(nZV3{os)Tl{$X7LDStavu@QJ%p&TeOpH&X{ta;ZlIdfg!I~rDm+q@-&aPAB`q+aa zvG_IVlrKt98OJZ|r*)e)b^RkI>ufAhEruLS}&p0{!#hgFqmSZ|?S{4kp%iuB>j~-0hPDXqW&@COIi_ z4X?~|1AC7@^r$q4x3tBU1V1(h>`GHDTYAr>Vv z^JRsX8|?1v>}-vR(Y#(eLbS7s?#JyJoLz=o)+W>g5h<7<8Jk(#LD(_HFoR=?YGG<> zxtc&cKL`IggpRPivqNF74m_S8Ir4FAq&f5zB6~U9-`?+ z2f0BHV+w#0;DmZ|QtQ~hQ))mmiMF9LL1-~iHb8O24rgsDAJ1mI{gq$@6*{8w34?I| zU>de@x?3R0#f>9Ihih09ErEN9$=4)ba_UGpr559R+Bd(^sfS_e0B}@mHc8(MFbUI0Fa*HKo#kEjpDM1< zl4j1P%wGOXgq)+osZF=;#{<2YNF6^46U`6Tpz8d&)aJ&f1S5d%k{Z3g%+xb;sMt|h7^fggD1axI}P)6o; zNkF#!@bS33r3{NDj41`RdE?A=-$zwJJ9?wl7K)4wD3Z&*g+D-;d^l^{5{yG;a=G32 zeTmHj@1z&Zmjtg^h~bEpwF@lAeGv^59Un6uyjPcMl8d__t9?;%&XjEcDb%*kRwvJ% z5#=zHLW(V`6p93kN_TcDAEqpV8$ik8a+sK9h4djLM^oV(&9$)a@aPBa9-tIv0)rIS zLKh{V{o~5fDb&ZymTt`dnH;>tZ1*+7B>(;aeFDO31L$$CGBpdyFa8co;}!XN-m~&J z0J@PuZe<>=-WU;V|H>uN|M=|sl(yKh$#^Nmw}niPzrzrWTIi5% z$Y-LEWq9A1>LQAk>O;J~*@vl`8-HN1DdkoIZ&>Gr%d&~qpv;?M`75?}kihPw66o8wr*Fdkk%q8E@U?Jz6u%uvMR{GCQhhMh2GmhxiE~|=X-OXYm+D}#DSu;h zQ|#^V2r)%@B>0+#mom#El~iX0A3Mq-%Fjt0JA-vqP@%Atd@1JZ#D%-(oI!M*a0Mek zIU!-XoENl)A-j*?tb*jFfB&PK;Hwfhm`;kz!ltaAR}fwnW?PBy@!{4OM+zmXj(P#IOns~UWJ5j_gCFXoEtoHtMV zYpGB5Rt}l|`yF1}_j$;=xWQt!1CJmel!uwUQ4I~xfM!Fd*ZN01G2CY}QDKS(1}du= z&>Zyh-VDKUcxW>NJLCShz~CS;xZ5Q#_thatS1X=)CG=wb){UUhO1cLQg823Vz^*I{ z%t5?O#wXma1+K-#xZsS5B!2UjFAK0S3N--(f84KV zrn$EbB!7Ctn(Pq3(Dy?GhsK-g4=RuCCd{l#2-S_{2UD$lb+$!=6bN7og{6$ll#wZc z;tG>T=IdPH3RDnX;y5dnpd%5edD4L0e3Ya5q9$8m?UYNGZzv?8shP2v+~{!%+sG$2 zpJ0_D?YuAII1yGmL#B>Jf3gG2t_ObuG;4)WN|(3%jJrb_YlJ!)bP3h`n)`2wJfx6i zfEIe}O-jO4IZ*QFz-7^7_i`wKm%uvshYY_xiSXfPpGWY^DlnW3J9M6N^mTt*Z4PXG z0Fr>d&tXw#mP+>AzaZgfy`(QPUaTz7sULKWQ;#Gy@TY*^)NIW+$sb@sm`Gy$K2=6aiABI) z$9Ors!JV6W02sLYGEn`vUL~BC5h>QgIh7u4lkrJa1WBN$IER7%&S2X7jg^?4DRt(a z7-b=mtIliF#4>13u(Ipo2Tf+koHkM6SxAve%qG+%VkTdd-n)kw-y)sH@-xQjz%EzpA#5JdFk|JQX6A2jIRvQeP{i+J7h>tT{61As> zb}&&gl|ic}4iH|d9Rx&t#`9?d1Dm1oUkITG;mJ`_eBe{8`C?MDA*(hrLNJCbsAO53 zt4;360k)bK&$o@-ji1)=2k0~M{6+rsbM=MhAM+Q@@ot4Mp|HVcDGx|*>$&mIem|{c z&9sZSD-4QyRl@MJ>$L6@NDf&cx6}9%ehV{vyE=E{2q-r#nzUw_%Ox_XPIp`n>^kSX z(m?;yDL3kDB!snMp~f{QM*S9;4x+!q?^2Y^0p4lQrx=IF-aG-qii4nd3% z1+B0UJmF|{dY`|fi!2!G+Iq}DeuWQ45uYlgLXsVDig}myMy>gkD}ui^dGa?n;2S0! z7=W{4P+vXfwM4-09HKWTl%)f?S)yIqDvp3R2%l-uXIZ9+@H>l?_u~@|P_-w}p7;=>5FfogfefiDl23LPHEx;oQgBmlC*$ zhy_(0!C+L6&4f$>87|{OLS#2Tn#A{C03t=5rafVz#<*ZP&0NQRJ@~+3S`DHAd*+zA z7^~6ybK4VJBn;#B@z24>tDC<~JGPH|FE64~T84B6yr|Qw5#kJAgeOM&Rj6zqy2#KZuFwwaJYMFbHh zGQ>M5hd${)Lwv+L_8EFlIZ-#bTY{&z@`dK;-!|SPZyUmOt?t{ii#O(|Oz*e7$PgL7 znv{JadqXv%GEZe_CDd=2&QnTuy1;232`a%RVBggn!(fE?qyYH9Iz@RIReYRhw5P zzznLOV2cc-kU%p+=i;<^ZnG!%7P-;2sY2aK#FOJ;yjy-eY#BY8ghjpsZx2Q?Pnz($ z1J&-tJeSj-#W&z{|Co+>R8(1lQ5WJhA`IY#IBwtIlHQ*WMKA0YsJcHiV1HqFp?&@( zi=1NBz1J!p#yW?t2`+*7Ap!Y+EM*;#ooyncwxmZ2grr=*{dq zpZcd#T~MEy4BA6nm`tN7&|TNZvTxjNg{*j3oQba`>|%v0Yt>^yVS8=)w@l=t^Yd?^ zZb_d0^Yz|$-JYq-4O<)_4Nc=wif&wNx%8~!8!h6gScxMwg%@Qf`jo%p{gnjqd$Qve zsiJic#2B4@*k4|D#EzwMJ#vA4pZ@n6B?6kqgl*m$RoeD=#vX(Upu3@>gjERX0wEV0 za)q^{4BpSO#|wsDq!#>IfyY1lBJ9Gh;pcvdov#t@#-c~aTMuX6oRC$c7difLq$|ta z`}@%>7BOHAPMkvN&(?4aCp^4W=VoOXu;Y(Io+a=aAtI^zBBk!}atl85XiK^dlx;Io zhhIlMvmz3O-J#ynz$zdiLcb^%4u}>=KikgQeu=<#tc!74jNzG;$F%7S zJRR{ONA?LiP|9=)UKAfQ_1L?uSk#-feqtJ~I7!ic30cU$`mGpRLWa%N0G~Y zN{3aBGf_H#>`;b<^TPxca=7Ht5(oT6UWpk8b3JRgwagJtKy1e-tjhlonB^`-m(@Mv z`k-;2`;#KQvk2WUBe&OcT=GbZ3l58f4Hu+(P1Bp9G8MW;^1h$AE}yTqtD$*|2#X#> z+}bJ7ckqEghQ5|QEO!T(gN6)bn7W%dFk=kFK~R8eJ=LdSM-4yv?}()x9wpj2@QJ;L zxMJxshtKI)w~pq?sQ53tAA{?V@M5t2XY7%w7Avegu&6a8P8bkkkUE|r1BeMjayoIb{BtDRWN(1B1W0+i zrwUMFcM+3L)QrRajhbfE_2T&n9{d(6#`BUMSm`+Ge&|;!IsDe7GW6ck1)`2WBy62g z7?uhp>*V<4_Tk_G@y)%q=O*&RPsAJ1e5B<9(- z_G4(U=U~FM(%E_7uPJ(=w;$RI9>aB_8O=cEueDN}xLz(uV{+>Mn*q>Wy2|`D95T9Cdh~QR>fmow*^)q}03 zOC|(=lKfo)D^>hJ$NWR8HL8<6J;(9+-+`6p;-6E|JSxH0kjr@lOJ^~^8?=8RO>ADn zMdN{AR?VbEDbOly6sJa`hePMWm}i{6&=z$mKZUSJ`k`S#Ix$W8xplCa15@YWbrUJ&_nNQ=AlRnLQCDs*dRNvXlUA0hk}wYZU!0o%Nrp)RcvztR!DH9(aR1jzk%YjD{jWVa@4x?P^YZ>n zALgY<5|u_w>g0w0FP-yW>pQQ;|7$0gK}-Vk{mWh-#h3E$4UM=4#J^7XN^t&fI!{uE z1cUBB1f73D#s3Q_{trRtzhxQvf75kT6(At7LD>I6l1u#0`5V%IyMaI;L&PLeNdmHe z!vCM6xc?T~Bu`1Ye-)P}Nd)pdK`CsaVBoX90Z&Ei8DayYS{?}OVUj`n&q&!~S zBotow|BKOqFNu|xl<|Lg{m-U@i2pl12m~tTOS0l6|3BhfOA|qE|C5CH|6;)9PjZ!} z{a2Nl(nOGo{7EQ$3~2vp%zx_qCqw~%5~>WX;6E)e@7Itvg$IGQ*g+t~|5d;WKM3UN h=51&3FFMqJ!u$uR?6MZQ(H;kZqN)G|jST|9gFyJwJV_|ZDEQJmlEcyS!G_QvkYR&0 zH53X53nzyLyMQ1Ury#cgI1`Erj$e+OU5SemJP5@KApm}WYKP?F1J^@y0{^Yy~pE zeW?XP0U$X@2-SXfv~AvoRE|<%>qn>VMeT3>K>xVqStNM*B);xdmqj5+Qe(M4%_kyp z9jR!WBfxLAbpFg45FrJuJhZ+hHGOIMC{=gP`0%aEyaKcnd6EV%f0Q_{#!Mgnv#*Ys zo993>i>x8R!L*W7na29{+aLcx;X1P7jF*;}7^E#x1C=-!Ih0Q+IQ(QghgnLipg*C? zcSX!rPPMXwSCZK<3PUy9bc?5zy?+4_J(-k)1Axc49V>9(z-jv zw)Y%QuQB4=#8YjBW&qcSkgmgJxI(V?_m+>EjWUmR&coZUVT_TnDkR^-}Zg49S?<~B*x!b@g9dgse-5dM6h>gI1Q3vR0;V@km62! zB*Q_YFy`G#IWZ>#s&QGwjTm}G?Mz5%6M(ErR^*yOP%piSNy?e%z)Kf{xv|t%`@W}} zc%n+ilh!SAN$NacEiItNF5X&id3FY|$m?F|a#Ew~v1plI9m}G7A)C+azPUC`hdHHE z*Nkqu)ADy+j4aEs5!pRbW51VDi7dnlehYU9AUY*o`#kdDLO|r5Kw{p;Wa?rC0E+mL zd|2^9JyDDK?xdSjDO}hu$NYKO6zn9kOa~=I8;WQaVbafoFGMDUx!U@}& z8=>4>2zZ4J(76OV>fVC~-9^y(#GHiRh=aTbeO_pD1c!|raGRi{O5G4K)@senYK!-3 z3a`{I%;TlDvzR00eIIn&INyOy0G~LQ`YG-w#+F7s3ALnT*?miu-R1{GkL;u5v4KJR zB~};ytzqRxp;EhT*!!7ilsI}=k#xM>wzXXyavGGg{~O-@vu-@8h|QUSl-qz(dzw!^ zQ?ewtFM`FxR^%*{3IpoxXbxxF3f`!1mn~0;N@Bt7Q%V|CRK3ru$YiM}K-@G0hIUcH z7VtN4`IM^VZtlNx(vUy<=lS7>G}85JbYFTkb|ACM`Eb=ZzJ&XCIzjwQnM#|rIPL?9 zGkHCIAv@f*Btt9#w?kwS0TW5gGVTji3k@tft0}dpP>p;{tK2fjt{>7cm*F|>;Ug;K z-g;m9;SkU?zG$UxfFJw)fw1R^f}FGs+MhTGdE;%#_O9m+qPVoPKkIUa!Jn?a9AtcT z#ay3bhtBT&eBz*s8WL!vH9gB2OCRET!Ch23>Ll31C+v<&SKBPtFH270+Db1`Ekw?V zaXskuf>Pae^1M1M_ysdg!d*?8`ax#f`-AYfSqz6d4+Tum$ke8*0=#fh#8x>p;hn&0 zYom)8U}mM~3DQ0OGX23)|418t7hP+gNFy^TnZi)+JCs};+}@A>?Q^R_$kU@_#6FBD z+g5|75y_3JFN`LNvI( zpFai20Phcr7GzPnHQ~wMPO|32ao@~E#t%U~ zG-rST|M+jAXCm7ptB7dUnvTgqf>TEmT?DuaNemhXRQjKX7(RgE0VI-7q- zvyHpIjjzqVIsWkB$`lqAjVD{-U)xlQ{Ot>vx>mzZSGi_KT+F3pP1FA3{26h8#Yqbe zSkY|EZgn6_Ysqd7)DHOE`n@povP`zSV}(`#J2*e)+sb9kxnR71K#v`ZLH?C6`}Ae` z+HY4&#LlAr!;4R0lNTM;CzqS^y*K-^qugX-f&8P3o{Nt<+P{NsTb1~}1D0y5wfPo+ z&Z0(*DzfLiKH(?-FZz0=WGcA8dReEr9Zr5OvuHM}70&KT6#_TCEUhY~qG<8x*AV#N zQ4yTulF?ekBe$!s9|t37Vw0EP#d}qL5hH%Zr9X}xqU7MZIg2yHphnWd+}ioyML`w` z;ZwL_KV#Z5?7>Q{8=54|*1hn3>egYv?3-iDy^2XjC!6n&+-ag1Nw;O_GOi58{%M=r z=jx;;!CYKL11v?Z#r$eh#1*@rzYwXjj5BQoA=E^e_18LW9SqFT&U|LkV1j<7D>W){ z*mZC(Zt`z!*U;NEuB&h@-evc|>JrwvCJN#ktQ^K^t{D`xRcMCf>(R_v>AB2FUU-)f2bAM3X8q`Xi75NZ{7V$INk8k?IVEPqSu_wGUClf8FK)JSt#{mbvAe6uS&sRVU?gji(XRl=ntY^r{7Y5BD&6 zRcH)@>(_OwP@wtUg4DNdH(^+!fG_XUs(AD}_f#ip@MDbl9RE3B{#tac3>dFp8aUzX z4w?FMCe@>Wr}FSE|K@2Dbx4Z=dA)==%m8=Op=sn=RQ~Exf);n)0<}E`Kz7b4ej&JQ zMB&YF4rXcP6t(CiQNC3288>g>5>sE~Y#lNiBR)QkTAVNM$lbL3QP<>gd-|GYu=!)9 zyqC6V!>pron$#2i;7;(*T%NzsOFE0VuLIhvU@c%U;N-UKW3?9c=jl|o;ttnS)eSi>}EQ@d@aB7-RFMt)6v?*a<#j`M%E)~(P^`+BjqTij_lx?pYK#G$dj)T z`zKr5FFyX~#O8rP?-Ig$R4qhrTB4GJMnS~(M*u%$Y779dx8=N);%$r9^-*joT3wg^ zqFkf(Lw7`@_)Q>buIPkGu}L9$qeMw9C>0t1M~RYJNGfuJTC_^Y-_boUUPvl(>sa`^ zkn}O{kq!5P2XxYN53Maz=Rymep-L0yo;oj3#riqD(Mt@Uh(s_A=XZxB--z885-~AN z8RflftyO@?ZF!d{p_%i_>zCx zhy62Hewze7| z#JL##$;v1Eb4|wrPA_esW|-4fif>j?XG5ANsse|G+l)W(Q;cp4{fq8A7F8IL-o9Rw z$t=fr)L5{6abm*_Y;v0Wv!*7vh38iHmqZb5!|T|{=7Eg}iKd1$Ug@$YWc=m=Q8N>v zI4}Un`M|jST5q7-pzaE(3P>YeF*|A}%H=bcg(06g(jj%E49`+rZQ-+#J^s&f- zRc<2F)#7`bnW%$2^QCbqEQYXur{+ddzj?bNpC*>w?$gm5SG;Ip=Is!4JU^sYpo{>M zbI}aPBi3jCmgdqkcfQC~l*lY+X(fF&TbDwh#)HoG(E4_Mp4?$eW3}-?F!Q3(0bIdR zSK(8}TD{m5adA|FO={X2(@?b^Q2>g|q)qi#^I|P76W1rf-h*hgX%%tWos>$*oD|c7 z4L0KNCKQiSQPqc5lauSCB0-nHr?oG&+l9Q5?87dd^T0gprA`q6m!k-@#BlG(cX?yZL04RZ7*T^5t*PVydQogV zb{WXfn?zffV*-a{KMspl-gYw8%S8lrIWTV}i9_=8YKa|!Pq?VO?A7~oM1GdXFS{Q1 z%*ntLT`7kJPJ@HVs{NKRcvd~;vUH+kXxeIg8n091cc5>O8=F^=% z?}Y1g)`6j7s%Hughp0WQ+E)mr&azhtgrb0s==)Q~xQ=|mx+-*cM7UDvC~I15iND-o z7jgyE#|tH5(PSX3MP3@$b5jJrE5ZyqoZe+5%XR27l`AQh21#{sB8fQw=2FQSjzy}h z4VC^|6he`2%QV$qht0^!u>jaOs=UqLNV14l*aK;YdW_kKy}(LQRz^@qS_*38DvV4n#Z8Z^%Y2Uv-A1IG5ry5?zFbnL)M|x@wH>~!O ze0O|NNM^we>DsvUQBpf~X2!U6iH$Y~+4<``sAsw^!YJEC?W4IKr_I@Xl%oX5>vW0Cz)Ap;~owUgN0>;Q5P z5LN2r4b4{OBj}evofp4=91l9 zSe)~GN}K|l1imW6#0x{ z@7`JbccGSIaRa)G16R%ZBztLnh^K+?^RHZ){dJ)AW?eA40HYbRwYSPS`3oW)6a!SD zPf~&6@D>nQH*4&N-msT&>bRO!BX&G>)S*zNK4SfDV9@k|Z4=xY%6mB}mV*`FX~``- z%DB?h-Prj~D8} zF#;&VH4HRztn~{TG!gsZRENrB5G);JK=%1k8AA1aA=IyMn)}A5R4@-=rca!RZ%dq! z0P{1=MBl9F>{#o3(pZm?s%?58N;J=>6v0b-HHR2@_&ZifH__7Zd#8}Y_YP%0O21#M zi&a2{B|2RMd+wZpOb6CspiH-FX@|YimsVw*!bPI)N2@}1QiMX8uYr(mmJ{O|z~Ka} zCJ*6w)-5!W*!RLyvDTZARe$&2{o}A$HFG?aZM#~^BoG4eg>;`S`wH--h0uM>I49i z5-pd%1l`Tq3(W|Tybg)gb=TH}qEpT?{4Ixi*-0D2^dQ23`lfQr;9c%7ZLGnUgAbwz zceZ4|D-cz`Z26|?k@-!QKO95~%knrFKI%zdtLd+q%-nH~V&neR4(BK=oLh&!J)p3s zCx=nM8K5_uJN5osN-j#*B)x>8r8NV*r%Ik_s$U@VW9Z@Fk!KI(LDVv13K)Mj`9Nb# zqejLO=}%AaVL?t^Ix?EEm-nN1Jkua$s#1w`D2;ZDl{y$AM#kb)M68EECv1fb{W%O$ zH=5sB69`+q>e;BalWfje&XlZ7{Yu(|HlkXmSS+afVRE!DXvZ7tq4xCK9$o|xBpA3N zyXdf~e;w`+B|Iy-UP?Kxm&f;{W6R-DO3qP(iY6NU>Gf^o%6ZeRuTzRt%*7^uRUKBS z#&t0VLx;&|=t4)CpcQLblR1zdRM4_!&ezG8ixtQ)Qu3n@tk*}He1*sC-Mf9=8}w01 z^+V5J)3q&(G`seyD!r(t(We8D13SczVZp#?G{~t#xb;59Ej}ULU%evz{RqSuh#cw_ zd{%MmeGVogS9mRSw5|l0?E0M1f7&} zPyRYn^q&YVe+h47df7-xSnrJfnk2iqfcfP=on?FEU}8_RlkS{aJHH6k!!`;Qd;7AF zN7bICo^Y7Rl;hvS+Q5(k)W?4yEom!je!bi6b9~8}m*L}07G~m47TlP~t>EPC*%Wg& z=DQf+Fq4HmYJ^U@B?$`B%re5sC@T`CNun1};aDUa zC@1bT4=>@iA)S)6UH1!0yUh=OrdrNYNe-Z}Pn%UIj7vf{!B=Vz#>yQjiHyNss)9RG zUX&*#$G^++sLW_(wh|^;>dq&42#3KG^N_nE08gXz({51Dd`6eE*ZGj=o7GWUXxEk- zv{&70a5wu}jfrOptWI>C5Iv>+ikF5K@i6sg&YQ(BxOLR3B$YVr`*ixVw=|{+r2~t6 z9lkPuV$5xS_8SL%8Z^uDv-bUOibnIz^>V{RA8?0g@qO2{bxcL}@x5WdHAQ0`(0F~iEBSjRd@F6Vj6zQY~ zTRFPzq3w#Ci~BxQwE+*&nDfwve1LO^R*1Kh z4?xaiIl8>F018|Y7!U0ZE0CXQ5G(q_8?@z9RI79=mNxc1wV~qC}+eJq)xJFtkzLW;Wc(h zbPKIVcmW8F*vMVFa7@a!?nt8M67}O^6wGuwntSS^bk5`#kO%Za{dacz^!Sn_Rov0Y z;-JrpKvz!IzOUj8sxYms?H4>Ja#DQ6-an^vNgPXYGNseLOw1zDdB>c%9^~|0BsOlT zR;$6ciuz9jXHm*&IvonFA#DNqyNA%>YD*ibd0t))QYzNJh%IMf}t)jLFw4 zbYk=)25=fXFLrY!Sf9sLy5e^w%Q;Wo7@Jn^OiSo?I0RE&O85Fg=Z6a;KaJ9W3lEvm zDk+8c8#tqaY=4t^+l4!;HH9oaj_nRMKz1iG_n$Q#xgPDnbG&devN>#-uViA<(Jd) z<0Fha8)RlxtFP@YlY80v;tu&^d_g8c6n$vs8oKyM*usQ3(%4{eay3~MqmPJ6DvD*IvxXq$j z^~mPrVw(TDS{s4##AHy;K(wT7_eY?&5$r-l7k+OMXu-RPsNVMFuK#5I)V78YNt+^nBtB-!50YTTgYrqGG>|7t+HPLkjFgfp*5% zs;_+u2%lD+IPFnC-63X7juTK&;SE@3{;=r-m0BnNED!^mCIU1iB=O5xG~>(2rLM%{ z8oB%D=FV3LWTl6R^7(}`sF|T82x#1`OeGCbmy5}v$VNJlcFy)+whR?xfG<-w!O0O0 zhC4ljl~UU=vAI*qiMI`|J6f+7Q!tPx&jU=}mf|-8^+RB8Rq}6bbV;-@tK~gfEGmwm(2|8Ekj|=B;u%(08<1Vq~tX=B@E{j1})4sAiQWwlq zdPw==qy^!Ao#7@I5`F|Y<^Eu>^ENdxKY~##SkhepFDp?1}j!u8tLPN zNR{ysU0N{M8NK}s`GnQtvxk5)Ch8Y2shrRWUK`Y$P>+!It@iR+z}V165{hmIL0QuC z1R;L<#$}t@KE&ou?=oO7aGP5ATg8J!;xz24in8S4Fh(QlrmcW8W)JLBKG!au-_W#X zy#bobZ-|qpK6&rrF%Lctgo!v7bCN+^)SOU0(WQWqoX~U0e5AwTup3uQ%mH~hBPcqG zJ0WE5mv~=~pTXdIU?{CL(<;+vt?cAP118h4^+`9%|FnhS+$z`wDZY??4H zfw0fTbm&hQA$o=AsdOha<~|yfeiOlOUHb_igCYa zm-9-uh6gcfQtP^6y6?&N85~`ox*GEl<6b(oIKQg&)EV;$yPR*FSFN3D(r>|aniyb3 z4@cYSVVovECcdH#be}!$1U-uTjk+YqBIfm6r97bD0xi`SgVVtmoG^2R3>EXFu#{z!rb` zz(L^(^g6jW1@|A``mrcR(%DB%LO2^j5M`jRdCTy;=03+p^Zg91_>Ml=Zxf9$;;%4L z-{}GUj7ck9C*GkLd9A2j#Vym0*bfzU^F0O8^h+>$H=_M<2ExrCdGCaozp7UNVoFDM;+uStjmI2ty_%wH?x`YiX&&qwP0=JD|m+3f3k#v3S{1B)xDfyWYLW;X#E{+$64`<(*{ zU(XDdy>%Gb*glS+Z<+A_0RaC&s16Pc3gH(%p@)(wI;-BPTeVyOD9@f!e+!g~MH)H% zgiN0L_iWdwD?%HrjD-wPjuV0A_8=K3J~3;pjGm~SE1Cl)P&M>#$-14}L=viRl!$mj zb~K?@@=z72J#u7781PrAerup_n%VT+F$Cf&%ui=56p#pxx*kGKA%UdFgn@L}1mr7r zQFfVzZ#NRVTqIfNVTpe=y%>PHA85%OTD9$)Iy|AhiExKRLT32o(3>LaT2Owu@p+usr3&7Z4FCM~h^~n|nY4*^zLMCj%n)$bJrHP<%XK=tP$H z-hnf}otgg8WAyN3wq8eH z=>xkCs;+gI3%KhJ^y@9?o$myW zH#Q32*VLl|;=apM(a|-yYJriWVlF2hz@XFUer0qcgQWcdk+N;&+uy7G#N=yCNi$o@ z_}NM;*!3ZQ``L!4vVj0yWh7xK_gKC@qs>hQ{V^G;Wfq6M7X$g(1tf-y+@bQG4ctRf zRq6+3N{F*xiEEz1qNUx7`@kLJ-)Bh2Kb0a{z}nz1@#Nrfsl<2aT7y3Rh34 za+RI&%K~Xugnv#j&TJ((PV3WGxHNQrcO?$%+p|+gQ<(v^v4ht@Us?)0fn*=et91o) zR;AniHp&ILgo+teQN=vOo1UW5NvJp!km5QyDVXTTa|0zcew5p|#Z4#Nq+|LD zE=;~Kev&Ua5euyI18LA0fEM32yop1DKH#8PjNa~sKd=nt8mbJl%@AEC^%^SH0qJk|Y zJxXrA{G-*;OD=LuWjgm3h&1wwdV_P%OU7Rsk*AD_*dl^U58m6prX)H@tNoxa&}&+7 z-I`6jjH!#!ZMVbe#+n%r(KGc954Jquwf7PrBr&zS2;PlzewwOm2e%&Ts*(xKrwZkVv@in%advAFKQeo@-2 z5!_tpyyaOi2Bk^I#~h0OEE2Di0nu2o`hx^(RAV348;mmynB6r3(=Hb^lE!ts;wGoI zYd=I_d*wRaS1tG0nZ!OXSD@6>w@}7d>uk|x9`d*KcK3BAgSuBi;tIbpuU6MW zjOUU%zp6z7^0Gfq!^GErjt@H=7oY@*(Je93Km@$@J{NR){rMV)gWR_Y@?a+%X$e8A zHJMX$X2OOVlvK!)#koc;o zPwMa2y9b`$XxP0eDLC2d;m9To8ae5?5U>t|IG2|Nkm=yQCjIeUbb=IyA#-C=sEkCcS+qpeENDW zDDUC{LfQ3QUKb11>5&r_(u_rrvn5DHK7BOohIE_IW-)qZ6*f{1eZ+%}w5wy>Sty_{L+Rm-E5qJ3Yg2q7*g-=DbFH{yVbls=_(23J2 z(QvOIqqydP&W*YIx_euG3UhL*WqeiJlu!bQAFM^8Tn-E`;NO9qn6+T42w6Sk1TTbm zputG4Mm(@Mdwwr|(|uSv#@m>=h`$`vnioJG1VOBoDPC=Ba|}S)9IJ7~h}f(`1txlOQB6?@f&CW#lD#Ebdl_GDXBJIX{*P|IHR} z7@G(4FH5j;dHO=S&}6$#9=uS4NWmrphK>P5^xq*dl4AUz-d^s#zY8W6;iw6p0F6Mzd$v*uQ6-!=vu1eHstX^3B!a2&w zGrX`LOosHq`OK+Fjy3?rRMnfaU)^$*p$8-M+Pm>$N5S4Go?#5Cq+G*6_D(&YCCA*5 zCGQPv>GYQ*_O6VUdrK|<&g z!21)OzucwQ{T1*gin3Er`D)TP?EL4($9zX1@b^q8rnqx}>P!?VS@}(e6XRPi?A$R# zqGX*1TY2O^%OIXGfuXAM$BWdg2BCuOs zKrnM%uXu=W{6Y=5MxOBxuPAs53!@RA9$k3tUlO!3_Z(t%8Kax+^ggMv&+z4;>?CaO z$-^p`TC&a55XAJ1#gh$au5#9+2jY1OsIGM*9RaVjzaK%7zCi8NA0Nq*EA=6|0kYwJ z$C(>0llq>3m~{%6^kqz=ZwcO2!k`sk9L*fwx1fGeK?tB=@a6yF7|vl$0N1CBj7mGr z{6VZAxp>v1%gPRWlOsVsm??5fS6<&4MEL4opqucqyC*nn3i`@L#$Tzs%cZKhG3FD5 z2Tw6Fd`@P~2E800+G9E0!*fkK8Vg%U33X39+I3Pm@;rLAb@j#)q57>Z65*`}`Wnjo zfKaK{=@Q^3@N~B7W#r`yQt%=7AuJ43b(R+hIum=B8h_UK73w^!>R$blZ?qA!$#YeH zZUIWa^1X#qS-cX3j(hdr?cBHhU^jpSQrB+jpSP!YgMxGudy!mdWvH*xt6-E&grN8v zUwJA6g?aiyM9|?R6|TASNt-TZrQh=3j8RB476Fj6A7P(`aH2Y(JSmTsQ`NhbBfuwo z)eFid>`QVm4bl=r_b#a4!pfhYMuz@!IucjG*G${Sn&`9AyS4&C^$98u?DH$ItLxqN zJ@$M!66_HjSs1r>&K5MW`$m^+hbBI(pC=;K&((NW-~{&+2uqYV2M*g_ONO(?SU(Bs z2Cn3ug_GBDOaI81EN_6s&x1{Dus-h93!aVVjlR`R>+^i25m3eiN+G!V%w3t@8jeT) ze%@ygzEIBpqhJP`fmRDM1c*p;6+9JLCE>Vzo2H5+5O)nDOz6KbWbI;DmYx7zL37EE zi1m$UcVX! z*_#Auj}3y@MXj9I`nJ@}d#Pewag@!Gp!fqerUkx1Mt5&v(DJPsc$+NJ>{8qxzQ7jD z2Wi2o@LlX{F|+4UYgg6j$M3cGK%|wawft<+EWAj3>s&-3=b6aUqYM#?RT)ov1u%0B z6pmf-6$r_fBBH#g6k`; zp{i)#V9LZo*TK4L>!X!+WTsz8$5?#V?H%~fmd!IuaFdWC3?2<^W0_R^5|q41f*#$g z7Zys8#bAcHo<~eFQYY+Y$g*n-fHrRiIqC{C`u97A!tE4pZmw2n2kfRYYoIGm#_is& zN{{OBRpu6KeP9&6=NV=EL=IrS=ieT?#kB=0Z>Gc9I6TAS5Amcq$cxy72%7AegTrO- zqlIVu^_6)`G}4K>;@zVZt%5yh@!O!0*pf_o$LuLVuWT4Z&}z7@W@g?!pj}A#xmD5_ zsk%COw@10sa0y9{Y{nEMGu{1~g&&6iCQ9tbqI6!Ad}MvQCPgP$_rOaQEf@lU24E?3 zSF|aAiaY%chA-K-@ljcp?0jKk2oO()2ud~-z7g78LC^61tgkuJg^52+%Q-70Mu?&+ zx03-lSPx=&MFpaLQ<6>qW*tG5s72=Fv3+cZh?Rf#&x$rc;ml>vAg;b4j-h#GV^ETE z?D~NL6xsB%Yuq}Bz~TM?-by^Psm_re)xace*gA2@$>!5t{38Z#>sOd()vn`o98AL6RB}|B5V0as9Wr1dJ!mK=zMfq$i`rjlB1lVK@CF|hSojm-zg$V5h#-r3!G!#zDF1cdzXEH#;M!00 z|G{DLfusK)9EA)KqyisUREF_ixCR*_$S^)|?I&Dto(%ebT%CO2DH&Swe{T2>H^_ez zr28+TH+*1g0S2&$Eb@Qyq5}L+#(Q=91=v8lOzzL7*)T5D4+VP6*@&*U94l aD|<|q2ohfcoFIt@ewRgub@-QF=l=jBG4O8y diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 74be1cd23f..3f88b8c8c9 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -39,6 +39,7 @@ MODULES += modules/sensors # System commands # MODULES += systemcmds/eeprom +MODULES += systemcmds/ramtron MODULES += systemcmds/bl_update MODULES += systemcmds/boardinfo MODULES += systemcmds/i2c diff --git a/src/systemcmds/ramtron/module.mk b/src/systemcmds/ramtron/module.mk new file mode 100644 index 0000000000..e4eb1d143c --- /dev/null +++ b/src/systemcmds/ramtron/module.mk @@ -0,0 +1,6 @@ +# +# RAMTRON file system driver +# + +MODULE_COMMAND = ramtron +SRCS = ramtron.c diff --git a/src/systemcmds/ramtron/ramtron.c b/src/systemcmds/ramtron/ramtron.c new file mode 100644 index 0000000000..03c713987a --- /dev/null +++ b/src/systemcmds/ramtron/ramtron.c @@ -0,0 +1,279 @@ +/**************************************************************************** + * + * 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 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 40/44] 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 41/44] 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 zcmdVAby$>J_dY(-B_K+7OAg(kpfpNK=Pn;w z<%0(R0ALUp813N%wsLZULO@n%2m%gth1>8WtWXdXKf(zNw?TkhU|=|!-wtWzWDfzM zwEjd$_|hsN4+{Xee7+Nc(N_HKFsO{YI}FO?3Pz$J2)HbZAin?$6BrIc*g)WRvMl;~ zN_-M5@^S<+2wPhS2rTup7rsk8lRFFwM@ju?l4Ws0!ll03BL%mDfl*Rukks#nN&T)Z z^}VAX-?&2|a7S4ddo5m`o`fj?A zfPe__$LF6`qhJu|zwPl-mk)%1Ia#40*3dus)CvxP{acz#-R~p)-D*3ejSciacK>g zm6y{eC-Z$0A#ey9Vg=;`A;DH?1X51V9s#pLF)6!PL%~QH;NR-}Kz>I+5O6*lD>PV6 zNI+1CPe6oEP(n{oL`q0hN<{Jx^q=))Y(P@K0VMbYB`*Pjl2U@=GQgjWms;T(9&=9yCpN$Lh`>e=m=?SWch-eB6>;7TEe`)*~2=V|y!6-Rl!M~{g@%;~FJ1`uK z{O%zQh&2*?|NGAyD9kU)rU8MwxLX)Xh*^k#k5F0@^w_ znv=`O-!ZB4t43Hg`mkeC;}BVC)K}Gcbax~Sti!8DlG`!*h6r>l@dD zM@&biRH9#+H>>pXV8E@39RbpmluSozQ4W_Xqp8%m-dwfG^NC!|_4gc!n~V^)j3VTQ z!@l9kK~zjYhXK~(8mRi+w`U#$q|W35k8fM*0IR&Y9;7`C308?8u1$Wpqq{=7_N>|D z)7?8SR#Ab;p+o7>tSj1|YR_RMPJ$0HUrfjhpKrZPkexiQB&-)&Ius(60tXVS?cnoW{4gR#GGIB)0^66#=ZovBH0d3{o)Sf3H73hK~#U6?G z9dZc3f@Swrx<{j46JFPhs9thoR`^XpB%+rKtd>|Xu(ovS2^Pm#&jlZkfN|mdB z)+ByFyDcU^f->5cOQZK@R7|j(*S))_y5Z-2u@cwAM~Au~W=c@zLEkujf+6ma7z5j2 zBYnzIs$+pu>mS`9Ft0O0ht|7ls&Ji5Z{<%Y5YQ zKH@3sMfv`iajpy2MAX0^+Q-!fRFs3bJhay*SIknTpA96!>m^&tS5QzScMn*`l<2&8 z#JFg4ZojAH!IMOz-THZLbT5X5W#~HT@pZN7QZ@yK6cDPtZJM~Fd^|Z<`2axNaq{)$ zA!d4D{FwobSxVxP@m>#tu)ENDKh1~IjX-#t%y50QDm zWkVI^5UHPElvG_9Xs^~wLhh5N-1b*k!!{NkFPBdKm0AgK9v4dSt9XH_+kU2s0FH8g<6 z`QAX&L5f$C$`xGIvJYHxp_C^$q^{@QqLC(i=}fFR&m3nCL-@|KOUyJGT#>zT`~n)e z&+FB-aK5mFNN@0W^;92su)U(-cu#h9Xj7#2wQ44~alSv+qYi>AQ6)srC3~TrK0ECbPmPLtzm-Q|ppNW=ZKX~H(0w!if zlb!P}=Ys*<{0?<_Q4MeW!yO?v9IfLsg1yxX);aUV(y*~HY5hg{&!g|3$ZpmdY$rC% zrDhHW4T+sIW+f?kTlb`gLIwqJ;8zYAH$S>t^73TYV+?x0gd8Y5XZc>j+)JxNKgS)c z4zT*9`n>mgpA1ae9+U0*)ToK*ov|6=uk=czifkm6bQARXf1*L`QM#AuRQ{&S~M5fg0PsLIDB zN&m}R$3<;lb0f=HIFTq%-9wkcH1_S@8n5LfVeb7NdsoLd*uKL&N1cPj)vu0Stv$DU z@=MQ!!;tUSAb}D3MJB8-9 zRczg~_UH0tSAu#(^cB|L%VxSaC#r4?g(|# zv*GQDRM6Vk`gJsl*oRanM&G&p0&x=JJ#{e&oM3S&w=sbqe%MJvr(D^hD0<3EpH{fg z(Ot(_4G}VmeUZ(Z%%vh6hu@<>F$9&={dTfWIcnhJe!N0&!fUURdyUY5tLHV%tFX2s ztl|o!v8r8fVRtUkv&s}(3HIfwfxk=A`w|GFRLWPokDom#(#-00z3+bkGwIJr7K z_U#OH$fnbWjpZViXk+dC*nr>`HF}5&0G}bq?Wemi%BnFv=tvuJ;(d~HJsoU}NO*Plb=jQX%Q(V&CNRr*7dhX$J z5dJiSp4ILBp;9A=+cq`mWl?Jef$Mq+gsR$H)~!<9Zd4q5IeRVtiQTATN&w#iuPipr z8Z*6!-YbeY#A6kJHZfJACp$d8&%SKa*W3Lq_{ZYEla6$LZXpI8;ex4=9ik*$m{C zkMo>-WRQX%6IiHmyxdmD{kd;Y^{~dtGxv_9&PEV6j{j~(0e7ZD#Irj?Pc)x(M6bVU z_Rwg{mFx;M?C8d=5+a+YoM+KV@^QQ_iW{cV!o|hedWEXgGClC|>#%ruEVr@cP~0aB zpuG}<=Hh2NdzNcNb>?Emv@{`TxP8#$)=EwSqt*-uAII*CjR9TLhaA|)1mroOt=iVt zMOOq}jT4*mxU}BZgRQP{u!2;@~ykpmx-7SiF-?5|R%twlM=kb0FxJDrr>rX{fXfSCQRs2VE< z_ZmHa3Tu!Dt@Tvi(PpCgCiX(34Sx8J-vuWq=<7qJJbHjxA={6vVsLPEcbl3=>lT$^1bRRc8;c+uxJY^s&d}=S^9py2&qp%_t|Up zRbB|dFrKB<<{DPgNHHjxvWR<3D&yn8EF1so%mKATBITUcibTLYeCUBHX6vM4_Zu1o z72#Png)ijS_GZ}>21ZGRM9(x?mdvj*Z)z?qnvtZ7C*^%DVzy}-lA$-fmRa*WFWOl& zI7Qyz#ZK^MRkfUZiw@xm@5d^VL(Sec=~~2%Bd$^6SH{Vqb|diWqdHd)cHLb+^$&oa z&_v@e!bWrYEMI7Jm;<(X)JKInB_(%M%->bgPR{f+myV{+#VH8~Duo+gaJ5K(Uc@-I z<}rt@Z$8J!O@>#zMToViRA7`srh37lj3R>q7Jd}LS$;|G9-5IQ_qWZlRbuJ;tR@cu zCYd+vv}J`AN}uP{2L;%azn%*pVYlL%@3! z&nRlowOgO4PWPO7wwt?c^Ngxpq@A0^oCULtgTqHb;V!geOoo#lGadC@2Kz|dmN>a# zXv@w)ExUKW^MRn(fna(z$p|r}>|I8SedsRJy6Hfg)TRtZzBUH_S3xV@Cb1A5;~T|m zDcaSmPtBZBLKBo<@C~n*G8;W}px?V%hQ|$8=|u*scvHAYPy04e1#U3}ZcS>faZs-f zWY7wC({wTAbuq2>IV9#}dcT#@Z-ZJ!`3gQBd!2#N8zN`)ZX2>^I($KgGKB4LI3_q5 zI-C1GlDWSdf5ekt505<92_MdVi9NGS_$>|`r>M}Ea6MXxb2cZ@c6L^HwP<`ML;1y= z6x*vP+ns$!vxi@K%J51%cK10Ynkc6U^D(K?vcqImo(tRIn_%t3>~kG!_QTu#r)wsI zUV3C>@O6(q^td+T^uopHc)TnHOpVWsO4%Df(eX9Qup2b9u`juX{<^(-yF%yo*({%) zyhl{ND~U;%-LEOvm$G+179r1@sms@!nk(i|=2d!m?WM;w&q#(hwqr${m}m(_jT9UcwC za(wR$J0_$qjX${G>>78Nj-Tw!^TFohvodd&L{aKWTEp`+*({0$b zvvnV>J+S)ILd~hV-O}^BvGx7qUIt%Jn=dNn=PxcdI$;xSHf4AKz`^aG8=arWlVw<0 z0001a%W6dc0C!6D&TT#SlCom!wzGynOU@qMUs_BO`RAq<6vuUa{1N67Iz1 z5x9T%Hv1_=bZG3+0H8-iuSO}ROn5Y%)+!x%q zQ;$n^+n*MVqi;=-+q0wEpTF#lVV(_qi>aIo>5}ci++{v}iqqfc z*0Ylm=j3zoJUb+UC)J}Pl45$w*=F`zXYR@@B4y3KAr5KKQj2haSI%mEnR?oPYPRe9 zQ3Aa2GAD8+bq2+aaITf+>eaS?wSmLq4^Ti<(@S(n zZ~#;I=9O0Z9zZ7%Z{vlW?17MAk3bMt()&!9DG8~-Fea_FUMDa%3MH~#h;Jd{^~g~6 zl<%YvL+M#?DK6E4_U2Lb8Cfj7^T!fpiK7pM#7skWYXU?mT)@X)W~n`Zdft17Cjm{y zljmF@&g{ILFbHD1n@>a5Xf#gJL+!NxJjEjNLUiV2UpcwS8TRn3U|kh+*N(~n`yl=B z*hIbWRU~5ayrpH}B$NQ@WozbDCgw7>)Hhndf41s%ee7kr+0jYF^%=-=k%9%jzz6qM z8aqoBOBVO@*IBlDT}eQ>EPo5U$R5`>~ZtSW95bcRs8TLg|SHC zEk3!U^JH4$^v1-`pEms8r+YgyJ8PVgBgS~|zfDW(IVr(r5A;o|duMpI$ZpZuUQqi@ z*G!$$do*Y{_9L|9Tthj(R=K)YYU9h!)ri%})Ar)zz2U~v!Zi23t$20Reb_W|$)WcH z+qmUst4j3t70;S05hhQ0#)6JRYTXVrT+?eUj&0X_eP$yM<~Z9GNJKXmst`AhPK+(b zJp6iIl*k{s%zl`PY!Yc_CwMG7O$W{YiZdph?Ip`T&G?4W->WBRcrNGK^tgabwUof~ zx^MAm7JCP#Le4cX0YzE-ouu{HQcC#=*^?cw4zrpX*%;dTx*0;Yr+fYtPNfs?&d%KU z>czC9BrE1lPr11bZ=|fDTJFx)UbtzW-zOQE8s1#Q_sOhZ`{?#6&8NXVe^w-JXdLr{ z#KDv2RNk_H$Zy)cg**eVH?K$(QFF8(0)|2to5Rvwx*KXB2AapO8JN^~ug4OB5+x|{ zhWmZ^Nd;ake3{7*Q>VMVQMQrG4d1=mtNua&vqB!XtW&av!gBO#!USfS(L#zz;)916 zWg9D4S@*W?J&6c?osJ!@4X5$~AoeqXBx0t;kmPa!AWy^or>?Hp3WSPAMb*Tr{?u*} zLSk0$XgXxX&YbtHYdgHYB^F9Qk;>OavlS7yezbaAKND+G9d2Y4?X$2{TMjOojyFj* zC?-rfpGp(k{_9^P&@N9}6__(`ZF2Hwlt$`$i3ESD?<)LTB*z8J?GU z+qI^C12vJ$EjdVzyBQH&gT|^ga{tUH1u!Nxf_(9@c@QGT}kH9 zeCGQKPRPZ5Gx3(T^cl=B1IEoaT-?-4HGH*vE%rCEp52yq;I1)vaAvlwjwqEzk4VE^ zd;EJqieD{nc?56qy|+~zpk<|(F((+0Ke&8@<&lu$1$*LCOR=mu zQzpwLQb2a#S@li2H_b6&lbBl9G;R{_65%F3nV6-(rqY(d5Bh)THS{k{t@ORZihkTf z{uowz`PNsxd+$z(f~EhT3zNSc1x0fL5EIiZ06 z45s-TuoJ?`#R&$6yZj$(c8 zTxzH@B-P5Pw(X2-H@V-t*B5DkCdJx>=nZFic5wnu)00WOn#d+T*l|r0>qlpF*e5DY zR1q6#9kYZCsdcxG;2xz<6VkiOO=0%=sV$xV zEsAC;f)PWSQw!75MhhY(ryIx2n99}{Rc>ZB5%K(@+#B)&+JanhaLta_Dek~!N+m5#d z=;AD&=PwMa=mq(qsC(UsYV0t2Tv*j4=+F>`>*V)FGYw|%YTjXtxZbZeybv^pb^hrE zmfnm&@dLAYDFu^wtQIc86_ad62ItOsD)zhBDvy+8KL}hXn||86&v-MXQp9OB0WT?W zh!_j>NQ?~^TP4HaPGZ;ohMv+KshgqJbx^Wh`~hJZ*#JR77uA3``Ajou&*821B2$9I z{;tVJWd-9_58?MmOV_{IEl(}fKXi%-2iNkj_e89I>^>5%78%K=#TGvNh`%u*{t5_T zEwB>tZ~8VRE*k%ty7q!w;^j6|#sd(QPSG%7VSMfZ=>wkA$-$i&S?RhrpVhrWlgqMS zD1_bJN^AQ3G9T|~KCF`if6Nc54x$gz!+RCvn0K+$Yv8-NW)s8LPd+gEa-I#EWuVN^ zVynOWWFnIu`$G?Be|+VjL}pkO-p6RyTy2G!7!N*eXieB4ESlz0qQRry%u1LCY~Tl1naMp$7Z+$NHQk5am!FP5R-8fL(GQE4rT z$9N3r;X95P`V0^icW)w1V5gSl`T3}zNF9@+L1|3pNe2}HXN5t}yW~(o5%2i(`UX1r zQjvQWW?`8VJmK#{355=%7SVGSVJ}WD3^J2-lACj$aesp5yNVH%6|iiOy1yoq%1qN|CiCH672p(L9{FhhpQZmU`V9?;PiiQ)zKVceR}T z>k<=qPS3Wdh;Bib+n8|mDt)7hRmz=3CfzD)nZjbSy9$oY((fN~jhHw!(ZA#v#(c}# z`0Wl$Z4Oy$rHA7%_Yfq>s>1-YB(VBK~(Q% z+19Rn-eI@%Jk8hV92O_NHK>$BQ;N_2SaxewQ5?-Cyj%MQwoqY}1RAR$+zUh59ewyf z*Qq>wJ10J%Nn1JX?EumSo68+v<1tY7;n`t-MNa7Fx^A|)^1f?nO?30Is~KP7=5}XS z&|^%hFYL>YtH&(+ImGWv@&Y+qZuw0Rc#a*_(^S;0y|0K-RdXsHXah1DF=RB_q9}-m zsBso0r4S$yx(1bePsx}!%ig+?rIMk8c{?Gkz2fTA#d*RC?9jcn@-SPhXYuY4Up-CH z=Gm27XL6b2@VO!!M_6(c@s)<&g5u5La>pBAIsm(KS>2~P-o-hMj^SFY_U<#J?VpGV zUJr18MK0FKN^zPZm^A5#lCf?aaAer($(M4#Dej#!Rbp!bg-tbPcn{QzJQMseL`~m) zJz6KC%MEj~GBBk`v|?-s3C%Jzx+nzbh}##G<3^r4g=Y=Yw(vM%R#-doTgTHe7UMRw z=oevA^XGi&pZ?Zo0LTf_Gw}3<`R>_k)i5eC^c?NeXMvtxAPq$^49HVb-{mX%JuNlv zlWw}20>4Guiu4DNAkFyAKt{1a)-f$tU0ffr`F`npzMjN~1)YHFP9J-MGWqwN z>s^i}K1$t`s@9motd*5s3oC>Wy%Qq$7d6&~T<6?6=1l~;>@gQQiAV{SD?P!~sV{ba z@@!7Sn!6N3^OoL2mHW7343Lk96R)3uTrKj$H2wLRNhGG21@B#D%01;yaEol9My9|t zOfoBR2-y#{*XR~!lfOo8w$!OnbK=X;mOR7b`InzbXoFwQvb{oSdBfaNZ-D*(U@ z=A~1wVB7%w^9{*A%g_6ge?|TE8ssn0zPx4m$EC=hsGnQh-z&bC_l{i z`w{A8MfjIg6aJ|_{1f<3C#=6D{l-6^xBivo7wSiH^-DJB{yUfWuT<;L9{&Xfd{4H1 z2`Bx3ll`80{aYT3zv1~k75le5&;Ewz_tfm4c`lQ)Uo!YNJbzBr{+a1A?fND74FBz+ zU#Z)_Ws(0ImS3sdzh!ax8J>}Q( zIsgCx2mrWYLG%v*05BZ2;s5{uH#~Hd{U++;M$v z1;^NaQA^0{{Sop33S9gwsS1?>-_(6yR$H0GI&E^0IoqlbaYnQ$3rr?p+Vt zH@B%RsYMkC9=Q>qrhiE3n$}DwyKD9e2Dqzp*XuCyig?`9t`R(HtsUg?m=zfzr26T~ zsdZ@c-l%_@tTY?J#P{A~ZvV2w;D$%0(0I_S$8z9GUnGZe9N@ZWJtN@#TO(5p{97TG z{r_1dN0?5)O1{Px^^}?U9l;LEXEOXmB-jQVVWk2NH)ENV>k@u@i!TU{wx-11c15-Z97%|ao3;4vUV{BwrKO~#SXfvz5zd$uG5uc%mVRMTaPnAU+` zo^D(aqzk``i;owwAIy0{z^$}pQ zxw*NyHB~PuDVhAIQ`BXqWoKunuTPD^N2{#5y1LY$qRpl^$$hD3=pFz7AZPsTdUm*# zk?~lTJT5-|>O_o_6X_^gR8X*V`O{w5*4ml~{4FglEjIRzFfD=XuV24jtE;2>@kNw2 z3W-Fr#Urf+Q&G#`zq3Hl{vn9z*=7Eeq@+SEjya zo|u?uB&aZLbU#?th8goJ>#UhOE_6jbyd?`k?=^&4C1z#@ZT_wzAffC_6$*C-0023~ zp9>Z;P*zpv2P2x|;^L3E^ok9u^1{OjUvX2N9c_nP;KsQP%1zg2qu9RYF%e}9q| zHtb+A%}$fGCzog2YqtRaFq2-14l5s@bNk0TBZcbubU)s5vl=k=Wy^$MryDV&GK~Ycf>C>mn{h4P=$rcjNpW6%5(&DiT;H`RSz-Y*mBy)M3?=ss)FX5-9BK?EdyE__X(Uu7gab#dW@Yy3r$D_+2}B zPuPT`XgZ3&Wk+tLP+jJD?&jZ41)stPq(4VRWl9AcmYX%l#mCdg(4;FS z!9Zv{MlRlG+{853yUe!r_xC6BTX?&7u)S!gwJe{nDwu3?n^xvryCWKNs*42CbYdU zgQR!g(2#ci&>%U!$!{WI7ujL9*47+}DxXSU7N!&o=m)%0%Ci;=sCAibLxd8>&`XYu zjEszr*GEQn?96v0^B7qP)27D7h-ss$?mI!eCMaBZCs9lC{2+bknGX`Ywtd9`o>VZv zy9(b(n%hp9*x8E|A}ARc7y?(aTTEO1^(hou&9@g9^}MlO^70>$Nt%y$d%kvYl8Q+f1&ZShlETcL{qc5g0S|GO4rNihunREmM#{?fqO&;0Qwu(

&V6-M_`=e_!b!VE5%UQZ&;nmysQX}6KNIlT%O)RLCmCWR+e^!jx;lnA zXHLS3uhi1D9V%?y0RI30?=yaHqY1ArwnHk+nh!nUZ#n}5MvBGi#!cN;dzYI`Ho|K| zoK!+PBGL-WLp(;Ke+(Q|I4!VZCNBM($JuYu6IX2Iyq5HMDHDPrh4*DEergdkJ@(u_ z#k9SfC38A8|Jj*U15OM(mu>C)rTn%&fdAY^S7{)UnXz_FEI8;4({Z7nH!K_LZI!&# zfs%B1ryD|xc3fodKI4HLcZS$n_`TU!`+|e{FtdA_rt2f66`l4Lk^9RiT?m@jq^@?q z#3ENNtSgF+YL?)it3@K0RvZwEBT^e}XD{8YcUfSokU9Ml(B7X5Weap~G4S2tKM@oA zIac@7xH%=yK&Efmal3T8XQ-yabH?BQk5CW9B6_uIk~)Xyg_+1~HF|Lla}v_f(xjp$ z(`ZuTGmf2{9L?W``Pod5t<)VJ@fIH07(vHmE{_*BD&TbkXoC`+g4_3KS3M=75dZ+- zC!qop2gffI%IWg_MAL=p`{Kj&erog6$}h5<#FwoGkDXl5jYLQpXQ}O>t$bT^E?M%x zDbjZWe#iYBZ|SuM#{zdxzJg>uOASYKJyr_F+PGvr_aNm1pH)Ojz=ppVIbKM}XMp%t zrxU<)#$shz3)s~FHiQN1=e(Sfp?uYxd=4Uw#LyP?*)AKFnTSZvt9Df{&pamI`p3VK zb{hm|)G&HU?-Vt*nu)-jIoW`$BgzO?Ny&hvo(8yovL^acR%nJnwqDQ-i|X>zpcZMT6%5N=JnS3O3vP9i{JsqJ=& zr@I&t*it1%GuBg@FQnDJc=+VGt(lt09Wax`sxYxE`K>UWT-U*O^0MUeVRBCluOu7- zcNkN)>94H1+Uen}h7>BCTmEUIE7|ng_NKM?FKFjJAdnTbo9-pgkh+`^$V`qf3#_%a zwY5Dv+)~g!*x7OQ_O4s;%T7%6!mXpr%6Ona6Fm_ZOjF_tdsbG~lP6EWOc~GJ@_;*NQeiZ#% z37>3_8IE;2Tv>Ll6Keie1k>VAtdW}*x>{+AJ@{s;2=}~sl4{~hmneH>@qPWDCkJK1 zZ)GdgxemNc3|d+}rox1kpJAd+Y5ca=x(P|B_#&gCPd4@+9>!CSH-rT@6>;>D^}!6MvD7_XZ%f>qUj`ZC805ihq*Pk^eeMvx&b%D6J2lqq3_aylVkjGde2Pa~ z1vRynTEK(P4!4qdjC7I~LM45$36>x&O19E16mO&HLHfvO@Y|W!NBm9F`)aRO-ofj! zlsQ4a`d3`4n{xUcLZ>3;gN(&WsP@KOcx5t1U>Q32lX=mjN7s>Y^KY#xD=bt{? zeX-fVk=6j8E=9gE{Dp99@^EVkesMVExo~3?PqwZ1Uu%!l zovroYEuAb}RdAZR5}qF&>p!)EGtx_VJ`X&u%!K$+j*}%E! z)ed!%sV13DvJqY1x^#hsWHB~Th`0*5mx%f4_Mgj3u4ar0{tmP_(V0$VWn~2p4JDAp z`_z~wFPcYxIOX-l;@?0<#sE)yi&ooT`Qbblc@|f=uFAV8&+U zrsALE`5ruY@QIAkSumAW1TRf1C;Z*)hjY;BT9JT&00RTVPr@JZzCF7LG{k^T z)UjBP%VoM@eto^i_g5zt(|mQj5YrJ(MtAo%BO~K=r_GP3sFIVCypOPE#y4JkDSFKK z_=WE?Ny(|9q1f1Ov8$`AGpzxtaRDAd_lX2&Il?=&(*o*<-?5%_+IXX;NC_BoEW^bRX^L* z(BSLmH+1c%a*$*h2UZ52xX%Q!NNQ_qqte9;xDv<9&GvV8a-QIO)lz%`OTK^@RLsB} z#uK>>+}A!tW=MGTSPOp1E7mFbd*4c+*PLhBIX~H7=!(JzAG)IGXaF?Is;VSJL@DAP zwil;3%=EPV^#v}0Uh|1GwUqzCmxt^u%6Vsk?(^+obxu=Fjg1Nl3T}wMMk1O|q@PjW zy>a8lHvCE&lN`$rKNl1iPd(zfo{9;*JiAbKjf~%wZ(eQBv<4hup?X|vZIPp;`jC*T z%Zipg;$((vOBy}*A}|mFbD3>ZP3DvGTBn%!5SbwzBq1z((9IZP+Uk$nACS?!zCq>O zD+9(|}^&t$%^^AdwUW-Sknkf-p7w0 z_at(&E5}t-RHzg*!7VGyTfMg?^|fT#+1W!8-{3ha1$#IgN_VigR~3S$)N@@MF34Ak z>9^SFilW19j1TBmDnwAO^k?>3?6e-uqzlMYLD>pHU*1`rh0Cbp zaqs>ER^>dBmv?^k_iL!A2+~H?{?n;mF+SzAQ}4MpEbz9gp|P>Evr|9^@IG#+@=XVw zn6p}{pv}SR5FX3}=@_--glW|q-IrEx0st@X(22WS>*~6AA|yY{C{KR<-4&4w*?To6kTDF{hv=kC+e7U z=STd)`ZWLmv_9*2;SkHHbi%vT-x3oG#y8^Q;-)beU0vOc(UO{gBkUy1!Oq6UYkMYW zbubsx>?4+r%2$jkHETXB*3OsLHm$WEDo{yeR>S8{TD6q{qvbTlYa_?=D`ID(Sb-PQGXvyaOq_z{=h@mBrp`T6-C#p4&gu7-xc zb7VvJC`@Z?)vc`;(?lE`Df@VF8x`;wi%R8qHgR$B(A)QVbX|wPD-(z1<$%RpX39+J zogE!FF9w0I5 z%1CCD&$jvN*S}EdV)|Ts2a3BoT!~MfJZbjX=Bq*iOP4(z9UXzdBqkyx5_xr=o{(TI znm#f->>gqzOe-WPcuN)^WdHT+8Eq7p$=cfbdtsri9lp>-buBJhUq{^gY&~>z;?SU0 zxFyzQpGr+tRhNU}gv8d)j-8!79ko0N@L#wxM4WPy%Ha!%Qfq+!0fI223 ziOlF&xhfS+%~_a(0cQZX)@~qcW4uB&&brEw+KS>R*Lr)V6^TSOag&1bV$ep93tKDu!1#OZz(jXG~9Yv0w_4UDaMn$$bneAX_@3c!jh$6397 z%dKCkCuqXMYQV^2+Tc1?W`r))m-Ij27T~ar>9r-@dmu)b7zb& zhJh5gwaQvrS~f-HAKpSBk(?YHtB{H|tM6K6W94QhT-(VyC7xbhOIqLuDeqVVV^uj% zR)4w$Yfl)9a=_tciFSThThN)x zrpI5Xj!{3{#UsVS!onkBg14N^*+GXBku*Z*=jZ)dQmWT(@{dd8bLmQBXdZ|3(X_`s zTH)j4g%}!D8l?I?mCc)S*8yM6*Im1agSC+(EJo6IXYM|;;kKPXIdumm10)1 zL)zYUM+@J=KZdnz`R<1yd(%2cBY%H?6&2!q4(9!3lu5Onw1OE+ zdT;)2a9iNiE&NxM`Tj}J8^kvJ>T*bl(P_3Vv!3@?uM%Sr1ugCR>S}`};vXL$pMUcR zy$~`}Q`3x$4C7jR#4$1qX-!Nc=4 z9V5dyz9J9^+Zw;k-&Ox65j1uYvCK*{ek=5eD(HF_i|U&+C#(4}c+9~zZ`V0v(yqy? zkEkrEvp<~?_{$$-=Is}E#5)P!y?aMWN_smqSEoSbUu;2*-9Vio&rL$o@Az?W_&JQ1 zw|Z>=Tm5mL$=dCU#>#TPXMYlNY3@Oo|>1V58G&$eA`)(r4jw6&PG z`e%goyaoc3fDrTsP9Fj+_&bLVhYXB?R~JV&2}yY@+Rjh*S7>-?CSVQ*K;YO=z7jn> zJZ#m`6f$^4C>0H(kwZL%o25CG{_*@ zC7_Wz-70&bR>7xhMadSyCn&MmgTq5UNsD-G7zi!uG`TrZ(+z_49GO2mi72{R$xKR0 z`iM*KdGL7y{r1~j)k4EDz1+Skm5=eP|JDNhn`LNceOt5q@CDybo}ltcRmlehXWo$t znX?6|$xoj?)zQ^WMQSb~W|!+2+`FWwYc}5!OR2U~*x^ zkIq5$t5UlWx?dV!#Rjj!)*oT126w`)%A~VFu-z#Ym~oq6z&2yy=mKM%(`7%I53h|C z0lkE0u|5Pi8@L~ZwEnZZxXX4Gx*{Gk^^-6LX;t;{)2Ft>NeBF=o06GcOX&pMF{~83 zUkaM`DxH)JU>@9aHD_OG16i8M53=-SLcx0}`IBgma_PTUMWaF^U=Zmi#Afy&2Qlh7Q zNysRxW$$glB`tTXJ%=a#xLI2!x9EDe(Lh$J#A-);NYU=q`QaE&7t+KU1{ZM4F4%22 z;m-*08O}PcCTH55s^3nw2=+T!O3uv8eD&%T^1iP%n{*|Kr1z%%U=AYpRrvBiwnek| zR^IbSGm|5YqT8|vuTT&HjQZKO7FdDYJ#YEr?Su0tM-8bSe&#ixR%TrSS@Q2?+!k## zV;mem;L9HQW9GfpULGU30;keC68P@;O~vIeySR(7}W-(l78>0}>)pBl?{>dxtuA#s0Rr|QVH%K4u zy$Z1~8{k~^+lflV$c1Cok*$6MOW85oS8`{RxQ&mbUp}iu8A6fZdLBQ!40Svo^!%S$8`szy%5ivFIl<$jTv8u&)~9v0)eS`};&5y1oz#o-z%&*j zvZ}(%kOwlOe*`go@JEQp^&$PeC=ekKs#A0FgFxxQmAP=zlq8#{GX=#Q6}g0?e!}ht z?ja5$@Y2l9qd{8~_^{`Y?f+n|l&Vh*tIo<$nBLYC2rp=?c&gGb=ExvuTC{RwEI?=C zxup?LQgLzdmxt_>ve8=0cJ8u-V5R4y%aTnKFTAN*tS>{J@r4aY?{5B_myITH!aO*_ z)DBop@?C;J1E))w`YKR6X!HUQN|UmWPN*nfk-P_N(sRaKb*doYimXdgzF%pxKVi&^ zt(v@q(3{i;>&O1xw$Nh>?}?uL7PIs|#cRi{e%VbE5{kc#KfO@qc0W9uAQZCeZwWl9&d#>bexxS3Hx$Vn z1(!H9dzH!RJlltCChZRQ#BuDr^bI!ov*^^F)POm|Zh7akZ`#*Pa$lh&z36ouE_*V? zK1Gu1k)%@9Z&FS2fi{zZ7q`yoXe&L(>TcJVIG((#?LEANj#DphN+0R4axQNmGH(x* zdRPKqv1_mWe-dfylF~aR@Bat7%$8yjZ=E*kpEHC-w}GFEMWg)R2B02=w>g$K!-8L*jTZ_(Zz(QeBI=rL zi%M^~TxG}Jkqoa(+d=M{_i{aIc@T4S($aP0(sr67Md65!wBND{sBm<$GV0{N6gul6 zG11g4t7xSY&s~@-Qz1Kf>DHnt??5$z{`@}>fQ<&gKHL3?8oTaD8eJCj`e?~Wp?Z4w zNpECiNNdSP_Tx8ui^vZjKD_#LS0EkLx2TkkRGA|DXFit z`jt_5TbqL;WT54EOI&~d5eh3q`n74!+^hwDdTHIB&cBE}(y722RqX;#$_MF66dTG%cOpcC5?+7aLpQt)z4`=;CB0J3FwGUdn&eHrjRb zcNHR(P|SWX=OY3g_vPDp{M62mVyjQHxZL%W+l6Q9S6C)bRnL+*I{al8O zE902Bwf<;i+Wfm)_`ul3I#L6@19Jg#EzisI(8 z{ZkY)Lo#g4QPRuCM3$U5(DISqhoIY{yIRCx&5dLe&?juGmH$W=3i{^NMu@P>25g*t ztoq!gH`pe8X<+qM81&x7{>yaFzzfcLhABy)JNd2Lo(SeNR9fZ2Ucx7wejbOtL)&qn z0*pyQzih3fabL&5B9TerM1R~)o|Ve~F_nU>ZoX3TOC@dc3@$>y^tPzpmTguS&XdKl zeFls)Xu06QEkym+H_G_%?MOjyM_}!^m&;Tg>RK1|Dx9>c$^D&h+T7e+(Al9>=ka^w z)hZrzFMZg1fhBI>obrj4&h=<8Q^VNSgS?6A?XOkv3hWw6qGlo^A;EKJPFB+NzPPw} zquu82?yh%3K)o~O!DX=1;X5cQM#DwPa01uCk zCAvknHa46T#I}3+C~FhKf5OA1M``J#^$bu1ys06#1?Jno{8YJccri!LZo|sDyt=-D z_VZS@K&bx?5yLzs0*eG`!fCHEZb;s$rLXe5NSTAfr7kSsUV+QFfo215@>{Z_Xh);n znXcJ59$b&id7}}wCjb5W_i=uyD|3iYcFnB7y~xWO@QZ~QnP_@RU};t_WgWl?D(w(< zSTTCOo%TyIH2jQiAkaf=#7|vnB|O-*oP`K1viqygppdn#4jaLcxTiMu4}< zt=0okr^#BI-lWRP%G_7sly8i-gcu!-?pN94`lNL)lXamZzi4U{MUJ={1Wv!6PA_w0 zNDOde=nQj4nSLEpS^TJ z^}G5?qcbEQKDoN13p)PH@>gxFx&x=VDwlF&aC$DI=JTO_$N@DNJ77vft{x<;qTTz=1g`!;C}=Bu>X*w?|?-~A+1 z=(84V-R+_)DJc=M8#x>?7tnsj6i1nPhgz)qWK+oIOJsoO|B$pzuR10 zq!qC8N~4}q>wzti4R)i{rU`Y(L~fZ= zB~z(G21@_gtB{8px7nXC?^bX}_i@(8Gp^lNDDm=05R4auf^#Tt=~_9)HL}>{10h?Z zB_mB<8!En!4mQSJE>3YLx}o2{e>ZRSSCE&Fq?bILa)H~h$xJd#N|V3X%mw0H&F=aA zTwxQf$Lei_-5&mkmg$16FYg}>si?p!mzo36O2UHY8~3&5C$JY^L?+czajLxp1C1*I zu6p)Cv&) zP+`6`l;176-7-@9ZiGh2_WX3C!e*J%^@fA#+Qsw_|B+;c%Yp5m0}I%2hbh| z6L?u`-c*W!3E1GMJjcJ`t$dqJaW$O%UA4?oRkNci1kPIMo}x%*}b4?;lp92=#{ykxY3=XYSYqN{toi0J*gE> z`-|)fXn5uBS8zh0P(xgl|Cr`<-QLRc_yiA+?v#GaN`{#9*m^*pR4t|N?7mdg(72P? z?qRp}hqGam=~t`sV)9*m<>XZqz6r`*F+EjrUT&_};gv&}82I|6 zNECL>3seMFu5B`=QaX6cjgsw$lbuZ39QUge2pLz%-sw{18PPYae{rK?%Vo(7rGju!ITdJz6BBA1QoN4j< zVms)ao1^3yW*6~cpbKhIw<+J)hAEW>Juf~if2ai;*&Jvxy_}0ekGnJMQNP(gq1GJ! z>U}wdo^hP2+nR3la2PL#8dPK{=5r2DuJ>SO9YgGO!sm8vwe{9R{exPb$+L50N~kfk zz4L^R1#q7xRLoYX-s>KrRIW^6HH$AV9XP9%xHw~^k1j$HLoM6!;lbQjUJ{stwGodBk;)>ow|g@Ei}ilo zuy$Yxwd~;Sda91ITIq)Y>}W_wICoPL^Y1#7#@_vGhkKi@PM59Lv>6Q2&hN+bu=ncx zllNVAPn$=Y+Ag!_Z&JEUJ>$wD8c(>E+laO$+Hu3`gIax+4_3*H$9$zs)LMrv*%J}DMRW-?8nAXL`rI}t! zn?gZ*@d@N^RSIw8Rcw$O@UbG?pM>sjjn$m;L4$*6#Po6yK zBc)*=id?b#ctA>s4 zHc4H&7M~6eS)kAR`Q^1EqoR1Lcqg@uZL19BwLLvO9j6!Ne1%;6U&Y=heZ zGM>Goqa$7TU7ntM3y1Ea)Ja5Lp~M{Y=J<@224HV-ZuV`zkJR!YQ9|C$55vt1?V|jdP!LU{@2*w4sMCS}#nt7JOdIF* zlk}t&kux?lHyf1b*z7GLJuMX5j{ig~E?Upj;AahBqx+?cut+m|ruLog)#U{~eGCX$ zYm3yYFmE-eFuzGix;Xq-QWL6z)f)uC4zZZCngMCae@UYxeaaOgD8otVPfs^0I@;U+ zrP`8Z^~Zf+Q8tFwIgFPdm??He(+8}Na<*AL#CO_L{opHEf0k6h$=(voVH{Yjg%}u! zY3uzQ6Qc<=hS~OKC|@U*=lR+1_ z@xaAvf+WF)^**EZbuokjLqb9zXuO}3n!1L?VpmsFzJ0S4O~+s`i7GZaI&mz@SS&V< zg_V_+lY*FxEM{|a^ZR!eDA3^MR?I$QiPK z@bIA%rJ9n3z8#8~n83@VG-X2(Okb^ZbmBO^VzF31Vm3B532||nyPwWT*jQM;7Zo)( zH?MHw2MsgEU@%UU2Rl2@Xrq*sm5-=AJv>G>a9_TB@gt_admCn)nUZ1;GsgJ`!GkZb z(~bE+2$J-xJeKaIm6eq}!B>4_W7=&|d@=&hLg=)RN&e7t&}gw#z~L=ILb|9fAk


$4bTKx9;%$jPgI={Xk2szuTkEWNz6Y!Vdd$huaRaOc$wx~Ud z$CBP<5Xi>C+K7Vo`C`209+ju3XN&8+ToyPrHFZGx%rOhx8gNu+41L=bS!LupkR>%z zq$%S%_v3;fC@_%EtSJF*IolRARqrAbcGyYbEWd00Lz0`oY0=g)WZ&Yp za69}#LLafat1E~8?gyQcGOb)WfB&YUqN32y(B|f5GzfQa;OXw}?%^Rs8^yrD;NNOq zG_ut8wOpqpBQp~Xf@u`(9~_K=VE(P<5VXI)e<>OiieMrFBP@UQ^z`Uz6^%U78$=?J zLqh@~h-s?xeTvZy91@8ncr?0!V_;x7A(43g+}GdV93CvCiBCx6w0}m8r*AVe9}z2D zf@!0=Fc_&2*?43EJO=`SAg#HIbK>K5FTq(^Stczs#^oj{IY7 zt#B7nLC5Yww+p5TUHfiiZ>g8+sBW^($>eLt{ohYo%`L2^9;A)|-an}M&)e(Jy&ukI z4X*R&C;JCCI#C@R`N0>bOFfC)A9PRg8EM(lK|6DZT6$kcE@M2>pAit^%Lrit?a@bl#aR!jkFg|TgeLGM*VF~RK3zd4+x2c|)lwkTSdF{Z`OLz{xe0H2o0u95L9 zRqa(c>0i>@vR*|w(6Y*~KSTVjXu47)H6o|y*X}~MI$OM4?&>6r`)`tGv%boo&`?6M zG?Z@`*#-QxZ}C&bFI>&;ED9-=x7Z!HHuqrcIFU~#gT!# zom6=oO-)U=Z`~TiCk+EC?Fybq8^S<|a=C*WIDG12airsPgLa9Y_v+vW{5t}?&*Z*$ zts_ZPv1#_+qSl}hpp8oAx2Q9Q1{(b<&vc@jaBXdEXlN*o#f_4SA0NpvhH@pADnwBJ z^#C?AHWxxOC4E%lz5^lRB#FtNKNArWhTCQNDVFFB{~d})bqpC0YP>WzH(0FA+%IP% zANL)9PA@Lrr4{~+mr?-UU+Dh2;5qme%PcM~{_4}+H#|0r2Wuk}6BBtHduHi)6DE?q zw$r)nnn5h4Stv=c+NzWIukt+<@$%o2m$UWIN8G?-J+6?D5HT%kD*JzH0mQ_*bQIgp zu#yn;B+S78@3y`FBWm^Yvn?u3K~WJeI{bCE9y&dszBvY^yUEGCySp25c~Zop%&Zj6 zqw5nm)8aQjKcAYK+INEjQdU;Bj)u5QR2P^wy5r|Tmi!Qlp`)VmS^O1SS^2E#MndQD zTz{tI?(Qy_spWJXa`$^=nMu6{`K?S10|*c*=+)gFMaNDA210B|a|~_l>=-4z9T8vx zkLAAHYn2F>U^H3V<*9=n)zQQ{1d`LxTmys6+2IzA0?n7t zpIu#Di?#DVDdt}f8o)&59!2IpAQuV-kAg($7l~Ywb9IM*G((&q1Pr z`5Ph|7A`I>X69Gqw{DZ-U+(MuTln|RR)0p(i4lW;7!_}p8CJC;5Kn}K^(Ykn z0?Xc0ID~Ah%qahQu~S8Kx}P4rtC@J=xvKTopqjbn_=i|q4CVhFB_?8x0>1@N8bggml$4ZiYbqXMF%DIRr??HJzX{CI z)|8BkSz(7*OnPkm|BevfIK?{&1q1{d?Q%m2$!r&`7bE!F$Q6b#7|g&x%wOpey4=j9 zKnIO?8~~bf8oRRc^0(}A-D}+z6bp1F%FQINw@6&Q@9v+UKYxPIr9=2F!YTc`#ZSmC zw>my6i{a5DR^{Q(_nEJAB>r1Ya{4iol$4Z&L|Tp3#6+V<5sUJFLWZ@9=TtOHJ z%@w7nTVXC$pria(Jyu8|C_&=o>S{mTP-T`GmX=2aD;>LNUW}VC9-BBymxk|@u4Oa6 zE>S89M;GhC);_*PvNo}ksm6V0R*JT^vm>JwE*`BY5O~`qFE4LxXO}!C={xH<&{S=+ zHFQh$PFd_9Q>&zAnU;}ij1s#}LEfwwC+;}hDILDwVHSa3h2)G02S)Z98qxGY``Oko z74U!QaAJ9vf66oH)PWX?F0Znu&)3dU{ChR&v*_~pky3v4MVi_D{r!{*Rhrq-1;M<$ zhLx7bJM$8mV}<>-r~DuC8`B`clIXZ}fAf8_cu>$?vJ(6A|{gD{tz2Pnm+F=6q($XJa7AWXebP zhPvAQX0r$JQ_l>B-8G}+Nm>4Rn5oXxkZc>hD&BTi5?FFjl*{X3Ycb=%RjUYk^-&$Fv$wgbffLRv1{0wK5_O|#vC|!S)ez=Qu+Ln3trVrB^ zaQE}cfgX%pj(Wc>&}Pr<^0GC6@PPKk7Alhp<&|0gr)R?4b$NtlBpo0*H6*-tslmTAaIwi{d9GLa#9;pgGrQ=CR)C}d0FON3+U)5dpTa#_y z$D2ps76lAIS_J71>2ZSsj+B-TDK|=LNGnVf1ax#eknVPjfr5Z^j2bYyVRVjqj}71F zd5`0L|AF`V={mM+`<~~w_W9O1^l7U+!#1uVY~GN7T%5=@<}u`w7EY&!I16*e84XRX zaM2@gf3Tt7)cy;%C?1)#h9|7Ir`s_euh8N#!J8)+rNJ?-`nAhYxPFEvLo!{7&*w<$ zfW^v-_3o)&KAUbjWs0tx{plvL5i`LKQ^StNs3qf(Z&ORp8_s9Hnz-T88-6cGhO^-( zrDoR`NpB%|2RPV#Mct3WmF(9Y+Bp$T8Hd>KRGq7|=yuIa$Z7AJKxS~%V8F$CwFW9< z7geu`=JmtuP9nL_B!Z0xX}Dh=PNn1oBe$@Q=r#bt_iS0eG9y_0a!UiSdPEf9W0&!7 zJnFu_$6DsgAMbKUvnq`5H%&C9aL6CegkHOLt;(SX6!!GVNTE6v&MVMy_<-K4D{Aaq;TW+RSPHF!)hjm)l*YFg1EOLo^&wOfBqI?q&y5Vn0x!SdFCPI z?4;+@5P%@^2ah}_e23M$EYq`uRc&~DoF6r;3=1pu|Mh|m#Thm~eI_4el_o4KfInhC zdR?~fnfPc{fp<3b3tea|&v=5zk4JNR11#0bAGB>=EA3^ByU(=(P-O?q2^#+TeFsUa zZuyG0R;3ry9Uo7h_7~$4`?M_aufM`8nnNk+g%*~V`6KS!z3W*uf`DvIU7Vj%vP&>( z>C0)*sub|6Ne7+zIy*aC2s`~g`{xc-qs>wEC`CsF%8kil>ibMBh+W2KW63n(AQE_D ze_78_(qeUM_cQ7jv1C}(} z4{3dp#!V{wL&7-yq< ztypZj)eoYCq)aR=ErWs@Y38_m;7#n)Vgj98!(saktFbyIlP>q`3d1caZ1~2I8;eI$ z0l^)`uy~mMqt5t=Bm2W{rMOs^iuM5)X^FA zqJ$CGNm>zb;=vyF(|Y^h0A;d1Spzoiq1M*c*1|m%6c9M;xdVY5U7Vj54X>S_9zoVe za4Q4ZbdjwiEwE~`bae`LgG%)r$rVoauy1+=VJf$C2PqS2Lle>QXcL$1L1PCxrjoR} zk6fX1kVwDRk?S-10YPGOUpfF=ok6s=B8W24p~zO zaroc0l9u1-8H_LynK}l&5K`P`zC*h`*t|c_aum1@nB8%eWshs#=bocmU&_geIT``B znq}hwuW^b?O=}(T&HLP}Rd{vqbtzwjdh4532lgT5q)5+7;Tn8u-Ony;#opMh3D$MX zcF01?H(znBhP85Ra!$fE^g+(bLH8e}R?{1Jo zTC9@Dy@MGg4E<059v-K?rJgewDGA9BE%2L^3!2#2ST{d<{Hbg;!#(fzlQ<~l5q9@z zyO)tYEN53wDMz21O()&1F<=G#iz6rg5v`Hi2x`ap20Le6<6S@cQme}O2HgSxa<=00 zP8nOlXY;KzulCkq4RN8Au<|(OQ@h?`>PG&egDAI?ov83hRjP(XvO(6IjqTIRx=Nhq zmi*DUTy~7Y<^KBs{g=!&g@uLP-Q81~t_5pM}3)d$H`nuE`BB^DH*FouDyYJoR#)X`tjVsK7$*dy>!+ z-SiCZDA*}_)K&=KKd>?0Ye<}m+j*;1-(Of*_UMy zfCE>0V59e0I3>sK($w9Vt>sZghivrk@(B>u=lRLYajAOtCvro<$R<6%6`Tw|DkDR& zw4@DjiFS)VyMS_!q=Umq*cBA8wiWpXg||6WtJ98WHZWC(pBabNvL>|5%OA{5QvOsR z{p+t5x>X0^Wcm%$OBK@Spu1#DiP1PoSC=1h!E?Bp6+ij?LxDPbILhyUI@zB~x*@WK zjRlmBoS9M7i^yc26#jb2F-;w`c+hVKI@+oHf42vUbdXQ^gK%$yo>ah*x!Q? zrw0G=bb7-$``R`5S6dVlA&%|x00KX1=go&;BFoFm_xJZ%75tdxeYd$veKsc%ZVfxC z=!Q3NE+IrOr37PChaG56yj1jtV{N`&JWUop`~(sscewj@VYWB;b$r_fb$Ha|#n4-C z_EK-ux7`)~C!2D6gQa1&U2h!((B!!9b^jEG05KP7nJ$X;s!@zJ{ztB^mV|-zp5dV~ zz%xzFAyCb=YuD_^5AEBdSyZz{`S=R2_dJS^n7;_m4t=L}bb55&p17>lY+fz==s`o`i7Ni1P?kRaMm^f8&{vk&%f> zGL3C#9IpZC=qU+E{A@8X+)oJ(l3W%f;*U&*kEilJfNmZWI?E0|_rs{$rn;mB zE9L~vaX?0qkv-jaA1i`9gU_w?Yg8wsNsqGuryJrx7&9~TU!wS_vG zdUu_&))lMH8?wZ}CJ`@Gy=%9N)M!N6Ar7CQ?nSD+`u#=11qcK(MmhWlxd!7DC7g%T zztWqjXr-s;u`{Qleodn9_^S=_dCu;_E`|e-_ue^V+1>8Upu0c`#Qtcq~chUTA$^$x7kaa_6dB= zN$0blC%76;^?dtSZ8GgLkA0n%XLl|oN1RIorejfVF%v!~>V?+wsFjS~mOH)XC!>Q{ zPd~h3b=3=sms5#lnvGr4O^~e+%g{U&VsCC(<5p?(LMKUalo782Bb)f|I{!WZDMyAC zen}*=-}`z5P4l=D(+7+*z-#5Xx3{;Z=FKYN^y&v{#*twmuchwfTa|A+Io2ujit&f1 zcTcA_E7n`{9-lck#9egHXZkl*uZI`Uliz(ub-CUV#~j=5t8?mWsTi*9si%|P^=WIl z|5fie%ilJZoqYuSEdxk6#13p7mV9hD9^ZdM-u0*^)I4B@KaswvcT&0voY=oIq0OB) zvOvC=46gfVgWmE&+zE4%{e&o+2v*eS6TiX!v}1OGW%olqpf`6i4nys>9ppVR+Y(Ow zO(ECfa7KUi5;-=r_H1PH8O7e65moS+=9ux`{MG_Ny$6swMaLVmbOrsB&o}X$)uZ^10fy!o1$<~9$JSqzh@_&&c zruT)2I~q;XpN{-;|GjrgN}xieQaif$bf^8R1yEA)Bx1L;iF|x~%q%R)^@L4XYiR8Y3;$|w2TP=sS|HaB@b58hqlcxEr$Tk0lCn+# z@zfhsLjEV`x2CPcitKV03_gk>dZkjk{*B+X@U{hf=qY_?I_2MF!l3~0(~l&DzbpHX>y=Tl7p=vQx%ukiFIQn?Au+LBtx}|%` zrQ+l7-PeW+QoyR(nE-6XOEm|AGbWK>(%M;qrlqB2Wj%~+6$`}gzaM`u3O-2L(x9~w z8bhstU-o?g6lz?L*G>7pzFpanK8dn46;{=Cgnl z8XXlnOWpVxWaYGCbia%{p68MGRMTJ@_j}05MeVK&nF{tbz<#zlu?k+H-B z`bc(^LN%T}a~cyGa@M{11?q`xxu~NKPBt+43srz_m zJ~lQM*U*qVsnepCH+5;)`7dD%7gKeTpk%Ns{D1!b*J6eT2lb4Nja77OU9pVJ%-utH zg(%gRV#z5ppPq<|gNE|4NC^4$>n>9b$siJv2VpBi1?ZE#8cF^3HirY?Wm35C(lqOQWNs9rOsf>VNjo)vlJ`$Dxly<>*c0LdmI(3=M%WiJ&vz zLSinvM+aSx4-p#D7BsDXR$^4=Ha*qa3I!1aK=|xjXjs_4>Yw{pze01V=r*^s@V0ut z5TIj!T4YqhbDh!P%^L(wGa4OBKnycnAk&>|7WoRDU0q1uoh+J%TwL!#=HW=Bzmk%Y zipuqzkXxGRvhfeEo>ksa3L;#MSv)>iD5FlJe;-P&z17#=SI7jcp)isAHxIGUPEdhYaEfbJTQw_H z>$JR-#O_D$Cq_qAmG0P~T3E4RJoES}zPIoeOIKar8XE)u)C3GRQfs&O37MhMohDLN zH$`h6=Y!##f0Iv_`;UXe7RILPqDt5Qlfv-Xq>p9U02>+_ zIymGGIHgH~>Ck_ZkdSEg7n@XNWoL)qWKiY}Y04@v4}6Y>nhGQ=xnDMHEUa>lo_&LO z=Hn5Qb}n$lQY&oatN!2YVd_Q&)nw_MVV@27;>&ps%ga_*SLq^E66^ud*GNeEC3@0i zVjq$OTj(S3Uvnu93k*0^Kb4o)Bw!N|eEk*q;9_D_=W zsq{V@V>S|ud0MF>%n@r>Aw>WWciGs>A^yMNb-xiKbT@1&_gEDC_MJ>jk~x9;xtcaY zL^T)Z;#HrYw#|%>UtC`14*T8JwYR@tz5b4|N|E`o$EiN~2=x0%RXIbFxMS~JYovm_ zyoaafze#^AqP}zYt|4E1US1x`kz7y<1S+I?_#YrV!Z{auus*5*drA+oxFG(U z@-Z?pn~}Ko2FZ&aN+=Y{%F3$z0p)*mxQY&cVk=B1Xu7}MLcM-~hr#aru{N`LtH5oH zVKRdPIL@{N*wLvX0^_6 z${INg2GiQw8j+=$2}r+k4I2GP#C9@W-P;!VSd)6M0#0CwS>5JX1qUHMAPGtMDmou( z-<1G_Ei5gm(u1ss-d&7Zi%^RQNyrwR4_#QWGf5y63T?_ca&mGo7)(Uguhv%Gt39$a z3Iccp15N?|zf0|(Xk^?y}jCX<6DCFKu;P7iTK zdIeWZsHTbXIrur4qfuk(Qf7&=Gg%TDql|2=bnIiz9=OlKqIJcGMW;03&$KF-Dn}h} zZ%K>%KnxO6HsBP;`ReR==MSmqHUxfV=4Ys(p&^V@D?>i{rM24J{JbQi7Sac2Zf^dE zAam4RHcn2?{Nc4j+yojrp4gKrmD;oP;RD4Vma5PHB2RtnqId6+ynGs|wc76Pu8?H| zPnhq_Tk=2O!4pNpX8zrsT~X0WH!dmZK2->dNrf$xrWu1lXe0{#Sx}s+uNR?-?FkEii@LdEB?dcSI#VK z28M>iUhqkTwbkI@pa5N@K-ZJ^H{n-$Jvb%{c&4LM_d}g$g8$(kB4U`$fscfy_Is^Af3k~+e6FAPV&9eUN+RVg zDY@Pak~crNlt@Vaaw7ak03l?paE2Tx>FL3YidaOfLpXs$Sj+oSZ5(RRNj(mm=2vp) zR^53^4B$R@*rkZRBvYy5n5c7;O6}o`2X!Zj{t>7EQ!DvZv;*VJm~yisYFAWDOpIk& z-W3CEF+70$Rb`~ts;$Uf+_;0Iy zs;a7YWm6r_uMY@Kpt`zWvUt#WI(c(GcB_LqFwQr=zSS-h34d(cA@bN7Q)v(5L?95} z8)IK0Cca35M}AkzgNAtiXmXn1TxeX}J)-?;BXGYLyArFas{W@_Yz9VTNvx3FQ_(Fj zP^RGK=8jT*(uz|70zVEo4Xq#KV0tIb#7K`#P^-HQ;A@nBm^~I??rs+IrSXTL;OF# biMga^;&F}qip)D9YzwHO{j^ls`rUs4S@#rH 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 zcmeHtby!r}`v1@!A|(xiba#Vv2}*Yi0}Ko^zzp4?C@r0m(p?hL(%mJXf`Fs~(%|nw zk5|vV=iKkP|Nq|S+0UMt{eC|CUGG}6_WJDgYN?^15(5C30KmC3fovuU*Bf>K0C00) z0ssI)QLa)N+?mIyEm%IyZV=7L$m!Ei2^69{Sz1G+kbpa?Eo7fUBQFc7Zw zCqlB?<);Ox0Km=hoe+eu8b&75g5K7}U}c1Q$a9#eNS=?00Xm z?>GAKiw6V@b&zDRLm-^QxVhck-MQTPxnM4~+`OWqqTJuFGW_9c4g8m%ldB8lyO%YP z8w3H}G#$>(%f-w6)AuIAe;U+{@9!Zwxq#pxDB^pb|0&1snBTczFxbC>zRAarbbSw< zkB3Kq`^Wd6QNta|0Lx!?U6`Hyz|_tuL3TWhUdEZzSrf|rN;#)pCK2fNsB1C@_K z>gTAu={_lm@0|#Sf)QX#2q(}5WQl;eNa@(Y94+B=O0HHAkc$NOU;6w&en)^|P)=)0 z1W1aHhnJ6&M}U)8M2A;Ej89NZK=cpvpZz4PfnvV_L^yc`b$Erucz*zXUcB-8n}~k9 z@*@tAH5dVg+HzXEx_s{yDJ>mdWdU9deje>VBKQxFKLdfDKnMsf#rHGdpYDJB{=?Z8 z1O>T#&yYIU$_1qP{qN1q&n3vH4u-mVm>Y-)nF|Tf{dUpZ$pvN)0wTEi1$i8K8SlG- zA=aFHe}wdl?g#z9<_Y-Cp9qcs1L?k}9%gkz!3l)9LJ^V-e1Z(zQWAfRi9dSr=eK_` zeDB;JlNlx^=J(kV@SEWR001}$ag#Fm&4jjOwCM6dgwS`TLiyoErLi$;S`2Do2rC>% zJs_YF)#G+OGKFl|2rNX8U{md?!@%eJ=E3gyDsEMQ` zp&5YUX=dQLb-y|#afK#>pifVel>GS_(CS`Dn&wNNm9}G8Icr+}kqK84_A>NI6Rryu zn!Lql&yYoUJ(yEbEs^nHV@%1V!_!tpwcy$I;z6DF3_6^lS%K!F$ei%WunKRGG2UPUk~3-dpYtO;<1y zjXmUbt@A6LIZBQRIdez7indduN;kwU=j}VK=;H{tF|RAGq{)$PO|fG@u#`dUyJ@w*i(jbJ0Voj+7{3tmVn z7&7!NPDH3uL5+CQ_jc|^bF>8WXnaN3?E5gGv6^`kjjh6FqkAO|br(Zdz8bR=C+BqR z-^xD;FD&iKjONurM8wqzFi5Ad3Rq2g3!T}&&I-3<(J7H%PZN|z_rZ{e~#x#$rpDXDomfpq6>W} zK1NdAfK*Q@Cc8(_*haZYO5)A5L)1`ArM+Jn7F9a-Er~2?F`1j|Ryhh2HhHL0+3e&A zeeOq$Q>?|i+4>-mD9A%#Elw{qRF8?5$7}9@sxKgmLotevQ6MHj$$+b!_Z(w}H_VpW zm8K7>piQqTNYkRPSVTu8iS8<$Kjle}QQILZMC;M8^g`s=Yw3%KM1Y*LpRL2!cA)J1 zbpmP9`zDY1jhKW$KvEKk0^{0!Z#L3%o7JZ#S62j@6rVRz>AGi0E>kB}MD&WR$YUNw zClux`)D?Tq#l@59`Udt8wD7T0f$w}aw0j`V$n1kcLmFGp9`*E@Ig5C&v9IpHy}o+- zv$@vI$hIf(HOojXZO0^xmM6>Fmr7a}OECwiJgCP;z7A9Td$kH83i74|a(8u}`nvc{ zNt}2-M;3~;$d>b=7&#QAEB(A-Pg-vzC8vnXb@F=mmYRq2Qsb6{-6}C_29R8n*)uH* zv(%G{Y|1ezPV!41V>M~dBmv%7iE>E%9b2NQAdX@YD{vzQ6?O}WKD&g)COz)zS8alB ztG0nGzUNOKFk6CID>X17s-K~jO>c@*37w)lq~^D!%0N1O-YSI3FZcu1XZ$g!Uei5+ zVAZ{hNalMt()42WO@c|V@|FkSZq@cNOG`F@w7RJ@eJjqx@HVAI;|k+~{Ox?dN7$xe zl66DM@fZ)jK6!~qdsd&$MZ8=dba^I+I#+a+Fp=t20=Z=N6FbkE{I-{9+!FPze@ws2 zj$*C1u<0T7$;bV(JRrF#bLdb(vCtMpI1wvX$99P=1ak*o|$~|EPcL~UPDz$#Z6Z2>3;k&aiS^-=6T@OhOm5aem`z`$4MjgNam>e)|KjX0+Dqi( z`dAY-XC({d(=>QJqRe%a{1MsDfk%vcLwA1|GJGi7#l*QGI-)E}_9dN!5vDlYJOdZh zpMDe;ia2rty`|>tYatgmSUB$a(ENp;eRXd$WOaA0V}ev>7vH?HDtLcT$DBt-lD#s^ z+w5(Dz&96uW2}cm8t~>N3gcc2A8-y!nELdh7}YDc?$m+-wr3i#M52aZ29%UYM@3Yc z?abQUrud2)@lGYVU^FR%>7Y0w^>@xpyuC|>;`zN5!!82NLW4-jt0e2Wp7{|MI?l0Q zbev=N=5WKO+s~h@dvEGUFSjjz39|)m#MVm|T0ICKk2W-P@8$0?(*GD>U&HS1IOsCG z)dXyj1h;+eU!81=~Vg#wdMqTqmX;!#Grp50_ytC7n1T+%1rFH5f2t z^@_YqJ`rCndB;&bNkSzmHAp-P%LUyk2gWk*C%mmtF!?6p_-Rqz^;<&FR3sWR2Hjx1 z(C)pLjE=QCf}k!u{>-pau?V zXWWg^Zvvo9E;&}zaIgFa*p{QvG@tB=&$bRKK9w5##)hlX;Ub&N6fc8B$7zylkHtfn5D;l(a;cSxiNo|J`dqFKl{ zWaUleq43b!nyC#+{2CvTesX?;t_jv^CaZkwCohGjnsxbr5V$6oDr(MF=BC(DSJ zDX-d{kl}rfujamoxQE;!!8L@B#DY=G@%N0{?};zBWwAn1(m&=wV;nFDEquF0t|C>e zHbq{l8MK+tzRU^__3erbp<7M?5!YM7#T$#yV{6J<84!)g3mi^H_xFR4rk<(abM3(X zM0${?pK&aHFGOeSt|_Y_=Da1wh2-nhm!FWilBxO9t)BQ&+q~x5KQu7g_%b-S=f_kv z_o&Lsfj;|kz*VX$*^Q9ea42n_fJ#QPs;~ZIguz;Nowr}fs#G9{8lF`CfOISN0sq>Y z-e6@ss&@OxMG}~ClLJ0njU}}p`kA^74e!1zRRdz#K4NP-jXOC{;0n)1L63gHGtGwD z1(Z(UI#4UcbmDrlxpCnWP;vx0E_rh}ycZ^&d#Vl3TB3YQK zehpZ#DPbQp;zBjo_bx*z-o7$?@3N&r8yM`1gbxY?Hn0Z9XA020mIz7jCk%>RS72Cs z@Ko!R;nu-Dxjvz{WY1!x@7x~=f5V)NpGj6c`Q93{kz1!A7weW+idbZ6Ki$D~TS(KS z>BhqPyN3=-&b_gr$2n5kExx&1ik{U*x-q&?u8N1o8vDgAt|G?zO-#fxTgvr&-fE;C z83RUgciw2VR;zRCH_(L&KT@i5v|KE?l-7e`tP3=zjH3#6pDcsIXxG9OPrGMw*p{~I zkjoeSv`2(NJbdXab`;qrShxjsfoS0oS}&%ihS=@>5E=I2Bo-Qea|EulyDPIMG(bB8 zOtu-UqFH5pyP1;04*E0I)+3c8Cd)gwE@ed-R?IFV1KksCz(NOQ=eAdUg9weIpmCG< z&oXXnYW&uZ^?+vPA-nBO+1KJOX^C7%2U$NOSee_Oj zD)9}w-%{vPF)i$=KRVZJdZAo5-d0BtwvJ()k}U0euHHqnSQ(7(y)_7))2@siNOG>& zX}ssXjS=)TdZY@&aE$Q52yJ@LHZhKeiBZd=8Pv)8Q`xe!DaZiJMuhtV z&c(PMs5@M5et(C*%EqFro@+ylgDUIxn|I0a9|?2M5nIcM6K~WcgBNiIJbn?%BXrLn z*bPetArE}!tYAWl<#>8o`0|-=`|W1nBXI_Ltru=}W%kQ~r3ZZ!nbx*YcZ%j7GeK%X zslyIAym$s9QQ5WH%eR)(0RA#-@fM8@6NPF^+$N7f-+-Qy-AetIYwQ*`?`$7vFBL6jQq==eF35-SvHb3m4DGWf`!k^hAIvrzbXW)va@bNpMR|j@zTiWQq6y%SR>cvGHU1M;G$mB(hIJa zepDlu>{4oDj>fVk6GrIz`~Yte+e`VY#*P~SHQE3*>VQA4)*e2~TKiEdfte$rOD0zn znxr81y)bCtttTT>XJ@^c%l7`@=tpa9-XAzLu)b|OJ2qJtkFw)`ZdDw!HN~uLUgW=D z@v51C0D2xGk<`2pyeKYG-x7Q%_Ef^DN~}?qv|3oVmB8PZUqu42%i|$|FYrw@t7tP@ zW|B5|LEwP=c#Svx0nJ?j*QR4_y~+guUbTLQv!k+ zm?UHT8S`YeXT zpk{UEZ`PXxOrf?OTTyG^Z)pSqOG>nEbE`!T@=5+*zsOyc8Eyo8NRS)l%-aL|PZKR% zFb9#|Z#mVvz2@OVe!Z}2r;{MCOnn_FOySawLL!|DqY%I7KXBTS&js2FU`7fPiy7OQ zIOXF%7prD)fJFG@1h3&}SG|{utI+5!4qg)?fnWBC4(1oj`iZ{2urm}Y8ht*z+&i$| z{>^{u*#Bk$ryKV<^eGkq(60J(0r&HjY8`SFi4YC|aC49Y00133S4S(TB^UzdM*RH9 z$W=$ z#^(^F`$iA5p1x+3$wTjyQ^*ZDP>c!v>Jwq4P*l-eGP{sMNxiWX0iSh%mCsU&!}(`Z zwh`sKkvawO%X5dK0k*nR>@zhCB=V??S=o<>*JO}g=27JWFja)2HT+gaYv+gW&0j_D zxu0b2?6-O05)d2$3J;tRC;%!fB)|kAfDZ5fK1J#RPJLQ+DJ-28it8wNn5KrB*alIu z=FjH#Nq6+ELQN;3yeJnnJOHZs3nYW;4)*{{*Ojc$zBt%r(USUnL_g(vp-r%_AyL5i z-B;(!j|XVwt3H$$YqoCo57S;(*y}+acv-`jG$rw--7_1SrN5-p?E2TR%1HS%st5?% z8s-~_G!eb1^CC;NNiQxecQ_d|rFPp$EiO1Vkvkp99KAleTHn2xq*PNgx;@)wVC;2T zys~}aqN8h@fU^8L^m6TfoBw59-R5i&r_uug4zEv*TfkQm!692C*Rpj^W^Q)dXrOn+ z42{ugvJQCf-+rVR!f#LZ3%AX(GNj|L*~?J3iOn(QNDMt(!%>vJJA2u-nZnNN3-2+b z1}j=V&(UgTdC<99W>S*jyFUs}?Jab?NM=4f&UduVukO@1kN&pzY6v)$KRhIVuGsXx zctZ^@GtvR2m81dp5ILY+x`EsT128d!8Bpi7J0p3SD~t?Dz6HQPHWryeHo-Zrs$RYuM8Z1^z^Y79dRq6(}mS& z&xiL*`?%Dnz_-F5C&Ok&ZW+uW^N=*V*hL14Z?I`5n5AB?zd%g)V}q1~G?%Id>fe1Z zRijN8T{*3+X*-!YYmIpIs#`$#ERQilhb-D0ORcGRC!}yMmzHWLk(=bCslVFB&)Dm( z1oP4QC&g?=e}&HB>f6N~N^;L*>lfV2ua9h)18=h`9t)+(ysnigO&K`e8UV^!S*@lNRfXxO$Zl?8)Fg-A^`GQ2cbKp5 zkSJ}I395{LP0i{#RB9c0Tp`RVq;xVd=s>*i34b?N#PU)}V`u8Ym5{IQaTE&p{PDPV z@>%WkGDXL$k9`L_1u%oWGwvwxabn9kXlPP@WmKR>SDSJE?IBi^oZB0yM8L~Z*Hia* zC!MzS{teCR@{#*$^k12;ug}U(ePL|zz3ltv(&qa6b)ekZ^}ec}*2+#i7f}Dc^eqyy zGqVauB5SgOdOyPnikixzBNuDE<S~Oe$_SSw)&U;i8iEs{+!=BocFdkbdp6 zUOp;d*%v!6?WS6Dznn^RdhX@=7tg(%fFb=ErSP88klyRskrNTO&s`&ZQ}6NzY{1a5 zY1IVHu?Vdqb2Zo17=J}s$P$?n1+BxY7qnXEqt{lZk~XgjUTx%NZ*mm1Df^ZbE9yrZ z9_(4}?>e9tiwih>hF3K5)q=gP245wu{}U zOm|or_SNLsmnSf;xzkh?_NsUrNi+rV6j23^!{pPW7wh3bzFO`6W7Bit{n>g2^Jq~9 zqvDe5q}@xqJNyaTq!lxMX0hxul684?K{0O{2+h*#Enf?C=`#)~u7hpyFjRQ_5sfx5 zbOTvYff&VYF+jTrOK3gCUM;G6sEeJx16DGcDc$!Ongtz@;W~Dg3~(8N^P~?A&`#)% zV)4qz0Y}I>JjmV&GYY+ZBq^QQn^HR~KgHvz1bT|9;L_@wNA)V(bDztCYeXmj7?iL5 z&(^v-LK-s)q@)DlU0Y;E>}*~_Z8UzH1k7FG!cS>WqFF)V@sCd>3!n{IN5;gLKnHoV z);ELWyBKlKyns0BMpq1@b)Hghsd?Gi1NhU>Z=IbVhlY-&NqFKs!Tm#SC$wYwSCO2c z$y)mn6GycV9B&y!FgK8SnpU@}k({Z@`Yw6|u{8Sx|ytdL^%}*v=jpstg~Y4c0IU z4@iA$)r_rD9oN5}j-)rwZ20JKo3kZDOay-enMc)s@=y!wFnL5mzU6g73QG<@?lQ}K zwflUCrg8QnC#G6IF3`p*Ct1mH9wGk)Y6`0H7=$SbHG%b0$D@P!-{}D$S4*>-YU>JU zC=Dh!p~&ss9q5X%W7>Km$FL>p(xvc)?MQ+8#)z>KvKKSB?s3r~mWAH(eaS@)093T^u0sHlAwE z`5cgp?J8~&!HzDYuarSJ?Ryj)ymavLgPE}5%n(cs7P1i{qeP(12kDV`i zmK?sWf&=iAa00Z_B{F-{XvGf%TwYx>5|&*gA(2K)kdQ^UGI|gC;h{coZUg|5yFQ@= zWU>b0ZQutqk|8t9Y6vJXZHz7=QpKRDiM^AVA>%pZ-We?KhNuBMti!$2_{5WwDCF1Nrj%7D0cm zHu!CS4nPY40OVj$8?fyk8=7!FZm^@JEeOtiAB=Fcbb@pLJ(%Jzz)mnHS0_gh)b)SF zAz(0wlO+@c`5$pNTbQnJD@&LEf}{GYI9*`2E+F{-fxM9-|DK+kNdNo&{t9)IlK&lL z1A$p0KtJ2|S39iCe-WW25D0?&*g)n6y1Kah@g^JvaHGL)djCc&-Pqs1M86SOaD*oW z^kduB*gS4gfY5(K+j^)y?Sr(+f|^|vk{IsL5&1h7T+Ilp!78KqgT8~06WkqlSE4mL zRja8*tKbi~-SwkJcp}~Om#@Iz>}K~$Dqz||P4qcg62@ZJb8tmQ98dY0uM?gZizl0% zXXghs`VvuKWzt&&gYnixBrb!>yvXlM4ah%CuqxEQYsl(m=wf9h* zoVoKCFXNO`xJ}$^<|BmTc*z`QGe8Ny?>;*)^1? zGZ+hX^L-Ls!8yTxdhV|ebMs@G$R2(4nzQh}>|uuu1=RQje7Ud~RlU-|6=gK7Y5i4q zi|9b>Egd4us!*kQxuH&U=NE2)=svADR8QZsB*Atbuu?(Fl%mJVhXc_md$^$;e0 zki2#G${p=$;!F_}pCE*)TI;FLAS@|L_&_mGIMu_3I#y<@i{fC~h{%JM>eWI;Oi&v$ zOQ(Vr>|AoV&phyC*1>@JIZ*i)r^}O9cD;P|<0WBi$}A38TsX8tRsIZ$)pY}$%O2~d zAw>!}3#GEO?3|1vI=dCK`<3gQamc;yX;YtazN;Q_RUf*4|`I9HEN zswe6qf8bj2y>2R~uR!?I0nRP-LidMZn`u@NhO!jR^pB8eUyxZOEW-4<%6G&n>p3uk z*tOpXD@#kPMRaA{4mxTbZ^fNRIO zLttxfJbRII4SNHzNc%#pCE*hKtJAm|_^6)FtRFbEK}C&?UEV-`Dt{7VGB%D z+C3CFsR@dcJomW!OLGeQdSbv@ooH8p(9k<;Y)$BGUizf5J;v0cqER|s&*(rbx|bID z@l}}YTrZnOUB}6vy%e&@q}vp$Vp#_eQGF6;j$|OIpJ51MFeiKlU9_uxw)o(~GOKCp zgzvpzhM=g^nBksxVgtDRMhOwOMET_F${iA~!OF^YWNI5L{?|~dk%c!0qMUIPxV*2C zRpB$-J3;lCz9-t-g6Z$R3Yj{ur^lvf)TfWMjy-f6nz-$RxfdABm1?Ju^^sl>bCe*v zf1dClGE-VSB;Qtk^MfISfH>v-4v%w=TVBpWA@@d!GLtsCHd593rZsH1onyvO57RaDcR^X(#X&<`18EN z!W9m4sHxTQ_rz@|E^1z=#1(woPG%I`7mgarGNZ|qO{v_bmeo*KlpxWFW1}G&VIx}_ z3$jo0izymcGQjsVA6};EIcoOl8bWf-!__nGp16D3g0nGQ6($4Rac}+%U8JIrCfb#o3;7J}E+cwlapxXJQ8kuh_fn zahC;^MJF#qZQEXW*1GUYgsCIZcu{qH>b)i5foBiJTHbSfu#Njc1b5?5a~t;wYNO|X zpSS3-H^tDCG3VBTugSY|ndv&}L_v35Y5mTJTriGEQYW(rM%rnk#=(IPfk%u*Tc2d? zU!Ay0w|?Ldqi(`bWzXb5Oh)x%CJ?T@_r0Zo#ija%{EOEd;>F9lopY&d?edKh^liv? zJU&*-P+{r$M7Aw4;v>L)AE#rh;M_pXckND2s@Cf3dr#kU3OJQ%pPvoD#XO=K%rsNx zjD^tp_Bmv}7WE*$+2>`I|h5fWMZN7S9b)NeVNf~fi=>D2EF9|aCnqz*2<>I!&tr-TQZG2w7n zG{ptld5hS1GqaJ}CuZV~aX^y@J!#`!5LH{!s&CG!#9_UL2oyVuhRi!}IQGaX^ zsVATp&M)Ls-@c#VNv69Q`JnC7Qq&^E@ec7!$_=BOHh^606Qw} zg>(b&yif0E4k-%62$7n5-xNqS6X^8ZlbwyxoZr@=iEHzMXe6z^#sPE3&sbQ7NMUCH zFU^%!PS`=|1|C8tD>&D~ll6xM9i4nv!KYu8wl#0kN?ypnM~nmjETi0{6$zOb@b^W` zf3}|`&Hs-2_e$ko_VA_<`j5KhpQxV;*53;^Zb|}w84cQ>3k3fi`TLH+O<~6`i^cg< zna5Ay-)$)TGHsH--(L84mS3nJQt6kq(fy|~_z&Uq=ZyaX1HMbAUv~KyWWNikf6603 z|DQqqF0B4359BX+eivGQ&vPTSep%jM@cdbL{XNr-i27yAf5G%ii2YL*Vut_B&o5#2 zPgzv|g5{S``@!;aBS+&&A&~Mxb0fYb{Q~;oh;|BEq0QYhhqW}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?RWmH>D*#4WAwzw26UZ510;!bgQ_u}pnG*oacUI^|^A-J} zt+USm!})T~WF=WUYu3!3N%lRnuj_XwR9R699fb%5005xNNQ002C5Rh1G2ln;~a004kjCUR2Z0Ql1*v!x&o001C6N$a=*02rN5&u0k?7{mYo z0MSiGK>~3B2@~V>a}O6$4FKRRKt^0d-E)3_5%>{j3yye9lN2d}^@5@BGlKHB5cQWT zoq{OtfUvKRA0-$HtzOsFJ56dx)zD|#mxc5z>z;?})*PyoRO@!lW%Il-4oJ|Cy?c0# zD6P%;HtT4{D6!pj#P2Yj=4inn{pXt?3cyndP^NwM^!}FUX)u87KcD`8`r!X;jFWGq zfKAMCeWIeGv9YmXVPQ^h-KAAjVw7nGK=+T0)tkqBdlDR*8A#^6btJ!LJ`C2>S`1T zuPBnUi;F1duBxmoO42}0WhF8ysu*YHrJ02V=w>5{J^>{UFsj1mHTAQ;zTO^M%VOBf z%FW&84{ueb?ff!{T<5Up;^C2RJwGyX)O6G;CbAm~ft(#c>lPOmF-dqn+k8Cmx;-xn z415V5(u9!%0BJdKbtaZ0>1i=Bzt>JyS69EIx(DhrU!9-F_nApbO2T~4&{3WP0H3W2 zUv3Sjg@=Vv2FPa!wdmD3@B}oPoUC?PTU!f|9gSv*QN|#>d3`4Owpi06<8PE*3U+Y+BmThRfROs;2;1RE8og z9o@<4X>6a_`}gmOx$HiQ0000i^qS?#BDJxxF zedFxrpQcuVW2N7LKp+kU=aW4UhDpJfJONJ7(qfMD=RB1D(XKvef3H|jKR#p;?;{6qa5~@mfWtJ@+3?K&iB_Rv$NV^*_$I7j+U0eU;l&x8L`JUBn^z0w}|w`XxFsSG~%u#S~dy}EJ*Fc*({ zqe*`}oobQ#Tdd_dWdHymE_UE~bGotK7iXQ~;pT>hg3|6hj)#nl92y#G$K^9uWnNob z`?tC4+gp4B0@N2@fBblZA0D`ti&Irqb^q{Soq`|Um6etCx8D9@)75HMxIQy*Ad#s| zx29cW9Pjb*ao17|law#OQta73KY}@k{ID3564>aQ;dyOv@z-=!*&YaX_+JnK) z4#8AR2`oZ>{rJGImkb7j>-LxVEK~;5d^Je-rTQM~ACe#mx^^+3>KY(4MyA1>h~=Uq zdT?f@uCP%0Ef$G@C)P+12p3{8R8>_aD=Ry`L|l`Cp5gDzrFlUE_aGTls=c!2zb_Ow zlslM-=FRfRCs^DQ0C22ZU9b1WjgBe@ijEa1kqZmAVLB)!Hg;I{ma=Eahc$Y_Gpd7U zu12i<>|1;43#HtqSi

a&}--AiR)AzFpZ`E-~5}7nAl4K?JmZj>p4b@`T$tWsG2m z*O`R?@onY)e9hib8{7j3ETAp6ht`s(z83y;ZN;MCx6D&)@_DkIr)+>XOEaHl+S5X1qohrd}R8GEt7&X~%RX%$@)hCL>al#9$7JCiOJ5Kz1SEOxrzIR89{sV-PFI6v^v3^w3+Fo)(23?~;KAsNrhnJv$;?@0&k zjacFdFRad6bdC_36S1hkS*2Y0Q<@6wl`@2;CMI%di-AW=XublJG21O!Lnf8;)z)Wc zBf=&Azx(=R-eKQdU;ADk8^7_=U2T7DU|(uq3ia3)wB9Q7#iQ~Ea*eb2>#)~K-PLL) zaxt%Q84hZ);ziZh(H!5Qw+csbp#7?158*K13LxW}PHSxP3bIduK9++r{!O`)>SZW1ypBXy|tTUT>H+Vt;s-Z1oqr z&c6HH#PD5j0dkKUecntTDQ9{R2eCgT+7PX$;5E#PIr5+z2*Ji{I?)Y8! zVpJv7J64(7em*`nwtd6pYJbku#^!bf9lzl5D5%}p&uBu`mf2O_pgZb)02bxUISpgf z=QKE!?ppvVkmNjFk_>cq)Qzjs%0nWsvfs~SB7hl`Wra3=j6_SRLesY z>{xn**@w(`Z%cB3O*#?KR{G!0?iKaykWx86AS<|oz8)0ee_CKl`r;;u;PL`Y3fua* z$MSn3sut?y?Qev$c@x9(%J+kmFNIBr^GaUGMpENJQ|x(>^v&*M|4U&5Urv#S!&dpV z^PCxbhV-s@M@ucl$i<17RTZC;Rf#sxLs)pYmw@3&y5LN?0rYr@zi;Cd5tGc!!eaUi zlo%f$?>}?3Jw^ot0`bGA8r^L%f^*7Na{7fn2%m@SY`O*qb1*em*B|}(`9q}V9(JEj z`EXpFNmUy|0NSSW#>Zi`lC59sDpO2wP&EDaB~Q^k62WPzz}rzTll&m9;kH%kKC%Jh z>mZJ6&_0W`PO+bL!?T2ybFZDO+1}*+AzyIj;Pxi zpi{s>5KnPCi$G43E&)siG*?c=>%;CC8@N(pYw6l0Vv)4fl*AA(Q8I!s?-(I_&;Lo1 zpP8-^2bgjWTefR9>$<~Hyw_%zoY1fAxE&(V1||8Ex9F_}XyPTvY9!%&{qjZRXsM+# zk^ZyhWVqG!^6zhfs08%5D43X-EG#T#)kTcGwAftSt265j-1y;6Os{-Gh}FbZc3}am zyjrFp_G1CIT%U{G|H`hTo=`6cu!EV$kYT#aR(9vOPDXjKTYhf}LO zAU{~yQfq-+D{O5FOwpUPTu}*_eUF#F+?s#t2tr492^i%lQ>ULISlPYVfXhD4#L+0J z(t&HML z3l(nx!;vAUFy@!yfRoQ8&_P4nT0<#fna@tL^Ov258CZA zt+0D`OVjszvH2j?d_S5??dJ96#qSNp^$>w*=}NK&b%%C3RZTXn=I}mUFvqTouIJ@G zA;tR6L_tUp0G)!UT(9nMsl`X183=3jla!R4x6!l`%w=%wKkTf|!eLxmc&TEM8lmk6 z9F4VB^bRn2Et%yl7$aw1T<4eqGa&Z9a;z;(jxn^o$|-28rgN8)h`G$P@KarHi=_{J z9gJnJqFMQ?H&cdPEb-jDRn?CKcRWeLdkBpu01LlOqixy!;p@y;GWVt8RT{Pf!D3eI zH`?(@jHKL|B^9+I^&H8_Y-?R3Blt>3FuEsSZB>=`N9fR@03OrVt^-|7+ALXb8QOy`*G2q zO^}&$S5;3|SarS@MWQMy{f&b7X~zhQXeUOrZx2;JtoeMQ>UZhFXP4$%`w=3y%+nS~ zVX==!^z=B+ho+*lw-fd>75BGE+0Zcjp=-fe;YaVlT#iG6NqujV*iBGX%K48`EiV4U z&5xUQQgN)pPRSzB7dIin;z*V%?0x#%PVGz**O<7L)g&DTVx|&L z@Mm~j5AUbJO*F1kF<`?yk` z!S807T328+-%E=nI5psi#exAjrhqhBV8r=iKT~R3s>v^S_?9m1eSqykeoJ6TUU9W^ zVphIKK#kWjm*diX54pcn!$OPC)vCRB%bPyjE(^%e;NXkrA|fJRLPPs*FZSeQWgQk9 z@kmJYa}d!>h=ht`_e-(;N<8v?6WNZg{F>BIWOKXv*(`J3QS9zBq{Ijd-fmb@waL zR60CeBAoRMkexM6hl_GiW`=<9&9Uu46FPJ@uXy{x3%b>X`0dW^XO-Q|qA-1rpO#Cm zk{mOI-NbLy=U{TOwP`pc=C?36uX(D! zsJ<84qQ4_}n6_A#o7fQj{wHzgJm-8_Q_I9Tw49;!_8up_;i}d?eJ6a8Zw|_j0sV~` zrMqF#OQ}B)^ZT32G-fTt9@c6)!W%6(&E$-2ZKZ#CDH^cpVKeY>cSXRcovBP4gh9Hy zvlFVKPA>n0RisEA^og=`>DZW?n9ni0?{`d8l;EouBpk^#=dQ-8%k_?jeX#UMm>uy6 zLSx+Z!Xa_ zULx!+Dtph0t0C6r+0>&CPuBxAhB5Pk%8GZ#`s;{}tydyB21E{sUsF~eI^LYyI3$hC zBh!~Pr!UqU-@_a^&zv2*%09Il!Ykzoyc1` zjD}QLNVH*%zBg>c2%j;p#>$EEb8|}#nl$rNZ?3P=NO-Ua4YYhOrnHKRiUi1%nnr@2 z{|e5`Ak}Nx*~m;rP?)2A1@QeIjf1}7a?=|_WzLpdS$Q&Drsw>|tt*Wms9CC=1>%}q zTqJ$@tPnBGk=Y&MjyytCXJ6@R>Z?Qz@Xd@qL*Ag4OU%v7JMnD(hKRYlw+AOc8M0@8 zm-26fVag1kJ@?v*8nG`HiD zew{;_Y~Ja`1u5$%z+VO9Y;(xx@t!xjCpDmyOJLg|r z!f9tbFO46FEt)T%Jf0(kscxjjs9U|gGf|+=e099i@t?Ggz`(#=y*>*I3)|^ZksbH0 zsS>TJ49W~1=j@UahQA#{EJub12iIL1Dl03We*xspAa`|j?J7}o+fLg(++O^>4Nm2C zwK!U8VZ^tcF4Zw;@{m|`m(bRpEzzpD_66D5l`7MU|D%Tp$NwuFG@1`24kR*(jk$N- zoNWP*mK2bXF)%z_TtxpBPCnh9@665336QY}38nX}Wo`3iWoG_@Lc#ev_)NN``VH9s zh&Gd7*Vos7{CE?Vy*Zp_>*yFAwiovO`}fjPM&=}90)n2cGnId*I{^&l_t@7?$%oe3 zH(8BQ#_MUN^10iAu4c|EHoD6A}{AciB8&A^7o1haDGj;50IJXy?dCbiOq) zG1%*D^FPEVVq$P=>fnl#W|{6(xdFerj@FA;uZj`;?Ccny3;rvyn3=u!Be6I-l4E0k z#oi0MzP`@Qea8hRef`?l)b!hv!g7yj4Oi>n_t>YUrF|Q)(Cme?x3Ytkl8;Og6&1y9 zIV{deM8?hzVbCh??Ck99>dGQg_ED$D>tJQXN6iC#L#`B84{x=QJ54^_fvnP{_#0NJvQVeCNw8ER?3jB@+fU`&=CsN~XyuDIHA|j0_~P zH0U!IKdT8geuIGUEt%aiC?J4idGY?B4kj5*mX?svwc_M7nsr&IPA?|baj`e!A>r0s5Rhnp4CawP6BsGUZQhYoKugiR#qKR zK`SdOO6dZ|mD+Y(#8Mc+*! zN1HHz_>ctz5$z4D$G$d+TcKbQv%!3WtEGd3gMouOO^&g%b7et6f&6=RZf^L^Rz{#G z#V}c#)82I1uU{Xzzz17f+;+39xVcfz4GS2geAhQOS-8qR=|X-)L`3t;6?rPST`NwF z?t4McUe?GeDLGypF1ib3x}9q7@6SQl+1NY<4E6O%T(Zi)4{YpybTl(NAL52(K1JM% zleFmJi|d63R}~eNfbTmK1;D*&^k8KzM#E+vCZ@=qHBvq|>37)wUb*DOe?wRzlU})g z19p#+mVT3m{Xim9!1vFe0o>f&e}z6#QPC<0q(R?7U!Nqpr{iP-nVOo~(9n=Ad9bt7 ztRo2hKSD2`J3Sv?N_OGTpR9<8h$I3AA1sGc30MpZGtj3dCdB@YyXuC9>Cw^A`pk7z zRVbL4Juwq_1kCy&5fSeK|h#=gwV%!LL0iv$|qv~T6KjEv`(mx%)#o12?Y z>%`y4M@L7;%p8?nC=rey+GRq*W$?jvx^!?*{sNNaD@6WRPXDjrYvspIm=Wk^BbXeN zNlVYcF*!E&`fsPdetj%b@83EzH8nl4PiPdSPq@9l9_6q%Hm-ErQT;n9t7~g4cn9?-p~ogJfu z%GuUP9R%_;DK@3c?YOpQKwXc0e(QleJ8Fu6QOvq}UG$|ZeVt99t~QXA?E~dyxw?i( zc>mzKPB{W)`3CzDNK$xiso>x^2RjJsc5HgdUh4gZ%{?^s&iRg|q^=ynW)xcIW3Y3W z)U|G8FxIwJx-M_tA#kzl&Vh!6L`zG%e0GC~NtR2Cf)l9N+t)|P?@=oM9#UItSnouE z@*HsNXp}7>hLM|JP*6}H?Bi>{HA(<}Zb3Stu5ru{zjwE}3&7VRKqITYw0M?7@upQa zh5u;Ul31*X)53az=&z*8VOh3akyCC~;zmu_3e%I!GpU~B$x)5zUbJ*Pujh1pJc)Qk zh_UCm6c!aFREZi;Apv+*2OPT+4N-=+}(@UMQ{&L*X2z zLX}FB>U(kgt28Uhq)Bo0a@BB+OTSlh9KH``Wj>YJ#aF8Pl~bV}0J@#Xj#;#`x3iyj zcSBuBpfpE%@YFNXt03j?==Mh2-54F?{dCo0;$9M_RnT_ozB5{0lVCq`Vq_Fc8_KqK z-wk)I*&8i_w5%-?!eDesrUP(fiU3f0vxyrfKR+Vk-EjHZ^g~Kf>8G4L@4Yr>=c7wQ zBNpPZqK=;}*45pT9Al$mw`0>nd0^}?n!q_D9Xv0sAS-Px!&YBjuT!&>d{R=|?^z?9F06yxyk(8h%18Z0Z*e!Hfev0$yaolW4s*^n=RU8DK z9vF90p69f%Yr(E~oYtlj;-Gi%xOgI?UjI?|e66lvw?+R}fCf814+! zawpIp3gIW_EhX&xNA9a~^0@Zh|sTWYjP1lQp1&s{wAclnT^A`p(8 z?lDQZdOif^_UFH(K5AmwOznM7#NF>V16@ontG{VWV?%0l+A0Xe*N=>hZ^J6~eQnel z%oz3ApqNgSmWrUwp&_*LN)`)!FQlTv(b>83sg_FCMic_ zj=!Rdc8SHEk3OEV~;&Wx#>=`q# z;V@T~r%|H$1KTaIt*z~LZd5E7V`WYm@EJ3Yo=2#=Tc5P|JcS=k&*PJf<2U;9#9m0c zbYcF`#XxH_gGi?3Ig~IA8NOn;6u`igXzt2ZM(CfG5Efkk1T6V z!{zTxLsAH2bFx{scpx_E8Kg>CXD8tN^WT8A{m*)htPD!lPdhB|5d!| z-?i+9{ajk|URNKLzG1Y^otb}VA)_BBi?=Dx$^c#zbE9=!Uth<^$0G%{Z*N=4qc*M{ zK(Y)P-Hy{Eojw99Eo0mytJk z=Lb8C|B7wxEODi-6J*dr@(x+W(r7H=erJqDn7Dy!$U!}6@SD%DB|Vag419s#bT?5i zP~P1CR73W|z|WE-F~#;P0!TtY??jYT`c}QS2bSg=MA&7mzGXjWwpQ!NBK^?{asPcm zvaFbEN6?k?z%3p+@V|PH?Dkw`hWFOX)9N?SIsjb!5<=!q*%pL86<(88TzRjWb~*9i z4aZ;%($kBJ7N4u~T39(={(JH3t0Oye2M33xs&9KgBt8I7HOO5orq7ighi=W>Is4sA z8wFPmHA!!*ELhS!J(lcz1khFM`%F{*Zt8ig4(ZF{^9m^Geg@u z4U?jxNF&~--7I?45xbL1zuk9lqL#S4={KM%Ll6=|0b0w4PyEo!1OCg@vsu$cY?{{; z-X<(s-qAjmS4@~-v^4Iq^<`+SF`eReYry7VxqoXE{MM?|-Ug=p+#oO6A09&D+zKa)4wpYB^)a-PKi zIZe`Ycc2*AEuBxB?)iDmC6-JeHQn^~`&_@*%1!r~u5L1jdsUB(sOBgDy4R+~RmJ7> zJpOc0$1Et^;I}u-HJxz;qSS&1Jo;$CJeK;rIBg4f%tPfeB8yI=^%*6MJtU*#HCS#N zEJw(MGDg-;D5@uhbrxrf?+)2?-xy@CTTY|HH)+3lA@Es5m7# zc}7aLu8U(+Q-TDn0TCp}l8Gn50upZi^f_;8tBFk0&7_aq!P%aDbt{#~E+*h#ZAKyg z$9tc)(MnUPFCTxJ^Jed<@N0XgQ(St)UiX??~d9C!n?Y=yB{AP$z4cQ68z{__k0wI zv$bw{QaD$C24?VhGToi@gj629qz}SUumvY%8=JG;v{a-*J*i77CI{5G>#Lc3=34Ki zy^iF|U3fV}f5hGizrft5cQ7@ETFyTPQxi!6UxFE$+~&$%`5B1K1F-U!qYdJ`=jPpR zs|&WW1@~_2?gWJP45ItpgdTLLON#s=cmux67R1~)g2i@s&}+EKbJdE}>l|T+QzZo8 zp;`!JB62Sz1({DVeb3YMU@546wqHv5bSAxqyJ-kKnGOR0%UgZX%qQ{{=;-M5nSmqe zg8BLRH8{c=&+n3L1%niI&RyFISB7K}I|xpG$F*|b?#`C2FeTFn-(p@EO`XhWv>LJS zY?9TwuE%`1!Y}jL!KtZhis`k!D}K>4)v`J~SOq%sEdIHOC8cp4Xz8Z4x60qg0(F09 z>A0y-#p>&RU{~&$lGaLpH+w%yl@A^vB^$3k9$#%WZ8v%KaPIZ-E>b1bA92vChgt%- zsu=gE*F^Z!&{_NCO!SG;qg&~>xA4>URuE+Ej>O}E+H-!)gJ0?B$hKWT__XUY%Vr46 z{!dWL3Ada~+5a$#8DJy2-(zFh%zD4Cu9|Rxhb$n$7^L&ZlG5JZjiOmRUZ-XvA|if= zTW4D%1G$adgwC*5zo4KXGBUERt}ae{2+xH-H*VD4T}oo3LHh@HLjGHKCjphiPN7XW z*PDFubbPl?uG4l*L5UHQ=dToyfz9<(MPcuXvwr_lwX8brGDcrJpQutoNyvRCjsH%6 z&f)Eqy|M#Ir-Eh27$WAB}+CpSDmsg|tJE`DbM(_=*24-UB|cIAhV-?PrS zIyw`36mdfrfE`Yah7rJwD=FtmEYsb!Aqo|-2-u~12gak2H!y9GVm@1$R-Il$S~{e% zveM(QcH+q2;lf@rm$q0e7(+rrf{z zac?<9w0_0+KaJdqd0!f-(H@w{zgpx|&MZAld&G}|FqaY(aP|#OYcK=O6h31i-?N#XCv_E{aHg^lAb!pZGjBVxHd=CSvy;ESt4jOOgCTWX(B{kndUnPWDom5PWP= zBA^R!wI@y1k0L_p1KH~plXi-L9~YS0HE&r@3{Rk#0SUTOq1!rP3OgA_cts(gMSb*i zUf0cV0+z|M(`0r_qD{14tO4Imd!inW{NW`d5Ag$>!rM8jMW<(Haj~&gRaG{P+25<) z=19*jgjC#g7DNnW%yNA2HQ>7FH)CiduGHx?QD5H>p^p(NIXx;GU&s`hTB{yZ(@6Em z=>c+E;EWFr%_In~nC-fPUi#-byS_h4WcDFI=ZLP7jMXc6{6Nkn%4kvr2tW{mc4?JW=%lS5<0Z|CH z6B2&WclfQ62x#EBD%!Ew7EO+xAe)zzlqCOtVrB*gu~f2mjAC=qYtFW9ds#BfJN&ky zr)EEnZ`R!-hl?BTxi3w57fw>KM z4;m6+AIF_46shDYZPiZfcU4t5rQAiE~-qwdH5QR1)6%OZHeSV6%B7LSS0H3m{LxBe)`{EpvYJ+u=Gag zjbSU7z88Fdo-h>E#QUAMgxjTJ2wZ@NdsC4sYtl&}t`o1p$jWA=TIT*ksNLsWB}bAj zLDtXjAsCZ#qwIn_j+_`3A8zw%>1X+Il{_Sz@mE;23~3&H2LUh zpH4R8)&9d)Uerh^v(I-nXOr_2twhREZW*>x)!EUSrYDdqaY{|}lS#5@CKL(O>GGvQ z5F7H>IN2<2awF9H^wuoQB}_fwCvq0GHE&p0zD{IGk+aY)NxQZ7RvTZTL9^#rU!M#E zI?9XZ$?}(ml!GH9jx*(pDV(<5k;F9k;pBqe0m+C&xzWCrTf=Gm1Bpy(^a)gw5y!{J zg(W(jzU#X`H<4HFG72kNtqnV+H9TEidqI#uVuJEHp7jw4*XUOD?25a@#$|VbXfPAJX-XB0@ z8C(6rHB?fAp>`veOr+&Lo-zdHhM)A1>oWt7mRfoPFP?#i9LBP{dSj^U?d-^ee61WD zTK(=W3zRY(=Bgwf+$P(s;>;(3D|S6??NUP_&ByPQ6bV|Iy__Dm`w$@tL&Pcx6@TWo zoy*R+Q=siZUowOqu6f@_kjLV$HM-oy-ryY`Id+B7y~O+}gl%v23#waz2$w|)yjao} zVx2Akp5^71lM{H%{9znM-f0h)$S(c#hQ7p5;h>E>coIJFodlz2a4=$EV{>b(&Tfv4 zo<1yphe4}6f|y(J4r*G3Em_UMQgCrS(O}(lSLZIAnpMUSPc;3m_>oUx-hfTd{xPNnCNhi%Hr>&_~+mT4U)mJjnVIGNhYIJT+&F`<`oS44Vs z1T*^i>5FLA8$P$ff&v;79Y0pn?g-0~bZhF@iS4%hJ3Z_683g2LhZDd1s|#fa0F42Tj`|6U+-v!f-BWC6a;gNKB z5rubKscAVrKnO7XLMubVsDXRU=8<6t4AqQVX+OfMHnxd75;|I#+kxc4>m#kG3a#E? zL_=WOU9^vmLlhUV<=@}%P$bG|+JPd?J0SrDJ5S~6@&fOTcbA~Fl9G~=|GgNjxD6># zrKlJV_}KUGN8d|APSGC-MNYaxV=aVYv(w|L>48CQb3_S+b_qg?&O(jR^|Z>Ko;*nd z8)r9teSPpgjhO8M;rj3vj5hVj_F}u5I@}adV@pdZmH4bIV-F9m>DqBTxQ&5WVVG)` zI$X@dGC{5B1I_8K$JvE5hV`30BF&=dY0g1-SA}~pVG=5gY|WqYu7>dbqI@(f!^3W| zs%9dfut}mKx&~af)t%RIV7FLD9_?gva3g#%N7Gc-Dn)#>E|7mMaz035z!!GFH}A2( zQ}^hbDEfGXY08(JoU9Y(BhPoLs^cJ{e3RpNJL?H*GQE6r^+k{$=yV#b?pQK7o>dlX zw?M+NJP}oew}%J!63HTfWGDv3Wd%AciF6NfpvNGLB{LWp{P=BHI=oM4$!Qt z+_bt=4fDp9J4Y`(u%?WfhvL4qsr}YAn~U+}Jjh;fm2H4=pfEOnKXtUDyHO3uJ@QlG z%%_^n<(^~>H0HwUk{n@e zk2M!vHG37Z$P}eBs7!%I^=A{}a_A#bvMdseZIkv}3Br%{4_hp9^N$x3U1*72^#>)5 zsHGO2X^|w;rS}7HuzAFLaq9OO{C5gTdwWw*dLIcUY7w^0UkT8n87?;-0->#K)D7^< zuLi4T1M&OlX?!Zuj@dxWLw#C|I&DNcnJu%Yy7?+3j zT@Oo8y`FsKz&F*{C z@a2zf4UNYh3DQQs;9qUOA!LHX4RpajBllBN28;@m@J(9utYoMh;_$NvAs;F&k1S~A z?^r@_ch5F8($n)2KbY)1?Encjl0JAtgm4Rz!4(YfinyzA7$YMd#}jwhI`y-UIglng zzdsW3=<#4RUnJj7l=F~d)bPg*ZFu=lC=r*zj|T@o+N`II+ErVOV#0r-`b>BEKvwLB zclNE)K4W{+!N&PwZIi>~tI-%32YpUo6 z#w`!InqHNejIJ(GbPvDhab|1lqrYP&DrsW6Uv>3@w8I~oVb8w6`ajVOYnEcqcDER6 z1Gltf(v6HUzRY*w6QRHunZzrXn3!^%v+}rK{4dm9S%J*dOj3z{_x8g@7D@sh6JuU) zqsqfY7Kfd#O1#?5t#W^Mspxp`^$?{FCC-D(P%AXCTT#}9lL?X+x=CGVm3@XPJe6eS z`EYxo0Ooov`uzFxg@pyyUH7ijjRA6D(BOs(CJE1{PoF-21ps{IkMMQJs~K^_VZ}zr zjiBFq+k?bD1$T`2bgB_r~FU8S>j)$vtb zBl0kt@xC$%Z6)u7QGnruZgjVdD|ejT$+>trSc4HIkqud=frM+zIGg8n<-@qPM# z;X5v9iEOm-!%TVEJe7xUe|yv(K!N+bTa`VH)QZ`dhH=spx61L|FPG=JA9F8ff>(8v zmaff90#wrG`Rf%0VPjB9rM%K(8DWJqyUwZVLCqcdzNLHKEf~}Dyqw+BwNU~VLtLa6 zBp5XB-n}R>-2OfXv2^7j5z2t?RkURjX*a(DgwIUQuW~9^Ob6dy6J4)z{%3^b_nm-& z^Tn>lML{o(V(RwpZrE1<;3Mhv_MX^-<C5NOWGisO!o#OB zWVzVc_1Zv!PsEA)HygfBH>a*5t_F4muM>MMJk!cC1Ff|0hEsVVz#~Kaa8BFl(sF~Q z?88P%M#lZA5-ndLVJqr-6sg>V8?@G*fJryN zWiL#vK=A<9mhoiL{$w_2{No*m1nIK6?@l&13y?(vuaAu}5Xl+G(Y?I9b}hx2n3y^` zI{tDY((>~1($b$Gb8<<{2eXw_Hf0Q7zkYRbb)6asa%s^2#~nQulX(|=veq-fvDoT& zHwUrI8EvHeuQu&p8}<3~=eeqM86(2J*R0?n$t?G;;*=+6XF1mM-Q5;T&0c?}rn9^I zJq?X3PpU?VW{vF(hQ>7BmoHy-Kavv@hkwNUC%1}_knq{FXB-MpC^R@AAhWZPQb=E98nTd(h7qnNflg_ z@n4?a-rYStIHJd6*+eQu>WuiPYC4hh`Reoy`sMn}6_7}jK+y($(8+2S-`!F^nV`3R zt1lr!vE-W|<2SDmiY0MTUUsl5fVqYS2TLK5HvS@nVq#(!!tt`y7{v}NPCUUFq@v7r z-=8BOOpPgLDQ6OKdVin_SWYO-$Fn^qH#s{wQIQfuqeUy^E1X^a{cX=BXTHs*P@SF{ zTSi3WSyZ9Je_~d|sAHs0PfwMDckfPm$f+nP&o3@2jM}1X)HD9@E5!p95@mNKLG%f- zlrhqIsw9WIPeEB=Z8h`D$ym`0QIEZihjWN>2f@SL%MkEh>M2n2#J!i9!Hz zv8UJnw+}uC$rY(5#>Z!3gaiQqfMX*|Q&Tln)zj@Us`%$)Pt?`p-YX1}5X$Wr7_v_% zRHLAz6y0S~IcFE2o!+7Ge|nPFtR4OI#}l=o?0K;}m7PsFi8zJ@$ZQ33JCaGX2y^S|>N4xs zV|6_%q|?&U5)^E?0?n4`)r|<<4UUdtU5IeJ02Cex-K^udx}J>-kIl@qx$h+=B@sMz z!H8d?lp%EVz$z>ZgF=bBo+^)`n|4RgJ!A-apJSl}npD0?cy>+D-rlawI1Po{&6F=X zwmop!&9bV$8p8s7?vzIT}<7{;O(vv<$g)rw{nLYV%>5(yfb zg2uVkF9?YD_xG%steLy}5^4|Thwcyw1Hpm{{e~*PJC8uou_oZr=g)vtzD7!B=EL3? zs(|l&;NK!l)YO3k8}qZX0fB)}d>k7)d)xh~T!QS>Par!dXF@h@mU6w{od=0qp~hNw zBvk+|9v%geW`2GB?8JoH`?zE<7=C{?l1DHeaJxTUruXH`7dtNK$Oz_0%A_E35;RK; zQCL_w{<+P_M1hi+m>3+jPNzY?yt4AcE8NN2&z}K#syaz}lYM%XPpoEd@A8SKv$Jz= zV52B=QVBv!Ow1TJ%=ZuNH!0RgfIgDOPk@Iffs`!d=UwNp=!E3nwb~UvF+T1ou#_bh zEKd3Q?=pshg3{d5Vx8hJSGCcfz~FrE)>UIWQ)@RTiiC`W<$g6y0ex-b+}R97dbU%w~tTsH^3 zPF4eN=adBn1^+H&8yg!p*VnxpE({DM$Hz`2yavuI?SZ|$(xSbSMQUkjX@3{Se`!l2 zul5<MCuRZnf3x)n#kCK-WlR)WcC!%)!C-QC>&|06;gR#OG#^y@Hl;Zu-l%mvHg!!VOF%YwKX+W zRZ3ixoSYnIPq!|prC5{O4mJr%#NVG)6e)kXQQPo_3vhqd*uotEV$Fm78IAG~scrf~Z)(OcX z@5&Mj_Vx2ST58dgqM6AlYk@||_fJiIQGR%Ymk5@Xyn^kg=%d=V^7HA!%nKjl?pN@& zN`Bv^Gwew?E~UwZRWCk38_9>2ty?xu5q6ExccVGzD2Oy+aWqPzVq$nG5*b2%_xJbJ zi_MJg!6V;wEQOMB-A^8ctuZT(GRAJ_eWRUKqPL6L^JKfMZhWvc}n$5^(4 z?v7flIVk!|&xqk8Q{`d>!9~)%!1*9?LrXhoUG{fol(;~8m!)-KO_smo7e4- z-yZ%AJKI?g@BaHA#}miE&VE1b){{xz_kG0$Ly%(zy1R!*I)^p3Pcxwuw${L;4?H~*+i6bhkWcZ;mI4$klH$Tf6=RMGnI`-{R;p<@>#Z3)2dV0gO z$Nrf-v8HLwTEQNFKbh=OtG8A}sMINlq6*!j8VD=)a869 z2ev?YoaHP^DpM#>^6_S#hm`v_jjTcX&kZNaTWrrBOs^cHqW0ZwiK6%^rb^!UcA|zv z*Im?HEHqxo!HoTc4`%%qF2f7Bl}?D}p;_O~a{Zz=@LET$_!d$O3+R0>yjpJ9wy?#J zDEiNHT!r@N9VUt+&pHLK!eGL3oUM;Gvu@O`AwePr)-Na9k~L~YhWPKuyNYNYW~;5$ z{``-_BE&MfsHkWf%A)uHLl0cLZOzY1{IvO_F@m&Ah?w&MIh^X#7Tlx%?Mgc-VoO0x zFzmkRgG4+F2BOmK(sqeyT~M7_`u(=>q`yXwQ4;u=cBdvIp1}kMih4RC@0#5BxVydR zfWKB-A?u{S$Z$BwxCb<%W^BQ&yjQLB(~1?sqccj=ZCEY{CsfSfHh2ABY}?Mu25pcY z!(d!L{3)&VU&Jn??Zb@7cQ2FS?+?^Wwr7Pco+sHxZJ@5ME&;L%%aL^3newjY`$_@- z$L2wwtp94wrWpR>Omhh~SW3Hzq|5fKW%=J-;lFzGS1F=T|6rBJk_a<0A*FxuQHjFUKe*2LByCO_8M*$ z#c@V&=iJyfepX>aE_{2w4?PTHi#nKYzoQ6L(xU4Dq1&DE=O=HTI&_}uKTO3g& z1*DbvC^8GCcL5xS>xZ4u{Qp;N?;X}e+ir`;f+C2ZB1ktBr6awAfPnN4(xnR_fb@=q zqEw~#9$M%SdI0GisR05(dMETA_+8=s-tX-FeeSdO@0{yAf6kSe$ul$0-0NOz-S@9oQ7r!ib{l=F+>DM^SeYs0G%5jT=&$c=H;$ioaV?Ux- ztKj0|B0D>~u#mN%1rP4mGsCg1yKFlMr%p2!p>4quZ=4%6zd#c2=Hc^`B^)N!l=u>c zSaYGbv>P2?$lK8129Y-m!&W~U@QU4HDew=nipV{At30~LY{CP)j3;!wo|P7G+6r#T zM4;{Zo@ZlOM8B5q^Y$$9p^1c@CtuvI#-qO8pYZ3w@`mo4Y9vaE@`#E(B~nYPma(~XwlCotOWC4Eb&Y_d>VKldq$VOoLU~#WRLov34`%2@kgfwPO zH-dU)I$G-Mj}#53)4`J9`0*#9Uki+AVY)ZA>>duOo@XfKA6$1oIXgS^I@-)H!q{GX z%Uhj<(gv=M(NmR6_rKnBywWDIT#U|^^$>2$Q?ZRH{Epx-mcz|BIlGCqOA-f3ziF>_ z!ucb~cn^q`gAd2_O|DCV@f>+=Szf4U+$F}Un{UX;Hq=UlZ8MESW;KrgbLB55(9eL3 zj0_EtVvpO{+?=ko9yvcoE6_(;_9rf_tbl~NXN8x7i7f_Pr6pvj>1>XcHRr!3-c#6K zZ1RxQS$O+>(Q>hXoY%*RdYzZEpm1fWvn6_&+!Hd|z!qi(e9>ra3GXOBx(XsFG&R=gTlxUD<}Pg4`J z)W2=S9nCcQSU_~A`glpgH3ni47xi#{S7lcOf+WTn3}&(mso4Ok8wNgM+!uUA&^zAX zv9FvaRy1bQbhgeyN*Wi$Lt5X#0UHi8C=)D3zKqzg%2d*E>$_MjDMm+FgE=%KRYR9S zAW!X2ryW5NNygRi)3-%#Ze=AjHP$NvgS1w#un&H5mLstI5hh!s+)@w6;U8M|_bCNo zOFtolc)-wvZ@SOtG9R`?CnZ~L%>OnwF_Q1eVQ_POh3ga^0`HRRXWMM#q!XJt`Mz$= zmvnx##nOxI>@%1udj7Kb#;g2F>yhQ=Pq(TWS}Lpt&(6*oPnVOx$SN?hYO6cy1)If3 zq_!Y@ITmJ^<>nSyUTmI-cTCbz$WnW>9j^Bw4lE&e=~@<@-~fK4VQFA152#TW80Ci~#6iG6lTZ3TmroNZ>gtrZJ%1rM*a30;kRpfi?b_(Iwe)EcooJQmxv+i% z-6c7qcT*Cm3U`&a(<|1+g%LU07$oih&-?L5{zxS{yEvWVn{N7tIJwvE=(eK~yR8$5ltOmymb)C8+8Av&d z3~C%q&X2axu1<+ao!So9>Y}Y8Nz5>xZ!JeVy+3fOQb55<>BL37ipc^n{xOUu9V^W-IVnnh~iBm;S??MIX>{kC-6^Qh!@f z+eqHgcgZts+Lm6U18rO+keZSfqf-Ey)EYp6rx*CH&}b3q?sKo!$TW4O>ZWw!kfUel zftgviw_ZFAm{%GzEy$Uj@_+@+dk_3#s}JUn4N1bA+9_!jCLQlZ{tUYlBF^YEzN1!> zEMqpOT3%7HKMYZz*_(DIFh2K8LVivNX)%hAWyMz-TjqG6+Xz;So6-aN>o;dV+~|C; zTACH><9a$%5fKT8vyMV8kz07x6X|o8TSM}3Mf6?W@bYp=8kLp6%ilF=0u^^ zVAehbvo$$6T*C!~IGGzyVaZ_JgE4Y9^3hJG&Knw&er#8L3EWZ7mAJ^mBqSt&K;Wij z@0T*O&Z7-Pi5nUfu!5`bA*)4LTX3uhRGwp*)*dn#ku>~sg)K&23+D2+t?+^JaBV#p zUoS~4jV+u?xP5lt7{}&##mKmB$3s@G%gqkA9gI)0y&0p2s|L?Teh#bJmt{8?_<$AzNvGHMI9gE_jQQH1@Y~<64t0et4_z9gl{QXG_+{@O8B9PHohq#P z&KA@a&U|i-Gjj_-iu+q@7p{1x_{U|P`F}Ds^VO`oy5OOKdhQi9qCab_nH>Ej~ z4OeH=kKL@7>Y`+_hLA{oh`OMlAS63`r&u>+yhwlJ@az(E9@ou$tcuWrP7qPkMh$76 zr2if*91pu=J6Kx0-PztQ7nwcup82T$;PM=eoSYmh(vQ1EK+P8>Lno(hU@%RWv|vV| zD&~8Etw-y(bh^647<=zZi?!>92s$mdwY9A}*9Cck8G8f;7v!tzB2yCOqdA@S#&sI> z;k9f-jEdGx(sqqgrA}rtA8v@KM_9d@eE0J9-Mgg3#5Hww?0S`7tAFZYD`q=F$(~0s z(bLnveEI#eNJ9B>xb^H+z5Ffh6C%By!~&Z*La_lMO0=PVCv!m$sDyU--s0%S!r}0%%X51xtCfj~x3aQ!*%nGumDWys zi`~u5%`gx`oj^o{l*8y?XGaw}R?e#PyFHl?JT+bGG&3_Zm?GSn6doiG9ZOWq!6#)O zEjBzK>f7bK&qyQWyxMeyDIqdl{gtsO$+GwJF3rXMptxR<>(&%(Q4#=P&X%Pj*x%om zl9D30^92fJIUX#fm5rcI;kQqnw51ksco)ZRh*d;hw{q>EywD8v^sCNwd3lUpUd5W_ z4{&gBfIwh5t4_Z9(uj&Ujzz$*S27RJ==4YRPWt+=_2iV zUyLW*NJRq6iHYSUCnvXLERyru^rea>4eN(|xl2gm8{&PkGk1A;iRG{|O~{^#`+BRZ zM`}aEf`iLpFvx*6kb{GRp1$qf%bNQ7!8GwStk%ZEdaK@bOAlrfLoa6!Kh%b57v&B+SWc0Azgw{PEW zj2AKeW6m8E_SxCltIl<+tM5~kWrvC+U0q$%#C*(ki?yKRK{UQ^u4fYa35=|gmXRsY zEO49kK_C!u!TKS7SLd_c-Q9XcuC0Lte0+S@^O^f1ucG32x)f)jYd29kx7Z!UR1G`X z?WEBuF)C8eM|rHINIkd z|GwbM{Ym_G(|Ov^T&1M(1`j72FdMeKH8s`99h|2P{p)8mnl?7;-+@x*x^`2QYbU!4 zOqH++Y~d#Xg(maZVs{k0q2V95`la*gufjrB3W}t|4Fq(|1`qs1T|?t80Xcndd2a5C z7aES`4xf?7e#*FKFX1OTMIvbZXm8x+415f;|R{cy0V=1Vvj z+*Qu%|9-N3DapQ3j+Z%=oY#g@z~LDemt$)nfo9fXpJfHTTqM0(aHNi+S~Q+9r;ZMy zp`l@aWzdNxXtr=C7JiK=efMZqdrO4-M`9=vQF&PV4#J zZ7#2*#3u3qm&FtW+SuH*1%VWpmseY_>gka);4doyNyRv+YejK~uBgwq6^#U!Zdf49JNLSq9#n!+6H}iazzgr&&0Dw&SlEAjMc<5?vcibrY{GC~sjq!lMKy}*R5)R`; zfOlG*Y%x9Wd6Rek%y?~Yi49*{P^)h^VT!+n}mx&G`>&8eJ_@Js&UNCnWphIn5@^Ej&Ct8k!j5e*7@uN}!~q*V+4NrsakC}lOpU^S68P_Kt%8f zq?|0U+s8dfOiY|NwvP0DMzEC7ZO)a{UsYB0ghTR4agbh7tXnO14Q4V1R7*(y5N)WE+@VUt#0g>FJJKS@D4mNSWwit~DF z9GB!#??p66a#flf=2~d{E+m*<@!T#>-~&$u;FCHF%~a3&BFoHV@l2m6K95REOPjQH zb#OSD3!-60-IR~aX6#9q_~Kr&tLlR}MC|VFj^1dWqv&y;rxbKtT!;|oOX`;jybmPR z`%&w((s7LhN}4XG+S>y@0{}xr?%2kse}%CkJ(r)KafsWnfqwl9q1ej=MQqLf{rlO^ zu&bx1Ia@Ajeqq5y$WT*L6CxkO_*Lt>h2V845)cw%H>``kJ|g3-^JBDegL@g#JPct3 zLKIWsl#y^-_MNPx`BmzH&CRp3vgmMb05X9)>3e&7lGxxY1+y7j?oX1HC~P0fl3f`{ z0r4ea>&4j(>r}tX(p_D|l6?_A<15^lQ|rvy9hs5k5d3b#yxs1&nYlu7$6l%F^wrl3 zZVGL*N-g+Nh)V1{j`UQuNDQZ)^h)5TjgrLPg8Obqx$$Dr-efm2fvRE+m?NZ4iP6}a zGXb!{%zyQcD1h;+#r(Ilr`X+Au6%!ID`T*rhF`fQ+xdutgX_3uYt{UN4*?P z#Fqxs6J=&;9?N8Srfiq{X;%gf?rOOsKKuRrp77MqBD6U7Iv2Lm@ZM{5DnF7O)&iZQ zOWZE)W1FJnyR1k~ypGPyQC+B+y2@kF(1*VDru~rDJ^K&g$ot42-g8isFRg>^toPSm znrh6$qUmRkvXe`}GEFNDaLk3b{t02~v4Z-~EsmNR3&$O9C6Od|J{y!t+unjMiN;J( zKeHsRN$@OBh8Ii89T)OSvc^5<)bD1b@LxR6KMzo1{hwpO=cP(tet{DL(nL(f?2x7C zBSoNpmw5eAksTYn!KWe76Gn5fiz1G)wPvzoH4FTHr8`|Fx4P1c@~D+X9QpPm?;Cy) z+BfR$>VEwe2Pbc}yu5sRdRmiN3+{P{hlj`b6(-=mlO7fpCX+=b>Uj`V+7RF-#YAez z$$)t|RWDOv^q52zL)tiZ>BMpqBk@(rXptuBPhEHJ6ih5Z5c1N&d+^*rqk zm`{;MhUhb}_&3h!VcQ=smO`!&P?KIa-#TWNV4&|psil$;Mr=}Z5hrI6eTUCRZ14Pa zmTAuff4)Tud+%T`Ka!((5`QkmW^|p$%q_C;X^AcQ{F`2CZqh%wbMb~)e1H#wdlSyBkR4s^Puv+U|QozPVj`k(!KH}NX^jQ(~CW2 zUK=<43#(#X&RjI*%(T-s^lL?6-bqI|RZ?VR=9mq? z?L_*>8sk^3uHIgj3+?ixB;>{EK2ui~l}f?XVUuuE5=#4$_hKuxh#axML4CBQ5_cbQ zSpXj9$SX@Biu|JT4wN(^p2~z_!;d+T8tQ}|_(F=HGPvNd0V$-yUA{E-sqg~%=HS-z zOXQdmo8|*CjL>-3M^3V%E~EPCl$JkD)AF=KAJ8AJJnkj zxkCo0ALB^k0!L$Jm`PC;Z^0|J`rm(mSY0+cHlbv}D2yJrWR_cXuS!n?gvxC1C&zR6 z^wQ~yaKo>%bELQh69Zgc6})1e`$!U34x%QP>A(d;8TwV9vm&eF%Yh9M2Ma-%RJ&i5 z3tv@^V{JEeEHoyM&Kl@}(dz7UuXt`#mxYFg-nez=>HR>@!*!(uu7J;PLqxrf{DXq< zfh{d9dewGH64ac6yVd9_N@e!@vXKKY>o`9pO3m}VOYxC@NnDdY#XjbXBqn~r!EtHh zGvQ*JgKcH?@t8i)X>Ys>0|GTu_C{EK{b;v@gXL+B;L>7snyg{* z$WMeWgFjJ6ynUv!IZI1&x!+7lIU*#CEqOFXliA70CcG^E1w*cOhOae6({!BaqZXp$ zrX5l8tM8Ua{KoGFROALq3`%|^g_-x9V4zPrEA}h)f(3tAeK2ZQ6&`a`d!+oF7}sP# zgap3eIQI-jS#SETy1J^ZSMoiS=lyy{T%SCXKKmM1x$CF*xFYQO)plXw;o8tKjT}X5 zRD&Q+8Hs)4simW%;~Xpln_Mgojg0$kL3!=9C;5tZ8*$2j)x7QQ{VjA~(V z0mJL%d(U0m$Ey!1USO>H)^z(@-W0)g@|qgBN~M3dJpBTB(a(F%YDD=+9P%Zi#J)Fu z5Zpp*>EaM+*Z8~8sropuz8K$ba<7(M3Q^n0Ta-I9{_u;qFqnuTS?9yhFSd8XU)MM8 zIVHn1Y>+PfN8? zj+>bShHgp%lruBmU}JhXw{LHv;KGcI@3*F4nzu-fq@w{(hQB_fD=#m%z0Uu-0>){% zxhwpxF7JHFu$!qvH(iNcM`6`FnORxYb~6RqP^*FD$(j#lc&2Q4B?N32+FXdho6TlF z;~=U-25?W8)n6Hn#A6(PdjZN>&reU`r^`viZF=5Um}3e)Th)Bcs23_nM@Ko&mZGYD zQZyy|d=UaXd1^(VHgum#h(}l$+0n6_WZ$Tk|F*SA%Eo3rUE+(m?$N=4HyVD-hzlSh z_{3Fe*`Ju^dnT7P)R)9x;)^*WZqo~W%1O)39R-rQ@$o%wbV6?&M+BvydhAjxn|?U8 zXq_#&mZK@(fH%x3#1rci)vZss`q=#=m#aVGo%PF~RGdfGr=AKBH_MNuv0{t|~X z?bvUv$Z*UkWWsG(a(Yq<+Btp&HjViCuvE6{4XJcDXO4Qm`sQiNQ3vXz{ABDhJD?J&EEgy+?TYI0ds&}C8~ z%tnb-gG3oX+D4~La&w*Nit6QvC^Qb zzUA6)kV;-voJMB6?9f}?YHfyPj4SEqq7Qy8M$8)etqtf0cHKi-9(WBPk%NQP0aw30 zn&=bS`U$ejj60Pv_Jzg4M3V9I{7S2+9;igh9dKZYNQ#>msJi4Lm?$%zt!t0jP%_ps z+Rt@Me@4&KRr)J39zyy*)9G}PiR@y z8_gN9-7WhWu^IR!q(HDqc}?JVN>}l01mjuHKn0(nA8RKGb*(+$6U)oR(LFRwVTIC^*c@c+6c+H(Fubv%x+0Z*q2605Rm9``Xe*N5WowF;nYlouP$7~& zUz0iNn_5exT3=P8{lL}`cySReBz@q>u}8W9=_=(+B4cea}9EA2mtq#ed7d}9Iw1rqWfD@(_UV^OM61aJZrXe{OgSkzW%RaJ>%(G z`M8r?83AO65hsX{fk*t=KZHHpNWglqENnv z>thxZT$^D z&o_boMMYa?3H4fbpO|y`&;!01BQ@5-Q*7JbPS(SO(ljN*UY7bgVMLiSD;Zla!X~_h zN<4P#mq|4WeZoQCyy=)>#PauTx?zu>=f#nj~sfV zSHSi>qk4%y{>EP`EH0pt?EUkHDU;~W?{TBe()=z@Go*ql^|po~3ZT(Ewb-N}DPEs# zNSlH5MBH<#g2QdkL#hZRL7kDk1-i2nX%gzKJ{-Y1<%H)z|DK%kB6(aOeT>YbdG_7r zc<-GMLa`ZVuJ&wo7TqgzCQJ`4VCDJBS9z^XErigfp01&ReVD~r2mE5M*Rn!4lHSej z*m19D@$=`;+1d2K*JA}*G?-})!#Z;aGQ9`V8ckLtq?8D&UwZoitj}p_+^>4D9a91? zBZt=;Ugj&FRuL@55_Ar9Z=VIGN7~I2ZI|!OHsX*uu@(-yx$0dFPtmbl95PJy*y<}z z5;d9*6%d{)VS0a+BJ&6>!>m_&NY^BIZuew4tqj01N65d}hc9;sn2{Y@vinrrWhl~wpX-1}u^5`?3_9HSiw0|D< z`3WL!vhU2-t28Jq`gG*G_JV@f?dnkzSju0j<3$=)b$n}J-}|d4hUFMNTQag1%c{#| zJ5lObE<`2bUh1+jF8MWtltV1=BSc+yOKEG&?#9TAlC?cl=OBTm9HJsUD%yo%MAJQ) z)6%dT=H@mUe4@|yJ*a#Sy2VyFOvp#qouiyv>XFj2+$|@o4d--N9F4sjS7mk;f)^ap zXwptBy@sr|mynQv$j3CE%!hE<8#}I@r0ud@B~Q88o}iq_?g$?D47of$hc~jf7g;jI z{3|Hin`z2o5)>Ud&d+vXIi@EIcxjdLme+N(#Z0jM&J8&T*9v5rSTs9fUn6p#1p!*L zq)XuPy|QWF-MlCi8DT4_d^y(tB4n+!XEIl+=%k-Q#hghpe3rUQbn@*wDi*6*P}nyB zdmWSbz&$GLZC_HX^2jcRgva=m4Skdwt6Hk@4i%6mOO3=)M1eI|0qCKVAfAf)PI;qb zQ|(LBaF8;I_S&Ozfvk&(C%5Y1Fa{$MNqvZf1|i&BTOQ%}@jb4{qbqC?{>cJik#@b~ zk~}|ub83dU?Qn!3s;o5=tyjypGyXEThIoWD~Rwb78Zg8ue~o_B9)Izhl|bHn^NqHuOh4 zr@&O4Clw)K_KoFTnmBGePb!O1$XKC5(8bw{g>~D_jgiqoztPlXACay8=T2*$`aQ4w z7N&mjg2qe9b)M=)d~)g>uZ;%Pq(1p0G~F(XB&|PuYjmojpE@wl>?4cYcR33f)c2bx z-QU}{RNyABf=zxcw%)(hki-L?YMAl&^X&6#f;DPl?iPMChb@r04`VRLvtnXmcfJ4_ z85xCy5MfI>!(|HW1)>RPgQ+cg*#eqSR8e`Pu#qD(-n=PA||eM z-O?+#fqzab4*;2SB}ht2-oGQY)Dxpq_*O!quwDG>Vt+sw{WPpYIYlU@+5i{ujJ!p! zKZ&2?`EwcQm@noK!OqT3+{PT=zuW?nI`qV})?k}J@w7#)j^=BOtE+D$3MJ=Y88|pN4<0<2o0}uP4fq=PicG+DbK+V?+y8ju zmXY_aG@dD&9h5#?TE8mA`6aC?wn#`Vq%vE zI#l2kN&X8e8X6j!tHCRm(OF^b#D0dWq13+^rZ=2%7Ap!U%ltYl$P2RSiDvrn;e$}h zc9MPL(8eKg8*^7VB{{jx%csf7$+7H)@)D`r6PmAc{*wl+#Mw>SNX{p4 zVbIs|{Q(^xgHed%UhSap7@E>|Zi?+&`El6cE;U9WhbU)JG_7GCJ=2#PVBh<(%s92D zF?K!loAAngTV$ac##3pEKzFBih{MiWLwSNPYt{*c^7Un1TK7v++FX911cQ-miFRLy$;kjmJRRIaHVc+t^&s!tahp|o^QN?{>|1bfd3AN}GwqD@^z@x@UM;9L=3qpHsVhqPKhQ1n9ZQ}z@OmS| z>DN_kIkvcHI?RblQ!WM1mcaZ7T&~?m<+WkaK2b@?tgXs-?ubHEE}AzzA?4+gfl_Zo z#OeZ~P`AReKT%ZJMn_q~G)L`eMM+K)ix!MS1W>S*Vt6o>ZWb=q3(FU6!Vd12{M2 zi{bTI+HIt3%&I>=j1w*CDJv_diTT{WBh{bCYc-gvBvIIoeFL-V()vH;G<|)3w8ezG zEw`oFD=jCGp!&>TaR2Q=cyBq8<7V)u8PwDx4*ZOw;q?3sDvJj6gj*uNWPE-1kA%73)hxCddSfiKmwzQRmQa?mjuY3a$S zDRm;~_qaHn6K<)o0<9!rH+CF}Zkgxx^Mk=+nS_^ zAieb5-9%O8ttr?BB+iH{sehp}B8?YBf>TCfVq(%8$Dsoqt9L{DE+<$O=B?Z%q_&-@ zgAvV_Z9dgvj>%-)jM^>z6aBKJp{=cbb&0XiE!M~#sI(qo{0ci+iZiCArS&JWZ`ciV zS(3ymFiVJdPBV3Nb?0lEPB}O0FPhGNwy~TQQEYgAP1F4)z*K>e<3;+p>iH<2V?!Dm z8az|B|Hu-*O1}%p1ghQ{9v(LGJ+;t{rQoy0HlxBbWpmw}D0AJ?i;?FwX}K*fE{=B- z@LDSUekeIFGaa2&?ufLsv^CGgK@L`7U!868laP?WoE_#Wr^rhHn&m%COP@wYMOE0% z2m$>w8QJtI)1Qq?###XVQ&MIE2`F$62tR*v7fCFFc^BY zS5Hh#jE;_8TzJcW3hJMnob2xYCiL+=?uKeD*2Kr6aaY9J*4Fmv!mXVX@pTPs1>}Dt zfBs);zyAljmwM9p9Q>e{V~#0MO5#Htg)+y;LmZu*`}+GKVt}uKfSucF#E_lYmb(EF zTFhFOmX@BLLWehYUjMM$#Jlmk+ng(bhrA!GGM=X807+sptl-)l6;is**lRnD#-#F+R%KNZb(iJ9?-zRfKj@8&AG1FuwLf%>(cTYucZJ>qf;=@T>|oK z#-5bp(`LhX#hjLNCXL|8C<|TOAIZtyD;z<$N`)x7KL#^Be=Y-2pPZaz(=GS6`JF*7 z;$BKb%g-P89+!yVMzpbBQI&iQ^OrjWnZ)jSfe)x`xDxVisdB!2kG<*FUkkmiLA`F1 zj-A*4WMdv~baH$cxAE3=rcr+)FKFCuS^S;jV!onN8AqHMsp#xWcaSI3vO|g7U+f{| zfd49Hkj*2*q(muSKH)H%bp;1oYO9_5YdVe@^)}*w_DL||3 zYi`&j{ui~kPZuBaPhu}IwBK@`8vEaIfqhKk0|pLthn*m?&DnAphOnvPMB~+ilBU#C zM-BZ7TL14Hb_tXhijN1Mr-miEJuSO%A7^9giLY@QXs+rfA1gs*&wR&e%1QKpnVdS3 zBe7bg2=pfkjE_L_ZPtrcbkV!4E{3Z004Px1$x##YVrZ(Q5XV7p?> zzf)qTD|DXKWL0!hU1cFg@5$@ldD^F0N-)-&%R)o zJ~Hkc2DPTU=hSob&E9W=&*wNT_e$sy>S#3x{knt9{!Z)3p_z=IzTXjQq>K~UqSz~= zJQJ5c&GHR3^iHz>r-G#@NZ)=lFs=2=bWHD%Nr{iO`1ZM(ALTiljq32Gjullm+tg>u z`t|;ZfrGbRixZ!y6oiZ?T*ZuWO_(hU3XQFNcQ&|tA6)Eqc0U$}&+ZJeoj)pZGajBO z;3m9U6>vf4v$cv=lIWKTa9|&#yi&zU9jC2=+KD%@Zi-qrwJA}@v&D8c8IC(1LkM;z zzS9nYia!IVVbLRJH;^iBMmANb$mUb7Gsu(>&~_aMj^eZG%!#M{)|c#RdtSRP>dA{x zkX%?6&rYg8V%M-v0j)*(hKHV=mOy2y2hg&8Yr0ZSa0a4i!7HX5j_OYM`n;BHxfE!=n191% z1;>e&(wEF~!-mTs z7T^7j$GXAa7pi4#RT_IW{|&h@Z!7#F(eH99fBDzL*mZ3LM$V^tY_u4?*DkTkvN8^P zgKyBt*5C&&QvEMkhY`e`Fkaqs@2Z+(Nd9H&A%$CVlCb$&-wG82>UG2(m{1DVa8YH1}R}aK8a_i5mO@# z5xMY5b8Y=pd3}C?LeSI&0R3DkiO-&YE{%F0WnWZnfD^(t@ivhZbpNC5!H}WaiSF(6 zo7jE^|8#N6^6scw!}OxMo#$EtreGiqg61i#G3p;34gL_^$ECv!54>A{7p?KrL`!F_ z#5VjYMdWBg+MGyfulfSV&NUR<;lod>Go4zS4|Vz@(y_$CZPg4WOQ+h4F;?)*9K~_T z<~-x;%LHD0+6UP?pwHJ~)Zt&=YkQBX`d5#WtE`iez>S zF~z@o;8ADTwHUK6#J^6K;tg_B>h==zXrHZ5P{E&#yr@o!r#<5jmFI~KyTVQ>;hff>K$1AE1JM2ybMY?7vn|%9L?KcKdUP649 z`tjD2UHRu+Pk{bi!l#C&zv9kSQUxp1cN=T>2`y(Ts$=WVj)Ti+Qq~%ex^|_6#cV1! zt}c5t^6e+Nlh|d0;71Tl4LSnzVY50>gl<=p)QZO76YrO;2~hyy!m} zBW6FKwyNM-F(01<9b>AYNqTvd-bM#7gh*r{)@jKPfRTzL|C!9ypp>DW6l;l;hG(d-Iqoio$BEYug+}ksaTK){F<@Q`}b&3Pu6D3j4bdc zl2o^*2NIhpJBH_Jwi~&CbBbfeVuds&x2E=OgsqUDduwGBocbFR?TR%IJvEL7*d=jI zh$Zv3k~fP7H5u+f%;E4XXsvZ^BudM8qOsUUl(fIdjgRN=B%W0Fw-|!m{ach%LcJqd``#k2cjJv`D)8>Q(Ac)w(s5%dg2_C&%w>vOK-p< z8SfaiZ)fktr#QVQ&!*F;j{l23`P32FS;511vlCX%CbnPd*?zJuS4$xrGBvx(x5h#wciUH zNUl|t%= zDFF4bm7DZj>kHKzN=ba+?djU>?d_F;lq_<$NHbEG?K)7)-0HUSQaZn7RP7F^J5XHQ zvk~!)@IlGi{5$FPQ5)FvsI`^=d>9B}Id-#<%8KB|@3M}T#iA1TYELKqOttu7-;il< zn8`}VQ8Z5TLJL9_@Vm_SRms%S7edzv-)e9ar{u8LQ6grtmwGb+oBjNLILzn15LaOz z9nrWdBDri!kkFcRGu^=32!iz(|NqK40DyEwhb)nFQ%4t<{@z|;zsm;Y+$?eiE54)v zBIYMFNeVx)PVKiNfK1@WJ*Y;mvNR!*5h$%@cl&j8a8?$bG=Le9?;wtwKHuHfr>LMn zw-i0S)EkF{fpXRJFE7vS3)CEiQU)d`CsC+Wb-)vV6~QOG-k;dF4G`xH|J8ji%pW;hqVec^IuX?3%iEeV6R#8S~TNMN3P|G%=sN``F}8%==V^E&aqz7j>N zSZnh&@W^JN#HQfbzu*AII-#*=ZH93!(aDCtOuYa5TYK2vM?4lTF2|`#YdJYNNQ!C+ zf{2dIPLxheOq{>%`}pzW7*uDr)4!zY@+_83|Nb2*>lcOk z)!UH_3aLIvlf%k27QL~@C@(Zt-1LV0e3z$Ry*-d3Y-ngWxeWm2X54-y&Fj4S>*B(@ zNLzpE9>JZ~TBnt5`y5gZqrRS=x`=xmhIN|mqzl7BewW^kj*h;*zSb`^iI;{U3e}>g zKkw31+KjDlXLVa!Tkr1f9#_X78%{W_3_x;olN57?mE*sE|DK%eP2;5a=FJ;LMb>Up z@~{r^s|%<0;3tn?D4W;c!mj*JcnT18rr^CX9pe~RNiQ!i8k)2~0t!^8A|a)K!_nsC zd3>oa=1fH#Q>mO=AJON0ak9I)xjC%7y16-BZqaKqRuJRbvbniQCmU|i;JzzHGJ-%L zkjQhf=hz}5m1F^6ucP&gLfwjG4HeO))z!CC_o5;rAJB*;M@Bjh>L{m)VOj$4fj}S# zQEX9v>uVsO$A!n7qO+BRh^W--cso7)Std~RVK`OvKe~3kBFodr4bRFl+nRzg;i%rg zditAhk@4BSUFZl4LHUz^Je=2)N^hChlLEZTkND?)|GV|^R~xYZqUhmO_u8RnFaW^# zgn$9STu@UZP%)`U1pqL-U<#Ief_=L^RlT$Gc8SX8YAul$K6}Pn-xYOg#aD<*GiBa; z)m0XfYX7u>7rtt&@Jg(DF(44m2N8=@X@;y$gtar38(`1AW3IvFr@x!x+x)EBaL&uF zqxx?#Yu5Xj|KEfNv2+@%F{`U0XHqY7Y^;ff#n#2?KC;@r$$9M&l;;)C?T_b{$|#t( zaleUu!)}R8Q^|yHJH0>AUO-78!2@y9ic%{~B7qT}IBCVp?AEVJ-*EmxQJkI`UsE3O zexAxncQTM%0Ys8d|8_8Em|vB7yCa{cHWnG|OAi8PDl{IHVz37o`R zU|b?s55)IXV%t<|sUpLq?jIfP?}O*W-BBEJ0fUznHD*!22IJuSjuFLMn8a$bx_Rei zHY)BmcFzp!)z52ipG2IZ;NFUfE-Kbz)kX+Yt#{*(5E3?WLC3|O7#7{!8<{}BG{*u2 z-Ew8STe1xUH43cP?z8Y4eGeegi};%cS@xS(Ve=cWLQN2e2i>hTMrzHRfQDY!GjtYv z?q_j}j#CS|zUzz}AgxLnB$bT+GX_46ZEP!{;XXs2RUD^=hfR`L>hU?QH!8NfGjZAW zJ&#Bbj-VFxJURbR$8pJP;uWlmD_5jpfvIZeVKv>ani2Oq8qGM}_j9X-n33zdEYHzU zZr+ugJq7obnBnz{Qjx0H5?8W*MZBHEPKkmpS}okc0%C&7evYhtp?<(>e4OF=vJDG znu1V7KmdBl$!EoVbkMV^PcV%Oxk3Ch@0X@w|Tnaoy(|u4a0qIK{Yo=O4VU6S`)vlGfU#@fp4Be1{q!k&RZwD*(ha~6(JLHC z_Ep`*-IaUdS4U`>fG^p50XxmRFSn4A<3hl7rUWk zyK6GQQBSvjvM3_-(7)jEe^8{x4u91P%jxPAi!z1k>NsxAP$|@nMAOUFq4uc4-m~47 z>lNie+2R4HaRM0uBAz)=ao@&Hh}&@;zvK6+j*twy^Eh;k>7z(_ivfjxPL#KU!eZTN z_EdgsNTdT-#w%Q><+4?(I13=XRoVmCJiooj4+yTHuUFfVc@|OR2)9p~yk51VN~9XD z)A%!6-Gs_ta58O|BJ}O9k2~M^}KUwD}xo`XMX~u@`$vcxDP$K&a7n9KL zKiEE^GXDgTpI7`BRuIw0x%rbT742{irNiUG*_wsvX`q6Y7@E=A=1;nl=H_WVEfx3l zl%pJZtrg*o-$TFc7y%#eKKeU0q+gf4{&x(>^{fA@jx&OIH#h5CHeCH? z?1nM}wi`$D)E0K;T8}w9J@%JtYig!DDXAzabCgp&uS0sCM(zNH%@Xc;xLs0O0zXPL zDrt%kL>-^qYOZtOCr)oEP|K3>_HGz@&w63+>gww0dFE3Ym6DPY6XTMV63LyQ*xlWI zj5u9fTs)7@BBG_EqvPj47JII!q}1QtT^o_GytD+#&Yte1B)B7`r#FRRv$U~U_aUuH zPj5Eon(4H0@Y^5+Y_!a%e#C>Or$6K6te}wpZ`B$I`ho{ diff --git a/Documentation/position_estimator_app.odg b/Documentation/position_estimator_app.odg deleted file mode 100644 index a6fc6737337467cfd40275885016f66f10831f48..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 12160 zcmeIYcQo8v_dh;LbV2l%C_xBDuhDz&qRU_~493ieULy!Wq7x!obP~PyUL$%Zg6O>j z;kzU^Pjc^b@AJE#|9^X}_gXV^_Um=_+2_o8?|shJR6#>00RXT7fC`sM$y7AXw)+48 z;QGM=000gU2Qbnd1_r@kP>3Z632|}+K6bR?bOIqD2u>#$*wM<#(!~Mnh~%_^gJ8B0 zON8d12p3N0)Uwe5fa~WwAs7kbbaQ|{kZ^N=(me*l5fCRwF$QiNEb_A#j%z%fn*-DlA@ZY1jKKx&DDvGN5l4^%7$JhR6#3mS zk>9mNzIXKF7dI%x(O!(f7Kwz30D-QquAHvCoKA2XAh)ovFz|aT!yl?vmjBU%xxk^{ zwX7_GU?}){=m;P;CpYk??zM&g)~IXU-%WzS!3eM;^1Gk^EywSe-?^Neoc?3$~YZTwHv>AK!mkjc|ZK|80-gx*V2H4locBVgdb=PeG0lhkr|Rt^0kXzguksx3Yr% z$L`-Ig@=oa7ia^t0wF;hk0D@J#-En|7{~t}t?*w)YXt|n{!auq7w}q#f$j&p$Zrdk zhe7=3s=S^)@dw{05#k6zLO@UsOE?&Wbb^cP+B!La5OfMI7Emz!0q}2iejvXiAWn`P zRv;u;oQI2>hl7icgIh?Kn@@y?UxZKi5A>h)9#~n5{00!<;NjQh77*d%7vbZ30Q}i_ zt@RHU{nqls4zLvj330UHuyTQapA~UUU2a7_ZZ&RRoj)x2FO5F~E!{1lV1zg?*I(5C z`2B~n4cHM3|L!4Ghy@(1@%`@&1a z+;^p2AW$m~omLO%>cxDuRZW#gg13sBY5_j_a8`-CAJDZ{gN`H@r&Uf!;I?bKE@ zTJTgYU~J!wy8$H4L6U zkGZ!H5|0I=2V&RCiYbl_E5FK6A)4Ip5tX;{NlnCFjD=UzVR1fbVFC{)8?loihGvg6 zBc(Xg{6g@=!(oU4=0dgZ`$?}uOK9qaQ?<`PNFmUgft8z?RuR1SYCNMlY&X|raiT!Y zRAUOdm}+qY3$F1LyK~#EzHGf}tDR$-79${oSC@%AqT8f^%#|@~KXG5gcMPI)S%R~& z&k=@>Y)!5)FumzrGpN||kvgDRp#pr|f9@Xf%#DI8T~-C0q;aB%yW|r_8d$lRg_^%8O^Z7X`R=>p1kct!(pi6&f$*op82a&E@GrWeDX^4*}##xWLHif=D)xPp~-sh>w} zQKX{Pw_~EaVc;9yY{p$-k=^lU-2@281!gPUx^!SfCD2Z$R~;M^v<<_ECfBi9)A~x7 zwWLaLUWXm>gnk?bAY*;&lu)xT6YjqzDQ+heyPRwJnE@4jQ>!lI(^wpNAld%bY(fz! zQ;}$`3B;|;=!JkmS5IX)flys_o+9G}gU&$8MNMs_jf%$hOVkVF0*H?1&6Gj4Ztt6; zSxGN$G$~u6)Rrl8&+>DB^*MPz*lojxl|OzNWu52h+Wt01Td+T0R1Y#|HajPfm0YFQ zFZ#7Qmn`O$y-t14eb>Fs58il_*|ETeRM3!HRKTO@MoRELQN-7an{;u;_mR@OrKpu| zF;TSZnS`Na#aiYV)uAuN1Q%*^M8CYDQj{hp(zWqZO;e9&NhWz6jv{~avsf3BYSTP0 zKfy&Zh{?p?|3y3gyRDID$Cn8kwL#n3?{!)R{HfzC*LUKFo-v(W9d1U^T%JxYGdEZi zYc~l!u&qyO3{M0~G(}Fl#;T{c@8xcdroU4zB91g5Va!l4oqvjl)ua76M@pKJ$jxsV zk7miYDbiWQr_AkcolKGlw#!m;G&qWiVMyo039<65O^E_+vcAt0}V$z^UD;$y*lKw47LB6fk*TqDz%=o>q}ryuVHe5H}G{K#mJFHH1d>7f4?2 z`cY7)sV8R~L~kQf$ypcZu*pQ*v-cS0(OV*}O!`0R_p)?_bSx*Gcv;{|6zV(-QwUGS z$wJ@_uQ55@()AP5SPH4>b}qaBIze`<1u2qFd&ty=yqiM{oFYv0q^ ze3x*a-R=+MY8$qfky;#u+>|{h)uZEO{>HLrGBT6|WhZR8>`lGpJe1|3-*#lOGTfai z!rsdrCLZ|B7dY9?vpry|nBJx7Ker}jo3k2WeSG$sBJ%dLWYIf~Zh593+GRf-;)T2B zNqs1SXe@cX?5#fN&Pn%6D*0k(_Goqf{Zf)iglEYer0f2pm1Y(4ljmn0r_Tfj2*N(b zUA`+CFYvORFA%@IR?1e?$Lu}~U?h+jWYX8^JTBX}eHpsWR|EIC>VS$5ywMszd`oFS zurhjZan=vdI**MTdl)(ks^_L*tr0G06f~o1FG~9ozFwv+*srW0Xj2@-;~p{z1UP*# zxeWcBsLQuWEV?F#rHDW&q%yUrD$C0Kn485qTYryE#C&Or|52s))P?A7YuIPXLCV zj?5-(w`088>{aFJ>H|obk=Z?~sAdd9Wtv}M*-yCYjn7mxRh^8>+Sb=_r4l2UB{RGm zmaR@|$aGS74rx>`=UBV}p6th?98+a9?7Nl3;bd(tex*iWEirq!NNdb)tGa?6CTJfO z>(N(o%g3He68|j9?Xz3sUKL zd7@dmf>)r1y0L^rUxDSpR5&fW6^gFQX+St_9Z=i58F1usJN8gE%v-s%Sg=&ja0M|u zv-P-RK!CzL=^mbp&T$1!XQ4^MVs4DGMRcYtyM98Kq%~tLGnh|bf<8Yl#$n7gFfxdl zErU0IC7FZ{b(*w|M)0M`+t%VOIA3i=@9l&oy*7mdRUFq`3znr^3zqc>7u_O{P3nX@ zZ*(qCcQ3o{H{7m`d$A=+ib#r_vt}xcuz6md7m5;Fs^an7Ci@XG+f1&j2&#NWnjGD{6`nvcn+f8n4NGstc?groe zo_nGUIt37sDIB_KnW=jj8M$;;gC@baJckV1Ny(p|#~1pOEfJs?+^D1|>~Wd8(<1A{ zSo2v4u0=BPUJc8JQ1y_5srHU_%J7;9cPp_)kER5lEKaUX^C(Ie&r{Wn%$Q6ySz9^# zt}bzwWSp{e-4|x&F;*+Jf#Gh@tKOsA!B?-x&nwqtIJ&;fx$_~pQ zxf$lcw2b3#Q`zsG7E17RQb6`q6n0d54c=+{RxR6ZZ>rIe;XQ9&6*yl$H5n1%1wd_- zC~tKrs;}=dO~pq5*`47fxAayxvZ|`R3$vc;?hNpm8;|`;Vel8>N3w28N@>lDfL`b0 z*e{|A;6-Arvzuit0;2Nno>Vs{sxk53 zBG)pK+zCK2dsaoX&eZ$VsEgEyb<4GYU9PJBLu`~BtH?Xwsn&eGBu=iJT!X_T_q}iZ zz1u!4&ea*qp$^I@%V=9(?FkbEK#BwFV_rp%0;)pBq64?B^bZ zn*06L&+LM9z5UjbthWHY@19`T51I8^v_|`b`3CL`s!KHSM^%;ItKeXZcvmz5Ev-!m z!EF&66T|I|G_9m!Jg@nL%WNy%*qqnZ)BAY#tzq!FP0W!?Xg*x|*yZH(Tgr`!gKzaD zrV^>nlD5ZCyPgsi<*=zr(Yyu)UOl>}b?k*QO|#5uO1XL|>9i}UdXakZoco)vCVj6C zb{^aJ-0i_wrdZU4ATh-p-W;=a)9{fU#Qu@WmI_1D*Y$6;pCh2V}EKsX^ES7sT zy;Y;K*TveddzQ0E0v`QpY{wc*I?&7}S$@olu=>i}-)OC9XUf_sw|u+GvOCQ?$3Cxe z$10tTEnlz4Xtuwd*RGenv%rMRW@B9er8|ked(6A>g-PtcPrVGsB*Nz(365doNTfxYl=rvX-9OVottjyVrQ1_an_SWC*t%n#yKwF*P zW>-Ita;E|l`7#bhN7;N9BXj9OELXr&J=yhB2|npR+3HMvM@WqATiYW32}cwkd~p+e z0lD`?y47X(^WIAFsM1;7`2$vG`P;fu!9vZlRiGO!b9^tVmg6!H!xL!&K+yZeJ~#gbr*rgGZ5wLCAPL*yiS>vUY!NuD2h&(or#9U zZaOAg`QBbtE)8bBNYPY*-C9~qcsBNh4P_5sW#64b31cVFi8JWrnR3?L-ut@S(az0}QI?YG4`O=QrC=GFsSy~xtDZDJ{=6ny$k2NxD3{e#ItvJc#u7!&n9z|EFf%y5kUMsq)$Alh5gZ!Fq@ zP{X-WDN^Zsu0_(L{k1_aaJChSVF_kJ==k=To4d7)dgagZWcOk>Kf5Z;j!oYUZ18_j zApIq0t-y-fq&<@3$xh}uH{SMAI@`3DrWWE+f8p*}?Dm;Y)oA-F=t1heQrrlsd|)YY zm5Ui|i=LVpG{NVIaA z0Q}9tDGnKMLDklwlvI5mCgWo|I$%StZbxKR;8WQN6kr$aSlDDOHR12+ zd-+swEtuvQBXe&~J|ujcVCGG`oTiFthP#t$|0=+CFDOjHu(q${C9(XItR3gN!rN_v zdlBZSBx?H`-qx$VzSe_RtMGG)>v(XrIqTs#HUK~<|1%!^d4O9r6<4Q<4FFs}6aWA~ z*Ve_s!Vv_4B7n%BA30%;HqSKG74UJWZ~y=RzLKJ>HUNNfeYjDMg$e)wBpy}B007v; zO0rVAZpmA-zN#@Nv`u?xU+JHl+r7sTT8Kb(y{D^%p^bS%j#h7jeN296Kwz>4>dR;N z$wH)*!??mqsgm9B3N{(%GL(t`J`wrEF|3%XaIg=4S;>+Z0lv7t`Ms;+KWC zt5&yfZy)%y({wtE4<6L7&JE6rozMg(^jqW8>4h|s19n+Z{cOHgBC|nGrI9;q~GZ1PFlH=lQ4Wa z?cC5{vvB-@vA0OyT$#h&Lgjr$A-|)Hy2-o7c<+xd_Ga^jIlNn)tEq4GQ62P0)-;$V zxUIHKo{)drefSlBG<(}N)nMk-r*_TEpn3an`|Wf}c)ilvY$_FTDZEFScY02AIyQ#Z zrM!dUrP-xwwPRXiFtNc1t>i>#lo&8}V&JxWwbgnBSGk4x%PqL6d(^l6o=*;AJN>OH z`1EWwC&q#Hy(bNP%jcsN!<*XE`^-D%?~i)VHuqBBLim=)ieGg$Xv~>HYNaCx;&ka; zFu7**JTH#U-o%Qg4me79*KGA}Bk=D>(3m-Yl2+YT^j;0U7-4$pDv`5>9UiLs-0sYR z%e)x3!EicCI}Vwl*610`IWylYK|5%p+i@S|-f@cr(tXHZ#?tsKl$;|Q(_xiB%u?7; z^l?hx^Y^^R3OH(W%p18$74c6xYV?OS5869k`(vVI3{__-jn8@13bUKW8(wZMZI#;; zl?6G>m`^<3hYmhTQ0#xCsBYF(okxv5RaM+N?w}^}wWEI3r_9+sr%{3EP2DYksN|gz zP2-$#+rvaA;&_rGc4~?I>EnQJ`vt3I(O2M6AoIYw@A?zDnBEKk$xORwJ*6D;wnwOP zc>5wvy@+$Lmw>`UYrYMai>mfyPe7a&YsrlI+oi=r(?;TZJY=iHT2^PF?9V-0n1hQaMUTh4;k2RciqD4N{Q0;u;5G$SE-#OhI z?6zq31v=_Akn&7cPaV#$I745uXou!baf|g&u=366sQkC>G zZ}R@nNIpj~)SHy^V#nix;giJ|cQ3!BijNl$cW|1)mP;{Xfh!fhBkA`!m0nlO563>! zC|X-AsyX32&ZcOYYWPw^9i^3Y2a%n>yzh%S26ZoMSXchMpKw`}wi${)^s=VlG}jY6 zb2}vWXv^}bw}K4s;@m0PIC#ak?)Kwd$u^ckB1*6^&GYuz#lAATg5+%xgr^X3(9{N1 z<9g%A7|ptpjf-m0sU2p%Z{Ny$u{9jnW?#?y9;zZ=PfmWhkWR~%Y^@LPudJmO7nr;9 z;Imj%+^Nrr%@r(4I(%>48rNqZPcEjH^aUm{Cn&(HGYo%++ETuZ>1*Q|uXqqV?^I@9 z(OaSI@+z8^Gv2d!Q97P{JLlc&?ry5uyP!l+?3VZa*1^!X-^^Ee;R12*Mz$mr%U?Uc zb1_&QGkH5W(wr4njwsAn9$we!2c4DQm=;)@p1bH3Z63Tj{#y2~dZ25MrZpOuqjJn{ z`jyA|;n?s|u_MjZ;-U@zfWj)dBj&@v8Oj+&1$YMwZu3| z0-ADQ-vZvI#U)V;*2oK68w*aQP*aH$x6RuKF_;ldN^+<{7J3e?h*cMk@-w$aogEZH zzUFSxV&6C!bg>efyG%7sRH=1h$#NAGI)6ZD-F^;OCyX?ltgoGnOg*J zTt4)yCVp7%EopO6$uQ~bKckw8*-~JF-*ghJfhxXW2bi%Zdf|qH{-@VM|CVcjSZbDt z>pf>=rK+O@YTt(WjR(XL+hk$cl7wo{04ra$4561yIt+l}!bpi7+=#DZyGJ^sdbIgw zKFd$}->YA$X9Nre)SV_-RaNeJIGwmGWl+OC>^CrUR8+>>1`l0pglar5wHf?&W72mr z4Fe9ZTN&@fB=GWG zd{2NUF<;#W^qq7)UgeOYU%YVd@LOpFSg1ryTzVWXrd%dU+;Q>?s+S~m$#cW-z4+kM!-M65C8E+`TsZkSM2bAb4l41+6p<>-iFAF?dxDkNlsn1 zNcvI0pKrW>yCVYJ0RR9pPL9?Pn?Ekq5IjJL1IPx907^rU4j>o;_|IUfzX8LXU@kBR zu%pZW5r=egg2F(KVCer5cYTfKg0KL={|Aod@9cy-*}%bw{}1GKfcjVWTwD6T`};f8 zwM+i*C~K$_2nqfO1E8sIuIzn=Z;5c*pF`K0zb z>_#Bnq2M1^hsF+((*n0HeHvRdhtB0U+UKmcdL5lzo6~NT$azlBq^05*rL!}~+|wNK zNRe>9vvYM6k33~aEMY26c5@we@MBo%)8r*seafpn=jEDO+D%JDy4)U1u8!s;9h$&W zW?=5VhBOGlM+=ToK_>6p!YG>p2SVsMZqZj~@4C0;| zS$DfVOk^s8Mt}ui4e^)wghyA7b6Xe6pDk0f+(b3o1L89J`DTh9tk&u2VJAEq zUzeBSI_Y-`_C&;ZGv?fF0YyfZbSAWOe0s2hhJPx3M~JXmhjV@^MMq%DZh;nd%jCn* zhx>DA4@q$@q;P>=Qp%iGxQZg;Yb`qI0$?j1n^smCE$Xpy#V9j&Grt8n*BEHS zp2+Az6(jpGja2qnuquR5solc7#Ld#Bc;EBTAYF*xXPf+J9U{h^8dl%8 z>!yub)G`L4k+Q0X^Q4Cl=jNX->`Hdgt32(JIQ zmchz%J?-5{bf&7F8MS#{R+uvGzA?$gFHKl7lrK^^i%wW+)KW8fusb z8Z3!*A?h{4%$Pgx$+tCQv*AVNq@fq0H*4A~Cgiky)YJ_KD2af-ZaP+_tF}{Q4fedn zaVtGtYc}zaQ<=!SQkgqn(O&RWV4<}ar(i$0-)=J26mx8hR0`Iuc#5$W+?nj0)1p1{ z2)ikVoci-ssEXOQE!wBjh4`s6x1@ARr?{K3-te>fq3jng2y=?iFvW5Uwb7D|1lk@H zg!-WBrn|EqQMI<$bl4j(JT(h(H&sOGscYQwylcg8!k5&*bZ6Ihy_J~eH{XFt z$tTBNW*)K$yO%|ckx}DY&!FE4Yt8tI*v8_?YK%_ecU=O)z%9Piag$syIK zHgAoSzRKC6g462jlpM#4kND2fak~17?-c8X(dN5D-x1jGaSM+y_u#7`skB+U3@g;H z`oV85CpN9%{9ka!OY~t><&*g`k@NpJ!@Q zztbQ@rU;WD0F>&79O2B*aExt;qznr}WKT@_YT6ut&O0$h^Iry@OA$#acy)m-Vg8mu zl!bO3A;}c!M&tY{SA2IfIX^#~+qt?j-+&D;M+`y|lgUCBNj0ZReU{0}zHQc~8aXYZ zJ5_!S<=u(tgO)5`d@`m5ce0D21b@MWeUKwA#NxxwL|I&>=M$xtPTM;m5B_lR9Luyp zF_3d0NRuz6Q8Cag1wU;vtZnt^>#lp6``JDetKZ!AwOKMzT6|)5>jIR}^rHG!xl9G^ zD~S;|+LZjJ(zI#A`%l!!LB?3M6G*~Yz2Pk6_!LGv=f;|%{Bth~^!atYaGKEr;#QH6 zHLMvLDKnL$rV0&&q7hLdwplT+Rj17jpnSMy2l615TM8Svh2CDkFY=70lvY_S!y4&= zmxm$_3exZ%gR-ym`v}|&2^1%jGB*C=92>T<@O-5)^R&97y%-6Xv213UCq6@#QlUku zjG#QqHQk_TjpRDiaGcwF-qU@uV8!@cbmy~mQ(K%k^fMsrm>?>iQXpdGEP{+YP%G+K zh_rFzAXglNI-nMY3{oV(i#%ONd$t^;tT=34HYX}$_qNKQtoZFv^XCPXPSxREi$@CD9ZGDX7;XlLcrQgY)oL)+} zeBqQJ{3ar1C@`-{g z+GH8YDDq7xU7=WNi-UfmzJD!QDyd`7V$UU|Ie|`4W6}wjy(sx)@|MTIN!jgE&o8CX zp-S?w^zGKcRKweTbLqm7K?~1Y_9#-wDDdS6qw-!8WIB4zA1>V=h#F4w%q-g=FMcTXB} zOC?4-jn+%MDEI?0R{5pyoYMR^l0Rw)`j59F+Kw=K+U81FB|%OocKSyL?63n{s=${j zw$_P57H4*8=0=7bH*VNgy{R31MJc38y7Y0YipDa?`;eKH0G{>jBTX*8k?l-7nuN*X z>5|bd)l5_JL}-{SX(#5nl<)2cJAG&D$m{A^Zy{{?Tqge5xo?jp-1+n?@5tZ&;CdFZ z$ldSD-$(T%A7>x}Hlh1wKYwNaWQ*&KfhB22ijIf9c=5PMo`|Sq zl=;DOLD?HoG*A7V&{t;m>@k+!G>(%usWOzQP<2(GJ_^_8(+}en@TzFqiFGH}`x36+ zxHcOx4RxR-IU*%iE!dZW(Q_Z4CiJ7QiqASKCHdLX=u9OWcxJ9GjvY{Cix8sJcD7}U z*AnP6iyDsEHBIz=1=Z}lMUPiOy+Sf`-dwI zvYT6YzCAhJQ`peB4(up$c(+MV0Dw8PYqz4Hk^ug>YWC0avxfGssK1uR{t~V0%G*B* zWq+c6MyJ1*0$kUi{gT@^{#=pvSLE-9#@D3+zvMmcp9%+l0{`hu`Ij`4{__d*Us-;k ze&j{JMCQ(arvd+!CH>jszrcX+dD1WO`x~;~v!;K`Q}s7Izh_bZmS^{Gcz(~S{+Z`G zulgnT=>FSDf6lW0ndv%X`Xv^B!}Kfb`nN0zf5Y-C3;VY$1AoKvD=YiK@^j^1kKku& zb)A>}5_J0i_RT+JX+KxxPtxCa%j>M{ml)Iko}>L0_xpBmy_f!yS=N8pSv6H|U|g#a R0tf*D=l}rUb&);b{{j3RqO1S_ 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 zcmaibbyQW|*0(4nC5VLN5v1c3-Ccqp-F;{{#Gy-2xb{5iDyEB{M^vxt|?5Cg0K1)9(bSQq}ff z%CKhNJ9K^eYwD{H14USB+VRwAPI@baTteFX zs8~!comk@0$r|MD^3=e^OE{-V3H&*ddG?jP1k1I3-5`2X7yawjJ$WcpQ;o8BV2141 zMkt8Dy$sWW-no;VF7{Pro8Dl2w1PiCHbIPmu*slB(m@JpRy$lA7VCc4T6|bdqcn_eU41X;aK@Tfnq` zAS5PlS+6J`YV&#Z;|05FISTev9YOhq!KRux_B4-~;d{A4)PoCKRwMheQ_wX-gkQv;){@pI+ycCiS6>_?Twa(OmNca|DpM{eccJoPxF(PkA@a?&bspff7; z4Gz>?BmLgiNof9*Wy*cLN9!9B=ext3(3f7hZ%2vMgHToH=o6Ja=~o9|mVZap_Fqi#OhXBMrf>9oZ+9v!H>daDR3p+VEkrg~ z_bWq|)LLmQ|Cq=A4+#s$e>vJS4RdB;P%2P6a@J-9Cw8#VnKJxIQ(Ye`Ya`aoM(&tt z#!d-Igp#mQs#dcD9jt?sQRGXN*(Ygh#eizFQqh=;fII6f;7#fFD>?LgrDUnLQ(~7& zx!>>!I-)t`=Gf_TOYvRfoc$=&W>He`e(ZsBU=|L$}rv zyC#ZKhU^W3JE9s2UjNuB$4F?tEPK^hbE`D8cq2tqw|H|b(lRmbUgN`n7^CXttsI3a_MOC`i3Pa`{ZxBFulRx)aV7h_yD(+hl|X}O++P5{ zP9u>@rTT|8L!kf`>yPibUN7G^F16v3a~6G{O74G&?35j8OQ!s1&w^51d9fI->7CKAQsN7rVUunBFIr9>u%7HTO zh+V>xO}3WXT8g>FVOaBPTo=EolgyuvFBVy#e&0!L4&4@pJ%^m1L|xslyt=mC@7!;P zc7@#T?kQb?pLU9H*2pHV$sdsA+@U{ui~^DMNGL)>C0svA?N7vr-HDN8CWC^rcvxI#B2zfAR}|zQB-|8 zpi9oF{+%7aX>)G(Yw)1Mfl&Ic^TdH%;p=U|@Q0`M&{k3mn2qsYMHOaa{8)!E9?S3J z4;aeM_Aes)e^qIY|D#I(RmH&oFgqKF?e8^v!QEO&tEYT>IL+bQ=ZQ4nIWju=8v&Zv z2FMA(HZY~g=V`*~awN28n{#^lk*TdIdls;Q*IJ$E~+e?|5nVCtQnMs`C?`c~} z<$s$LiWe@WGshE<=4tj@>vJS0x=(G1j_`@h!qhl!+MCZwZUHydF!#kfXOY?mfEdHM zHTeO5*+qc$XR|Wt8^8Os;Y0SiZ`vaBM7SS*Mg*?ZxyPzE_oLs`pd4LW51!M%aYbdO zoaLFG_!R?RCvQKsW4^6%Tm&m;srMWFdZA8O<7~6XAaLCM^)s^yUY0!$b~thbZV%rZ z8k8b0vs%-9vo(3fvPQz5D~{DC57Pu;8NOc_dN46^WXN-Z!h65MIRJ`h~+z`vC^Yj3KI(GGg`lIk*-Oc5Ak@f|1ed8(-|HuS-yq2 z&TB?*zTBo;BWAHgBY0=1dJI2SIt96sFi_HNop`-sfpgvk^2w^j9Gs`uHmy@Y!XXr& zkRU*08%{CW{zkIhztJsbBK7_Tjy0q?Z(edXAh~J9+%`~zqn4hMNoUg_cZyi z)639IyUGRSbz|+^i5S0l*+BUvclOoFk8yW8^ynHtt$BRZdT)WupYm4ho3*)(W`l{N zk^V$KK@G>e;!)|@#H6wsOFSb};|45;rfVP=BYv~aA-=Yv5&|7NFz2w$5-uI@?l#N% z$(SRu%#G2hVtM5lm^m1Zn{Iw}8(&t@gpZdx^@c};D$9d&>~kkhqHJT7qDcQ@GJOsx z=eyK%p7NAfpj}Xv6ZqUDOsDZlao7;Lpn?$`Pc$Cp;)ivXX#WNklY_Jx*AoBMvJ)2( zSoLP9E;z>eCJrU3b?F;zKDsj6?oSgV zU&=;6l$<(x7&}M60M$&ahrg7K>AOIuvZNh95+nS=*IM}+R*MEbGgj*3e0ZzS-G+mz z{IyT1ndNe3^2syG(~gJ`#n#rT!FQlK|S7HxqW$wTd+?9MY1#=^sE z8;okPzJpnJAo}K0lZBnYOqm7RB-?--)sTq)F7D2D@OO+lOH1_;!vir%IT!TM_@?q- zG^>f}+&Tc-mgP4n**X4r$=^mxAeMAV4ep|o;p;Zq=1qnU6)bP7mXT|wlif8FGBf?{ zP0Dza=ZykYORa6xjo@Zh)~w-JZ?)T|PhMAXmX~wV1H zTCG?Hg&0;5?+|O{Cn(-ws%WFSJ?;EpO#L;16+dw(WayH@J)}twOWMbTmQ*RCXd@6} zoGQ6#ae$q(7wcz1#Zjb74}$r746pBfA^jFJ5F-8{H*tYEvHH1xvCPC5Tq8;RlFZdJ z5QHBWe9?EhYq~dcxYsEj%A~0~f}ckdRJ`F;ZAG_#v4DTcKC}U0cZ+O@J~H;~ib6G0 z*Q)CD8!p=YPL9Kt7Ps7*G`Sg%NKhnKpY!m4T6~yq!JQiJI0OtLW-?}msrwtFL=h0@ zO{gpMo%aEyKZo{JHHJnG=n#GE<(hbkBQ=FW(!E1y`^wIPn68h@X@!~Q@@x30_f+tL zl~?oFnBeGWyH!ep0`>I^5&cr3gK4Js&s4+$viA8^-h?#;uQ0uChJ>nt8eg(JlP&9X z-1=NHc^}_N!>q2T_^HMw^Ep(XrjH-HQ^!l9uaI>sT^0T4OZp1E?>bx0kEf#P9~gh8 ze@RF3zuLCG!Af3K7451+xFAaO%x?Ce?7x#COP&sUu9z*p#?gxQ>SNfiA_&Kkdh$OV z$_qxn9|sPONS*Z4dpA{e$?Sb$k*QDTZT}Fy!h|Qko4uwHsUlF#Cca0_lgcXZtkP46 z$h6OA4#+$$u(x0d_+_8Kn$D2NP$HBxoIOEX82r>XNLhEdw5XHxd)2`-m~Ve^+KF3G zQ2I(&YiuLOb-22ktYG8H%Eg4nV%qqPVft3xs`lKj)W-V#k!ip zV)Vl0w8HT(ZKPu!%-Hs`Ry#6yoa&V_4*z7_os8j3u2w&1Y5!2s(yrw;M&Q!Vw25g_{HXYE3I-oag1#9(Bhm;#=IQ)3@IJbav?Dq$+CHjOj&WAtHdO6gVY zT->Is&8xmx{XrBBs=H5C=Sy9q&nS>P+T|(jqKV;D4 zQg0XL(=BlBETT7m;oP16SfJy8Z6H#oJ+EStD=Ino{Z5A-JZ$(~?0QlE*lv717|lN( zvDSs8AEZ*LYdYvVfkj))n(?02@<(IBA(P$c@;AHHdb|E$(;vqY{vB1Fpdx0qoi&*s z%X}0yhxYele5;6VBDc_+-U>!p6b=SIw~=cNqYue~)~+(LZnB$WvH6w0*ZY;;*2U9} z_RoQ2*^O-)sRM$2`pI0<@Vh@v>X;v^zM5zd<)Agn0>q|I~EA|e*bDi^Bs_4EMrJ^7koJZ4_sSQbd&wuSXPjpt>T%Pl@!e0eB-ZMI)vl>!0Zbydl{Pr2m>nKC6oCsXq zo~@IVVAIV_5bcetZcdt7M<@wv!JF(f)o~*WV#SDp0u^jAY_$yxcIv4-*tJ>#(ur>z zCuDkEf_OO9-q;VjWrCLD|6xVqpR! zRpg?27i+8#+F$nPSd#d3A(>GGpGL=X^=uo`UnEKJt3@mPP-eK8FiposdmRksFEG3? z(c9y_6_MgosefQtx%UNb*fY!oUzSr8g=etjm#}&ixMOSKVKQq4p zN?+|ex0}!@!-|G8M6$r;3{hI~Pxe-Y1EJmQU3ShA@?zt0+dgLXiJyjE?LsvnW|=5X zJ!GMoFOy`HZ>&}OOsL(9VpJ_0BZ3Zbt`d@=HeBMmG|F!?x+ts<)W!iUa#9u}K~q(j zt|Zc;d2CRUZ=>jZ222(KI1A|YksQ?(vmgPQokg<_`;l77b2aM4bdVlBz_` zo(Y<&W=!9AW-w$&vOQVygiq%A1(SBG)8BnNqJ&epZ!j%>bN4DU9m*u%V|E}li*X;p zUs|#^Ib0iOIq#7d`8mK}x93z!&uGS2gMyZ6=t(XNHbgb2+#DVgk-NO z2RjwES*yd$IQPNmnjKpHuFvw=q%4}2^cA{m3b|oqwB+#}-SwiE9KWoY4WZO;R`iFc ze6Wk(k`+PmsyB#Eyidc^NK@y|8Lb=l-1Q0)1ndkC1!}MQzRvU3kk4sAZ%fLic(22T z@6b%W@5-z&t%>pPpIK){|CX5b%6@9WxLg34)W->?{S3t?JhBCc zfr7XXW_)UdFHnd!OJ!`t7IbaB+o(~r&5=5Z&<`(#(Y|wKv>{=jagF_&zQkcKQWeE6 zv42Bh?WYmo0T;c9?d{7=Nz9~l(#6?gvtN&@LNxV>Dbwbfvb@_^U+$Y!D^VbRE;Xg4 zDDtiKLGs{dgXE?_;_cRcyy3eBibHF+vYKrB>!9$8xf;jo3er3;HjksLZq>IQg4MPQ zhwRCRmfzKEJV9k1MzK3T8aUB5O|l+*LS5BXvlu)#e8osvx#YB8fy8H>I(TJ~aRBh5(k6#%Oq5lzeG z{n&YBgz@c%N9UL-o@YL*hERZ7pX^3hwIKrj-qa;?IqA65zC!s@yTmr)>xIJB8EH>) z>hR`C*oZTQg`+}8Tb*DNC+HYRIY`dOb@fK%=+68yk}vLMXu;MsYDH)x6+4Q<)yA0c z8pT?6)SRJjD3$HoPvuXLEwYtkl2T;G_YRy^B`Fh#pY4N0HlV^B}HIHtO+0OL+zO# zHE0|HkVdLQ_4c3Y=6OIS=Zp7Cr{w}WYNaj5g|YC0Gm9kqBP<>@E1g3tYYX~npR>t1 z(o{n8W!1eK37yH)#+)xWmW_)a<{DOyM;l&{kkL3Duwa)&Gl#r4s%|Ju>hQW2CN#25 zvu5tjSHNcOHUo8wb(C-aG9$63q`ox26~7HlO|SkmiDTqc2JB3T6j}f& zQ<;QCb)q1rHcFl;d)bBh_}Ln^2u!=ETNEI}zrn4Y#UDJGn1Q=zNuKsa+#v?2wM_%6 z>vXTK$TWHPaz~~vr)C|d7Dqwu5y##03)SCNnQ1h7!IB`G&6th#WX1b@=lOS%UwghX z40Rj7m63Xx55-$Zi8PeWeEqsWfI*F4y)nY+^VOdT<-P}9)25Q(^@jLd1HI%YN!ApML8qz!*bVASPkeDA?s zX6L5Dw~8P!_(+oAihSX|dxRV|`*ZsHuB^PL4OL#*&&BHTW*d0S8s#?|IExi0pS$tE zb-!|dyb7FIZqh`>{d_F$%W%B>$ObBjtBq8SjP9hma#^)(V~f2~S(zW2rRIt>p*1U4GRguk#r=pZw-JQUD!@ZwrQhKFeWzKj&puHkeFPf^i zoP`K5Nepp265Y%axF*`n+QjiU0?P-Mkrc}^kZw;eARQW-H;vvrU_Q%lE`Jmt&nruHTTpK!PO39E~M{QtF)#>t9ru1`1nZP_U z;=m74ne@uG7$}XU*XqJC$N>tBwiZbD^d3|Sez^D@ba-eCG$~1~lzntutf`91n+)6^ zp3CI)^}=lZ$nut#Jr9irXWyTcp2ogN5TQ*n-37@d=E|wb`OYB=&0(LMG#COTmR(-< zREW!K1WZNZh)f#g_$OegjHSdl9)e-kYRYkSXdk(#1Kkl5E1slV@=x$c7x zFWwbTnQicXH@kFA?aD?WN!A}t%h7c4DAAg}o#N*k($#4a!?m|mH63BW-s-^ME!l(I zTmkWVeh*^SS`*EfkMTVT0As0}n(AUbM?M9l1PgZ|GjO8|iXw`yn0W$J-o> zG!dmNLV$Ojn3OInP#JQMP5dGA3xqEh$r_1wkcnf^=ZZX{rrAXH< zjB4<+qc{<7{Q%~)=qKk-&LQzNZa$_u9?Lm-jiqi3lSe0u3dJYwQ(Lb|%_&%2k!Dg1 zt-{@QC^!;WbnE*uVY*WB(&aVcSzkk^vg4iHGutq~gtC}5sRFU_4=yRr1=c)g243_Z zbm&-n%?zM+^m%@qe+KY=wV^b*jS;hEYE|^(fPYZTSad_-vtT9ah|AK2{j^yK5yrZN zCNQ=!v{$}q-VTVY5mRQRUCTR3G?}X3iPbbWK>amDH-mhU;mGdjdwkF0S>y8M)2P*^ z3>hXY<2@=ZGG~_vYPkKh0G&tkPgY91&pHF`LF3`a?7#h{_bhBmY+5qi)-Jl6r`gDU z&65(9pS}?f@`yaG;nc`Q9w9=O3}2?O(CD)sH~?zTInfYuB4irqlxjOqg=)UvTxyMv zFe`Y@NLY=>SlQflk94nJWBYBe+c+%-+=X@GTk8p z-JLR>>ER~j#BOtnvsJu47{|b)TpCq`hUYWn<>@Kd1v8%%Bv!lOi9Q$7MKl{qx;$cg za&0&BfC}22vwMLjU(p-+%B+vLH$z~KN2@eUD}Fv%R_i6|OM1$HlCBss6*@@}vL3TEXk2|Nxk!TKcbVHjeO=NXB0hT%{fy@H)UnJDMw#-QOQITzFjelizE7Dy(o&#h#kNF0~({{B3pk$<(H9 zqe0(e&05OkTm4NzonZ6bdCqMd!IJY1@6yfG?LhzGgWAt=zq*!o-BZ>eS|&ZJ-@gZ4 z!xkwo(7CgWm0<0i65NFR1adjsLJ0b#owwT}bLqb|-Xx5#wI8wSA zwzOx?E2krBK zkgD*YTBz(XX6g{Xs+C?z5L&{Zd@lVo@6{@Swk+>36SCxG%dUM+dM>6vDdO`PX zpBfxxyo7X^Ud(Y$XIpCAn0NY<9PXO+AG{8<_RVP>1iKcFh`d9Ag(-w~RF`R{c&)eo zj30x<5m357K9hzaGOI%b?OU=$o!Oh+$if`U zhH5S+%8t$96%6-wT6sunYlm4DhY+%y^B#lOp10`YhGW)WmRnE;cjQ1{#)RA_1|2tt zP&lR9euy;?BFylgAgtTYN|1kp#={zdPHu&@Gfkl8(SAWaRjT9dbYfJYNva)5^kFa0 zzH+U?!YP1#>|ixo$5uskaU|i}WgSk#aQ(Fmk;3X&UA|0TMTV8Ol!^?!f(VI;I|Fx$ zs^v)dg zEW3_g$>fOinP*^eJRw3+oP-EUxqYH!8+>iNG|>7d3ZlPHwtEMwh1p&g`i#yW|CeKwhw@UhkpcBG12QS9RoUzK zvC<*0FHC6*vU(I-kQd?Jmm_E!35IO|UDn3;(RMv0D_N^w`94g1@Q{54-5>g9<{hny zR?bt2;Qe#mfSRI((#r>F>U~; zdCE*qco-|&DNXo;iim_Vuv;24fk0EASK$RdxDopcit%O;S6sKN`et=GHV9ZrpVR|Wtxri` zeVdw5-_?l3M2V7Oq?~9IkqTRfY8%|gI5+=#=3;vl?scO#2Nu4;UdUYdW{%cako%k+nPlca9|oxgpBoMOc2n{B)3>DnwQIhU!e)io{Q zcq_Fo3Q8hQ%d#oddFo@sXWRPs0Uus(ETy}>{W3{c^LE^=*)Q*Q1s(P0UJE_0Ff*A0 z`ia2HypVy8`A=$Hei)e*xB_{(p&!MGB(uVNd4(Q0o9XrQ8Z#=(kDe30$4p3jRjbR- zyc4n}a8>PQ<8oEQpHGI9X6nW>Ai%r~yKAb*FS;qNs4$z|-(%5{?s7G6oYgoSSp|+% zWwSz)gkfI z<7`-S61DLpp=*F1)LmqUcC&Vur=?{H%ni)9ERC}VF{k6Fh6eKcIqD=@oVmw+d2C_N z8N7t)OUG%2m7~?^CPr&^KmH7IRC3JZ5wI=5$=%aeArGA(Fa0{p<4oS9?)*hKqklA) zrGr1g$+gu?5e$Kn5lxdqXDKkp&g2`a_Jw_OM-AleT(V&ACR z(%{nQb`5NizGG{${-ze}3AS;rshNwH#)ip>-Zz(KE$#C0aM?qMw*2x&%3SN#HA%La zz8z@VRLLY;1mCD`jTDa*%_*n-{E;we+f%>gKq7Ncg%4l!9_b2D#X=-8#lal7Bri15 z?>gY#BTdz7$xW`Vo=ar2u2wPBHMc>>u0IC0e;#&owJtIdO7EncqT3YZx-gy~dHJ{W zQ+uT3@eOpluGppV;b?vr;yeVedw85o0Pc0~S6+DcTD$HQk2GISYE_grzPRf~>*f6v zDpMuNB~`&~mBTSiwih#>B#rH<@+>CFD9IH&uaD%}QqDQkPHgtx*x6WV?%B6Lv_RZLEkIVTX`13rsZD8QE4w0t>sd?bL+k(jvsjw z%I%Y6R*zQMzzRbfnu6v_=`%S!>baeOY=6o(x7*HrNFF7hC`TU1()V0NCdXeI`ccN% zF;gnUMhX~^yOMZY2hvHkpqa~*9STcCAn*f2y4`er8i`rrIQ4a&>;TaPY30!c)6%;* z-j!P!c$Rz3;12-T&IHIJLVhF5mZjfpa}Rg%_crw`wR_VezmmS5@=5F?|AtU$*$u7N zG8!wIz_Pr@O(pl_x=eAZy2M`KSqQi}+IhfrPG-*0S#v=wapg84X<=6#ZH)3egOWYp+>JG_Kw^ar%DJM~=TEwausPU^Qv@fV$BA z#>wV@OjlrRqOz&MR9%~DQOs7!PG{s8{ZstrCQE~=BmT;RAv)J#vrm-%2#5-;Iz+C{ z(!NW`w9M39VSj#+r9{W7_FIi}MxmsH(*+h9Z$X4+v|luz>k zy_1c%?c8K;6a}q(86~Xo{pzAH+3#L``0?fN3I**$@3365d%drrEv~tHXEA+`lhy1D z=lpnOm~_1o#mT|lGo8ED?dA97m4$_-^noM>>)s&_hw<1>dxq4m+1o{^eYme_I*dP_ zM|o+xP_Z&ct;g{F*7E;hF(z7nvO|}uz9*8OW<{s-mMC+>nCU)fs){1&9sl)y+ZJmb z%hyH%Efs_MGLpF>aTfxOplPJUW_)kq>_f3x3dFNibhz+5VCQb^9^Q4CyzZqw^kfX) zGs~_%8}6aeAW(td({s%tDNAHnJ>ZE&z3|diS+9F#z;ddOojT+?hl?t=9B6T|LH2O; z9e2_>eUOI!3`Ys4w=p@=Fie&pQVW8Oys=n4plsQa(W5eL1gti_sh60cIm0pJ9(2WB zxesLJ{F)Z9frl74AT%azOA{=0HF4-LbNs})6BuR_Kfi_XnlknvaN=Sh=Z#`;W|y2z z{DXbero^xgUUMDfJ2t~Z<$-T4mA^6nWiNC-;QPwV@E2Db(L#%8YYzjj1lIPm>n?|R zCc(r_$#p_uGU+@%HOwM8% zw}|8#i>2yjxsBv=H^Yjf;+6ol+<{_2bYsny2j`i|U-1B2gYEWdlyI8wXGE)~o|9)^ zw$xH7`C7Jqm!IVgGX)Hj3F7l~n2)sn48e87`wsM#xfR*KRMTDV7EyXbf*}{c>d$pm z(64lU?U1>(eeOV%{`Jt5DLtnr&1dIG_cyDKqy6by$8<8jU%P$3Vt%hlju-oU1-T&W z@;{aIAl#e6p;NyiOXK77P8e{PatjRSM;47Sia}Vs%%uaqA5#gKeSuA}dU?B9+;jNJ z^NO_!Rg$ron!auM(tgiLFO&WG%jChdPTHIROT~;qa`mb3mN}1i#iW{dld2xwTRrU0 z^YI1JElJje22||NW!5~XzmQ;tcq$r6R3EXJTR++L%$kVc+dFpdM~nAR^FR!u<$4&! zP<)rG_pruC8AC=cQnk*h)@hI&u&lBZ`yw8*^5ZVccS#(at`?&V`I3x z5<-Tp#7}t!%<&5>o`)kl^UR1DlV&d*_gdh*&6-iV?Eu$0q^7aKfyhW#` zCO+{Er1S|xj|c^wqw8b-4&&zBjOj0Y!u#A0}CILzuk* z!W?d+WMJcf@z}s_>HuKF__I+&1n#260s%n*EKm>>00yyf1GvE;9iTMAz{=c6*v8Zf z1^{6Ig&mAwHV6PWh#dp?sOxdU0s(_DfT9MrQZRE)#gqv&Ej1{r}TouM<6F^9h9Y@rX}6d?C~KbBn5o6gkVwfIBm* z7eYZhkrF~a6fU=29CO*^LV9F#9&ay0cC{0|PV^3@C(8m$IA`1W7OgQ?F=`fF6rV5D z3{+=1^RmTkHO#uD5)m_whiPp7g4@7#_Zgk&_;pv>&h&~<=aQ4BJzrI6OV`43;XTI6n-JW2m{`Ne7OuHsOqPp|!!$4B9NT+vuK$!39h8^QQ38RzR7z|w-q~|*lkh0~OIF!{+F2K{;vOaru7+p}D;SLe$K_{xP^@4gUIvvS9$#%#9Id4q8wSb^tp&2LK9% z{`o>6kUw8`5C{O_Ar)|8f0suJeyz{&$W69#c>e1E>sFu`z$V2?BVG=>HMoV9>vDk^lo9QTw0k z;J>ZIZ4iJz42l>)1$(%W5)7dQR1lK@D#Kh5I)Bfczj6J+S;4>*22?Pxf6Pa=M;$;# zm;>C=-U#LZ_@hD*CLb?0hR3yY#eMKWf-{v zMU{YJFeh^(n4+WzP#S=+cZ3ND07c<82$&7R0q}S^M)7Z%4F20~8Bw_7qaDCMz6F5) zackz$w}1Wr4?F(Z)Xm5D7as_yY>u#k@kxkFNPs}>P!Nbi6a?bn27x%(Kp+lw5C{SS zfuLZ4KLrS(^@xNbP+db40D3eC0Mhv<4u8({_d`Ac^H@gt`2G!=1IB+Lh4F8w0Ds5o z(f{wvjUBWAe{?=h|1$OOK>Vi?Q3Hg572NcXhaCRl8w{YlEzCyP=&=_62G}@S zS^eV$(!l`AJ0h&iZ65vi2kifW+TXg~g&h%QaQlD4^#~Cc2*e=)0&$3eKpbEYh!gq` z$k;eRAWn7=hy(H$r0gINCqw`PC~6NgK>SMt8`~rKFIG;0KY?iMXaxJG3bucG1M=5C zb`Xf|Q60x$FU05Ato5e`QH{=};y22k3@ z1P=HUSC11hfEIvHm>nv{4(4PR69b8Jv9WPO#JSmo#W+CX?4sNt2pdQMT*xA!|hLP#LEYaqBLxI=JvA0#+~yGsZJm*5V;-Q5Z91P`u*+W-R$dW+;a z=RNg1&%IUmzjsef)vmo)?e4vLclWo~`gEw0g5=vbgl_-(SINrrIKdUH%Aer>l_`@whS$_`=i4X=#$;;us>dVIu5*{3q-*<*ui< z5)pwSmRq+DY6}`39o@F)wwkYSad7zbj}4ah%~`hTNTOpiakela8cZ2mTv-h~oM1Iq z7HaY5F<&Gozw1^|sDGlB!H`-0r%C@W_1M2R_c~sGV5Oa2;c4-N_`*rqj(;?LwdF-WGFy}$2ay?9g*6V5VwKapRw%<2^o zI4JNw*w*XXF~cft@~37}8G0iD!F59!})W0tKM((3nH;9*>s+YEUsZM!RZ7m$UO z=Gxq1!|bnwdF<#m)7P4sZ=D)SHP?Q27$!-#X6Az@TJo#$o=BH-^jCB^%5@$)ZY5L- zrnqPVUmL8=E!sfu1)+z~MOTo^_yk`LettRa!q|*%t1BaJ@!yU+<^Co1olobQ)8@wu zaXd19cl+x)F2CKT6mzWC!HVIwS>Gd3xP5nq!EfK5lxaE0=3UMgcQ?YpL-X=Hnz|5tID_;o zy$bGSA?euGm&o)9eVxg@VNsqx-`#DH35mBMICK(Fhux{_k|-RkTu2DcXJ+8518<<_ zPMK30@kcukjs|Y!Nd(M_|J80XfIHauhGcGsRiI{mPl(3M*p^`mw)l(0ij~6y zmB6V|LtqRHKP~&--)XWj?=9nEOC9Tce%LRjOlc0od+@_6md=nkjiV1N>!+Cs&DQ7T z4{njVG|uJYG-67%^U1jTyHV|MB1>k(bmf< zj=YOUIkh^K%as>^@;2Oppz%`^?RJfe6t3y|{E5-lNSnh;!NgwNZ2eHyg;{|xXsfu7 zQ@S<)&?Sxp@MQ<-=)PfKXB+et8^=lAHxrOGMIx{35)P&gL=W3h3B*2^+!9}_8FVJz zAzj?*^c~oI6l9@v(d}o^Vy(`X_SALMko(fQ<=e+3(9E5&Ca9ijZXh@U9XX`a-`Puv ze;>;|Yhxd1CZgb(H06RKd=0B}2*mV%iloRK>8jDQNOq@3Ok!fy`T1U@%YBH}&U2;bL zbI9CWxA$G_ExDJ0NwIR}DwPZ^m0g9fGPe4eIk70&u4QSmRs)`6{8w!W=s7uEk{b`B^I=-jjSF=HK*{>5nmRYj!>a+vb?gyQ z7!OqDO(IeZ2K8-kmQR|NwvP5(J&4Wo@I8hs(nWpCKvlgTbofz^iccZr){+k9b~P1{ z;UN=D%fOvO0T1{yAyduUvR%k>$oLvSaqkA0m^y~_<27cIh4A3jc3^7F7NSSNk#8YuhRO*+%L@o@0e+Bk>(U>O zgMMyzP489&T06Gvvpt->k`UL9tmI(T7i@Rs`IX!9DOg@}{Ao6@vd&2AYq;cT(Pr(_B{;matfCU)mss5P?8103)6&OuzqZefDQ6_AkDjx} zYwf{Y6E;Wa9@G?mC%`JP!PyWtrvj34?x*34D!l84diN^#{zqESNjKGFJ3T$3mW*uv z;Ov|*oz~cP=ic~XM3E3LueZ201+BuQ=5fbY@KE_Oo zL#8CTA)yV?dI0}3f=zl$@yBR^Dt&t zjk!5aCi9NtYVXXr@AmZ9dYwbi06Q-)J|K`L8VfPQOZ!mO{(7XC-Zpym?B6ZK@ao6ZFoHYFdOp|5MS+g zpW>Avu!h=;?ZXPVFG1`0YNHibKPNdRG5qB2%5usOleWua zV&q-=zIzj?dS`#34n$8Co%YWDLJ_FME|0}i+SVocQo-jLf?Yv3@`XGDh ziZJqz!<-uO%Imr9yN=Y4tEiPfjeQ7L7iUzoq=Y(`$p>x4l?&e+G=i&NX~bRT9Z7CX z#V1dwP-SSwBW++($VR?VL>Iays1-LK+OPE)d#QHtZH-7#lVez=Wovo!_$cLsr;#E4 z7|F1ktTX}u0K_vTt38X~Z-o#RG-B`AeoPM|i(ha18{$k8a`4*TZNE}SQPx?{J@eJs z+c^x1wKXT4w^L=>xrw2nNc`~89ATVVD#2M$G4y+9^rm7F+Y>wA4Xr@rokJ~H>n;2sAz0W(|a;&u=35j)SM zoidmPLV3)_2CQ}FJ6CHP&D(A{`E{#fJxU#FeY~R5SUvZG-haZfT5928n{MG-c0Ht| zGZ_ePti>_?I6hi;f{JEFBE&DPeZR&K{rp}6*ds>yX7VOxW{L6f*x1-JjdliN2mpW# zGFC^2=&mf=Dd~w>gzxikOv%f;xV)_U4&B5oC&H}wXP)OD83A}+8=PU8w)56;u~!%2 zgruB7%MULFps)cuU8#YNQ=bkGvOl`l7b97%GW$a@>6JtHRR0ONbP3b zL@19o1*6?);f#&6g-&Knyjo!7tgGA=$>~M;9ny0_RPb>J9B`Ta2=^#*m!U#;oYggT zHDy-QW|wo4Ic<$2$(p4ZOkR~bf(_BK0~%4N$J8f28RAHWg6Z17JDW2ya&y}QE`EW@ zAz_k}|0xfXNRNnloR?aY4t19z1aTQ?Y6443gLsx^OHV(qRgL87O-yNtAQ^VgH`coX z1v(WUJlh-e7p4jq2A$}J(+1nYQM5s!NH;YOs9<^Q)sK**Ys1ys`dUZ5&Q&k_O4ms1 zRMZvsht0)mTjp|-Lyn8z7aBS2x^ml@6i4s>IC07ya09m;YQ8JSr{nOLuxrS2Vq*pQ z42gJ9_R##WXz?~&zubF*h(K?KwFay5$gxJt!VF_r($52W|FWKx|J+aMWfZc-u^WNINZ;`i9C zM#kghUe)9Gl*Gw;C}c6vHFfcce5#c*-MCe9*^_|&ZMEk`rEl-L&^Q(#Lj2=hxXNhi-0|ff;@<$iJ%5z%#j$*IO*7Lhdl}^g5$p4>-T; zvU`_&DNfkjW2;03R*S|i7Dds5m0b9x(}2F&^D6GIth~RaGZ$j85gAHsF1F736$KVi z78@whytCvN*;lWnXDOO)mB(SuzVxmApb!mXR3~Ddy+Z;B8Em*PcT~TTASm;IthfmK z4g=u;!V5tzTX4ScpziVv^{_}FlFE+HVszwD zsQa%LO~A}K{c!z@^9jm_dwuOeUcANX`!hDQf#;M$Hd=N(?6tkya^>Jp@TRlxom%l` z?HEStYo|&AMtRk_7r7=Q%W9nDjAh0!R*w!PVJs1(v20L>k}!q{ZE8Vix;hzi0tw&? zX4iiy&S>|_GR=Q9CmZ;kAOHa93o3*Fgox9eU2l__Hh(Tn=y!PUZ-#bed>amHlU6kr z50g~+JJ3r|oAt-h`E^we2P$d&9%6M#+;E%3WgXVw+? zofwA|4qx{?`;MLCQdk4+16 zU^*RzGp+P3r^zWJ$5~NT6%v={`Xh=&0B5;FwU}5nD3){Ov_DMfuCH%|WJWMeaq$DB z4M@3fC?l!Pdw=~Pim;&>8ID{bj*C8O$)tTRh6z1wDAhHe_w)>WeNA@63Kc^UMVhE< zsBiurTZ=6}!WK7`ANcPovy>JfNx)zwqB(X_WSMgo<>S^A)*KButNqijd_*`|*Kbl7 zlDOELYK{7sFvtT<1bAcF?bpT%S?nsy-1^LSs-s!+IXFnwZ*(qYoDy0y#E&?~Z4z zuCA79lpEnALMBOx*^(A=>0dx?eph)6V0^+UxV@SY;PBiF`XHTI?tH|n3cPCsS)Oh~ zXFN961Q;NtEqAcy{!ts%wbc&8$}#wfFH|-Wbls)@A}v+Lfn4ThUT(oBhx)_+Dl$tw zYsS@A16v-HR|8X{LOa=XCvp3hBmp-d5B~qPf+eR3v_HIhYA>b>wjWzWamD2qx~5n4 zkw(t8iT0FEBBLB)Gsy6OEuAStSF?OF#|s1nu~Z8skCQ$P`)c-il^m#ZdQA0P#Hf2g zt8rA~E54T~ zPwCtaB9MUM;{7Va9(0Owp7?@t9|iuaA(&g|oliVU2=pLwnZ1W^Vz69g;OV97y}_d! z!@T$T`1c`?C#SB80fdfw-Rk2}0UPt3C+nvjhsQ|CtGl^pEt+2wstep%xj9Uuvk}o7 zV60sm&;ltUty#`NKlDY@cjw!Z!TrdaghwDrMHit>mBq+O#_8dxFe}4Xu)mad>6@4` zJ&@H=l6c!PAHjRgIQ01F6X0r`N<_Nm2(iJu9xWYSN!_EoWw_G=pVFz$mRi@0=Ap=F zeJZ*k@r9*=n@($33}J8LO$Or=?=7^+cTaCz;@e9)vcImVY6^)L{;~xC0PiB_^CmIm zf!f;NzI_8fD!zaJK3nN`9Z0qJ6#&2HEUF5S_@t>x%zmEJW)|G z%xN*{Jm%3Fcru6g2MAplv5^_8?&#o-7r4{-gJu--Z%a&MvmxtC{ zaBXFUB!f=9ZN~}qSfcWCF9fCD$wSd6g(NfLPA|by={>c{dusRL>s2IBp za%R6(`trrW$6QhXV7-;~Fi^GUh)|ISi-D?Ud+9EEV0Qm=cH!(>xIdp0ck}M7v4j8s z(B<~ldDu<2>WA@78Loy4Q=0pVRkL%?JEsZ_t``8n7inm!)W=Fvwu3(^R5vSu^^^sk8h!mf`@yE7}BuQFQnH(>u|*|)iKF?IwzU!m9P4l%N{ETO)h?(N-P zZgx^HQG;Av^@C)P47D57OErA%u4V(r(*?Y)rt)Qts__TJ*=9@BM`ma19l^t$?!>)D z5PyVMr2Ot*R7F~oQ&U|}mYbDxB?zao&d$!TXcWZ6#W#LgP>YK8ppx*`SubE_4|1*Y zxt%P3L&nQfq07k@zw!1>wB6m^ThBlMPOb*0UI5Qp0fq zgQi6)GZ78tNKHyg3by$E!9ij^GRWS(DlILo;Sx6QN$7WXbzE;X&x&GfVWE{TgQLq_ zFYfK#wmF^uxVDeLI)O_3I+#C$ET%uia$s3)bE!TXI}AIsF#w7I24hB9_IfuYmm0&z=+ zspX6VG!@vhfkMb$G(*;hCDLnDT~SeylCp5IJK^BW{%b6a3s`3X2^aE1efxH$&4Z2H zWV1KaYQCaRJDbVd+dGk2j~*RKA)Pz>6T(Yo%|BkP9vvN3QBk49d@YiFwm(gShK3eo zNXTVNOh~A6h1p$mFjK5rQBmP7=(pPDA(CAcaZD22vvC2FO=L{@U#NcMk{1qB0Bd|e^ISGxBy~ubV3JFOVa{qXDy1&2A%gcLreJY7s$rKwK8-zm8 z{UIVhA6%wgi;fP+gDh0&wKmu+af*Z#7Mjg8FS zyO-BMUmu;V_QBrXyLURDC}NsgT3AtxEiGGYS9o8%_~Gt)yyyZR#$irsH5*GMzT2t!SZ~++3LVqd&r{;ZU{SZofPVnK$f zoHhp=8~$G`!bO8oGk9IXM!?MaZNIy_;o+Xkv^kh5e*OA2Kk4bOY*BcBfTSLSiK!_a zHDVHrfiHMC;kiH%2y}9Cf*G3U2|Yl@V-^#x>pNa*oUb%cL?YmEG&!6r$3XvL^jX_= zz003~fS{$N#oymQS)r0?b8}N7ig@UQ+`}!jP%h=`7r?v73D=G8Z!4{Cs@NPhi*-S7 zi8jAmg)h{a5A^mTz4#jN3hm(V@clc0rH6+H6&2O%7hijV(TpRhY+_PUifKD7&CD8% z`rbS{^#0+&Zl$Gf3vz#dU!qsxc+O^d1@L$*k(+UgC9UWP- zCWO3i>{GOVSB;Jg4l2o^RH)>?Ij}~+7MGD3?(#>V!jwKI!NV(|FpgZEt{E`m9v&W^uC^1wP2!RXdgBZEwi$uCAX@|P-vOkyY9H=SJAeNC z$u2*U!Zt8Ij`|7+luP53S2pM4=EiqvfD1EPZgQZbqYI;H(PhSin|u?dgNV|jR;pnG z+3b7%?#m21AAbhC;wPP0TkBNGmq7|?z~^_jmyigGiW=|mxlt^fs$)un>&*f4gxMsetGGjRR_M?dPBHR#sNT zW;P!kHhX(}#by=|X?fAm(3Wdvc#DgR5fD+nOHp!I&Lnf$k;20(@t10pdtMz8L=P-A zJDJ1I!5HY}T{TBv;1FtRYOrMyDE>4G6(uDKnP9qMvM2Pw!^>+6-zuEVeEh}Bmy_%Q zR&$JAUS7}N*>e{Z^hq57Gi%r6*{-xadtS)*es?14CH&89(O@NCoFDG`ZSEUeTkqqB zJg<%xTHWkkhyib4u$5M~=z%Spl@^?Ol%+nrSO3KV0KWJ8aTxU?#YpARLe&iF)6}Iy4}Puw64S+mN23=#AE1ZxS^OTX@HtEhS%N-$zsOSyp6)Lc;|*TYlBUS*?Cem- zNTIxa+i1O@vhEUb&F}xFzdL>A7OVqW6QBwHi@}h zuhq3fb75xbk>(phuv%N)u_fl+R^@?zDS|Ea@T}d?Fqm;;7T<-^*-P?0l*nl`yulQM zS7Sz^(~qok@&>Y{s-l986`*WR^n*4CjVv=WlNlWem6%(2njJm|=YJ00M+>zW=wCLq z+uR|C^OZ2~$JKT(c{#ZctJ7hSOkL*F`N}LUM%*{wicA4t*dI$3vjjcd-9Mmg?d|P> z!RluRG4`NCXvzEbw*J}nQ@<^w>N9?oL4dpV7E^ zOjEh-%ox$ecCY5~`msIZYDWs$rWVWOTD|sL)T_6xa*I&LNGiFT+lD#Y(%tJ~gUb0o z0l2+s>+NQ2u>AI_`(Xl;LBpuLG?pbF_2U%n#av}Z!r?7+HNdOh%4FJkum2ElKFY-j zbgWgGGLYGbDS~8}qjzWck{STdRvY|q`%(E&Y}?HRxn zE^qg`)^Br<839*lRp*$Er9OX{0-ny6mL*{@BY+a6VkSTAu(EU8vAMO?YraD75Mb>alPIt2k<@fuW~RQFSYT{Y%HZ(|aZrZL_aPwz{P`cb z22GTwhp}9T>7{C*&MR%ikzrNaQIJ;Y?kc{+<;kiG;dm4JKvfy#&fuV@Mvo#*o-V%G ztjQ`#OuA``;;y&kIRBNu;lg&Dk7d0URHeJ7?6Sw-7Z*A}5{g-CJ+~x)P)0b`95*gz zZDY{4YzlqAUP#)pyyi(6WgSlazP-q8KC&Fo8B&DI zP87AxT+3ssv!|SJv^neNFs1@(g%#VCb6I>szV4Gj&l<07V zQBhG&zjtp;YvC|xU?aWo_4Vx>e3YS#<#jpu#je-k4V#%!i@2^cZM)v= zL)O#NLk-?KI0&1dvmm6Qp~+U_{@ev%I&fO>Andf7uVB!uuy0=Gu$oIwOT$|hKHup& z35?nTrcK2w*H#NmUBB$W#`_&&KHHh}jhQ^&@Zm(^Yt;pd&??XUVBJI&E>2V6S&1|L zWLS#_f5gXP>WI#^r*$x%!&Df_&dd9iTE|S#`u|HJJcqWM?R2VV?t|jY!o+aupjtxIe+gTH@CME5)$X`Z4Y`gbG%(y!D|X3zE*Nd)9#o9@Z&0I+Z{b43~#7XGd5+Vf(JnymCjAbtA)C-Uj)Gp~n zCq_eL|AbZB{v&6`I-eBqt1Ml={A7UH6S$)zB}E8LReI?)fJ1NfRnjQlrmWz#NJv#x zl#i%V+_(Z+t$5Y;dQ0+mfWCLQ;d**{RG8A=-r#6d>X&=p ze1&B0L|$j|d(^l?jGA>rntdxQDwD;QaiafQ_~gcYYzE&Jy)f`Xw=3H{Xj{ zN1vA2!De_!iL+xVehXB$qnl3C$3vMqEnQ{tJa0$FXRDnEJux+;aJh-~N3@KHw^ zTz}9L|AaoQC5;7jo;|9Yq898_p03V`GpC|9A($xxDhm&(oSZ`Z;uEQc<8j=`5{Njh zwLCprqM{U(l)mrCp+rSSzC}i6@FIg6l?z-TBvtr#OHsyNpRU!GrJ|va)F8Y<9UUH? znx0;2bvso&LQi`<*xQWBAhuF3*QvLhU5v_*VCEss{D~z%)0qNfKj1Xn8l%iV#2MP0kaIa{+H zI*Le^cN7#x=i5Un#WM>F9>1#$>BsB$a)BqB4lW-jT*zWH>*Mb1q8msehcDW*jptJq z7dz!uy=W>6$B~~-v_lPMS0*Mn%xu$cudd#D+2Fb(GJ;gA%?u{ShZtIZYik3S>e68i z1LqzJA|jXnO&564l`gwIP|u@v93LNB+hp)7;5(m~mRHg%g6TosS~e;p%2R>Wi&3HB zgql$)BS*?OUvD|Bf46Og{CK14<8_cpDBvtwCl0x){-M|E`YkY!){SI%p8SFfpj`rbfym3R4aG>=rD#t5h9v(9gq zwUOlKhB);r_31rGdB*$|QLU9gjmrMN0CA<@xM(_ph5w!t=zqgyS7>t#82 z6uhD#Z)GHvuq+vX&zaFtGSIW&^ccyoA*O%qT|G5hV=C+8<0C5CBOON#(hz)t%H3@? zRJKQ@9?qianj_D*W2&}$x(H^im1);@bqTA(ye%w>va-m?O)mE)nSc$w?ux*Eua1rm z3=9l!K_OaNDG*aY&CmY+{;saB{(dv)!EAokL@DXp#Kj`aq`54|AN47^%yx@)bn?@P zh=^oDzW1w(g~M+GyC={|NXjcK6{np`HOkq`$6eDnZO)ew3yT)(t+Mz%R7B}#W%Vm8 zO((6uH6PnsT`l%MugzU#X{MBIkF{`WRFryqEor-4M}L1-C7mxHQWq9^xn~;fI7}A6 z+@OE!fV&YQF_^ap}LpSMOZ3%kI4tj-pob)F8Mk2)?|$)Ya8x)@}NJ zH;q9`T2WdmJ6#tZKB9OW!T8v_&YRdt7M%cQPDsZj$zU|pPQ=k8F$R647mL48Ip~XV zVUje!s4m-^LP930JTx$frEK@QqigTF#Y&0B<6elk=Tfe?_a1lQNE9P^%2hO$MV1Zc zh3a@&dnD7FYirEH3QV@($=+&r7aMYp;R+1VHwO@*qrXE(dIA4QSon)srY}t5B_blC zzP|qc{(io0aYt85;vtGB33t8~0uhjph#@UeR6|#O(5L;@2b{%ZbNduoD%iY#FUg!NM=Km*L6iy6l!n}YJ&7MnHQ zX5gVcjOcX`9RG5aCU({To zgA36ko zC8Z2_Goa+$=l&;B)CYnSZXUgsh?qNH(v#mD-mgt z%E`_i5gGYVoFUzM0@AZu?;H}BuTWt|skA!w5QsE2g*?eum8w);%XJ2jD;iI!F_ERf zKHKJc<}&9M@n+>4j5luC#WMx;($6Ul`*qOivC*y7C^C)=3uO@*u9&R$jK=cR#KgpS zdU~?UH-e@moCe_Nx3@1+6Z`QxX6Ddz&1HcVUZ#wZnyC|t$shbjz;9lB1vc6mwiPnf z)YOcQje$}*+1O-dW$#?3-1A}Hue}wV{J=P-DZ=UoKbzMi_h%Kaz@pAa&F32N5%ljB zEpGDFiKg9|m>sTn#?lsQ&1LhaY*$*Khx2Gy40YnsqyiQC?J`J1!^0)owPvsDXp=@v zSr@J+fUnWePFLIc#Fg{;nXX1yd3vjS-DrMhUsSRJcl0Z$y`#QBiJj`KTm;GU%ql-JC64l6If?|V-+?_@taYM9F)n zY(+8r^R2F1TCmAIIjk92X^h#ndw5yxh*FYsD!;zDpbsR zyk7J3;LlW}2SePK8tpWBHE#S(KoEkK1o@f(nl}W8{O8{E z!wkG6@Ya_|*~4!7PLS>D46i8LvJW< znDEE^#b=rzQOu&3y!Q`GFum~_<>M}<%n(dsk#?y`x_;Q@!{c-EbpQt%2Xo~V!Z%~O|{d{*B zrDwU#<6>tlttaSh+>i+|>cGfIsdOAQz9cAIB9c&CLIP6+6BBdT+r=|~w@QxM>+!z1 zvGF>BfDMUU$R{$kG90hw^)RBBU?j223@Y6#^~s?JL77TlJ>Z!-8l4XzPu>dihmt&z zIg8!zDsdnyLYBCpTj*h-mY?I@)v*vYPsuUPc|Y=QuObcxhQrQiO8U{BS5Wd=%6lIM z!7MvV%hZ$<80=z~>^!J1$uA`xg>I-_H}ZhW21&WvQEqCtX~Oa0+%xQHb1x-c6(*2> zJ_hplN0mn+#~#Z^GL(HXQN7L3Il3rRL-ov;Ng(91WyB0+Ht3K;a&T~PaB+FqUwb2= zj>2lRS*w*Ji9uoAaC8*O$RpjkGwWjGx{;?lgj24$P(6R|bD={-XX|h_%-16C=A5RW zCGD*>*wNV*+#LSceqWgJZr%Y#oY7sbH1<9B!28j2L_XD?L8*^b>g5ENx)n7TI23BE z)ecVsdoU+}?St<7BZ+W$_{Eji{Aj8JS$wd?Q&LkMo0k={1QQm`lW|>F+$Pqvlb=Rf z_GE2*=6QiSPAjVXiLmijPQt;it{)y3JN%@l+e2|-hZ~!H;U8D0akI0tC$fZCHX!1+|LY4=+(1XhLqibbf zXdGrYO(43qj&)d#Mjq&;WI|TGmsBYGqvW%EtTmr-=U*Mq;2TL|iAE@9ns0i1xEldG z`uIG^CNU@c_P3fXQ5O*r>GXZz=jWfX<@Y$>4n`x}8Ck8ZsS)&hWQ-eHUS19q*+^sp z%5VsbHOfVOFU5CO<(dDKFT1#{n~YpR+(S(a%~cUHc?x6XpyyZalz6LZs)>?t2)4is z%enD>498=s1Ls24e+DeWnkl@JM!=1>D`DZ`;bCDaa)sB|*DU_ydpfR8o6#$$IF?;uPRDQ@78|?goGf8%cGMopy zi$*IgE@)(e+Yom?*CUJNCWp}aku8WtYK3}fVr^~hVq|1wB(m9QMMZ_*BdoBwnTNc0 ze!ek&i`K_ueLe2eYLusR_9rglT4s38V7J+jWajAFU!ys;op&u#sy z(r2#Op!wn8SKl%HuN<1z$KSMs%|_nFTmyMHa7hDa2b>5YgWL{+*H4t*xzhW=ARv-mN*m z`%2|P9)tq6k%BAGWtt$?-DP(sjv)CxH9`b(#!TYl=dC=ByBvf^(i1iLXfw<#(iQKs zExU&!`SW|+`KFeb%i%jU0_A0YO-Dg29&&@kPnIcO1eAsaCFYCbt6GVKBrI$dmiMY; zeGG|`xZ!;w*=Jq;2srd=v5v%!2KlNi-} zXEY@$D(ZQF22B_A_4Pqu_qmeMIyyR!Z(2t;?3;9LFLuV9%uiJd3|b>2q|FSGp~Msw z?HNnsvJ#1YV*t?hpuh#MWh-2-H`!$xsYTS|{^cfhF3k5Clhe1Lhx1N5qcJl18N4oz zZf^6xu||i7!_d1wL{ND7U7zS#TOT#pEMfDsNzhiwDRe|TY{)Ls0$U`qG-rMOle?ai zh@Z;03TxCy#Rl)hsL@A8N88O;th9Swi-?N0x3`N^Om=@mHf7b$67*?tJJmPh>aavv zaj}&>jd)jiHOEo%pwS3BgHBi~3V9Ay0{gmS4fL6!1^iXzCfwbsO7!b>>KDg?PDcs% zI_<*LR|h^2tF}^ub1K{9G+hLDM;kOdP*jq|_K{@v`+ZrEt<$g0hwskikL7$V2|GQZ z2Q-SAw6@xb8mLd@ViYmozKPr0+iPfONJ)iAY@dY*tqtb(%ps|Wj;R1EDaDCgO7;FM ziQXs3^cgvbi3OIIA49eVdb+!DnRP8}Z3XSug+s+uYR$%)opvqH2kXup))lp>(&XFg ztKtV-N&*7|X$#)TXY#}5i%ox2RthITl)?3a-5^+gLN>&0J6_h8NooyMg9a4l7 z41V^Jsi*|nBS+Df{@$3n-2&;+Nf{UzkVY5g<~rS8g5>w2FQ=<9P;C+g9~=76lLu{% zt=#y&n~T%b)OZn_p+bC>LcX#nHFtQJ3rz+J9%5Gaa6%6%l%G4%mjsjkxQM`YDp-Y9| zKQ$FwuTH92rkzrs!_9k<^pLi^Oy+aMo&CR{o9>S78XutkaLwQg|TO#fI zK#%&xg_`RUu<>1!vo(0{m+j{2ytaYeT0e2xLV2~#@tP$UQM~|T9QyyCbbv?*`_<-J z0C1)hSX!VyvZlEv75l$;q$r=*-T+ydsF$M-LTlYnE^%P%c&&47aIgsFxHM`k zS^MoN(-KCa`Z?aw@dzn<%CRBS4M-7e!m6pMS*>MlVbNr>#97WwIzB#rbHPrlx3jYY zJ)EC-5Gqv2;C0?Z5AI3fbE_yXFGsw7IOMMSMQ(7V>G0Em@J~KtX@`jo5xTcLJXx@S z^i(AW2GWxr`H^7t0~0oz6mVErD)aIv{e|ss&Nd8668-)CKhX(#4HTWv=gFHB^?dNT zyGoFvq^73!_4Q44fTAJ`W*)FNdGLgV*fQ$a=ME*NMUx5nI2!6_?9x;WNWb3rHww9i zM%YwPfMCf=b8lMHO#`TF(6E^(bp@#^9AFkWokk-QYV)y|x}VyRJuy}KpZn5GAM3vc zvQxWn2Ikf$>LVljdGxC`n3hfa>pqvFW%1BGN2VZlnD_nXP_&FJ0k56ILx#8^&+C(w zT60D30~!6r`cNj%li6dQvJTR(*(9Wb-c8;x$7WqYi(fyYNca+~+qaUTS`EEBgYmO& zVpLjwiSq5Wjt9!ERI;rp4{iPfQ~9z6?Vf#GkVn{VR&22;K|ndlrt1Sy6llZjg)m)l#%`7Y4fqzl5P$!up~Z{8OMq{s(iikwHihUIfq zs6OY`?yin=L7x2)1gNN}+;JaE0<&b&WR_unBJuQ@@&x$!79vTGEMLl;senO6TCp+c z-Hm%fb=n@xbnT@ju=EOB%j3(c@5QB=lkcIf z0cr;)C(JQY5s{G`xrzR+46Cd>-HAk`ZEIilK**tDIZdXZKZHd~O;dP!nBKhpu?!M9 zxgB+aQd+#>me9EVT?!Mw$GOR5j(8Z%h?$w0I}R?){Bm!SB1Y;RIx)Zd_nyhUU7zLw zf3d#rEaq2eHj8~vwj=jjb#G)ehNx}gZ9wB=^&i}eBM;T2rKOc;SgY#lE+LSgAYF~% zczkt=$S1SwlNDgIW4o3zWcSPdVs|1sBxD`p{^`@Fpr9ZmB;k*}0|U|cAHN#nOG*yVsTNqQp<;7x8~+XV zD+M|bra8L?4KpP~yp~;qYz;&c^K@_6?~J9H8yg3(5&U>zF|gME^iNRu5AicIKR^GY z^4PcAl^C;Ujq%it3)-}{ zIuVzvlN>LmJx`(`)#N~1EA-)T?kAqc z`l6$)tsVA~gF&sR$`LH{LJYV)ibuq160$RjhwzKHCm2mpRu&8C#ivi7bd;GG=ed=R zzbj@Y6xpU-xxniLZ9^77XFo-z#at*j0S*v!`1pHt;b?CfgFzs7rda!p4P31=I1 zk>6d!SDMJqungTmSHhb5b2ro8KgCA)LCLr!#|THLYCbzgjb(h=`Y#s1<6=i#TpR+s z|MBD9+hS9|j}5cYWC&zSQZUPJ?-#kAp56;FhLAp^zOkfp@CbvM3PAYd3q(ZyCVT%8 zFtb5No9pqS&g8D{mTlS-wQta2$66X>A_bpTS^Tn)2y-4Cr0qg6Z-&UFe zlnN|vzPb|-5U7`^Wz&}E)LW*cq@=b1YWi79wJ?#Xcbi-e6QiO~lSW9mY;}uIVT~0; z22E3XT%^MXEfB^L{dP}vNO20Q>6@rrT*%ecj$<>t|N3wO1L15nMFo*T{58227wKXD zlL?uSFZP>n?DAYzb8^f{R*D0iQ3$f$gPJ*8yy{;A0$#$yWlb2gdvXXym_9n`1R1W} zklEc{?mIX*gqf@I^75w6|C|B>V8Dm_mvNn(2?^jo$jHZ!_&-9Xrl)bNc-6{vT=u8( zkwO}pJT7+nBZ*#<=SoJ~&X(XjGav!4(8dP`e@#v=Z*9+FXNm>Q#lTM zg3-b(^F2MaR569yi&YEz2L>+O+eCv=U%!BVA;w^0X4cZu64tjVlR(b|Y(Rm7qs=7Y zbJgwi%^27!2R5EGuK7+^jPFJuoW^f+SD6gBl%NoC$~jz6(b7tl+I9fqU#0?!1(}%2 z4LW^MdXm%9Saj;7;#k&skl*2{9Z?bZRb_R4c8s!`udrEZNkC_HJ^H;fmbS%)_+zdw z9Pj#QL3H}E4m3^3X&v&#B7FIxPiX}3!+o{WPv{R-rc-apVL3y~v>Z^m)%Be#Zg{mx zAz`J}&7i|OWdvNI+gxKdmdYImCzHG*7@5TmQZX{h*<8TRni$BQdecmU`1EkS_KcQM z#8`BFfx`^#U0(KHZSz11X&6jl*#U#|t1tQh?8GBA2#6?ye^OS+C@9b1Suh$IzkmQi z5NIlI=y$d8Uw~*lgRjwUO)#~sT7sTC-E|z?RKoU9n68JyM9q|3umDu8w=0J)c296%`dk zRASl~Da*Ms9=8)+VoIABFC+V0iAZ#GK>g$0Y3Cp8Ou*~Pnvaj~g&2@_CwyZEx$D~f z`edaJG@YjcT57NfMj`n6#RB=iQjKkIi8$3tHQxS(@$PRRSwemqDADfxq^PkP=%Hc{ zch>{GpTFeDDkzY$TcG!Ra5dh3te5psRibv$s6nIU%mja5k_hrZlPG= zeYdx_t**x+!gb;%CfnOXaRfmQuCAnl-rRpswWVU!LR2!r(GB~Z@eC_thO#A`@ zadB}F>o-64`Xh;wQd3K4zZYnw60sYMdspk!Tf%N`-n|3#)tZf^4n&h(xVIfIHENb= zVZcqk`EP1%fB*QITKmH?($Rqizmuc%XzA#Tr*a?%O9Joza%;)>C`!%)Q6zk>NBF@# zDMEf7_4OR^IZV%`#>P^hBiUcP{PA1A)AwP3%x}=7rb4f^rMa2>-J;RMEfkHEe;wiu z2M3oxuP!1C_}*_$B;Z*mMX6H8HNNrx6!+FaaW!AN=tO})kl+Lf?(R+|NN{%x5Nwda z9fkx81PLCTK+r*gJG?+3fkA={?kFk|Z{4ape@#Qz+TFeP?ta#@ z)_TUt$*UUZ;&Qmq9z_34ezwsam9T_Ly9y2tHtP)K#?mY|X|Wy2r+zWDw9*qV7frtC zBqSjr@tO0nn%Et?q0L5w83OEb!O13^Yxd^#J+Uv+nyRq)5paD$eV67%A>ns6TBJ#i zZ9SADLqtR*Brs);n5c*dZ?8YUuO>|^7p*l@iG_{bT_B4(6RIjJQ-xg_P&)`LnG#dB zN^u`lp6P0D;$Wuu@`0DA=PsLRtJwYfYFm7(dlw>Z8=q2B71R^dm=JRxJ02N=r-Gse?Ng=@=N6z77-7#BN+5 zw+Un#8XAzhv(N7_hnAGEg-ci3Pgce=s?v~=ZLIaDycn7+nPjP- zl*go?KEF#mxxLn(#u`xXg9J@Z(1uIXBq|_}k9)g!f4=1be)#g`%UXe~+C1vK7GpW(dB0P+1m^1 z2*#+f8^3Y)XwWQBxp(g#qe?pN$1Y2Y7!Kn`x?~tCR&T{~-srxqlFBE~dzoKQP-oT| zdV6!J>fCg%`cYWt=4jE#H?z)wcFv;9)4j{f%QoNBGJC{8ljmMXM@L^@Ur9+xZ#N|= z8ChdPgRro$tqd54T*zsE;brXWU}!`KMZR8AmswC{sa1b!MMVX#^}sO_DZ_Ud9u-xpRiptg z))p5RU++r^3IrsOiczXE#LLLa>Xe&M4E;2-usAwgg@NG3GSbp7$N~qM0XEEJ)PS=@ zcGK2$T$*R$?}LKyo&uPrd3bm_Iy&C+q)5{=_?~jyzkgSfEp`!beKBtkoyeE>|*!~Xx? z{}n^LjGWx`^mLu$Y@<zZl5(5K+I=I?#c4}-)$JDe9 z81kglux{(M&>JpjN)f&&QH$6Rs}y1hCYjAv9ur}o^P!TZ=n$g1P!=2l%*b#!v?wPLtPE4wXR-8$oC^?RF7mvfWLr*an#HKrF(9oBgNwwsQD zz5&0?*`L;)YovGc;Qy^&rS@BSD*KOw73jCt&7Y>!A3dwl-zrmont^`=sS1BtU*Lt=G^t*zJBGkwe6_QXlwmEqKCELT-llJVJm`uv$G_!C`tyAEd6 zBwMh}uk7{)*Y($T@>%wI-EGJ*!#c;=N;QTC{YI*6&=m+6xH!8V@bHn*ucPGZ?1(Kv#%diLwruf9H|7LzvrOOFhdA6!tNhlj_TH`zH% z+QnKa{B}ftd(Jj_?oHJwLg53SxjRQj;<)osBuwUzlD=gk&~w~p$*ba(I0x0x1<^r!F^=#&~nmKg+xhUOO( zY$Go+L_K>emHuAe#pMviq|4Y&d|Uh(OG|1{b9OwU>bW~p1P2u;rD&9!h~K}vJ86Xn z*B3}we}7F?)yMGgSi0~p+99K(qpkjzED=kKi`>pj(tmqC7qA!dJNu?mU|4Mv+tehw zTuekwP2Dy__Nf62HO7A!Kzndne7pr0Nv*?l{*Vp&-5NzeqEwZX$oWADJ#Rsim8*gG9+0Ti zOjO&BB%1~ljcl$BW(^uWMve3h{@nl&lf06W^X=_s%iU3tc?NX!^dX_4ED^(B<>P<- zQu{k^SQ5La|3x($EH*ZF6_#wx2G3E=l9(a8n~OcPn~{!ADP3sjEl-WZv;Y&+hj&^Z z;ZR*Fai4@g>kb(wf z*kJ1F>Xy9;W(3-c$qiVDogG2&-0$1_2A}_?H<5KDUzs{w;|tiI_H z=b5i*rxojuJw2BYrR~9I4wMT_KZR4vzk!y%W{(z zue?+y7la+Z|MH&#W#kp?MDMDy>TjAAMfGhvONk1%1=P6SQcm+y( zLPtzw5M@!YafYgtYjC~n4o@tfx#sffTR&w7GU@7Klh+Jh?})EMP(Er+eHZ6!y5tLl zRPU`8*!9pFpD|;n*(n{|1M!mZfXWy;{Q4m`Uh5ig=$;p+{DadEiTGM4*>;LU=>4(l z@M621n1Db?M1&{#?){ihh?0cdTp=c_FxTt0M~g=0cam_h2QKz~U^s$(==()_K-NtK z9ou2w-AwQa=f+C@wf_jemY4I!S#k-ZL_-{_^vmG}QS2xYfpQQh2K6Saj-+N2Hn@J) za3uk|QiRS)4%sZd;q;A#i2L-h4*J5u3)s? zd;N6H_8l`>k&u+qhn_&gS7SW5I|$c~y%zHj$l?_wAKqNO{!=_2*B~R|de)?~klh#O zJB7&*Vq)|_G@cFkp&2ua!P5|O+yUPsf=fJ;xb;fH?eOzl-~WWfwm8kazCncVfM>Eq z-wYHP$y*oni+TU@-V!7}#VXEc^)ndBn5YZg@p0T0)P1&e`c$x-Tm<<#A0AhEyW`x{ z+y9}-ZS}C|Cy}*PSQlL?WdLb?tyibub^MO*Vb;Yz*F4ED$IFaUV0Ulc4MT>3hg)|f zspQRBu1WcPqdPP{eq??=Tlg}d%s)iqqNB}{f^ti6|4lwFkYr2w%I(J|m$st)?v>nF z%q7HBS<(87V6FVlFw=lW-`Q^C*kz(fC5>KwKlgto>RwH2jon&ZGOw$C)!E!p2clCa z7bCoG)%s3!=uK=*3U;db9YSz{c)*|TJ|0j9&S0j=Y(?JA=pfxA69S-VllAgsPyTCZgzfma zm4G{3A!lkkR!&rpJcBN3)EU`B9Fkk5^C9l(l<)MOvR5{GvgxUgOUbhCd3!CUt<~O> zsRBVzPfw3>Dqjx_He$nv0@oUOy}aHBGp+uH=w@6bUY)43KfC+(xk`pe&71c7AG?Oj zP1^(WsZyj1?R{VH#MwZe$IE&dQvrZ2S>4I^A%WCZf z(~%ptrRkWQF3GU7hmofkB%CGPm%7+;ZIZQ+H)HEz4C9bO#?)c3<66O@CroHP)J7+&*g*j|;ThGcU&jqRZ!wyzXEL z=31Xogtb*M{9?@CpSh>_GP+ecUmyL8yPK&3+aYx#{WL z(k!t?A6Y5?wro<(`rgv7q!JCCG!M~PwoI$2EJ3h|ib^ytuwW!FKVM>6R~?qb?)~qo zEI)bjs2wOTE1{5u_o`it(21MWB z7S#wR&pXay{LI@0o(^a|)uRd<%{6S(Ze|#-CDx^CscJ13Y;1e8GwyHQW~3AE9&p_R zt9m?u}RD2GtOa#Ns0ErixgfJu#rE9=sfq} z)xJEkBi(zubuupwHgdsYqMkr0?n4qKtE)TS8HOX7xcveEI7<@~7cbSZd-<}x+IHmi z1DWrdSJy-U{?^w*9tb^Y>0n$MI=U6xECP1jy`~$fh7Xg9ven+}j+wZjF379KsClH> zpln_Z&E)}9oVe2Y<7aM9`{{UJ6pXSKTKVblPszQ#^kXE zkPDVZoicrdYvc^rfjNr}fj*-hjSBBzG|yyJ4vxI4q_$5wJ`pM!2ycI9jeqR$d}#SR zW3^Y;?tJa*rtv(vcs;oEob#s9z{785hevrk*~frC;No~w5ImP)Da^nSij4zcqG@#7 zL~RQ}XgJRvMchY2LxVsd#KgoofPHB?DBR$!CkH2IxlXBpyu5rOi*}M|;yP^|~nCXGyg?`|#j+QBlcDs@bto&d291y0mLh&z8(?KBoee4A4+c zNY7g`A*Y36ZKziop|hi-BPl5s~*)}J;A@=*r>_Hmep1=BGx zF%?x*#2%0r{nx(n7JoHh;if~qwGMN9U>5+v8 zJd3xkYFbk`H(>ayyyxx=^VNQcT?@*}!X`@&Bi!2Bdb~vc=;r!T8>-XdviijHO6Oy) zTukfnu%cC!Fdv^=PaOTjoG0m8I0TC6S~vhHXKm@WC@OKE;~+GgxB7Dx7HAYE>@KdZ znBb>+Ux1GsSMEHtT8(8KO0jy|5r!yPd?KQ;LUr25@+fxFb8oJtV`Os&f%pr;2mAW4 zo;=|pi-JRSvqaokXulGLVN*mzL_7mVlJWPBk0(n30HC-A&g{n1@0#9iHy;lUo7do? zKj;i8n^bP#6lpQ}pF?mJI)-)lef^SdwyAE^Ay;fT;ujypua>oMhHq{st?vN{rpc(t z$Wk*i9l1z65EIle9@?)@CMPG$+in_%Y)TAjw)#?dF&+Zcu2xNFD{cBK2tMKh%Op0I zbM2;uZxsixeyE;q=c=}bK~|+Qjj;hzQJl|Cc4wO`eqcw*@_HYxTp+i3#XtvRhTy#X ze4>D}obhdxxpXE$8j~{o{h{7(bLAd3o0{d``&+Cjf`ZtH=jX4kp52ZGc`_1T)#v*j zy+h-3)9iK!_Da? zWy3)hmH&RdxR&Ei%1mcnv>Zi@0nz}+#C>;hdh^N?mT#EmBXG>5HQl0-r%;;2z!YPk z>y4Hzg2 z#_6{+94NJ$*oLplm8NNJ#txb{Qt)1t&cdzyz1R9u;(dQ?jkgG!K_bqAS{?xktGmO3 zgWp#Z-mMM=%j%Oxl_$%?n{Z63MZ z+Ue!)C}L_t#)m~TpLy09*+Wa^!Bjw)dIyo_RlTysJT{vZVXqkGHyT8mtI|#|#%l5* zbw@^J={!57y((lbvaI5sG&JfY#I~e;oYKsh~PlnTXo<)-aR*F{7yR;(HN!^zC^2%hT;t zm)*S8d42p1e9bfWh`bka^9&<&bnCLlGx#`0N=OO+sm)bt&V;MCtI2{I?w4gc8#B$- zC#sHDx6`B}LCf27hRv722>sj|tJ$BGCw?<=NeP?<*ha=%8RE-i!t$!sWz3f*q41&p z&2|4V;l{~z(>|>mt4Kf~jrKB?m>1WZe*iM-WCHd=R(&M0GVBuPEAcUsH+oRGN}52a zNsG_J`v5i8$(lx251@HcUikGOTx7dD1PvR`lK2b#pt_BFOr)_vL~PvhG}%HtKrjWI zvPRJ>LoVcT7T4oxWhvN+Ii(yH6YfesjRieRu)40v-=&g#n`bsKcP(B_`nB)&*pBCh zTaiW5F~Dv#b_^!5t*sm|?Cu`z$e}T&nzGh0&!?;}xhhgG3|qqHA4Cc@#nz)WT0l#U(b~daf0V-)1&JBX>Y{@n*Nf)SwzmprdmEz}=IE~Y8i;P@1RfV!*D^<9 zyDOrbnKn5f4S$S0cQ3O%O^)8g^DT7uwH(f_H1rj_y~5miUzbF|+XB6|4!Y!MGQZkM zC3SYy{a%n^I-DD8O+DX!Im{Pha;md)+y7FRnTw|5b|7KwX>&`~-bt+4S*ma;mAA7b zV4?g|$(Xgb{;;a#wH8#TbY{lL)N~%)cC8b4hGF{+0|Efx~f->o}LG2*lg*r|KO@}b8=eG*Pdsn)Oj5&6>CFzNI*m7rfnTKrsn46 zXZw#(C$)V}_k63r@AnUQ5jlKzV{CME!Le!|pFS5Lm+;do7-2W4{y96FA%*IieKzg| zg_98wBqS$WgTYi36#ZOmGQ9;4F{Z3+)0+i%YAS7#d9@0w%x#H&I(?VB=>XbHl?uCYh@nRJ_t^AD5 zm5b@EY_^}Q>`i3Fzmw#gkd7Mc>0!QlWp2JyZ978ppoS~0ABZj~*>>;2<4<>t+Jr*X z>HdD9Zn=rMc}`Uo?}KcblarHD!@5jiR|a*|R05yEy)slh7dsy1+zBr&$lHEE{T=ZC zhIsy$hyG6{``_k>Hw&|C7o7xA}+3{@382<{xVOUxWWonDYPc49bL;74E26S*=Aq z7v$mLAxX=TFCTAeYD(rb&14Fs88EM)qobpvr^gFv6cQ4uZ)!?r)(m9=00Koo%>@PP z8KR!m2J9A^d@21_)Zc6D#zA8x@?=u6mNf>xr@Ji<(*o4NvYp|&ATptkT^eU-!vFwa ztMI^cZ;lX1g7vsN-=?>}pAbkc8IVqfLtx3OTQ<|;TZaowvdmDCdjX0~PL@Ll0HiGW zO>&3y*pkxI$-DDyTwGmYKYuP1qh&K)E{0KcM^o7Gk%_u(?4Pe^;eRl&pQ(4=Uuf5X zx*sfceZ2<&P)?_Y0{{{DQ211p_2B#W_tDV8klW+C#?KK}o_q^SjsIZWd z0=z5i+JZx4s3bXHhr@Y_th!|=P8D_QyRs(jvC+|)eiO7!9_;T5Wz5Z&3e|H7WNarZ zEuEaWP;mf|7+@k8N8${Xj8n-5p7_=dhbKyDeR1Lly1Md1Lko*~F8Ft#^p)RV7gIa(0ubId&tJk!^5P){L#BY z86dFZdpN!_gJzS*&inW8QQ%r_`QASaed)qS7s%~OHaR)Druur^4=kVi*E(=a)6>&) za&rE5OBeOz5EGj*uXy3uG!+)n{{I6N1Gy!&QZuRnU@N6Tzrzc!W>&yOFploi% z+nzX9-7>o0HUVk-v!3&)eGF8CO~RG!zCHFZhp5V`ztLkS)uepB+1s^9BkzyV>@(Ql zAPzdZ8bO}@WaZKNAR}ai}+rook+Nb${^Hw7vg|8@OTK4xZS`SNk_d~1tz__K#O zPh@i|b-tR6+Fb7zK9WlE=H~jc zk_|lHIy*2BeRta*7P}9;%pp&=gj#KbH?o5LP z7s+Q7QHZjp^VZT5iI~(>Phin5?)%IgBsIE}+<+B|MLL`#gL(H@oIylZ$5Gu)xVIBD=1ih{|K|PvXZiH;^z9&!rYvXtUnk7zqzGF+u3Gq zWspHdWZHYNo?&TY^poYIpi`rp#i@gzC&>jk`jp_SYt{BXFr=+dyD5K}xYfsFcsgrd z6C6t==s45jdwT5SZ*R|rLLvarRaN%PjLTW+8a1?(d`ZUT_v&-so6T9au0mnQiCe&tgKh~s8 zIMh}bB*c>6m6vmtd!XJj2+<12KY7p=v@YTDGXBhE!&Z> zu&Jw*Q^cvYsy$@+X6Bx&%Bq5hsKZ)M(12!J zL%p>ce~R0^=hgygRFmtk?mUAhZA0))Hx}CiU31AE`?2*$x;+WcAhd13&fd@tGz8SE zK|;uNyRPfX8D?W-*u0o_({sXlUi@5njRyb#+&-kh6XTDgLu|R(Y3dWjy;>Eq#F8(s zDJ#T}dj+535Y`=59;;sFX3V(ubT7^!2BKUe^MT;mgFURIV58Dys0qFHVR%FilWeZ@ z_YZiqa?x-5J}QF=fJ&KS=hvt6j8WDdHhecPv$BMo&ATE9_vTula8QAAnohZiIJ~)9 zV<78w>F{)JFmBR&#C%isd}I>kXn;Vn7)j8fk6e%}IyIj`l&tC5bm7+_ zo8T^%KH<~h!@UxW<8bDy#9ob0x!`zPBA^Y$EV=d(w5ZFx!k|=#b^L%>u%V&B+uM6( zzhq7)<|dp*UP3}5Pcd1-X(14|V|rSYjZI1BhowSW;uluKhOav4P-FQZrn9^{!z11! zer%P;n}T7N6PDHV&;)q?tcoBeKm5%9^5lBI69VsgOi7{!9+4psjwh;F&60H1-tuUL==)Na=wnz9&t#T^ zPQSwnWq$|EOLgoTTvodyNsp9TpLx2w`yX@>Q&3QNf4m2fiVDMxleOqk?B~WfSTDCq zHu5tCyFuEg$}a~38cG5rDyeZgZJGeyxO7RlV!bB$n+qLrMSL9Qq3JX|DLrvAvpf&xZP z7XVCb`v zRdsd5KtAvss=oAb5H%YcVt2MFO%NQg7(yJ1MViADQCD}mF_f$AX*4yA^fv}~b*-aQ z2V0Ev*vTc&5UlL%&Uu|xSS`lB0`&sX&00^hyzz)zLZ3zaTtKHcq z&z-3}IH*81OC<~q08q`)8s%_FvYdR&T>>nZ>hJ>9iUc z_{`il#X9sYm+jNt^C8u8>SJbR<_C?U^0IzqxA(*|YWq?=1OS*C&jct3Bma%!-nPZ8 zna)<6+eD;%S2NmlYs90KZ9bW@!|^;*P80A)!gWP592Yx6wh;S3^d_HI3=$9)v8|Y0 z!sOe3h8afp4)`T+ho|;=TjPOSWTVb~?d|RQ`uZLo9@DiBxv1y{NGyV|;UYUGrp#ge z>Q+1z;ttE<|DnM~_jo!sA>nu}4g5O>|K(L!@u^g`V|nOc(dog43}Y3gXLO?fj_w1$ zbgHAQ*#E|erm;M6wzo&zTwl72%%%&wY6+r_cQs6v;veze5sYwF48>`WGf+oQ#*QYf zNb@0l+hS%};`(N6XF5OBA}1+q^tHiMZKp1NG=~BO+Ff$;|%0@85t@SL|sne~%&OAWM9h*kX&6h77Dx!2q* z=IeX8v0-!PRE~O0i2WftUf=IB1OhvPG4PcbG^cAFd{1|kUx4sPNxiSmob{7vX=qrq zi=}_#?zHsgEMfly;`;aImocVqGrJ-I=p9Fa0DzhpCmVErl1wZv@gF zJa~Zl8#Hiz^6fX(bP zO@glZ`FR_@#`=0T)7EsU(WRxXk0S-Df@%HbEhh%!WyXJTY4hovujJK!5F3n}n|okj z;9<@ahIr;Xcqbw%3OOE=QD zSm)^O;)3$r_DeP*rm$0#7^tPayo4+?`SSAe2&3@=+g@;TmfMcx1JUK=enb$m9#*Na zmzlP;I?jqvOFKC^ZI6|rmPG7T92~@MAWA0>L>Cnm?asGhVPg7bPkEW!rxGA%7_GMj!}Qd0K>fwE6a z>#HzqcEeh_CkvcR>N(P3*c2*R5)ND>uV2Z~$%Ce~@A?mqXO zTlL8WwM_VfsBNr9*iQUYcoUI(}`AL}>nMjGv>`fd@t?VuMN!3(8FmRCy z3c&F>n44RfnDPA43&R_p*u&1&-kIn3CVo;^CwrdX;^DD3vNLn$aWUcfYhXNo_2&7l zqu)RAu(h(c;U~3padG4U0^Qx+8QobK9h@wH%-r1Ez~5R)|KVzC@?UbUd6}93 z&1}uyhVBexW@HBb;rkZhe;U-A?_Wc5bTV@`vv>I|&;KdMUon5>a&U0?ub|)Z@q4;{ z3!R0Di4FMs`#+*~wzIPRPkVgxWiWBDb2M_XGPeDvoEq6%+5M+9Z@#~c^siA{IGLK- z{#V?8nG_Z#CRU&Y(A3Dqh{4Uu%$@9y$bTQl|2$gme;KW*lac%Xh+t*{zWI<6|IW_y zmxangD)7gue49Q2zTYO%%HGPw%E*?%#L3La#lcBH)zZPv$eCEe)!5d|i4XX zLs&W3Gng8=m1|LFd|HUBfp#M8vq%vpftU%dbE@$bGC zX7*-Izhy_(%Gk+F;kU0gkd=|0T-M6o)x$uOi^G6}jrcE(298b+)@CLyKvs4pJ7#hb zS1VgnhCllFlkRu=|Joy*-@ZW3E>F?W#KG0xg`bpzl@utz_mB1Pj~V>q z-G4FsHnG2NWH2x=zwL~GzZe1l0B|;Qc}th`+h(?+y{1CSjSTAS?8#^eZH30~BC1IG z8eB?MUz)YPdfXnI4&`J%r6ToVyK{~F(_qi1G!hMsy+BOXpa>-?8>TGWS@;A6*ulw{mzNVAdI)lm zlJCWnFxv1oF0#xPVeaE%+{DwP^>bpw912E*7J9y%SvULOj|l)jj0Dx{HUF4b4w5Qo zN18`!AkCs|?MbV#smLi?ta|nl_on}DdK4wi&1Mo1c)!cotjcal|75Yj5gpmgY~d%Z zDs1d?X!tV!rHs(BXAwSlD6$;D@KxA^eJoJ$#l=Ti_laR*l1l@0eYJgMsqv&NGKIRs+$PdC44L>e zTI>AHFXDhP!e}Z+!&I8$8x_R+Ev%T7JGqG_hP@k2e@pLe@Ar4wC8HwnpUi`q^aS!W;oB+sm6K?=JR2*c~xptc9N$m4!s5#rY%fGRcXx zCW>|=u8c%FY-_QI>4$BN5enp4ga+0q#<*-f*?wb(_S!8xBD5C%lzVyL8B zHu}|#Zs!@C&fyd}x!;UbeaKUcm*|LsD>H$MCJ-QzwL-^tXBs<+ZHm=LCV#=XG0*&B zU6)3%Pm`?@rs+z6=S*(qpYJ;fd!F!f>})E%3u#U z&)xk2pVk##IsWBv3`8SaO!qD$a8z!@XyVkDoq$0!m*vc+MBut$?VC@v=P!JDU90%M zSRvzW+e0HYcOg^C_3&zT{9VuK8sz$zBnoh3PHNNyZ!*U=KUdd9BG`l&Z>@woxT@Ji z&^Sz?^~^8vMKDZEF`d+)T^)sNG+xt|RV+;pv|cGG4UX?Dbw5OsxJ$goYDJ-)V_Tq7!~10W4n1_~AbgIkTa1JO7i=VgZ-2hng?dUF;1N7PNV_7DT1e5Y=N@)w zGYYaXFb&OoVJ|o*P?Uj&S&n`@7=Zu)bV&e!f4>RB0{{RM2YZ*ddp{35+he_@n4_j- z-*F8XL?}r@@=Ho(dY5eCxsnsZxD!CSC#-6N?q~c37V>7sXEe{O*Gyn~JBRe%Xz{KeQrs`QY-$Nvk9O!mO zV{Io=oJYof_ujTnRy|p8L<7UeYr?1C{i!q+sRNUE|Yw?M-h#-d%eLrs>7r@-vMS zZW=R<%bKLp`Uqsv`qQ5Eso*;QX@KjOKZ~^UjUkLv zErvYv{=-J9K}Q8f=l#*l9QD<)X-9FQT{kIIK&OzBoyfDRPp)k7v)*ZBVAZX78%WYZ z?wp5lB9htQsRd2G(^K~c)u?Zy-V?iF61rMO5+OFUhi<%|+*655jC48#c~RX?UscAA z7GlHc97?wz8d5(LfxeF%oCoQAu%1ORxm$xym+V26K@rXwD7iYp4h#{{Ch<#fTl~Q} zrtoM`%L^&+tXfX%b7bmsNbDV9onD<8oO4+-0b;bD!M4JSXu_&s*F13ZOVFY?qQ~eY z*;R#4wDBbJ=i1@Zi*gayC8cDF$Z}Bfb4CG3S_KlEr~bp${8_CHw*Ccon*&?h)6>T2 z=}YpD@{(^}-#IZv?uS1L@T9evFgZ|l0s%kC0)LS47{)ygoIHGxXj|KFQy&5$;>Rf8 zaXWVY@K1CwIYGd`E@gwsW^snLG!|ZRF?z}7FbGqsRx6Jf%^zAsw9|u5W1Lo7^0)ms zP#f}YZ=*usoIk`Nuc!@sYri}RiDa_m0*Ax#AsTuto#L{|Cv9F_AZ1zpC7~+8kL6-q zu)EPz;DFE$Gv{KxiRUCn=eiI<&$siWhPTuPTA_Ben^nyMfsi7%{J7LQQJ1Kk1JhD& z9O5Bb9bW)uf-O%(&rFgv=TH$k;)Tr9iAYw+6)JdB5}4ne*^b9!o(Pl~ zId*Xtd(M&n1*LV7X1b*1**H{Nba5z6ANr_pSnZk|+sf0J`1+jd*H~@7(&r^S4egoJ z@2)tFi>-C}%tiY?NU#U{>8`eIqz>wnT==d%d+3n4w*8(9?-sqH_#F{cs)>Ua6ymRU z_`|Mzfti$%ZIZai0)!$yY(bV?0^}mbVnGE+;fh?iBJ{{as3hFDB2S{5g#*2Nfrkf{ zY(ag{Gt*vTK?21&1EpT%VLb*Z1r6nm9XH?HP5g8|rj8pd0+$G$fNSaVD7WWF)U`LG z=e%~Qes2D?Qjqgii%H0>=@6gnR&o=>+lH8CnckacqHdp!gnDG-uYMgc z-}b|P>i(EKTVl!lq>&!fUBq$sol}hLqQ%_v%>AnA3}bMRs-(stV{IbQzDgQXR78oBe!*Xr?c5fr@=(goO#V zuN+(@;_+CswL+~rwi=vtM)o_t4N_08IaTGTCDLMNC|T0_uO#|<<{cA~j`a+spXXE3 zI+svYbW#neydgfGzssp@ZJlYix~+wBNuZaRs|;hHv`N&uz1_uu_7j$sYJ0tTvECg3 z>m8uTc9JX^AR!;R%m-1D9oj~?++8}5aB4C{O*hCyCx!3@2n{GI1#ezO!`Z5&aZVK)`-?bL<9^5Ws z;jGE~e!G|VLYT`3*`Y6#+R)tOn2Tsuy!QK9Om38iL}McAoMGHYE-)V9pkY#RY{gM| zr_FJ}r}NGb&ukoOv@i<6=F6DnNkrEx$sZeFOJ*ks?~_8&ET9Mvjn9WNHO?swDigGl zvGj^I1|_Ha5o8V*ianMoIr*lS!r#IDqK9Kgv=A#yp+L|gar?;NQ-Tjyz~Nsq_RL(n z1aj1C!{e$usuj2Huo?Rz(ppoV3+-Y+8#hsi`k7P!-V-LUlvEIP34V-h%E>L%3VfXt zN)`H>ysH&h^gD48EX7t>bf&PoCO#sim0;>q;h&~swj?ve04CgRFVleOBjM9eF}#+z zSId+?pqk+ML4-sHLINys#{3U+!TJy>20Z)hFGi7s9Iyl@-L}PTNc@wLIr|&>fyxjC z9`rqfXt^@wzK1Fw(0#(fhK|6Zq1hs`VBy`Axs#k%>>;8di!{JP+SAIMcPo~ShJ;08 zS&||=5@?txqF@!^NxRZY9}b^UDs?_r^Z`356&lfUA$1#z!E1`y)>XL;8wX4W6$zv) zKqEppp$%wuZaHpA{FXXDg45-?SDlmKbzufRSEJv-@}UcCWo1-=S;nGCaM(I^>K)#L z6~yn{DZL|e<%!W9sF2HwZaST8ulZ=KvOSIC;z2&361@J(I_Pe7t;@=N>&7i#)&tsF z`p`M{OSQx`9}2}t`JES1(x;PF#pCEOLdZ@=r(`@>QWE^9<+#WNyB0vy7=&UjRGf7j z>H$?>An`>60K$Tm4}5zQ3eZydkKf*hg(!i z8-W*oKUjDmZ2JR@hE~CF5WGhpCC{bB&$m>2BRf2rTe!JE5$~2Fp+`d`@VbQb3sAvB z+SP1<^5M&xjwp6N4o{mInB!n~4it%dl3457&+zt>egPh6ZzCE#FcA^QzyRSQva~C1 z6cjG&fEf)X>TAx+_JdW-Q%UbOHU!f8Oy~(>gfJ;EF8T6MuE*u>=EE7)uaHqr-YLu& zk~^Bv?(rcw6s1y~ANLJjjUy$(!hMfH&Ie=KTHIpy>2&<}%;V0+jEjEABWqfkNy<&9L;GspQT(}MiLaLo! z54IRGh{ZbT*T>Q1+crsr&qhY_iIqH;>57QlNj74?5rZ(!U;CsvBxw*Z!^cqlp3yOL z-XA#AGjpfBynx7(Lj3cZ@#ZLwnuueD&re$q0~38$M9|eOoj7Seow%ui{2o$sJwAkE z%Y%>nr}&q=N&lXFuzW;1m%L-$U(|-1@35Ur`|#G!+=h#cAe>2gw(_QAVEk{WnmOQ$ zV$zQE$|K>juy4gJ>aCTN~jv>ey*y$5zY#@wAzT=vq*fq;erFq$`Ox>xg zUMYRwI(_wv&|uh9O(ZIzYU;3l>l(Dc1wBOej`C~f3!ppBNBlx^&)j7m?Lc$VBs(Us znT(aF(TKQdBgrVJ(8U)+`sMwcfY;lSz;wx8`1xFRF24rk@2=M;$!tn~C8P+qoh> z_>{rkrsaXcJ_pbkNK47cWAxDZ=BG7tMYEnTxe9+74{m~FGaO#vfviKObwA~X`=;t$ zTxjo13>?1oGT6B~z;cw4l&~#vw^AQB$F$nZDc9t+chX{+AP$diJp)Ur*V4hrg*sB zWrG`5a?5k&829n$oiZuUJLO}DB4jsiv5>Owz;J4z)5=?5R4#aoN3E~LcV~oxXxLbH zDR}8ym478YJO_Sxwg*EEn2S{QcSli<@cs~WpCDP^4l(+0Y)o^DOh<5xUg0Ls5Wr5n zF(e76*dbGQwKwiOI+w#Xyj(4sp z#6uFC86*0hgO|QZ$)}=1Kd-i9(0;)uE2=>$=y)gNVOAt8#YZ9d<)vv4!OdVJa=!3< zcC-BExC}in7`q=n6TQxuY%roNoOHKiN(7@~CrDM}nW=6cEPW>e3Je3R6IoEKPegy7 z21lhu9;K%m5t}wamu)`nx7n&~c%F!jvnZ~~HmK^su)Hgv#`^qYpXal$BP%HqtKyHD zYoS9PDD!urCm-vXh=;kW8hEo@i?8GK;%*q+bv)Nm#jZ%v;n7LAD3e1yJ{6X$c%L15 zA-jU4!xrhxtHr+gEp}om%0c89h}QT}ek?=X8<2aN6m|9DRN@lKRSh!YLXxqt=s%#LKW*IDl2fmb zkVD5x*BmEJZ7#74YWX}zM zKId*Wysu^VhzsG@cH<)r%*|T((?Q~S-0kEmyHofB4j%fXaQ8XAE$*}jx`b{y5!fOe zCG`4Dc4Wc?9TsHPofZ=meO2+8Y|!Z#)^B6+l#S?P z?c~?#2vEGndZIX3iPbcTzxO;WyWEj#s zl0S~qhKNVF#_<7ww+kBp0H|8J+8Ns$S=l-RUH*8<=xA>dt|%|@9u5}{006v~k`z-0 z008v>02lz~9RL9E63&YP0Ps_!#DrBnvW~N1eb9IEyDZGdmose=o z9@UB7G;t+6yRo${UDn*9BRf5tZs_*)876UoyW_|0+UZNjBpQUj5HbG#3?e{mT1b$X zIFAS!c>)OrW*-^?;tKrTy9Y2Zu;)*oK7oXU{@*m4Oe4*GMiQJE%}%va1nmugx)xA1$@$#{r zeCNBLQ(vnt5j^dShMi1ZU98aIVr9I23Dua-*KWgB0TDx-bZF~QY929=^2BJR1+((`ca(M=K>C3sdqc(GdxrluD&?G?&FK( z5j|n6fUtkba0qk+E#KVCaYw)>d}+9jO@0Jb((5*GfAzcEUGI)GzxNxX%g+`(LVO*^ zxJ-sSBDD9kU$sOr~bMDiLm z;m9JUbdH1r4s!HFz9|EPn2O<9kGm6i|HvMP!SK-SL0Yhd>PY&GY293lF|+bet?+!X z;+rT_V({FrGM}hp0(wqNguJX%MtGiAJ^CEU4L?z+u_uV4C{`(CJ%ZGqpz^?=I`&Jc zec?;&*cgxRFHM))j5|OkI6G23W1B#Yqij#53CwR|+ zmYZ@nTZ7T8m*EX)t?pTPeY6$o^63c{4W%}rEg;L1Bze?~((hPI<|*fn90AKiT)W-g z67P!DF$-ge%CSazMMC6O9laKB>}_%zKYsZ2ow3d2^)$BRi=K7{>S9Ml1gZ36zAx*( zq>YrMT;Iao7`#M=bmz-m#_n3jG~Uuuw9Xb(#$uF2b?4ei`0>F97F1~7OTq^wGg~I6 z;gY6^hkRphK2&NMQUpGX?rwPF;)WsjJykAz!k@Num68Hy>S!6C?h%FL8m4NuZ{68R z&hJWfrX!_?`J{rMuyux@=%VJMw|Tl5dagyLW7gf&a08NF(?Ix2UpJ3^OInJHaLJl= zil{e2VHPGgf>c#Tdg+v?^M$q|HT>$+c*%#!NopTS_QzpnL;?%K#_X|6&Z11JOp=tu z^aZ>80Ju|5__SccBOh^y$})ANF!JzYO)Jbah|#irtP_LVJY- zM=^p}ZXB~2-BAn7AF(mk@?l}=`Ygqpaw3gK^OVJ7p<1tLwl4x-15JwH;tNe#OTSq% zW!2twOCV-o?guYkHgGqauTievcOO;OaV-Dzt2+0v^XqQw8S+$>Azl5r?poOOOY;Ob zG=gDmIM3-7KjIMa$#@z(_UWMCM6mD1e#!M4#w0~!M^oqJ2P66Ab>5lk23Z51agW_7 zPKFiRDI{Iq<#GDpGvRV5Mw)Yd2YW~JZ5|{W?}CskP*60Kiw!YKDWZK5=1S7VQ+UOg z&5A4kB=cPBvKI4X(@DrF?9B{;En|iBz)>Pqzo%{!&a_cHglzF?%h!<>9UHgVZ~Y2# zqQH*&cK1o;=j615lVf%bddOM2NB!l@>nj^1bNG1i6A0P-E3$ntfU(Ti#Z91tdSSl} z=&Oy~dLR|3hwCUOv}5PhVS#jaCPV=X7va4rG{lLpVm3;%&#J#B48(MP&|qWe+4D~d zOxZeXdW!fJq$z}4w5Vs(U#KMYvrHOjnme%Kh~f~s(}o64uOVHtQ52b_?RDUSLkCzr zajpJh#)A8?;UfrA$h4RQWnRjXKka%Fyg!xGAA}OKl7?GNN@^PK;D}o9*^tK1#~xZ2 zdC|dfh`P*nO;9`4kpD_hYbVjAEV}AVwY_^nKL1h{;wEGo*#H+s{+@jM;1jxtfOpR- zk4VvZ;ILwY`lTI>#R}|x=MIkyD)uvR)U)o{0cU)fm3$42JL;W3q6Kxl4#NIyD$R2q z8m`CLt-zHBq?a;!juTcHk!90V2$w3&w~%+=fvUf>cARa>PAFE9v?{9eE&H&87@;?8 zA1^-8E{KY)Argm@4l6XH9fZmb4PXOKn~;efLk*r6&<+RN`dFx5M%%GrQ<|%!~h8^!;pAH>07Jl0HEG}`IN;3TT z#lKWE-iVaLKb>ePGi%~SU?d4F`_4TRI)VuSS+Xpy`-05?(SDveg9;guUR$e{`@(X3 zs{OJmvpvAF>yOdl$4W73teWmbHIL-A*{wzlV-ubd-&ScX%b5*(85oO?eszN|021c> zY(KbHT(F@+L+0|!ll;p!;1ZSWU5=! zY$ba~^K`v^?-#M53v4h@7+Np!a&+F^zR@MHzKD+k>Lxhk|hwFTqsU zOy7fAb5~40UO)XZDO=hbXk46@W?8Vd15C%Qvu}-T+B^^8CyE@;Hm~3fjzM@4QWUeG zNlO_fV-`lKPVFjyk|*Tel2YjB<0_7g8A?ksiH<%U$*_%1xX|gFLt@5Q?0Rw;+*iN+ z8Zm)ni2pD zlYp#e72ic_Q0gSgI5wP^U4=gBt`@uENBY8`Mocxob1Lu$@M=QZ$Rpx}m-8OP zIku(im%gb88tAnOUe6+sp*DB=6Hm)ZcU@Nv{0sF@Y{qT6!k~9C;95uY(yKgeM5>#@ zM52duW(-vsX!Cc&m++<8JFyHztGMzY4108qVw{}GwF;reEbT_jIMCf7h690G0y6r0 zln;1=2lUrc{dt3O^?pJfPH0)^tSnJP`TffEt$JDA5jzT}_MTf#`U8%T3bE)QS5c`v z43YaBK7(b|3N{}m*>Lirxi~W<1v(cT5=BTy#j-3wlLhE3`8oz$3VkLmHEV2f}_w za?DP#kc#7>|8wRv* z1fuFkLX@^3v#19NcjXmszvLu396x30xOk$yY2StU4Hxz3i?HAn8NRh zjV4dChHU3ASdM#@J<&S>XPZIH6f!LvK5$zGQE;pcYznw}juw_Pq=Q7o!` z9<~Wp96cK|MR6b4;z3bTKG&(u&SUIzhlx>)_r)y$*tI)h;wG%~#$ui8T#~d^!>A6o z3rXMV)rL~iOdmanjhjy??r6(?6>zwt#y=o$ZD|#Gk(c)iR1)Nl`?9JvlKT(imO4JJ z?Z--VG6sNGmJmg7SVggZa`?0!E)8nR5S(`}`bgbQ&01Mn5O$4R^#L&~!IJHH!ZM_Q zV*A9CL}>`g5| zZR*5k;(XAVUtWAeh*4SNYU9AXC*k{_ExiWPSh*U^bH;TF95p^LtXS!aG|y))bG}cF zb_({~aSvw=b5Ckt&uS_Z(rvk?myaA3Jl>D5rOs3$WK3c}j4AMoN{f_FQ-9tI}QW+k4|EfhSudze~K&GzyLG}8a-WpVHJLu+Y>;Py6J1Eo1z{fxriX( z9_E!kWX}kf$dZ~{m>b&$U%3-b_fe58p_pi!mls~;{i^@i7@^6x1GpH?=JM)Zzx*UH zY+#f$cU#QE>*FetTM7SJc5)(547(T>($hn#pFplsvk$+aSBt9H3AA?S)`73mrA#5e z{?8@%m+}|*L01`2NcZ!@DdHl+gL{r|v42;!+Z9DJaHR8WRcFQQmY!bn)aMj@jV1+w zEH(wzdij@_j7Y%xN_1*`Q5223@%KnWo*$8Ei3N&cC6XY#8luvwd`Qmibq|ddPn-U4 znnlwDn!(_aqdy{uuv^lQa~rpgEn@wg80=bjDXaV3o-|Dy5_;XGXV=e4<*4dYEH7W% z?mjkB2%>S4->}ycw{YQ^EZef5LiHV5&!pC(43+lvrqw$tVb<=?RzvwwrE+JrE0=YN z9YSxoBKegJanYOMGwr)fbzViLCfXoOq_7uNQdl>PXJy+B#T*eQjDuFOy=9=B-#E2p zuho-A$YJtT5!Nq57^^-LfRhq>~@Q=Vlg6#v`@w`YnRqdD3yXL$_hj+ zAts_xaQPSSTepRpZ;%3RMNEf9-9?h^nGR<&r1_BJL3f8W7OmGqGz~>Lz4bwn?u%VK zc3Bov1@m)BQ6v})lj!fB9UD(P%}eZ$Bl2Sr@wu5Dmjo+a2$uYqUY7!@x_O|9@Sle{ zb3|k$As+nGr&-!^U2z=3#oKrY0>~!In0?zBCmTzEo5(Ht;J!!^#&WqJm!V`$zE&=+ zGTr#vAes1cy*nYzXTXfE%h1jd5#6m_k|1BGPq>g$zN#>ZBXqi5e%h+3n6BtusYL9d zpj}f=P9pWp@m-zxSZcC0e)ql1=vYQW5KRq32?6Jd>uDR?#Zy=XRSW;?Gal{IqI1h? zy@lT|-zeKiCS0|ng3PZGpPme5Bw_f@C^PSt3pA@`T1v#fn(G9O3bDR(EpJIET8^-s z7IYKjs>2TS9eO4KmcY7qW!MDCTmd-6~(CB2i z6*mk`JGV@?7|O>t*V_!TD)eW#_=+}_*1Nc{FEs|6>l6wxSDhb8vrM9+XroPNUBE}n zRq3NgkI-ZV)Mwi?`yZNAe$-eBCpQ}Zab(GJ!>vVhzN5KO$M6o=+`O&~ZOsaYQ2SGs zTD)lvXnGt5>qZsRMsGKxeDSK|^V-qiS@%i#P;o@kH>gXimVqZnAbafY*R0>E%y6gs z16rMl@Sq5}So?V}HDt^?r<^AG&r4a1d`(!vWPgD_(J}V|IRBb=lz)ulX zt(W_)t;;y9Q^UUZk)Yel>RL>ju-oyQv8P?mUGi2v!tB$<6Ho~UX5upGnO?fIzMP21 zXQJ9K#`ak*k8|pJM;{?Yga8rjlhpZ0e67h9_NgoYlsbyDMQSS`^~Maju;Ftsv`-?k z%1K14Q|Nd%*26GcZ$ECW)^o5y4BNN0l8y5t)SJnuny26(WikH)%P25F1_6=~)kO~9 zL$me~%FmN0?jSq9PsMq!(O2`I!D9{-@xGadf4vCxk%AGTjMfo>=3|K-Kfij8kFrjL zGdh6w6K7-3Qxpf77~YF!RHq7)el>1954( zw<>GAK^uhZ;P;#fyx*fA7@TqNzM9N#cpu3iZ{o7JTwMu_Na08$Jpzi<;mwi+`Wv`H zzijP||Kdw=Drc^L?%K<(FDRC69o4M`Y3<##kFMy=c_W>Afed(=-SrE$3TzN8m{pVe za-lpP4_8+QEq0!qW_qoH|?K+uj>hlk5@4C07@ zj*WHP@ev)<0NssuAIF!a))G@b8&Zp$px^-<&ND_y6ov&=VHU2s&Yq!gZ+_`=*_hIk zKGzW!rmoktO@w_naJ(WCHs1NuALe@_rx)?H&+~pYzCYPa;2_4 zj_*)TJq5Fgy0pSnYs2DZ`^|;;Co{IL{h6qI^2t{WzeJq#2#NXpw|Emjz?= zgPsm2Mf4ie-D*)G*~&K+xfAYWB-A>50iF`)yFWy;e18g8p*86U;Ui+b^Z5YAdfhku zPO~mYk%+brGy!#O>MaWGuPv?1C-%$jze)DG)>!$2mD}Ns{Dk10BD!jVLqnoprS!CJ z&k_wCKP{cqID;p@%qKmVh#4OI-Ze-W`qbv4n{b|u|7Z8Mh#Egl0G6*&+!Z}m;VhQW<6h} zEr6wjI&`5v8-cKbN}ff%`7KX=gGbXzMg)jD*3U z5AD|v8GWf%k|z}IH;*e`&osxY++zE6mDSYHF*MQ6Eh{EDShu1PA1P@v$tpsfajc-J zY|wCyZulZg^NH>i%FNG0o()-~x_EsuDRr#0hV#jwt>YF{@Sbf*dAycOJ7ZlmV_*`I zX-DT-J`B`}$NaJrBrR_>?S!?Vua#6GxGR$}c&OwB*V*y(e~rkw3vU8A=XQTV z*K(XTo!#Fw?CotZ$o;d;;At#!|1E!;SA_`20c2SM7%n;Ge^4@f!QMz_HbGP{ep{MxAOPQJ?ymQ6kGZL3!@a;)UAZhfx?(In0>Nnu9s zn16mf8b9Tkwvf+I%aT25emPg@e1uA1wYl87mBVN<&;RBWC5?JEhNSP1t%i{{wP&@| zdK}Q+l_FtNL0};jX8tr$qDF6UNSAB;Gmw4WL8smLC*i7M``{+PtsWVCRKl&(g-^hr z>(VoFO#kEcv&_exX6}r%N>cvCv)*a>1zOXo6G#^@cC&H^5oVlo` zunolI#xosR@YtV+8Rrx>Us@7iUM~>zIjRfhDD9r^0 zuollma}5>txehsY_i*%@fEFa~+APzQ>2gr~U&2a5IiAjpzGCh!E`?vImVeuD)#dsq zl4~B``k6_1z2LQg%G-&8@WS=n5`XlL*~RF!BZF@BXVUON_%<%pLlk5M?Kcg9Y)#7n zBznq{r-mN9_wRFmnvEmT->qA7>#9^JNXxtI4ALn>fTi-4?mFN2$8ObJLQcjJ?FLkT zp%aQTyW)QnVn8AKuNL(U6!j&dBI}Lfj%G z`SS3Ml-7`>Lfk~SO+|bKNhR)$2O-MZh|3?lZ}Ol!JWl-92%B7=%L|4)X+qXL#;r7L zma@K)llMriGM%r7A0C9BRKH$N85VCXA2fMxi+L;5)f{67SFGJ8c@7ID*(=2n5gY&s9e@;NYJHIo~M8Q6_ zdhMGmxkS4Bf@u&LKO7aF*i2mhDD0tKh+12vPeclx79;zO>cK%OR&eIC0(*%X)PT1@ zt)x$17n>-XbqP_+w{ASfl*vJq4iYo$q0uzOaOi>#q6^|_r#dt_L@{`fB>T6-j>Ber zts#gc@W}uoa-+GuYRtzfBS~`09;7N1two$dc4jmrF)~n`r6Rm(8xrt+WXMyVAvqN- zi&5fxIEDw|cR31q07XQx5fJfV=LB|1;WO`urKJwyiWtz{7NI<%DK0Y*G2>F4&v zJCh%G!osor-$%Yqz%rSPBk?e~?U>s>g2m(ge>)!g|9bZJzau|?eJ<5JESfd;dMl5S z5|7dsmF!c($|UNfmy!k@fNL;eQ2JhYr!y6Ag`A{yixXvf40DRWtI`(j=V^($JK9J3TO|_7oS8gA@!{ z++&i>agza9V0xk5S_t zv+pB9z>XbQ?kArJm%>55re5@L{<UwISi6hrzE^4D;!ANU1u#li%l6S&IUPH3f^x z7mEIz|Jr?hc$=(zb_>zpBzv3+l5oD@xLWJ@^bxi71NwBWp+}?}t-OT3hN>{>!jJV@ zgf4rsK8TJb+ddc85GGPM%0V?LwYIz(h87w zQ2~)SSMMGO)^fPeO&DS4ZA9Nq`uAQs;`@ns$1s7)^ z0aBEJc4F42Eo6{%b)k|Xjxe&GiLe|Cr%dt{_$SmcxUxa)u{jL=UgV)`p}q=TxUV~N zbG|a~UN_p9uOK}`{VKBNxPT7qwdq>+GE%joI(YYE#xkNfE7aK2N7$v64yHs?ACy}s zVLE(gEHY>rqL!bi+!vbz5$kb#8S81=$&gOUVMSLtF3~M7eXiJhKpf0F z%OhhptzhOlWG;+S$1oA&`A|CGnmrx+A?W9%@4?IEt$|&a7O=)xetgI>23z01XyvHH z4P}{X&DY%bJ@1`YW+j)i0*QHVN?jxs&q$1?*E_@wiS;}iN^O)T`8cSc!O)2-TNp^n zF(LwyI#yDbduo&xE_8V<(!;cl>EV=X@5VC zFvb@HF}v_1yi87)bDl+Y|N4!FI(5WM9WmeFQs_)PG54R#$}J|xke>->N8^*y?)^^% zCkt`8%a^D=xFS!ZG-;uEQp^M#^N*rhiJH=S)XOWaIE{F&P7B}TRxSQ&Yfo6OJxNZh zF?WqG3&!Qkpi8eAW@&$y7j(dKz0h7ZX}78&!58mnBJSuv>S{1NVEq;El6T0j%JBu- z^@Y6ol0W};E|D2|L4;tx{@YRJ&J9ZN3*u-j-{+}&!T_rv=e^?zgr@o7&}@9g$w}c_ z(tgSxzrIgSLmDNK^ON*fKa!R!?WL z?B|J|)f^W|IWkWuU0nO|6BOQX29UKETMT;3Q650)$f@-DloVKnZ8C0rN#D;%Q4PJy zb_sn6-0M0mA9UlaTEoOEUMpcW`*uK^dO~s{_W(*trXzG9nwr{@C~t`pfPBZlKsRG3 zM~(AKZ7tVbR04SEtlmiAQ=7TVb$!6&*>hj(&1Z|aLbj1NMcb2WNjz>&1zGDv;{lTk z<+prxoNIJasT(y;s`6>jUc%$SEy!Iza8V_o^KquQ4q6IT{PMn}9@->f`Ae-|bQT0S z){y!{U1!M(MQf%2e_2`)#NZ*{)7cLv_$&5|I!Bl>ChXWrtMEy~D`M4aM`Bmt?Wmnk zzm^Y=i@O+IF1<@#P6teK-1g)kX$Fd}`li6e_1TnXN`={)J52i}REPf8n}&QB;w##c z+K$wimBO#F;BD>IzYZm?zQahFkoyo7DhWl2((g+DV zfLVXI_F{M3@VRgisE3prcfyo^5-QZzp`jM)g)qxPYKhngNH~cW| zT%*=BICe@hkdx4Sc%=;d8!+kbwaJwweE@TM!HY03au>D$F1y{{d)cWN&3| z=KNb_W2H*BeJ?RW`z;;miGO7YEXA?WR7c(;;6oNVEW$e#c0WPXGP~k3mBMRtlgD-o z{^?)iW9n34LmsvZbbdw{c{kbJ`DVGHu@BM5?wJELZ2aU2sd=={X;oGuPGSdYEK&td zapYD9;D&pyZlB2gZbs4%G8iCi7wlD5?z~L$881J!x!x`;@=)_M$S#97^YiXUm0KZ9 zuwVqRYb#lyQT@83PXoGMkd!;J@i5nX2nAPe`{EIrx-M%>Tm4Q>NYzJD0eY6uYVmrZ zDb&QxpfpM@fRO}=Yng;u{ylN=18s_XY&(uqmYu9l{x>Liifg5P{H?Xj=h&m}R%sk6 zSU$X}R2aJFlF6RJ6VA;!q7`58x1^Q>b_P+w0Dx8Sx1@r-LkIl(r-=Ns{qanZe?|T4 zqeA{PrMD-M{NuqPf1v)jIsI#~>RVm@pN0$h&sF;Wiu~)}Hs6X_|1=`Fe=2SL1NiU$ z)%m9>;Qjmmc>XKPpQztu(VwQu_1{&%e-lanobf-wfZt@&pBDc&WPcS+|0&PV-|+lZ zME$2cVBG(GaDNq5|DNYfR{d$*f5Y?7BJ1BXy$Pm2&G~Pb{uEvRDNEVku>2{){!^B< zzhU`Pl>N@~$I5>j!5_-%O_u#>7(D+y$Nxs8{jn>BOPH=bkSN!Lkdtcor zH8oYcrmJS{?p}NM>h2w`tSF6&M2G|c0IICa7gYd&6$SuU76fPj0314-+W-K7a#ocV z2P(#h4*&r8U?MO51$cXZa@va%002OAkkN4l0JOgM7b=MXjR*h$co$g(N%$269ApfE z>dpg803Ziszlf=OEFG`9ifZf;!JqH-p)#*J7OKI)VTzHY<^ z;gfn}oHq1-tY8c&y#F?O_503-#QytlQOy6R5j+X^ zUqJucU~M7)KLP)r$p0Jg{{{Jf0sb%J{{wkOnJ%8k9V=3AZ@ z6U+PG@uula>^94LmW*psy)aS=Ni`ZP9A4A@ zbv%iLUcDfE4hnvH3!6$k(~aymDwkDmYt}5^G@a0Na`RA%wH|v$1Hs zUe63yuQ4Z^RBPL8%{gC&f(bM-V9ngk`6K#m{e14HxEJ1KrN3QWdrVI1Xx%+qP<(hA4#5yd;Ns*=20mSz z2mbABo3K}RXesgR>Z2;ZHdA6bTfc++m3Q~&Z?vd$o&6X)*ol%wf6C@NbX(XG|5r$) ze3|tX(f#7EXE!h1ahhvx5WR{3A-T9!_jR$am`;g8^N^?i;0&A4x}^O$m2!9`pP0+EwJ&R?&aOSzq+7k8&V6nGg0`Z`07baaf(dSTedHJE5a3w#%_Lpfk?S4n2jyqtrvRu9L{xZ;g?$298NFD9^%b3%K8C@`jI4WishIl0%a>n{p zU!T|c>)xfmuyKSPlN$#c+mSoDM5)a3j;)D_3D0Sz&u+Fz^2(p3nZAP2SoA{TLC4F2 zb%FF$-qFaif4u!yF9w0L<@@hX+3#jz;CkH{0fmfPgVv`zvZeKDeaWmFR_vT-pKr@o_9Mx0 zs(G-e=@x6&-y@Uc$6p9;eD#!6Zj;)L<)YV2m#nZao9@OS3jk0O9{uI*6iwaK^&Ash z>*Wp%_BcsEpV3GBuzgh9R;&-pZ4&%nDJmLDHcn%&qcRK1nHV1Ei$ou?$|6hfA{lVQ zTy3kmb5az&+i#zzS8t8E@fobehlYI8vwIpvZoQumfy`GJbduB@xcw~}rFa!=4c2r5 zKD_wptV%!Y?&orzfSfRxPT2-b7t7?IKFbT*Fdw%L9-tEKfS{DeI@}Fa5dqQ38OT$w zpNA_M8yk$hPCqzXy>hpbX*+XAcTxr3zLes>GPu?K{eat}1J8?LdR=G7a3p$KUhp6s zkUZDY7OPL3yTjJfy8B?-ok9jSKuEHDjJ3*tm|N&gv=H+B!`Nsw-SIYa`%(<8mF8rp z(~0PRs^{*y#B%%Sz+WpfUvEltg2&-(rc}8qQxvUn08*k28Z&K!#jYg#<#Bv#!I=6L ze@*-&aR1>fyK$T8BWuaPp|ItqQW+m=m*1CWbMG6TuH!%q@sjRtGM?axBlTlw9~APt z{iOs;mH`%XD$HfSPV``T5%lSMhPdRdEmlu2HU3_Ojyu&EG*Jk|wfEwuk$zSM6?+R6Ry*_a zm5U$Yaf3bxAV2{gv*~vq$+#dijBokYihladRlWHCA?jHRdGK1!A;10XKkIz-u?w^& z0p^_gj^l%*7lF#63q2M?p{~Tx>sZ5_zm^_G7q7M!XF;<6SO?vOBrA5gUE{aHjT+GR z6L>m0TT81LFCIHi?z+Eq&7if2msifizRub|g&GRS4x%1?mo-}xB6fMC(^k;t8@OG6 z5)C%bm=vlTCvA>LLR-J~W-DM_KW)D%>M&CiW`+2t-eX(8#_jZgRS`b@XXzq@mmBw< zeNbc4DqnK6>UEdaQC%%_eS?EoD4la_K`Hz7K*OO0g=*VAaSfSF91v&cLP^P~O_Lb2 z5M5n*etuAB=pi+=xUH=&d6)Qq1ciDlJ(-Pm)rQ|d5X6{Iih}2kv#5#^Ay=x9lIvzD zjl)oT%aJb&(2pdZ?HKoeKHCtQDVZFXK zH?9Pk!io&XaKo2Cn5EQNNzYoH7v9yo)35U!#h2zHenR>*bN-QrMugvocVm0#ctP9D zj7lt?GkYAWN^a-P8CgNiN4S4WMUWH&HeZ?5iH{3f`_$^5vbTc?D|YD-_4NY)t)M_cMD$Xm5UsDz z$nP>?J$L-_(v9CNC?YJpGZ0-?QnDf)8xbE*9~prF=#qa+l1nzzaBy^uLc6Ggu0e0s;c*oH`U$UHF=){DfyBMVFS6Ri|VsQj3lMu(UJbA@2{0LIsbNJ zMPA#@kip6huwwBAu8nqC@+sVo?v?ene`8`g9;TI)6tm5f3ZjL;3H~wbD;yUo3pM%5Sh$qsPICwb z;ovT(RR8fx(uM&LkJ1Qg@iPOgg)BZ#&vWkOBWwzBEHA;Rucpn_lwO^LE;cB2=szRTy=8= zmR^2)UaFVyeHy03iWs-&^Qt>5QlOOFFqVAR{QJ?g@#(tpS%&FJ8p)XkaT$6l%E~(0 zv`oy&vXl`u?2=}Ms`O^tPMW3L+PDBhJf$p_;WIWuAUOg#!Z#hXfAx$iT#yVJg7dk~ z30^drcyfe5@+LgwM+=jfE$w9RBMrm}I5!!BmBqr5RK}5%F7^7tV3H>8n&WtKG8Y4#`JLBRF5e3aJ!47Dq$PI*z0?y^X=Rlv|3VUy6Iq@399FDV3h23k zK}TYEMhN>?4c!tXB3Q{dPKB$7x(FmC%1v-7A}7}a2t+BVBK}EGjV-Yu>1*RAc^0^w6#6wboyKUp#5D?UTOap1Wza2nRSW`VJ#kr_Vzd@AFPpL zW~N})$FQ>8_$2i{kEj?B*7&-*WAD2fGQqz}GPItrZJZ3?ni3g9Lo`Nt3|QG|SOsiY zDB?ldq(9=_8aue8v71+(^z?#pGC37v^ApOGQ>v4bm9v%iL1Lxz%*7mjRKZAJ39mX34-?ol&hrm{Oox+nn4g37owD% z+~$J}_itUz87;sRUn;lcutpLY78(^*0|q9VTA{AI9F>?P+Ccw0gJ%z1%9W+|C$FHO zO*$4STZlnUF8=%XL^CrDT-;$f`HvqzYA9`C;Am)w29on8n2cc4dpsdx30E18o`90q?p(Dwi3LaxMime<&!;_43@sRF_~-)L|*OHB83=7;+jfG zI8JkA;UW;5G+c%nF(bcw#oWh4!hamXK-bdZavnIAK$1jL4{|GgCrz^ys!6;@p)|> zFLTb5c^?{r{OuQ=jBjl;OY4r8T=&yB?q`JGV+s_B-z-SO&3&=iUnk&xxwT1|mR9!l z1FYD^1FUR~oY`!bzPN&dD>k+Q2M39@wXd}FmS*{N2A8#9qq3Enq@kgdwzk}lA7erA zlHuWnIyw}UZ6mJx##fOe=c4pQszLPqp0Nj$X@S!q@tlQYL0ihGQWL! zil0$W`_cn7AxJ7VO$?#mar(!b6%i4tT{d5qrt@^GDJ=Y9G-C_#0-_<^-&>X^Mob%wROSw zY3%EtzqB}LzK_=;E+tUe)7fY!ZJieAV)1JtZ^y!>A4t9aGwt9+b{#Km?VeIKf{l%k z@hpw)Js1cUj^xFIMy1pSerOJ@1`LdWfB-fRk2M)tb*uNPk1%Pw)Az!u6?k-2yS0&s zh~d~+7Fl^PBO`2bITAn&pYArPYy; zCIR=uGY^y5ZuSvj`?DD$9vNZ((f3@zC2y#i>~S!))f+Z_x)S&OI{;CI z?(S^wL;!Ld8j?do;%aLp2V;^AT1qlfzfBSXF=khrn^}MOlYDNh#)9BKdU_HMPWlLo zsmO)o9sZP^u+^zax%5;(!#@oj_V2i z%-lfUr|Wc%1Zv5%1+l5?f7mo-t*+LT-kENDV{6O?_=Po=XKOGqr2Xar|8*oKtGl$7 zFO993Jr)y_EJq0oP+>U8QT4KNW>;F++wYv5@P7XlSIZ%M9+0SNxwP7eAlHD0|dX6oGK(>r%STdH zKlAf5vyEz@U|dd)t2Fn8z84mj^4Je#^Cw~AY9^-AR+f+>1Y#lZh8iczWr=>90cl)8 z!K9-T7MOnz-Vu++fUsuR*hZ?V){Tr7Q&TDn8s;zg#%wk43G4~`&`!-}rlrdvhb&OO zi%#WwKjGTEJW^PA8lz^_`|WVm+!8N1N{R%i0A+bdlLo`nT6@OrK|V9CY4b#JDI={+ ziwoUrUwEQk<8VzaRKVtyPDmh}^5hh|_57G+AHp)JkOQyHj7PBjf`jF$ejvG&VXOI4 zg#ksG=xJ}*vR>mZ{w_EKS>WXyh8yuev8}kn$5-9mjUE`}Y+}M2`pHu;kQ`+Atw|@qc4}E&-Qi1Wnf@5mk6-+4DISRJ04>B5|==&?vOv;e5Gzm`;c%bk3Gd`%+UOi!JHd zEV14JL+BX%pO|=~VWJBcaXWrJT_wQ8jM7(};v94&hFofBj0y@Fz`&II`c!4JJ@z!G zZ`I`Io8BIKdY$U4sA4$~_wPBQ^s=Lr=b3CC9`gQBo_>ANKt-w2Ea?C6k(5Rv z6^aABFw*4U*O5QG?C(YTveav_iVc8EEm#+GP96ATk-TiTg&U~17V9vG1DN3Pxs_mW(zZK4IJ?CeoIm&DM%d3GHP}6AJ0lW znty8+`ny-_#3zjb^73*M@@~iyBv}6*c33HYwYP52n!I_nx3k-^_fYYMVGv-~`EVB0 zezP8Lu<(cCMQS%Nn3gro zVb+^UkF2#*(a{kDvMOb&vKJ3UCrkCjd{ephMm`BbAZdDJWNgJO9}MC@n3$hf7${`0 zWU%l_5zQ%hF{9Ckn4X>wm5+~d%`2w6BX{V(o9}P z$w++ZwVs6YAZb{Asx4-|Fn8kP@3NJ`hq0H!Gn*T-6r#=^h9MvEDH_8kn#e5-$wE?l z7Ti6|MP+DQ8HOR(W90R>@pAqMe5;9#y-D|KCjQY#W=~3B`g(Z(BO=iNrY%{DzT4?C z4LNchTOR=a-GVfAVYgN8hJ5&`1Rfql_RGV$I<@s@t zjpvTa3H!~|KdqiY1qu))c&OAqrGizKdTrYGD7s9VNW!f7Hz-3D&_7RP&hJm&2#98s zs#ywWo2Ir#AMbF#XYA-0N}-p-&Hm1`jLOEEmUbsIOLJ-fVP=*D9+i*`x1p+_z}~?j zp}`h0uuC`hQE_mf=!m6rL`E?yA#QS~IJ>UA94a6QqE=xfGF7=Q$5k)V@pw47(JPmR zVjXf=_G{gbLT2g{c}|fX%Y@09-z`wn8urHQDb!l^(1S!NTX0k2Np0=tKIp9 ziT#-Z59cG?@v8My3l}aDmkcO0^aPJF^?84?EfBhsNe@N04hZ~4Kz(%9DG`eDprhvO ze|I{hRpG!GSugG?w^3^mKk_wZt1X$iygF$@q3vlAN_|b3SmRO3i4UU`7Th5;V&uyk z!hpE$*?7nd=g7uSti z3sDRoSJ#xue44e+&YYYs|2;)hJUm7mE6U*X^opN9u|I#tO-jB+M&ovLrl5_`pv^LB zZRpf%OiEAxBoSsVDQTRmOoG|qCj^x29}@EN&93Nrn6ExA0g3DUSWKQ&%{VK37`d?E zjt<;PAwCLUFE%+OzjjM^#=e>8t(Hp z?spnqUVFt#EOKA_#B*7Wj2&1V^dm7Tgw3fnRa9OTRd;O{``f&Y7y_n_q{$N7)Af6j zzAes=U)FE;Bn!u~06AmC^y>**2L3D1c*HBf@L--N>>Dpx)vhu`GX$dr8z& zO7E*Vp1#`CDa6WnKbcZ)r(|J>T&S~bPnyN0Dc%=({Wc6i44iOx*l)L<58T|$wHQlv z-wznCCckFs09k=AwmM_N(-M+q55mZ1`b~h}Nr_)<7HcNg{DPttwv(AIFP#{1K)%hf zq_XmIK$q`QU2GZ)2W{8TsX?ewVjEMdw#%6*B6+jhc6VoVCR3YUlD-di zJgZqLyCSa~6;>ra-OFyNPJ^Ex{^@$C#T^|SY&9M9@`Mp3ZgU6d8_XO`p+23JC888xkXF1WJvRUS zvcDk8oo`8EtDNJa-0PMbhPKH^umcMSU_cVNS90>KmB%l%D^LJLEn~K)TdXh-?WXa( zF#yr}7xRYJfnqnfs)M;`7!SV}{s!E4R<~48QtedACiqQG@w0ik7@K_Vb_9in3R};O zjE|FfT$dO};%a{menmFbn(wAj8e^f|ueMAmDy4%`&Ps5$J(x1OxxV%E7U}dOF-nZG zLK}2^aCDSwUa|c9TUY1PI;gmlPV_Wn3sDuQQ04x5`aiV*tjAp>e5vr)bzYEO#$b@7 zJT{$UjK*o}}oN`sd2;DEP}@14%8H^)68 zB&VlDwl=45aCBzufs{-FZp6M@1IO1cu>>6VR#w`dgN2t7Gt<+T3uLFUv1$4TxXCzw zZC~lc$TvHhRyN-8SM!=|Nl8k=X(IZ%J;ajLBEdm@TdcP}DO35jbw=~yFQ5NqcoYMY zh=(-VuJ3dC+9Q5P7br4}8YnPqiYxV)hu#VIE4N$DCgc!F$I^0tI0<}nqZCWVGBgYg1euS1$Q0xg5$W7Q7nzx1NX8Vm&w&fX z?G01%eD+Yav6&Y3m5DIHiSQN^J1Q@~b2^Y26+FKaq>MV2(bCIGO3vG6U_3F_4)v_rrw)Nw{M_0a_StHN$6H5cC5zbR9ds^>#CW%HR~&`2 zvlBm~0ll);o;LT*Smr8;Kt*HKueIicI7s!E{Z3ks+bC0=ASF+$xVWU`wy*;Ii;A$i z;9K7oBB0<{-?1Kg1lmidbFYv|@G7_S~>ThntQmIJarL~L(e(TG(YmkJ{c##4#nyFSIG*{K4Ud1vV42SSF~K9J znT}4B_+;Pe%a+CH(&D(;p7-mDr|ryvSg3vbdEw?nW5(;LuP1SUj=lfUodsG}|F0bE zk&!t0aWfjDXWy~@b)zTeQ8(we1>xT6(6AjI+x09BT6!d;s?nU550%XM1E23UdfN?J zY%C`?hYqH@YU*UR>pd=3j&0sZ1Xvr%)$#nZX+aNNKh;P@vM@;PR@(){;v0^5C%-@hxqLUvaA;lGOn;Gc(R&xd)TW&ef}U|wJK^y*|TkIBh96SKqm z*I|G<)m>cL{9jz{6cxklJ958#PBtbb5o{V-dsWUBmXwv%Cc7rx;p2l9Qx+sm&g1{_ z@nZz}@YQ7%&btuiDxu`M`P=m~Bb_^1#5KZ9=Vyc4xb3pJ#rHaVJ}e1janvADgZADU zv#YC1AI%Vp47GiZ#7gCGXxXsGl1 zz4>O)sh!hHQKWcX?e;f2b9||{-l%*1b~<=?T|nX zdc=73$?56(`ugLQMaz9<18;9e!k+!WiKlHLKOd`};A8JQ{KEJG%doZf*0+R?Ctf8)-T%xEsc%M934IFDkzy0;mb{CsAc~y8a)Iy^UOnGI6n~IX;PO&j+U>_Ven|Qg;OAP+|Lo~9~xSq#+1UF z@!09>vvG521C#wY=7RpOvppgA*G%I3LFu;#91KjO)(5H)g9%#d`so7h`I)O%NAuO}r~!2a z+sE5O3|yRw@E_!+rq-~GGI*3)e43YAT+_|Xi3i!(b$t0G)a<$3HvaHMN^xsZb@Ywf zNx}`X>dwuPaixHMioN@ok+FO-ZxljENDL7c@^%B)UhTjkvvPipVlJunaM~UDfE@XE zG(#s;WppUH--ibOc{!JNjj}?XK#%eM|?anG;{#DT$afCeEISQ6b$`&b(j|e z4Yj#au_D;T<#nw_QpNDKLQx}BQE^UKn7UjKOh58c36pv;J)pz=y z#HJ4Y-HG}-;P}UHx+t4ffC-~%Je7@xX3+l1{AcI~u=0vQqn&fDc{4hhNvkBjfwF{V zdfG#A_WH)_3j-1|UHWY*m$jEujmCV1HbL+NjWP!}DLxka;{d9ywe`QI`>nxwJ)Qp7 z2O7;H(hXi_xAhLxxjDVe%xt61vFc+Hi%0v6g{487gUcOe22B7Ei-+doil>}DTj^%+ zFj~u(21F<7L?yPSEAh@f%BjDmCS{$n`w7a%ONNJw+1cfaygi?Nl0e8uwo(>RjLYD$ zud0?6^v~Mjm7po^Dxp2o0H232A>_W5goh2z+sj1c zpZ)lR8)>@?JF?_Qb2m$8=>7H06c-Kn!+3HyaL_Jv{9csWCYhollI0OkRzD-ji2HP` zsO9&~T}?uQj`Yl6eBU1@OJ>ITXfD@c9Ld!Mzxnymef{L}vS*SVLke#uM`mi;-P_AB zRVX8F=tu5^`_@3${tx0=oKM%y7?cOXrUNrgywjB(n+Tt|IIrE|!_IGxF1#E_w9?b) zSQx;&eP~cn4;L4u*i<^z7o)?&n!G+}m#A!sC5COFdr_%0{9) ztKV8b85I2)_VoP=FM0U$f&~7>gI7?aC{He^W`D8#1@idB+|J}VSsI-b{5G}h+=m|4 zlZAJIGCJ~wFD|T;?4Qt6PgpC9pT`E!l_XVpcE+{2_q%g?IQWCPIltLOO5@jqC3jbK zF6$IbQpKsd-94h!g&O&kgYfXt4=6y4JUa67!KtBA%gOr{t?%F7Ab5Xw2bosy6rk#0 z(p1W+#`+t%7{)s-_X;iTgm(u}-*U*aKp<7>R!;v{O^ZEH1$&9zrGCpyo~d;F;L|^c z?$5q2ZB4vq8sHzf=j-VGwo9yXW@0|igJlV$olW02()7tQl=v``u6ZwSN0;Mb6Y^rm ztSNxs&o@W8+w*pw-$|Dp)#~@qY4WmZXar>yo2ori`GD`IMvm+WP{2P*V-dghi%&4= znVkYxw8Dp{tEm<$@a7H4LNN?)|K@ytybr|7i~PSsTD}r*W?{?>4BtCD7xAxuKP#zh zj;2N&o;WMoFb+COjg4hrEFf}mJ&_6S*P5gD@8Jo0H>}Rq-#<9pOd;eWg9ZyECE=g0 z`PjVb+G^r8RW8=6P2VqCd4%|@!w%5iWIG`B4sF?u_2w?K;uZp<$lhO*2J zbNmo+JOF%wzrTh&Oh?!w54`7MT{-?i0j1{C-UqQAAOOSt#*zxC^3?JZNJP#Na5yTu zVAjO}fbj|Iv6$%9Sx~LenE@|Q<(cBQnu3_a!~0|TJC6Y&5Kz3wX7)tZ3x07UlCfCyPaUe5x5xdctDwHQGE6@HTj7mITppa4O=*Sd` zK3GE@Z1q#d$bX{RG$@t~&&ry^>7o9t6Wz(3MOL&M zZob0zB&NL@%pe<2JXjbSs_7jJ-y09tR4!z?V(b@$+mU3op}LwDkJgQMPztJe@1QOoOU1ge0hw^VKxmh1@! zB7vS7et|!Dc!TsfumP@(c3h6InW1PT4%-M!IGVU0PcE-VVk3Jsqgh*W9>1vQcnBuJ zT%51ah*}DCRolB5PS?)uv~xECfGC{>uQCp$UtDmW5jNb=CcOQJeb)Kt3L! zkO=cT*{-OPDVxTve2y0qi$+XNCpS9ryRt}ALV99u+`g|rvQCDQfo^fR9$Z&~pvTp- zA9xt{XJKLekgj^Q!oQk!(agnFvWZ8Z4DWDHu{1P-$n2AL%lNiXV+09Nz>nT=jbv@DX zMVyC*Z^Ymgjbg{9U2MfG<0usEV-lY5Q0wuqdO>Rxe+AqR#i}Q?a57J-rzpU$>v%g5OR6}aJ4#PjAX zIPrd2+W(yEF?f_ZIGrBo(vYJ!I{Gm{N5B2%8!RA~!wdjv1<%o#zZd1guY=eW=tn)z z1LB6Pa>pCY_Qr(4S_y)NkL})jMGC#t?+j~^r%NIw;=4TF9+GR;FDVz=+>|^s^2-&z zUZ4_3m_fcJ*+dVy)+F5E`-wfH{FXZH?t*QD=E-QEbmZgFQ1qG*+ zRhKFBWZ)dWy7D9UH_WfK=33pMLP{4~<;(+wT9cvjY{k zE?9Qk?iEL=Gm33yc5#J50Hk`voj z44TZHtj^|ZTZ0Q#m{NG^jg)@`n`alB&kxk%iik6wcao1>B7s zn8~ZEfjNE=D-F)c!2+d&x9d#zdlf`93Y{HpEB6v`06-4@?W@kiB3?Y*CQ1}A)mfyV zO_ZJw0N*ItT8rRc)1LSa#R*)DSf^mg-QR*s1@a;iH6Z>~?gObzWG$s?I@+n&L=d(S z$k|1iB~G@;_6%Kaaj$AS;jKlUCzHrdh!`*xc-~WH_)u0q(fo| z!T>=$KC7(1JbBwJh$6y%goE?<@LF51M}}PX?}&KjB|`L2h&}*9L4jqyKBTbl?naHL zK^*CIc1#mfo4luEm7RVbT!bgPiq^7F1!ts(D=p4vuf9G4yvr@!}SOK>4?N z$#WAE9(Q)Nv!sQ>Z>b8Rnc?o)X-K=L+PXdSke=%UqkSdKj4sPUb5|0)q*lk3d!4)G z{8+u^^l9WPeT{=MJdi_sNg}cF#cplHk(dfY`{90OHy7vN=x(twcKgbCYm0)%exTt! z##kx^dE8TqE$$z0%2Z1&>_zCf=jO)IA%Pem7JV2PX`{}Hy!_t3-z{jAgg@fnvsH3^ z$xbV)Q`b>}BDR=p<^V8YC*RID;3OpnDk^5v+Hd;80gQU*;=IcsC4U5xB2xZNJ8=td zA$p#TvsO$cNVGt#0Rfhy@oHVSB97?r1A}Em?26CN(Gr73#qz9)#WkQN0jt*Yc1Q7o9ZGC-hTioFbFQ)?G;;&t7Huf{ipG?VEB=)hlg}myDt>+_F^drXI3EBJHuXgWT zzDObD@`FFKuq>>L2=J$G@xGXkhGq(ZnQ={Ztc*58ke_^g>3)8*lshLC$({N`P%7?2f38YLmu6;_Or6XIXK`V6HJ9^YBqrbt8-ezXkFwF=c@0^V}L;`ZLYGeYE7ejO4Dx)MtLUr z*k9x_Q(co62`Li~VPpvL>WN8`FBj55^r%YXlOHa#!|e6yPOaudd|UeG8enpt2|9<*D{;;q~!=Svar^E)B+8>tmHdnuxz)L2;NF9UWb>>(N}j z^*pJtPikUfVnTwNq2X8!BY*)bh5;)ZzakF=GSGir<>uNIJq-qOB>7tY>l8bT-C=dr#Wg3u`{uFcfZ z6{|O-ahL0Hg;Il+4hmTx_s=@d1c(STG>4%lbaBi1KSZV7x+=ln@DTmjA5NO@cuCGF zLEP8~WzzGzh<-;JF4sF87~oJ-Lk#Tt5X;($s%YbntRRl@V0g$i-ei8lb1n211 zg-rZ+d@1G>n1GHBzvTv7cr@buqa$!>X}AJfE{hCx9PHCWVOSW9?9%-`3a<}7*&f)k zFfGkGgL4C6Q?L11Bqqewa;>du-H(Fq@MuBXK%jL%dn76fm76wBObXUs^6NrYr-$&#{H++0E$z99Aijm?^xw!CN8?5pX5WM+X#>Noy3H$KEPx!9#Hx4BbX;6`o3VN7a z|A^W0;jwc;MJW>?O2)><-rgO6MnOQcTj~^P@C=@W^YvT2J3BjFP+^WcS6BZ)Dq?5Q zdbatpS)h8*V7r{mV#FLL1LAkTc<>Ps>1=l1YiVtrpD0!R@nb)o%bHogN!gVl)J%tj zB=fBE&F^@j+DDjdnNqy|cl6Zl(xZQ@58W^} zSNldDuDHIW1elnuZEfGN5Sg%0h1@Gtc9J6^B6c7tM+XO^X&l7`1;OM9JUopFG)l?I z$)tQv1))yJ00!*F!GY&yA7c0yEG(?e%}sHPFJfZdb(YiD*VldzJ9wq)5lq;*OWTC_ z3oN{;G#KjJyC0fc@u;Yb6|BUEuJ%OZ52>lMt$+I7o#9zo(iKj@yuMyuUJfWrNHL?I zE~?QbU8-xqlM3m=ho$U4UX26F7-U9&{zTc58oP*Ps|}B4c(=N!Bqm+V&PW+Fo1E^< zdfW=}@@g~UvKV#f(XvL zRJ$BZQ7fbq3%H>y(}>p(i%A-;p}F7nSd3RuXB$|WQ&*Mk?zNT{=79zF z?;YjHX-9|o`K;7UOEwlu)sVA=^6#Jhy1NM#(r3DvIPWg8tSq4hL;NPSM#-a?OLAq~ zJT8=sj66O0j3i7)qKP&MTZfeA1--8S&d$1yq_Sa!2NxYwn+_Hg6c7t~Obibn%G<_g zX0Bdr4JITcgrO2isi>={O#c2Pu~cuJ^80rH>c?DN)1xDS^98o72sufyZZ!1RKpLeg z>TE4fKjA^v7H;nByDtx5$w-+9IbP>?extSq7$40EEi|IbOmVSJR9KAjw`P{pC~gBL zcV`w!ayGXJ`N)qbSc;kaI2bu)CCZa?r2cmmagp+-3)Y3I%`OM3T3Yi@cV{pG#l?HQ zVd#za>#wiXJyy}$jBB+PN?*Tz&EU2L$OQ#g78f6iv;9DXzX(35BippNles+eDp7(M z8CMo74E%fq=e9ZGQxaL_3jMBjv)!w+PN2+V8v(|7_$HH1&xwwbPrxn`VTXGk_e?`V32%#G__x!dnm)}IxL%+ znF$C82ty~UVFZK0ta4}zHG?i0!E=0g+qX1i$nNSRZ>Nz8UkT>dVK+9siQ$b zp_VHcwtMARC>4G!GPM;FW>?kTlb&5)?C>@JUQk_ob^i;&<^kcn0{M}}|3za5m&p(7s5f>MShK7d6tlu>k zseDp(JY}}9SX&nnQC9LJrMQ?*bB=1qNKe;waBxso{w+#Q%fy6=fS}#% zMAcv%{D1N66>M=ZvDOQP;*SefU*T*QzHeZ*v<>NbU>us$1d`^t#m0;E9P`YR4rM{(BfC zB)MK7{ZH7Jnv66%2VU#a=a!~=>c9)d7xsId5Pq*zp*cM}BNg)DG3p6;ZbJDc74<77 zrn#|Eg9aOt%ACvRN(ZT5O#568zi(gw4GN|e>gJ&|Q%+@yh(N9!_E*iwQTnH);cP*U zrc#9cM&39&hM#`=I-0)F{od7u%Xr$dp%hIB9x}C-lG-`>E{zmKQRU-9lMyp;81xT9 zm4t-)3ULH0StLUW0?)II>TLbs4YM+h<#zWA-zgJF%q+I)49N5?BT_S4-7csmXMJ&=O)i%dfKR?E3{ zTE@rqc8kS)_zIO(gH|@vM@KWLk2+3)N>(<<(MY~zrC6Sc2|FuY`MT?++sm_!RNhcz zWZz;efOJNhw1}M9p`rn#t%>uG>Oq6~Cg8U2vDVhsJ?3@h!GoLV=;-0tBNG)>)vcW! ztk0iC6LvRygWbMfDVmU|&oVvp6ECRPFSFHmRE(Rk(PBA+)5jwR-y|Kb?i!4f$yfK;V7E1e}XekU3YS}y$#P@St zNIlWRwY@VD!gqgpN4+_J5TK`?S?KXVnHNBYm_UY@Kw*`!dqpFZyM1Go7e|eG^;0Y` zG*m=hzOaIRdO?ewMTL`X8Y6NplS7r8t2jjL)h|zK+r`LeG)E9lwpq9K_l)}nP*h0t za6)+F@y+}Dhv0Nt+9s#)m?0HA$2hY-G18e{t?uJj^IqpZ@1$yG zN91p>Foia*0vl0?NkvEJmPbQ3zr2=Rfmcx-Q4L*=s5&YC6%jZ9OZ5?R8hIKmk$YX( zeBry+=MT8%;}5aW%D$?b_JdV#f9f2I36j*W;>RP&FOQEu{m&AW3=O*r3*i7%N?Ct= zU);X5mqhZpk9Ro*_tg&$4&H6Z7RW;O8a2vqDe*$5oOvlzKR{q1)5sxg%y{CesFJK4 zV{E7_sC_J#_p(7yv=|ef7$6?adnAwnV$1-kXXs;L=&R*`rsDo(38Ih{%B?6Gn3=~p zJVA+yY77zcB_u5Ph!&Nd?OIhOOY(_R{3mkHQ+*7&fuq0=SZ|LXsDF(Ua&u*Kl%eZ;%E^KpT@;dM42zqN=V9HUMBpLiN+d6YZ6E(sc zq^pSqT1FUK5&XbG6ytR%u(GYRv9dCJ3!K-R}5`@y>x&=izX(@5yZ7 z`1tzS{TxwHFrLb=pR_NO^7Se#JQ8wPT1tA1;Owk)ck#a8`yn)6hH1fODu4dwV4>Lw zH8elp|K)6cx(GQvicA)Zx+L&m{76S<{w|Y=p8jR7C%|ke*M6}>r)4Wyxg{^pwQ=DI&5q`sal_jVrE8*^>-{JQjA|0Aw0tV?F9vewJJuI zJiJWR)j!LsD2Yzy=%MqB^2{}PTGg+c>J6w^4gUU%QTWJZ*nKR4bxyHoD};AP>hk-T z)P}8?Y<@lincNJJ1c9813{FLA<-zZJ(5A8VE{<<~R+GPl5I*H=22`TJUdb95ba=ulL$`R8G#$d=JL6t?gGkJVB^^=NsLh0MUfpF)=aw^Gn0MbI(69BLxKo zv9Pe2l$$9cLRe&l9BWjtM{#0pjMueeKaFtQvCpMVN z3$p7CsvlKI0XinQT;7~Cn?;7k$J4DnR5Vy@Y;@^EMs20M_^jcF+Q=|Ssow`8I~jF` z28?}ePOey4U0K|F$?8vjR^?Q2OM<4@wWD_6zsxhEM+#XG57xcPSN%V$-N&Qht1k#F+%G68jSO3&i ze~5G>>(-$8KJQ{tVS=aWHg;{OiK;+08ZL1=b;uND5ihzGB5p z91IMRncLmrL~e)mN=QiFVQWWU-=NF< zV-tEa(X^Wop|0-0Xh`Dz%u%JX3D>KJ9cL=Y%?)XG#@{Hb@F zF!HK+|4<#@;<&!E>vk^UGyS!`Tnk(}S+M^m?Y2?(ffMc@w>==Hvuq8&LGeUgRyvkU zULV_Z<61!n_8VRLREfT`Z5VK@E{BsR3pKF>oYun$l+gs7BSS;Ajg1Nl3cKY?9*qiA z4NXmBSh*7GoBN<)cPH1elKo0)59!L&L3gFrGAhl;I_3~=xjfk%%fsr zqFJHJm!gG?u5Rs8&@(SI)MpTp#!eIYrbLs+7uMF!w7HIzDA(vqY2?WuqeY`5dl3_l zO>^|_)L{=ya(u-|Mpj(UrYR*~uKXWkE*xrR^O+RN``D8-veHVU3rU1%h6+9A~WddJlFhab(|bD&pfiIyxTKJFELb=f>%i zv@|F}e+mdYQ{24yTB&{p(5%51sjzTF!#Hwsw(95Rs6d(y=kb{F+RuFOQFU9UgVAC-WnJfN~w3 zon~z5F)>PxjzKr<(%R8<-lfG>YLl`wRd%Q~sJjMhtqtcw}=kCN-*sek1GftDox zbCpw5c@zl&HwR~J?ln*?dPXKCR3uqsw6Vx&M*kZrP0eCGO!2rvHhtz$AVVk+FoNCL zQ;*umf_=Ae>~Cksm^ZmNHPs~@`?1rj%o72bGWjjPY#25wHk=jYDrpC!jSB~B+3J&8 zVbcpq^&!q4MnZDs=9TjB@Tf89EL1CNXaH$wB!z|!_68$J#}FX_C}h!z`8XIDY>#Kl zZVo22#-lP=fPdFJy<7F{t*y(`2}vY6} zQ-%j6q>wYYYa$m6;}a91hpJ9G8HKefYI+Rx^od#;wH#wJQ(H%emv?uZQBk)i3*2_A zKftR*Yv-R3*|>2J4q9@AyVoMV$e@|(V<7%v^L-8`=66gWx_r4nI~EI@mmVG+b#Za2 zEG;e7s##B@R*s5}h7qAkw6d~F&&X)DSzsb3C+Fe$Gq!>6iGqwgIyOcd@%(g<>tD@z zBJ@t5!k}I6cBYd+0djV}y}eZ_002_V*bDN{?UoXJjuP}329d;gPsD5dpg8OnT=={R z-!RCMF*anz6RBTxnhU=mr}hTFkO)P=Jz>+g>V@VPQ&5!l{dMU_Ai9{NXB5yoJmTHH zw<`?w3Nl9~fBX70k}Tcs{vlu`jn#FbrIvx;s3%}#L@rRo@noKHr+Y@@#-js=QODHG zEIB1b$m{m7$^j;T(`H@;dtlGmVj?HHyf+9Qg@*`TQnmZ-nO;pCDHMoPrE@3jWGt$^ zbSV7pLc|hKQ8WPiZ_zV{>rBfRDjbSNub?0y_O%PXfl9Gse**0II&d^2o67W6ROl(L z#L7sUk&}c(%c8Qg6F)+1Lbu89TY)O>&xDcHRlEE9>3X){k7!ha{s!(hf_BS|R=q*+ zc%f%&?e2$@c^7X-W0~AjQ&YY#_rBcb8j_MB;o;$WOu3vkIL|+{*nFRF?N*wvo?e53 zU||T9AK}s;&Lu0g6J4I_*=k^o(tyDq?NXUs4;Pfvk+A|F)$lUb=l(c}`UogXTj=?KYOXlUmKgax3Th6@l6HGs8As%|xt%=+I=}$(R1Oag9(w!i7pnE0TeHZ1!K2{(&iHLQoIpt-J7QYD z*6#j|Qz*pqWH;^%d$K z1W8U#4O7aAf_vH}MDcAXre19X+qqD?@dN5YZqN_kOvr&;;V8T!Kl{r>11$KE+|Sgyah<#Mww_rp}diM=S3-k;0UCH4f0Pb31RH8qCW z`rF&v&L9ws(b05KDOCq#Lil~O{xp-@At5m_o?xzbdF7?#@-n@~z%zo zOiWB89ZcQOdqTB>XUp{TyTw+}eub8OffNufFHYufD#Mbc^|R57+ded^6tSP$a1?H< z-GNjofzrxK`Q+N9l`0PV3lJ}~V9(S#YO*ibY$>ZmIUakcjchhPjNg5qnrfR!sk=b> z$(0xLyjs8g`ubWXVYR_R+0~8^k|X4s0mL)w!tF;uCFF`STQUL1e5LKeR>Vp)Xm_6& z8nR^b;Zef49vP`kXK&%>>+-w=ga?+9JlhP>w`(KN^u6+T0DJdyletCwC!7V8~b(o@_0PZHILt}Zf*)NWu&@$GPTP*uakln5`Z z#prWN0E?@YGQxiNkk!`<;S6I;SIVV(7go0pv23Z=Xwy0n3TpI`qk zEZ^tfTeuQ)jr#RJODZ5Lvja$2aRhRvMMVKXA~ZA#cxPrBIMRA1L|3op)YM!;-UL+| zh3xFL!KktsGb9ugdIpAm7Tdj%h;F&=6w z6F|CFIi}GrB(+9Ih-zJ>N{AS7_}J#qcm+h^#cLii!^5lM98+1iQkp z;^Gg$k8VFG?wQB^sWy7pH*Dl5AE9#0TrqL+zR}Srieb>f_*c#@T)fbx4EBSPOm0p^ z1NhhC(kjO6`5LgJ06QPw#S@6)7aOHnc1&3Kqnkojwsr&^Wc2@C zU_6#!fCf9GxY#b0q3pzLsnH4xQvdPeN5eMLz4cCS3RymWek})(<~0?o?sJj;&g=;^ zTY@~k)IrASd;7FQP$wlK7^5blR& z-w>i~-u{HLP96p>4*7pCB^3Vk>ywickL>gLhT%eRBTYk0Ed#%C|1ah>Zc56K;v*`> z42`~k-Su^W4%ZcJZh1V;N|tJSdk)2t!ouIpH)~rbM`*1sW%@>Bq6w12!|ki9*TyFC z48K10uvG3WH{pevt+stnODjE}FRF|(OXDNf`FM3Udvj@|t@$;cg(LdEG&91&;cGQb z5t^?+z}; zZBI{tS(**#pu83PdPFW1$f2mHTBTwE_wgfM%m)!!FFrN#HIXOFxyUr=3%xVQDdAKf zjMYly=_XN$5oU|}74h%j;NaiC+mUW1RyqtgA4DQ?7_CLESnNt*)U&(Hf-{@wK3iWU>!U9n7e-}rNz1I$vIh< zcST1p%jIE2YKKm7v5Pl}jcr-k(9_Ye738DZ+Qk!C!#`uFmQZ&|IQy;(q!in=yRd>l z6*Fe|o_@QJkvq(721&~Cgi$OW885eyZWALT#@aYwCleDB4c7AF9F@{2(bVkh=-E!w=*H4Gi?EGUNu53LQME?p4(TRFPA-Qow{stks~vP^Sv`Juz$d;c zyU0!3diJPExaqu(LE!xip3UrG{;3(i`P$UQixoUOt@iDqw@l<+so^j3n`-6+*olbI z{R!qUEi*PeW}bspRi>!q6`IIwD3w9BzRe1R-Q+1y5fJv%vy)U|g3Om|)tIBHX-jz> zmCXCoe-r7Ni4J*Gu8eHu1tb+50fyShG?Fg|B57N*Hl2O_o+RNTzLCM_`qZ&1m}~F9 zr9sCYxNs|R8kaY$UxLp_Q3tSbaOkQaAw`6_YAXJtQ)#Kn-yA|VJTY+Hoq!+`6=kj( zbY|ng702CuasCp%4*;I14L6#{O+J5mbbz{}>s3&sX8^yV&>Iiud2g=!n-4}R0m$5* zokV1*2#tDXowz9=pL*D9ZQeF>fvHF#w*9?;&PXYh{|c>P?p+29RRS^ zzAZ=6HL;pJt9{*${0UZ7RZb)&&E2AnjI8nTmSRec1pfGnEdFG&8W}Q>c4)abS~v6d zru}gKRS`qZgO86(NGM<@zWc2_2U%l(4+a7o1A+_6V3($hukhkLX<^rnDc7@;>h|+Z zDIS1_|F5v6lhHOe9}WC~7qIa91S>B7-6I4m7yabb9hE7?tSE`&*mX8ZUfpHkIKzRB z)D@WIOjBG~2-n9Vl>5Sy41?i%zA^o?U^RTwm9X8*O{)fdjpzr`-7rW);8XPH55ETO z)8^)HYxDz6rk!6g{Y?NvUKy0$4&D{CVa=%S^Sv;D9c>rrlZX)(>LHl_0qhrR&oBF0 zJ+(8j3v<+Z>uBWtfe7%M!E0t8kKl1#RQiMWvZWCKfH$#f@%A=G{74qN`q+Jd37~o( z+)wlbgnn?dBit#L1^^rtR>s%cn=0mo!CEnG*toa_#kVGtP4xuCUk12Y;vxrn_1lun zP0187M(b^X&d#c82?RL8!c6FWM^1(P|F;X^q%^kwxmez$FE@o=#jIivZ+WSX zgOQO|^uH2B)E?m@8;7E`rN>xi2?1ro_mM73?@+V)k$UugBFp9y{JN+g$xU+WDoUFY z;_QH-W$u%M&0o6--3H$U!iHaz;2jKS#rvOjuUwWdJf8U&x1M2B9}M&GCPV-L7lwq&T`t1aUe#9J6-{=e$`%K!9U?Us8uh;On#DZ8zJAp zgnfHoF-C-po>_P{FSxN0+bReEfXr8MqN1_{{A#k9n`-Ou2u!3<)+L;S`x#&GO;PoF zM2-T!o(b{0xQ^O20}mdcV}HDASoEGiS_y)6jTIvxT)+7oG@DSP!!`~ZFKM)dN12}{ zgc^zkO+jq{{N9dXz&kuMohh7|TslEFj2uhUq7FkDpPM(o-X>?x75a0wum_?-Jz5%E zs)nR!0eaXjhWR$d-N^zU^^tUs$!|B4G z#(+2phU2v@U!P|te-WswwItBE4I989FeZ#QfH~^`gig$D|52cNxmz&o?C4O+;>lC_ z{We4z7#=C#y#wYIFtCyuEc1h^>~sE1C{{17Wgzt4hO6>ptYe`?qLvK|>^UEn<3~zLfv2xE!pKSf^Xf`RdNEB}T)%Z6*;7)(T;qrHV#BHhei44i z_Freu)*wv)AUu&mY2=F8M<*Hf{^K`SnfaehUskU3J;S-NtUx;5XUFt;iheJ47iAS! zlnQ>UV^~hy%C_1=4JS>GGi_7nZMpaN8td7N4F_-`7M(Z9GtKw6Y|&8mEpcx0$uB-0 zWI;832mm>9lP&|Qw$0~+uN5S8A|;Uh4>JVaiPZ`5Npu^K7DWNiQ+3_2{ zQP}VujRYPQM8N!BKbRPRu6`T|vpp?FLVB)xiM3SMoE_@J_D%VYRh@#f$pc|Y_$xM- zh7>C@4-W$nf$YVLiUKB0cV((mG^;wtE3YdnXtnxg{+iUAu*tF0eM!bM(hHI|g6m_$ z7FR_bfQ9t(>gX{F<`{U%@@bTCU>nu2pgaD0{^|YgA)Jx=ne!UU5sr|{_J@~EnF7@Z zvfB()9XF%NiTaM8hy2_Qp@yH@oiCCZcuk)~>YVxmg^K&Z=n&1p$_vt3MtG6-x{J6R z14W`!LN04lUFAr{)x~OYv1f!#2wfp50k)1FISe4DdS9zW)M~q{&O~_^uoxx$r*-3{ zVZ|{A2N&?WH@|&>YQ@KSJCj^d3jnArRQMY(-hLkP{nwsDjW%7fG2VQkY~sO0?hHqj z3Qc~&zat$(bhN+EWi?$G5C9;F4a?9~+~jn(2a5e|*xUraJY@3ldn;xA;!p*_g@*2r zWm*V&U=U*$+RqmW&_}{gR`Ibp@Ach*V$6`2-@Krg81(3Xp2K*-R5ub2$EDYXY-K+w zmY8s9gbQge$Ixc`xz@-q07Wb=GYaGUS?j?_%sCYtAc|)h7bsa)bK41lTki#5uMPD}Qz%k;THd#-{9xi&*Q zb29E2bB5%25N>Y85ZvGSF#4>h<>G?bMdeZfH6htT=3b&pb{QGQq6MoE9=unoz z#m=@7hU^<%-F6?FO2`CxL2l7*ih2*LwP^(m0DtO;Gzxo|&BUOOe?A15Hk?R(a&pq` zP7&dCx!F4u|E;O9Q9w}e;cSIEIo~pGBbS8V9a&Hizg56?zOs>!JC5v^xq2}RvgCX) z!ZDYHf}TpxbYoz){+AUQ%yENZgq=6gYvtQ{Q}3OQQqDSD>0x4g$Z2Y}YKqU54oTXh z;-S&CmN1UhvRQq%Rnz!@#)UCUYFAa%)WV`x&)jT3BDt^-$$veGq>=Xh{`DS%NFRxy zH6QYu1@Ond-#qk4tC-&wgi(pWTQjo4%)wN+@~UDf4f0{}`BZW-_a zh`JsbPU{UEpOiyW0RV`~MJFjKF|sf895Jo^RM$~?lJk$88bMt22BT~9OVe0PHhzz#X@On#4PHHMIo zc3vvu;I`_GvqXi241}QI3h{|Y<(Epwl0@UPOX=#atgZPzoUdVq!*TXp!1wNNk=}DXL(^T04Zzh z1VEhAfuDJi26;iC$z+ez2Y^AgAm;bSg^=3mQC-mjaF)itP<;4?Zr@)413vQ05qf+S zfbAYc9TZmMkMw(s-MtW+`l)R)WJ~yywx2S3(0oNKyceNQ<7boSv;7zwK#!0<3CoS8 zZTdA`+20p_Y9%2<eyu2Ju$h}@?683{Zit%b?>*Of7(^QmH1kpKTB4g62(;a=|;Ev_D7|;4%q50hjgOHFApfXhSVSW_#tmQ~{cDXA$ zII8M|5M$3lZ9VA&pnD)8I{2Mn3-3tZ;fqnXhg1n;qE&tiU?2C zM)%S})T1$sDN;KQiSGx1i1{huyj!M*($ob!$Ih}cucu2T+J@C&-q;b;JZs|B#2{5T zC4K3KN|6Q*n+;#l(?CEXZ; z3%IUli^vD`{QV0Hn6EJ;#l%d=cuq%j;7}CyzPG*J9iAyx1i83maac_c#ebXfN^|J# z8MohDY5;rPR}PH}om~iXFrfBLKEymvdpurNfDVe++KPlEQ*dzU!CkH=3pK{<_MM@F z7|BnEO^w}GD{&bvPR4p)MSOL|nUstH&cpmLr(Yy%B4C7a=tH$8%1Bm+BRm-iO`jj8 zc9-gw=J;@*TG4n)$^A23Sy=$6SOqS_)*lI6Rkhaze10TlMZvh}w45Vk#h4#nHac!# zbuHU8X1noJMgPcDiTiDY4KT{Lnx4orJlvd&2>D_)Gjsp2zOmj0U3kI){PBKZ3I*y# zpa8m}edxa=o7LA_jg`QM2W@i?ilg72t+ZHgzyb&e2u8w{hm#gA+|ilvCd&g^Q*v|C z(h~Y+K}Q_qm!|z!;pqO|mOO3+?v>{!rC~6DxV`OvLUQe@`Mf7_q34`sv(ihp} zJH9BLn-^%UqB=q=1^{2nzJpy{Va9HJN!})`8C#A`&EU(;G3ODd&BYmt{0bh1;a5OK z+?(s}^+Fkb`ckXs6a2*$Rf7cnYP!u{_nGNE0tz{UID|4$w z{IchfD@4zeH8wxb>4gJd_2>3lt>xR=W5uHcS+DLu-v=iF4DJ=9`FGRzhARtt(=Qtj zQHj*bIEZj)*@S%d?s`t%l2WoCA@#hxycro8c%iMWt;44E$3)=K(J1gvm0>r@_vCWz zChIS;V0Lb9{|B(^$^3U=hU>$rg0;1^A~jmfn|8^_(=CK{O7&acha;)IEu$>7HT)J`!=&yRe=5d%VFO!nbEQp+9v&AiD#3K46! zS6?_^?X>C*pc1?JD3&*AvZOwIFn-q>sakk(PKM2=6k9DZ_f%2dU#VTe!O_giLqg->W;^_rb{+eyhIE40O8>>m)k% zrAoWOoPdDf!$(w)2Wdk?Ln1IdZ12fJO@%*^qT-ln@W;GmHBRWu!@}g`<@L4KgLEiR zKv1xP9a!f7{zgSb#cbFmA?MdJudn@-8Ldbb3eB(5Pf7@aQ`Kcs%x+77pm}xciiYsc zc0sMtq6-AQG)#2MFSqiZJ}mR3p@fKmUT}Pip*Sf_=5KE%SHYd^Uf#=yAz~;NxvZHE zlp$y>Z{W6Cg{2+FU_piuF(CA<1Voea9eZ_!d!fejL!OG|QX#mq&ppT+YNs#cUR};D zGQYR-27RY(#fcc3TWv0z>TjD|CUh>gwR zdA(~*VzK(iskgV6i;IidphM(KG4koznPI0Fr`PSF-AZ%ki?^Fwb9T1=T*alnzCI=9 zaKsn-k7xuxlU`%6DXA~4rzO6|<1H`8_+S4l$P4696~Eruc5C}n3qX;Vw*f6zUksSb zLq<9}=239Hm~}(XgyXzGJz_i9jj&z0nlarU;+~c{57K@1-y5eZ3Ry`Dy zNOWR8vW@FC*4l;}Vb_RV=g67q@mQj8I925+VqzzB1i-ZYx<=Tw=I-8X7lj-biEk%QSU762j|nlJR3QxpT?6G{ISbLqs{N{g1) zSB_&fc;#H7A}a#$6_?%e>q|{A!l(1ax}6f!5-UDNM!T6}MVY~j-=YuaRr})ujsjP& zPo=-fD1K#R{Ls}+0DF7Bb&RBH=;(|L?EzFK)`-{Ke`4Cn%clS>TZ#TP0{Qk>omN=2 z42D_@*Cx4{a}vCx#+MbnrxgtikOr6@F|e`jgIy7d+&3vHR9E711^M^jR-Y%fus&8! zPTv>EYAZ-P#ns*2VY%@LmssxqMua=y*aE&A+89z{rG!Ei8jVog7jAG2@yy&D^x*oWXDoo4$n6^+O3fpA0P zQlQkV=ZUfTM}`;WHp`!00oQG%1Pl-%K^H{8s#NrIMB}F~*Abnu4<98F%u+2(0$3UP zdU?B|eNr3sw~e>2b5ohf$%80{rJ@Nsp%!v-$e}<&Zu{4Wf+p*^&rel#s>x zjK#$H{Uwd8B2+U?9b0FpAgZFpdpWR9svf8yg!KC~9eG2?PQ&x$NxA z)aN@$m9@?HtEm(zBqarivzZ}NGe}L~7J!JGTeBY1 z#e5YZASoq9NUi^Y-TPeFK^XKBm`7a(AU=wL;qe>f6(nAI&2#A_Et(z%GjLEuLWWX*I%e+f`O4? zHPy#(1;|m!cl&1Mm8LXU_`fj@)qf5DdcShYPkesM@PH3Uv&ytPX|D3{yBdC@w&}aA z{WJuDsNbJ>dw2kP0zV+&g>E^w`uX`8x{CXa=UZhsVSW zI_asaCxUli0_xSfEhcj2luzCq%qMabXKrUolp`Y|RG^-zK|w*d%m$Mjg6#xccmO?p zeO!hgjyr?VcP9({JUjqEDDdBoTqtmAY6=MnNoJa$$S(}N^Wn6&bv5YEpG4?$o@+(9 zT-aPi-9(65KVm)$?UC-^##t`oSmHhzwRQu+oMx`_563UPau{5>nXmu=xw5h#Jv}i9 z^uH$c?5wpTp@S=(Os=u$xpy0VUV_hxPZXuI36u5Xqha=GuR8><-A?-#ncVcPJ&#C) ze1^6hqoSe!n|CJ*M@L7feWRJ&7rHS^tssk{&&y3VxaGnZ^}a7|DP~VTU9qvsobKAq zw%Ydg=f6IGTYuX=IIys^9AX*$8-fyF$QccZ`?@ZlY77@oLgH7p+^YTA6(y|8S2)vm zx_?+!Q`3BR^EX?OpXU{M%uc!KAcmpzN|8JaxWeGCq+{!Sr}ww2I9JhGv}uQRQ<@Ri z#ajROGBtxINVZ`V7oK7_Tc?C(&{mqVZ*JHQiBxoqwbgpPQW6srQw$j*2m}J~IPW5c z0+*MU4GFNG`YebHlz9>AqoBw$*VO!C(dGx@Qwe_! zOo0eLTZ@-|$u}Q+Y-{^IYa0ZH#72rY4E$$8y@@fl8ZF=tD*pBPg|klA{y9M+8kM{Q z;}=LjPw0c|At5&{ldWZ1MVSpTospazGNk_g{vP1C-H#MRRxV7Y0w0OXJm}QX*m&C? zj#Y|7i-e9|U0OU)cCdN9H61 zC7jM;xSpXx4n==mz;ASt!zj)5<^J&eTNVO(<;V($gA!!V+}>V>=3ih3NVmHI;qq+k ztAVDs_wa6~Ppn%~ThqGoMM+7)AgMpmGMPDU%kPcZqHB@AGqST4Rg)?zDio+9BO}#m zuy+QdU+(*smzJ7r7GlhnBqMS1er%0cH+Wnb0}dDK3X+rOxJjZRd*fNWSbeqMq+?i6 zgLkX0EcirGUw1y;q%a2NpF{6;4}T(+YF6OsF;o|g#r+3Jlh2S;{c90%~Vt4Y+d8)AI{#|>&i+g-)FMqf9?S@ve8jC z3NgVS^gUhN%{R^M6A}vZNkB=2`QTu4ae$RedMjvI2-I*#p-F}8IrBp5nV6Wu(22L5 zTa}cQh|mw(iB`wP#@5!dfob7b)O0({6^zIs#>cZ|3=l4d_0{3wqjsX1p`oGm^&E=f z-@nObHT+R2VsSArr%N3S0l)Y`RDaZ|t*mGhB+Vup>Yrzm@WlD~^TH6W(425>zO+u{ zeBa-%2Pjf2iaikL^_!e7#=hAfAL~3`7bUlFCm?F$N)T@zZS~;={FSh=-{vdHR%)4c zfcfYa>IM|=`x_R<&0+gv0VORh4G};gYi(^UB`L{@I#VDWd*ShFx6&L>k)D~^ZU(_| zt(GC=wr8NBA(M4pX|~(As>PyG_)T;Ce0O4fj_QBdmre0PEWB>okC;WqcD}lFbgGw@ z_RCZif4N5QY08QnF7=;>pI7Q3;T1DtXYlYBWX7mW+aAxx#_$m=E-$+rOK5(3K!Mf9 z?f0M9+39Ur0iFzM!U?09<4L8KcuzhUy%s*Y&7Wx$1WZj$QOF)2AIlY~?d7Kiey^T; zQ4P90o?tb~G7;cEfH5vTFDs{Ht$PyrBKfIENwhupw!Y3-4pek+p{aJr@AXfwdv;8q$UOWNbeL}9m}r%EQz0Pf z6Hkw2i)xK|ht90m=hV&eAF^0jSgfcG&CNofebiWRLtR~&Ust@fv90YZgt>c@hlGH@ zYwIt(YlXbUcvh>|UAePlL|)#OyYSm$oyiwuNeKx!>t^AcXCa{-6XRPuJN$@e(An}@ zPL8CktV~Lq(#&w8@Q{%0_O9t-ZQe*>R_t;uOrO(AwZ3p>2v(jw4;tQOZxGYWVDwl9 z$7eh|GN*r0sD_ua5W12*F@^^4+zG1DKEE2N?Hrv-O$i&ss$@Vrk1N0ZGzV2Wx9q* zN@1pI3PIu@^WH~lE;XM?{W=nM5j_2Vq)7g6axpO2?RH$*3o$pP=pL8^5ynOyh2(=yH#(!-Q6Kv zBEPK6^Zs<{LMW?9LRooYXy_N&FB5P~9@T4Z&)n>(_pZ#lddVLhokl%BySLX)MxCU> zqOWGhOvIWsgR<9W!jzPhbPbbx<0Hv{-&V%tw#(RSmi^sV2KBpkg~-*__TxL?`>rk- z98-OaCUksCT^Eyh@VkKVjR`C2$y}}0aihjd#Z#2RJy$`boSL?_tZGtlu(+fod>_j? zCl0jM5BmIaf41Y?T31*1PaF~^#|hdW?eCXhN+l#BvbD0(22op2<-^M+q%!G?p*;!r zce!6!(bC>`dI14TpGfW9T{@m_CXmD7Xw`A2SlBR|EdPh5v+QbvX}fl?LLo?7Bsc|% z6@t4LcP;Mj?k*R>p?GnJ;_d`Xae})RcPZ|?tM{|s`31A)%ba`m-pAxW2gWsf1lU#D z#Iz?v14sjJ8Efq-+FYmfCH-(Qn3=1an_ZyMZKbqInhQPSSi>Qe7zG~AcXRrg8+P+j z)umb^%0^xuf0kTB$N!=iH_E>QaAosXI4$9!qm0(8mf-@V6FJz~E81K!NqC$t{`3NB zO$XzkzIWvw#mjB3`(6G|0Hf=JsV>e{^SM$b@-{s(a`O1)%fMGC|HW!sS8uN#6O&GU zgjNHMG__BsC$mnMA;Dq0GnFI`KzX8H!pJD^d(y-Jx#VJ{Hc;XN5z$%h(4SxtK+g)9 zZgn%)h+r~&~20WSMx^_kM+ zbtpfKWp{TsB_-vT%G*BA}C4CbtDeb_IP)V#b@ywMq%T&9bb$vM;1hz#h; z&$j`#?eq`O=(PfP*8ip%wq|4;;8O{Oxr~Dp6T@U=Fnw>uLnw|zelh7OK^+?U_wKK@ zfiSIOU8$Iu#VONp{JWZnugqd%&ftaX4vWoS_SDqWe|W~X{}vP!NGIAY)()`Sp(BUX z*0SU)(cyA?(E9LKZ zte6e{Wd>?xZl6v~_e`+VmP%i<_aZsNs;fR{xcuUIf5pj}DMpgB?vg-Tys4xtI z*V`4xy}dncZEe*u4r=Nm-@7y6z1fLeVNXxbQaV`*oafi4^R;$&H3Y%8`|bE(Bvb}m z^bm@z?QLQXs|%Ro>HaS-{8Yc{*9RZ+0*0G#$iot48%#|M)}WbJJ2IjsCf*vUos}`F zbV0`J`ZIy_gY7tAG4W7m}hcP$7@!g z%Z=`K2nt+oZFwy(&m<;s#>6P2DC_Rv;n8c>4CL_q!AA&u3o!;s{$Cq?l7lLZ9e}8>pC29`nrm3t<^P>38KoW^v3y;fm>MI%ed%&( zj#4-$(Up7Ua~uSl9;RW7?faC>_jaD9-_(cvpDjvPOj^emE#PfEI0 zZ!V{=uOBJ?O$9e?RKL|}Gx3Yu1s@NW!pwDF7)Fc38bjLX&Gq%j=%@sx%5uEI@drY} zrFM5)a9YK+V#Kn%wd6q6?r1K#@VGKAWSeo+21LX~DAc($TgHcvFP)n~wLhHn3zPUG zvq5rNnki45D^H`|cs--0nAqr;{Kmk*@1> z26Dm2ib6hiH9f7NddA^R07Qk2Fm9VBmY6$JV99%uA`T*HPj{0p8oCwuMoK#zFc@EG zrE(Nm^o!2o?RC)i7Pq(vF#1ssJjyb%A74^e7gt=I0QDF2^vn+rua1p{1S1UZcX#lM z%_R2q)oa$chDY?@UhgnEyc}OI|mI%lY2p9>KD_2N=V;FMb&Lp7&e{!cmlo>+j!rX~qW6&Dw_xNUeQx3K?XV_BIs=`_pNucH$a%rrFb09o1D zNQj83jN1RkyHF|N-zIgbsrZ28loa|mRF%<$loY}BhW+(s``sEtB*;Iw$Isv@`D{c~{v2L`a#pSFO3U)Yd}(i{#9gPG?EAZ>ki_Aw zfHy&(?Sa)&C2c?!1t^NLRgVfa{M}kRFE)|c$;orD@EhewL;aRwt|CvM5G{?Qh5;52 z7JzZ|C?nH1j(DHdIHacsu!i!l=nsTXjyf`L;53O!4tpUxN<87Y>Wn|w>8_bsYp16z zc>LXJmP;$I<*~4^=Fh#6Lhj#suU{{+S;dTG$=9Z46WQs#?RQIDfdZz1k~YYwcx; zxvZ-(bvR?Sh*?>z%b=mzcyR+Nl&-aYXmU1PuF_?c*rXn=uM{!t);G#q`K2NbM{qO1xS4T%jwQP2ERX|uc@cLj%x7qH2bw4&H=KAtd z^|d=VI5;#^OkDi;>&sKAd^%-{Y@6QM#U_l~ZZWU0P|ddZD?NR>kpE+uTB#XZx(LN0 z)c5YkXEA`$-PzhqiNcdoWwbIKBLjm@hsWvL694%xx@zXQ4f>S>=*e_+P~IYjmI^h4 zN&kB2mx0AtB2$h!>H!DFx&g2WfiEs29a78i;Dp4 z#FyQ3J=1&R?ySReJd4+E!!g2awZk(I23bgBRznVUZUf3pbHHa7T8@_*6qJ96)fi-u zKXK`?QBl>vGt*uUK8Ver0i<+0Zgz%AE#YjnEej&2MXKpudt*@dpb|plO)G16 z{mxccr8be=uaEyo63jZ{^eK{xiZf)w)wJujj7_nXd4JB1=CD0a3(yb&IJixx%X7B9 zh~Yy19EJKx6)?)B~$i=(q~AySR@+UJFPp6#x{+Q72TITqUd&%+LJG35?$Rg+c(>~{{0y-)xsz~vA`<3Q0wNjgs^c8Mtt#5{Y4b=#XGeA9th z8JyaJG-gLegDkfPHf3B2G)<|}joVYQLdm(??GC8R?i#19RS1iRM~>H%hdm=}-7L3N zV$5>=m*>)4tFRDJ9Na`3esukO#fd<6WH5-Q%B5V7sVM;q6W7S0BNIN z(6*)urK)sW=H=%cq5ZQQj_ZEQjn)koa6~}Zw>q1-a!g{bU+N4bgZldVcPC3T`Rml* zBVuB*1iW2bT-g3GN*#w2zeE!-?>X@}Dz*CD90egD-TQTkQ%+qpp&%pw7Z&DzG7)le)+>Z56B^ij04r_ee#^1a>xD;kUX)Dg-S>TO8!~KM4 z`VcRVogsLCw0VDj4~t%KkLSxHms&|}n~Bz8-(}Z)X@qu~C8?K(h(wuuqkMII$C>rn zgT$BrUhcPFFp1rmm@G?+I84N#J~t!%{V0RZiPQ)p3@PZyh?uj!=j%}LdB-O7hVZG| zM_vIF9X%={B99JTLPbew;^uh4^L!nO1;4r52xQi4Wf2m}DX}IQ^!M}gI9)b>Q4#os zicRL_?futFAbr67e6`Kh^K{wV);9CUkDe}6BEn?Z6e9fF>z?4o4$o0n*E!Y@9Nc1c zh74n`_I3++Cjb3oI~JMU-lodiCoF?Zer}s9i_4RFzR(t)c zEaAX_#ad%OA;W)}VM(0-ERJ4!bmif?xpkh{2HgSvkJpFk>FGci1)7PaWsA*RdA?Y< z3DK&ZERMLe^iaL|=(+&}3Vj*R=J)sWV-R@T9Zhp^aNvonP-nmto`m||jsIj7Gc@eZ z%M0?y<8UBMBE(B^dURV}>yThJOhiY?qZ{93;ZP`3528R66BCn?GG1xEh59Vr9H?Yp zXgB>{sx!?c6?{Bj__%3f%kO{leW6&cB6S0jf7nr>x$$tLsgp0#wyN=o=Gvem)zL^< zX+H+6&nN6%-}wtoRE3JRRE2<u6TTgzKTWpTPV9-Aajogr)RxXs0U|KUozrcYAo z78XAE{9+y!h89J%yn-#{COunc`qHT`<8j-6IFnRkSo)nokK&-iUiVlgX_0nFHmzhl zX_YoW>IJ^PMzW9&z}w<({oH&(B9Ep1qK0FURKuR-;@vj$Jg3;xZ3yi_MTgpU<10| zovmRKbLn*l=ohQz(?wB4baXtmyC3`9oxP-!&NQp9dX%j z9jX*=g@g(VL=_++h3>&1?%MT5m(Ft|uC8Jb%+a{We0tf1K9ik?t5o}y`70?&2Hb@` zxNm2mumVo22#eEOz}+USg36p~p{5&ZgIBChNmp*_Ahfm0Yuw>sw_vr(0{qnEY`PdP zoGANceEUYLuFrO}@9{k1=4iTj#&nQjbc6-G@P)$YPnW+QSBCIc{S3y>%-?AAe^P4> zKkx+FZd8fdhm`Bh*6{KDrzga~G23R?EooQh*!8eCnJ>1yyu7=+OPO$xBAMtIaKcpb z5832>wdZ-Z`Y?-4MMV{OzZo78fd(;F#x(~?N=Xe44qA@=Wc7c%E-RC#F*i5YtT7Pu zxwi81YL%x^`-%gE`P`ng`P>|Nq<}D$al^J-A3F**Q5o=~F)=Y!aEs}p{6BLnP09bQ z(4-H1%l5c)cx|xUiUF!Jpa7C#D!vI*$f8NqNI}kRen?3Aa&k!g{A%3XYS`EqN=jl< zgV?H5*6Qt@FMb8T;);v+7wfVK81Fkb+1j&FN2=^a45Sf!|{yBXclKBt8PiBo;9 zXcQ8cX=tdJ^>F4gN%IX^)yp{2s4yS}iyr(^ zWYT6omfw zAM&Q9X?{fiRwydA!$y}NCufQ=2rInsc9e~s-FBnPf1z5x!{hYm@KF0ffuAk?xa_gmDHdu+X|aFRw>@dwsx0g*I*U zfrv1uem0OUrJUvSrh=E(JS;ry{d;plLYKOqG%`C?Iifi32B(44m=Nd2#(M}vhlYl4 zZ_h_V<{r&Gt75h(CwQ&ff*kjtaTR`js zo@?zsO|anNRORGklFJ*o?<20L3aa78XQ?=j);e^t8BdL>sQVjD)#9z=VBmcM_T$w`Ip3r^{bxXfC}3!oIP( z>tZneV~gM94e}*DK~q2@ZXb@*Bzeb zVPQvuzm;({m1<6t>9hC7=jv*Wh&_@(S7zp<2lG|bOqknFodn>MzoX2UcLoNAZ67~^ zq=(G(n5tCr^F0K8>nGAuz_Gak);SZRxoHy2&dB7;eg|Da{(hb9N$_+Pl_w~a73^tk zy1`=P=$M%)o8Bcb)v!f1Q;o#y* zm8S0SJkQ~AE`a2gb#-;AGYGow$%}{po&t;>ROv$KMu&#{pIa$}x~RWMBxWHr4)gyK@k`<1z;A4Q%yK>9(jM=bPJ|thO+h zsee>0(_>8C+n2k#N+~V|!ty{67apL@G;aUYbp7q^8HZzz>G`@{)>4U>jO>VzqoZ|z z(D?R^c6ZlH3?b%ATs@fp&uVGBEM+fB$Y!Y`@6G9`khw-XhlQ%FYCG9M#@FH9&CcDm zROX}lUy@P&^?`v0*N1-oFJZBQ@<|B^D&F3_Ar#ayuP=8Sx#;QNLxCWcKU@9LxxAuE zO3bXRbvCx7jtR2GN;v|Nv9a*6F-9;LKf3>8KoOy4HQSrioS`Kt2fF@BvFgayaiytAt>XD;#9|BZS>?7$>#6# zA|g~5e_>`o1gL2)yl-)^&dlV-T9LG0f4⪻ZUGL>-&H8k9>n5EoQc_roL4oCO}2v1*33~*T18kGIA*(U z!zmea5iJ#zD+Gr9w_GQsDsirOpY>lm2AW7T)xHqW(iZZpudI}omUesn{dP5>ZfI!8 zh;M0TR$GIXx*SwkY<_ZN^ZeyK;ZA@5W#6|pEkkHpRt7fQM274)m(CgnWe;_PRue#P=w<{r`OWJIzJjFc? z{LaJU>FrK8d4pCGAqS}n4qhyL~u>r9-&hMe2U(Nr6 zl$Uz6b$(%HW~Qbt%9t)5x8CS_foF0XcKK=3PNPUnJwN;1GWDt|;eZI=3;95QYdBbD zS4*2MwR4KiEMb$U?(d4|k0vDkxJ?pQx6T%fms$B_FwSSDb zSTQgF$_#UL0WVQ%YOG*xqx1EFBHh;qm!)OJxQNA-wubV?YomBFLt!r?b^8hXRED1M zxLN$tEu{zYtF$t+cE7dEZO8da2LynO20q|GW5TlRRZUN?GL9{V0SJAQA zsL)hapZz(Swyl(1kSyDkv;JGRrIG0HM0MedoB*x72q1AhxBG6z(azKeAt-voFA48c zs51{V;H9bmCu{5_nS!4FpguI}>Vd89-YHk8{4L|a%(z%C)L3dP&Ut@;UOKES?l825 z+zofm51H0FKnTwA$i)@AlK2mn6J-K|Y`1z~q6oYQyd5%?NS?CK=h?56fB#A{NC;_j z+6;kIXw>ASq^8!Nqo?}72Yp39{H}MmZTT!_*WvzkVmKeI&;R}+Ju))sZ1qsUF()Th z;o?v4NIhGe2+QHw+JGR{O5h-tl(29Hwd32RoR2v2idF{CL_Aq6zXuS(ir?R-l-HH$ zZ*~-)2Z_rGXka(h+)OWvFU9}5(#;z9>~>uGu&`Glosu1_e=@73`DtPKmxO`d*blQp zr60*ZfBwRvi!uHgaO!wc7Sr-GNst=)Zn7 zH6&oXA^b-3v@aLAJ-@#0AO?w8Zef;D=x<%U-3Z|4W_P{rkG2m9X@rl>mae_-rmYUf zvtkVfE>ugNqsE&oPMQujGBL>%vw2NY@ODHj|3@Ei!|?A0Ev~m(YoB<$iG2;wN5#B+ zef33_Fw7EqIT`xUj8HpWj373pJ{gv`asHynW=0&%gpl4k;lkfNf=k8IOgf8J}NesvpZA3i_YlpqQNLUjLS<1nedsAACHpe-J0u+!$#NJ(>aGk8y4xZ z%gJJi5m|NI_`#%d)`Vt6e`%N^X~6%_0!YT1Af<9CNEcuJ>K6W-hvC@giJwNQr`= z08z{Lnd#}-2Yf(J!L4ih`>=0&RJSKf?B16wJPuD13RM^&&L@41PC zgW^nM^36w!vW>=Uz9wqUxuL14w+Z2WOUtM8<=xp9W{s&5{%>GmUK8Xp^`j_pB#(0k zKAL)~xe?DbKHR~XvsG`8dzKZ83<^(;YTVM2Edhf+k)PVX8LJTrnl27CSn~4mC4X~H zoI9;_v;NV5#lg#Hwz#`9ibg>tC}}|AuF~^i)+Uxi0s(fwaclpmt*s5nn}0t)Kkx2> ziHc1o;Qx4CrQ1T3>-_=w9~mix0-H==((D&21_nk(2_8Di(~(ixL}MxrX6wSbci_@0*Z2lQ!XYW1vFs(7JOd1Ipm&=!%sicU=|J8E4ty$!MEE~&bSBHlc=Tj*v z#4gu|8UJinE6wor;S$9F@_FIxy1Y+68MxbMIL()FcDOXlpzvyM?@B=%U%Gc9P8OwnmdHfSUYahMXE=DT8(uF8Ga6ZHb1X@w_36`l-0u(+c2RJ*kN~loFsQ$}m zj5W6qp^E-UXSZYn77hnlAK5=5i`L#+S|ev=b41dhbyYjm7zWyB;7_*H9X`Ua(Lw}x z-RSOyKQ+s6d@#^&PsYOw+q&0WX?AvZ%P9Hq?0MR!wKguB1}WB+%pvkVocn?-O4FRx z3Vri{54~?{bwr;o?(EDepbMd(i*oVwtVy!Xvu<}L_FitZ22iBPe){x@Q|+HI31f*} zuVqvS=5BE?my|33%_mDa0{*A0?bH|&bN&sRr`D&%p)YeCvQ}qcJ&Sgao z=k;dq5ihPM^S2gimLR>dX^+*qlDUNbpAQi!Sh{xavtRi+OTMU^n+H+k-a#EmhIU<| z3h1KBVNftbO1X1|I6FJLnwlCA_U+p@4z)tQFJHduYY`zV?88mzMkbfq`VXcQmaur@ z32Gh5LyURr>Xxv{>oE(bK9PT}j?B~(bFp}Ms;Zz8XpKm$KO4<-6le+>sG_Tlr^&hLUdTf@lBIG#m<)z( z>UDT1h@F$-q5!z4G33N(_ooUwTX~Qrx|ciKX!w{@{O|uEA<%i$w34z5Q=?vfSiC$P z>uMt?yg`i+R=9`+kBr;h)4&$Fac;6D=ci1MN|g}9H_NYO&r_5Wfmq8x!IZnQVI~G< zv)ZP|#<&VYI^jotD!GoP!2Vg$H38CDJPz9x+nrT-{$F!P;XSv%aBU`W$^_}zmph&Z z+Cd%W`8(W5aY~g1!`vaEiWT2#oiG4(wyyp8dTgz$kg}7Zkyl zQ(#NITvMN@!)h?<+1B2|1 z&D%3v2Jq+NbY440Cl|WPB`VsQiZ7XLHnT~nebVB3GL?E2&(E(fSP zyjp|&$;AGYxX~%&<8r(+;MkslC|$sXMGid;BLM)|Z=TE*9PI&Kb!Sh7*5oL$pQq!% zdQVvhwYhcf9u;p#yr8sWsMF_A3MDL3Rjz5TqDnXGUo60@o3I+OEwP~B%`@1scnct? zzLO*)$W2C8w$E9QNgs%bd3^jGi5C$|*Z{@_ z9NfGzG1|RtCFtuj-Q1JJHJ3FkM3BcDyxF$$0$%J+SGyD60{~+tJsF1We-Va$ewQ1! z=q9Ml9pi&qeFwfb;`Tqz(nv{s&fXiBV2z;}E>#G)!v3m%L?Gt?ejo5*j78q)s;B$i zYZ#@wsYtQ-G_HnzVp7uFx(QuWMtb^Oo6Ve-euk1)i1E+nW-f>^D=RBe#RtI1;u3u- zTSg=qpB%7?^=6efDGs(T$uo1 zZZ-s)#un~$+l2lBp_4#v8(#9{QYGx~1v8LYNSpTK>)^=b<(Ok*o)3?~kAMr4iFM1% zKn9}66(v$ulOKzqiU2Q4tg^I>q;6A#cl(>!jkKini+9jC}17>Eojc)Jg^r>=A> zV?Oa~b(NdN&nWRf@#9GHyd=*rP#+i=Amec|f@g3>6ENrSxgWg>zfsGm>S^HP;x-!f zhNOJeJX>n`2ii-(L{?K(#X(kajKYZ&x5KFXE-x?dL=yOTU1m`Zb0(2ci4^bC$tnJv z=>67J-bsRBbqD7r9}_S;xxG^c~9abi(lNoq)O^8A^KJlUp*`B z{r=Ud&#k!gb8jk>9lv$50KXpypc6y%-FE}^>qb5tuygm#{M+$YY{)#K&vKv0<`I`d(&?o6~ z8NP7=WYX*IH%&bthGW#6cU#hx^KdrFtG!|A3@?X5X;rXY^THGbpcIb1TR(;>MSv~;IW9gXM~J@>fD?>G zFtV#1uLvg3Dnb_)hLsiEHJ&`AioCfi$pES&s~T9raM=KNVYAa0_62->e!yITC9Me>f)-;DY-c$-Zu6-WuFQ?vY+P+@5gU&4hKVhPM~VaG!i1f^T$wC8G9$=jOU>OZG++)c1X3`t+%}iG$`cS2zt14*}+uA=q(iv$=SW z>8x|La@;{np7!AO_NEAGKY0CX^^pW}-LSppe@+mkxnPP1Fxp<2IZ84m%bB@AaTTr{ zaqfeJ(fU@!GV?W=UEODnu1roH6J+BdX(=u7bytlOct`2FpA5~+sHLRzpDa$9eVVl~ zdG5)`WBacd5-TLABT9FIc~TS8*4J+%BF&w$;eN6h4D!_>)m)Bv@}AmTZwT36uEW=q#9%DmswF~ zB9}&Ut>(u4LB8@!uIKK3u&0E0Lz-u3z%S08%@~-qU^!P#>Ql78Fvo?P0fXp$;BgxBtFzYTb8A5Y5OL3X_u5*X%LSnR4_aP}L`7$F zz8&h!GZ9a2sVhgdJ-0iG7Sagfy_5?`hFU5|TjZLY+(Zei@p>3yHlxyE2tVjOYUJWd zm8ZxFKVk2_|H71r2sp?%*6f}5?_9`q8^{lc&=vIiJ)j9F7}h0dT&Nn^Z{0pw;*gN3 zZ@?qMZh^@Xqy`pCXqQZgk`vO;>{*2?02`(o$`eeiGlT-3Tf@V{q0pCh_v6`Z2`Z{W zV;Drg)2pttQ-GcQYPHQZnt=IizA7^=PSJcH%d2y~N_QfieSfjeR7OSyJ&cl)l9G;Y zXk-Lk6sJtxXJ;s3zDgG(tS^?Bd;Th!h+3vxodIHu7LsS(9w|+5v*(^7Tl`RNZ)Zmr zHND6du^gWOKkl2xiR2F;>2=nZlgr6jr&X#yT3Fb8V~3Hj6Sx8Z7>2@wo^eD=gh&87 z*4Q2yw#w^1TZAVn5W+2i08=sP~>LMR3RfHJBReIqq0v@^T# z5m>%_1Z@7U!r(vnZcjGV=UVlMLlr9XZ}s|EVoI!$MPp)PGo>rUaEcWB zn0Wa3RB?-0newqnXj5dD?tpTkR1eFXxUfoSr;ul2WYQu3_E+TXJOJR466V>2IMS~I z_~lg_ri=aJoW%(s3^e;2adw7PW6nFvF|4UfJZCQBJ_-pZo(Wf3)U(d zFagr4i5uEzY|b13j+GHE?%n`EQPiV2r=tJUzv2Zx)Tf{8r=-|OEHNO+iKm2&%YED=qxHS+aJ#cgTYNc{P_6zqiM`aN=ot3(ZoW2JW&PcVJ0t+ zH{bG|#4k(8UNy|3;b9wl_LrvJc>0A)JdlL|<2uL=&i z5PgDJQen<#_AX&-hw?UF#RNB{l!HetbMtON0pzjBgv41D1=fpCwo6*{8 z^}8kg_>XW85yji`QW`p-gy-nqA8!%s(({)QJ4S*1K0PvkZP&T^$hG`s^Hj791#YCk&=+4 zGHRzQ(<(s;$?(Y9gbq$UAO6`VLJ+LUwO0#`KQ`1^^U?6mP z@a<%Y9V@(0k*lD%xW9RLd7!Tkk>jT-1h)CVn>Qgb88?vv2Y_n0F_EK170N%BH#f8! zxE3Mj?YF&{TCDcYqj3{~&M>?h^mi>xp!{;*k3z}K3m_shDrAtEZ`SVu00awlXKcPn zkn)@G_a(^>Fzms=!Z(e9##Q38`7ZMp6zSVr^aa?w=R{SY=o+O-$EH zV`7N0##kEl%*|J?WzczVX6~ybL>A*x2(Y)D!7M5lo%dd&Yg4jY0reMD*uUkA#~)f7 zGPzrN5&kHcjfAh95FS?i;s8v#*3MP!-S<>WVP_OX8FX8$$QOzxCW)1)gAovj%H#J1 zYIDDc+@{FYT$(DbYKFk`l;{WmryASuejOu>lrl$7t_GU8d$}0H9*WJwRxXuEEZ91_4ZTX1xXSedJ zQ@j7Urqp6oZH-<6WH1)@k3WLKiuueWq)bWT3{Gi>zo>d(-oDx#)S?i$tZQRPAY-ks zQv&kdCsxn$l7}8N5zf9tp+jFI&3RiN&5;)FrqV;8IGEgMYPVgx74%g_{#;YDLa*J` zDmr3Tq&f`HYPPQ^<9mR=yJ-Lnp<(j+?{sasj-ZHC%*C{wItM+&Hv9tlPN^0wDZjcM zR{o#_IOXuQLLt3moBv{lhNiEt%L9{h1;qf$Sm9Uw z;MHVR)kngSqTi+MUpCAyG%WzuPxJo`_gE+gZCfTbJK0G&8Z0Sb^E9nY?o#q=jZ9-_J0r5S5<3B%2vK#|57SYx=|P4 zqUu1+(k`&)lA@+WLql_WyueIFg(NYhQKh5b>LjZEq~X)YXer%d9diKm#KqxdDW$JsoyVjKh zkF{Nc(?t<$(5J2I!xA#Gob7?8OraOosaRoAYac#^MEok9xyL3K5*mlcSJk(TT=7?~ zMc2ZzZ0HA?Va4%O0HAv&o>+3l1(3(Kug-#3xbk<9>MJ{h3B$ME)TC4x)1D;eSLY7n zdq9wR&z_j8uKGsqyKNU|piFSyJ*lNcWU@*=NJ@b=}6)?f~ryeSaFITI^XKn*?kGuzQE)wDTIiO5UeIJ5?K_=j({N^4_WN&|3C>4LU){!>2Ekm6cjD&i& zSXZc6El!hEW~xMwiyl>Qa(a3^&jy5XgefEV36aBC;AX|@mbJ#lQ!Kl@yZ~h!0#DPa zf+h$=my{Hi3TAry*al{1D0tu3u2#C-ttCEcI)BKIijRHg!X<&e-szW~C8yhbk$ry^ z8L_?5`kujGvERHy@%8v@7rt?AYhL_4?mtT1QfnE*xus(rsB>al}Ed8PCywaR2$dKcPahFmvrC`G>19{yiYbT_k8GkV{^C z(0@9|7dvD@o_KO7Gb5!an5S<_bgL|cF%)t_IK+-r@36-FSgiL77o!LK6vWo z4(VPVTXn6bpr}*KMgEfhpXGQiN3&(`KhX^By4c&FUhPjjag3Ff6crV%LwzmH&7Ip; z|Mj*mN12Jbg8pSl&eyX?cQ3sJ(&aracZNkn-_50Po}8XGG&FGAFLRg<#4J~jPEIN_ zq`X5##U^AEzw$gfImt>%;dET@{9d6k=b;bvy^D*AI$EePl$J(&x-^~wwP;qh-ds(* z$;)(NUPc$Rr>0hizH`svo|x?2y!ul4+c~2Ee`nV^GrjKiSs<|4=KJ$e%KrV|7tb@Z zDwX}pk7&OFO%0&-&uCFLnVFgvq{19H;x^FND0oEjVPZK+Qb z)I#;$AHs#no}IV)-y{DxJT1}GZaG=3GhJgj0*TW*}GjWnY^HkR5SB_yN%cIhO6_ElKp}B3E#^dwJ*P5TXpTlY!{e79NZKe zv(IU}qkMh*r)`PHEa-J0gh?(|_0)=+Hk%}WpXE6?;k-A`IWd%Wa z`T0K~_p-!PRoRnfgixTtPo_`-$f7vNWiTk1C<%O&`2{V+|E<=_i{<6PIIFYv;&2nz zvE2OfUFrPypI%3Yjexs3DK%Ucpw&^>AmR-~ENL*wX4H zxxW%ctJmMHh!0dC2(SCmY^V1Xhlaa}38li!Q9nKq<|SZ2x*R-vvVto5qkY7qps)}L zknuqgjsM=XEGc-|l3N?fAEPEi9l1YFdbH#k+kBh94mC7r6;Vs()4~s_&mA9;B>+%p z9Zu760O`}%fmB8_mERHVKYcO+aXD)addoI5o&g6Df zOlOlQR^{d6gM^14A0KlQJsE*K4kkaR$hzO2ED66o&y0=P4JUpf`o+!7ty!kNyu3W$ z<}lUSd+hX-o|=juLV+Gj4Zuf32EuB6Pql22GN^a^`(^923{(r~n7*f`GRVo{eT*!x ztfZqqjD|P^VLx2FkKmbQ#>Swy%=QkXkUYB|kt4lRQ^shNv|Jui*?ceczw(nu%B_DM z*snCg;om>L7gOn!I7?kT6@q!J1YDK>fFCd#=Oc@ygc79iDEIy&zco#(w+9zm!8ziwh0?dU(V zoFP&?n?7E(j4margf64tN1&krT?ilq5Jia=l1CRp@iQ+fSS6N(6w}UL&0$?VZA>V6 zB*?jqLxG)|UQy1pN`;(nI?ewD0TAS9XE)d7Kb}Nee(8cc$O=y5H2Z?8bh1kFRo^BD zTIb75tuON7+V}h%wN2woP>L4g*+NaO9(ZAH4(k8ZTvldX$bp+S3JrMi8H^*{-rnwh zeLUWSXZrg1%p17hovn%C{5P>*T3TufvRF(Ou$_w};-n%IlGN4BGzP^Ezeg5TKLJao zdS1&|`}lacxs4Y}_174t!HraJ{(lz0!a{a#OPrzjJtF9xs0uC&Ai)YW#X&|e0)R5! zWt42Z<{INPS&6D3!*GCNtiW9-780p8y_iuv5Ye8WOn|3;g7jjSAbpa#gcNZ{>%IM| zm;I|BBwN0Uq)0t#tF>ox(sW09p2%HsmOPLpVvKVo3I!%!S>qPAA{Ta?QX-v!(|^b z<>cg!2V#jG92`vQyn2EV{{H=Y@r@nt}R~d4lHjTnTJaZCS3IvRd z@Z#0hs-qT*Cz5_ja@m&Dke44mUZ@X2ES84=@<0%0p1dDHMUHt9dD(ld{L{zMxabA!X(t19nvZ~B!4T=#xY=BE(0EO~jea%2e(LB=-z0e^%x}=nX)V0$~HA5hMvezYw~d4350$MrY)cE zYtKM46h?(FO!qoAOmqAsXP#FGhrQ~8(2V`u*a zsI02WR2QhuDsmWz*|lacwngec{l=x64bj8NzhlbWgM|(%(LlhNBf<=%BhNtG5PNz|}T^b4sM_pY7CF8E& zu9O77R=nLQ+uPrB3$e+WBQvl7HI?Ey{~upx5fw)ltNXf;$8! z1PShL!7V^=*T$`bySsVKgcb)G$drJ!Lvq$W{c8Kc{h@!g}en^2* zjE};>i!LZS|8gr6?QHvJAfyt>J?C9w5JX?_ktJhhMXDE&Ku^>xMwk{p#d*CLH z?v|C6ofG4L;IXl>PmU9I<@40b>zA8y2?g$`1=+Kh~ytU9)cd3bqPr1?gBGZMc;kM*Kp!Aw9 z#}bQ+Kbz2Ib~t2PKh)HCE1K}=44r?r#nkS0tU{j+@M}%)yWGIcqx0aCmkh_6k$QPs zoN8W={b+cA`?z8ApAm$i<^!7ly~Xgq%a2(7JcNzWHB&{FJf8xNhUzFlL1Sk;ZB63m zU3juSYzvhX7V`KesXXnDrYg#b*Q(og(t>fkd>`pU|vQ3Sl^rRnL;ZyMiSHhzM}HnS|{TUti$_V*(z+Hz8rtPhlEuaUE` znF1rOF8Gp>8UlL4E=N@XnDcQMRpF?b7d_=F2?;?z4}_fuw6zaa71w^OD+mb3|NMcC z&8T^+YtSHuO2`uz7Z#>Dih8^~uQJSb*+x)I zzzu`L3i(-@mzX#j2*WrK!|Cc-efb$HEe!}P_4D!5TTVzy>h0^>W7Kua;h!HFtw=~z z(I+CxZx`UFE{>PQDZY9ca5rgDNhH%Q3<=?o&G7pA+n_)w&@|0re?oU)z^G7r&2;A^ z%lopJlE00$UVApvHgyU{gvaAG{ZmIsX;62)XtH)s4?Xzr*1L#p-4oBc6kV6ZR=osj zL?iXC13%1a99_7{yLJ!|X3EM8aIh@;5@=`R204C8{D#zwy$o}QkXni@{M zyWvC{FM*tb0y9lbY=9JGYH6vt-=r|@b{azU)sYEikaLfP%l&9(Bx|nLV)W*8nE(&3 zrdmElIfe|Edh=v)92GUd{XFOCcAZ0(oX26d?wasU6Ue?w<+Amw4o*LZuyAmNGVGY*h7cB0-gb@6mQe7!DjnVGPo8JA=~4bDA*kzKhMGjF3=0%@gnHIt8{;Zx#s+K|ClC4EAWMS% z^z<5MXGdhpWLHnoxC3NpWj2hn#J{609%l=f(yenEU@sIxFdBG`4sp zdzRz!@+KFT;PegFDZgG0MMmIeNC8pD0#DS*u6fHEpfxyOK)nODEH2*}fym zKRz)M{6_k-<8xbn>1xZ&oRNRDXqZ~w)gprrI0+%%$9~tyr=$wWv-aqyN%ChM0SJ{iyVXndxmp|N^>c|NLXi;h-IwC5&7-S7Se#}h+CMP<B6=4 zmf6XRu{74*#YIq%w)+_&79KAB&8h9W~I&GM}GhbK$00@gkdiv~BX$qC$ z5}&6ww=&IJj&DEdch|f6v8C@d#8fL@#+;wo;3PJf>YBb<<&R&}?5&UfZ5LM^sUd`U*#+4uB+2_U zYeKcA>eY_SI~`qD58k)9>v;T*os{E5c8Z6+eZRX>P!GB8osQb@!{VvVat}^#SLgmn zA7U`d>k+WGQ}X_sSsFI*!!aE5H`=E)I!)(s_H=_m5y2{;IiZz+FClHZ4}{dCuu> zFJtaP##GzH35hgX=fAo9akl;HZE%=n+6=A``qZ@Wdh)I`#q74)x3xjlQH{%SdUdd5 zUhC9eUsz~iqRG^Q|9iU>Fw=Jh`N7uIE`Ow z`*)*P7Dv5@N0F1kpKA6V5@a`FI;fItbca1H(o~~ zWT%Q97uhddZ~&#%&C1dz635oh+MvYxQ0c3+KB4jKs*>y(Fiq-{r$T$ux|P=yxjMleHs?nmB>-Kux8 zh?C3R-_X}F4cW|AP>6l1a5DGBSyzd8*etB*-=Cry+`AR0{$hD5v_~~}VzsTw<^Ra% z5Eqa_#K2vCj_R+vdSBRYEEj!*HK?D~bZD`bl##Vas!RJdYjIejIBYyzH^ZRyz2A+L zrurj=DTd@w!=4RiFceK^ce@keJg3e!Xge1j>oUXjl1FvgJQ!sY2vJK8DP8Ub*4EZy zVq%aX4BEecN_{{^LZXm$x%;~b#ARm6Clr>HSS7O2#SX%u6c^4+O+7?~C@LuA7Zf0( zy_lYl1P2Fy`mE`8wz9aefIH}ngcRA`-5pK99U2-cB_$=~_rSr+t3#bg1`For0VQ4bsHKwrvTxZ2s#Kgnu$sG2~^qpSP; za<`qi4`s|$y>kIJj*o5e2qywgy2K>2#NjTUNBte9DxPPB{?HyNUS6J_oY1Q&$;u9ILc(GRdH+4#yC%zpnBc~2Q_7Zmes~WL%g)X&FE4Lq zW=2Fr+J08;o%`FD(dCMt2k|8VFAq*4tTn|$l$c) z`A;O4#%e~bkk&oGSAjX=>cSN8Xg{?(iY01H7$a@Gp_R#vl%f6QuIUG#heC@N`{7o9 zmBuaM+;Pjc^?;=;??HRlIl(60dmu3Gy?8n=NBoaOD zeKw1leN#GM8)n)ky`w2%q=x9mpxTJWFjXqckL>b#@5OcD-{*jR-4$oUv^1GAbx@#q zuF&ErSq&@PuA4B^JU&2?f>8}<8BUu3V4T+>fXL?TR@QpPmiqbO`tst! z*~v+zWa$?rhhmr4<=)OFwN-CwO#=6yjQ&2bl%s;Vk-<`@5y z$ikf&Zbwx^s?M(ultsZXK&Zc?!$N6M*zjYntva-r|{ldA+9n4Jm< zdxo8Km|H}s>Pjl4jHEjcFdNrv)^o9)lz_$(iL)vg+l@`nR;EJZrmY5Bvi+jLz`Ca|KW=5k(z z1;(GAVFFcXU2+A=yy?tevZJ^8_!=%ykTdG8<{5or!q&X?f3D9hHw5*gf9u?U7zSTl z-vJ^c$sE9+2p1~Ac*%Pu*0)Qg^BVw&T%XCI8ii?PuD=FPm%vEcx4Bo8#G+pkt_&X- z!GY`qLx3XQB1(YP$mofmWGqzS_TF=inEUpT>(5hejptT+#XDm@yB_rAfQ~1X?-T12 z4)4ro!XMKwavyCc^^PeR5q#3Q{%oe|jHd9UK7L*Aq<>1$lr!f5Kv(w-F1JQ2NH*UJ z|EL(_Za6Vyq_y#XHn0g@`L}|XYK6`*37&CwIUb&+lcP^wYx9hy9By&luZ`Y=vm8r< z0WiWT+1P4FLL?+5!~0DEm2-*@XlVORJfWeXisNZV8aRq_I6xY|=hvXDU^!{?63S+oPJ~b4Ts9dk$@)sW;-**I*R;Nud z9i7D@`P5eT<4_Y^NpMe3kAs7QzrVk7u8>8W$vFA&L?@rmjW>JUYmMieGq^B-Fo3#o z;T?9Np2&yz1wg5j1ln2VQeS!_WIe~>c!PJBQqyR74>bkg={qW4{`Sd$Z zJ1*^(q&;OZ+iK5iFFk$#QegdSy9r#CCWT$&V7r$qJ3Iea*83g>U!CsR>FI{XP%ww- zXbL^H=&&gl3ULjUK;o2xpz)C-!7HCL?~|9W&B``X#iK73WvX2HlW)7^kmLsdkWP(- z1&pf#;Q&%|(`%gKr{H!O(PI*a#bL|RfhB1}6_vY9xbW>$YUQeeRFzSYyVps^U>6mD zHV75~G#vDq087U45e7MD1_Q=J<&j^(umHpAuMw$vsVl-v0)U=|m7<~D5lL>o@!cM^ zu8QF4lRdRUH!H*anjmaNy#-F+o+}I>LZ_MXndG36O!#;htLh;}Pvz4YY&2$z8RD3w zp2tDA06pHJ>L)1!LaM=?S?*78Ko+lSC@Ba#lGABJqc+WNxK5GAXkhpy@QAUt^JD`x-+`=a6m6%U!Z+{w1z#Sox&+mEmW^Q^iwwOf}jmr`AS!;Edr^K*dtd-Q#N~IkB`}gn7 z>9XhP5+@niw-&sL_uov;nGFSYHfvUw_-vrWVwIub`sb^|OE$JAE{C0?BQ`~Kx#e(7 zx}YCzZsFysYc%CMlXGw+Fe3cFy4-mWZVw9{9-DbHKBxdJ;8qauSLfhw&>hxr$sk$8 zwy6sYkWz(B2mqrC{U6=|g%Xr>ohq{LmDOMXzQ(zwhRczFngC(R1O{U0z+lM)s(&XP z(LwQR;XPT>Sgug!-x=iRLbq?D>pf4Umr0S=A&l(|C(0(YyY4H^dfZX(a`1ot_$aAjJ;)T<$6A9OkRgrZDJCwR>F# zyxfQ7)0&xWKR@2?@4roWbD{h5|91aOO=YlKDH$5BZ9>8n6%}CsG!h}Z#oFC=uggMJ zI#*#$Z2hvRE|*>N^R?rK1}GX{0uhlS7%LNctNq*9!Q1;ho1dVP-`{J>Vu}(FZ5E4n zdG*&=(oae#g9XxB+R}du#dAQRp^*T96&}FW=yP#fQj@Cw-s*M`0DgJ9H<`l#q}h$a z4IwbJ$g2U|=ZP#N+Dp4X+vI?+L=Sw){I9TNEC3KU8;kL8s~ZL+n&tmcCZr_bs*srp z8;6%@IIyjf{d}{|A!Mh9C=Re07Je3vkH4r10dN=7by9Ba6A?D`$0jFPZRb%%Crk92 zG`+2={2ZALfWIZujuxq>mJ%-=kW@2M;x6^SJm};s*Z?3Rr684VD-xb#@IxhO-Hg)- zM?F?+FjkH7ecdAJ^CLT&tW>Ld459Tzz3ns$tgYjkfBtdb5e_a9QKe=DjZ)UoRa!Nh z$BA}Cexa(huCDGUkM(vhc2RUYuFM!l1Yl@rNTp1@!{@dNsiDBkyrf+a}crV5(&`^BR*0u}&NZ^*t5mli>tfD;ZND_p|`%wWxZiLYaz&MmN^L zU?e*mAn7%hYs4J3ck|-MDB?eKGiv=R6gHeM{iyu>XtT}xGy?(c7%X_VsLLj7mHPP@ z!VbBsNV}H&>zs9@g=4zqbp;VB2Rx|jsHzSdH1LmQ9KixN<`>Mz5O(X)FYO2SMs=wI zy}*+H5-lQXU-=V(NeMUMM7#IgXl>HuWEWF3GSXo&9OizC|xm#&*Oyp@!cbo=gkG*iYjQ^h6z$=23Z4eNULtI?;;foK8(ZU?*N#!3}h zLN2?7Ix8rBvso;$;E0sOpV`?Wv&iAye;3<>Xv6}|rKKRr$u}&7x%pd)_t2DF97y_Q z;kSvkwe`1e-#|e>B=RQp^t}eG;Cn{z}U|`TD z1f%ygYg7pN+&t-O-(7AGD#5@wp=7>tM!^uuq7UDm$=20nXBG>J3ZN?+3V}SzyzPF0 z!vXW}r_P#B`fQ8@13QrM&mGpM3gq`unNWr5lxg6MkGh^0R#Mi(y?X18jNt%uqs+zO zo~qp_X^r;pXG}(@z#lda4(sV+Lqjcx$aDfJy`l4ob1vhX&@NOvBewkIG^C>G=O+&& zZdC5n_3ZOowT)u9!PqlHp{l`+@78urRGFdL`MUwjD&C!DB0#SxnDX9jxpCxd)FaK~ zi&Y?9x8b|!!#}??N~*G#+v*8_pT#5NUaz;>7IGp1-40yd&LjrF?*n_t(h`TObG`G4 zfU{QN{Q+-wL+7+vg&&Uk_pG$EtsQd_a5grRIdN>1TNxpZQEq#xH(JOfQ3r=HJp#bv zx`!M@ihzL7V8*7dY`xwo7}?+Id+%c5xzg%hAy*^@uID(q>hQTG1x-y&O;r(qIfdEz zs=@HEqV9!AD6$DuR8;#D*{+_R^OKW!9AEx;QqYQ^&s6GhKd?vkN5saGaD4gG=6SAL z|Hb*=j%)&DCbuIo5mATjd{t}u%n#_k<68Uu>2gz5RTZTy0wN+mKY!ORrK^$$G|7aJ z_wOeWQT6eK{c|ghb6Z=F-QAV1Paltl;`93?Fa}`&T?B*}IE1KnZ}&2V8+rAl<(V?V zJvuED-5A2~e_ydgSByGZKfsxnq+2=KW$qk*3Eb%yj{PAQm;UhbWaTt7ZeJJLBmu~D zIG03);I6xi4mDgC2##TukxWPM7TZ5S`Mmz94? zlf>n9Bknl)`~2t=svW?M#Ww11`ezBiA$zmxQtIi4490Qr^Pf#oiGXt=v1iwv{*e&M#JXr>k`j4GkOECDguSy~x>Zic7xNXE~xNuS^=G z1JAclt}ch@p0@U&A$fJN!80|`>wet-bpbrq-W$xxf&!WbH7}V;5t?wA3Tfq*S5`(w zBfSLX?tcFw1CuguRBuBnjG^K=l(II33Z9;x#IfAQ-9W_VGNHg%bWwC7qHMX-j%`}Y9*E-f!sbRl$ zudlzpJU^~4-A)!r*MqZ~nwrwn7bgp(y#$EiMfI6H52uQ7LuVuXWzhRZl0UcTGr@}r z5IerUJV$SyL1vGhnwzx(Uj57_vM~J~PCPtb)M)kJLq3yz;f!pMlDDl)nIi$!eh8X# zYH1@RVvZreA;B+C8BRmga(7(#^!Y_3j*~DZzd6ksB_h8{DYx^3=-hjFo0cr=XoM)r z&$gVI&xk<+t2N)>&OcycXx1$T{5&{TD@mIxwZ_+#8(EyU`pim2V3CXOCa1>5=b+x02h={YZv$3(Um{@Np3c*oKh+Z-{LgJmX^Sg_S zch1gKbaY!$$U25O`K2;c@#r?303Zs+l_bM0mPzPl5dotk*EKY_+uKFy)&D+STdk5t z>#SkD{5?f_=DIJm_WN7kZ<t&q3R4 z8w6lue}A6V2bA)AwduH+a_07KdAoCW!4VG^_qR3!G9CRn4b09KF0W^`EZv^O_bKhKz4Ugj4P>Qv4ZVr6CJ_dFXL z8oGNt@6vIHI$~&*nR|InjVZ`_G*a^GrDT3)rd7eh9zjC-)ZZVmW!j(}MTZqEC%M4` z55PlMf<$N^95<*FD4nyoo`XIHQ=x;RqTGH}q7V{}@q5(&yTR7gV`px`52>hF_LwTP z^0|?)TRkGiT^K6BU%5Z!7ORw6w7Y#c{0UW|^PR7XZu<(R!Vp|;Yuf&$6Wv1hVQXuv zTK^mAkku?bb+$YsFk4I%5G@uLEFULt3eFFS=^tDq0c*3DGtkiuudNXW{am`5t%{v` z2N+vhr|0H&*)7(pRwug*L7|>bPPBA%&Q4BWZ_f;@<`n1W0_gr0DC~;vVL6ofhi;1pB zgFab1s$$lr23L!gr3fQ&7}S8DI4b|zpDd@J*R4*kT1h=)0}G)IB7Gl3Df=TIfbT(< z=wS&WMMs7M1(AY8(Cwe45-26nu~zYnaV_d}e1(*iV;#*4%}mJZYgnC}SiVg5He1MR zR_+j)-eKq%uH6(XzE3Xi|C0x&oNY5!(A2e5Pxijob+gyOLUR%ip9LorEg;}Upm%pd zR@Qo~)vqg4Pe}n8+HGv;&DU$mPE=5A%~QeTlY6enq-5FiYa3>evq%pBVo8Lh&a>66Q6ZPFE_!X&9>ryvlxLFXb>SzFu&-Ac`h!*GNkQaRz& zBf$qNjUj#saFSfn!+vhS*-DGJo`xtohiTsr@i0`fYk>i*%<)dA&E8)+byY+H3pZ!0 z(XcSc8g{jNb?Z-7b_kQL`D4OG0X+dmlL2%O?2=%&G{lH}nS>Ylc*>5D7tSbBmdKFb zi?peuTbI1BFw)XtCDqjy#y@SX%gijO>T4$J>ZZ9kE!KXxV|K>JpOXYU)tSrM$;b>2 z$y~+|5m@o-X@2>|~c}r5{&EK3}XjN^{&qjB5OI0kdXY;4t?x95GKfgRg zddaa*6=Cd*UgA90{rLH#6V;Dj&vVXr7z_q8U`HzX45|n*F)^{SvXTh--koWC&6I*` zYHI#B^v=Dn4-N^bS+s++as-HHI@WZ3r8L1!iI2Z{xIPXJ4!*j&`t|EqdwcuVmT9;I zdFp7gT#;N+uX7eE4w&z6h)LRuyd&N7-*onYvPb_LT!GD=XvU zr~Q#QczAd~V3}IU*e?J}`&R|UT#fu+BJ+7DMnf^qD7E8p4kshrL}Tg@5o@h-yV!* zLDtjOX7Sr?tG8Rk7`%9TdUElnNE{ADA@De!V}uulg@coh#=l-f>xDo}a2-}#-3=0% zz+i9~8c9rexU8Jq$ixH_9bFF#au6xJs0vomyZ4NgL&|hS;?rG)CNz{4(iAO(@y+n?5s1`?u5YiXq#I)+C@ z>8o$16&4p4pDs5IvM{i*vGMWo(a?nTn<}QUkkQhXe!Cvi2t#B3Gr1V>mlUC3bCd67JU#8KK%b)#UiuMJQe%x~eANX!fj z@IaC~`78d{ht0LKuE8ZH`dsD7s5D=(B_eO+TzsCYI=r?MvS0fvErN|3 z3lEipRl>@N=%qOw((A0>kOsVPQ(8#_M)@U)n#ydOPRp{0X^e;t%MB*CHDL(|2oflF zUGAIw2K)L-)ysRnBfc&uQDH}(ueRY}V`Jmt$y({) zv6+K1$ECnYl(K|_htY1NX7={>c`9Fwjg7y2`C@KvZfa_3XJ>aq5*iwsT-$D1qsy&H#Y}^C*#P(TRqQTmL0ob0AD{pf*glD=@dPW(~&V~ z*Vl`!p6`hE_V)V|*`or_cpN_z=c|~$BXscl+-x4rD*E{`uB;Ns_R}Q@@PCQZrI%bd z2`rFK&-nv#f9%GjiFv%2b#bX0Ph;H}iXTwB^|XR^3i@D6p+k)VW*z6E4w0kW%4p$b zqdwq;#HS@!X&4WRM5i(*4%0@kv9Od5#eQ;rl=k4qEPxNB*nlk)p!m151tYs~xCvH+ z6TgJ%!~FeCJ^p^{DIyTK0^vR!Sgam4~OuqKE@E;4h(_8zhrf+M)o0*vxH0)k{{j62RaI2-gly~+zQPTz$y01kqpjD0ceZfh6wOm_; zgASx@U`dV$Awa*FSz21oc~2tonc>8fa80a@jg9p>o<0*^cfBij&9!?hD@#vLPrr?U zzqShd!hNrzUX_tgE0*A7ofr0Ypp$EccNg&Jzp!UvX=%y%5ObH9sNS)DU}9-G=k{da zOcnE3In^nqs)_+G%79&QA{8%F@Av2d2M6~?h^L871mhb=Ha=kBhWW8>Qc@XdJ8PMxIA24m+P(7=`w%*BWBsXbko)ezRBqRSrX(4?UP(_cDPzP9pr*2*8cN+~ZmA0< z4gaPD*HPJSyM-=Slt3xl5iyawIL6!VT*!_H0L@%4mjezhjqE7E@ggEOa#54b;!W=D z=tSf(#y_L}h#!pt@G|TA(eZG`Le`h<69cb0el<}7#S8>4Gp`cHhwFrC!t2RSb<%)=%2sUpXsIy;$zqodH!P>-XTvgYQm zcYimz9oNhWckwuWST8rO&Q(5I4JRbEd7d-qO!+-OAm}gV_w}hgKWx$`$F$rBiif3D ztfzhZXnwal>Z7mEQg(G-Wl+-TJsW67rH1A1JeHQp?vOg|rzk6&P-$+{UJNZJz4J3YznL)OiI;@UTHcL+kRnby)nVR}|k207WDt1NqN(&v7~D zg&jNc1wJ*}3|yJx+ZVxNc{w>b;o;#O9UXObuE%qgncR+sN&{%E@OdiQwo~tder|1T zm7gL3xGcuqm-|q5Hnva{f<~{)Jxwwx~dWj$TWL%nhv7oH8d>OTcgxwB>ehSV9;7xq}nLL z!p0C)P&uyuAQcl6(*FkuX95|QbbS1|&F9vLoE*P=)PErgkEBZf8+xDFi*MM=bGkfK zCRGkSo5+v%g$=pK)^8sFGMdxy1u_#R&WxPwkti1PX+qlC*iqXu8&*u41pp2*Qm=;) zSqMU4NXwMDtZhHLn&nD#J^p3orJ|xEJ6o+tmF>p@0?CC@_HB&kcM^-x(<;Yd06Cc^TrHbO{qXQWO-;SGx92^}&R6no))RBq_CsqBd3@=IM{ge= zA8+s0*48ScuC?LevMi$riG1tnViVlCPQSy2b|!;XEMj7zfS0GhK)}q* zth@Us87TqAFpv_W3ay3ghx1eD9UnEb&HIaqv@Z>~x5ic)o82i%{)pjcudcr26 z>3o6o`p=&g?3O!&135RhB<`oWkWtrvf1$!gL_)|iQ>>)jR@XLr`Rr3gE($2wa&f_B zjfcNb>p1jkW$5tzP432HxxHx7$VqP$J@Q;lLT=12wg1eA?(Py4ZFr%1Oc?#<6sU{R z{?q7u$>IOVqjY~Ct0Qnz5~8uXR-`&u37FQTVUuZ$GO>AI9c*lD6f0&93=DAX`6P_) zYI@B|YH7XAus+@IR(HM7r;aY#-L$ywAf-ARLu*sWF{z8-6weTEmixmk_u z&WH-HKOCms9v|QqUV{g&tmneihQ1+fZci|D_vbXt) zB!@gZ=rfEl{~psAUKWJJzqwzMB1a(AamHxm?=wk`0g2LWB=owrf#|7}OV5mI;3SZj z1S^u!<`+4S`lCK`XxJ$zDRid?&LqqPXb{2U&_y6mBO~SYW)MiLQpGkB-+_Q7ljllT zvtJ_%LBo=VlPv^SU})stUH>_*>}T|oZc%>Prggd6(3Gj^!2k66X5_{c1s0{ zE}BEP#HkG5mDi_BC~hbo9^UiAadmWK_M7q5b$=o$Damv zWl_F?qTT^O+{eT`dbOViiyYK6*<`u|6IWCDIN|1CveVfr| zVn=FlZ|hI?WZRxPxxvk4x#=`Jkx7D;l$1KWuWfc>g&iHwQHl6euo}KhlJ8k`t5C3i z3=PGkAZO@kCyj^@`ubO-%_Bc4=|SUNL_Tq)Q9v(LnKAx%eSN4=>x|2e%-#r_FHUuT z9}6PT9C8)elo zu%vFUR@KJyw~)57Z+H~nXXkfg<@#BSar-B{n5(wQPE1U|ixw6Y&8qvk@iC^&;=_<` z9}IChbiyGZUL8&q>kNYRa&?e1HhK^NEb332$)6Ke?XI?jS^?w9<%FZn+Y4S> zRWg^8u6(w$JI+QO-XWwv($jS;mPHt_g#%s)AuQCYjDU!=G~!HJkG6us*ztTd8EC25 znPPed2prGk7DrFY%JMy56D;P$wSjFEVcDCj^hl(EfD&%c3{)bqopG4wQWI16_g_!9 zT^)Dj2qE=~iUIz2f2yR>_A=Piday)K{>`55NKox-npgzm1(zcv{^ z0;-NHvekvrFs3U3P+^)>ROhC-(7<*HDz_6Mi~a0B7TLj0io~~&FtjT-e~ZkGp?C^P z+1f?B0cjH8XLYr5LZJe6MR+d`gSH4bDLoypZbxkU?Ck8|Kn6V18-kQRXIx5#&ee8X zW$;}&Tg*#9KaWS)RAQ(UJd%OjpZ9UisJ*#Dr>;H>4F*tpd0}7c;&yhosG=4x`f_y4 zzrD)O&dnW>zn0Bg*QQfa!^(R=LM%&2}?E1T_kc$%5kDBmv8*{em^+Fkz7pC@7qr zbE%1mX4cm40UnQ&g&!X&(un00O>}B$qk}3IGC|Eo+gALB{~-R6O-nvVg`%WZzXW9romMIA)+B6 zfS$H5RBh8r)j&Dxo_qXb#D`4c&BFFih%LTb_=h@I)DP&84K~vf0&TDVz4jk!;okD9B*}s@)NCKh$iU*V)ewsTQPXgFNU~vdlJVb^%7Vu-)3+3%!X?Sr!5HC?DGEk z=9Iww6u&?Z_fVB_Pe1p2JTA#D^R=$-qMtKHuAf=sDe7`6FZ1i_)oGEi*|&=W%>u7q z0ogUk$jB;KC@3fvt@6B-R8*Ths6eURkKgXcb6~8Zl9IP|6vX2q%?cR6iBTysBRxHy zvP_+x)9_!Oco-=NpT~(58KMx&_%7(D^Y#E3%l&AE?(Kc?gZuv()|$_Sq1|-&h@-3H zk_42x?!yuB6$*X*Yo@FK*8XbS6ErR*rR;g~6BP6r3xQDhMc&*T6A^K*ob?Ml5?XA! zv$G(VqZALJLS<*2+o7d6WRQUSMH>+}g3?S}%!AX`gNsxoCl!(6$8qp`*Qu$cD1t%U zaMr0J-S%N0%oKD4@xR_(*S=g`wQaB7kMjocZ8ArXT*B0_m`kEvZt}--m0+w6?`!&L zgOSav!)e+Gd|X_0dY)Q!`l7+eIxA>Z=5_wI>HOa1=*mhKrK~QSbsQRrkhz5g43IWk z$(+t1n9gz`_sqI+VBUd`JyIIou|D_2BDB0Lt=830&?*F+dN)zFcCFtWICl|R1A;Z;_FY-)b zS~WNR3(c4O7Zju`geO+%UlZ`E>3X?g0+FDj1A@kunqH~cYG1#>>F33@Xh*q~F@2kd zd!N9vgQsM}U-qFb)`n9qvZ!CQGq=BYdSqG?+Ss!Bnu>~mf?udvVPE1qw4eS-MdL833jWAUzyjc6|)Tj=cXnmqF}6!;383vlLZ*jxV*f)$VjAV17XO> z$jHC|f@oZ&UK3kokBTkF^>ub~8qd>I5p_%q5V%!X==vS;l@800ke&K=wjx8QwYHGb z=JsrLVuJtl#E?W-2?Ku2(ldkK(_d5b7KLCzS+SgX85|IpyU1Ev8@j00z@o0*|u zPFWcpKq@HM@gY8d;63a&kvtVbL2tLQG}ccmA(XNd6cq6?9KLsdF=>=$#=VP5O7!&f zC_q88`LaxmDI7kIy4u=1ySs|HLVk}orwX3W32!nqqfUKk>5|gYAJ!Y>~G z8#0z|CzRWQjoc94{&Qoq)t&j~d@xxKUKA7*_^~hFY;bOSkpJP)77zDJU(QeG|LX!A ziKOZ0xZFC7#Z!bgIc&P{Mv+p+h=aENG&wf8A0uaFr`z_(;3!TVOH>CWys*x3Ddi@j zifb6rC6rPMXWt)s-MH4MK4}=?IDS6AeRn>+SD4J#`sd*III@2$nt*#ElRNg1!zdvx zPGnGmiI(zN&%3+3V#Un4@$#bLVlMloq<+&f^>ST)+BZ*)T#;&L zXy`|_^e82q%ZKaZ5k3k|3^sQ5%3r?#Ku1T%O+^$TbV)iT6~}L*JMueXKOP=Bz!HRR z!x?BINI>wJnfY<8qq5Dd%ub(LziiCwn*L%SdS|)G)v!x*)STsQq!(@iinLg-NF98- zPsz!N(h-KB1yla$JD#U#bWrrU`auo~9;aqOR>9Ju<*=QfsFFr&%Mr}v;UiD3ktv~- zOUlafe)aFYKF0g_G2s^j02r{riz*Tl@sFiVx?FvUY2=!IiE^7{xd^#nylpI`JsJw6 zu)q;7M-ateuNvoh-mBMUeEGNB!}NW;VZ7<~!B^M2I}nE3am~%m%~#_x^6ommySw}6 zPf~Gl@ukdsu}czMOKWQ#6_t(seb48IYd*aOt!l%T)>aputPIfoHRFOESIqXs#l;)` zRpuKR8JTz}vPq5h2)^Nu>iL7CqY?Ak)izJ|GBBP$Prs}z^UY~wn_C$z-TOGoUQ-wl zIcpTDEGVd%kI&c4>|6XtE#=sP0?6d#=Ha0zC}`OHL%a+fMp?h9mq{K6w-#6>uwoV+ z07bt0LM8#$H!zS_hI*(KFI=C5|JGKpWuGBp2_e7f4N3csSXWTM+Cms)65LPzKB$`o z1O$)n65xUq6ulHPoZw+&REDOf%`Uz+tClg)fm4!7i&Q1S@f1y}i9_7f=3&t+$G*qYbu28($%~1b2eFJHdmyyE_DT2_8JS6Ck*|yR#s; zySuxe!N148_dJ|>>$mQ%>aMS3&bgGpPjFivKHp~1U@12piT zB?J74L1xtk7{S0FUcumP=;&T1gxbZ8&V_1n$v7)^$v6~f2WOXCTibNk^EJnv?|Dh| zsk8mCfY#vnx$)(o_OC`_p!~Q)PPqjJ_(A!IgwTruBZLwZ|NbQ6rRBLd;@CMu5BS@y zwm3BFQJr4FlbW4dA=?!S(BKh=cKIM(7+)f5o&L-&^I|bH9h^;#d=^rD@P#L*l<(8 zKI_>p*m#!sLm=HsgKP9l%v^2`7)C}OULq1~$ zD=+!*Uw%R8eS3SuV$fOW^b;i06)*-T(W5}8rl&72EvfxT{wkeBg#piz-fjv`dSdo0 zS{0@87SN}N&o3;rF6qk1zz-k}K_>d=Jnx9jW-+nS>?B5t8e&K{5FU~v2iaYfRbHM| zZd)qfSjofz`}Hd!I7v23Ak*?|2<#_ys=C|j+S_Z|*2}k%#25}c3~W4kpT{`MTyfz{ zr05J%sph9m8fc-?)(UaMsN%B6#yw?!E4vAAlZfBU%0?Lo8Fk!CnRLAEV_v*N9utjs zX`J?iVv3fQmetkOGM&_7ISN5RL9yiAmP%rQYJy&OCl{N&ObFwdyz_tK-U{ktRA_>U zL1NabJI4nHT}(O-gE?2jach6fLccp+2 z@aNRjR7wRD(BGU%!6k_q++qI$@MHFfh>5BTOGd`t)h@(%q#q z8bfTh!#OAL`hz0xZ(Udz=u5=yB1}nytnQV`alr+Ce+&Y?k)2(1E*1Ky|Ih#IH$$Sa z<%3cj=_B3Sj4SSE72I^9XVPaF|1Pu6G1Ep7l$qIrQUUqSm({@-B1RO@_c)ynZ|-Rq z05JcTf%;37387NAwc+Fr3J!^jhsV>)YrWa2@Z@e{Vq$wRMg)b;evQw~?cP&SLd$2i zraPs&npsRSZ6xYpZwwDwsI0s^mGD{jg$32Cy^@mB z_wS%~tKTUp2dAg9`_9OSh~*NS=?PM%r+AT?+S=&QB#Bb&N@*H&6p~YI6h@+GTMN?K zX2`cLwq|n1=S#LbxlqV8Gw-jE(hFy{c6N6B6gpSKSw~H>nWJN4wv;RJ0O0>(`6oiG zG<6&T*qH5cRomOMqt&N<=O0*(MO1#}&nO!m8ymCLawf!Yx;BezGaDT#D=VW4pHcz; z7qc@|O;Rw#pf09qj7aCl-`{7aj4PudK%>_w>e1`orkd9Vh?2kgzEtu!Bt3e+rLkM1 zKz~9+j0y|0sCzA_s`_!c)ekLnb2M8jo6Z6FXY#r=SWM=YdBF;yK>plVYxjD5eAI1m zMvds_Bm9uhkWJ?(ce^b&g>%Eh!wVqZacmZsQl`QnmpnQ=w0xke9^E+9eKE5^^u^cj zVyUgJWu6Yk^l-SBFT8 z`Ykz}Xl7$+`6@Kr`2Y0%Uh`FGylxIqv9TXat*bQ3j0dBeo11rcc7AYWOc%<#oh(%Q z&ZPH4MHI4W7B~3A0otAPNMNWR*EofF@kZJFz84Rg zHcF$x!311DSf#B%x=w1XIj_vZ+x?m*JpgohjGT4G5Un!x;UMYkQBzBX zuRNHL`FEl0lL%KRDEAYF3HblUh9q<1`B!YF2nxXG_na9YXXNMi8H^^legj`Gxw~KO zNdEZ21T93XRyH&?W;>ZHW@xyn?w6X7aC5mW5uWSLw|2JL`uh5MtZQm{s05~_c5!wF z0BE7U!NLETW9sO<>?-+-l2TJs=TIHBsuF{GhK9c9?Nj+Uv5O=5KmHxN=D~ZXJkby* zR8B(VKJp_KyjCrMUr?96K;>5F%ou|FHsN%Cx&Dkjd8`)}4GyC>-=WS-?hIRPf9zg> z@)eftsEdq@WTV2x`S3b+2V&Xk-G2WyD{<+bcM&sw<4>vN(ogEr3169@{Ww(|zKU{- z*}B(3d@~4(Fx!c3Y`ph}fC>l<^m{&S%;NW&3zhN16`}irjL(HK=&(fl$9B1a{Bev9 zKmVBNLve)3P?+DhC4p8K171u`O-)Nn%hS{If6#so4i1WnzcuL8s4!SkWf+o6XRQ!= zRcJ7UP_RROlmFW05>vzw`%Nwhj$srFtF2`P{9PL!OTe;XY?#s80AOotJ2pa_{YU+9 z`KuD~hHnkQ*1wx$pKObg&wr|{xG!&D};g}MvEr=r>O}$fH+^N*h6e^Zcc4)K;W0}{id;_ zl$4V2N~=0!d^j}#h^fu{egQ|x_Cf$0nKpuM?tu?TglZdVZRCe}VHZ2r6Ue{pzK*2S ztXeL2xAorXEw7HPetZT{BAL+2Q~>b(_1A0f#Kd1|8{d=G7dI6Dxu=R*gKFvCWMPz< zk)}l0U4?iG*?_>n=bOX$)YK1xM&rR~_K>q0`}L0F`O4|ugJed1wI7Vt8ZWwe1ud|W zan;q;^A)F^Ru)0><9tGb#+}18G775i9tdrNTI#Ej`ejP_Tb$S{b5M2 zLR1*=(2%yawz|5y0@?EKv(wYtm+pLo^7{JOul2j`G5WZQo(=N!sL_-SX|x)i)@Ryx_|6 z>%GP?x0_uIJy(P8arN=|G&yvM`T3-q%tn9%VF;$OMGzOqO_zRQg+S!5@pvcz7#}JY ziP=_B(CTIC{&-8}@;Mu!tJR9m^_@i5Y)+yymoBa(;X9AR@~4v_(-x&CSi-`P%bNzwRE zRh5^Uo85kGWq4R}x2&><$mIO3a<(y-}oDLha@QMnY&OwRaUfXP+ z9Bk~EnA7~(YIMGhqIFuj@qfP-!-iMi+$Dn8gXaPOVG1?n_e7;9og^%30Prsa&)OU` z1_VH2hcq`fl~B_}c7fs^G+rD;FTyO<3+b=4FcwG@0xb)$v1$HnU~&_!ecc7mJQOyf zEd5QCD5ap9{)P}m5KayOfC`29Q>*KyJDvF-z99hGT@v{P}}p_zVZ;jP_9Yp z&#GtvqoWB+%%RUc0zrxxw_eHX>>4L&&(>7m*f-e^E$5ZD_uH&yOD--hhK7bxShM$9LckPHkU2f97}TV3F^u!xPzVk;Q-q0SRE+?};Pu+$p9@_P5ou z#!GnB-z|*}h>Q!fWyW}_&#q2rjYq+mRkY|Y*E^TN@352ISEP3`IQ7(0-nQ3^J8QL_ zI6{=CJ(dOwwr4dCr*$=JCOjTTvy=Oh1aS=MSvI8K1HfC+w)|?!rZi0bi*Du+FngY( z<-g2%0*I3t_3fq$WL;hFx_(0S_Vym@UaW`5W@n#oZYu8XoY5rG@bIK@lue!dk|al4 zBIzh9D*F4ETu?CkO+iOTM?-@O?N^^swFX_1R6a|pOtDJItW^N9#WMqjm?fAKfABC& ziS7${XlQ77czAkxdVRf9wNwoh5Q)u9N=FyTaal6P(O6aWhf0dfa`n+$0HL?Jxfz#_ z|NjkzRR#e6|8E|ARCvGMhW*vkm1OHP4#IzUSLYva-wRLWZ8t*|gL9tG8EoboBMSwR zT)7V_&;Y&A4msRAX7KRvPs5bK?bD-L+6SL1wD-rv;zjf8&i{u3;ltKUsBGQtU ztk35Jf}H!106hMuIBjzUn;j^}LJ;Wq+YG~5g6*u;Q=_qMFk^QM2*R#*=1TwTA($N%GarLv9n6O3;Aii*Rr3#q(0RjfmE*veN2*XnvysT#;GEXf?0hlm$$DrAQnbcDWBrqjK{=<$ZB7 z94{kpHIL85`6grFKJ-vII~bN=%uH+5-SaQ*5Wl07qi2<}21QEv>v?_!fCy;7tvHU-ol=j#d;NKi>* z_wUZ1KXv2f)x-@NIN$)_2fGji03nr{9LLZz!qX*0r~4Vtm=L-I{bl-Zv!##4Pz$N< z9G?ah#L)QM_%~@|MQ1WrvfBJbz#mgrZRX~&(QsK*yw8P_Lb8~aBNlkdNv9)z+e!i)J0np2oJ~lTsMT2*g zJiebCk~B9pH8nR^pf2a^;^OhKE6c;f1Nqax-)NGg`R3;4z(Btqs{LC~ZoN-oo#k|h zUU`YHqMe;xC=$U`*r_H?lN{^#8q?y{zCISwz@XqblvV+~k6)Ic?Oxd3hT~p!SYa{e z+23)O8e@pQruQtrI%Jy_mn(6TlE0#}ebvt!IMRE!R66dKybq!+RVS3N<*!WU)A<^x zFba|l*rB5tz5-WOtNr|~F(Cr(nMoQ5mN?wbXUxtof2)1(UT_uQi;IiNB^&Hkae*!& z?sPAkEMFHMxs46*ECC1rKmp&WC2^b_Mn|n#v7EJ-#*GQFY!xWx5d;w`T;QY^6X!ir zS`pFj5`S)LD?ke=s)&4!9^LZ!qIq4b9=mn>^af!r=wdL7nS8bYrCbIG1S;y} z{C7NG>ErDk9ud*3W2c}n@o>2f0i3V3e?~$Qa68knv#ZF-F%%aM5hZ=JQw#|S=?z8B z=CIZBv4LB%h*CbDlpY-$g8;}SzhGenyg zwq3psue&kNekNh89nHOdzAybFTc(>}H9?K`A*bK4*AmQZdK$8!j3*91&LVI3w9RgQ z%$WNOa@4TBGeUhNj$%M8CyJtR?LI*#IM6TYUas_b=95SL-KG{Oz~;tAM^=YjwLs%* z$L-}8$+(Dita(S5G&ajz6&i_1>}uE3B}bOAdDDQvKz@Gyh=>RezO`njeT!8{z+$cK z@oE>m-r@6nFq!w8Ok!zi>FDsVxv6PpkL5eP$Uaq>&mm+lQ!+T1_+TuZbCzyoZZ1hp zC{54Z(qd@WF;NNzuvl(5?L>9}@f`S}1k>3PKf4Dd|%VBWqrD2-LD<$1j=8$j-R`=T27(LVSVM;`u%Ogpk{7gtO|LR(vV zo9k_m$j|w7iJg+N&^Ky^Qa+2%YKE#=hXDir{c%6r_w~u=kyS!s&=j21?)}I@Lt}Na zQ0?mKDx5RX-!Ddm!BGVV9b$+f=HMr~A(o>sWK^9c=%+X4sDLp$I~#2HFp@|+>Q#Yn zx85OZem*(**lDdJ-;nUDW=AC8tg3 zNl8f`(k4uX!WI?>+k-KgnVF0_O%vtXjV+M==JE_lmYeq>t0!iJn9%q2>FQ(OtLeo~~S!GEdsRlgq0ewzy`2L;_Y9TW;h zU6MYFMYF+u+u%H3_x+v^4cYy8y&o75z=ba-DJi+$;Uf`+tE!-&VE+75saU7O+asOB z77ZO86*`sQ>n;L|v7=Ob#K_qAgAaFTXlTAt|NRQgC?_Y!!^89M-#=JbSgz>#?LpFL zWsLqu)QHKsxj7W*uM`w&okb8(um;#_uP_-QW4)osl5r=qrSs;??}KX|gA$52e%@x_ z*&Ds@IiWyK@&qsBl+Yn08Z^XjiUTN8T|!K1QhF*?9_*bQbm0R6VSkJ%uc2V_o0YKJB!1{K*CLmwh+0I!@5f{?J7mhjaN3yOCEW}Oyt?kC#AIQ$ths$mI^$y)U zam1|s`_tw9{ryJQQ?1XDzK`qgZy#4i{qRYqr>Cbeg!~_ba!EXeNtKo7ADhnl9WNJ~ zy~FX8^QG$NBZ;(UXJ>OyF9s~CD)m8KUEiX&m6VmiYcsJVBJNp?R8%PW3Nrb9223WV zrpySe-VYb^@3>2h2^8xY-65pKUW@m>Czr;ZEw5EL%v-CTXs+YwGo3D({;nb&8r7#W zulQtlpk4#LK=yRhaoUrUDrx}mqkMni{wuAE#lm?vH;Z@4GtRKBj^E;Nv~Ssq8wdQ& z;7cCRcuo$&JSOJdnh1l6L2_Sk|2y`JOZ@Bq?gD&AFO?;;c79myMGlqY!5Wrtu8e=7<=r%*Xpf8zI~c* ztgin3Hr3tT%{PvPg%!afztmtWtvE9fg?FiY9#y8>npAK|A)D4_E58|fCP-DBoS}u+ z%o(Tbh!$6!reX6fa_C#IL>{4WhgLoBi_p}oQ>(fUdqLvM&*M}JCH z6cct=E!~EPSiUrBP_@Eg&Hg4~h%qPtWQj&W1U;yYmC`r}v5it?BB5%oTZSW;|3hv!xv*a}Us=iCXY2p^z=RC|gCs!-8Z8Egq!7Qx(YDzf z__p>Nu~@(P^_C-oNHEKf)Y`RSG~%g#^W(8wIUmgwr=+CF3%;s^y+=nxJilCz6X4?? z&6V?dT_@s;jGUSWJe-(mA=K^DJA`EA`YX_1gX3ePamu zFL2#Cg+rKI;o%`}?(Pbxq!LCA$R+O%r$fny5%D-S41I#xt>+XlW^+VB-LNilKvuSu z^^Qtw3$@i53GZ|7oQX2C?c#3Xf9BS;V#dNy(N|{|yJwFZj;@DK61C;Yr-VcV-p`U> z_w(Y2^aW}>4zY;p9rHiJmiVtg50bHJIDG44d0QJAu<_T~>U>_W&x~_@4dK&+;%f{@ z1ES=l{U3wXOi{JN_JF?MD?1Cz)gX}{pVu8-FH>=G@p6Oha-Ai*5Q?6jp3CuExqhc_ zsap9`o#poN@$=c8lao`Wey8v5NFp3EVP9Y0-~9Y)I%!1=Arv|=8uVn7!*(jG`Q7=t zzFz;)za*IGZ4_ZlRV!8|ri%Q3Z-+%5ogbtu07 zhVpVgTj&rwozJ^wPANeW1_5ye)nBWesrS8D#!sV{qEOOSylcY7#P`Mbj~pR@+NIHw zZ|NQC!t?>eJT6Bw#mbaPri}U>ZC>|hVPRo?eWF1M|4lL8cEQQ>mHLd(R>~M+apbbo z@WBD(lF{2T6zIK7bYS>GHfW&~y&|2TpD_W0b9_vlkbeCvQkr1`}+F2 zdpkKfA>(rqgRtZ1#(Igx6cAT%`TlvmJio42J9me{SspK!&8L{P4~)XLF_0aNJYH{N zG3fBU^j_Ku0tWM5<74y$dPv=+MO)3-GGaMnqtGa5S;99>sQ&bL*Xl!5aWXSGzz0y%B&2gY6{S1pBXys zu0pX2ji6xX7kVx4ht1F!BEb+80q=(@^-8^R?Zyh_LZmtRT^i9t_!d?)=*^Q88O52y z>B9cS(mzG-FZ+Uk|LgPp=U;mzEb`d`t2L&dfekQYrwUDCzMZ*A?{82Jq_L2dA&njj z_T&cQB681t*`xgT_YEHQ^gC>R>)mtpaBJkuYRCOlUf$Nlc8{ONwT30J&cnk$p@p`3 z#p!fM(yN-7lFTLJ@Nv0R`po>AUZ5mnqxf-Ki*#u2Q*aPMDCM(=gYXFm>VuCTTinQprVqf1!nubHB03iX}WIp{ZjSzE|kx<<48AUSv*;+1y4m+wpX_I z5JEORciXjDF_H2o=%!6IsnsHjkH4KaY+sIiA@X~Cy;F8W%jy}?b zncrtnhNNr9Kn^;}OeJB~XbJ0DI<~e9u-l!LqF0WXHTzwBVD+S$WWHaQs(d&|$Ht~| zVYJ0{79;r972otiMMVW*5b3Y{z`rsw@IfS+IV2z67NRvrn%5gniq60@0@~0W5&~Vl8 zjmO}yh8SYY%a0#Ui#1^(BH`QYjUhV`ZK(#L!Yw0}#+Or#Rs+pL#p)~XQ* zJXl<9WvbWU*bpGV0ssOoVodqG{vE>%k!^=lL2i!$$%5h+Cl}( z9JJn=lL%FTmDSZ4!hXE=T`@a51|by8V}Z3AQ)v*%_%$+7_?-p<$x4S0uk188H#az$ zu`+zh+Z%+-1cn?p{DK?*j2@=$F+qJgG zgULJyVBPQiwcdKZWTtAZ)9*dqzGKs)!+yO(nCGfyyTnm-SS8kfb9mEz)1a>lztwW8 z=eti=3Oi+9obnc-V6?n!G*7dujnCaccyYSX*n%)Noi6mDk$I@>&wObQMFYC9kticn z+KPb%4?oIp-{gjupX)0%tmDY3XI!W|rEM0fHv9d|%*`dl#rJl1H;Z)$clP(up%pjt z(X{F;giwMsBnPstr{x8ko0?K&3f^9yKP&R9LS)L#H`?pxO&)A)T#Q)Jkk#W`4^wGs z$YASnVWTqj6Rn^#THjAsVp1j8t~Ccp@*_TT zz$7v3_TN1(qY67Jt+k80p{66Yqf4QgjBD|KvOvXD{h(tnHVv8>OXt-0m|R}gE-DU1 zC5RF?{xoGe@khw4_EAhiNU^H6_W8K7^JDWR4~N^)1QTca6FP;7nc2whRc|PAYuHoZ z{6Hb1@PYUMV%rZUQiFfLhGAUE2pR=O7I%JiPSq(~$W1_|j5Z$v9ru6O{H#99A>uvz65CCR1?I>6&gTI4&qScr1%Q z-E>i{Tx%>_Q2*v``LO{Cl)~-gsmP0H`FCl*?;7q<{TXBT-J6v_UWafi&7pF6Uxl zxr(av^6=OUOuqV4RfQsKVGcp!Pr&O+F3CbC^TGuW+FWb*f`Wt`HM{Qng)X1LrAQsh z!pGy zL7yy@GM?z$>(>fvT)2i4s%_R$>Rf5_xVBYf!@J?-u7<>%u=fbHGr4y@E^RvI3-oXVFLw&;kDR~8iwYH#=9)*TvOi=jB6 zwN$@Y>JB3g!5d#{v{jN$?{ixA)8ca58*TpVx8lmt-Eg~O3%AFv+B@(3IhGv!71o&h z0wK_SEyvTvCY&Z%6o&Q+@$uK=FVG)GEnkuXe6+Uy?-3VYpmud!eP&Bk?Vptu6+eJY zGBPsXz5!X&q@?5#POh#M7g^57b5S4X&u9W(4wE62$z?Yem-ZiJ9 zqgl-#A*RDUF18=KY4^p|V@J9ie2Es}Lk1KyyX@J-r$TKl8EW4*eW7CmRO&9QNQ`Rz zydq}L3`v^%Ez)3t1Lu}2iYngTI9xLo`l!k33Y<7R+WL!>(edx){(xX-oS&SnHZ;% zK*n+-JdQ}beIzfzs9F2A<@RXy&Lsyvo=EJ&_+=P8xqbDyT)GWPke*g_0D#<~C!8i! zw2)!>%r^da&7JRQ|LvCuaD)h;nb3$WgtGe^pPPh)MDSf#wMAK3+3j@c15wIXC?;As zeaUxzcxd@4^V5IU?0%WMXv0uQld9clhpARHY=X;arz0o#4@=+Mu)Vj@<#^6=x&S9i z+|W?!2gTxKC0Q>kZXj$WflTokm%8~qwqL!dJ>uKxWp`E+3Q+<4H61f58nk8(dmeM5 zS_>1t6Xh{dXj7~i2`NYG^_$!#`JixHf0v-|z;5;P?RJb{$1@^qV7CF&N|QsLDLBbp zD^TwRe$vaqr`ovk!; z+N~_KdDPD4)3e}4>3d)H-<>XNCf(lN`aInfPg>N~*VCUL!#2Y}Kx<^tGkxKr`q9O< z$FDep^LSgv@eVCbD$=8m_a2!%|7sxm&H3Nl8hR9tzpC3;`dlFndKRj9ni~?yu@oQe@U`Ne-uhX+#^C zK^}r8vv6{mkK=;QjUA_LBOX5vidEZJvfq_rvbZb{0+2(3SB0Gh47?0W*kC?=A{QHW zP-~|F(fB=`A2RCG*wJCFC)3f2Aq%0I=Nyr^hB53>b=a2LDa)oZ|l&(X6IA(sU(c-@R zCsd^a0iP$8w8v|Bqp|F`KeJZg6vhSNy>a`_*8-(t;vmOn@3}HfgkItx40sqJ6!l8I zM1waKeO=vZmFkTb$is6%OfEm@+}zxYSBbi3`O95umv){CFC$;uw^%E6MtKSDzH7K~ zA`|X$!Kv}=UNQ*=<`Pnh~SH>Wq$po_^o2{h+C z@EyaE=~0K*(-vkBHM-co_@k%GTC9cdE%IKFK9A>P47d8tR4IlS1OQzg-K_%C;BwX` zQ@+M(0C0$@=B?RKw+6ch6B>92}>12jUw$)~* z{R-Vy*B3aFtELao*mC3fLbY+L>uEq>pt6!uGy!kOIGUJH-XzG_iaQ?-6oAd`NFMY9 zoJ7Ax*lxGh_V_5MnUpwe5<|!j2{@mvaC2}pc-^0&^b{2peNyeFkje}`uqE* z3uLXA>JH1b8;OH5d0fJyqE09C2Cq3mG&2JO;sO6=97}=$Df;jIv>;^)jJI;@fCYLy zhQ0O#smNizx84wUl!g2|a5X~@ITkbmtTN`r{vKoyzPEQ3bqVgSZ~C&M`Dchvob~DH zOR{AgIML1VKB3#qpJXXD64-;=jg9lvO0x@-!XqPhJbY)06ng}1 zZEP&kvY3qrBIIpSYGM--L{WlJI!(Aov-o-0*w_RG-$xQ@ZI|j$^T$L&kuWha+aJQy z)3r@Z{>Dlz%+B8K495?~5D^Lbwu$F0wzwP<`Mof^ovj>B7fPc%yxBSPtTJ}K)YvSt zwCf=QKb)OcYD~dhKcV#J&Ei~&E1Yzr_Z?lD-C+zzpil2F)uA}NTfCf?TiXSXW@{Q+ z;SXwv^m$tDSI}$MgC>5?7Qv_QU`L95Pk!<4bBJcQGEi3G9(mRn+&3p$L|aUFmqo1} zQ(Wl( zD)f4>vNf20-2PX$3To2w5(C9>lks2`byaUl%FdA^YXl2-R{DZXZrGSzM|nUe| zV%^t*(1d~#W+4<5VQHt;Vwt~%h4CNT%=G2P>%PzQzaA1xlBNw1MtSrdiLvrG7l@`wR6HqDe>leY=|o0NC@99Fftg7o8;c zHKGY74TADDl^K%ruzFg-m?W?wVS`->a5y+P!d;E|E;bh%-5eYoeB+FoHGfaaWz#uM zZ?SMfHa!G5IPPu*Jv=?_7Hht;vO4|C;C5`z*lxPGxUgGo;pXCs#9`fgdwt%$DgU6Z zJS@!S;o@>WoZ7uPoW>sbo1|OW zq+%b3@s&{>1wEvN$^?~kZGj9$APT(QJ=%Ay3wbK;0=}V<5mHd@3^xQAIXw420hSNS z{%!**X=T{J&Cyg=`jMUq)fARkFoP5chbW5<#Mow9Ga05 z<8Oe!sIwiLo@mNc9=~9YB$$!mSWmycagU>N(Rl!qpaHeuNGUcJ0Q}ixwKVu>#KQ~! zTv?}WH^Vg}b4905h>jXOO|<4flV_;@(`!hgswWAeh?flbJjrIukzTJwpVhZ3s;5U7 zG%-9p4EfCA^K`QdPG&{8UbgR)O=ZcSIi=HUd$7e+k)@ap{){CoEWCCbS@8jt3JMC^ z+1s;QYx6jsD=#iCriiEJ;dxqX_mWPc%b^;Xot+&VEYxfFluhTbU1_S$&d!dA0Mlma z!UhWEO_EbmN{ETAwz$wzP*AY5-yTjE(t+d1B^48@3i$Z>KYE&$Q{?jU3s|*imEm`tRb_4lbu@QSc8`$QA>Xec}WPs zfL8cEjqc(~Yf`>r29Y{G_%j*f2KCVwQ!%iC($8-j?(fdKrOK0I6RB*MY*IA3dTYHGT< zx!Kw>A_*7Ycq{}3pj;^|FD-d`c+3_n7fQxcoG#U)uZ)jaP=y$hCoyC-WDN%of7IZp zhHF?;r-8ejo|goTAE)m8o2>~ZVt27_r?SZc&AYxhcLk2q|X+R7gy zyA7DI5v203Y%RO{NEsRB6(r&iqtcfUiDL`Ldm})~;Y6nQ4S5vxFkL^!QNT0;uijEn zFdXo(*YLrXmH7_IXZCNx>#~Wpvm<==~5#J6WjS zt8azEok~8K+2xZ>ic(uez)a*NdFa3t_w0LB~MVg3SG5jUJ585m49ya_8St;*V0Xe zKyuM#ES_xdtX)k=w07&;1{v!T6`GubCboGXPN zcKmxAZTw&7)fD-jk=ysqmv0}B# z?o~mpJ3IuDK<7k-!ZnCv{?*~I3?J)H?N6l}k48dco!Aw=f{ET2D0%z;dO}f0f z`a>qv30D0B-72V4mAYi#m3~IFs4OlUc(8e14NLm_N5--{TT`i}FZM4!4tN7y3j@aV zb7@lfXe2icxPDt(2M0sfe6HBElsBIIRcLULhtq}f8C;hykJkvj6JJYdb=o~$HrvDs zr+0UEcXxKkzkWp|62J#0azsM6wzk^Z_;N_iWn>~dJ3Cd8O?`a@f)u1a9Tok+_{#{c z#Sq$@4MN2XP*T{?)PjhR{aKuAveG80kg&8$ke(a91`W=eTvcq{t!w)!0fl=16N!%p zAgN1Sep-6gDr2{`u|W}@3OeNF@l*#3gi}oFBGeL>vdjK@b&XMD# zQcoDXKEBgI;d;Ekxeqc<18hNf93BCp2JnLGC@ zOE2pyWFMWo-^L~c4vF>Q>QvmI0%$sUZ>GP$ABKb+AIYGvlXY(ozJHazvy>*0hKlN7 zGEd@ozVdvvHDS_JB8D&#yjyQQU*RpHsi6^u5~tBJ5i5?ed*Ik+(|%#qlK^Ym*C&^) z>wY+o=RlG969Q16H;*p6*4p}X!WvRcia}0EmgQEij+~xrMfw(>I`C)mfF1BxM3nfo zaB^Cf+LwS(AzZN~vH9Raig-0vN95y_^znvdM{WYj(aeDbVv7P#R>8e#D0pH=Z zkT2s?2rdFF;IEp2X3S(-$VD4rj(wg)|KC43G_P8M#9vBEb5*F0rqCgci_AI*xGP;A zk1MARI+P~UU0GfA$V#U8`fWCW0Y#WP;%7oIDw(+V<8HEe-eq?noX~mpe%5x=&W=fv zDI6lM3U&VH@oO|`tT^INq8OY&7g^RnpLvXj? z?m;e2kRZWbf;$8WehKdG?hrh6QM@L{W!U37@Oe`!c z(A_+lUcL8kMspd}A!AaruKx@T@!5qdEv`u$Z&BnHPc&)h`uh41cY;S7G1=C^0sXcF zo&P&9W|}=Mz9eGq0!xn}B?rDc z)YZ{3{vw+rmn`s0v*8e8#dvg+GcWnm5kq=MTFB{hGQEt$XE@O~2Y&u;4?)VGbWC0= zIM2Fs*EcseH%JE$gOkFW7bhcj8^^~hCc1n`fT1dv>-o*i$(5Y-!-51X!K0h!Bli)X zrFnLx?kJW7i9TFL>UPbQh_Z8rEFy!(CI3xJ6vC^n^6>EZ`C7#oelDo2j3otqv&V%6-b&WKPv=rz zUIGL5r-v6l4_B7an?etJIkLP79|C@uX@|*0Oj0U{h?&p+%L}CAl<%Kt>d8Nn^V(Dp zx@#DK_grkdiqoKU955V`KFE`UQ&@Vu`%-2*u?k@~{)_550suj26$F36cw3By?x%?G zTifT%!q-0CJPO930e<63lTAFzz`lvktM#7$nHK<5USBzGIjCWj6YIHOuebk8`&fGS zH-dR)h1z*MP%-PL1n|dtTD|IIAwHr7TOT=Q&G+Q7-USQ*ciD%pM0`#V4tPMh>CwX> zh5MET-{Vu|Dnr_}^;pq+67S|sgm=Ka$J`agB?d+X@!iWo7DcA*T0>>T;pISl9M_kZ z$!*P9CgL+V%7d0!oRZNrJZ|1zQJ_Wh)argxLY9|IU3~8FTJ_gb2{|SXjyR}nZ#qvr zs6Z!?qS<<7(8uN^qB~)WyCdo zbDzhNlJblPupqj8mJkm3qZY3Q&y_pskCcWE^p4l z^OaDr;Qk~Kzf75DmUlEQ`K9CZ;mmmF7DaYG$!nONKb+PbnkA!wlTqw|}$5PpKe2 z_uDw2tdf$Fm}^_(HlnvkkTCG?)RfxfKT=cR9V3L*tP#HN@}nW)RuTHE%^-Yi~;5V`_4!*9%ItxK>x9aii~fdxnAyoRV$oEOu0yWyW;GD}P9}ebw{_m8yKX8Fl~5lyEtz5$2}ao^{cq1^-pNl}qL7AM;191W-vYAi>bfrYewvD! zrN1}jv%HbDY1H6&9GXZb$3w4`k9}?&GkxNaHCI7y?z(5n9xn2Sz*uMZ4ez^uAp_Aw zo>zM+gTf9sM+@26PbN3~TDz5<~KOkVou2ia|DGaCN6TE6T82cGRW7|fjJ^QxyaGiQbYVjP)iy#oLkjuO6$q~=-x0cV!_ z$BDKKB@H+5@TUl`>xi2sP#6F?seOM=;`-t^lts}D21r5u6!jZg8i*oG27w-A9^eUz z{MIVdH?G5jVn&0>5vqfJqzTNuNG;sJmI!S=UBf8|96z)ho> z)_RMD(R=la^*bQeihto-L1|#OC;|X{73_gMTb&HjY@ghUcopj>rvLzYYpjapP*7sc z!@XQA2ip2?zins{SDDE?`c+6(MDN~pZYul4Dd(Ubp6Ll#4TR$-spHw3qn&A zG5}clI-ZXt;5#i4B#1Q=MhVhWn8B1ALpLDOO`T-rb{XxO>?|_qWC>|$3_qOg9UT0@ zJ6l`pODTKFqhHUI&f>8CZEq*0q`2>lq{K-l1tH;F2-umJOjQ_k4Dm%0@yeIbqlk46p+bDKeZk$FM$Cv3nV5rqIuGz>Pi}@Zf zLm6&fLB*U@R2L>yPISR zoB6yF3V$+F^4PSbN@b&rxbMJli5+t{_L9+ORr&Wza>?*}Ao3%=4bx>@Hf{7KRM3;U zt4>c(4*>4(@Bi;l_@WWa_M@}2^XTX(joa?mR*KJDIRxCz>$szCEc_-^Tjmw(Fn4SYzfZ@mT& zNKT$N2RnS1%lG~Ad;17dJGe44r%K0>em=-s%~$M30kpa|2;c<3a?=(T0QOy{6iE19 za^jS`Mgz3g)`&W(EtGY)&)M%^k)o34vKtPCAE^uX#!hk;SeCmEZtcnhJo>>^Cx)sG zu{dLpyQk3iJwgZ!aMv9z4g$R~^p*j3qP3T1(YuoolcTNf%Il<6ivnqG*rcQsX3mgO z>U$Om6*y683Y!1&2o_q}&Ia}gBi!I!_c|RL$cpV$KFV;ly}kYG!*DA&m)gt*>3!k$?(G!KF}I5xanD0C>6`+OBjVFu++K z0*zL5rc-VuX54VmWqMd0@Rv9fyIR%)<-5eK@2l~~2@VFI_<*7#_3Q^=<<<5sa%Dn7 z%w9&*(WGaK&L{|&zs}&4rae^c{xGcD{CQXMGL!~9v8+}*@+ZXj;~<^8Uj*m&&)=5# zVuceHl#QBoRx@r;oKK&PdL_Q&)-v1J*?<%j{H>pPg2*-VyxUo=Fwvc}!d>d>>}FAxA&Xcg9J$Q7mTL#Y-NpJy>{5 zY!~YmhwUC69uHoiKrYFBv3Xnb=%TCb8Y8L2`h{GdALx$JN#b_*9$jwU@Lo2lrz*tK z|EBW#H)!GnIyYHy?svMiHW>ajPx+ffYCM>Pgd}>?iBIoF(TgV7PCS`+}Fpx%@UehTRjDhaT#$yxX(sb}ucz?I*n5=cZLhl>?SO!9Jk<+f_F)T=YGqs`qf0*fzDSFF=%;Jz z1Ym`)dWvoGXzJeF6E57mP&p>~ZM0YWfS5A5W)V;xFG7(@&W8c}53pm#ltRco0E2*Y zmZeUXaQiGkVw_IQOOo^7T$5m+l+dZ+SEoyvsw-|JnEO2aW4BbG7NsA&-o>0iS zD*;=4d4EZAjjp2{mx$H`dc>3XQBN}J^e9WUSsn_mbleW237%MGu`XLLPDqwjTFjFJ zk!5n(l)j{i1lirP%(=c^^o2yvXF35uT}#QkcYsAl*grgswTHcvd5gU#Ch=E6?!u9h zsf3w~{ML(u;Q2_D@w5v(Uuu)5!%WIH$;=Tq&XIHnTds|k42pKo{XX#ujXhH9!<&?* zdL@MP3Ay?8lF)i3j5M5KvhoZ&{wn;|ByS}rRF1*i2#x~gI;$Bm5JI^EuKhoEVlv94 z;j;4G^73*H1%r04`zYV2h=?>{U!ehe?}w|mz=z?MbhX7bhBOp$B9lWD7We|~lS5FG zo!?kCUe{Sl{NOj-=J5%pQ0J;N2Mz!udQur)A-^7IM#xk5eC<&;hEh@4Q>%6U7S((r zN=_(y#^-DaHx!2se!^i7G z^G_*9M@RM63#$9@Z_+Ui1v%d>|E^HL?9>e2fp|9==Jskb3*OIak>$?^z^@jS0^Kh@ za|($jpD*L%K(iq|cj}!R)CdUlIbPB|pZg8LpMK{)ILGb%?C3VT_Bi$@0qvzH_w)ot zqycZP2ZLqPw}U@?QZ|??U|SmyHHqmrzGf7lOD7H0TrDdd{w?;m#`K)#Q%a;!a${rT z&S=`^0wX!$01QxiuJT*I&BOI%*&jwp(jgh|9f7 z`3VDnNd4kxjEDTIPyEI{dU8c(#;ysRR;0CN4;LEJ2%Yw?Ix}DgVez7#YDwL{o|x^>!Q-t2i;rAv?rhYvl*YwoVLrAAvY;%@l0*x%!Wl}L{@&j8BF2jx z8Zm)!-OVDo&HgCuU!y}q9^2Oy9WM`CgYlFyW2u}auBWRSMqm?TW3X5hK4;v^?yn9b~UOV0`-39Z5FpY3QgH-e%|P}2F7$kJhd=) zhXYI*l@n3X*%t}gQ!)Z(!beNhihd!k#mHV78SM}7ufJg1m%pDZAGGVcp(OnY&aOrO ziB3kd{c`hS?98B+W@(5Fz@Q2K%@zG4qoJqAIJ$jwe0=TU?d2r^9op!wE=}Z%0%?`$)O{Vrhwj27<5s$zZ_s}VO-V^X?tz1cm-DqG$_W7LB-JqVPm*TvGxNMy zcti)+xjL$X0pJs<>GO}UD4m&l3ImUVE<-=Cj)^t#2Q{(k)0NFHvmOyD?N?jJ)28$O ze~pmN3N;Iznv$GR$)^86YF9=p=UG8nWy`ZNmS(n0E-o%0vNnB|(QQ3FJqJg}`1ts9 zb!?oh-n27=L$N|5W3DvbXbKs0pwhT6ye|TW9eJuyB`1U5RTFIhJ$kcNhe@pPO)&D^ z85#hNi|v&|P~)=Tca7P7CAB`R^;L7BYSTw0>lHFd9ts!DVH5KF02B(Fg6cm=5{6Xu znuj5eJC(0$m)bsK-6o|ca65goaQ>iCG6NzTM921Ya|3`+FP!m&JI{GYVt-awSMkkB zMZut~t1G9#HzX(yi~dNpwX*Wt{YddxyS1@#b}aMkz<|_434u0+h=}4Qk0_{aJQF|#DkVeM06*Eh$;0cpa>$!mY#b^W0Y?1zQOJHHP^YY%j{+ABO;jZT z@*WE^TjK#bD?*Ya=ZO{vX+wzUk@EvTpRULanL?uoOw5jQrbN`Dk^iDZ*%Rs)q`F;_Mx`r<$>c zRj2G%{yvr5FG4=2Ld5=4Nhv8<;2kV1!`6Z1Y$%|r?1n=~@gBKnT?9woOd=`Xgr4y; z=>3KWPUM%#ZP^1Xd$ax@1Mpi3t@$Pj-#7}}+62Y^n0}IRYzjspa3G}7*7Pe5SZCc? zUpIuTthTsTG&HzsYGR9pQVvcPD2=DE7gz~R<>uyAGA?CHM1-ToM#6|mix7JH{R9Pq z$5?}l5(MUJ;Kihu78f=C(((0Ag1d~4>{m^Q&&!I#H2E)752yeUPvH{ArB6dwQ<}AK zm?VYwwd2CrQ4nf};zdzWQ3GR5CxfzSQ}f9J8|lpwsVFE+<|~cLbQ{`zUxfft9v-*V zR(DDnO*8K9tu50xE*=U#M`5y*%q$2{o|F|3Wqb^t|f)@9D%_LIC(LoDD?{TAp|Ty5di`{omg!CqY`~ z=H_Qgxq%#wjg88f*LxEb0%@-kQ?5AI2OL)7rFcLmR_}5vmcgII4c<;;@y||tE2*5{ ziZx1R>%Ps&B{7o)T3cJUzrH+fZEc|n-2ng?4DPf~H^pmaip8K&RK~=@#8fvL{|S%< z_FS={8*$*HiOrkis@*r%8Ntd-=_{lve@QXvjbqlDs+fd3E_A>w5&t*%?~|D3Qc-;( zenK`aC@Vq8WOa4*KXBvb!V|Z={z%W=UV`yQ;CG9V@87?9uJkha0WGelK35Y`V`F3N z=3^s+gD}8!ImC0W9D*P9b+%M{oWjw|+dD7)2e!1jI_7Y-pr_^+BU%cR&)_0UPW@Bd)$Z=@P$(2#ul(z1s#b-*!kcg4K2yf#)DoWjRj-Nu`DgH=)PdpQ~`B#t5u@sWh6$$DPQP zE2YL3`?926D;_u9t&U-Spiz>9wUm(U1|1(6Nsw#?t%^1^HMw!UMio!wT9$QV8@yZ} z4*Pag+dk-SJo@{3dR6Y~=E?=}M+$meSsX9c!J`s0($a!+LBMaFIxDpTMHB>ts=7Mw z0duoYDGS!oF)q&MM#qPfwIO{oKU-D*}k&tLxfb9 zvrD!4C6jN4pW~VLCH5J|xg6{$W$iAm+^J{b$gFow`n1nXKj95mYinyy>XpmHQzQ3a zVq&f@JfU9jWgd5|>_5~cr*C9?mh9RjD(Ueyy`l0`M@Ck!3j_&T81)p^^wOCJjG7 zKQmmY#IeH$vPT+Gib*2}l&Bihm_OuHQ1MUbYo z%qv@-4JS$8cF38a4J4NqQC0?vN&h*FfdPP?6^Veay|+tOOI!8TnNOJ5O?~G87!2#gI z>20TOOFX*En%f$yH2Or@GR?=UeKkww-K{M+vMqNZ3W}bkC4zBFGWl2g9OI7wK+8#{ z*1pSuBkM2iOQbUM$ z1wR1FvDNWQVeD$`b}&Gy2Und{TCqC4Kk3EA1!YTiWuMRU!*#f~UQM!$&3mH3ra=d5S?t z`xh0!I>B>W_;glv=2IMCgaT9|D zhKTbk<_?F&n{#t>N0Qk#=c`P_%2`21hKB2{?w21>@F_heT+PkR1K-+I7B9||2zez_ z4r-R^XjpT9iQYy#-CYmSqL2)~@2`HV*rzl$I?)CGU0qvivV~ZqL?%yCQL}siln0uk zX(3I&Tu?|wFls}hLNu19S67M2DD#|(v?^A&hm+#t;?4qngsO-R>Yslz1AQk+4G^ts ze2(00&!<8pqX+UEYJUDV|JloCj4)is$2uKB+vUa-cJqf{X-E|%B@AMPg@uK(QO$#< z9%t(?1NIm+ily_=@1d{&4_*41YOl0kYzTPHxl28cze)3P>&mj%-lpRLQ5Tk?+DV2< ze%q})%TrvX*@66DV0wb*g1dH$0udo00H_La)>}*%_XMNF<(bq|TQ9zNonRV5R~IiY zPo>CnR4=YXjt{gt6xJp%Lh8=lhE+no(~~2PLj@mCT28s_RvF<8=NA{54cY}LDFd?$ z9iCUAP$=O577mV9(S(rq1IK_poaoiwM9#Yw6$?f<036#nXvH?!SEhxtkC`mn zxl*Q!HjaTg^LK+9i#TpZ`*TW%|R3@@)nJGc=2kot8YHmDTBy%fM+xZBV?4qr8mjuy5!e)9u2~16N>A!64GK@V6r`5|&i=XgN1YhLZ8R`o188 z;G=%4qqDihQ+v;OzN>Z}CeCM2nND4?`{j4TYs2ZcgyZEdlZ;!8Ie<0xkwIQ4yTEk!_NfeG_1A56AcKZwhJ!QHrD$78SL zWZjTU3Q;17qqL;JFlV{Hi{IoBZCPs8^6%8_(vk}O9vgWuQ-T3!e|rKEC@_GoI}p65 z9bxo3MuRepFan7DeQAoCwK_I*J4TX{k~LpPUmgxw0+kzVSJ2VXn_W-!Rn~O>V38TO z!wl0fG9m-4-`6`4Pi3N+;on&>)bt&qQlvP!w;!@+Yp6y-LJ|lbu2$8rRmqVAWi>YP2oxBIX}3t3@Lk^~`sTOh zQl`{az6MjPp|s3;OmR^Ko_XiV>FMd^NJbf(n9zl%a@(zjVbBl~5iy*3A{oGtsY^`D zDJm*TN`4rw#-NrjJR95EzW_;xeks8TpbK-NJ8ccZm2c{18|kBx0|Ku+$De%82eq~<&5@DF0tE)M zJO8;ZOU9e=h?~db+Ht!15>NBS*-6XHWJwxs zuv>eXkRs9U)uI7KZz3Wh1|n!TE!0|K03v0Y@Y;T!PVHnQFk7Wg{fDR&c}`u1rKz4B z&tIpl5aN!St>0v5dbx6vDj$H(r7_(EA5$FjG+xK=b?ZY$nsJo8(Vh=iMW(j5HcRzb zasN`~^TS7xzgZUIk1sYvr95r-J1+V1-M&6lUvFu2jMx-2w^Yl^$|8RJIBUTnoA-&4 zu~fIg_7^*XJ9K<(tQ>LDY_mTK+?^#Jq9bOGDE~UJs@*T;>}2#bl9<@I6if>v1_J+X z)csM9>53?USnGy_$T-w;e$D*P zJG$EDn3=J_Kc2z6yJZ-e!I<%9k0Jp-Hx!(uM{)7AfX5E*hsoeuxPL$w1(EbN=UPsF zW_(z9OcY7#Glr6(!rH19$@Il0nrTPcTU%QfY2%nA3k}%+`}Yq8pMzBJamKEvY-J?C zwO^>o`%>RJKf2oK2BlnUYKgj|-5|C|L{U-ka%VKEeS5ttAb(RA@H4^{1*@v5m1tE! z$93PES(}ztlaf8xMk#TU5G>ZVuOH4;5KQ?irE&~nF2A%Es665jQHe(G%o z4{^FS*v@Qkk*3-<7{aIooMn~DMRSD=c!g2IMT~}V?r4{r>J}OQp^qPg6Ag`tdE>tn zWlS$D@KR809xc@LHn)})EIoKn&sKC&g|hbF+Y;iyW$8B94h{~g7CD`+wwdX6JuBp@ z(hb<-;o;qPXm}sD+=!QB?Wqyicr~7yV3aHfnvW3%#>T`b)mhERX9-#b=wM2?GPr&^ z0_7PcIy%Dq2H~M0z+u2dZ0r}Qq4mGmEb+m?fki^w7=W6KrbMby_)F$IcrpKxJrS*@AYgGm# z$;M=B&CE6CnDA73Y?i3PqnDPRnDq$VY~K3rLff~l3D*5nG4XZSF1s065= zELz$S1s+E-o;7(ROna7zR%z8tyNApi2iK>*fkmoC57&nUbBAqhZF3a{cBxv-@q@JCpKPh=;12lHZYe(?6U@zC*X`mb zc;}$?z}CDjV`Xub4eQlgj!k`Hi3-y!^`Z@DuDo4cV1C`WNzCx5tf2|JF z{sN1h^i_KX+id1bvxoH|;2Aa%P1@vo7}im7Vw`rf`{NI}45#H}ZhAUlk-Ep#o(d8Y z(p0OHNj7g?bF8NL^tROxVAqB(0GW9h$t|72uj09KQJWVIA2{AqG*G|91F zW2R4NvM?qH5Y_1*W#WnLttVbvLTriGn`4N7Kp1HtswLzTF)OATxg0YPo3F?o8oaYQ z$`DzqsHpfJg`Jj{kcde8*Lyz#ZrfPsGoiSZDg9joLjChNIbt<})js^f`GQ`S@Wsw( zS{j#)7)T+VhmDo>uPFyHnD*dirK9uNXN#8PQN<~iXkl=I-sgsnTSC7I z=b_oq)G)w|j~-sN5(5W~GexY`%}q@R{>po8e0`Ex%9J!TZ$?9j2<%)(SU}lKoM z$#jXyGoXc}Tp-ZuWjePY_2Ja$u*D;Fq-G^BFfg7*$vCn=F~f?lS}IqHl|$`kTr^mo zu=+rZwt({Wa(sn|A1tO&pipytLGBM0Ds`68C{PWpj{oK793~wB0KdN4|6%}cf>yZgQ@?Ovr3C9sHSKhg;&161578ka*xh&>W%1qq^LB!ws zwdP30SfsAj+oXjhy(A2p0?KzQ0ku;D5i#Ws$vodS!=g|XTivkSYf~$~pWg*@<;VA1 zTx<tq@u8)FPsBad+g1^OF~uu7I9WqJLOIPdg>As^6gYTKv<8=)Z;-BnE~v$*Y{qbv~ROh#`rIj;0oTzoJXMw(R$Vjab;Hl{TEj`|9U@#W%d3 z*$DKzK+|@J58vH=WNqORn$pyTTS|@ZXsng3gBl{N&%@RJ%kv|eSdIBOR|en>gpNk# z(GD&6!!?6tXPTuc(aGOu5uT4P)@jF(s4*_t9BQUg@mnJVr7U0_R}$KM{GdnfL%~QF znT5-;gjlD!x4lgjo~>BGuzl%rH2-t=zOYWE-S3PZv3^{%kHAIb5n zx9*;JnbLseqia;z%a{NLuE|Xl$<*dRjIifTWd8p4a8lY!5CP4V#8F^27uCUPj*}o& zO?{Q|brEWXfxw$<>(X~+bW365fLbAy66BwlI5TJ9Yol5%tR@8O7oKpCVYq?I9$962 zAw?@}@#&KojY7Bo`dWLNQiRH=zc*qLY45yyfF+|zLPDZ~ zDYqtk_xL!)!363q(`~@#un>7@n8;k3esSna`5{d6Sc`mpR4=xDmsUe9pG*q!FDpCNGVnIDsy4S` zf3H%wp&W!PB)0#5|9>mE-sO0z#+)wLlHa$zE(9JeP+4|XqQ?@Bu~EATtK;vWD^X~+giCTF3#CVx*Tcf zJpGc{uegAp1zP~EwKaqvaqz&#yrf9;&Tz#G8-E7HYrKo zS-lTIB?%4=CJ)>h&$RPTGfnWIV!5b;e2edrqUAh%$1>>v22m?MJU?b(P=^xk&a~c3 zCCaanDuRPj={i%XHuT{-5opXWL^)A@A z`7&C0FNmYn{ct@$Zp(dB*FLAB?tZS*E>I6j|~1#dNTHZ68D!JpPcE!DM-w6Ce|#5X4^o}2wB zsrgCF5G(%$!_2S3?*aV1IQls`(ya(KXw(-R|9wa6tv}0waFX=L-s^sO5lCo(%Ehxm zIPPc>`dobqNG=TbzXE?HNH=yA8JU=fPhD*e#K_&Z{`m2uzqEa>!hq(P0PwT75x)I9 zOV*C+^5j7(JG*{(t;J$PI5l0TtnWS;M};X-XT31F*t{$+6E&!cl)>PCeav3uy_jw1 z!%LjfXB6L@Ju)(4)Dvt^h=Yzk*)$u%AU?xWn%Bn4k@OuwbCN1GyUa6$0aAeC-F0V~jHZ&B_(hCW-*LJ9c zU!0%+l&18&IU;+0$Stnljj*4Q!0hWL z%6~DR>BrR}YTqg0>Jow?vYgHpo^Lm`erm}^qmV3Arw{vFZ8Gq2YS|JDMITeO4tf%$ zNUnB<0gNG_eEG#TPpJ?T43rOZI(0fvr@o)TV)nE{(GddP#DKE$yY~khj+-#Q?+C`_ z!RF?>QZd9-l#~fCMFgBywRUUma!Jf7mIa#7=j<08^EI}f_Lf$;^2j2lo1 z$0xt&zGox^Gn;-36~D`r%@&tpHpsB~b}KMYSf^p9Rwt#*<}?7FE|oeJEW6Z9xkW`P zf(&^_FdBauCjovwerAAH+uGU!vA=$4J`}w5wYWK6GBGwDsZ(2em@AGiqwC~nda^Yrm;lf1^?9-xB6u*RKtyxkV5;TiX*q7+9WYBt%4fVV~APE8--K z5EytKxL94JERM1W+VE`)7KX0Y2Xot#onK6x+S=%H!!HGj3vO{V{DIY#%;!z#nAwz0 z2)U%6zT%ebsF!Wf9d2)%$w%uw6xgmba{{=?!SnN9NJvO(4yUoNza9(e_-DF4KR5?; zu^M*zT~Gzo)p7PWUPT~zgZiTg3e@SNmPi#AM5s&R+<&6FpinnpixnBM;dZ$ZR;X2>zg@DeT2#9?8#FE#>Yh+KeVNUs zN@DV3iZ1^2C1cijXg+pwCBuH5_jU}ke52IEk5E3EN+|K;X*$uiZ&-roNEcUl7+$d+l*!+@@o z%c~H_bD6I-=ABKEW_^?At!;w}pBg|x4e?Gi~nCd7bM<20#Bw6Ybh7R1`d zCJYlU{(`BXKRQat3s*(G$A0r53SWYQEFsTX1y3EMe69si)hNPceV-6j`>xzct4LJ> zvrla96AKxi)86;}$vl47lUQc`+OS48W)fg5gI{XODMvDDXeDTAanU#uiRh60YdTbr zfn%jwv*8ERme!oLk~P~!gjKLq(hYGN#c{Rq?J`#$&zGsGDcuI!vZ;M*Yiq>}J~RIy zJ^k&klL~OsL$Z0136cC_MO~MzwBar;E}s$o_wRn0P)MyVwBiB9F2{>sR|T>Wvf${3 z%IyOTMf@y^8+pl3@>X)tn9R4aRJFCVwBFA9zd@X`{=|YFAph9JL=EaLF6!P6jPsu+ zk8=rrCM`cP`jPKTe{uS$C1II!x0;jNGR9zFVVSYw3OydxT-<)~H~I}SdT37m>w7hu zS+>w*yt6e(alq`#)@)Ab(AZ_m$vz7dIgLQvD3;aOHc>;2apDANA%=6JZs znU15C5Axn;^j#U4l%d1W{JKYXkPz5hJXxxs53=DwH_%b^`ukh-_H->tn(}bA?3*&N zKffK-N;ci%+-lOY7AOy4{1Vs1)6sb%CQ*%<)`m*{dJh%caKdbj>c$W#G1rd8hUbaa=*+-gnjg=%}*zCLb?na?Kgw9UC+oBdS|Ta z?0-Dooo}iZP0uyx2}yDPDrC3{W=nCU5Ds1Ty!wd^Yj&(P`Xhn|qv!*`eEq`yF{yv( zwLgmB&Fm%$)~UDVt$4DIQyi1y0tHLzNBN1+O2CPB;_~zIqS1lOLb=!-O=`X>jc4T0 z7LSFZWz1F3U3pF(TJS;3M zWMo}l{BA#~H+0Holl4a|o(|?J417jwT3S5GMxmY|6-&CGN4`yYP5+>**GbZ>-(PA! z;&$2D>hj(d4z^-?G9#%UWzZ@o6!fU=GCaGzU2Cu-fhgMgq<3!HyOW2G(sNS0eO6;V zZK}ba2xig`0q`XO0cy4@*|_-=xiUmaEHvj#a8uRH>78UE$QsMeolefpenG$hqOSYm z#Kh0+!fJ<)CnqP8r?sx9`j^M+eQBX@Y0BarE%1z7h&_UbUL+sT;$+l zjS~HKuO>n)P)CLX0qft;o5~yDU6xZBQVKQtP;4>=4Ht*SZ&{hFyvdKlNewUiG}#DU zTcr_f@&^5wxBDfk6{uZL#N0IWN+Zg5e{EeT+_PCk6G3{B%G&{N%VZ zqL9Y5O|Y=ByNiR3U2i@P?e^k2B%IG34Phi;2;cbglcK?Tfjrzeo?1aMoyQ1ynodg3 z-6iP5%8c*-YXM;L#Wd%rl0R8mT7t+@;jqB6L;eP}`udV1 zb$u>FVz~fF&BHZfB#N}czkK$i|BeS|U|=8$uCA#WE{4hAckRbLbZTyKJ)JGJ{1p~+ zF^2k0sBdHLk|Fg=yAax3utL$Am+uPEzeC+tlZZye0&$Q`o@&0pmh}0}jf=DMC^v@d z_wSXOCC=Z!yFv1h4C)B&RW$sjzSMp3G=dDHuk`1s7QMB_#K%Vjj+YvQzpwjM;ac2p zh(5r=AVo27QvbIa85vPvV`*X zVfB`gO;qqyKx7D1MV$;QoL1B8?)pXQzcgTvj*gaBR;H$=<|+(2jQbET_h-EnN7|AJ ziGgV}d&|LUPa|%s3c}uv$HcLp?gYB&P20?a!8BqN^@Phkg%dg-bM1MauaM*5m+|9 zw6rvdvlkSo3Pfz=W%{-YxH4DFv8!6vSWcxXWJc45(~7fN9+HQ?`=B?1Y;rqw${t!3 zr@56&%V{+Yh7&EB`DH}F=X%m=)Dui06`h>uEE-&B03XS7?SS{Mzz4E=!=)WDUfkhn z5T{>Zj@yqbuF9OuVLAEM2&cxpR5efb4c=F6HthRqxbS_o$}w+kJ&{36G3Ap)!IVti zBp&-$`Ang<^qYppWgg;7KeAq?z-4t%o{XgA2eCo{W_9!-il*~(Pme3VE;pXz^w(}mo`%TD#4wqv9LiQVHYIIOeR}O! zalvAV3|h=ATE{0RC;R(&BqXop+<}3Cw287fI7y%EtP~X$UtgZbp@PHq={Y%@T>BO;+G4#0L|e_YvplhX1Oj6 zlduda!j3Hj*&hb{xA4m&pQ<_?rn1YY7DUGKbED)g!_e^XV%-MYl-jJXqp1!}dL=Wq zYwg}6$!t4QRgg4f+yyuhg7T;hGx3g>e90_~4FrFYDW}2yJ##a&prD|YR(EzTE-o4x zsUmeN4*V#|9{Y58>YDohMqQl-Ev80^rp;t-SY{@PMsm>I%kyJLK`_ODz1;$n=7C<5 zL!RgD2_7CEa!;+zlFL9eQFL_lc5_2UB=4XqW7q^u!k`)up1tM3`_upIA8VodfMlfG z_jNx*)=CHW-Rr||SNr0oWC=8fVro>Cc!FwaVc_EV5@x{A%q&lx{&clXS9A6~kjiEA z2H#=Qtxt}3cK^|OS!6eKAwH&x3v zG@M*N|0U($HbXY;g~0fw0PsaehaNNh;rj6QWTnOVaP~AaM?Rg${^jZ3ZiRj4V~ridn7 ztCExP^Rs=qKLa+mwx(L0Pf*Dv*{x;|$ECXx5)xu!CKIT?umAk9*6Pg0#x_dlG-$v~ zuUWS{NbEa%a>p+3>FN2&)1}wpftj0Aig>K*Ob0k2pDIWq=E+saw#ZT`&=7Nph&-Mg z_pVdS%C7IRZi% zBdlBwQ|BmRP{Q;)-5jhm*?s5r24hikxMi}>e_mZ({baV#0@3mE;sF}Td)yNi)W-|e z8^!V&^Of3PAR#eE1d5A`^;#VE#?sh)-|p0%oY*ICEG;cRNw;f_LyC$_C$j~pyt-!=c_W~0)uO#6pl3F0$yQ0Po7)_JfM+aVJQl`{vv)g(i3DYCOUnw zQ9?u4Y_~BrHPzRIGScL1NHfqZ(#2hhK!+MprB;QhtuG`bB!V(MJw4KhD;A8f<^Fzq zH1njUP2Dcjsrijbul;fA8}VGV{>NAv8;)_9_;juD;LXA0!T$dFMpu{P!35yrk_j4lqUQ;jv5CPL zn;JqxyINm^JQp*wB1+)t>1mzKfFBsdC)M^R-(BGhHe|t|XN+Bo$DLIa9>*ua z84(c@aDINC!D*vRmlT3TXfE`}G*4y=e5ML6XUn1-^h`{4=c_Ff6BBRGcWjKpPft&T z-1eLM;~5`Ii)t**2@c;(6~X@g)q)r{|y$%l( zlilmRQR!yc-#&dTk}w_4zUneEBdILL(F8m_H~jK5Kg!i~o9zt;qX|d<1P}^%unP*l zhYT>v(R@z*b*V^()q$(;}ZP&Cwj^M13gzq%}`=>a40Y6kewF?Uii-^ab%4!;}SDi9!5`o1K9v%H@grkP} zxw*R-q4#E=HxC1Y&GNWsw6I-Wu;;wIyzcJqAAeNctqD~1^zCa8Ul1~fFrO;?X$=0t#Aa4L z1~t&r(_5r>x?bolarO=j6suKgA@tJgwkF=bc(GJzwX*|*F~rq+9nWVgO{k(dzVGfj zI;)Gd#`0|PYEn`|9i9(rRXR`CNsb2--uFx9)t%ok`t^O^=GNBUc4CC0LqpvbzL}bv zcUkGy)zvlHt}VAXnp0DklXh5P%QGk|x4>bm(D7U}IyGLFLt~ZghD5h{A*AvLo~JQ^*<+^uW+K)}(V=v>siyra+BS~;o;%wDZkt0CY$-h?*2X=;ppL10XaE&LPA0cgZ6zk zq9rC8VKpC`yLjLB*G~#FyhV4O+-|b_w}xH7O%6Y zsA!d5hgPWpbwD?>%jsgu9><=8yS@FTd5-sdlbyc4zP{r*Dc||orbKprDJdu<_DYmS z?8Kkt{_>JU83j&CS!1#4^Q~4)mVRHVQnK*=)~Kf^jwQ;IPjf<~tfe)kkF!P%7#U_XiX|&MYBrwEf>3YJ4L*GbzpbaNqQa!p3;>^m<7X>Pqj7d%eqa#L zHS`&onfzvBIKa^8Xq(fKGHN{gkV)P1-N|H*kPs)QT9LADn~TkIgQeNIHehfC>Svc| zy0SE8pu|LmF%4!BA0HS9mJ*>El0SQ{GtEfnP@$w&p=J_3 ze|VFMEoA4X2`H*`+c+n01~BAI6-JX8Y<~V^9*|9@C++yi640SyqpB~av3k1Rt2Y~` zE5UZS-j&`F^78f$@b?doRsTCO@@FhzCygYciV++E$sxpSeLNH|u#Sv{1(j4hVTqbl zsE$}jPrY32cB%m9Z2aJ8krc8E$sX?=YiO1e}=Nwst8bsu`b?Pcu@XDg3XEDSHO4#bEd@mBJR@%xgP zD2o@==yFy;{hcP*lGFLvFM+zqB!skkwIZTEs6JGJp@iXDlMR#xLyljji9lrh8(s+` z$~|o)^J-_1JW!QxZmHgU7!DwV0 zOt`*sp+-R09)d(1?pknaiu$JIR2%E-M<*saoln&2&8TYGd`1#!-(DWNyq+9nWWqD> z(|iQXm+DNvMH7g?L=p12oG#X4-m$*DzD{KEEtD!1tgfz}ueEKoxn7tyMMg(=x|}U< z_IzCjQ57(1VzZGzivyyipMWcg}&~(14x&4cC1FpYYf9ysm8Y;RUkKI2vmsD)2 zQYvFvXuVM7&_ZC`?sjFw3LW`+GbuDvEWg8D^`l(vW`DeV5gVU?pxyOCFWJ=C*!Wuv z(cASM-H$&Ac-cBUo5leI(kGO@e5q?+uP@AyydBwGOWrPmBB;U$VES5d63DUZ>54QBm5X#E<%vRCdvgBa0$ib|qNKrWqwOGc$QzPD4?i zuLg<7y$~{meBUp(dNCx%GkNL_dxQ5Kw-9;>cpStTQ>;PDsN|Bd`n_ICxT>%tkP5rd z3q*3WB#AscJUlo%{w6%ssSufxH{WjdaamX*RhJE)uFYnox^=*78LJgMXrRGllrdTE zV*Q{H7X53P(Uau=G>ppnyg!)(Qqs~a2i!k*(jf+ay}!SI7A#tHJ5y2?!ZE*Eqzii9 zpB~MW3?py9@Z23@3~2aMklK=pBZ@A0S|-V0NT{o;lR=3v<21S+#y)R?F~l|Kw>R6m zS4l~dc%hv1DANa(7PgaVVGERSl{0&*d_6OwprI+1NutBqIhrZSI0H25Or({S(MIdE zn{10{Mi4L`uSc06z`@iGaiZVS2xH_i#S%TVg+y@RfH?mBJvN<&lL)p9mPc! z*E(M6trskUEd?FTI+O}RsUVGX-y;%}l`)cv6~1oofYGNWjTEab?@?^OPoV@|Vrp_SM#^wP=XK-b{9-8putFkOw0-v?gZZtI(q!DNrKqTL zBC68x1XHOv{jv#H3Ku`7JXu6A_;i_}dqTE*+i?1&_sy zP_S_FS>?E{e^eu5Ba@&f3zW)*?-oaa1T#L}+7c;b);3beY-aWC9J=v2Tk&l*LtGk_ zA(`LH(vYq|5tUeHh6em;H0qM~$(@9S0U$M3;BcWj$DOgAUaKMWz&+WNT0ULe2WEA3 z_4)P)0&qN-*mGB|J7UQ6a0)NdpoXUoHVVZHWc^k!We|xf%9<8gYM5;zjg3BaRMU%XrbZG>r>J=aJf(`vrhCmNbnQ6%}>Mj){rk0tHX83)rpm2mU*n zDJdu@7~ehlX9XHfX6VI1CKk+`&F8$H`7We{QKVe<{BZ(_sUkj5k#6qpAnOGrV1F!4Y}PH|#qvRd zp7Zjj@TW7eu&@k3GK<6A>|XxMTl${Es%#k};CcG?7DfVTqQgSD&Krs?2#cRVB(f+E53e!t?UkQMshg4BOWg;9cZbQzUu z{4}(*@YL_+8HDQML;|3fmX=`snMV+=yGsfS#U&(Q{h5;};=HmpHx2%qR;x1|4aKYO zfz2GqMXgh$x`>6r7hbv^9~G$a+8Ln=&Y!Emey6c#DA%C7CZ0hUEQn zow{Hzp)dT`Z!dDSqQS-9K30k%g-M^YyO9N<-eFHB*sw~kvUji~|g4mbco6A~YJ}HPVvi_4M=*dOw3=@lyMGhv&=73%oz` z&qZb>jIWp2weB}&;rSl-r_$F_ox`at#sCQu)5ZRHhImwpPITAUbVbK%wv-4n>h$z9 zis;0|gg9J1*=f@T>-k2BM&k*w?@&a-e2!;pYm%svqr>7C+P(gMdh24v*$i)Wb*zxj z=zyP$CJRRs`Kyt!jiy6+6Ge0%t4zOAizBjj*z8Ia#%8hRck$8V6bmzS4Cx?a5*qS6j!lZq`H#*XEVbRkJ9%+b+NJ`EiP99hs)uACIN zfMtAbxa{0S)_-0G7ZMn!h;hffV~85vZxHRNbUar+c;h81>Ob6Aqf{XIDP{t>wPM%B z(d`6I*|XIf0w&Cu^7%B6{AikPaWn_GJ@4t`wkfA@r(j}p1ZcGtm@yq39K@AwZz)`s zBe~h#n5$=49G(tN7SK6h`dTsYzJ_5&9S%hfk!2;Z_IB`ob^^H>`S?~6@ms9s=#ouu zuCM8=f>*s??xl;Sd7Y1AyFVDAkqCxvyo`+U6~1Ae)> z3u|1DTVt{fSv{Vw8vk=|IhZw7v^!v%@v zT~;l5Y<>?Rvdq4S-9qPVQm0w2?C|jF{^tVn!hj1>x6fcY$cbF&;$DxncX?XKI)40$ z5k3;-F)8>e{&2jHR}sy_YA4l(q8}uhSNb|tqF>FO@~BmD`+`i3A~V#=J(@)u9zGiO zwWn5DG91`DbQqJd4ihI!7)B9ovR!*d$zh_|F>(wdBTQ?rED%*P?K8y${;u+<*brv^ zJSEfuS?$f(PKkN9{CJIG?#s+1*kO$LOscv+CWxWJ;b355{~r!#g)@c2?oTu8SpDtO zv!DaOjOEmH#{wgSUUSvUEW!$38f}OTX5g@!OzlJL)UxLT5i+l5R&$D@j(72VZO6Gf z_Fr#~C$7HSyhI9)IHh;m4kqszi`9v$Bb>C|b`k-Bv*ZPQUbUO{GIN3|?_4h#`>(%$ ziKz*^Ei|oaua}>d>NCyAe;Z5Za@|jHW~V+t{>kR_jo`rx?s~l!Ht?ed<4MZZ`oYuk z0qq7Y!oDIinLIGjqo`&0?DRABE!dT+i`JLT|81dsZ`J-!2t+l&6q36|gSMY{79dHI>1b~s+Vn-1&-fJWIJ!Go2*Utk z3r0~z#Qjz)*TV216Alx2cyNpZW0R6Fl?r+a6y!TvTo?d$9KQMW3kdO5OY(WfHZ%M4 zCi4$}Doz++bM!YuYOps_=G#qJryk-_#6#_wI`MO50XY=FaNIV)ap<_YnfDFd|Mk2& z)tP_gerDr)<@v5C#NU)RyqKR?cf}=QkInYbQC2eB@7AaqQdX#Q065Hm^{&O!|CIx zS0V}|$WKQjS@y!ftGn`_3Pr?6T0TyDqj*hHexl&MCFGw{S4;T8B)1C-GVj1VZb357}qTx2* zLeOFCly85ej6^57kC|K6h1*vo^}+q-scMD%@+BlFNJ2s)&4Il3H@aWh)7o(%)5)Pz z>sD_Fe!atwK%T?57YvD~r#OD4r++nuVj?Kl*VmEXUB-2y+Gt&I!)xOfW1~fwQOU^2 zEYhiD8TW;4yG&W%P?D|F=Oh~%2@0f zR=B=)@x!5o@Pk5lo*h#4!|NuB_uZhY#88GMK?M+oQKf-n6@3ogy8%t~9S8Rs?~5(S zo(v4{xuRlgdA&_XLLF zq>OG{vE$S}#HP9>IH+Y61!m11)iS(RXDX|NadUmm9c{d%9w61+%n-mQ*B1Q86_?XA zRkYaK<>uc$xpikt^<6uElb+xd)pe^1*Tf2|^KoZ;@dgu~GF$E+)gkViH|hWv3JpkS zT$YaLdcpm%#>$&6Ztt^$1Yd;vl=c!n)#F-=gpVhl9Uo5}o70gCD;~LbpVt7-ht9|C zh|*FTF0Q5nJ5T1W4_B~`68cp&L~&#ocM#iNB|}Wl%La zK3#kvHLJ32^ zt=u0o+`C40!t&m|5IT)C#~bUYv5vjC!S%nN=fMOv!6}~OTfemQ7WJ)6-g@ikvrokm z#Ql6t=_~rfMj$`pQn6B(^ag(t@Pp-mNzina0T=SHBLp3W(o*--#DzT{ik^SMLuanc z{t35|LJi2}EFG7(<>KN>FNP9n_I$8iYptfx^7f6@5j?JAbk=Tq97MW@6^vT()lo+} z?ke$WA{SZr>P};L>(B)J^7MUp>%A|=>x&62y4qp}`Etw@)!yZo`SvQHLLJK&8jbNY zM&3QG7pf|i%RKImov*h0v4!~JUB0?7zV?NITPW#rds@xTm2l25R=pLo!UK0}+X}wz z&)dU;&&8y55Bln$gEL>xUH#7WqTINkk9_4aND-3xB9g_Gm6N;YHrI>$)1{fQA}OUJ zgGd1zsWTz}G6S7f>LW=ye(J#(Y$y>kb9L9*H zKi+~!8HAJ*^leRF`%DVfS=AXPx(B8i)w6YJ{m;5_%6UMzbmyn1V|Ax#Z035NAU_cY zC^3BZO;uj*hsUanhlo48k*X=K9V-Z5?}xdu9xpv%;lCqEUp158UM{+@ne<*?f2bD7 zihVO)5WzZMZv>K-8!B#Jbs_^&1pIh)`>`)u*HNERe0SiO(rLnh%`K(J!2|#6?!10u zPY@EUB2F2>bn!;w1`}n+YT#ghrFEqujn+F}lKsA~uC=-{jhFvQNDZ#tzZNM1QzKE3RE$j zBw`7qMpJ_mA^+v>Gc!;kB!-@tuPM~5*TZRSeu^&=5f=9l`_Bz9ukB@&g|@F|tMO+c zF{dxa!+o}uAvq?yz%qdi7#-t~Rb;l%Ulqsq70#TPtgihBQZ0t6x*ilD~^QnBDq z{Lx~qvC!+KSVnR;0AMK~O=H6|!zjTB+nQfZL#eRejnFy1FWf~Bb@?mOOu1z<8U5o) zY4*J>F^(w$158i0c9>X9`lyQ}^j0}vw&U=-bTwv{?lzq1y~i#Be3zb3ApBDARL@KX z+bP92SRn+uNocGb`nEzv)g_{yytwqCcYzY2AI zzbf;cIOT8}B}V|};e73QPlgk$J$+jmKQ{jfxlCG}yYxVrj!_iSVY1PWzU1ICH;AgJ!? zsoMR&zlm?f6CF!T+kDeG9Ot(B6Jo%26pJiVXhRm}Iu;AgdP3``(mCzceBYM8a5ua@ z^>zQbIjH7q*e-dCl$DCncL_W_W1}2?RL=-zi+ROuHtAj#%Q(p10+t>*iI^{5%HB@+ zeNP|Xdtn37K#ZL(oxgZ~#o@*U3H(#Ar8ZJxIviKL;&na_3vgD}3#&F<#zxiM1lnr74cdP>)990c%S zvh#0Co5-+rIi=h;=RPb43cTVwcavM+zaLxp!9Kco(-ZGWH~>)5E@-|x0t5C_dvd+g zK`N9GQRleGR3A|fORZ1I%*G~)Wnz@P>`tWD5>lk}Ts7;{u(MVm5*U!x9GSAJ>aDvw zGBP2!pBbB(;_a7EO>^%q!JNmth_)J=p;*(wV0zCpLQ-GKXkV5ew*&;~+>fBHX(EX4 zl<(GMID^k(Sf|8wn;TpRas-zby6eS~)l1qQ<30~MxBo>Vb6tNO{|P|>{0u^EixaZ? zUL1VL09?BDKR-S>0Vydv?zu^GNO;6qVE*Rry{|#{oA#SS46S>>g?VC{Hz!|Cvgslp zq!@aOy37X10s6j!J-!DnE-qh?2rL$=bR8U)&C<{@9@QICyL~UZE_;0392{6hLm6)c zgq<%QZ4mv89`nN{z2Six#wf|L!ZYm}Mh$475&#~tN3jHV zxEK$yX`q1EC#USk{%!QH+hFa3RXH1@kAH$T%+W(Cxw*Nh-X;PF@}e`L_wI^DZQ)6* zYfWB01fAJ938V#9BW zVy!z;F9}Z^o?KpDR>G*<**>>f8PL*_v9VF|nVzEm+Enj}D=Q;i#OnEijIE_*g#!rz zO|Xd~Y>NY_;&l^+#Ui*&zywAqK$wQ*M0v7+i0S$${kDhb&}56k z-y(ay$a1DQpXSe;Ri)ZjUzYMwYN_Z(2j^T8Ix_k&Yl6Svez7iwqndkP=b=c`!8h*+ zpaJ(J#xvdb#YVf~t!l12mf+mb5qxX)APBgl^}oOAjOt4ivUpw3nUE6=EK!yI7KG!z zKD@&-oraXpSp}l>Vl+;!G-!DrEYH$8adfwr7I(zI#8u5P$Q-`L|~!0cfGSUwSe6wfEQD+g7(gFBeH{Jdd@=mYItg z`@+B``q6C<3Gw?mmi#7O>Z}Wv;AtY5?>?XH%p~*LNls3-L4cktE$tNx4#j~Oc&ctN zq<K!Q=v04 zWP&kThlN#9R5UvxV`NNT4@z2I96CKUX>4Tu_6^?CGp(RtY`zilOT}{TfFCM}br}Z= z43)5s4#7aGA&zo@?Hrdt z@HcJuUc9+UDWv;j*#%b$_m_4!;5KLb!o9uZY=gDqS_nDQuG9X42VX9p8+B8x#oA^a z=La*_8n;&2q&qC(J=N&0)dd~*$1=F8blP#jo?q0z6WOfp)O#ThAGBWYbzti)B6C$W zZT1WzfdQ1Yjq^o<%^oK{w>u@Zwcm}%E;e9&v9L@!zOFj<0E=XB zpytQoOm$XB9+2&uAB&Hkh6pT=&hR!hx~=^R|Kmmk#Gg|hktp_U=0lo zY~~Z~4UA9F!!6F5Aie`%p-P@Q^F8@x(#xGK?c^`EKOgqid=DPSOBAelyrzQC`G^kK zai*HSwLz6c&uY~eyv1SGKZGTM)H{e&d@{M)vs_s?FGvDiE*?Q1in7tz`(8`c#+!G! zxw&3cbr)S#SWj4#xf_mKK~eNhPELI|H(pzaY&kBL{Y@JTJSmSO?Q6>=dgu$GU*qfw z(_=NIH(IMGlnvl-qoj;x;DraU;@BNA}=7!YQ5w;A+O1;g~bqM zU~7ABnMQw55Hpd*r@k%bw{YUTwB)Y_543mZj!x{~dWh*|3sQgElRxiLq2N*Di@-toYV?jKtLJNlmRx4(f6EHBTQH>u8W`oJ1#%2%bk#2`@Sn51MsY z?m~Y**8w?pBR8ZhLHLDA++YZhkdW~4y6B++zB!}?W=W6tv$%j@dz~TXn`Xef|{>{YKXnSSD!Vum5eR^*hWPMOJceV_Q z2o1HjFKybi-S%HtmFz+fdxLY+eUf+FBSQrH6 zL4p?_mI=$hf0V11?_byk6<{^}B*cA5{&iKgr99*#DqTqd0AMrkyl+t(FWJxJX_W*( zjanII_x_J^f1ap3i(a`hRd7Gh-IpcGeyJig;^uUs>KV)WI`*TZ<5^XC$zWb`v4pt1 z@v+&x{o^E=4rNP4Iz&9g>bYxP!s;1V=zzaBBrrI}V>g*J*U%6}YSho+iJ`bzD9)F; zQ@f%5fWLuUgFFiYLtKqROW(5A{-(jvuF28q&$BJVle06$mO5jD+$hm25z(KpW@Eh} z$h6^qRLjuf@tX7$vND_Hh8Bmt@Sq@x7K@f&z7mF>gcBX@yAOka+?&4W z1H!FGzp#Zv_MWhkYcA%H((?0@rkJ?iDu`xo!RNl3hgk6DJPODD?(WV7Waj7mXWtG? zDZTlmwl%w|+K2EtaAh*w#Ra4l#nQ+y)f}h%W|=Vj>1FWxy&*Fe*YWWVJ3C3Ruzz-U zwOc$bj-xpkT%UwI4{%ZXuimeg9D)j5FD<6UMHEH);lhpVLZ8CcXrRM7tc@;=!tlQ0 zd0uFse9foHN29-`(pBK*-i&TrVg0~PeT@nWjdI}1QBPi4S-KcIpKv`$GuLVzqC_*5 zkN|D{mZ3DkNiHTGt-~lvlqs^?2v<=l->Eqfi#%@^qbJk<5|^$ae%Pj&Wk^=fDY926p=i9H8= ziSb_q=9+4ZDK}4`GiRrz6E7$rH>@NC_kcKg|EP@56aa>%H%8kmc#*GXVcIk?Ti$-E z#r%EP*VXv7yS-)1B<*)o7qS3eDV@7_ydb@^EPplU9S6UB&+%@(4wXDe2=94gN?l!A z>W6ZCbX2x-HjD~`aC(M#dRG3?y7TI&;P40JJPLb4wf3x)pdda4&xUEx`p)Pfm}9&Mt$dH zsIlCYRq1=KreggJyk<@F$=iuyg1?DELhLrvEK}Io?aj?NHVcRVO){1k0-iO_$Dmjw zNkfpRP2Rud(G%kkHkl#{rfP1|JZ{P&dN!5#1QktH3I;|sDGFgaQyMr{1crp+#F0PS z+fCBa%>1uwt%LxK|E86d6%PK1mKGj|wb}8$+18QeY&%cbwM-coT3BH5(f!#9Ijw5U z=@;bEKXia_$WnbA9!#HWE#tZTDsmt3Q2EfyDf$it{F10;9-bDquC6X3B4Ue<&&7HN z7z8x?bh$>m+b?P9;VRv>DxDTI0)lqWhx6br6HRsXriO;w?tm|#CPv|soy;;@u6dzJ zKJNTEkeSV?Q(03Q(@cbB-O|4+=mli{_+*oCOM`3g;;hFBHl(+EkHbh=ckKPU)|%O| zd1aE(aW54p;BS`Ca#Ldo>AUOj(aSg)O{pgsQROk3mIgoDSMZax(;N4v| zIx<2NetmnZ>Uu)?is0{7a39)Y9JC+Vbe=h0x$vx)l*AN!a86Os`q7>bUQ5^|PNSa(>Hc zNvF59wBa4wnwlnMWf2k)t-Dpi0|ukX43w0VpSir#VQg{n{{DCdzFQCj1H)H3x@F>RNRU-!GTU^d-Fue~uwb=4aaSw|)hS%1brME5Vc z3qE;#NIK0o>}+h9!1UivW8{w=WUtm?<<|M$SSOCQUPWHC1aX` zL=z4lUMFM;!+%1)RaI44y@%4PCyK$yvv-X$gZKW@m6g?%9reY>56-7pT7vqX)A@8W zxxKqPJvKIyPv)+PD>*|iF+4hwn3S{~8F_oMkOs0Q9o>fP=3@R=-@tCQ-X7N025M^h z6@evA9=0n!n|*uh1OOr^G(2_3V5D+gK3PRaoaj^}94MhNoxEKRaV+qf6Ea99hCP$8 z<53w4@4_pUjX_C4H+0Ea2r%Uyc-lPb<2sq4}^Of4%(O;mU zZC4sANhdoZ@i>lqg5W16CTeSI5BIBor>3Sx6Y@E<=(Olm?JK9+u`*TCt*u%++OKQ| zD-vrlVpCG=4)$RP`08b*(+y7~hl@M?z=ZVMwEq*ZqnU0-3kL{WSy*sb8lCQ%OyvdW z#t;=(YLT+dEH2fXPtKO9+}+-alc6e$^$&U89>y^00)XRsJ8JIk0!-hx$7M}yf?h-p zgwb77R9w^?Q{708C<$dHNzGu7@Psq1X&AyWrs9jfdeQw~Um5$HQro^gemml3ra(7RHg2LspTYtJ!2Y~O|+Jn>6g{HFQ3R$OK z-iQPQ|K{1FA{G}lkV0k(rO_#Zj#2BKzbc@3aB>bck)Ui$wE_SE0^xSVHu0`t>K0GI z{Wr}+4T?}ShY^R_`PLeGZ6zhrBpLjdcA=Ef4!5iAP*n1so*so9L0vU9m-E$@;55gv z!NHK?qxg8VAkl6y>nx#(EIwDMcqj3;Jg{7oM0yhjXS`b?JjfL5<72Dm$wNVROUv`# z5Y4!_pzk@!g+mz*HqPP*sz*P+JeMtXw{)lQ}FYvbeN zEjo-6N}rIase*6DT?9xWj@P@x(g{?Ad@l54WIYQD4@HaBw@DK9nI=~F=UE7F@(I#=TBjz2v=BfUNI+@3rCa@UY7_ zSUlUQxywyMu^2s8N^)`? z{Yx*h5D5p)5C9->sFJ!U%*@VGlH_h=3;d2Dp7egXR}V6pt~b~9ed^B_`|>-F^e;1D zn52=3jgAhonmbpkRJ(LrIX#<10KgcV&F zker#tDElou`-S9sqqh%KW7cW!NDL9C|y>m zislQj38)W4k#b9?gKTZ)Tb=J{aOzH1`uZBI7xXqdv~OSCO_fkhQp4NZ3;q2ARZ2(# zb!=>Ak{Jk}@15VbzIgNTIhD)`_?Em|ueEY0i}g#jI6&1^tfaC?!9i}LGgViAz(OEG zFn0IbpZ;3kSti~y+3f>Y6Ztx;=0QwMT%??qoLp?Qz~TG;YCITy_4Imu?Vzu}@$cV1 z=pP+%N+a4==DBpQz^QB5TT)X>%%MgVZMab%q6$o|!FA98rGe?#{pNSq@fvV%>Ct{bPI$|5d9;CvBT%(tfaYFLiy;lz5Sifb=m1;U}2{B zk0X1R+b_GP>$CCnA1kSci1;Hn*NQn$RpOG84lO#y#>Nyu;a3O5zMGJFre?(q7-SqM zpIc|7V&sk%qIJ90{B{K^_#2%`f@x00!`j+9o&pTWX%REp`8zjvw>O${whS`HG5dIb ztE#G^rKLqQ5|%_+Yjq}F$(9a+d~jhSVKSvqOG+!BtE#FXMOM3f^?xwM_HO-LX*^qPaa>+rh6^$p zh{P4}xGjB<&-M25dh`+uwEuX2J4C${WKH`7s$xitr?NnlfdMqhm^(O(o4L+V#7!)% zt&Ct`U@1(K*bybBCQjO&tAB@K$zhUBW$WvRDsbnc?G>#082nI{0OIGDRF+>81 zGNwlP;gfuKXDeI`43*E$o)71`o}Mqyy5{~nkFlg;%m^=MO&cVEhqRYmd3kvVz4qLh zd14`C8~{N1gAym&@)sx;10*szP&}G1A>#Y~6d}iXzdyb&7IJ-eM+$_;#~*|shcw!C zseL<`jU~n9vaLY~*nQTaqoezSE$QLmLB^pP_ShRD&A5PJ0}~-UTjacjLZF+?D1w5D ziwY7Nky(HYA*|JENiyQ%0eH)ecW} z!YVEr8X8j4&k+rj9_sJe%`GkCnLH|VN%P+FS`8Lct3f^=3!`Dg3AM59tnGqLiLku}<{2jj zCfH?Vcda_4>jMHHVg~tK&ok3?>}HDP3-a?7GP(0gN(Pz7F1kK!O--F2FAbATPnxMn zNl9^ni;9W_ydF^mU;qFfiyi=+j;8z9*NMuM<^KnfAlP zJ2-8ot(P%+nYHM=-CrN|kYnWK(^s`Sb%I&Vy)p-5hLYta2gv$#;T~Q5JrbAKv!lsjkIL~zh}TsC7G5mE@Lk@@itfJ| zA1SyWWLIOjNHONSyMcwmB*)9GZmFJ|I1_cJH~Gs7Z}6ZX00=hSZFoKhHV+O;6lv<} z>*pBuwMkHZuD3t!ji#)%xqbmKu&|&ZA=zz~+3D#kCJGmuf02uzFzI);I~~RI3PEAO zN!Z&n_cEU?gFd6M2mO0gWV{IA+{`N#e(^gwEo~v5l1;A*$>(X>W(+5OG6ZE`$lYOi z(ypV^r*AARDJV#)$jTxeE25uW{^5KLzbsE?SI`SabH4E#G6fX4(!zXDpR}WmBT_d{ zit5TDH8^!MH#USuI=8$Hey;IgG*0jodsb#s`Jd$qd@l>;k{G#ar+$a+|E?{=~kdmvzttu~K>@DdO3IknX>MPKjH&0YlR0K!|uTM8tU;Q&O zv{hAAot&K7T+aTJ*4-J5Sy))e;c+zkKf2DcDX%W*(g!D4?gWBs(BSS)g1fsr!QCym zySuwPH!i^;xVyVMO!3sbQ!^jt{DZT1?XJ~VtzNz9{C47YFiC_Gq@b+aXg*7Mi^fMz zZt`DJI)lMLb8~aH$rjvPKtOp;AW>{C?V2$3)XD@MJ*$(lm)GE8T}x^zsORMQ{+Ap-Epxma<*ai0ND`erJFbF)0#dK6iX7IJfdSD7q#wP-EW(H4^LIQvpVS$mKwbA5 zpd~e4GA5B8*y}H~$7ybBizC7M@+D`_bE>y@d$Tu)fq`MQ&3VvPlQzkExp8cGczAjF z`D51TN9gF{qHE8ePoN&DG}c*z+C4YJm1bM<0(k`m)C#*tHgVx0!8uXgKl#NH%u^XZO34lCm-`yPdx#>v}?G4Hom}78X=!p}tUXl(Q#wXOVbZ zxp{dUxZ{nM%MOlm_!XaXuu@@6=L#~lrAZbU2{-oh^Sj7pPTcPY7{X(R&SWTLaw*^?O`K3QImb-d-{06rn0IT(m2)CW*Xc8RUF_|M|9&1@% zTWhz`oxas5hY>a{CkjxRcVW*br)o3z- zE-{jJz4v2yMCo}+r^DkDQ6GKz6BmjgOSU0n%g>(La)VB<51F)9F2R;&MQvzsrEjj* zks`+g03+3lMvD=~%nF&W>R0obP?DQdyn;E~GM~*OJKhv)jK@+-W(VT4!b(aGbAN>~ zGBMTF*6vMYeMm#3UNnUMI+F?G(PTY6J-y$*SDLKXPnVlajE%h(f6P_ste2}X707d# z&lKM{e9MCU1B%3C$gQr99^BSyw&|V(jZu0iQUE?EpGifmC`>UiZ;(EvP4q-SuiGI2b;b#QXJjemsLK&+At17?Kcn%0toLzpP*v z?D2Tw2RVVoWD}eJE%dL^2&;x#fp$lE?7Rk8n1B>eWRR!R8EDbup`!Yz`B`(jh^&S6 zQw^J2EADFd*#4T~JF^-4-_B3j{L-EXyknkBh1|PUUeEr<5dR1ro|vdAEfvhDWj#1L zio{|f`~F?VYzxkspWDbCnqNWq!uC~B39{i@>xxwP^bC>lzu&mM9bv zc)u`^kbI;;3=Iu2rkwb%m#=~1Ciau!<6Yd{%Z~o#HCW8!bGv{9*-a<2e}$pvblflu zf7=BBB$2rS-=6vD>(zQQWh<+)8UqI0q@?)tt9!nKQ?1mP9DSA4=xBbq_^7DQ<_=1^ zgskYjwhHm+SiTREf308a+07~~X=6jjNixk0w9E3btc2_Y7XixM=rjfIVkj)rDvXvogN0rq(O_gA#w>-O1tr}yq~ z0<)C6t1BLd9W;$?iEmSF6J{4Y5-E-4Bz$-T+}ZlN-rWhJ!5})=CC2{!4Fw|!g~`N8 zt35d{CkGNkR8G;>mI2W1@_{IBQTk*n44Y4pR;d+(2H$6Lc?xB+{Au|MrY&(^qu4;J zx^n?0Wf67JW^hkD?<(J5XIz{t1scNX@(p(9m1ZrP-<6GbTI7fVK*7s7seQn`U30P? zriwXq9Y-~A|J#xr4Iu#K6mASDg67fr09Ol*w=6@J;zs+c+9&`3k=tXbEZcT1A0x3D zR~8$WE?TV)pFVwZeYnUGCCQ~I&Ce(K{(b9X6V7~9R$N?MPL5uKTsJ+Epr~BDBpDSA z4Gk?VEj9J%(9oB#eiAWAV6EMC`}9;xS-FsLt6ZnkYpX9rNl9sZd_0LxXV0#sxOaxX zr5(4I9#Ukk;EV1`ZhtxiF6U{t*<1`AM`V3FIGPN<->fTsnHqk3 z%Spi=7b2svw4m_BYP|2OC9<`y(o8eC%VhYv`egLCPa$B8EQ9;m0>i&^;MeQ({fA_F zeZH3~dTBg3KE6Mg$`gsge}AJZQB2Lq$jHph%*xV{lao_YQc_bBn|3fV+U*a+2n!2~ zi;Z1sw8Z)L&B$u4*aq(4thIrM+l z`9fKbWf3%4>nPb?9_9$qa5~|>3=+6WrLnGsmA(z@nwy92i7JJ})-%Hsb8$^EIqH1DSJhql?1GLr?X&VK$MD>eYo z>qk%j?3A+JwmZ;1TLotx`qqU@iL7g%VFSR$TR1|3?LpF{*}#S)P9+2(3TEKm;s*duXpaPsEfNwz2% zA~$i<{qs$K+BDQZoh?kUvOn}BGvumN+2!Usv2#6Jtt_yzH^*pCf!*)n{cIc^e?^pu z8?LsCMU%*=UPJ z^jD|;?tDdn>=}LU>J{0?XngBaF>j@(q=va@lfg5-SHVS@w_15S{?gQRN8bej`22{_ zzV1DE#gZDp|s;eibr>`F_w?Tq*baY6)lTFL&@;Sv_zyMLSqnQUL7Z)6_C+9^JAA4$QxS*}) zT)BbglVSq%FmhjPT-=Y)qmZ6Z#jq2&&-5rF>*FY5zWg(tju61Z(xX1mmgxmf+&#TH z6%F@@zb+=C@WZ;(1RG};+zfR*5_@V|rh~nb8}CFFoxZ)y_{LMHLHnfC^}ACE*-Diq z(mECTnWyYdEk}~n0chNzV=8aQ?U;KfC!^b!k$7BzPe!k`R;#T?e5z_{5!fu^8X9e- zrIdt(gcKB_IkL>Th%L6;fpKvPnwq!*AXGBRg(hnP^OYq9GP+)dbcyV50uf)4dNoBN z(=$^RX9nS*2)FmfP9q~1@6T8&%c4hi^=p##lD$ml1!uP`1tDQ`Qqpi@A$?6jb4KaQ z?4bqPNgb8B<_Skl5w1As)t{_Uu>;B43nAKa1m5E!foY6U<3wv6#yi@Ta7teDHW%1G_t)t%!k4`yWjRTtDNytRKDPO<|Y5sI~lV_ zxc@hitDnUUBeDj}0Q?GhJa_%7jN8IZZ#q;$O$q>}ciK1h&Q&QIWa>Wo$kTUZ-Vd+5 zgoHkNm@%UHrCg!R2&H-bYslK9v7@7s@SAle6Mp{wpZr9nq%3DkXLEmrVPBzeH(9SY zHZ`qxcydWi-`(BW+S=xcLXlBk6khMdh2$=wi-!9nEwNMmbiLtENUS)|*we zxi22iN9113THMf3Q_FIdVuoJXCF=cdZ~x!_3N6i!!(lIWwuupBq0kYggz;A}MV?Ga z{8%fdluzX|7WeP1bGmgUnCWWMU2_CL7=+nH4+-a^Ec^b2SD5vXb@Gei>Z0q9=PDkm zk`qLndo4tnK9;w43%0^t2KQ?U)aYhCVbfv0v9P!})TqH;`jeyCvSN!l3~!MzB?Dt) zr@c`ul%VTn>&^^5Z*3WwsNCY{Xb=@unM4vT3;+6Tll8jS>(e(hG!XO`G_;$oe#Cf% z+mUDr63oa;F+(jyh`2-=e^k`ffp7?RTDMzsm61fT{Ry@g^Yu<|g278x%cX2|MbhEx zt5P=f>6%(Wb3zbuPb&bxav~e5?rA$!K!zbRBb7o8XQ6XfIRC0&l1@4C+dao)H5_gQ zi$vnBHGH4+7T~78%-S*vMqM(7g{DB%;PyNV%_|`oO|>~0sK`1g_NdQpS}z}a{v2SH zzB}(cl%+b7GV+uLCMfnlbWp7xS_gG#^4WVY!C7c)YH4xcj)$O<%g&e6y+xvz6=r8| zjHWQndY?@f$w*5}%gTZTK>9TgK?Ghl&dyPhkyh}t=pjE93MI|v%GG}UgdVAtmX`iZ zz`N4n$(0o)yr%Q?&A${9bipCY|IL>egtXG>eQ>#r>&yQmA(McG(yccTR(t>E#vwG< z!^1=Ny5uXz{kZ}A`0Sjpm;xvm)=*2hEz+1!;XBoj#BcM3?Inpnl6KZcTh-oUFVeku zUCn0yD%WyxCDA1}*^FHpGIa(FRt7k*bwL!)J8o)P+ml@`UHT_!$9q;Uk`zu`O%+%W zZL5n_TC3HXE+$&&&)ecuWn}JMZ6=O4cie9wLpdz&9~#wfcq!&R#}b zY1gZ=%rY3Hq@`6}&mwGe8C;%6@t;%bs01p7GX#W(=#gN;OR&dY zU;K2yjP*?>@xyHrN!kcVzpEv5C_*V|XpArmozK^bHx)zLlQCmQW?7kpR$L zo0BK|oY|Vk$wJNb{>1yndT(#9$yjPaOpKf-Di#)&R0bytJ$<#6lawCj-qY>z@mz)b z%LBtmEdcOl@fi$+yI$`d9vr;v6ScIo%+1X~3&^6~#^@*&p5C3;TrG+O+Tp#4axP1V zXmJWv<$>|{cyAgnJ8*5VR<)*63 zz+cSbDE9|31gHk5yDX3}LByb}3Fj5Wl8kD+q>W5B$5Pe+9vW`5KxwzM{Jm2>Bcp<< zs;KRUZhttr^Ky6IVDz%R*W{Y}!|5U!dHH`CT+XE?x}jlVNz`ikR#s(-^L~u>hkb5-ywmRWsanX?$wXH+y zCHgPtY{`5EYo{I;$QCfqeipplFgJ_nuLA8%|_gJclei1mvQJJs>A`w@<`!bAQdpEcl_^G2z5*e?_^&}gPz%5r@0wcsrTT( z)Q?cT-qaUcqQBVfIkCV@ugysm0XkPt4dWgC4aA=!pQs-DG}LppcgEgDgox84{`y2p zPamCIytA_tnC_)Q`bgNc@T|CxRkpdXHp`#@t&FrZufxIQ1mF9~>8YiGLGSjZrl#h{ zd~kAdu_7e|z{<)>L`3vG=HMen`+5CcH1>t{>xE=mT8~`_WbPW^ zHxIV46IGNnJPQ>XBVo1FXCktO#;!1fm^5qltQtK_l^7#onfRnaL8rEe) zvdXU$SLqFvgRL^?jf>_As&ecNt1}TDII}Hcr7G%7NcLwdE#3ZbdA#Z-$!Tft`{jrL zzlzHI+S=RU^wN`gqS5x&mUKG%moHypQd5WNkpw`vC~&>>sf9m6OSLon^e`j0p#?VB z$LW!J>Al~%K6=igry?{2n8XNCk*a=m49e$?i?ueI`Ak)= z;*!AB{SLE^Jl9AP@&#h{J~rr8yizHz-zPEnJn;z$xW2lIKYv0kQbZ4K%c0$FbVKcE zD~6QD#v%_4fP4y&{29ZEK*-~*lJIFZH~n&mcwymYSXtD#Hmn=+N2KJ$Ma^Qi=4+Ie z%Z(rTM-!Pmy*)j$1Qj@Tc6Q|z6&4iPRaNgdhYA`R%M-6giAK}^{#mVeyzUIe<>%+O zx3~ZMC*Pu}eJWoXfe@$%>N!gLGH4r1(okPNIy#Dri~BLszPmeHsl_EFHCEL=pstDm zP;JlM;8!ytnx?U_OmDs!s4Gu;jg>THrXKwxJ!xG0ri?y*&g@+>FYn-A%x#T|dhdKv zOhLDAZXVfT+nXyC^i&}uCMM?C^SMM(9WNwQ7P;1HopRjvt#lUQDE3o+>jC4gn-zoy^B}qFXQo zh&;mwMDp>(Z;qw1Aflk~+HCMkN=j;LXDU(}VZsWE$|=fqhdFAEjisXSyi(TH)_xWI zOCK(nL-FH>n5by8%jH(B(MYS~@!f4lfpXUsoP_sE3Jd@s3@!J(c+0DPH<>M#pui&i zBO6y1a)#pA)%+`rfPj0$%z~=mA8|*=V-&%>wI@Eei;rG1KOuj|uYQW~uwD+_jt<@r zJsdpO-@78@p9ev2bJIU1gMQa=3j2c_z6Z85&Rd1gjN%2V>pljzmlLo~<|} zBqZdMc#Nir2X)iJ^Gv!45+HnaG=3d=4_RZQ@V-qaPhe@f9-QdPq+}!xJ~Mb;`eZXh zWttdBJ+nu2oGYB%+8P-azH@jmDSw!Awz}RoIIkkLwY5c$WUdO6@Y!hWMiU|p{YsUPkVSoBd^AAXtRi2P9eB9f#umAqm5#vgfy#?Tqby~q zKY-2VA#qQ36<#k7d;1BXNc6)*z*OKGRd2v{-$xOV2rDh;-Z`a_mZ?fIH#9VyWL`zt zolxSSL_i=M!RFxn{sR;YYp&J0?6ALq3%~K$cb!GOGM_`&FYDd$h{`gWFBV4;I{f!9 z1s$D;xrep6*%w3v1nDf!M(;>(a`GHm3bduBLl&>y7Q-LVyPI#Ucu7TotcOE3c+z#i zVDY`m(e+}yjwyDZTqXQ`aY>p24FPZIb1D|L#+7v#KSscWIXM~vIO!+)JlJ<*DJpfI z$KCNF&|*lxpw&dwmDiijU~= zVh%+lSF;}y(*ve$_|UoC>KKsZoT^TQpX{tx)@0D}m-H#1uxcc!VLU+LrC*l z8|u*!0tBIQKi~e37huo{%4^MutIF*YREG1U3dKpw{^l$)s$1(Ke1KqCBJcKm&^|?n zCGt{}^~A0n1n^m8Do~cbzVj!l}BiZfMxGYat^eJAcnh(+Hbsk0mA7=7N5y zHSTRC-BwpwS>ds~D90i7_+UP_Y%u(juHEB&PSWNB&l@DwAIQhkx&MN;c6kG;2`hqlG+?4)l_M<@~;UGIj6hmY{mS5{VJHHtCCOX73PP*qeu zoLolHjy92mQQ5^O#S1U0p*if(MS-zWx2acR9e&E1;$Y?hM@b&D9<+7!N$ZnKZr|&T zEH5*Ia?v)&o4-#CYy=f3e9YsOOUI;@1iZf%OqS@}y;-Qe?M!bIEm0LVBe)RLUDwAI zwwjZYR16JwGI`t~p`hesUcD|{+9xL`Z@dEo6crVBc6Opk4i66>-y<6t#nLmSA{W~% z%y5ta0F&XbS?+palP!k>-Tj&N#7&plKw+LWoij23xOk8M8D_tcFeN*z;ochk$wdnQ z;fL$>S@)^nV{4g(oB67wpS1S`?#xxcE{3KNxen*&^-;r3_Ku#`5k*-l>SxS8A^ibC z7LQE-x({~y_j{vDJB>|bG&SLQXQ+U{`-aP{eq8$X<& zT1U|j^7p8NI0Y&d?&9Z`v6g@%92Lq|+a|I~A3c$w*1n)YQP8NU({TLv2qtYc1c7(@mgn4rfNA z4feb@Hrr?gW-p!{^b}PQHlC&NlutDPK(o#ExyoIRtP%Fa6#x{l!FxgLQHIP|&PSs? z(r&lAAm(KnKAgy>-ZpE@Xb6z0?PNt!hl^w;wYX?7BC-^>^Z3GI%Scavqy1WOF$Has zg{f(9Dt~`8`Zox8h)8?caSP}ziIOm)SXhzX*_i|h8)x3t$Dy8H4U{6)BU^3o?o5?9 zulFkr{ax0!$?H7ym&*Cg{lf|X&;CeH%+clZCTrjH2Hh!h`D!Xa_#=LDy^*Y=qvJ!e zO=NHdxtR+AOeZaFWBd|_ah}&APt8m0?yvNgr!mDRr82Y#IX{QK1Ec9QYwl{Bsme53 zCz9(0SFs}2T(P5&vKJJrI%?i3e-j7r`Mk()HJo<`K0$*Z>m_wo55bNW(`TzhQX&b`_*!GI*F zT2eepIZ}%8YX`=xA5e8u1@rj|9G!4Nq*{1ssE&bRP_1HbufAcI>L zH!PXKnUGt|_x@5>T8iK}=N1%$PR8e&%&+Enl~t>M-|{SW_*qCK)jyqB;|y*7K#P6g zZU8_d-Rs;JQ?=c>>dGc9s*MML>_zvfiB+(%Rf;J@EUV;lT6yu{$P6>XmO*ht*}1!q zfoT|yV-PVY9O?7EnZ>l-Sk@(l@R_@oOCC$Y3KLKP;f$5wTl3Bc- z@P4|Ou$CA9K*dk?x6$3bWN&Zs>aWg{y}1cxKLAVtU7!~p7f=^?9sC2cn7_;~BI{_f zUvScy*eAP)!Ftw)o*8WM;*HNBIbv|PCr3tT+Z#R^@5VrvYFQ|4o0RcvG}iLK#^|`d z0wWjQxqKmt}Sq`!ZAvP+%GPQTXZ|>s{n;vM>khSSPx(6Yr)LNa#7z8<2z~AVAK1;q7xnOPm zX-t8D816xr$!gm&J%StXH(;}RH5A#+g8{!9TdsLiIBZjQc1XPSsgG;Ut)IN2{Y{n* zf=PQp-W<7Qx-XjTO~p{#YB6o$O>@yz=W~Xm%5hX^yEkLGtmGsWfyLw>hq+{P0=qS2 z@#5(&gc%He?Jya43lJ2LLj$s1ulGcqzU9f2^Z=8LY$Ec6pop$kNmCw(UV1E=Fb_O6 z`=LxJcYRFZx|{8nC)M(*Ltf`zo1BxglT81jpg;H=56`hR9dFNe&G?8yfoidi+8>c~ zp}G172Hy~1j;d~vCJy)Gl9VHUleX2_Kl-^M&g06kUTe6VsEay7;p)0+VT|9hntZLo z<8wLuwFp;=*%`-pvaa?);WeB8)J##Mzo^{twO~xr*FBRzI4G!y@xTdJzQ9(U?wkf}h(kT{u|W zN!Z8p@T$%;8swb+Lx0q=>6W}4i2U5sNW(RNd5&%(; z1O@~kai; zuMe;tfw>sGoxz%!#?ML^*15{CfM_WRX4j-3Mjsz9b@a}KM3NIH7gfQ(?bjz5u#13A z%lZp-O-&7n*wMiOVYkv`t0+mdo&z<_hq5KErUiVkPEDY-Keb;!Nq2cMQ3KA&|}T6#RLrrv8S@>t(cBZ)lEThCyEAHalPbZ>`(h+=uBntYjMF`XaISQ@F0`p2OB*s)V#D zkFQ=zPiPNYg0(EM(mqyLNJvR>F~2!s2UTb|@itHT()|J7f_3pbS0M89dhnEQozUH{ zkQw9NBs*7*Ks|Q;IhaeL$k%6gXc!3KjoX3Zk&8rDOiHTX7T5A9H+Ak8Z4i>d!9j37 zKOuII;};v~HP$s~f#0t61$(hHQX1xVED*3LJbZt!&HhFc;i3c?EeZuiV+Wsq((tff z{D))Bvijmz7~!xB*_$cARP@H)C4~dzbuU|;-^-<8qK6g$>c@T$@H}%>Y)*E5;=7Mi zc_Z4LZ;gDJadEx1<^KLq|I}azYM7CUW&}FWd`+q6U;z56Ywke3uWMvzVqxaAhZg%1 zTRWTkL2|^GF73RYPaEtVmdmX9uv=W;W!f$!b9i*`LoCDg$DT`&OEw%{&ANwI_3j1X z{DZe;W=;Q9399+(VTQyND-gaRckiNnM%;#nR#ch|fq=r?Z5k~m`Wj-IYPDEP`cJJt z+mI0;>Y|Sfgq4T#HD#VFXp?e=5a|+hnvc_BNkX#1kz`O5w-s;6#ch~=dAuh2qxRn? zirjbam)KDO-Kdpnp$AOYTAEQyg;M1Mgi`L~nTC%J-l`}C!gDZi?5U0d9!NYmX+$EC z(VAAa;=^Mt_MJxSWyRTMtx{>MqK4n{PHruH^q_uuk>zrAb2~abga8_UFZ#{!d(gon^B`xJ%L@X){LB#A9?wW6BmhL#D4PM9qNc4Yh&^A{JOYZ~l6U8(g<*7=D@kum`!SYHx$B$t{Jf(q?x zr%eos7-td?|b7>G*CV?%y$YXUV4Ap7f63z}k{STMpbm_R*}K*#|Q%hYqz`pxMHX28}< z@RxtNxmEAoxw+rri6XaCQ&UB?mE23w&~(`&bNfNT114IjI4o?_tWfOmAt)s+hS4IR zetFvfTLkq}Cj-ObIvt6(nu^VOvuS#yvhwoq&`?1L%)lHUhCcE$Oj@>$f26S!DvHXPc)Tyiom61A z+fYJy-mIv4B_7JKPCN`%3qB#XshIvS4Z0yM=IwBLoY?OE$Zgze$qK{uQE)UWiK%!5W70=yTaU_ zzc4ZxkHRA$v^pLuD=8(wraDxT%4R-qoTO+>)b%Tk!e#w@9FJ3xauQx=d%t86Dw_Rs z%0{O6-d}%SSo{!DLx&)S^Z7Fu9*g>eTuFH!Fwh<2DBzLGib_tV)1LeV-^-%guaK9Q zjFwjCMZwI>3|asa8~eMG(q}cXPl0+KmX;r#p3-)_8%J44p_oKmBD6qxl(vrj5dS@Y zYR zW<)4X8n`?L7o6q1lvqPJzV4#w6d!q71UPfNOK7)Zp$90F408l+GdZQWdsK z$K-tHMAy*JQ2%$e-R+Wx;jZ~@rAveNJ<|qu`}yAXgGvZNtV8khzURAssP)+SqRIH% zV0tCrYpwnwZf7A3#(dNv@15?z`dCb}*F*e>;kwQpK3}_|y2WLLB`Q=S2{Zn6uIMtx z#+2j1sKO#zHsf6cR?XQ7cwx|4x*X}Clf6~b^XpFvGg2U%bBGA?Qj8f1$&1}RapQ8> z-k#Wa>}hL#Xkr2mP}R^N7E}5h@Y4?>JEtn@;~WbdAG5CCo1v2ePUZ$REGP=crmg6H z%WUoJiKHFZdsQ_;TZ-CV5U{m3nW#9U_K#HX-6X#}L*-t}NX%ENad$*ed%T)veHyG= ze+OkWd+nsVlMxF=W-hcXV1#k;y6a})_j=KtF*~0R2^|lr7iy`qx()T(J%nsl1wQxi z%{`?-5+1bc?h|m4vuq0-x|?L7u@{Pm$ceYySKlt89d%{-eKkokyVYg}%OD~ec&>h) zn%eQ0Q*k_;j^-G=W^T1=c61!f-T36oG@sGzX`U{N-Qe){=+_xbY2)Fny~1)0r$a~Z z&cW6Ac<48eL0ic7^&GOlNu@HP(hd`UWjb6oKb`vl;Q$%IGx6?b!!*o~*n;*O{n0<$ z{CG4=v5*Jq->r@o_tz7cf&B#R(fIgpMtt&`nxpjL85wy06mFwc6#3y{D6m1krulOL zLN)`f5ip?N-tFMM{--*w(L%K+vF^Cm)wI~dR+^K)g|lgb&M>TFe9TNFncLvYx!qGl zvIs1kn~_Y5O~iDnGio)vya#Zpy}K3H7sirK=Xo!_3bmyeAVH0DI`TB-bR8@aB^M?H zNyC2#zCh|H5A4K6y+6|)cLU&mb3WZ&ndb}|gT3zxM&^#pE#j5`)fRQWU!MfO`JdStUds4y zD$|v7vgMry-YDI^Abc0E>@&)s2HbyB&FXlR=L3r**@rB-amKDgT=}rPLTUb`a3+~5 zZ|_93{yfNKpSz*==2`*OCl`$lob6axiYB;AH0t?Y5k>f; zU!PWmtT+&tBc*qu-vhdW@wFxZzeX@F3jna|s6fdwid(kVrY9Nz+qRQ?w!stGoGOgn z`&3j^6OovgFfFl0j99(&H0t&I`la~wnkcHu(|yolzWg4@w^%581s1zjXZZJIR*PUG zC|o#?a?GHO8`}eWmfNH8g^cNCsj9qTvrl8t=djtsJt{DOXqC*7&8trTRUIj_OVWV6 zu3^`+#b~G=JFHJ&=7zO(Fe*C$>cDwxe5~5Eeo4F0$4-7>YJKCIu=-sL1IV^>ljXo2 zWk)BbZm2%KGn%jaWN~Gw>8{O420eeSqc!c^n^B)oKYs~Cb#a7xXBsYd^SHW4A#@?u zUX(gwor1WJ3ytr}zUgjB@;PCjR6+y*s;}Rfe7bd^8pN7O^NcXNCd(1G>=_&!PQZ>9 z4>Kh#Q&Tm|O-)&>r`N(w%*aH)m+F7W%ac|h8e$?tL49<&svli$%l*~c;B%+PHDexg zuk?G~6xg0?6j=gg1kGeGabNvNb?(;~eC&fe^zc6r5SMc-6bR3U`4`k0IRFjJA_6wF za$y1%r-7a4mpUfzr%mftYwaZ^?Uuncw_J{MlfJv36W^Md5CH%!wkhBn0p`rt$9+j+ zn=!nI?!0!B7CZ0lP6Y*~f*&EI0CNMAqOTrUxUPHkM*8H*Hg_TK;R-cz-BS?`s*(L} z=dNLdE&&G?$w4tKd<7&3PgqMEOxMLjPyhJx7>>hcMWd>_+EAuerrf|SON}n{F>%mx zuJkoAR~7#8Zz~~4M}#NJ&GXdbmidP8PuY1@WsWM`2nweMUU2tmRMWgCX$#p{I7D8vhe7S)cIFJqLMV$~bSaosM8N9a=kK-SN+H^L6+ zPJ_V*H@9$2uX5`TC_j=Xub^OyyKg6_&GoH;mKm9FhM7_Dqm^H1)x~6;wkHd#A=k+) z&ox(vO~_;n@h{nN@6J>WzJXGVSA&o+H5xSS3Tvh$2%6lSpoK*4ka zr4mVJWh$s7kDQc8YgfAs93)g!VI*QSG&K2{;*e_S{K0drgrJDE)`QF2r-l1&h>pAN zCG60}!)3KYH9gG6@8-W&%ksBd*s1j;blD>I;pSgzO?SuLha2nQPyl%y#2cl7=O$lT2Xf zZSWeemK67`yu7@u?1*4AN?$k3bpe1+J*G1;AK&AB=*jgBf_3vpT0V-^vfLn-ZZyUOMXPM1wEW zuGm%)}qKKFy`_w^Sqsx>?^_s}|sWVZ6mBKafpzalWceyz3H6!as!y1tH>#J%zU z9-+l)ETAeGdXSMo_+G;**7ocx0@wOJZT*#iDn>m8?uhpxwSG$a|J-HfB+v41cd!+$;3 z5P@`l`3LVfF*(*v)w$BRf|>2i`ig_2zTs@M8b940GUwm-ouU&%PFiQ!p_CK3!8PD3EeL@)3biGZvGF!%a4Q>--=8!uw$8 z2!ma6c^#jj!AR=%-pH}E0AY;iKm<;c@mOjE4jZj%HSkLmgG4$V1OFMPC5NIfVxNHb z`TXE`SlI1+cT>SHSHuLF|ogqT8Uz4y7FT- z8bbOYRr%o;_@Di8w6C~N5pDF+ze<#0t27sljr5G`G{#Weux{ioFP&CSl@lvupC6x} z;b39SnNu4q=EqZ*;5c?H7Q#h>-p0*VN)j??hrcP&hjX(sDr=`p9sY?_qA8=S)ydk# zL|0`98Ndpb?j%qA@wGwr4dIdIgCf*V!2&L1hb|yPjJU< zfxk5m8fE*aTnN&@Ibd*(=geR+3>$_ffgN5$malL3Mz_E7*-DFkf9S`a6hA;G&!fS> zcYW5_jmVu7JNqIFatQqHzP#DLJh@%Vw58fsS~LGks)PY)8}-0fFdijhFmfzB%)Q#l z^5pgyV<76h-SxVO6(PXSNR32`5<+f&e7D_OXCv!hUS8)@L{5bzm`Esk8WgO5g&3eU z?vNq2@h4Q-5@}KO&*Dj9omwOq$D2(lCUogDfKIC^3i=~oveN2EbtUX;nu7T$#_9)B z&MN=AS=J@q{3<#eXtC+t(ygns;rLCH*IBSi_zCcP5=xS`DP=6N#Y7<$5sqif97&u# znnPwkJ3L!;PW%=vr%)hYLv3MZ7UH2aWyWeGZaeBQI@%{J%)-qbJqQX$_@O0PFZncc z3I&9nQ;$;_X%T{t@6clf(HHp6-$Rx@1EnfeYZV$z+{i-H%yxg1N((moK1HAnn$YpQ zoq%&=k%X~aHGeA~t|E2{M}6veXIzrP`)avh@eCf}f+Txq&2Dlg$YOXqmRaRso_Sb2 zl$BOY$URey{1z*CgG3~bh}7$LvTU-sH^4A@>f3i2<-Lsk08QPLm|b222@)e zenf7kq@)N4P{bT3QS?NuD;(BswvjoS8(I+6mFs0>JrP?Os#I?}7+-ABj)PgjQ}IKa z_F3n=v4&jwb~w{?%m|g|jBbXf;SxdGd&&usd3r2ezUTzsb_C+dptIKBZ_Kti9Wg^& z4~}u#&1c_>NH7D9)Bt*ZQba0VK`kvU#ISSPI|YP*Z6AogTJS$%5^2#}(ND{lZE@M| z2UflthUnPy;r7}Wr=!M@%c4U1L_|ac1;PEdd!9Nw_^!M>erteS^Fdda=7CplVmv z^sr~3VLNr{yIgZb@VXjv98F7O>rAqlcrWdAw!B$@0?JiudKMQsNJ)+E&sIMs%NN%G{aY&tMsABnh|AcNcV131ZxPD_<+ZEe{juU)uzvW5kw#p3)_s`gYHs~R+`i4IPWP z6#+EQJAwd{MQ1nX*Lye*&E=@{Hsj?rD7ZT-ty8|{h~s7^tVH6yJNhz4V%J0ijz}R0 zgJ4F%>zUmz5qv&UABR7p^>3tUu(s88suMLL?BXN zyIF@8nuM97{&9S-tEa_xe@VTGW^`09ulG2r3P;iU!nBWgCK>>tqACwrn^!1QNn<0n5mTX49e!Y8XgEUxnw6BP6-C?FL8p((li#VT@h zcMCax$%y)Q1t!a{C@NRy>0hlsDi=`H(c%$GsVQ7dwUrvk34)gsrpF$O(FW_&>g)mf zzkj2ET@7?ilhf0~xfM9rua~W5oX@Bqkf*Z+gnyS?>wl+|58;2IU!fE8A4C2N{44?uANt5)a#@o zMRT4F-Sj;jVxvAcx{?{Uix$PeZFWk%q$EYk2E5dJ;=!7dBJfy&e92(ofee9M0F6_k z`0<2W?x-t0I8)Jl)!O@{Q^bJrY}EXFg8B`DcrHieHgk=JxQs)NoQcUBHdEWK?XIW@2b=f$5T27Sc37VRH2134-eGn@alS) zpL@+!RSB~cv3c8FYJkCgDC&p3&R(!v#>J%otstRz7hS8EYr;GwQtx+pVtg_l>d``f zDLB-SPeHbCDz7onV+M~`yB@qc1@bhS%^+7Ofd8B4V~u*-$X@oXeUS{oYP90DdPHW6 z>2-?6a%*pae-7y|T_DGusa5*@j%-L$)GwdJWk7}IaZqLl+vTnldALm^Yyah)7-cmL zYtIuJRi$YLhW_4x?Y*8_5L@*CYNv3|P$aWC8DU_p^Zun>-|x63JWG?{04~U%&nvDe zx7mblhzCK^oaOppvOy!MaqL(Tb+ee92xJ5)4O+cFG2<|agdFtUo(T!5nn)M0D#1-= z=R_chwKf=__xl?jCN!lF|MQbhTIZgT>)cKKOpT%MEqF)cU<08Sy@d`Eg?3Ogaw1g3 z@)J;4Scpn44eb+w!`9(`kHP_curh;Nyja@^4J9c*J;lzpHN=JB!+e{{I?U}bnDX$I z1J`!MnVMNyk)H*k=p=~ zP)c?V*gmcXVJ}l>e>yz1h&R?c#hwd|Wo#!RDGo#HgUJQG_~ThH0~=DA2D85L7~#a3Z7 zeCmZ;1kHti5pE$?^B`hdYRlryocCGaYgW;eYAO`{VS~QX=S39`sZUy529Si-55CtS z`i6`BpSULwp55S)0hofr*R#bhqyc(Zi3SZYOMkxwU-@obyMB*B5vUg5eVr{s_49wm z#4?(Tk`?6c38d;1qu_tRa~wW`)C40?>1 zts;Xo{gU%P(*BzM02huMlU`a(ItJkC>bg6c5w>+7Pb!(0msi%x8=S(x{^fFiky8f6 z@g%(gRFbMm>H-t+cuo_z>DOqFu-?0dLrmLK9q)ZK-pt9og^5W$N8*3}_xaGRABc#> zxU>j2VbKrshi9tcARE3t4u77Yi#EcE$yMSO*vtD_xvrGy{t z(;y~iktZal-Fmrm6@M4m>ZpT1dws!Q-N6MN2$=X~E+n*@){^)Fdn@TAp4FikONbuP z%S5E0pa6zWvf14u=jP__|9;Tu{HcyD){?74rIo_Y!SOzzKVLG|_d#X%7zD<4zcT-s zwc2xY#GN9pUlz`Wd)EhqR#l!XbiIxLx+g`GYJJYjSI9)PC6fBv`*QzuhjE5&zPmn^ z6MIFSlJ4!xU_Hs#-qDf4W+gIxy+4`n;_O`JMl@ggru%m%EX)gMODNs#tMAj|EUEWh zR`bj8c9NIQ!Z=aK;tFf(D|k`o+UIU+u@1|wz0iuqa&fWFMbA~n(e}@P%}yWdu+O2H zfp(YS?(t{IHMP6!nxoxZrv^bgZ0NPl!&8f<#UDoSitnR1g=X)fs)~xUi_7#?d|FzX zd(t&yF4f^AsT%meM#~U#&oh7;ekok4R!e7NY@BeH?>Cy>^X(h2!>UYV-*+9~zHx`d zL{%9r9A~wVo?p66-lZAy?P>{CraRX%lD+G6*Dw^6=#YgS2*Tv+IFM7z#n>Q-H3n zZgF8@UvDoC9$uc?+xIyY`p=cEoX`5Kb>;*3;m$%N@g-_yvZ)N7US7Lz9VF~G$NQ6$ z*bLQp$YXoF$l(1J+qAi^4+zR%7Ul}1oh_+=1-H}8&)A%|eIK_m;PZN)4>!#Ow>zFwRaK?cs*ds@q_FqgQu)e7x4-P3ryy?TwyIzK)JIaqz=) zIi$@^b#qf^G)oo{o=#qHvGqpLxK}Au?{zr{I(b>CJBlF)vS~VZ><3 zUt59hB83dZ?^0t5YebD*Oc@bl7!B{1*d(9yZ^cj2!<4B0QNN@UHa0fAZ;yphO0Dl7 zAF(=cXO@&>#09nf@QtRx729oeX_(}qxF1yqD!jwx56W7RUbQA0)v2n z;PdC?^z`(U6pGa09p@IE$`mQG_wV0(K6F-8R2-k2AcH`DeoO_0g@r1mA6WM%^TSk1 zpP$aUl%xFVb+A5Cg?h0b$jiT^58#K_N>plm3=skKMBNma81m*uNd*Mf z*4Fg%Ctdd^{t0ajeA%JavrI=pLgMy&zR#D8H8wGso|?K0h8ISI7dFHR{YSF_x}CsK zC%R!4P){u#)CpdA|KLEnPz3=YOd*R0vOghgVDKi%_*1XVEtS!L;ke3fss3QS>+Rfs ztNK&U2K^>89R?@&*w=BeC!F#e898}cT3S4rwDJrpV)pT|H?0QW{gt9b<$KT;0J5I5 zJ>A>mawJwH6VazvR3RnN&*8)MesYtLlN)=wOJDi=&lplf5R@4N2g=9%kgYZ11a<^N zYr#F$bRTgjX691V%FQhu40@*P++qoNcK5Ts38{TJfCb=FhblTIK*0`Q_kx47Wo z;4CcmUSFQvkLKicb=$bGRmHNIlXOAS*u9K@5-Ana*{uHTT_wxx#QJH_r-s?C+#9a) znCa-OwIT~AxaqalXR?>;e0x98WG4BT!8v|+9Kqu+z)li0Y3Z0iCY4~K9h%3L(&v~- zi5^e#i5e|Vo3JnZEiWmg#VfsF4sg<%5)mNmT0BP?a zc)Usc$&L%3CnB5b&V6QGQ7K$kpHsfhGH&*6sT!GBNtm@xTZyY}$wUH%Tru%v`5JHm3%$Md_Ig%Z{k28%qk4K#iQVa2T%JBY&#P^N zU%s4W3%s0P7V@xSFn!;?(vA*=nw17Xbl*R9Q1}ikz31m+3$2 zWL;YksIITSzP!X^G7N}{`WOp+dXSBbj^=mX9vDod%;EQzP{tHSW0Sw~XjjPMq1USJ zo}8?yM#aKn4bAI|OkrS?Eml;V$37r+ARbER_rCp($1Wo&NqJMON@(NkoPD}<^LJcu z2MNjZn+d2#E;AD^8fRmot4m1{)w9jCnvKBkdjCW`NoL{Hh+XRPYH*tuYzO>0JhS5Wbne)12&gDT0-0OQpJ_GZ(pcVcZ|@b# z%E$~QkjpmOugWN6h8lsPgQm6XeouDS`;$dQMP{ycnBscPj{lT<@6OgOaNa|mKs|Wu z*7er2Wmxn&J~jr1BRG**w0JB5rd**}P?GpqDg=!xeSV8EFezz%aB%PxkGYK2!s^a2 zsY0e98(t99#1gNE2@W5>I1ug#nV`(XJak20&N7+CbvT6=21cd@+{0w3-P!22D&U(g zpJlC94#I#X7x3}$zd78$+OulFgF2xI>C)VMZLPOo@8lBx=_ahEeI5yEc@*(|!+OOD zJ@M}pWTCHRsykV2ymHL`N^0O?^Tm2=9E8L4&o8pckEgTKvaq0YZx@HYqo(c&L*?Y; zT(35Q6IUjaMgem%v9Pc(FxaoPdzuyN0s+u1$kE)%T%|59E^c68U{O&K7#b29>gD0V z#l^MK;<88k1Z$(3CzB+es44Q{088v4E^sI1Rw?Eb`T4lZC!^E5r!wf7nYx-Sv8iidg&L()>L7Qz z*-1!9?9uBEsWkxs+S5fHvEVf7)H{BsKfS+U;NmDLvI$vC$_hOSo<>jwn!qUwuH+#GE5tbgtNZYt-OH=bi)V+L_~^^qyZ9{Yh^|ZPkpnv-0^l)j0kB^^X#;Dh7>fk_xhIX!< z<){8{>te)y)U~y>OdyP8GYJzAlwP;~T)@Y}%j+?znJYE`*y4dOC75z6WG7v-Q0*H& z-453`%nz7`dEfffI2hQ=3{{;q&1hC}%$K`c45F)RXiyV!Y~}d7HQD<%TPTWK)BJ5t zj2)l3zt8l5s3k5yNSgta5{8C*iKkHeqwakdr>R*{>r zzFDX-S#Gq$$Hopb`q9*Mx7_6L^71lloL6t!+}0*3CT6?RtW1Yx!AqrTM8tFNyg+H>VGH>ZDok>vN|)6K>4yR*-aC%v(m>6Sw0QixBv-QDb) z?g_0d)Axpui*;m$nhk5-1vbBBx`f~SEHq~`xge%4yvOVBsb5v4iF)11> zG_|8?p%}~0mr1EPY+;b2_hWRzOSBTX!s=&OHl9o!oAvQ{g?>k?euo!cwE6S>g<_6? zILZUVg9T3ipFf*(mAYZ5L>$x-r^C+gd#XQ?N|2F}fe3h#h{Ky4)_Hh& z9hMtU%6~9p(uWE?TTi_MBDE_@*(3pYqtnf)FHDYKJ?_B`UL$oDzov^bc(~5%>m31! z%CX2OZ^-e&h443xv~&inh&dhY6NmNJ{!H!~PKRA}y=U>iIJ=@+3yYKasnTS;y7eBu zyK+d4K_#`dD3B8`ry)#<{0&*MRksto&v@3Gf6qU<;n2F@Ni#EN%ci39W%E$(S>_1% zE2dvx)glL$ps7`ZOdis_tPVrN@DYO$@$t=V40X@1rJYNTP&84RKig@@LDC|Zo>++l zd`eV{6(l4=BO;_dJepyKaNo!uSici+IT~K?PksmyAx8U-%WA$elw6o_++5M(v?Vc~ z&A;R9sSmp&{O$eC;cV0vSCVdpmP3CCPQTGHZ2c!JWy0p>=HQT!o5NX~@ofIC0rJwF z%X?n;ys>O~pL1eM8kUf`@8(c z2g4({7Ybz`GdOVq0;A>MT=rgVR$|D`Yg0qNoX5po)aS}*a<2_&@h^*MYz#>YA>wuO+EJx2RW)fSMPgym+aq^`r1J^lbJ(6=U72XljgLEAZ1xR&F_6ZN5F<$)#tkjitXeym zE;eJ)4r%)ovz5Z2*J?V5-k>9&P#}>noJjW!OhJrA|gVyNKU)e z)k?g@T-|)P4H~<3y7F+oDc+yKxp=l#%EGE0`kM)~ci|Y+&GdbTD<%&obVDnJ7*T`_ z-O}bG1R^dW!J|?dBUfZ&Wo7D6MQ7mDxFga0rCl z&cVdt1iWq_Fc%s(SuC?jzwL5k^cELk?B31}vG^YFmx>E(8I z3Q0=ZT2gVapdTDqrKMY^rH8(Ir+O?C($Jl9hxt}j>{Rt7{8LqdA3%j4iZ1m z)U;lj7 z%baK|S1+g3<1dk`#AZE1MMEP)jF!pkKGxF%_aK%(simt+NkOs6C1ATyO|RRi7G&9q z&uQ;^vcyhFi2%L$`}c2=d`4cV#MHZsD5Vaso9pZA?(XjP>)2$}7_*&-2&;_^qWpZ; z_0D8Uax+Rw+NmiuZSC}9Tb)XCD?Ba~CQy$P7#c|I2u1+)ynf~e4?BaQI}zZN9WE3~ zL{-Y-ZD_3jv5bHXPS6Aki;Af!Fq}SDC3t^nmfPtke&=Ftd;BYferIryOM1?BRi~ti zQBh_{URv4A)Y946vLW5%$0k^Eeo7@ig@d0yx?;e^4UtUGPp?Qn9q*nhu6Ll?Ddcos zF^+PGa^51@{NB5Vhh=IsM@p?Ok)KXp31oZL^J_ahJm z40ew*pEi1+`<6iU?d75OBU=?+)L|0kP%M#qgLN_rxVWC+v zr0)l_iQCCih|xk4wQ35Zf&Sp>KdHvPKJi>796US$-^ZDe5fJ3{Pr=8)PuF}&Y6QxJ zmNquD$wOCr<4rd6D4zNEE180C8bU(M(Vk07yYd;Av86kFXa4?#|sVFaBneO** zYLmY6l;6uEy>4U0v@z&PMUNKScCkax?DLiDTQ$OVB@oTHvpzB8f5dsNA zK#2PO9SDF!d-1q{Gm{AQyxJ}K_9f1hTJ(|Uy3#@?c6Wb$>@_8q#)B=?XyMD5s82$U z=+5^pCc=gn&423OR8-;PdtLr-o$?tRA42lVJpVpFT*;;~6jGHzj^=pXj!P;?HQn9s zz9FDqK0GfhEOh!lX#_#$RVXF1zQIhvdy?x*OPw~F8Ez+9 zktzj++KrYQE;~c_;o`{z_uM#D_dBn#5V5!P5tQ^)zec(5G6iPX*@n_$x%G7Q(xQ~i=`dupX+wBFK^)rB|;VSquxcg zey!SHYB*|z9Kpj1dw6(2V+fLE%w}8e3JMBdU!Ka<%F@|wvbmh{oHbhxmKu%{$Yl|O znth*c)7fp5#wCgU-W>#K==ouR$~C(DP6+ucR#rckme%Xot#>>vR9AmOC2Su1VWd`$ zl|KnSoQobB-HGTEwO=Vg6Q`8@9vD3uaJ7dN7@%BU&TeUFX;Exv{h{wif{7Xp4X5VA z1?iy@BAMP07O!aAgZ&j!CKs;LK=S~+@=L)3FZRy6g*zx$iWPF}~Mq%T};^xyQ`!#m4 zxR_gu!T;X7TWK1f82dH#1kDqVnuCGC5hmmFSuos|YI^rEn1^TcjK(x3pFN!(8SiT* z5BqozB76daS%`s)ptq=ZWZ`=-k&@N|PDCQ~i4Z$3$X4F%&E!S7exzyS2eZlJ^#Pf5 zXmD_IOUvNSrHudZM{EY4i_LdA-bLiAQ09#r0lZ+=o->DaFJWU5}||rfErzY9jJU73s_^c}#mk1?lMx2>2tt@L;7= zYlFHYNIPQBk^CB4OR8&@BpT-Hbw$y)SMS@7h$NBCCL! zJD9*vl%xv!;hjo97Ju}c@Kx|xrrdTNzHRn=oI&mETVMBItTpoyc$+QP{O7V{Wy>qv zd2AP$BJ*4!5Kj9Qty!HGtLgtOou4c>b$Q)%(!ziPenw!H8S!$BN^Y9SL zru^V^i1AgtU(FOWNRAgi_wbD&pp{!w)996u=s*E?d$!LE4D7YJ!v%;Br(UFjZup z>BfNj_z@p2;D!J0DB@b}dzq{f_PatMy$#(WxwKlZ8*70aqR*da>#e4@x3`DfV(e!jIB+M99>!ecTD= zi`1Axwxbd3;fHrDZpRBXAwi`$a{n5R3C$B}quPZ8Y+;`W%v8 zqdob(kG%b9LmI2#n+kNK;w%D#9~B&@R`p8l2ZGXH7K-;fwx1CByMjPu9_=frM2)<> zT^(-7H&pNm426pH`8qJCFz^bQAVE)oM;{||`xJZC4Ea8$W5b2tB-Yv*PNB&7jSlMq zfkJWF*=u>?QHhj_8tJ;aZElrc8TKwbJk6-ePc?N?8RRoK3az}R3Z&_V^8^%YFr8uZ zRt9t-r7K8_Z=&c#d{WKc*regN_#Efu+f!bItyoyUSS?_?r}f&lk&qtVOs6|vf(Hir zP5KdCUGv6s-WqYtdOnf9&*X(pPpRx}gAdnUPHv7$4E}{aUmrc66XX->7(7>FrB6mC zFqLrD__IY?)&r$qkS^h8zI-UqtkR#aGMJy9R;5XXdk@lTb+sZN2+NI{ezs^8U04=(ul_>p;7 z^g2nJ9W^5BlVe%DE-o%eL0at|%+~8Xki&Z0MRdS?H;P<{7;Q($&5a|}h>sApC2vL= z8CB8e9t~J}yFiG9C4U!`^76A`RIb=zQ9 zE+w9PfhN_O#F6u-Kj2^NvYlD{Gg5I~;pVnFNcpf)x*;A84sL1rH|1iv!3J7;9DzZZ znUzI*+V7iUwl|)G3S{v>5(Z66oL~(9GaiSWlG32n70DAWP-vBv4jwZYgXycmZ=}jl&XHdkQmDm z%*oD<*}A_(@93l@N5hCaL%d59!owGavPer-ntPGMjy z2gy-8#imSGxMH?MIP8qs$dOn}H#R0A%N!!aQXf$TIShfaqDY~s!lW;bo0d8Gup)7l zgQqS9il4?8(i?5k)g1DS*fHL+Jp?ZV4skvwqF-rknTU$up7HDfdCxBI^ldcxUdNFzvC==kFb5gV9L`&eB^@Kiz#(wFy|{N@{D{KNIa`hT`XAG3IP2f)R&&S{))d>j zp4To(#KuZri@*2vTkEVo815Aulg)5P{&YWEW7KbVbaXV-c3bcCZLpd5yWEx*Z@E7{ zK1M(#oM7WO=?BduJzQL0V@CCXp>~V4?>ym>3&fH#Tz@mkDfJzarNAk=A9p*p$24&& z*VAp!AkD*3LTt<#69-LG6tYFJaw28CS&9SYC~Vqzu46?PDi^^r`KmP0gbhg~#_k1bz$21s8Qkk^T9WrH+%{f{$$b6da ze@ySOH-`fzka#;xS+uXz<6DSM?bDZ7&wiw!*uR+DcI7;p?TRXVcK5AwVAMpQO_MV} zTJb%c`D8RGQ_>m*2Cq><(kE z^IexOPj_{6!+Te4kfYEgW`4z=qY zTU=v(^G#B#2`{c$?zA~OP*Du$U_1oKn@2x?hGvj+Hk(GyA^;?!q8O4;l3-bd{Yd5VY)hfGoeEV(eZda@ zw}YcS=!PwC@wo;mMIMK7tOc(B*4kaUw1ND7+e8 z{OC>v?R(L2-O*eQzC4Yu^C6{AX%P^{>t=2(yB!8!d4Qq(>rGX?gmcWC?grIB&qX)} z<>uLnupUZafh=`C=>+%uTV?=S0qyh?(TPFtrjTHmp9x; ze}A8l-^&mO3m12>Lc2~mU&74X{53Cs>iD>%geugiNIoNU=~VY{rqsmJGJNZPEQ`0i z0)r|=q?{q#S@fUyDh1|;cv_kGfh{OZPv(0Rx}k9Sj!S5#DUk2C-1yzbSPB+6|DGPb z-s%!39Z1AP)Z}nG}H@7MQg3P`shKkd5JqZvHCaZD61$E1RAdg9;vC0UbgR$@FB>LTB-R+14fW4rVxU z&hvlO4BjEq_h(CHFVwPLDzxG>cKE4(spkrT#1is*?T+ALU|@tAxt*?9Sy{C>talnP z`5j;G41=K;9_{Tc6yXjB6S;6PTNdNl;=hE5hXUL2w53{;iey09A z6Xd@Le;?M}RVsU3L0hI^`-4?G>7@Gif0rExtZsw(0DJq#v%@|_E~(7NmFeQMZ& z4)06#2$ zJhMFWSv?dtBw1l~lPK}!M!T)e&F7aF>4cHNL0o2Iv7S)m96|qAS-tIC(J**e;Vd4A zl9-Ya2#+m1uVjDU^8IMu7qlI6Ju#9`&f-=VyMNvR#K9tPy2~UZY-jqtmcTil{76^i z+}0r8BK8E~?4ibZ6KTXF8lfUwfcjOs!LqTA8v_;)_o66gF0G$0F&AnO%(~@c2Lk|= zMqEDyI%Cvf0z6IXsu*P1muHh~)q5X@&^;>%G!1>T$TAhNFAPtY>3#lZ^yiOJHy^o)ekdUcqK}H5X z(C%^ZXK}GbGz=v^KE7+<^LqpYR?u{(ulI~r$YiaVET~5-#rOH1`SLxivcS~469~1q zJ^{A~B76}Fig*U|5QrQ=B+GNCMcO1;h1K{Sj4s?Mj8Q(M3P$Qwp+LOB3nSbyxo`?FyzO5fgWfo3IJ2p@ZQ`S*9uwOhu{Ff(XaK}N>s z9Jt~C_g9JSRC<%^Vue+SE0ZJev3C5F0*OA#KK0j;LYz)MIBi?4Q`0VK!^EJaEkByC zA`~%({5QjpY0?N>)!!CQ}(6|-Xhe8)Zh8SKZ#^Z!2{jfL+tCp z60DJ~~?hKA!pI6(s&(?AY!-b{_<$kRB zw3dgIhtA&X-}+u`h<{3fBS83dsnZ92_=5CBfYOIXY&F3EA&58>89yZ{sorcD3l0u0 z#fNMmm@Bg7rH0V-I zc2T@nYZ-Cd&hjru_My?IICA31udnJG9gWT_@t4`6t=tT96a6xTkY2az;TWbUFBl?my;7>NW{mfRIT--R1ms7G6PicjOz!-B*o8M|rq$u&{QRCqXMCdQGM@(nS&f zGculz;EKtK;W_aiC4!_Ag^&$y^n`VJ-`P(W$v-|mf}tV7!SxR7Ycn&hg9+qmfW7j-Q7LZ$Zrue zzXKqEBjWcr#FL=)!4f@AnJFn)&f=wUj(aF$TM^fh@itLRR)Qwgn8app14zp`rV{}0 zozM1c+bAQl&P!PBh^?oXN9cBaD~!G?;pZ*@EUc7ly~0_9OaL6D{_d;;88E+Zz$=vi zu@$tUyN!qnFmy3y_=O{|YlQYXWFuNY2VOV z18#f${V1QCq0~j47J$oa-1~HQhDs#xwOD}wkWy645%lkjh>+eJ%eoS2=^TE#JA(-@ zTg=SNER;>f!@&U&@^PJ|_I;tC2sK;GiNM;b4VtfLebv_<#9qIgAsDVLEiF}Vgrai= z66%U^$2A=WH6Hkz$A&?(3T4&Fvv{Qao_`Qa+m+UHkqAwB^vB>vd&D`}31cHXy&uis zEYoZ2cnblQ>ns5Pd?0qieWVp+$l$P-9F-vTyl1EYZ+=c`NlGd4)f%iSBea6Ytaqa(waUtY>P~ zr&}9%$2#(?_N{JBpp)~I9_{yS?*5&#c+t2$Q?435e1*>!5Hg0no6?>9Hufqz>cl}) z7FkNv9P#2cs%9egqOJdzq&D99w7fiIs-Iz>_4Rm5V_A+OQJejE(|sS}HW%eP?ak2; zKWMs(qQBM1pIo;;C^}V0GBH%EE_4K-Q=av%ra9S3D4$V+mgh|jFsv|;%hTMfmL|{h zOOBEpxunqey>I`4hNh<5abHC5eFTPUQyC51oSc}Mm~dE3r7SHiKM}p%UzofSvEz+) z`aX?}j`H*K_e92TT&%XaV~TV0^5%!${~E)L>f?$LEJ?sMQTj@i$CpbL`LB!^^fg}c zI2wQ6VqD+KvibK~Cp;d-%`9!VQxC~B$sRVN0!Hl0+R1!Je41DmI(8~W#kAj4V|m+q z9RN6QxEGI2U~;P5XgmF?#oK7&%j%@@obki7zxUVdPi|g^)yMKCa>2LM9IMo>UxYtq z+tLa--bd0kWcy}J9#v&!O@FNt+hPhFjni`1h2 zo>)KQ8@TSWq4I9R?8FpKN zV@&Al6*%5*$nABeS-^NeGxihX+W?@_EY*DXu$D*9nw-XQWP2XcY+18^d{j385sZ~7 zTxzt-sH~)yPJkCafA9$+c6D`qygl(gTjNhL>#AkUyM_@)i;0Qx{7m`r8<{lVakVQS z!T3X-cT$}uS%w$vA(>iLKJ$rIuRx`AG<1=0a=8hNNGb$5Ik|hE*A#l)IND1spc*g~5Ly$&+VuFDwR%D>n}mzo z_i)c+bJRyN*`QtLw~5Xc@6VPhQ`kr<*yTV=8RmVXlULYKZZ@pKy;S6NgY_{)^6C1a zCYCz;em+&^=*5roXx)K@C7afm@>$O#;rU|ji!On^$_mr zz?(9~ccZrDbL7zw^#Kgrre4pILGP%vo&4IX# z4DZYB!4!I3Yb&dk*4AHNTUavP+8EAfBB^_$U`)oLK+qSG{&!??oy_-=@@m;^>HY;nzR2?jqw2`UbmFwS6?o>+| z8O8p8JOHyyiLtiDL4lF*c*Br7anO3^>N>6NX`>68ztz}~JZQ?2y0c+$)-xkk;TS(? z+90t`<@ih5z<>yP;jYf2_gy4k$ou-!j)Z>qkH$t0=RWKs+#CZ(x+i9uvil>Z^kdr? zBUgI*DAv`k{Bjfi`Rpjd9iK(Av!E&{tPnDG`A`<0urAHJ7*$i#q@l@U9(QwGir29$ zqNg7vzw^AuiS)ky&ATcc)rO#ue}bc8NwSsx&I~0Sjqbu(HU3A++sv68EYm%N{o&o3 z;a~PB{a;ev#C~ZxG4TPcPmurMUP7moL0<_E;l7sZjdWTg-F=fGMomPdvM14PC#DM$ zceNT5E30m`p|G5soU!p{o_Lh?Oi7^851mTC$LoVkZkLM6N^*4RL<;#%{J|b3ITe+u z{mFb}5NLNSE5o12KU)jR^qu&_TF*~J-T7sk<44w9CmLT_U2hv|MtYw6fyj;14meVE zKnQQf;po7c5gz!v++2Tqepyj23jj*eP-u&1w1La>+7Vm!%+QidSrn}*iNlG(#JbCK z8md8IHWJ>(n)^k3*oAdG7Lsd!2Jh3Jw|l0`SzUnP4yvZB%|YG%`L_j7c4L2to7jgbN*&HgLKwM-&3y>oAVC!t3|zoGAlk5naz382Gq|uP?}<8#n<{ ziqD?UQ5amn2Mmd+!XTqOGiS5&&tIrV)XW-}*A;}RBbgd!8rlUnJL3nW2C2LWP9Zxv zv;%>KQVrI#&o3{eq@=2(kFJv}`@i6*&karE*5Ux6W&QMY^!FoZBA`r8}biF+Ru8l062qZoja^pFzO` z05gOgM&q5Uv|hTGz(W0Sokg}RO#A8mPs+F8u$4AnMzZIeV(4?`JK*x8KiDtB|2Nq~ z@9nZq7Iu~w-qS5)W_iAe1En55VEaW@k&+bvGM|5MG6yo^PTXiYo~myrKHcSXd7`rw z*6{G<#W|#2TR2?vFtlNQdfitzpDsb*4P7=N?h^2xTGRRvP;$y%kBb!NdZ;D#`k8j8 zT$C~q<~uKHnSo<)M@kA-sL|r$Vu>ONn%RfpTDsvp_0*{;CXjdy9W4h7&Dcc8Wc>pH zazNC|@pQ8}!Cs0zJ>LAUgX6jlZsZ=rpTz&y3s9>cc;q!m!gPo8XNf-b8qR1HQ1v3}DUXFN`Z#?cA*7-Sc-KHxFR2_BvVhUD1y zvv|iRovDiF`2rHiJOU;Ai!XRy?5DBK4#aFqN|C2wZ3h0{1l-j#lk@XLET#hwS9_|e zs?$?bZf9$Dx+8X}Z-1OJCGrJy` z5cr=zPTA5^pwZif(yb3 z2!Nd7n%~;5kQ-*hY}=&=m3ILd&8RlyfQSF?dHLI(@1U>Kx$Os`n^QRO$3gr2%F0nE zZ~_COn05~n2?NLc$0E7_XxnhdN#W3GU4+re7f;I<>WX}XToNS>>;;jAGHb(`C zX>ji_nVrKU?Xe=*lgTfW!S7 zu41vH1jJokj+o$eH|Hy2toqc6HP<|a-+E!ke#YF;bKm~i`XDOrv8xx#nI?EJ`9z!g znl}9tW&LNLl49i%wh99nC1ZI&8wA9?9CwGr0$3eSa}0C|y1Kf$c}goSzW9u$^9UN- z-LOyd#AievorCC`!~T1?Xm2KGeEE4&txR7D%tLXV(Q#Nvg2G8?l*N93hxuIh!)46q zGeoZ^y@zHuJQCJijVYH(dW0mwWsJ3F8)ZFK`(;HB12$4={KB#NpzO3$Z&lA>w$dA> z8%78)Bu4xIzya@p1xZ0|zz|@9>4q_c>4p_T0#E>3;IP9xegZeH!^#M9a7G1Q31s7P zPA`Jt+Szr(U&I`|AyETYchY4u3w8?EsdZZE@9&?OK25DzrIpCk4m@nUI6s^$k98+PUB()zQee-QQ&*Rk zRvEc!D#g`aTuieXbTH@`smOx?*lxz}N)=@7`nw`)0U#hQo-IzZz*H6h`m?^jCT|DY zo!Y(^F?hY3&^cK;e7@qAn5A1j2&C)_ari*~6B$F<9lS32vfFo=AzU@b(@F)G{&szB zM+neMqSToBHAvoY?>ii+1jL$-P`+KCt*;X$zK(C~`xBKL&p4q;>47BLc+=x@T_SO6X7`CQ#zEMBo&+|`+?7el}Dd`b_lgF(}b8f-lV z1x^)uf;NZ;JlC%XP#{v}a`?VhuFpvxZCGvw3+pn=G+rw8N6hoq(hVXV&A4sCtQ=?| zAt459!itLHOG`TP^73Tpg+)bJSXk*lesJ;rXYuf0eg3?-urRQb6EzcJ?Y4^J*W)*y zo&UROU0u~oI({#aWc*BTuohhHJfAX%a+pIDKq-@d%b;I-<@a0C08p<}u=k3X9DGX) zx2S$A3>J7LqTi4OfbfK}sVF+pZ=P8EY8;5TR2axhvthN1o{LD5Be3 z`4}jRoqX6leFqOLd?zryeL(t17)z&WbQGnwq-0FGGSZ1acFGg9IBG z0NtW?jZ>r9xq66f`>B;s5ROL~FBL43`;`GZLX0I%jwU&>&p3gM96jPIL+bF3N@-Fa zRhpbc0+}!xk>9Ie5C?!6M2sjxiWr@T8H9#NBB{L1|2JRj`~x=#@`L7h=3*)N-S~HhQZK#V-?no-8ygIF zPJBoH?a$g)r&YmWx3qtB1P4S$MX9Q)zJm>{tgNi7t4mBwOirHlNBA+oh}>s{cS|~- zjng8blMcrIjO+PkFXrL%i|ysH^%Kb|l+x!~U{Sj;gt74y+18augn^Zn)lZQ;NwRq9B9=5+hLi-dGDVgTk3%t3 z=;%o{xdf5xkj+m)B*e4GVoDJ?0DvLpNMO#AMu04#r>B?aaC>(b9UVP3I!Z@JM@LV8 zcYCXN=mhhG7XbsKqU^_;qe?eSuMJ*n?{|zK`AJUBQ>7!S<15yts+vm`K|7}dX91HD zP4cU(cc+j+eO|i<5dU=KAR#H`i z(Buc+S|IkVH)OLxRBQt;g;212B~2b(>65*FjbC>F=Z$31Y)4b)QsAV$Jmj z%XhKK0bmE2xMMuAQUaNkyN;6c8hpby^<;r7L6-De7_HsEg$ba|Fs4@|+*@;to6sYUJ!3VK&P&WL4awf*L_ z$Uh1TmYHE7@Ph!Dj%NBE`^3#g@{B9*ZRCAj?nTDFP#d+5SLXJ=<8Cl*##1Ox;b8JUrh5n37=XvjcK zx@761&ovzB#d}Vzid1wA4DzzFstrORy~3zJdkm>)X)7u!PL7X{Pfjv2GIX@GxVg9% zmzVvFh7qQ314x@=#iZbqB!3naO}ZGQFkoWB1u>l{SV}(m2+h#sbn~LZB{Col zLchRs&v9oIa7vg-#B^~zcU(L%`fJm%(Pztf?>kO^D_}A1U&Ab7FT&^J{9B{MAD@t* zqN%xQf4X0CIm0VK)(t zKmrZKi%L)s07*+73o`Kg%N?1&`!vHq zCH`7SN_{uxIEYqtE>ohlzLenSd_J3H6}Im_Wemi>AJ2AJnhQRBEzW*XcwE~|^tbE!NKj`WPOX*36KtErqWRyRuYDGSNuC~2xY&y^(A#g!| z8XHe4MAC$W5(?AvzBbT9OQ+=YE!$Zmdd8%3R@RCgbZsy@JNxM4_tBy%LNL^nU2HrJeV9+F^+&er zR#_O;MfieYhVdByq{l1Vqu#vLgKf7hU`S`4I1gIZp-;OG^oi~q^jMl-&**Ee6=IsY zmzML2+B)cNtvI2$cpvcc@ZoW4)1(_89Q@!owY9ay#l?k% zg&iFoJw3T&K`OG#zrK^U>gwz3XQ!rm+#Rd+yC4Ap{XfboD)8~}nylu^_1fL!<>d)^ z-F^~DbTc@_oftHnuC+Hs?7gRh{uLINmfoJ}SPaxCr)A5lB)ZW%7yC-J&CV*4m06iU z+ad%`@0Fl!5-L)cb;SFaZY20>+f*f;({@jDo0ajWUK(0lPPXH^Lm7NZhLaHq3#oI! zYA`Vl7}<;H-!4(ek&}9eU-85)SSDEVef+Uo-*B495TBn zm5vhDMpp07nY1!Hl7lc>4xoF&joo|aZX@9Fq$E8&qx_fo&rN27$9|?#R?l3}OsymL z*26WHb~E_C8h*qH94=uS{J!jaYb7gf22(xPc92Qltx$;V3QlxUI{&jfJc^$C$^6SVu+I=9qKOV0Wcy46N;<*Qq@>`KKvj4~mC_F8)O-at%I zQxff`Fev6uEl-y$pIUmR7jhYE+JVHO{Q0B+u5k1w(cH(6FJ>F!6^de60c?d9Pg>Fws~?hXkBrMbD;AN=UZ+Tr8*Y{1X|CObpuO>QQ0!1&BT zNkP$My?_jIOp~1_fTcr+#1g05EqAKlH)rpisVFP+yxEuY@c~z8)F>+}UteF-(9mEg ze*rlXfRr%Q{-G!y;?mR8tEi~x=;&~Aa-yKbCe!QmwwOnkUQnTymX#Udh|d~m|1}#w z`TMsbfr430HCaP#ZpR{&>t%h4KTPC;tWaYJqS|Px_23d0p~NGt?wtrG{(#{8?Acqo zBI#j5Gbg8g_b`D)cBE~h?i+9W`q_Kgng5d(6F~A5u7PsO>$%r6q6-0!lTOd;`6Qnu zSd`K)VXTl-p`|36^%&ffE9s>EBi}BA!?hWWk<-1ol^gPJ-LQ0#S-m{^^-f?tgF#q0 zv;E7Oo4_%+>GZ5JqrPEj8A=BQ?1YBcAA`bEU6bF<>-Uh5PZ=XYcoEw^p|&St{HA+) zcGlP1TbEIW(!j?4XoCj~^nn^*meWTE2PFwW?Ck7D8J0gwOG{h+gHMN2?Jrsiiv6dX zgNyafk)a`KditueGNs+cva&MIm;1A&dUN<7A=K}3a$}Q|f8;Va#>dAyz3%F2YXc+A z{jlcd=7_J6g^xcOb8<$I75NCr&D@!2=9BgMKkm*Pu>nGJe~PHp)6#J9ugy>UM-mkD zG*8N2re?m$@v>}9HyjTco!UymMdZ`Dx|ZsYD7JxpxDdxXuO4^^j}s{e z@qHa#77zc}nXPr{LJP-@@pGJ%9lpA~H#bByxWO)m#3Eh%JA;mX`f_!BtzB;>CnW_h zrZi@@simKtO|RNZvmHZ+JP7scwSl>+`?&jYvj>U*G&VYFnDJz)zsF@~`vHE->B87M zS!wCv*O!N#?d|yZcqeD)ii!%$^y;#*q0!ON@$oLNyW@Cr8C2-0>1nIE@}z_Wl^Xrd z)zwu)2iC!w$j~%gA=LC@nT?Jq>xF8f^}I9?r2>DJyz%@Os2K3RZI3WOKi1uC{Ji_h z7%P`O$3tTgbrsg7YG;8ud8ggtuqZDW`asb{6!Au$$^q9ZTqwP-@u z2|*eP+D^>87SA3D-bOc-f_@tBC82HQb+^CZpv7rlUrwKCO`fW>icT~$x8*HAJj&l}Gq=JSBc@NIEEcrJHHh#2<5@b$Z;vI&fX z`Q*j70Qrr*U=aTIv8*fF*K4k=-}+B-6@bKI%&&BuqW<~#xOgcIimHz0_;LJN8SMXd2JUi^{zJbw2Bip0m~sp=4c zeKrfcs2M?0+0l7Y)KngY*edxQYSL?xWD)W!(q|W(3PLyf)85x!eg#i;nR0%4&yLjl z{E+Jf(Oj2pH!uDh*Bn;g^`!0<-1-~Ssgby?uQall78Aq@3)Om}A|iGhU28tK>386h zp~j(DulF}!0EpRfb94LC!{(`o(OCC^bWZ#1A2P14uBxi4-@kts5fRbW#><&V8QEL< z4}pP!0Dy^^G+(9D-roN5_{hc0&73A{F>n!@PXz>jTi~>nh?f40L@y&p}vGkHw0RHtUpy3(f40yHHmXXV>wCx{!e3zSY%*?ESC0q)7Od zEYiWzQi`?2+KE|3i9*OgQtOhlUubvAMz`}-fLM~ND>o0%pHCuq_w}FT6m>EYvlx)O z2hILOe(Glc>6VkvZ74@n4EwU&4H=&Fz(uT%wORX53RLhQ;N5^&y>2biWRug=%Lij2 zo)`lI17#^@mY4C|O42Fu@bI8ukypF@-xDYm%FD|ief%^v7ay;7bQ-OS3JakD)XyQ| z;o%Sv5JW^o1jwL&|4eQVr&1UVs>{j(=PT&Z!=Z&yaVYZqY7dvb07Aoi{fq|lYB~{~ zKL7ye?Py5!|E*2}0{|jqZ->_Tg}u)vpyQksYN==pAb`4p`TZtcEQxIq07$+Jl}#)t zN=)0W=0XT*(Ph1xaaZuyrKf9@C_ts3bGg#k_@Pqi;eGR^dm$ilNDZm2tEgX#X;+i# zqJ}I$ug2h`^T-165cJoV*PWs)3l952M?VE$U0w>I{v;dv<#k1F5wY6kn?dp`Pc%$K zMF;?fhlhP%?)g0~H%}I7LPU&=jJBoj583PGQhRjFYBps5Z0{t54R@aCI@15EHro@nPRRC+xtTAN@;~PTz}Wo!o$y~MpkZOnO-u$&>dYsy$1*r4 zmY36e3;}?KmiA)3lh<+k9~Ql~g|)S}w|5S&JM#E|4@9dj@Sux-!U% z$rS-X4G@yIksj+7gHgKTp*VLH56``)_QdhBm307w+-!;;4gB*%EFHN4fE__)4(2!? z4P9z{2UMtgu1K6fRw#?r>B|e`uC+KyAM*yh7cz-Eh7UT zA79j3sO$PwNXgs##df8s)8k5n^fwtf`P0iwv;9W)m>CrC==1ja^6&}9 zn;`@0giiy18j+5gq$giiM6Yifjm%)lA4*$V%p9zUuY$)!5kh z6Qr=b{CG0G&WF>t35#Vq0}Tz2>v3X627boa`D*LU{#XXW=g+zQf4#$)Tjq<_l~_6E znOH@c>D)juJZe8J+;n)VFoD|&*8;3;xm{Wp7^SP-zoSbUowW_I?wh#8u`o0jMAb zluaCb4~C$kruOvkFvNlJ9eC?cqSY{A!3`pr)In61h>D8BqSwa2#->CMM@L65R>-k4 zG5JXXCyW{%9{%?BR$N^C{QNvqEa!c-E#}OT*lUEyks6x26NQT*Rjl95fE{^qJM>4- z!Rmno3bx2Qam}5;Cz^U%g)BgKW=y)CC*M4dSfvRsxQil zl+XZisIMJ-GKDZ?a(FljaXSrVj?De@XZOxJf=myKzT8-iO-v7mN0kA6%f>B--`g-D zSm@|_gsI1`H}5S>6Nfe|Wyfc>wY2yUAK?epy~Kl{T}*3Pbs+Z#}q8vu;Au|X43$bWatOdQD};!_fp z!%I&|fd&3LW|F`m_GM;fnvG{3?dXN~yz*#`w_ zT3N}+$SAes!U0mQcW%DE5hQIjItN`|u6pG(9@o2tVX)LGIw(YZ9phW5Byskz<88C} z1dGR#B0ER>Hcgrf#SVZGz6 zgM*xth1fRBP5A%U0>nutxw^s<26vsKQtA0=g{~l@5TKX-q{c*u%!=XKyL7U0q(pT| zdMRJ=Yi?ZBRu*Y{yx$HyfW0Q;vzUYV@$VNJ9v&Ws7`;{hpZDNc}FKp`9y8C@5a{^C+WKQkczL;b2uYwJ>BtJVL@XRYK_89ns)?J1eWH z0$7om2fvqSt9#2|rtItr_oonmOFDCKS^o9fooZnr!TF++s#bXY(zhCY)3UOjWSEZt zVpcjfSuZ+K$D|(q=ikvU6?NA$0{K9#3#I(x($ZHr z(uASj-rhFXlj5>6ZrkMs3T_GM88*b2RfpTfHq0I-B~Q;RjSlej>iZd|2t^+*;=_jD z%eiz!Hb3w7Ar&31F%>luzw^N46j~EATp~j^pTN8TcBr1AQKhm{*$i6AY{aZK=7O2^ z#$9{+l=ZhS#_AEYFIi`tPs=7PZrxu~*(~F$s~Ln*{rvpKJWp?C%T%bTsc}L-K|>3H zFb5UF#>`^zInO^v-I$v4x}7p{a>4?$v$L68j=ci|#c~-OB?>vo(nWGRKSD&l29eNV zA*?^ZCmwx}I_h7OyM5WS8hl8qw(Is&F9bG@tzZWAxkb}WjrsfDOjMYvTlSQziTtP0TQeu$R zv}lZ$MhK6j)6Ikvl|ZSm&6S;;Z<&49<%=& zcz1UL9Qgrpt?MgSXaqTX;)MJO| z*gTxZKy1mbQ*v=J$elc<(DL~xPt^S7?%Q|L;_~B1Sd>wIexsQnp`+=-L+ho7cwGI+Qyes8iXr0vydugPG$^<QdUOC#a-(3cE=DiWm$Tr!VA{~~*WUKl*S=UjLFE-Z92{fchdW1=Z8|o3DxoYN&uO2U zr@qXv$)>x(o?zHC*mm_6XR@Oxvk_|*P!g`~Cok^%8 zK~+|lqiJ$d()`Lwo1KB^wzf7lIdgM!g)AO59UbqvaWE@XiUjzKS@$?> zLSN_m)9GgW?zWPVe6jM-&_Z25qe0X%p~=e1et-99CbmpJM?tjCUd7;X^t8Z$pMmq~E^1KcCd>J8y}JiS>n{qzsvunVD6b zU~LjlgGoHY9}M7k1@{(@kB@29E2-${e87*jDJj?y`9EqsMw01aU|JL5QKLp*-kPsPTU2bQ1y5xvYn2t_PAFjQ2cITsMtZA|oQt>@KJ+{jYj_&UM z;KwUQM|kBj46jIEe-s!H1i&UI^C@WdWC6S(2(!D4Kw8gpPxf@q?+P!+-ufJv|*SU9`Tw&Zj@4P*U%9wtO&=!-^9X42z=OxAaa?sZ^0oq_cfu zW^3_*qe<^=V(f$v;xTai+=K!H(dFV81Jr=>9uQT zvPeisNL2)|qwC&`1~379#s-|CeH=Fem2JPx&o9g@EEXNlMjo;hhAJ8fk&wKJ#=c_6 zxOfpowAQ*hP28J>hK5qO8LMX>H@kRydOkJTt~4|>Sfs~9M&8`sHq_U9Uv5I!K*`}0 zm(u{7@58ahQfYLIJkQ5J;WJcKA#H4lZC9z@2BRl!`#+0PQff1x?u}5`=QQAR zW}hxWS+uRCGB>VuI|!xTdOW`1xqk$tz+c*3hbDD**g zF8{$jrTtbdd(MO_HYwp5n;FA{xq#t6k%4Dyce`4e>X&D6yxksY);@MWa6wLuj@K%G ztt@kLy*EOKRZ&>@Z)8M<44r)|lHcWUGKP?sDguwkr8FmpxZ_0*%X7cBHh2MguNkk= zYGz(=LH3ZO#n~ZyB7X(*BFhST!8}G6yX2VN_6i)nHaAUrFHcl^HnxC0=gd>h*R`a9 z0?4OeLV%!(8_ghq!FX%u=cpC0#+JLmz3!TfwWJm{|LHfB@T$S<_7U%UJtw;CDc9%n zyOU%@X2y;>)69d%1l$Hk6nmAwk*!%@pS&j?bu58^?b1cke&|NJm;0R$imrri6U)V19kdBv)kr5p{wU(2& z)QNAE@r`lb?-P*}20gd4<$e}MmuetJZP1bfBg7v2T`KI_W2KM9`r`Xa<&X;Y8?MVmFSMx9?DAg9u$Kf%y$CHwhYB$>< z0g|$^x7XLli?zlsE-v3XB+$d50f3*QyB@aB(8rZHBLDH}2_6FCrLwZg!g4K@za6wc zhLb^GUCB396j@qn*+#EgTmpN4EcUCPj-9>x(g7yp^?e~oHJupy!J;qJd3~KXI*OyB zJp18Fs@pLbH5>>!Y_u2L-tOPy(|?D8Wz%W;X^RM1gaA!lEe{bUYY^%Zf#>{d4E>_2t2QEPd|wT2)*^B9@3> zn;PqI302AFx^NBiP!X&Q#oMU4CfR_ATa zTAY2wy&1@*X^wb|F_xO?J5LP45;gN^dh{kCSUBPLPR-tScf2mTWXU~gH~Dq+(nV3e z#p2z?PqNMMZ?@s|q6lHS&v--<_$kGiGZZZ`ab6}(Dc(^95kTkb!~Y4#`+@moQm%g) z#ckf}{q9Fb(*fjP+U?h!hIaRhxBIgdd`>$}Ev+fG*W)=_1qB6j^MjP=Q8`IEtiDEu z4I~}C*NPV(CI-2g`0{dhY{pQz9QiNMfRLi9%k+%O`tJTB!uC$A%P|=yoFW0In=4X| z;CoBOi2!YdZCe}u(rL8Ky`#oL7(R!Ipbr%dZ2^Rkqi%((^@QM?W@-xO-B7}OFic)f z&UlcJ9}gE>Ppo;=8V(d@uVn|K)h0)GHw5h3SiF_81=QWvBd>AreZ~Cwd9}CO$%8Cx@ZwpIH zF$swijvXOp3^7x4bI`wk|3Dy0a&l91a}9NM=_2KLGWeie0;)}jy861>hd-Kh?Ck8u z#>V*g8RJ>J?d|Q&R&xQw=0pu)Mfo$EsY&t8) z0V(}Qdr@6b{A`dls~$c01xfg5-zE>2yWJleqB(QchvGbN2K1z$pTE3lfxGD>B!Zvv zBqBEH2!M3(tk%Qn5-T+|H6NeP8~8~}OA8(zUS3|lKs@Xio4WSS%y_GkF;pQK$9W;1MZ!zOg>?9@31$*CTr zW467oFVgAha(!MMnVHT|Fp?g80VGtRd*8*VZ}G*H*o3J%;86(<4i7DKw9;BymmZ&w z8?9mQSfQn{2Q@C)9-^`_&OC?frIp#Aw-4{u78o7%uGbn}nUCUmIPYp6yVWJCljGva z-IGtFH}JX0Ci@3Jr9bm>Icy3^NlAHlco-TQYH4XXI5>Q9IDkV!A{6xN_)e;%p%EJu z#m2&7W!IcU@@sK%F*i5Y`{CTw#AK2!I-e@IM@Z?`zF$O%O>Tw_i3Orp=uld_R_sb6 z{JXN2*3VKo~W>IB=VqTq+{JtDwEg%*JN1wf-lF*6Uuj+xKO< zuyC5w9@+hvjhRMzZt_y2+1B#M_K@A$zoaCp&@!i10)GC?ArmTE+LPmQT-+l~Ez4%h z0&C-f!aNAUTU07NlE&gJ{q}>IoCmJ8Z}l`Y@7eyc`m&pwLZ-#n?(32m28VSHiEE|Y zoCiOPLaD)^XPvu^HS^}$bmj)Ps=rL9(?v1~lnMg=Z{RAO<~H{WA|j&d;^O-geI+5G zzwzWUh00~s)#rU-C>d&!%(a>y$NKf&f=r4cA)EwGObITiw6yf_X`L&8$J-#M`D2!3UX1$ zt5Hi~0;$cj1A*nQsFdoOtI>-R_N)PCQTOGDw%Ckc{v3=44=!A>MEeQMyWZR0UR@n6 z)NG7r@h;RDFeXXAzP`GjExT_14g4w^3SM3LKI4+$vX-c-k<#U-_jqf0w9=e(bOa89 zRPt=CEDoiR3Lt?CHNpus#0er{1K7l-$fSPnZnS*@F;jdoW^v@m=-FaYQ`NMxl0H6` z#>2Crr*Ddhk&eWod47Jnx{Bqre@jjuNcgkQclyM(%p|Ga!Ih zCRx?ooY=`B_40CyG0TRTl7?n*MTY`|W$`pmShxxn`KN(1Tp~l9*TDC+-J^z*KG9IY zK|crnySCS_FTZNhu+p(M^tQUeplULM*56LXPM{%tK28f7OOfCO>CO+bWOCBsU_479 zo6mBi>$OU!*{`3dTbIG$k73W%4rtG*H7!j`RW)&|MzHQtuG1~P!}(x*zDkE!&`&m= zEVw6^>a&=VvGLCNT6-)W`-gv!!QG>>`Uf~zS)E;62zXo$!_F|oI{jXsPnYVO?KkA* zv; z1y5yaMnqV8dq$+ynid8Kp!0QjCVKC55k^J)6c9K3o^5WVg?!7w<8U~AUQw?Q#byKm zrNf}Gi9JX|05H^fy0vmVmOUJ=sF#mYt!yfJR6suShmS)R&1z5#D0RI(i`r|rdbFR{$B(BW2~La(R6NZ?)9~km<*Te@$5u;m@3`O z`<#lh`oZq*cd~Di~a8z#wD+{+8o)nmk>P!=t<}jPjK( z2Ce^0;WHpoO#Nx$faoJbZnBuTF-2Fi+Ff6&(FtZW^MEHUibH_@>#QTawpc9TraE>*g^TB z^72-pp{7z&m}O;W15sD2e}tRmG8E2N2NqHas(kG>g<2Ioj0WSz>&-l0pD5=KHR@iw z;jf-FC>7+}{jw5AlJ0H?*4iIhX+wn4;n)ft9r*X!t|?4+-M?D~PZvvM2(+v%df+La6xx|GRub8z@mSH}`W zA}uXlZ$6PMNhbFuf928PdNN;DT1quP&x(Tx3maB%J`vHsP3+*(&!;ev&5w&X5Z3>i zK&dc3G4USG@s%cr$be^dY#?=H&na5F9Wnbw!z3@N*wS-7JX_c9WNC{1y*p?-*H71O zWC&%W*&&~1>o6!Vi>^ht+EJ&5x}CUCEQ)n!xyFm3*fM=vaD%t406t}e{Q-%Z!Xmxc z($f=MTO^vP?bxdO#rs06qyQ4up_Oo`}A|TZ1Xo=>=_oU26oaf{!ARrl&GnyDq@(j zq#+|CQ&Uq5KEiPG@>Z0VMiFq=O$n%PmzNh#PF5sP5LzspD&J(p9T=VWO3 z(E~}pN6M!^h~Bp<$R>TUn*1A1^Pbx3s3YT~yE2kzcct zA{FX)6R|mvcyvGN44bi-|?fJ!Bs}@q&XaGTS239&{KrFh_%;a#eUCUi6o^6UL z90%X1Oij?YMpyqFeEGyVV;7GRo|oEM{FL_=#wW|4JJ#Ll++oxgDwn}AwC6+s($m$A zA>w~l@ft9AP8~AQX|`KyaV(If=yUAweYwxe%cG#6kb9Zu^S-xPZE-w0I)WBv!ift1 zLRqa$NHkewHopv?zraCH@bIlmn&K}YfF%ts2vwO{ zZU&JG=$I^(Bnd?L*VN#yKEI1sWEkYh(+x>w<>?m3 zo%IgSfswbm*e}u{apdN}yD*TNc(3Bb^HRgdm?I zP&Jvr?{&-NahY4|`0aCJr@i@T{Oi_tL z77;(Fs4Y`7oO#{t=4x_6Qn1_6I<^JEb;&;CaZT1K5VtE895Xl6mUe*WJ3KEK^zwI| zph08p?icOuHBCus-;}HuN)#BqUy@1TqIwSbyxp4bPSS>lFP}n$jv$|gR;9by`Ak|A zDNMF1)y^x_TWiWC-m6P9OOK3ZSSwhh(!WDk)!26zJRrM&aksd)C!?aWn6K1=3>TCw!6XC@bK{U_4SaD5CHJ? zeN`!u_w@4O(C+^b)TA&PphM^7=R2LRa@*V6KN7IZi-?F&$Y)YvMW)H_KVI#)U#zd? z_H2KQ`pC-SH|qUKOrj_GAGtf$>b&&(w;DHh0GXg{6$w?josG@z_Vn_~O1=i8JnOi| zOCY$VWn^dIs;=HLLPT-4MJ7dmr5T?K-0-_AYNgqpQBV8roG_OPy00aR=P8q~Y_1%$ zL*?TnMTguD-+qKR)q_o{^}c+N=f=%l-R&NfMnVk(oPi<Pcy7tvCM$emv<1SXt}wIqe#({vdCo#4&)u;Dr+T&Q^y!@EUJ=J`=^4NjB<)uTw@Sq-63902R$FN{TEvWYghnQZSBm#D`m=S(LbV@? zBkS3I{EEyp?F=SlXvM(VvU5dEG-JfyIX?plDva}$X8W7{F?M!#s)%W}s{DKwpU2A( z1Z)mnbeupThyBsC*Ov!MN=n)$L!9|$`;D;-&XvVQHqVR^lRBvc3cU^wC5i+~3yYtj zp>7xJuNvG>4Gj%}P_V@%CEwtti{&zY{et7?=YJ$%7uj`siom43zu2g8AVNSwI-9G| z5G5!LEJP5C_he?CKqegSaF)>2kIAPBGAh)K$uBhBRAWWg9T7ZzBt9q^RIXNgmt`xd43%%E!lU~Q-zqQUl$n`iU&*iZUM_%`R(10>ocrKMt z9G30M{c6)#?+C&=#z(;=4xTPN5-fNJ?`#pHEBE$l;`4JdxaezMTnv|Hmi9MechmTZ zO<@F)EEAl`t#L-z6NeRC_T9^MX4ace*e%tO^YdpFTS5z4q|eXJy12R$3iz}%H@mO- zHcQ6)Jl~d)!u}8!hY?faib)_F+Hx3(#&7m{x)yKzTd;)+2krZE?|Z!qA4F1JUER~u z)7G7C9;r&B*W!>zDplIm^;RGeOGihyDLTv5>UuJNxz!gUk{2I8olLK@Kc2OMI!(^X z>byUi_F*F6Z5w}lTsS%TQA-GTi=#si7*3K&%{0WPr+dZ{A*&RpdV7hqUay&mi3{kq zb1-rw7gJ$?q~cAes2zD->#nY9ukNZ+4nOTtQ`^fn9=wEKH zG~4ef+bV=Vst_wsUuIYrwoe6_8doSU9uLe5%t^)J!i!QiHot+3x00+rqL>m~L@A5v zf>&kMx@8-BHMD(Cv!bFRDk`eO_P_AyX=P|(9K=vkzUty)vy=I%v$Hc^x6{M(b2}rW zKwtWAI$~n|36u&ye*Dny^h!!iO-)IWh%Y4F;}AyWig`Gmv%cEy*K2pP6%ekLk(TD; z=T}iy#z7p2!ews{dF&|C+nj}3pH+QkoZEtUnLYy-orLCA^Jg5y z(3~6tAt9mH0lB8e#<9^+-8Pq_=ev{ccJwsGM-HyXp)TK|8UtG0Udc2>VN^L8nU$@+ zGfLUXpVuu!62y<-1@m#T(+z{{ct{I8^IFN)%zUciy1L||qU@|Jzc6GoA|f8!Wgm8) z`pV+s$GM6QiP#AJE;`?rCK~>%xFJPEQAgccApB%=v%}(dW2}NL6u;=l-uels#h1ft zP<%J}J}A}tS!M4uuKu;^ne$)ZdQ!KJo4M9^FK96p0N@DbpRimPISAn)AoRfQ`W+P& zm7AOU=g*&o8UvXkWihYsK!7d-B^)I17Yv6L8M4!&N|Pi>rd*~ z6N(1?HDv@1nwgpT>hcnY*R3)v40e4qR372;XI)+0&!0bQ(#=2LoutrdT~`=PRp~T` zBH>e@hbJZ__4W0wt*&kc&q!``s;LPG2-Mcr!Ub{h@aVU@$*HK+chNLAG|Mtts$iq#qR7`msrg_SW-bDc7d&JoPtWVU5qnXQ z&p84~mmX9>RCOD1(89xe0Du8<#6mD-V!}c&uXUhENF3Vz!AzYL4=pTN#3n@w7|K!v z83h!>mtg>Zr{>t*9BT==>(sja=+x9K%;BJ=Qw%b87-J?nxiv&2Q*mZ$Iyct4yzwoh z$trlP=Q`D}H}uG;Acaveayzx}wKshEqY8C(SXfzW^xCohbI#RPRsFYfMHK-Fn;bPR+>R<>Epl;F|33FIuWTW}u}#namS4GWxi)d7@!pFgSg{ zwI2j}I9;kQE*96);-;V|=KiPgDE1ZZ$NlM21k>vN{(dYG|MWslj;Fn|^G$qwytWi} z1Q}~@-;UeGczA@e1!joC@3OG4o1jnh-Vfs49AyY){)6IqKl5f1$| zbSS*|3ED9=GsD8h*7%Px`Y85Ee^+YO_V)IQXlQ5{7;Fp$eGa4&`^++w6Kwq|4LkMK9QY7t07&a%#ealNT|oi zO>0fA_vq=#ywcpwW@Ii7VAz*ZQ$xZw@&G8S{M~l&*5pOz1fhv z1%4~~d3%~s@BjVv_rwG&Fd3jOl2q)HUbkx78W;i5LFjtgy1cZcrK$O0!ErQQG)eL< zLXmKHw!%q66VYRMy3y^w{V!bZ0&iz$ho7In|3__LV9!VjqpOj0w79II;^gj7LeU3h zYv3BaQ-=mUWxX)&c&@v$)t9G%0}W}Z{ugNJCPR#> zZ9JI2WZu%Yq38Z;;OH*)pt2_OlN`x~3u`=m)<}6CTzM!pmA#)$B}87hTl3g0>z3w` zeIGR*9qPW@zEo$50OaQ9lX7w4Xzz57W^i6y?SODXpI%-#rPd$;2Pdb`@bE_UOa1-* zzR$P6hfFTJIJL#2@h~wk{{5(xmXXQI%v|sE)_CB-OfwODqV)6gdkp%d)6gK|<11s( z4Z}93tmdjyXJVwk-e5j)N+}!A_6ahOjdQbdq(&~OaQLEbV=b!PNxHgM6&??7wnnWx zRKOyw)J9@7CZGg@G)?mN=s%%3L(`O`ot4-FrcL(-Hw#NkH8nK|fQ^kUThQOm&JNl3 zIxsFS&T(hpH`&p_f&1xVZLx1{U|`@(v0MR_)&1!bulxB=_ipAdXlTqPgQ&HdmDSZm zU%sfM_(<>X?}vnh=rr493HrZ*R&IX$IH%K5$01he%rRqjadCNgXg-}o5Z+4t1`QcF z{pp(4`Sxkbvw2@i5+1=cx}LbX{lShScx@7voQibUcJR6M?kMR90Md(@F-|O}oQqzh zHNGwEf2nO|pz7$y=x(;0G3)&aKWTmnrKP21yV8^-Np`l}C?hFpflTXfHk#^qy2wlb z5)~EgG%7zGkW>9Xy1p_hj;3vTlaPc24Uk}q26uN|+}$n9;_fbiz~W1Ahv4oOJm})? z?(XhIVO>;M2+cc1%VQftDTB?yzn*#5vCWwWpUS4I+k)Xc<9R-t~fx~Q9TGf=4q-14F60SxghzeEbTfHA9Csn_GjoaKbVn{&J z0YSE(pB|nbZW5$(O-xKaefp%Wt-YcYlAcZ&314V%+_|Jy(FgKguimVXfBhQj{;f2g zo}bgYijWOazFLU*wU=8Cotye5@^XcsO-H^TmkLrbvDf1p z(~O%5y~86$9G7mI0__Asj(VPdYW*?zVtw>d={f^eGdg+qZ)9+>;ZwqJ*w3u!EX~;h z#JbtQS{K){gCfhF`Ib<|}E z+i5D|+}zwJzJUUe6MF3$v%B*xF4${`FdUx0?{&JnyX$eaU#MEdVLh+g=0jisdXJ5R zGh1#T7@C!umPW+qM*RF7ML9odoSL7%m&O|l@iTP(8Qa4FW%u$)FFMFs$VH>x^- z&B0Gk5Adz-N;=x@Fjwcfsg+z`_ix0^f@dc|z9(o427joDnf$@Hz|I9#Th{V!J~Vu^ zUCHa^pqB2MKO>3iUS7@F+27?Retkq+uD3N%d$@hLIU(ZrV1t6;FoJ{S7T#3quZ!15 z3$Jax6HZMoM+~}ufBGsQeacl$PD;e;-y*PU{sLX&(l2)0aiP_~n_Ce1@df};PAKv> z*}FoUW^8Uy6tR@_w=!8e6uNn*u3UUh_YQ7}{g71->CYzFxf-jSmKlir(dpjCx z0mkK=|9w()G+bn{#BkIvzF$>O6U`4z5MW2RmbW;?*RkhNe9U{j(eP~ zV{W|fnrJ+K3he#&dJOu_v)K}80i(+;p5ETx#U|+bZ9Yfa+dWK!gGsC!C7N$mOunwz zwmrGro`U^}A0Hp@uMTeFG#uz2&QI59SxpKY9J%B5hV1cx22BoIn@OxB;Q#=jP)4m@ z(CVct4D)M^e~{ZX#kGVdku!(=Gc~!p#;J`;FGZWF4|fp|*!d+$vnx4R)`R;hdDP86 zyAl$|!|<}8BU>DLgA37`o}cGoXP@fsCa0q-p>btQWde5$r}0Wfhlhn#|KvUUnl7IG z>VrF54-_Is{PfA*-u~`zz>vW}K+wesEd3c?#U(uJdcZ-##Z~_2$4aZW8i&$H06J8}@cL?9DEE{U8HIK}OU{ZQ{dov>=efm_WQLe8hV2y-?L{Cp2C%tvL*6DgQ z|9%DX)xg1_DlAOK$EP(n*VxVNZ+iN2(8zXIS1JKB>D`)0JebM9!g{J`V|%Cv6*Vs} zuc4s<9!YdES54W44gj=%%F``*lqJtIy-(wwcnQz!{k^?Ab)&vuUDK4}c4Ha`ADgxJ z+&S7~o%l{EDsRO$CTitx7hBxFL{!)IJbW)s8v*@*>>Yic<3JP}hRx`6efIeHn3$M& zdwW}?rLi-d7KU!I+?iGJALG&-mv_eI_7DAe}6cgAD_f&^`BpJGv6&? z@vRZd++4M3APB6jJ^%B~yJbOn>bRNh;icpCXr~(nP;ZHRTGY)6TC2;@Z2KD$(FwKy zQ~-e3`Ax>YW;Nt7_Ezai;tNica^m>0P}7=Ur(-O)V5KBGiskdt+Q}wvA9IYM30n#{ z4+3S1E$Hf~f5=3!3tXdoDr@d6;f>t2Hh>|0id*x^mrJR0zc9&EOpJ?ruM+V@ z!^h8WyWC8@dht@EB60P|Ei-{2HBH3Y<2c9C3LAb&KatKopRI(9f|36>!V=7r{Y|t9 zD|%&MHU#;^kRcb>g{4fBpiq^Lnk=@q9UlpOpnKX~vKU>)>IB`8LrJ>ONar-ftz}K$ zMIW?W?m>Pt*U&AX`hEvjMpCjstC|9CpTKBfGgC&8nxn0yrNxpI4o+wwm6e0ltSVT@Z#i5e^x~rAMHqyEZ@N}FG z7UHd9-xk;=uiF5cmVRJa~aLVl4D z#QzSVO=Jj_@;_fd=%M(qe)gbz^296WVoXBUc%U+%Q*xL3K!s*;q^ z;nk7h*G>B3elVK#CLQzbL{fRP8bOQaY=s_45*%>awnf8Xoc9C8og+?0w zBZu2&LzIc-AhJ5H8{z5Vtr^4t?C_r2-QFY2T&++5qElzpZm&xbGgY9JJ;|Bw;4xw? zl|cSxWVuJ8B_y)3c4+1UNvwm}-5l07zO8X}*>HxZz`M0!Oqf7Kn48zhbqoB9{m7#! z`!`}$JNu)v+wz(mvU?(L>qBnq4L^}4jo~EDhK6>uVNx-4(R!ODME}uY&G$5aPB-B7 zJUp$Qx9ISSWC9-9P?*c%+{EOh)6@MGg0OCr%hB`GgF&$=U2$DJp(O?nDR>>NL}g z|9a8wEPLQoc``mzXe-y5ELa?X&uNp&<6IOJ1g}REwXpE;@c61VDnb!sY+@px!cl5e z4Pd4I$jh1hfWbcd_-Lg7374N=sO{Uj7tY2*ZKc9?Bl4*%uN|J@ z&_w5J-TG6lRmGfO^Rjo}o`c>$$}QJK(2wQ9b^b_%mZoqcLw;znVr7p7n(8rV6F%+!2D903;G8|)VQ*lV4? z@Q>%+j9V%5H++rLjv2NR?(*(tclvFTfM}!`g*E|ij`PEb$^5$_FY;Vu86?l>b0gu= zw*u|1OfF`|6GctlHx%k}qDFT^*}TU6v74Jlz?XtrRwgDUR@MnP96mdH+ZmQFpT?sW zNJE)0Ffl%k4iX7MrH>&{Js7Xu4oY~)+P7hGI*Z_G+ttZd$g!^DSD07S3~&;V$7b@& zL?jWVrny7*z8^{5`=ont|q+M4JXQZz&;PH#xp`x}2COSBPw4VvtC3 zJiTj&Fh&lUaX{oRxEuWqvLU}@H8={-a-4EeN3*lD-z8u|`^v(i27gyq+5~eI z(Y<`0l(Of`4I(cDE^cbniq&6xk3FvTYs@F^Z%!C7ygjl5jI|Ic005!=x6;B2@N_*3 zSFM*HPtiIuli?m)OL4w}kDlVyxYa2`(`yHhAfhf!E54fJ(M;zc(tyuXff|tV`?hP} z)JLvD;t<1vw`%Pdmpck78D$M^A3B*tGBdM7Ahap!0;mF4gZohk$QkrH@JOPai#wPx zrzaity6>XGPK-WpKQ?XCHCOt>7-U@kS%HH+j+kfTIuDn1<|Dc9@0{Iv4lA4Mef^w$ z{D-gmh|;!nnf3KIb=C_uE3GJBxAP(9_xH{2k@Z&KNegAtJ^Rx?A~(kd?yt6$!=s}u zhr9pni%{Pn0DeaQ1mCY(-Xi$ggf)arV8S_o1D)vtmNVGCyuU&@qjKy`+0NGT}Q}SUddg#vy$3I==$V-e=*si3WYetHAF@eEh#j%-EJEO{AMuF zpors6;c3!o@Kn2TV6pc%Ny3npk;$eidZ;gZ>4*J2yVvMD5R7Tq)YEF?{YIj{5vQSm zT=%@nM0*~6jt<)5hKHo2;KMfP272J|nG!9`q9KK-jKtlUI_u|!dalTw{euN}II8}c ziJWGg)m&c;WmstFE6Ft(#0e$?03MmloZoaClXA?>n_G@w=8U0;U)ZIGD$%z#%vzPs zRq+mN;<<0#hPyyrRFY-6IZt)hYea|M%5?<<8(SyT*4UVnGLta9B_Ye-vb|W=_i!|S zj<~aFT11d}??HQ+TE}z6J!g9Kt9E1}U1VU;m70obbUCO@qg-E%7C-HVLn{Kk%4&S{ zvGX!^z}JC~3XPQ4HrSL=DJN;ur2#m1|=1F>-{}R%iH#9sjKPz{@Vf$gY(Nh z735BYx5DpJFA~^F)I`G3rTM&fg|FLMYPhDFQVt}-`O+iML6W742^(q!xw+(0(UC-g zPz#l3(#NN#`5L9It+TFm0ZMtcr)Lt{VvX`1dp=6aoykHKbOiw57CZ_@eneCW*&Aly zeX+QhArkfly7>r+6@L4`sO#>!^%#GV|5t%}WDhzJ(*U~zB)oa2`>az>Qc6XCYkj)Z z)ig4m-o4Xf+EaUN5n(^m;8kZeyh4rQdLIkXt>bvV?yT%?7u$cu(ZX5%IZI z*sXO4c;5@DzRC>Pipzs!CQVJp`r{^jkN6j8EqpmSvAzgTm50Ms?+KA8*ppSYFca4) zSPMrm&M_Tgxh>>}>|`?=6~ziME--B=7IQR1!MI%{BnoC!EQ3dJ1144ZtO^HhQ?9J8 ztmt^EX*8GTTQY=^rdMYcIA5Wo;PtbC?F02gE=Nk5eW?!^I+NzSUOj(9-r;3d_kASf zll|-U-8}i19(S$YOrgro`PP7xl+@{viVYX6iNkbwV<<%{l%+_`viIs>9Ak27YapTC zW{HP~=YA-Kv(|D3dioad5A9#SV-9sem-1(o?TEQlm;s1rx+Iu5t1X`eyy z#u0`Evx~DIPYC&BJijGg~buAa$1bMD#Ltyd>|1KUYA3+^GzwPkk;egsPCOnl!>XS zq2XbuS**gc19FwQ!9Co`K2D_y5O5N+p^RA#!+h@_Pf19N$v#?bKS z@bc{PRM(XD%6)>2)#Bpfa&&SSqTD!k_^rbx(DurUb`GIBmcVf>KGiPqomxqJ=@^-yf)ILXdve1qva!IC1v0| zwq9PS$*PeRGw~}D5~ik#2O)mJY43cIv*Ln5wBom)<*e)iE)WSb;Mh^51g$VtVs>;q zoRA1v^1N*fM;W~V3y&$QOY5RN^W{z*k}`TRC}BbJ7h{b|9_v5!8jf0Ah5C&{QtZFz;!Md zL=!5EJWvT70ON?SB4n&0xr3OgzeSOLQ6Ss=M4ltsksv7sa98 zgoGoDe&`{Eh(v+S*-uo9)#+(zUrWr@rX$eg)1hL02n6C!Y?cf)i#1<%sF6vi=d>jS zx)QJz3=F4nDJ4&syScgXdEJgqO{wu}rE)k+NlF%|m*OE1{l_B(S88W1FMe$Yt0{jH`=O{h_8#gxC)gLEH>~ zf+^q&S9|A6lb{?1S;$L0#pjGwBsYIFUvGl*WbgK4V7=q*>6#*DtG(0^6CWX3CzB>l z&S3?ccaBU#y|6G2j1z~m?CJh0cUjTv`O%$-hzJP3I6o)D2vMY(G-LbS2mlB%wf2pkX`z(P;Z-@qHwcan=jkn*28R|=K&skKw>+>O7_0}j;zi!A zXf9@Md$B^XO__(CyHntBuIetfp9PWwN99RMQE$cSiWSGkDi0M{#?ec zH>pHY^>zFFP$UPf`Bv?$<;;579R56`c~cjB`6K*?-{iRnh7o&<#nh$Gqc~$H3wKc} zotSz$je>|}4H}J^SUQga?*I@aDOUVh^*!5z?MF(KZ0ga+8`^F~&zHI4kV&j>-#WhB zQ5>OTNL!)@&}J4_GQ8=4xT$ z)Gjy=TeI`?dHMN_niZ=zE51P&>j%op%0?`>k??G)&sj?QWrN9AMi(Zq4WQ@EvHPx~ zR!;CoG(z3Kb|jJTf#KodzCK~ZvpX*+STo-HB}h|2VPtGfi8QK2tGZ_hMLXvWU{%E~ z1OE|$Oc=G8^YCc0ekMrQHKE}<>em7!^<^Du9Y)LMrb^!c!R~+ET5-e}A$GtS{T{#a zf!^MKOvsH9ae)gm2?EPifyRmZ%gg+zK&qwYt+NeydU|@T#S|X5gOQh)my^@w!{_ob zGaTsM=?6m}pXbgXvCQV#0`m-Tb}*l%ely}iAWJ6Tv+X{G&kFLm&tHD>JmT;&}@ z>v4&RlIQ`F2$*3BdAEQ5I6``uENVkyCjNzC%NQ^9DO~PNNJvQJ-NI);UZAI?^O z2NL`z@u=z|$U9Y^xVYXfT_){?X*055;F6${e zDT)i5K^baUKPt6Xa~+#pe$Kx)Pj$h;h{&BkhOWl5dIuLz)-tK-Hp9AqF&cbJFqY@C zoTjrsJ10f%R905Lzdl0xi1@z;C4TsZ^7wGSGt{>*=WI&fsf`2OD!iCpG=NmM=bat* zP=1&1Fnc!88;GZ;4(%Tp_@(Hj;^oEH$>e-69jF)!%pLbHO~*pPSo! zebcsh(m(QzGz(;d+0Y9NqFP$`LBZfeLnFrjpJCKT)rG{p|tQ^%Tw~2XzwtyI*L#i7?gwaiIC5xKGKcl&sk}`F`P4)V zywI4On?~oUg*y5m{^2Cne6EdHD=Vu;r@gl=-GEnudpb~DX5g)}W8L8Bz<96kRPO+1 zPTk)147s^aJ)RY|u-mAt#vsJ` z$fFo$3qgoy$OrD89QD|w0qAWe6CBnpd}&vR0qE;kQJz8Uwu0sp z4WnJ4%D{+PYDUg$zn7vl`WBNkg-q#uH-mgds!a#(fhxIVHa`m$&>B2aP|yusq+o2e z5(OSXo00Z8umhLX#H(fPeP_kyrqM3_2LQmJ^UbLxjWYHT+QLaIJnaS>%^(~p9`UrB z>xI$hqGc$um9J=&$|nxZ(88jB1n zeLv(|*5Kz{q}v=TEsc*?-Ty(Fd%Xj0l6GujZf-tzW=He%@?eZaIB02RZfc!Mn7Glgu!p zM~f9&&e_anH9Pw6pHQxHJNPZ&C!?P__GxkSDY?i#syo*@xP8(8Y3YWu!b<1|!qAw4 za{6uh^^{KT%w4s63_rB(0HRTbaYZf0;f-I@m_ov$bgi`MP- z25O3o;ZY*k{8t8r8Hx@{{MYX|yo_QUDCy|CG@KwEz}Ba*p&4Mb+>(;~+{E%ZbBDuX zE*y1e!NqAa_A=qRCr3}ynd&`B+O-ZU!>$o+2RbPDHxG)Y>tXo^1ke|q>E+=KY3*iP zZl6c4j1gBmyPuy`Fv7(hYb-US3(3f%ecrrryDK}P#t6xiPrHwUVq01s*eo>)+cEDhc*7?4@zTFb!vSpU4Nb)6eX*x;Z4MgcbuBX=T|P8zW3 zIubzp`dJN*JE#Ly1Uyc!pEa{RJmhf!h40+(xham!H$Ea&{Ahohsdzh=U(?ckf4TQA z=o0|Y>i>}h5C{EDd3ZA3)+Xc2UMfK3?IY70{~&c^9`BR>>?OJyth6IO#a_TpvXeA6BhG8C{ z*gt^v)uCkiAhO-_15h@Ui>-bov*B+@Opqz>32GXz8&}GC8_V-g=}5_(FQB?13$OX9 zk1>-r77=CQUwgW@nTOZ-yHXpcdw6vH}+BSO-?p0 z9FMDmMKLMmb(>u1;odxABDEG%S=rew&CRQlZ~jwDEWVr~v;aM?91e5AYzc-8);=|N z^6Lc2xdypyc&^~ZTci#8+;{>D7aV)Y4cO3!VR$dr9Qx5P*88bk&dZhuv3}zr5#S{A8DOTSup3kyizPa zIrHGf{zFa7A^@Ev>e<%+7t)m&B1w*tqLozG4ZG=ZsxV>{+1~#C=dasvtlYeNG#sJg zDQK;Q^X%U<%6Ox-j=&U7TlGTK3_cqO1Y&9m-?>B|dJ>xT^G$yiSvJ_14X?6A*avmfx6zpDY|Mhaa5gCTfSVb4M zu`*01I7njWhe|{eVDaR$GarDrIa5vcMjwf`GLRjc zO%>$8B-9uv$jF;dlkH>}Ax4k4XTC2_HUB%Zk|CVjE8QOVs7flbjwSAt)<^C}lajyG~BGobVM3 zD*y@|XXAI?S1q6s+#aqnE>y_CAe%FWqki{%$k0#k4#V~xZ|vB)z{J4#Q;+i>PxzO= zpFFiR3KkjMO!RMfPwA0yT5?=CFe8T3ud)1LF#Sm?bk#8;EwsOnQLwO&jL*3Zs zuvB{ZaX?+0JhD%*}G9?CF?OCe=GR7=3(k@sQ|c41?Bc zc7L>?Z1HVD6+W*N7DitLE^LHCEkIA zYGjorPuH3DU$meoCnu*K7{LP=KRGH&sorKuGCE-6{i|mQaO!TTyf{!ebLY3?xU<UvcX*ELc_DC6(`xZwmGI2GUelawOh_TXBNF{E1gu&_g=L&cUL*&{X9MNYY3@J6SUdDS<#pv@kp=|FJ#+b*rDh|N1QhJb9ch<`j@hVBo=MIU zq7igalioz^wGdNblLX*v&M+B`Lt>D=fO@kQpepzev!^op%_B%iNS2F#nc?=r!ou`A zbpaC>o&Y4o<=Hof^I(5VWPR`C>Ky!0*zti5n0v_P;udLX1 z-)W45KH(=hlqn{>x8L0m6gthg;xVH^lpEUY7}fqGtY!L`1R}0!u&k&-&*S?zh)$yS z%zMNf2JNSZo12>(P9`QvIk~Mfx0RSi;(*zX0-2`zV_wWlGKK_Du&HLXebX`|4|ZPj zrPUT=P4&}^tL>~a4Hp}aN(4GXrJc=m>rHQni1s6A1~VnvilFI!^3PyC)V(@QY^T3% zk_AR$?!!ER2=ASO^PDfM~6@QqS^)iKP(j8A0PV~i4uKoTG@d2^0f|7!XsQmIS zUH7OnQiG&OCbHE}IPsZgC_(5-qT13r&vV|&f}RR`e#frXxXRe2v$L8K5)!bD>!Sru zvr*y#2WDnwd3kvt{O<1V?*1Mm)QXg=XjM_Ew7r=)Q_4%jR%1xv^X?-mpT{MYFgiAa zuGvZ}Kal;uz2ndEgzUivpeOgL^S|s(iN3%-x&h)3oroADc;H?kvsII|>0FltLR9{e ztJW4n&K!mlb9`JndiqxgjLI}<^U0S_8=sj`P*9*md^_B9;$Xc!7=+Jhh`>z2HrX}T zK#CQz@wcn1%XB22oSfX)$Y^tW+r-2qoy-0$$>za9ae2Azj~_n_4V6o^YwxcPbaZq& zsR92XjN;q(oKQAGhwRghfiL0NgH*=Oxjo7v2V=l?5>zmq-x+gP)mxC_K!G~zfyt3Y zjU{BEN6`qea6lsAuJ72LJTs2gppg_o1hyo#K|izwgiLMc6VnBRVaywh%hlRxvKutApqTZZdJGS-3A#~nk0%jxH-l+ zRMgr2AT@@L-#^ibk)dM!wOPUJzaP?|w+5utBYHbKI~m-L+r3fW z71H_oMn>RFvP}UMyl}%*sIWcVPTFA4q4_N>s=xE999L%!ms%X|NP#40ZG7s zdsD^OsnRQ3-D{nGok8CNJctC3M_WAa4pmFlGx$ASp6;(QGc)N1J|nyh&C-mIlO$tc zV2Hryv>DHl3j0Q1Qc@Dy(4Lc%<9Tz;?{#}RmMyWiw&u_Pgxg1xO1m3-l4$HOooz6wW{-!vc(nO{P&9k z1bjbzsqf66ir&fMX{B|gKQNXf&5{3GW4SS13eQj~on8`{HBcX+Vq;M zXFD0j_1O}UgmS4|XLlDn^JkY(DAf1y3~t-@q@JE#9U2;XeY8;Tv^Sob3WROg0n2sj zkK^fe7MGSXDgG0!0A8{Lt&5$W`CI1;@Su4ww_kA{2QzSp&vfjc)xGQPrnCE8@ICT? zsIkP7hbJu?I~xlvOCd3}OjK@8T(AgVD*U?}R|hU^tO5_V#e_Vuc96K2IJdvRlfuPW zV>LTjR9M=2RKBocwb>i>aC1V5NXo=Cy0FkhGg%lAfPjsS-JpAXcnHM9D^dU_Pe|2KWl2JI*-JR;}n{QNU3hZ~mPD2^m&K3s&Ow(`u@ zxyh*b%pgP9WZ>If0+K$bWLtd)gEO`l%O?G-VFjdJByYb<`gbv>ZfS<*;=~K%V4R71 zyyX|E%uMQ%rHE6TDc4^psLQU*Zi#9MU@Yu?qfQf7R#sM7S*cveMoQW-K3?UZK@}lB z@z;JMfzcqedp&{CV19nSL+V-&RA<$|lbe#qs4(mfJ==h5)DFi3eii{*X8^Y(0YVzV>oE@IM%QOc zdUZ_I=%1_+j2$uKgDwsuj*cRZf~E+rpM_x?7)TgI%jGc0Aswnisb>sEBn zeXiDGq+<<^J9unnikh0cTU%GRXOK!wT`fyYxV=aaDhe9f&c&UNkI(OVFGe-}<%kAH zEokM*VgucId{GMHMT1P92_nad2&eK=oAZ8t4&9i z>up!&s!dBvOEWzH02)j)=QpcC6}YDNoXNKxkfGeAcf~K9f`t_AzFtApGrAl>z!P)z z=EK~>Y3IJ*rhE#Xgy~-iGw?HhXZ+SqOr{aqt8 zjUx{*0e_K%lSzIu$QqcL+B(?(?3DYquvO6@WhYT;P?kK;gvaC?&$sx-c%H|q{q@)G zDR3uL32UlEtJ-p=Ol?{~)p2KdsRH~CZV!ROmj2p*Pt{*J=&v!4$&Sy>=-#rVtMe--XXG@JWeWt1zTx9BD67_-E9T8N*m8Noh%GX!qr= zQvx0XHvKnc-A!OL5@k`vW?u&?aXOymteAizI2|<^_?5uoCpa+_!i{Q=NMij>6eH&+ zdaxVm7wYk?gV*X~RIA^pP)EY)r`ANQgXl&a=oc=MuaaUph$Lj|A(sIjWa6aAdq`Kg zAZn0gFcOOB2T(dXNsVE5Xm=QPHQhqCL?i?b1LLUoS-dt`Zx5%*OgQDsr^%=Bh@m5- z>aB>SM^(1>Kr;(WSWRkZr=$qj@P;M}Rc?+J^3{vUG5VHUJRdIiE@Zm8R#sl>SA0~c zu)G9(XDh(?oHhZOD*rA21?#(m4-398-W%O!TMt2^wN1mi4PLQL;4?-+8D3|w>if?i zjRd;6udV*dqC28NrUCGsZqr^?hgfd+qUN{G!mT`Qk}5f)RH`-7uk}1bF6fqK06G-R z1$}uyTjPR35GN=&=1*{851b=w=s~Yl%qGU8g<7=M7xD2{YMr6qnYE}Sw(-+y<^ko4yZwDz45Ss6^p+}zqZe}8}ZG@ihK06XB$ z>MA-8j%G`^sSbnQ+1c4rqjOkzc$a;%QnolYqke3>zTJNUIKW4#goXcD4wUy66JKkl ziWSrMg#Us_O7HV8iMr(P%NWgtca$PWaSGdP7u-{;uY033hX{~gwwYrQ*+9Z#-QyOxmOBPT!qWB$Yqjja5#nJIkCsaWuZ zuKQEe#Q3;&y$t~-rbzT=1-O&LdS2BbwmxyJX!Cp7Eu@X%(d(b&cY)%gS9 zROT1>9uT`ZPJ9vaQs!-H(YYcNC4+ z-6r!(wvBlz#g?+<2Scj7#S=-%_sW!*l$4nHRZWN&S63*_L^%IGxVgK(cCGWxj8ZuR z;c{s_&NF3tSYq7V-0wer6j?rpl#L{HDq~T9<4obMuBpSt#GEKnE55vR@)N4?x;rma z$$!pjCy{c1!w67OQ7^WK!a_m{4ceZEQaCMV%21|008S75)v*CSu`CWFr^iUP*rWk& z7=?*3*i<+Hzbnp~tAi;22GbqpZT_DZAZ($q@V1mew&!k)9@30qn?Y)j&8wbswi(F zKS6zY{rEUNC50C2^J{pd-ReJS^a2PRhC(Euo2x99J5H&PK3SrLNrU!UO#u{P$xVJZ zsk2-MLQ7VdCh}olLeR6S3_g@)FfTDS-w)zz^?hQ${xZE(^I2~3k(#~ z)JzNs`7}uc_{SLX4)6$=D$b3dw|+>M%oOxVmFGRu=^Xc-qgAu7H?pvhj^6Zp_pudn z5^8EG9=Y(Sti=xTz1&r*)C>nFDpI9#J5q=#wMqBg952yggw&85)R=u4sIsGYsu&Co zCii+a;9HI%;FUK1G#?1bFdjs&{ zepS98`7j}g;B%GpB!!G0=PKvF6=@!aGbvV%8@22p!M_Ic`kE>GeSM!vgGe|()41Of z0D=0gUffQ*ivGkMot+0W<$~tpIVUnN{b3w!RkgKKs5a))C36Qe<*)KKkS3(YbOgg@ zsl%@MsnOZZyu?D#^>{G|jVPL|!EOy?V6f7U$7x`&@|9NoHyJJl28-o1U4i8P@ET9F zw)r3`g0eLIuZg^hyrJ_e zD=WRd!FhW}3-vl$TCX7%poos@y4iR5DN=92PP$F}b_DJD4da67=B{z4}NM z*WdPhZ`lb&!Ha+rBRV=>42vXKx>)TO2bCrfH-7z`E|82IW0JX;U^!v=lOu)~Y!nVMqf;nAl1 z*5>mx-{1e4=IehyF%3V>(R{zXifh28_h}+H#{Qsw@T`jJxt~EWy|JRdhI7q6$pK}^ z#|iHuTsNf=Ppwic#Sj94!w5VNrs?C2nUQ0pbA6xhb`qH(0UZtmU%ILe_a^dphSO3K z6MOA}P%yj2)WjbtFH{qh5GrK#Sxdhj!+^Q zy@DLp>JReVxNxuIzC2HZhx!Ed?(DPm?y$LP(~s}pSJH){ub;VD&(|ceTdE&Smk!*o zA9jafTh5g6J8p+77j`ircQQ#xz}YRQRr5Z%(E2aV&eFqR!5ba~0*90Jwx8->kD{rB zz)1sM&+Z8c`s+14mM!7?aKs7Q;ILih^SCrC(Egv8U>ws}k+cKlz{MxC8eOPQizy7a zIg2p$VLy3Zp6V^aAOHLJ@7={thJbf+o_RExdGfaqQ34((9Ci!UV)at#N&+Z2addR_ zbxa47SQ{D|aG=b{zrdOU@$?$y`bz~$-wT#=k1ziSm%|7!_YX$;d;dwt!?w4!=4NNH zzJ7K0@X&AZsQvt*+Hq$%fzjYwSa(QB$cGOf6q^8muS94dfRO#yW#E#>VCnjxVeUrd z#dg_rqp>=M@#G!4+7WlcBjpTq3;9JO0*@U=$gi!c>U6m~Mz2#RDk@5a73#P%oW|q) z`M;A{tBhrch%z{==W+1yeNTFjK7S_U_i)-COj=!CO-#grf^WS9I+=j*KBKCr?-DRV z{`tvCEEq^jacfH~l`jO{Lco(lechyHuG(~9%ORTV=5S7heWSs0rYxD=k|wU-d?N4e z?oRmqyH{hr5V=261f3C!7_&Y#2S&X437I;5K8h~Bj_~q%?W2-}>12UYws=H;Z|~{F z1+UYtqLC3SNYw$cMu4qQnN(4u&TP+ z(a{kJ35k`3MftzW!NI{SxrZryWaoQ8jn3~rBYw|oAg@bFS{gw>i!8rpQ@k;b|A?*X zIyb$3n~(SEzcC@U)?BqW5vU}|^LHK+IWEsK#dpM+6d*^yIeMNVKJ5cG0dGf6Y$@%^7x9W(M8fCq#EKES#CNK9-oL9$7yhrcv*So_=Y=sfQ zICWNYRb$x_22C#XBqZ%UJs%9;{!g0oAdA3$5cwsPG<$3IeV{T}ghg*|Yj(gp^v1EF+{a3z1hQ6leU#GqCr6yMqApqd( zw?(_RfS)gis7n#(Ae=029wr*}x5{5~_&wvF_rG>9l}{DR{H2C%pc3*0qbDC!e)U3-rXI`n%~lTs|ExJd_-TwS|_SBVLk~yUrBH2{oWf6 z6*Lps8)e+N)otPxF%sT#x((GO2TVw(-;Lx4_Ux&tO`cxTuH_yt)@7xtTlU9M0cVlJ z3Hb>+7~>@zHoB35J^+5V`+U*|!~u$=+|URTsb)qG#V)i@-ykIZc&}@svPiQ z~T%G1$6XXFuJ;WxoVj$-cI>9!M@rW z(Iw)8OH z(p05%Lt**%^tSHhWve4yuz>S^e>boN9!^le0FX`3KhuGP%Mn5H-ltwDAkJD5Cw#j* z9G6vEHktJ!)I-ZF=<9U`{r*i9FF}S54KjL^;w4z!H$VCOCTuC?N(Q2cnZ5wCnZ zl_Ctx(v@;Ha?a(s=nz}KScfKoW_O&0Yr9kDh;Xa$;0EU}M}dTc19KPa>;f|>eTY7M z!hhlB z(Uq^0-D3U4&j0oi-Dak=00Ev6(TvH-vai;0we=lex^9!JgSPgsi+h$%z4F*tMJ1)l z=cfmd!#jYI6r&X3Pr~-XttxLbeVSfP>hRDp%$FNMlIXFy{7PU-`quP%7gj)0UHyK1 zw;oBY)yg)<@WKKv)B_nlx1)jjt04fwza_Yoh{2HVsm(P8=5Nmh{cEO&%A90ki+Pb0 znB=g+9|YVzLoz2PH=}?NhMG@jVtuu_Dn+p|F|0U4zXg4XYIK>uwE~iJ6%`df!@~$e zzeRxKVbq&mXivhb(NuJT1~WKCfyB-@Jf{~#iB)tbRhyBU5GiSIA2)h-S^TF~`ti;#-w*H;9?l30 zdNoiShvB;AGB)&^DQ)Mfc$|-PB%8<9TwHq`l!Ksmy#RF-xVV3)q~*EYW-(I`T3d2J zVeT6k4AsGSwLkTsOajhZnP;}UPe{Rbf`&~_{NC{ju24`=sAy;zs89fEq8|?Le!tHj zq!3G#-d$+Uar6CfT*7sUe>2neV6w$%tE=EO-uWR!@ggxDUQ&_K8c!lqT=9~6V`@g1 zB(}e_Q^#8^9`e}PS+z658F6uYF)}`HWMo7xB0mISe-Y7d-&)aaA*Ym9-=-^})2RAQ zNzKlVxeo&ThWh{G$OGihIk}XR-AYV zf1v5?ACTY8ftI#*HHso7x?VXJ)SFHJDItJXZFktd03Qg#WgomO&=)55%Rfx?J}{QL z(PXkQZYY|->$mR1jL4Ww@wA|L8sVd1!W42dEkAOrIf0b9KyKK?l7yJhzeWMeE4s%o zD?J{7V5FY#j??ji{;yxZ!hw8L(9Fmn7d~rDITUMoO@=ZizcW>+c0EwU9RuOsp8#z5LW8gFWAWUg^a19NF{`7P@Y_ z0Pr+2qER;Su}A3&Kq}XlJk&0Z{59L9rYEc)j^kEVeiN`X>n4OEj}8=)FT7kqr4wjt?a%q`I{f&7Y_G9#y;m|&%g7H3_)-`!YoymEnv1qsXQrp2b> zK0Qv3XGC`JoRm5gh@gRkxSrR;o-0f9fZ!ib^=yu)%JV&baibIziTria470h$75h%y>@dS)rE5@CN8H@LPmWzxRB3hpNei8B9mZXu*U?KRd499mTfvqonX|M>;5ik zHbC}&;h15Y1y@&fYPc%!GSR7=OUSIg7X(hM^B)5dq!Bz)PjP}xl8H%3hG$e)|3+MF z$FB_-y*{Wx7u(0`383P$s(zs7Kf%PtMtua0-}Juc28%!TeM#I<2g9vR9MkJq^ZJiU zH($7;VL$dS3_K`XXTSKn3@d@KM8 zN14c$h z3h2u8>|s+7JJXp>Q4uTB>RnE&snv@tuOW|<&!t#a1(N4JmbaKdJwBHSWO|2ZP4^(_ zd0B1d$KBT0f-~M zHG?wW#|H{g93Zd^E z^cbr4Qv2rWj+LhyAW`$FdTSK|ZT zmBdfFFd})FB9aaUq&y%9iNlLlBl=KP`S`6AWS@qN-yhh{DE!0;X{8wKmgAO4LW={AvDPy;S1mol@9l|tGNr-%h%{kvyI8}VeXUB zc8PHme}8`;qTPKxJIc3(SmG19znXVfE|b1%Hh~$bDj3$Y(=!Rdm{7|tX*|QbIbP)S z-bu}sp}W9jXJlM;(J4?;ITeJzd&bokI|(5YuD$#Ha(ObFDc|wo(5@%*KK8T>tOB^3h4|W_h1$7xa7b?I;!=^>9%ta3*o@VhEmMolNCZAVjU=T*x(W^R%GO3yM24#hrcp0Y zO+pevt(OWLc{N+o^nP(gL}+w(8$PdhcX#^`g}7nhzd64@nm#D3vtuGs8Vk-_4$iKgb@1aQVG$MEtp0SOvF zt{$M|ruALsT~-kdeV`fPXXc4q4ap(d94Z`1P-5lJj=<0wI~y!kakMfkOG_Czl=mPI zD8q88{D?X1ATT25U#^wsNo}aHURsMX zmRsgR1pYgVDPwEo(Knp<)_+1H$mf4WN4MGFfjZ~saY)br)VPZ%$a2(mk>u6(XwnrsdB=)xsjCp z69cK-CdrngE&L>7y~&fT(g(Y{qpU|88;TjQ)ONpYuCJ&2mT+;HsJ?shG4O9f9Mb<> zuMco*8b_FR15xcB1P_h*+Sc#UoXQBs|6+*1fif36@l;r(FR!k0C?)6^$V z;k-QM$^Nc_xHlXu*EX;&;`8zGp$5N4`v>arVg>Dv;i<0NCoNvOoJOboywcN#0{V2) zHA214e{4%?+dU^Q%cQXlXOpr{#7hKW3CvBgFE3WDWQ*&VFA5=?Y~)n&#qG4rmcI4%{qDlAM&vu1L!VX{b-0R(DWSt0a(X<)ZnW<*ph)8Q3<_omBi-Pt$E9R~~V z4ea{=WI-4tLaOC1K3M3Tu0iXo_m5VG#eU3r!;5d>WRqqcZ z9xp2rixG-Z_LKB*WC{w>K(e0%`N7q-@J0}QnEvofM{|E%B&p}TIMo|Jlag@xU}geQ ze|Ari~-SL|q8GVMA_V%!T%+DL3%H>B5Jz&$l#kY#w8ev*jz9_fvAnrdr8r3S-r zDlMH%9Af)>aOmmw5PPHo-}6>*qvhyFy`b+0)Zop@0!8s>J04zMGSuMIRQ!%_HFy9e z(ZAmjf8P>fdNgd8*xHxa@2xnAvGJwLfI zFffq5aNeA(V7|`~izEnw0#H*(0N-Z=wfhW8;@y+6Qk z=?}}?L8i;oI>;*t2`Xx?YFXOh!d2qcO8%_Zi^zl3IIlOiA>fO{`?Mwp}t0n`+)>d#A0v9A0l-$m1mGe^d=!fB{EuslqA zr0;^fev&G(kDNy{3LEo|Ppa$O%N_b`o+cs)5r2UjXT3w))+%;|nKg@S42-@-#6nEW z!j(*%JrT*DFv4A9KBpin%RoV4d~>{HHd88s`PkL$@c;*!pPv_jAppGLf0iD*zfzA* z8oSZ;o%nIO=j^j}ufLA#ZYHW*`m>I3=w;4*P$nMFN@Eg`n1zv%p@-pCECSEvbhS;t zCnCfCu0bg9(-BY8GDd{=?~c%OObKKLvS$28HEOOJzjbz9EN zpH7^8RII*r*NlYA#`@)pw1k94oo!BD9tGDra*;|2u^$#T_7}5hL=%8Oj(=D5JBh6m z2)Kr-M;hc}$fvn5HV5S(IVUkJixKoqao~gekK~)=FX$au>?WD|D$D-sH!EHYaP2vg ziQ^L!V<;jO6&1s2yaN}HgGnsWAKq+(f8#A_UuPxn{5p~Mh23x%R7)L?_|Fl=$?H(2HV+(4B*>p0n% zMg?isbRuCD3cnf}kcwaq+?wka{RNew?%fk{h9?%<@UI?nqgsBrD)v6k zwBS9rZo(d>j%Ou>``5)^rL*F{Fkx=g$00FWsHj@3CJ2YkViXn}{IQ$jZS}i5T^*iZSQDo$M(c#?8cS*}LJ(@B zJm=s?5cA;3j5=BU`(=I8tma99#O#cJek{~LLCQ_13S%i`spI?iCi2qxy_&lndk*I+ z5fBh^6sXwh-~FV1*OKwB`6t)Zh~1SFiK~O`chq>=z?$fjwP(=oBJyF4%NqkzUP7Tcs z!%H6^SOt4 zy1Dh#O3x;m86P4jn%qAjtPtMS2#uH=L@YV)W1ey`Cn~%DZ8RIoruRs6F+AN(Q@EwO zVh@o+Lc}G4A3D=%Ni)KVH5%&o;!bSQ$J*W<%hD_7pr^N7YxnpLz4%$L}A74t-rC`BaJC*%N92qia z;vEISqWYL05KP%riW~7fD#-pgdU)ljc3O?DSE0v|X2 zg_gV484^L+wON_DW1}LNuE%0d>-ff)|Nj5T!hwI$d_g$Gz|0)d~6GeMVizGW(}% z0+4Wzml{;5<3D`(P+wQ~5nQc(00zEiXRrPF6A&zXKETkzYB~w`k5x?iMMiur^Pkw? zS%z$k>n~=~!OEubx}C31cdcCR@;o?39A%4mNU`3}#jx*Ah~jwsxCnQ?qM%TBk9cVo z5kn;{ah=}?okVrLK1=$AGLtYPijH&cz9AX{q|?`*NQghHPk=xc29sD!lACR}`opkU z3e6atot?GnZ2fch3Ka7qUK1&(fI>W4YA87g4Z7_#-a^M0&l6vL2;t*dz99DvU4y52 zj){qFAWKq3Pnmwj)0d**!!XN}|0{8EF{1rNXT>1v5) zt=>P1i6ioV;_h3DWDeFhjhWS*`bS;d@_tc^p|I^AQRXhys|-7;x|uJfzxwC;>lqph z-5s^Vs1#&l=I$x!=-Ane*&T2Ro? zs%1KVgUfTib_IZfLuSC4_?cV z(86U}&313N@$>iSH7i}d#@m6+@>DKqzRwx7ksqu%Q5bYOLkA&M4ttAno*wpRe$kc$ zZcQ=e^=ecG=mz;N4irT)L79h@Pp2SWTB+4Ldj2P+JI$h;oU6?~G)zp)w*=nq{=P=e z44z_vQfX=F!_CPKN2%S;u#S!n7Z(>+?3ljD)DZ`)PmpmnkD6Xn2irNhB{a1|m_iMCduuy1vBwbe@V(f+;!T%G5WD}>ErePg3Y@BHlS zYP@n3s@tQ%lEw(lVT;t!vzAItVb^K=<|TJaV<(r{ z;0cg_vbz&#qpiPs8U8_jqJ_;c?z?eBGfDLaeCMaOlYEFsd+--kRE|rzk35kcGV*a@ z(I&ywQKECy$-iZtn~#dsmGkHH%5NtN6j_W0zhS*z9T$%CrQT*kbV}m6I~+G0m;Dnw zJZi9TrSS-#!+xAv*u&R1GlRrSG9ay@arMLOaRx~VYvcL}CuZ`d0H^6N)7k6BA!Ev^ zVWz&ixT}Y+5lt-YUUt{0&~SRlBL@1T8)~Tla{MOg$rI8?5~dk;F?7S@)I5qj1?BUP z_b)-2`O*+Jd`??o`ox{Bt-AX9;WS>&l2WJ}{lcmJxk}@P`ugqd?f$LvjzHux-4=q2 z^MCS?7fk$h^qGN#wdgDZ&q*HF#kG6t6{MTFA&D_!VMpOze%4fcwIo3*5FMmVKcGe~ z1I0enmq-HYcj+92A#%U6%07-vmt>jD*J!e#_?Ic0bUCj@)o#D+s96-$@5_Z5>DXGJ$qM252Xf#w*YE5o5RMZcj@Meot%Q`!S1HLaVEj>Lw9UUDpeR}ts zt8Kj(kQ4Lbdb9UK0^7~m^`@f|k=7!t+OIJ?|JFPW2riX&dVYCWcW59y;~dwnm0HnW zwzjU-NOL2X>bI6?xDH8lAY54fDeLB9v@`!%)fQ0<*_=oW`Evt>@?Bk_7I75c)dNv@ z#g+XK4mc>Gyj-~_Liqs#Uts@meWc$L;qZ1HNu$k1Kx*pJU=j-^oyKdq4!o6)ipuo< zRFTuse2zi^RzP`eEx*mWFoey55$bhY0q7ZI=kr&1{7tZ;rc0BjglYK}If~n=>{LzH z1CFu?=~Xv}pTV@SR=P_Izf@YdT8>vG4J%DxF*)_GCf3~u9#VkBxm^wp2gKpbofsG& z()k(Szz=hkMLj6hCKKcw9Jj6B&;$eo@cw!O33S|!hgkfcj}?XkQqs~i*8aEUsiud+j$ zS9wqVfjJr2zSDg3DKojYdPW~;`f;$H_n`FvI^jOy#JEum$FTQhG{a0WZ=CfgI)=FD zeIj|koRQIXe>}}=B~R5BLI)$S+qG7O!Pf@IqyDl@&u90e`D&-*#Wj~SATdVh($Z2Q zy|zY!=`a-(fRfyu30lq}_-g+b#uS|&P@`6G=Tp9>#303VAh8n7gi27RIj?qQK<1t+ zubWC`y+2T)!SRSrvxby{fuC=vwX^EGXR?5x_9|MEUVSjSI z+RSNhJSX2WdSFX3kzQIxX1T%;VISkw;{(X0di37@URQ3~zX78gQXY4O9?q(P#b*o$ z3J;j}_x9*?n|bKyjuLe}%d4x&{5H3@3ApU@zs8aW1Oze`3b#{f{`GGY4N}zLF1>O!TGZh8f~y=d zB`QTzrU`~GzZ!^9gW*6T6DCzvRmtpDd_P8iqmYQIX=>_+y#q*K0)FD`NX&lzNK!st z2}U>E9jh?p85uC0GUaf#M&fZdGdsAu*cnOZPY0sn;<_D7ml%(v`TO~Gc6AvV800Ha zM{GE!8LO)lC{@tX!1<`rZo8!I+-3UPk)j5Bdwb{P?yicdM(aQkV_<hbaLqlU>VS$E*4rnvQefwDeUmJq^4_C?_n+^z~7>;3=(}QE$23GlB z>0r!<9no;Q|10yjl+LekSKf(S;3%VFaB@ zUsy$nCIz`(QnE8e%PHMV6-A5MSmTMowJBo)ey(>YV*>JnkHr=--+N~yu{kUdg)^W1 zIMXAB3qZp8Rbw8^8bU%tgOGy&5C~o^L;y?*_pA^k29Y8m;WD#gWYR(Joviet`a78vSCHl~Z9LC1R1pg;bTLdPza8bxK;DOIAicv?MJr zZ)zqbFYjxtT2AWkcSL|`l)G}XRU?Dg-=rfW;&2A^gQHYDpumLvNh){wA2lii0|Pnq zoU*dW|5u_9oP_RaXdEbHIFsLiaGMEDjPlTZj`n50&;8=|@s zg2K5I5--bn(U^N`F1v>_KzcQC)zDH@$#xsq6KHP4MW}J z3`}E#eI^xU3{X^Gf`!{F%zym&;rjt8>cd;SGbB1a{bjWcT2^-CwK1HW{G5j&UIIH{ z%|)j~#SV`G4oZ3gu_H*BI5{^I9xK66J>eS{0v2fpI}Ia8cYNy zk)uEyO#}o0;^+Ze5*cz@jm|a;H5T69-aI3cq^M~->IsHe-HVHjo=^AE$*d*|H5P%N z@QaI!pADJjQd02v`S}S6(|`W_`RC7{-QC^CNB59SQq*9Ll5Lme*;(hq*>V=+;i{S% z(Zep*gX`iY2B(7{2WAX|QFIJd+MLDP+tlmpVu>m9%UuwK3{jLqXhcL!b@k_9Vbf|H z6ToZGiIQJON5^cs*yVB;WuSsMI)Aq%9OujaQp3&eSQb7$ev9=?Xk1)ek!qRFU+cB4 zfy7r3DU;6w~U8qD8#)d=1xwUw0H{(@J;2k%gfgVKh={%|)jPb_B%LqaOG!zQODDfNgkfP}fBrB!Io)Jh9P)WS-gY4KV_{>v zI6G(O5SjOwzkZ!I}Gmy)voM6XY~I303B8p1{B}3HoYp_=sq*87JRxd zA(s^;(xoIO29u&<!WmDHw;wN^C9+?-mP<6 zGtqgN zD&@08<1;Mg=jTH)86rYM?d zH1Ii4=P3kNSG!p)g|PMuzx4~h*2VvuR=+7zGDcC#xKGaQ$F+vRyi*UQ1$+WGF>Q2MwbCo%zEm~n#Xz-R%9q|ToBcsbnl zHp=Li&O%L}=@gjAkeHhrVmLRP%KhK28Iltb{kGZY#-!I;b!oO(sELk_t~44NU!;9x zcx|U>ZEdYKn+fS!kBf_=*RD5T{9A5B@0%8vXn*wdMG%e zI;!{R{9b{LgoUc$$A!A4re^j(Lu{_~*E&NnPsYZ^Mz7p?EK_78jhBUmr3i}9JUNZq z>3AYfHat9h%JgbHM=}rzS4B-tZK8f;BMr94&bHiL>%s16AgH$#1orJ-Ui$WMYLP;Lxw$zMG<4A}-JYwft7@6f)#>RstnI6V8H@R< z*Qeh=yc~D?24C{n;;@G;xp6n@(3ML_Ek023MR9xc=&c6@VTdebAr z)rXUomA^J50~IA2)#n!%EbQ!M^*vzu$^EG!cJo=HXmMf^lGK!x_4V~a59DQMuMO#O zTok(b39rasDEi`w?bRj|wz09;1@@ack_y_|?-c@wNk}*&%$6HD|DouqNCK^Th1CjQ z#D?qT?%LLta)aZMskI!7@i33=W{?!Qq=dvPT`)B@{cQ{5~LseZ5WjQ%HZEl;ylhU|HbQC%+)>B}BJ(Yoom@b4hSheVY z)#|vy;3E{3CcHl}14HDFOC0^1UnOxeo+C*>Kww&3?{cx7NUx0=EIf4xfJMTovRGg% zP{P5(duKUgFTJ`Rw)6Qc}Cp81|u z5JC09@oN{4%emfxiXbpK9DCx&uH5^~kIT!;h#gg}dK3TF#`t`*@9gYMq2O{x*Q@%^ zpZx2d2B#ApZf@>)i7&2~yQY<^Y7xxFqe+6MIu?}dT9Ym)q7GlFn3;!>aJ#AExf~9z zm#PuGfAl`woJ^TI+#D~Vz`VI2sN5d+mpPJ&SOH1=UY;|h+Ggz_NzxcxcFSIa3LhUI zkWhd%o+{EO)Ajh^0+<2?QCEjcM?{8K5=wUw3J_PbGPw4dPN=galQl=)LOynD(# z{&vd^DkSC%Zx3V5l5N#GSxt5XR*6sQFV%BJM8F9PEjPN5yt+h=j*jBcZz|h2n8vG_ zAtz26lZn9aWq(#I9A~Obm%m!0$)GQ0b91xMjc5&f?RaKsDy6|wJhlHAU3Miz^P=~QT?tCA5lReH3)_f;O9c`T(Tl5m3c zDCj`r-zNI)+*vi>iN2+^h6)Q-SaET2%hW3aa`((;O7CuOmAZt~PQM8{i~dz2<>fuB zN{Yb#;24~b059WyrTkqbL7d#K!A*5w7Axt;8fDBcQ6>7 z#^<5oukp;dzcw4HuUy=}JnCsyR)RG}cJ*y6GanY2GCKcay=%5B2T$v-wRf(Ghld9m z8rpw{Cd+)E3v_H~5>J;%(HX17<7OZer9i znS_$0r?+RA3$+M%GuErE!=acYQMRWCWi26H>neZiVcrx`czXyU24^x?LAE`BG56Po zL`44i`PtjsJHDk_kV>#g=DJ^X=b+y{UDn+)!`PdEHu_JIYMCsgnH3TZZm4I=jHC@&v*MiP)qd=d3O)`rk;1=GBWfU zXq@!)!-I$iUjcx)52f`2(p5&U(M5lMnEeEPIrM7NDeAPHlck142t?Cl0XrRcW$Q=c z<)eL)nxosH#UveB{N{<5Yb&7Ux4=N_xA9QSe9iu$9LYq=knyQ0k)?mw`FGOv>S&>s zGXlcxL_dBzxjUBCrN=aKktds8nw_`g@-_97gG9e%Ot1l_nAV}e)W;?jV(hgwu?9y& z1o-Ux`xRH0J@r-5hI6~)Mb2`y#d-&`|7h6XQtgIZg@PZ+1nic08 z6++O+;pWV!smjFaV`H!j)imOgXnh7*Wm-&D3m8dp6uP>)ISOCpCs*5iqyOQ0`$-tb zOH5uVl7P2U@2t*lhg!(ZHone7_GW3bGI&cJRzI-z*os@tQGh*OT;s=Xo8u9>i3xF? zd#67F64NT(M+7dD-ur(TFQ=6!o1P#}dbK|lD^4oDK^TtBBATPn5X&9IBQiwcx^>hFuA(gfuDv-#{0io04_>qW?|dAe96Su;0gKG$wp74 ziHV61k<>57cmMIO(w;~{1fNlS_Ca@@ljWw5AnJH(R@SP_`PQ?=Ys>}6kqJgBHeCkU zKm$EL|6`*Tt=LJNczcm*AeTMmU_a`>mVT*j?ZFg6l2TBXSfs*hIKj%;IPf11qazGd z$ji%9$D0oRViMo5vv+WimXg8>;B>n-_h)ToU!GaR40O5KE>Me)P}*q^LO|f66KIK3 z>Rf6NYj9NF-VCa)?pdzWpD4j)E}%?HOGE6q1nCYfoS^Zq-a(VWJ}iDjzMIPBb!LY;5$M-ccas9Dj89Gd*L_d z75jcj*3?oG5)#hN90L^-xza*7Z$>=i;Q8qRHMq00QEaiQSW6X{>GWb<}@- zh`1UW8Y)>Lcy@wyqhAxYva_?h@J<}}TW_Jnb-Oit{Ro<2ez|!eqeN{-Mc{vEv|Oq$ zr+rxK2(%3q2Kqr;eVR3|JwrU-gjoiUtd}koiuO6Ni5Yn zP(0iv)tCpXQIC2igmFNWZ9hePmsYXJu_JcITa+%Vi3DPhi2?DL)vy4ay?&`M3`f z{)ao7YBGs<4XfFTP^eahd1xn*Vok&9Bge1 zdqu75`s)0E8w4a;v|EUv`HB`#c&a6G5+k;PUbcP%<^rWcg@WZqmx*e#8D_7i-of5@ z9U5L=9`!Ub^o);7{l!xWI+|P>j-8Zrsia;niXQiydAZD}UyG;|U9FZR*0`S~zCBzY z`2mH5gv7+e{wF|1W#yEqLr=tKS5MkgT3I-hzD^~>;r`ZEB3|C7t${>CwR&qFC-(E> z5DJ=Q(#AEIG$3)NNU5||qJz4T)wjqqb<=lZk<0c@#_sFt+ zk;~MH-OlbIW2X`h6bySmn*@O@$a*H<)UrH!{mNya)F(Vn`I4_KWM^k*XVycoQha~q zF%Kc58yXsNBM8@jQNk^VNjpkqscQ1|udA!`7wTENKz_Nwg4Y?eG+*QBhy;S6cB*Tb z*_||=YfkNQLd8i#!o#1=XJgM}YVOS)_*RRnMT=UDU)Vody(gZGnbLTg+MjeOpa@J6 zUQ#eER&a3`&&EAIE|wrG(td!5MatDG5%BTxadL9{MX6UBfsg<{nZ1kX<$U3M1mL2@ zNz>iHI;}NpZkGNw8q;+1?8;*IPuGW=F~&3L#VyTV#YYq`vF9D$Rx>UEaDG5O66%%w zgdiZ>-S9XHT4W%CA5hzl+l-uqd3@)QD?K!kf`GfBxPeIsuEcOA$H{3TTcGTxJ$S!r ze>^)OKOr_l?TmjR^`OOLa5UUX$q$$m9RKm_r>2&j1~Dh?%d+-?f~3J{rg3Cv?eg+>e_@3d4>2123-bFx{$}Gb^u)ozL4`Dh zi^JGo6oD&v&4dp8O+=}3!cw8?X*nN{er*3;G;~?{;9&xcfB%A&b6?xprfPv4>D1Ehla@f9v_JLlSV8JlMxqPzYkb*bBg>O zOyur~oWI>)hPvrEDwD26d$}SDwR$#3 zM!M_{C**XiWlUCk<$>{%>(0F81$$y|V3s`WwX{{1EDAViHh;=_Kovq=c*9pB8*?5zjxZjJ5QAom>Z9PZoYNRO9412} zu2@bTlG_=kCLGM+z41OGch9x@0Lc#PS~}EfANO1EGIQ48P}3KE(b2g|9}T*M0a!xr z>Dj5zRit?MRs-9Zn zIE&<`n~-qzljrM-7cUjT-7T>>zupF^{kxq3tgx?%W5bz&I(^8;qA!yb(b=p=!&fbr zF=U;K4vm%16lf1rO>Ah3=CYO%_Xigxu-CP*p65<b`fJD=JbYvsupDPv%Hg9~}ZE4LdF#Yb+LiBolBu7UM}OLBG)_ zs%i~sd32Gdg+4dB9t`qzeqON297l4r7$KUk-skM3>yyZ2Hl~Mc#I*{3KOQl?)YtEBrS*(M41s4S79y7Q<5Bxj0Li3^8zhN;oV;F@7C;LdX=aXXankB?X7 zXoV@VBCSvE2TCU1TdoY##D^)(pY;%GC(yP@>%~u`ayx}s)@U_4GmZbNcGjylomzKE zGo15siKy|O);*!f%C2Vy!|AI1Uhngg#7v5~jD`1CHNc!gzAGnef4=jdgMv}*M^h2W z^#Kx3MZX-$uxpeukZhLaAdpbS$~wr%L|i6K4)+~zddKF@=YFt-MhW+#ra}s1A@PZd(New< z0041xv@-BtL`pQO;Xon?Ivz6jRwtFuTJxuzCr@Z_poEeVJ~wvsEZwp+dJt(h1+DDu zz{u=n?TBt;xcIQ4ZbbjNrxIVLO_DPy1%V;CkeAAz zBrT#v{B+2Ap1h|%6rF{-R*(^0nK4V|{L~cS)J7_1=A;+3J2L?T{ug&OLd;s0vz%gW zN)L(|HexU;eY$(>g-Hj3C$}9}qf%M#s2{NX<=`rBB~fI0W~QgN09g0&W8VE0H;c2i zpa#wm<1mZya71vy&DD%}Zj7XqRHO45G3fP{|CeTT?l)F<%PvAg;`MlYb|L#w=jtfN zY|I}DBrGSat9d?jF5vycA)UQB<5D-odtQ4-x|~87PK(cVxWI{1R7$!+L1UPkYDE%Gc! zt;$mC=Elo@Av}Ux``7V$-*aeO-#P+;c!dG@-fvb)FwQVLJ9~L~Ig}|4udTi77qp3D zQdisEvi@jW97jPGH~3g~MtvIY8nfMMkHhro__o4!q@$(viMyv?Szq7lU401IZ$%b% z+-KDt<3XQVMYwL^nDNlD=ukgGn!3BwpmmItQo)K+x%^JhI%!2zke$m%9y7`mj-K6~ zk~G^t*@tPVf-mMl$5QziL~fU%jlTp01jZpX*-R`A@x|qzrtDs)CMLmTJ&d`M&Sx8H z)^ou3EnIYO>8!1-yP>p9U-~np=|3@I06wCZHoScF9s=PYk1%QSIGV8%I;!*WO*iyL z{`z+K&BkcAmMJOiu;tX*ooU0rrS`YiMX3_;`4H`7i?OW;`?2o_*z9+|(8mN&$;OIm z^L^gy?;07sQt!B7Ea78cdXy7QkH=g~La;Uu!4S=f{2rn`FP$F7Bn_i`xzNBk|T8V?5l%%xRV=iN{Ojb%t@DvFuR~52K zuTu!hU)huP+&Kmt@R{Y!z1x!X%hS;^lU7#sjOtHQh`ZZs|2w>=-gWAYx$VC_4;oc4 zAi7b`3a+T+OSt@}b8)1l|7K;nDm@jIeyg8vO5VLMw>29n)yfLoY6#lopSdZPV)ojw zcCXbc+PW|CRUV{ga8N{8Si5+_d2`UH)lU)~4KR%P&NYBK#}m0h)2*PWsFSN$Y)=_s*7C%AZmdx5Cz5Yr}BT+tZVuFgrg#ls{VotFTa)RdseO2Yj(V7s#+> zs2|nfWbtrZQh*53K%mVncpLu@$I>n;C_}=WX!y0ZkQb4j9 z?fPs0pSUb~-K98hZEcNK-0cl;9f2^eCK3k#KBDJs%RL&cFjtZdGbkY`Ra_qGK z?fgN(OTG`~fc1&6gQWv(<)O(_7k!in=~B%*3I@HTa2CXzN>w`#HjFaO^$?Y zrRc72>~hx6o@HQQ??I;dF6N&@SARQs!q@vGVXzmx#*q!V$^>|L&)pF;s$} z0Ki9J-nQI;z{lb5-scG6Pm}#qQxw)WO!oHn6ciNUSwQ??JuZ}gaB=D!adUYjB_%OL z8V=jpanrBux88Xh`#Qv-D4^7+QOfsfe0Z3Thez$7^L(KFk@=gdNJ{>{SEsu&GBRO* zouTy7#zG@lu6-2m2?#Ktv`Aw(4=YdU)?;q-RYb8)&Bex3gD?Kx#a~&~GcGPJ_z0^$ zP4SF#Kb$c1YA&_-qRv}-hlYlFdhh~n76wv9Ju`Um@s(LQId-;Fgk@OODkT4fe~y71t}KOrU@?kE z7GFYJryGR-jAhb;^Z2nfi|UTt(g zm@G4i9$nX3TwK)G*9R&LeB;Nkz9FbB=ezh7Ofgr>jDv~$1(?9*B-cT{ zwST@2o7B73JIFa=dUMDVnoSk5DHi*BgYV;;?n~sZkUcaE5_WUr^Ym$IWMpKXYAQA+ zrfDL72DymDbrIuynW|fp5=nEg?<6<2_ zMvaBZ5<}JW+35-GtdgjB$ahxtjFX*-h}F91&Kow<+)y<#T8NL2PpM@R%h&Yvxe_|OINDN*c6#yzQ-%Z#lIVLP6Z4c>gof|?X|=U$ zg*Q8iEH0IZ&2$2%?(g>%Wo2dA*-YqY5BWc8PEJl-TwKRUr1$BLD{^CiI<;f9JKFmk zF@U_uko0CzOVcAIO5Uu)lx}s;R|{UMkE5c}7Yb5X_RO%Ls+i8v7YuC=qV0xGz-zm@ zG4C99#tXlavf>Apd!0gviHR})9oxU#UuyN==uiFSMW@)SZnVxR+?%liF zt5Z2y*`gz^q^6vlLqquDQr+YG9c?uqiB4ps-fOmS?PBW`k#acvV61y&phOM1p~r`R z$HT&s2aaRG56-fkt6f}Nqy+r~oKyx})l`v3j~)pN3Pyy56$H4K+E1689sTVj?2zz0 z&as`Vohaha;#f6q!mal>TCK9$K3FOy!%xYg{Q70nQ!O{^qruYXXsuH8hMip^t@tRT zjT2U8u4Z9cdU{Y`V0Cr1teo7yz(6eCgUbU71YB`Wn{*E+ zT&M6YlM+w9n*U4(P1~ENLlVAE{I^%E2V9bC-W$Wpm$U37P(Z|SC!@HkvgGC_@_0v^Cne>fSZ8)CkPub(y3 z2NoYct`41r)F>(_OiWICd3ot*Yo9jIW_hNT6y~fg&QwL|mR9TNxIHDz>X6X{4pf4` z_%y7?5}kZ>&z{LRI?7oM;Cmk_B;>P}x?QxKAr?}Tli6{9Ra*2(-5koHEM*7%kZZ=K zc57=ZC55^~$53B?``}=S9_lrcrGP_B_kof{T-re@ zzOI!BrAKiB18#~1IE5Tb#zhPiXli7%5EO(XuNVRX5hn9@2yzjAda~@Vp{WUri7~C3 z$?!(h|N141RojIPc-d-TJcL=Tcx{YKi`K_=lWIBG+R~v(uf4gO=-3 zqy(S0yZi3`T+~#la8hFJQuCa)$`Ljw&2FAvagX!WeEiHdA0e}gtHg*~@2h*8Ki$I2) z{QQHNs(j-6+LrI%mvfVhD`#w&l%P#sr#tHNW0;}Y$o8Pb%F4;!UT8|n;FXuNmR9u0 z))r#JMno0}4$q%k3D9jDg+J#F5eNBijxOzqI~3 zh_R@pdF;;$Ct4tpC~DkTJV2XZsCE(H{$Nx3-cv(k1hLR~e-!P1ad~-rciwss7wWk? zSrQ)~pOHalZ-212w?|(AKNK-^H#b+ZE!l3z&@#`iub&wmeQ*0|cYCYc-Sv6DWodpW ze2zJT^%X43I^6743Jabr3>3SmkijY+3j(KDBp?v8p8;iuhiD@sGLDXD=3NC65)NN~ zsq2P~WloZkZgJq7^H3l4=3&+oC0@nA)0Hz$SAB1y(=|C=kRR4hvPqg~cnCg1|6&jVB5kBx~1Ml!_}mMaPE@ z6WjCX=n~kEj){orNgn@*2y1(ZFX0RWS$z1gx6qgb>gn(Ax1FnfMhXDDr2ts1Ify+W zB`q^ObC zF73fUW-z0?Mm$LNP7Vg_80IQ|Q>-7QSU6E6A@R=T#S|Kbke}ad+so(}lA#}R3+U({ zf4X9`o}JCvqcSaFIn~wG7&t_x`8W?hWpiR;f{cPf*T`s~a_{PNSJY;D7>B5+smbSf zt!IUn77uf!tCCQ)Pc_I($Se}X9vtX*qQeU6Dd#GAJIX<}`#0-NvA(G2pu9Lg&^+ny)Wuc@b8AOEKgI`4t==4~*!{(kUjUmr8@d0<{PawNdp)Y9I+6 zD`624eM3W5`sB$E4V|Ft6uX}7&0t|+fxv3X0_%q>9R?+}qI7@mZm$Ie1Z+f7Q&Z=X z1+BWGo`%K|9BL~;Y4qzHesru*^1qkY(1=ycmSK6ox@PPlWCS_)3$GKlZpW6E7FM-1 zN`#NA5=ERjegCmY*Kdo+N90i`S2glZvcc0(DGW@ct; z*B@z#x)Zq#{jTShX7}B4HS4`jcT`hF%xd`CrZ{+c>81UeCLpJ0XDBN}v0LB)07V2Z z4<<)Oj;bZ)f-Nis9%78ZWZD!4>$>S}BMfCGHuoHqxf=%p9mS9}yoao!yK0sq&V z?AzPhQBhIJ$;m>hPougnk()SJSo;f!Dy zb(H1)Yz?Q*&kJ_ZH;Ev2US9i!23Jx0#d!LV&`^|S$+`4CpWkD9{35lwy*iz%wRIMw zxx2f=!ot#9dYGz)&$Zva{b|%F!pf=yQ~<-+!o#DYe31j9D1z;`9GN?}c5}7doSc2{ zD`G%kSWa2l!GYg-ipylg=U8c0ZpPO4P11>*5ztvDir{DVrTfBW`WVFx~ z^^}-is^5{OgYWpoU4?mfUT$vl&2b+Z8k%%(^R!KEU|?Vn4)Mm?8fBCs4747bSWr+f zkSfZ`%4(j2wcHb_xO%cZ*4Nw17Ot$OCgrjfqns;w z0|QA*w{}KQSbg|#aed9?^V#0@V6nL;j#X4dq>`)AX}$M+(VN(o9yPUnZxu`(=!VjY zdmJvG?oO$)kb+^#xtc%)=&HO%4x91=n>$2^T31(>f`URT@?d$Hw>ddCe<@nq_Iy4cl-AXW zv9tF)_&)dN;Jk*lg#Qqu&7Yr=kX0@1&){H-^Cq<2wA`QsQ)XCbfR9i?<5++U4C5k? zko{q*pU8l#0bI{u0zc{CGd4C3!hVz@=J>bC6PcBr&5qxQj_xDf9ZiqoG8nLQc699N z?M>k~#}+_Ctt39%wU3B7Vi^OvDj_N9?Ch)rrTMA{0K72*EQb~s6i^C7fT;RqF`z=7 z;<3?D5!+cHHFdZH!0%g8QPFefjq&mES1=$sd17knQy}n*9suAa{8|dldd2>VecC=HR?sTsG6?X8!lrOY6!QfTabK`>QF9Y(;Ht?Gd5ok0V*5qnan=fX`BZ zY#xAGJER618{5szP3jKF3{JGr($qxJfcsoHU}7D9C@Cq~-rlC*HC_`N92nRi{vp@X z(-VdT_-@};K=4`1!O?N1(Y;LehsPcg2AbJFGw+5fC@O}8gxD=K)a2*mIHLKK2wDw( z2@Ty`Uw@3rZ_yi%ihhOz04L0pu4oR7aV)A=H^`yPlSpQ8h*{q2v$nReAtWG(TN+vKVGAGKcA=u8vTr^m7hw$Y zLzRjsEG#6ZmjZzWxVZK*?{D&r%aphP0AFI3NHnq7wzjrMPeu3$ktJ}T!iXuK&1`i~ zUmuFKK8)y!HDhzhb2Hs>wQFK(N|3M$GEsDV?1a)-3w|~aU{HbNi%byq#MG33($ig+ zh5!tltLy7bF-Po%Bx;_P7Q0D*uy0037K zuPHGc6pf6GWMpJ4t1eUR_}>2xJ3Bi|OG_&#VEc`A8^9Lc=zefFQRc@i%{#xaaDTHY zJ(MbXV5lMm0Gv>vdP(uPuhKq6L=m=@F77@%J3CoosH>?NSoeL1lY;}FnArdJbZWq| zs)^>lJqTxedwYu;0Jz0hGy?fyWj=-Akp zHb(*ooSU0l)^b%88mi>w<)yDrh5p5OCxW--mAX1H5z%7JCyF5?b<{?7wA3%U_W;0W zJad5BfE^qM2M1nT`vkMXWqY)#si`lCch{w%+l~eIS5F-4lK=fJr*3Ij)~m58sUUwqf-wjWGDfhog)E1RoXV%+RCkRnVSg}nkm&GnzFPB})XLR-Mgu^h*_N>7VA|!3Ri^LNcD|t1;0^R%#n<;1N-Iu8BQ`ueeX&j?_-XPd z8K;iK`MmRV3SL?OTX=Ugy$RgT$jB%i1O|bxE-#yrgW|}I0dFDgCxC|;VTvzxKvGiD zB%SpP;{~CDhQv_u+af$t7A~WPliVa@Cr3w_Ux#DPVl<8J2a9!%*&`o8xPhP^vyPDF z`@3rtWh~Bv?OzGkclg{Kbsv|(^%GsiXn+dar&qcrzNk`l$9@(7^|=y5_}xXfw55f` z%)VP716w$?sNH-bw_z8QHUd>EXaWmx*YQ!v(!yeYp%I>w^JUXBSoRriAX~VUl$2K9 zYyBpVqa1J?-CR7?vQqt_+uroih!VZ9sA!)cC40Cs80>kz;C|{Qd5re3y1q~hWB>wz zd-L^zqN4EP;)pD^@GLQCHXGz{xn0n*U$5M>{ZA}Y1qb$Bci-N~nL7-m0b~ZlGBcNU z%UWA}E}fd9IUW{7ZRgGhi_IvKY-zuyq9SFWLa?k131+t=elX*U7hZ#D&$qX?fBg7? zi{H{19v;qZSW6@6HEvloBE*f0-dBmTnCpFbW|IcpgGm5<#4|Pt2nf#i=iKjZF1xxE zJ+%pkkXdXHp_FgmzOAjTRaaM+m-BtVGU+qr+e4MrhSDDY=93}$x3<|Wfop1Mt?Lj1 zP+N6?G)vWt&(+Cx5DqapIk}sQOALs8it=)5)2rEUXS}ei>9}`mB)cM-J3b*{f3{|K zOkLXd;_#UaNi<7{g{7tChYzOjDgXUX^_<+?_1|AfyQAq_9aj~-y~SlnlyfynFrlj- zQ-~ft^1Zv<92*^dLQ0A{9n_UJtC~?ue^K*ks#GP3N54cTB@YZ+^IV*mKy3y-P5x~E z&G%rspREcT8?SFJkxEb+b`B26$B!fmu@?H_S!>O9H3lWdW$Le9y;4=B6?fwj;oSA6 zrluyM5p&oY{^5VSYjQlZDF$T-Yin!Mud?JeY7lzyf|?x-HMRg^6wuYuclAyehbuQX zHz_I9o;7z&(_!0s%vXu zpdP+Ri476RcmWEm6LgJ_j*evB{L^c*oSa<8_E`Q<+H)-f0|OHiUR?AJKK$UoP0x%? zFl>C=#jDwGZ@OYEPc)A;+%IUOExwvJ?AV!%;YuVt&$2ScK)Re;*qkv z&Xn@KI9&0dy&?RX<#Bzs&!hxJ)X34C}3f$YGTRYC}<0_*;b zrz;j25)KXyRN}Cnp2y~3dMGjd?7rJ&0zYb?JJTq^azaD9+X65`iRq;*`@el9WmS}y zXG>7dIX|hct<8}3zgz2x>+I}&V33pf@n%?P-$4unc6wkYNR#rtny+_OilhuUXT^FL zbX(Cc#Kj2+2%Mdr%ZwUzw6w-1Ct1R?B-$exaO?X?Fn?$k`uOV?F`1j2qZYK~ z<$OPrFU=wqS94X8j*&gnleXp9UG4=*nAl*Pp6CxchzachpO(D^lV4AjnecLOaBy=sd!HjZLWvt28ss(N&-vrJjn^ar@){u2JW$`* zNKDDc00M!yxVQua1Xx%sFAi6zqwO6?Hwzi?+-1PMH;^N}M0yjl#cX)V2 zgv!g8ZRKVie^*!Y)zYa+NrTuu|5@bW+v@6SAO(dpedh=i;G^#B(E+t z479F6?Wx4&xusa5(^y|$-`Ke8@NppsNN320ITz zO-;SCyW4v4Hv)&4uDZ6?&DC|rMg)b0-uw*v0^cG?kRPOAO)4Dk_|uoSz^N>ZecVW@j538`sG;LEzDQ7GBXL(AQ1R z`nf-%rj#LOl!+Dz%DD!pG<_Z(9;dkxNDTskSX^9ukv=#vq0RFOfk2d&mL4}Z*424< zc>EF1;U`?(-Yy*ZCn&|868ye0HKgj$%*Ewd@j7`MHwDZ+N=uvkm@+=6#_}3Kg`>Xo@I32a*&mvP?~IHV78Wqj z(L)HS1Z<|uW0{l`6%;(Zy#4|)9$@XIbdl)5zyLQlH+ImE+}zxfl9H;bs%(_V*@=-y ztdE$6-E?TtRma{NmI_7t74)9U@yI%J72@rVl(G=$&I-sPjP$TT&1!{luApgBiVEudlKiB_${J+=#-);Z>+J9Ti asJzEe3zlEDwbt}TJszx}CSNLR8u)+4??>_g From 339c2599a44f82c177eec63c669d2025f88c539f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 29 Jul 2013 00:30:37 +0200 Subject: [PATCH 42/44] 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 db527ee88139ef470007f82675b57ec313cdc495 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 29 Jul 2013 11:00:36 +0200 Subject: [PATCH 43/44] 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 44/44] 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;