From d140d9c1fcbdb955eb43bbb9b43a0937dcfd929e Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 10 May 2011 02:11:34 -0500 Subject: [PATCH 01/43] Fix from Ivan for BootloaderUpdater not building with 4.5.1 --- flight/Bootloaders/BootloaderUpdater/main.c | 6 +- .../OpenPilotOSX.xcodeproj/project.pbxproj | 181 ++++++++++++++++++ 2 files changed, 184 insertions(+), 3 deletions(-) diff --git a/flight/Bootloaders/BootloaderUpdater/main.c b/flight/Bootloaders/BootloaderUpdater/main.c index 4db806ddf..9b1691dca 100644 --- a/flight/Bootloaders/BootloaderUpdater/main.c +++ b/flight/Bootloaders/BootloaderUpdater/main.c @@ -39,9 +39,9 @@ void error(int); * data. This is non-intuitive for _binary_size where you * might expect its value to hold the size but you'd be wrong. */ -extern void _binary_start; -extern void _binary_end; -extern void _binary_size; +extern uint32_t _binary_start; +extern uint32_t _binary_end; +extern uint32_t _binary_size; const uint32_t * embedded_image_start = (uint32_t *) &(_binary_start); const uint32_t * embedded_image_end = (uint32_t *) &(_binary_end); const uint32_t embedded_image_size = (uint32_t) &(_binary_size); diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj index 45267f708..5dd95349b 100644 --- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj +++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj @@ -3125,6 +3125,52 @@ 65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = ""; }; 65FC66AA123F30F100B04F74 /* ahrs_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_timer.c; path = ../../AHRS/ahrs_timer.c; sourceTree = SOURCE_ROOT; }; 65FC66AB123F312A00B04F74 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = ""; }; + 65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_slave_test.c; sourceTree = ""; }; + 65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program.c; sourceTree = ""; }; + 65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_master.c; sourceTree = ""; }; + 65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ahrs_spi_program_slave.c; sourceTree = ""; }; + 65FF4BB913791C3300146BE4 /* bl_fsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = bl_fsm.c; sourceTree = ""; }; + 65FF4BBB13791C3300146BE4 /* ahrs_bl.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_bl.h; sourceTree = ""; }; + 65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program.h; sourceTree = ""; }; + 65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_master.h; sourceTree = ""; }; + 65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_spi_program_slave.h; sourceTree = ""; }; + 65FF4BBF13791C3300146BE4 /* bl_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = bl_fsm.h; sourceTree = ""; }; + 65FF4BC013791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; + 65FF4BC113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 65FF4BC213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; + 65FF4BC313791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; + 65FF4BC613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; + 65FF4BC713791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 65FF4BC813791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; + 65FF4BC913791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; + 65FF4BCA13791C3300146BE4 /* test.bin */ = {isa = PBXFileReference; lastKnownFileType = archive.macbinary; path = test.bin; sourceTree = ""; }; + 65FF4BCD13791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; + 65FF4BCE13791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; + 65FF4BCF13791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; + 65FF4BD013791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; + 65FF4BD113791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 65FF4BD213791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; + 65FF4BD313791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; + 65FF4BD413791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; + 65FF4BD713791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; + 65FF4BD813791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; + 65FF4BD913791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; + 65FF4BDA13791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; + 65FF4BDB13791C3300146BE4 /* ssp.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ssp.h; sourceTree = ""; }; + 65FF4BDC13791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 65FF4BDD13791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; + 65FF4BDE13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; + 65FF4BDF13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; + 65FF4BE013791C3300146BE4 /* ssp.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp.c; sourceTree = ""; }; + 65FF4BE113791C3300146BE4 /* ssp_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ssp_timer.c; sourceTree = ""; }; + 65FF4BE413791C3300146BE4 /* common.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = common.h; sourceTree = ""; }; + 65FF4BE513791C3300146BE4 /* op_dfu.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_dfu.h; sourceTree = ""; }; + 65FF4BE613791C3300146BE4 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = ""; }; + 65FF4BE713791C3300146BE4 /* pios_usb.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb.h; sourceTree = ""; }; + 65FF4BE813791C3300146BE4 /* main.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = main.c; sourceTree = ""; }; + 65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; + 65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; + 65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; /* End PBXFileReference section */ /* Begin PBXGroup section */ @@ -3505,6 +3551,7 @@ 657CEEB5121DBC49007A1FBE /* flight */ = { isa = PBXGroup; children = ( + 65FF4BB313791C3300146BE4 /* Bootloaders */, 65F93B9012EE09280047DB36 /* PipXtreme */, 65B7E6AC120DF1CD000C1123 /* AHRS */, 65E6DF7012E02E8E00058553 /* CopterControl */, @@ -8238,6 +8285,140 @@ path = inc; sourceTree = ""; }; + 65FF4BB313791C3300146BE4 /* Bootloaders */ = { + isa = PBXGroup; + children = ( + 65FF4BB413791C3300146BE4 /* AHRS */, + 65FF4BC413791C3300146BE4 /* BootloaderUpdater */, + 65FF4BCB13791C3300146BE4 /* CopterControl */, + 65FF4BD513791C3300146BE4 /* OpenPilot */, + 65FF4BE213791C3300146BE4 /* PipXtreme */, + ); + name = Bootloaders; + path = ../../Bootloaders; + sourceTree = SOURCE_ROOT; + }; + 65FF4BB413791C3300146BE4 /* AHRS */ = { + isa = PBXGroup; + children = ( + 65FF4BB513791C3300146BE4 /* ahrs_slave_test.c */, + 65FF4BB613791C3300146BE4 /* ahrs_spi_program.c */, + 65FF4BB713791C3300146BE4 /* ahrs_spi_program_master.c */, + 65FF4BB813791C3300146BE4 /* ahrs_spi_program_slave.c */, + 65FF4BB913791C3300146BE4 /* bl_fsm.c */, + 65FF4BBA13791C3300146BE4 /* inc */, + 65FF4BC113791C3300146BE4 /* main.c */, + 65FF4BC213791C3300146BE4 /* Makefile */, + 65FF4BC313791C3300146BE4 /* pios_board.c */, + ); + path = AHRS; + sourceTree = ""; + }; + 65FF4BBA13791C3300146BE4 /* inc */ = { + isa = PBXGroup; + children = ( + 65FF4BBB13791C3300146BE4 /* ahrs_bl.h */, + 65FF4BBC13791C3300146BE4 /* ahrs_spi_program.h */, + 65FF4BBD13791C3300146BE4 /* ahrs_spi_program_master.h */, + 65FF4BBE13791C3300146BE4 /* ahrs_spi_program_slave.h */, + 65FF4BBF13791C3300146BE4 /* bl_fsm.h */, + 65FF4BC013791C3300146BE4 /* pios_config.h */, + ); + path = inc; + sourceTree = ""; + }; + 65FF4BC413791C3300146BE4 /* BootloaderUpdater */ = { + isa = PBXGroup; + children = ( + 65FF4BC513791C3300146BE4 /* inc */, + 65FF4BC713791C3300146BE4 /* main.c */, + 65FF4BC813791C3300146BE4 /* Makefile */, + 65FF4BC913791C3300146BE4 /* pios_board.c */, + 65FF4BCA13791C3300146BE4 /* test.bin */, + ); + path = BootloaderUpdater; + sourceTree = ""; + }; + 65FF4BC513791C3300146BE4 /* inc */ = { + isa = PBXGroup; + children = ( + 65FF4BC613791C3300146BE4 /* pios_config.h */, + ); + path = inc; + sourceTree = ""; + }; + 65FF4BCB13791C3300146BE4 /* CopterControl */ = { + isa = PBXGroup; + children = ( + 65FF4BCC13791C3300146BE4 /* inc */, + 65FF4BD113791C3300146BE4 /* main.c */, + 65FF4BD213791C3300146BE4 /* Makefile */, + 65FF4BD313791C3300146BE4 /* op_dfu.c */, + 65FF4BD413791C3300146BE4 /* pios_board.c */, + ); + path = CopterControl; + sourceTree = ""; + }; + 65FF4BCC13791C3300146BE4 /* inc */ = { + isa = PBXGroup; + children = ( + 65FF4BCD13791C3300146BE4 /* common.h */, + 65FF4BCE13791C3300146BE4 /* op_dfu.h */, + 65FF4BCF13791C3300146BE4 /* pios_config.h */, + 65FF4BD013791C3300146BE4 /* pios_usb.h */, + ); + path = inc; + sourceTree = ""; + }; + 65FF4BD513791C3300146BE4 /* OpenPilot */ = { + isa = PBXGroup; + children = ( + 65FF4BD613791C3300146BE4 /* inc */, + 65FF4BDC13791C3300146BE4 /* main.c */, + 65FF4BDD13791C3300146BE4 /* Makefile */, + 65FF4BDE13791C3300146BE4 /* op_dfu.c */, + 65FF4BDF13791C3300146BE4 /* pios_board.c */, + 65FF4BE013791C3300146BE4 /* ssp.c */, + 65FF4BE113791C3300146BE4 /* ssp_timer.c */, + ); + path = OpenPilot; + sourceTree = ""; + }; + 65FF4BD613791C3300146BE4 /* inc */ = { + isa = PBXGroup; + children = ( + 65FF4BD713791C3300146BE4 /* common.h */, + 65FF4BD813791C3300146BE4 /* op_dfu.h */, + 65FF4BD913791C3300146BE4 /* pios_config.h */, + 65FF4BDA13791C3300146BE4 /* pios_usb.h */, + 65FF4BDB13791C3300146BE4 /* ssp.h */, + ); + path = inc; + sourceTree = ""; + }; + 65FF4BE213791C3300146BE4 /* PipXtreme */ = { + isa = PBXGroup; + children = ( + 65FF4BE313791C3300146BE4 /* inc */, + 65FF4BE813791C3300146BE4 /* main.c */, + 65FF4BE913791C3300146BE4 /* Makefile */, + 65FF4BEA13791C3300146BE4 /* op_dfu.c */, + 65FF4BEB13791C3300146BE4 /* pios_board.c */, + ); + path = PipXtreme; + sourceTree = ""; + }; + 65FF4BE313791C3300146BE4 /* inc */ = { + isa = PBXGroup; + children = ( + 65FF4BE413791C3300146BE4 /* common.h */, + 65FF4BE513791C3300146BE4 /* op_dfu.h */, + 65FF4BE613791C3300146BE4 /* pios_config.h */, + 65FF4BE713791C3300146BE4 /* pios_usb.h */, + ); + path = inc; + sourceTree = ""; + }; C6A0FF2B0290797F04C91782 /* Documentation */ = { isa = PBXGroup; children = ( From 163d41fb604620854addbd8b71fca33df2d1aa8f Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 10 May 2011 02:43:55 -0500 Subject: [PATCH 02/43] OP-466: Make the test output panel work when there is not a valid mixer configured. However unlike previous patch keeps alarms showing so you will be unable to arm normally. --- flight/Modules/Actuator/actuator.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index c0a52b426..2766e1e0a 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -182,7 +182,7 @@ static void actuatorTask(void* parameters) nMixers ++; } } - if(nMixers < 2) //Nothing can fly with less than two mixers. + if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers. { setFailsafe(); // So that channels like PWM buzzer keep working continue; From fdd591b7000c96cd40ad197f0eb192e0c88b22b4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Tue, 10 May 2011 14:40:21 -0500 Subject: [PATCH 03/43] OP-488: If the FirmwareIAP receives a halt signal but system is not disarmed abort the halt. --- flight/Modules/FirmwareIAP/firmwareiap.c | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c index 71de8c390..11e8721fd 100644 --- a/flight/Modules/FirmwareIAP/firmwareiap.c +++ b/flight/Modules/FirmwareIAP/firmwareiap.c @@ -30,6 +30,7 @@ #include "openpilot.h" #include "firmwareiap.h" #include "firmwareiapobj.h" +#include "flightstatus.h" // Private constants #define IAP_CMD_STEP_1 1122 @@ -156,6 +157,16 @@ static void FirmwareIAPCallback(UAVObjEvent* ev) case IAP_STATE_STEP_2: if( data.Command == IAP_CMD_STEP_3 ) { if( delta > iap_time_3_low_end && delta < iap_time_3_high_end ) { + + FlightStatusData flightStatus; + FlightStatusGet(&flightStatus); + + if(flightStatus.Armed != FLIGHTSTATUS_ARMED_DISARMED) { + // Abort any attempts if not disarmed + iap_state = IAP_STATE_READY; + break; + } + // we've met the three sequence of command numbers // we've met the time requirements. PIOS_IAP_SetRequest1(); From 5d28276c49a6b0f8560808ed9aded01a428af782 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 11 May 2011 17:35:52 -0500 Subject: [PATCH 04/43] Reshuffle memory allocation on CC after FlightStatus object introduced --- flight/CopterControl/System/inc/pios_config.h | 10 +++++----- flight/Modules/System/systemmod.c | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 4362dbca2..af1b7d22d 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -84,16 +84,16 @@ #define AUXUART_BAUDRATE 19200 /* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 450 -#define HEAP_LIMIT_CRITICAL 350 +#define HEAP_LIMIT_WARNING 350 +#define HEAP_LIMIT_CRITICAL 250 #define CPULOAD_LIMIT_WARNING 80 #define CPULOAD_LIMIT_CRITICAL 95 /* Task stack sizes */ #define PIOS_ACTUATOR_STACK_SIZE 1020 -#define PIOS_MANUAL_STACK_SIZE 644 -#define PIOS_SYSTEM_STACK_SIZE 644 -#define PIOS_STABILIZATION_STACK_SIZE 624 +#define PIOS_MANUAL_STACK_SIZE 724 +#define PIOS_SYSTEM_STACK_SIZE 504 +#define PIOS_STABILIZATION_STACK_SIZE 524 #define PIOS_TELEM_STACK_SIZE 500 #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 1cc3a6a5b..c36160a1e 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -59,8 +59,8 @@ // optimisation options are changed. #endif -#if defined(PIOS_MANUAL_STACK_SIZE) -#define STACK_SIZE_BYTES PIOS_MANUAL_STACK_SIZE +#if defined(PIOS_SYSTEM_STACK_SIZE) +#define STACK_SIZE_BYTES PIOS_SYSTEM_STACK_SIZE #else #define STACK_SIZE_BYTES 924 #endif From 69c27aa1ce969fb4e4e34303a1827d4e908f4943 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 11 May 2011 17:45:14 -0500 Subject: [PATCH 05/43] Move "zero while arming" option to below other CC Attitude widgets. Was overlapping other fields. --- .../src/plugins/config/ccattitude.ui | 24 +++++++++---------- 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/ccattitude.ui b/ground/openpilotgcs/src/plugins/config/ccattitude.ui index 7c138ecd8..b6b00126c 100644 --- a/ground/openpilotgcs/src/plugins/config/ccattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/ccattitude.ui @@ -142,18 +142,6 @@ - - - - If enabled, a fast recalibration of gyro zero point will be done -whenever the frame is armed. Do not move the airframe while -arming it in that case! - - - Zero gyro bias upon airframe arming - - - @@ -253,6 +241,18 @@ arming it in that case! + + + + If enabled, a fast recalibration of gyro zero point will be done +whenever the frame is armed. Do not move the airframe while +arming it in that case! + + + Zero gyro bias upon airframe arming + + + From 338d3632890cd5e81bbafcf34e619f41043e076a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Wed, 11 May 2011 20:09:28 -0500 Subject: [PATCH 06/43] When a channel is disabled in the mixer force the channel to have a 0 us pulse duration. The default before was neutral in failsafe. --- flight/Modules/Actuator/actuator.c | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 2766e1e0a..b2f143adf 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -198,8 +198,12 @@ static void actuatorTask(void* parameters) float curve2 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve2); for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) { - if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) + if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) { + // Set to minimum if disabled. This is not the same as saying PWM pulse = 0 us + status[ct] = -1; + command.Channel[ct] = 0; continue; + } status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT); @@ -400,14 +404,19 @@ static void setFailsafe() // Reset ActuatorCommand to safe values for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { + if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { command.Channel[n] = settings.ChannelMin[n]; } - else + else if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_SERVO) { command.Channel[n] = settings.ChannelNeutral[n]; } + else + { + command.Channel[n] = 0; + } } // Set alarm From ab7fdfcc1fe105206b1ba0472c6f918287e2f3f1 Mon Sep 17 00:00:00 2001 From: elafargue Date: Thu, 12 May 2011 16:32:38 +0200 Subject: [PATCH 07/43] OPReview-40 : Disable min/max output channel range controls when doing a servo test, in order to avoid mistakes by careless users. --- .../src/plugins/config/configoutputwidget.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index a762ce742..5ef3daf72 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -265,10 +265,27 @@ void ConfigOutputWidget::runChannelTests(bool state) mdata.gcsTelemetryAcked = false; mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; mdata.gcsTelemetryUpdatePeriod = 100; + + // Prevent stupid users from touching the minimum & maximum ranges while + // moving the sliders. Thanks Ivan for the tip :) + foreach (QSpinBox* box, outMin) { + box->setEnabled(false); + } + foreach (QSpinBox* box, outMax) { + box->setEnabled(false); + } + } else { mdata = accInitialData; // Restore metadata + foreach (QSpinBox* box, outMin) { + box->setEnabled(true); + } + foreach (QSpinBox* box, outMax) { + box->setEnabled(true); + } + } obj->setMetadata(mdata); From dceae1a9b095b56a08096ffda347e0c83b1f3f67 Mon Sep 17 00:00:00 2001 From: elafargue Date: Fri, 13 May 2011 00:01:31 +0200 Subject: [PATCH 08/43] Make bargraph dials better (color and range for roll/pitch/yaw are now correct). Disable use of OpenGL by default on config to ensure max compatibility with all graphics cards. --- .../src/plugins/coreplugin/OpenPilotGCS.ini | 400 +++++++++--------- .../gcscontrol/gcscontrolgadgetwidget.cpp | 6 +- 2 files changed, 204 insertions(+), 202 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini index 37f9d42f5..c9a898c34 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini @@ -1,5 +1,5 @@ [General] -ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5\xa0\0\0\x3/\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0) +ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5V\0\0\x2\x9a\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0) [Workspace] NumberOfWorkspaces=6 @@ -42,19 +42,127 @@ Mode1\splitter\side0\side0\type=splitter Mode1\splitter\side0\side0\splitterOrientation=1 Mode1\splitter\side0\side0\splitterSizes=144, 608 Mode1\splitter\side0\side0\side0\type=splitter +Mode1\splitter\side0\side0\side0\splitterOrientation=2 +Mode1\splitter\side0\side0\side0\splitterSizes=215, 237 +Mode1\splitter\side0\side0\side0\side0\type=splitter +Mode1\splitter\side0\side0\side0\side0\splitterOrientation=2 +Mode1\splitter\side0\side0\side0\side0\splitterSizes=@Invalid() +Mode1\splitter\side0\side0\side0\side0\side0\type=uavGadget +Mode1\splitter\side0\side0\side0\side0\side0\classId=LineardialGadget +Mode1\splitter\side0\side0\side0\side0\side0\gadget\activeConfiguration=Flight Time +Mode1\splitter\side0\side0\side0\side0\side1\type=uavGadget +Mode1\splitter\side0\side0\side0\side0\side1\classId=LineardialGadget +Mode1\splitter\side0\side0\side0\side0\side1\gadget\activeConfiguration=GPS Sats +Mode1\splitter\side0\side0\side0\side1\type=splitter +Mode1\splitter\side0\side0\side0\side1\splitterOrientation=2 +Mode1\splitter\side0\side0\side0\side1\splitterSizes=@Invalid() +Mode1\splitter\side0\side0\side0\side1\side0\type=uavGadget +Mode1\splitter\side0\side0\side0\side1\side0\classId=LineardialGadget +Mode1\splitter\side0\side0\side0\side1\side0\gadget\activeConfiguration=Flight mode +Mode1\splitter\side0\side0\side0\side1\side1\type=uavGadget +Mode1\splitter\side0\side0\side0\side1\side1\classId=LineardialGadget +Mode1\splitter\side0\side0\side0\side1\side1\gadget\activeConfiguration=Arm Status Mode1\splitter\side0\side0\side1\type=uavGadget +Mode1\splitter\side0\side0\side1\classId=PFDGadget +Mode1\splitter\side0\side0\side1\gadget\activeConfiguration=raw Mode1\splitter\side0\side1\type=splitter +Mode1\splitter\side0\side1\splitterOrientation=1 +Mode1\splitter\side0\side1\splitterSizes=304, 433 +Mode1\splitter\side0\side1\side0\type=uavGadget +Mode1\splitter\side0\side1\side0\classId=ModelViewGadget +Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X +Mode1\splitter\side0\side1\side1\type=splitter +Mode1\splitter\side0\side1\side1\splitterOrientation=2 +Mode1\splitter\side0\side1\side1\splitterSizes=293, 64 +Mode1\splitter\side0\side1\side1\side0\type=splitter +Mode1\splitter\side0\side1\side1\side0\splitterOrientation=1 +Mode1\splitter\side0\side1\side1\side0\splitterSizes=291, 141 +Mode1\splitter\side0\side1\side1\side0\side0\type=uavGadget +Mode1\splitter\side0\side1\side1\side0\side0\classId=SystemHealthGadget +Mode1\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=default +Mode1\splitter\side0\side1\side1\side0\side1\type=splitter +Mode1\splitter\side0\side1\side1\side0\side1\splitterOrientation=1 +Mode1\splitter\side0\side1\side1\side0\side1\splitterSizes=64, 64 +Mode1\splitter\side0\side1\side1\side0\side1\side0\type=uavGadget +Mode1\splitter\side0\side1\side1\side0\side1\side0\classId=LineardialGadget +Mode1\splitter\side0\side1\side1\side0\side1\side0\gadget\activeConfiguration=Mainboard CPU +Mode1\splitter\side0\side1\side1\side0\side1\side1\type=uavGadget +Mode1\splitter\side0\side1\side1\side0\side1\side1\classId=LineardialGadget +Mode1\splitter\side0\side1\side1\side0\side1\side1\gadget\activeConfiguration=AHRS CPU +Mode1\splitter\side0\side1\side1\side1\type=splitter +Mode1\splitter\side0\side1\side1\side1\splitterOrientation=1 +Mode1\splitter\side0\side1\side1\side1\splitterSizes=@Invalid() +Mode1\splitter\side0\side1\side1\side1\side0\type=uavGadget +Mode1\splitter\side0\side1\side1\side1\side0\classId=LineardialGadget +Mode1\splitter\side0\side1\side1\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Horizontal +Mode1\splitter\side0\side1\side1\side1\side1\type=uavGadget +Mode1\splitter\side0\side1\side1\side1\side1\classId=LineardialGadget +Mode1\splitter\side0\side1\side1\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal Mode1\splitter\side1\type=splitter Mode1\splitter\side1\splitterOrientation=2 Mode1\splitter\side1\splitterSizes=492, 288 Mode1\splitter\side1\side0\type=uavGadget +Mode1\splitter\side1\side0\classId=OPMapGadget +Mode1\splitter\side1\side0\gadget\activeConfiguration=Google Sat Mode1\splitter\side1\side1\type=splitter Mode1\splitter\side1\side1\splitterOrientation=1 Mode1\splitter\side1\side1\splitterSizes=441, 259 Mode1\splitter\side1\side1\side0\type=splitter +Mode1\splitter\side1\side1\side0\splitterOrientation=1 +Mode1\splitter\side1\side1\side0\splitterSizes=277, 135 +Mode1\splitter\side1\side1\side0\side0\type=splitter +Mode1\splitter\side1\side1\side0\side0\splitterOrientation=1 +Mode1\splitter\side1\side1\side0\side0\splitterSizes=131, 138 +Mode1\splitter\side1\side1\side0\side0\side0\type=splitter +Mode1\splitter\side1\side1\side0\side0\side0\splitterOrientation=2 +Mode1\splitter\side1\side1\side0\side0\side0\splitterSizes=@Invalid() +Mode1\splitter\side1\side1\side0\side0\side0\side0\type=uavGadget +Mode1\splitter\side1\side1\side0\side0\side0\side0\classId=DialGadget +Mode1\splitter\side1\side1\side0\side0\side0\side0\gadget\activeConfiguration=Deluxe Groundspeed kph +Mode1\splitter\side1\side1\side0\side0\side0\side1\type=uavGadget +Mode1\splitter\side1\side1\side0\side0\side0\side1\classId=DialGadget +Mode1\splitter\side1\side1\side0\side0\side0\side1\gadget\activeConfiguration=Deluxe Barometer +Mode1\splitter\side1\side1\side0\side0\side1\type=splitter +Mode1\splitter\side1\side1\side0\side0\side1\splitterOrientation=2 +Mode1\splitter\side1\side1\side0\side0\side1\splitterSizes=@Invalid() +Mode1\splitter\side1\side1\side0\side0\side1\side0\type=uavGadget +Mode1\splitter\side1\side1\side0\side0\side1\side0\classId=DialGadget +Mode1\splitter\side1\side1\side0\side0\side1\side0\gadget\activeConfiguration=Deluxe Attitude +Mode1\splitter\side1\side1\side0\side0\side1\side1\type=uavGadget +Mode1\splitter\side1\side1\side0\side0\side1\side1\classId=DialGadget +Mode1\splitter\side1\side1\side0\side0\side1\side1\gadget\activeConfiguration=Deluxe Compass +Mode1\splitter\side1\side1\side0\side1\type=splitter +Mode1\splitter\side1\side1\side0\side1\splitterOrientation=2 +Mode1\splitter\side1\side1\side0\side1\splitterSizes=@Invalid() +Mode1\splitter\side1\side1\side0\side1\side0\type=uavGadget +Mode1\splitter\side1\side1\side0\side1\side0\classId=DialGadget +Mode1\splitter\side1\side1\side0\side1\side0\gadget\activeConfiguration=Deluxe Baro Altimeter +Mode1\splitter\side1\side1\side0\side1\side1\type=uavGadget +Mode1\splitter\side1\side1\side0\side1\side1\classId=DialGadget +Mode1\splitter\side1\side1\side0\side1\side1\gadget\activeConfiguration=Deluxe Climbrate Mode1\splitter\side1\side1\side1\type=splitter +Mode1\splitter\side1\side1\side1\splitterOrientation=1 +Mode1\splitter\side1\side1\side1\splitterSizes=64, 441 +Mode1\splitter\side1\side1\side1\side0\type=uavGadget +Mode1\splitter\side1\side1\side1\side0\classId=LineardialGadget +Mode1\splitter\side1\side1\side1\side0\gadget\activeConfiguration=Throttle +Mode1\splitter\side1\side1\side1\side1\type=splitter +Mode1\splitter\side1\side1\side1\side1\splitterOrientation=1 +Mode1\splitter\side1\side1\side1\side1\splitterSizes=64, 376 +Mode1\splitter\side1\side1\side1\side1\side0\type=uavGadget +Mode1\splitter\side1\side1\side1\side1\side0\classId=LineardialGadget +Mode1\splitter\side1\side1\side1\side1\side0\gadget\activeConfiguration=Roll +Mode1\splitter\side1\side1\side1\side1\side1\type=splitter +Mode1\splitter\side1\side1\side1\side1\side1\splitterOrientation=1 +Mode1\splitter\side1\side1\side1\side1\side1\splitterSizes=64, 311 +Mode1\splitter\side1\side1\side1\side1\side1\side0\type=uavGadget +Mode1\splitter\side1\side1\side1\side1\side1\side0\classId=LineardialGadget +Mode1\splitter\side1\side1\side1\side1\side1\side0\gadget\activeConfiguration=Pitch +Mode1\splitter\side1\side1\side1\side1\side1\side1\type=uavGadget +Mode1\splitter\side1\side1\side1\side1\side1\side1\classId=LineardialGadget +Mode1\splitter\side1\side1\side1\side1\side1\side1\gadget\activeConfiguration=Yaw Mode2\version=UAVGadgetManagerV1 -Mode2\showToolbars=false +Mode2\showToolbars=true Mode2\splitter\type=splitter Mode2\splitter\splitterOrientation=1 Mode2\splitter\splitterSizes=734, 631 @@ -111,11 +219,28 @@ Mode4\splitter\type=splitter Mode4\splitter\splitterOrientation=1 Mode4\splitter\splitterSizes=653, 660 Mode4\splitter\side0\type=splitter +Mode4\splitter\side0\splitterOrientation=2 +Mode4\splitter\side0\splitterSizes=@Invalid() +Mode4\splitter\side0\side0\type=uavGadget +Mode4\splitter\side0\side0\classId=ScopeGadget +Mode4\splitter\side0\side0\gadget\activeConfiguration=Accel +Mode4\splitter\side0\side1\type=uavGadget +Mode4\splitter\side0\side1\classId=ScopeGadget +Mode4\splitter\side0\side1\gadget\activeConfiguration=Raw Gyros Mode4\splitter\side1\type=splitter Mode4\splitter\side1\splitterOrientation=2 Mode4\splitter\side1\splitterSizes=661, 119 Mode4\splitter\side1\side0\type=splitter +Mode4\splitter\side1\side0\splitterOrientation=2 +Mode4\splitter\side1\side0\splitterSizes=390, 270 +Mode4\splitter\side1\side0\side0\type=uavGadget +Mode4\splitter\side1\side0\side0\classId=ScopeGadget +Mode4\splitter\side1\side0\side0\gadget\activeConfiguration=Attitude +Mode4\splitter\side1\side0\side1\type=uavGadget +Mode4\splitter\side1\side0\side1\classId=ScopeGadget +Mode4\splitter\side1\side0\side1\gadget\activeConfiguration=Uptimes Mode4\splitter\side1\side1\type=uavGadget +Mode4\splitter\side1\side1\classId=LoggingGadget Mode5\version=UAVGadgetManagerV1 Mode5\showToolbars=false Mode5\splitter\type=splitter @@ -147,138 +272,13 @@ Mode5\splitter\side0\side1\side1\side0\side1\classId=LineardialGadget Mode5\splitter\side0\side1\side1\side0\side1\gadget\activeConfiguration=PitchActual Mode5\splitter\side0\side1\side1\side1\type=uavGadget Mode5\splitter\side0\side1\side1\side1\classId=LineardialGadget -Mode5\splitter\side0\side1\side1\side1\gadget\activeConfiguration=PitchCommand +Mode5\splitter\side0\side1\side1\side1\gadget\activeConfiguration=Pitch Mode5\splitter\side1\type=uavGadget Mode5\splitter\side1\classId=UAVObjectBrowser Mode5\splitter\side1\gadget\activeConfiguration=default -Mode1\splitter\side0\side0\side0\splitterOrientation=2 -Mode1\splitter\side0\side0\side0\splitterSizes=215, 237 -Mode1\splitter\side0\side0\side0\side0\type=splitter -Mode1\splitter\side0\side0\side0\side1\type=splitter -Mode1\splitter\side0\side0\side0\side1\splitterOrientation=2 -Mode1\splitter\side0\side0\side0\side1\splitterSizes=@Invalid() -Mode1\splitter\side0\side0\side0\side1\side0\type=uavGadget -Mode1\splitter\side0\side0\side0\side1\side0\classId=LineardialGadget -Mode1\splitter\side0\side0\side0\side1\side0\gadget\activeConfiguration=Flight mode -Mode1\splitter\side0\side0\side0\side1\side1\type=uavGadget -Mode1\splitter\side0\side0\side0\side1\side1\classId=LineardialGadget -Mode1\splitter\side0\side0\side0\side1\side1\gadget\activeConfiguration=Arm Status -Mode1\splitter\side1\side0\classId=OPMapGadget -Mode1\splitter\side1\side0\gadget\activeConfiguration=Google Sat -Mode1\splitter\side1\side1\side0\splitterOrientation=1 -Mode1\splitter\side1\side1\side0\splitterSizes=277, 135 -Mode1\splitter\side1\side1\side0\side0\type=splitter -Mode1\splitter\side1\side1\side0\side1\type=splitter -Mode1\splitter\side0\side1\splitterOrientation=1 -Mode1\splitter\side0\side1\splitterSizes=304, 433 -Mode1\splitter\side0\side1\side0\type=uavGadget -Mode1\splitter\side0\side1\side1\type=splitter -Mode1\splitter\side0\side1\side1\splitterOrientation=2 -Mode1\splitter\side0\side1\side1\splitterSizes=293, 64 -Mode1\splitter\side0\side1\side1\side0\type=splitter -Mode1\splitter\side0\side1\side1\side1\type=splitter -Mode1\splitter\side1\side1\side0\side0\splitterOrientation=1 -Mode1\splitter\side1\side1\side0\side0\splitterSizes=131, 138 -Mode1\splitter\side1\side1\side0\side0\side0\type=splitter -Mode1\splitter\side1\side1\side0\side0\side1\type=splitter -Mode1\splitter\side0\side1\side0\classId=ModelViewGadget -Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X -Mode1\splitter\side0\side1\side1\side0\splitterOrientation=1 -Mode1\splitter\side0\side1\side1\side0\splitterSizes=291, 141 -Mode1\splitter\side0\side1\side1\side0\side0\type=uavGadget -Mode1\splitter\side0\side1\side1\side0\side0\classId=SystemHealthGadget -Mode1\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=default -Mode1\splitter\side0\side1\side1\side0\side1\type=splitter -Mode1\splitter\side0\side1\side1\side1\splitterOrientation=1 -Mode1\splitter\side0\side1\side1\side1\splitterSizes=@Invalid() -Mode1\splitter\side0\side1\side1\side1\side0\type=uavGadget -Mode1\splitter\side0\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side0\side1\side1\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Horizontal -Mode1\splitter\side0\side1\side1\side1\side1\type=uavGadget -Mode1\splitter\side0\side1\side1\side1\side1\classId=LineardialGadget -Mode1\splitter\side0\side1\side1\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal -Mode1\splitter\side0\side1\side1\side0\side1\splitterOrientation=1 -Mode1\splitter\side0\side1\side1\side0\side1\splitterSizes=64, 64 -Mode1\splitter\side0\side1\side1\side0\side1\side0\type=uavGadget -Mode1\splitter\side0\side1\side1\side0\side1\side0\classId=LineardialGadget -Mode1\splitter\side0\side1\side1\side0\side1\side0\gadget\activeConfiguration=Mainboard CPU -Mode1\splitter\side0\side1\side1\side0\side1\side1\type=uavGadget -Mode1\splitter\side0\side1\side1\side0\side1\side1\classId=LineardialGadget -Mode1\splitter\side0\side1\side1\side0\side1\side1\gadget\activeConfiguration=AHRS CPU -Mode1\splitter\side1\side1\side0\side0\side0\splitterOrientation=2 -Mode1\splitter\side1\side1\side0\side0\side0\splitterSizes=@Invalid() -Mode1\splitter\side1\side1\side0\side0\side0\side0\type=uavGadget -Mode1\splitter\side1\side1\side0\side0\side0\side0\classId=DialGadget -Mode1\splitter\side1\side1\side0\side0\side0\side0\gadget\activeConfiguration=Deluxe Groundspeed kph -Mode1\splitter\side1\side1\side0\side0\side0\side1\type=uavGadget -Mode1\splitter\side1\side1\side0\side0\side0\side1\classId=DialGadget -Mode1\splitter\side1\side1\side0\side0\side0\side1\gadget\activeConfiguration=Deluxe Barometer -Mode1\splitter\side1\side1\side0\side0\side1\splitterOrientation=2 -Mode1\splitter\side1\side1\side0\side0\side1\splitterSizes=@Invalid() -Mode1\splitter\side1\side1\side0\side0\side1\side0\type=uavGadget -Mode1\splitter\side1\side1\side0\side0\side1\side0\classId=DialGadget -Mode1\splitter\side1\side1\side0\side0\side1\side0\gadget\activeConfiguration=Deluxe Attitude -Mode1\splitter\side1\side1\side0\side0\side1\side1\type=uavGadget -Mode1\splitter\side1\side1\side0\side0\side1\side1\classId=DialGadget -Mode1\splitter\side1\side1\side0\side0\side1\side1\gadget\activeConfiguration=Deluxe Compass -Mode1\splitter\side1\side1\side0\side1\splitterOrientation=2 -Mode1\splitter\side1\side1\side0\side1\splitterSizes=@Invalid() -Mode1\splitter\side1\side1\side0\side1\side0\type=uavGadget -Mode1\splitter\side1\side1\side0\side1\side0\classId=DialGadget -Mode1\splitter\side1\side1\side0\side1\side0\gadget\activeConfiguration=Deluxe Baro Altimeter -Mode1\splitter\side1\side1\side0\side1\side1\type=uavGadget -Mode1\splitter\side1\side1\side0\side1\side1\classId=DialGadget -Mode1\splitter\side1\side1\side0\side1\side1\gadget\activeConfiguration=Deluxe Climbrate -Mode1\splitter\side0\side0\side0\side0\splitterOrientation=2 -Mode1\splitter\side0\side0\side0\side0\splitterSizes=@Invalid() -Mode1\splitter\side0\side0\side0\side0\side0\type=uavGadget -Mode1\splitter\side0\side0\side0\side0\side0\classId=LineardialGadget -Mode1\splitter\side0\side0\side0\side0\side0\gadget\activeConfiguration=Flight Time -Mode1\splitter\side0\side0\side0\side0\side1\type=uavGadget -Mode1\splitter\side0\side0\side0\side0\side1\classId=LineardialGadget -Mode1\splitter\side0\side0\side0\side0\side1\gadget\activeConfiguration=GPS Sats -Mode1\splitter\side0\side0\side1\classId=PFDGadget -Mode1\splitter\side0\side0\side1\gadget\activeConfiguration=raw -Mode1\splitter\side1\side1\side1\splitterOrientation=1 -Mode1\splitter\side1\side1\side1\splitterSizes=64, 441 -Mode1\splitter\side1\side1\side1\side0\type=uavGadget -Mode1\splitter\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side0\gadget\activeConfiguration=Throttle -Mode1\splitter\side1\side1\side1\side1\type=splitter -Mode1\splitter\side1\side1\side1\side1\splitterOrientation=1 -Mode1\splitter\side1\side1\side1\side1\splitterSizes=64, 376 -Mode1\splitter\side1\side1\side1\side1\side0\type=uavGadget -Mode1\splitter\side1\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side0\gadget\activeConfiguration=Roll -Mode1\splitter\side1\side1\side1\side1\side1\type=splitter -Mode1\splitter\side1\side1\side1\side1\side1\splitterOrientation=1 -Mode1\splitter\side1\side1\side1\side1\side1\splitterSizes=64, 311 -Mode1\splitter\side1\side1\side1\side1\side1\side0\type=uavGadget -Mode1\splitter\side1\side1\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side1\side0\gadget\activeConfiguration=PitchActual -Mode1\splitter\side1\side1\side1\side1\side1\side1\type=uavGadget -Mode1\splitter\side1\side1\side1\side1\side1\side1\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side1\side1\gadget\activeConfiguration=Yaw Mode6\version=UAVGadgetManagerV1 Mode6\showToolbars=false Mode6\splitter\type=splitter -Mode4\splitter\side0\splitterOrientation=2 -Mode4\splitter\side0\splitterSizes=@Invalid() -Mode4\splitter\side0\side0\type=uavGadget -Mode4\splitter\side0\side0\classId=ScopeGadget -Mode4\splitter\side0\side0\gadget\activeConfiguration=Accel -Mode4\splitter\side0\side1\type=uavGadget -Mode4\splitter\side0\side1\classId=ScopeGadget -Mode4\splitter\side0\side1\gadget\activeConfiguration=Raw Gyros -Mode4\splitter\side1\side0\splitterOrientation=2 -Mode4\splitter\side1\side0\splitterSizes=390, 270 -Mode4\splitter\side1\side0\side0\type=uavGadget -Mode4\splitter\side1\side0\side0\classId=ScopeGadget -Mode4\splitter\side1\side0\side0\gadget\activeConfiguration=Attitude -Mode4\splitter\side1\side0\side1\type=uavGadget -Mode4\splitter\side1\side0\side1\classId=ScopeGadget -Mode4\splitter\side1\side0\side1\gadget\activeConfiguration=Uptimes -Mode4\splitter\side1\side1\classId=LoggingGadget Mode6\splitter\splitterOrientation=1 Mode6\splitter\splitterSizes=@Invalid() Mode6\splitter\side0\type=uavGadget @@ -288,9 +288,6 @@ Mode6\splitter\side1\type=splitter Mode6\splitter\side1\splitterOrientation=2 Mode6\splitter\side1\splitterSizes=274, 506 Mode6\splitter\side1\side0\type=splitter -Mode6\splitter\side1\side1\type=uavGadget -Mode6\splitter\side1\side1\classId=ScopeGadget -Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes Mode6\splitter\side1\side0\splitterOrientation=1 Mode6\splitter\side1\side0\splitterSizes=322, 396 Mode6\splitter\side1\side0\side0\type=uavGadget @@ -299,17 +296,20 @@ Mode6\splitter\side1\side0\side0\gadget\activeConfiguration=default Mode6\splitter\side1\side0\side1\type=uavGadget Mode6\splitter\side1\side0\side1\classId=PFDGadget Mode6\splitter\side1\side0\side1\gadget\activeConfiguration=raw +Mode6\splitter\side1\side1\type=uavGadget +Mode6\splitter\side1\side1\classId=ScopeGadget +Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes [KeyBindings] size=0 [%General] SaveSettingsOnExit=true -LastPreferenceCategory=OPMapGadget -LastPreferencePage=default -SettingsWindowWidth=697 -SettingsWindowHeight=476 -OverrideLanguage=en_AU +TerminalEmulator=xterm -e +LastPreferenceCategory=LineardialGadget +LastPreferencePage=PitchCommand +SettingsWindowWidth=780 +SettingsWindowHeight=534 [UAVGadgetConfigurations] configInfo\version=1.2.0 @@ -340,7 +340,7 @@ DialGadget\Attitude\data\needle3Factor=-1 DialGadget\Attitude\data\needle1Move=Rotate DialGadget\Attitude\data\needle2Move=Vertical DialGadget\Attitude\data\needle3Move=Rotate -DialGadget\Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Attitude\data\useOpenGLFlag=false DialGadget\Attitude\data\beSmooth=false DialGadget\Attitude\configInfo\version=0.0.0 @@ -369,7 +369,7 @@ DialGadget\Baro%20Altimeter\data\needle3Factor=1 DialGadget\Baro%20Altimeter\data\needle1Move=Rotate DialGadget\Baro%20Altimeter\data\needle2Move=Rotate DialGadget\Baro%20Altimeter\data\needle3Move=Rotate -DialGadget\Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Baro%20Altimeter\data\useOpenGLFlag=false DialGadget\Baro%20Altimeter\data\beSmooth=false DialGadget\Baro%20Altimeter\configInfo\version=0.0.0 @@ -398,7 +398,7 @@ DialGadget\Barometer\data\needle3Factor=1 DialGadget\Barometer\data\needle1Move=Rotate DialGadget\Barometer\data\needle2Move=Rotate DialGadget\Barometer\data\needle3Move=Rotate -DialGadget\Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Barometer\data\useOpenGLFlag=false DialGadget\Barometer\data\beSmooth=false DialGadget\Barometer\configInfo\version=0.0.0 @@ -427,7 +427,7 @@ DialGadget\Climbrate\data\needle3Factor=1 DialGadget\Climbrate\data\needle1Move=Rotate DialGadget\Climbrate\data\needle2Move=Rotate DialGadget\Climbrate\data\needle3Move=Rotate -DialGadget\Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Climbrate\data\useOpenGLFlag=false DialGadget\Climbrate\data\beSmooth=false DialGadget\Climbrate\configInfo\version=0.0.0 @@ -456,7 +456,7 @@ DialGadget\Compass\data\needle3Factor=1 DialGadget\Compass\data\needle1Move=Rotate DialGadget\Compass\data\needle2Move=Rotate DialGadget\Compass\data\needle3Move=Rotate -DialGadget\Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Compass\data\useOpenGLFlag=false DialGadget\Compass\data\beSmooth=false DialGadget\Compass\configInfo\version=0.0.0 @@ -485,7 +485,7 @@ DialGadget\Deluxe%20Attitude\data\needle3Factor=-1 DialGadget\Deluxe%20Attitude\data\needle1Move=Rotate DialGadget\Deluxe%20Attitude\data\needle2Move=Vertical DialGadget\Deluxe%20Attitude\data\needle3Move=Rotate -DialGadget\Deluxe%20Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Attitude\data\useOpenGLFlag=false DialGadget\Deluxe%20Attitude\data\beSmooth=false DialGadget\Deluxe%20Attitude\configInfo\version=0.0.0 @@ -514,7 +514,7 @@ DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Factor=1 DialGadget\Deluxe%20Baro%20Altimeter\data\needle1Move=Rotate DialGadget\Deluxe%20Baro%20Altimeter\data\needle2Move=Rotate DialGadget\Deluxe%20Baro%20Altimeter\data\needle3Move=Rotate -DialGadget\Deluxe%20Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Baro%20Altimeter\data\useOpenGLFlag=false DialGadget\Deluxe%20Baro%20Altimeter\data\beSmooth=false DialGadget\Deluxe%20Baro%20Altimeter\configInfo\version=0.0.0 @@ -543,7 +543,7 @@ DialGadget\Deluxe%20Barometer\data\needle3Factor=1 DialGadget\Deluxe%20Barometer\data\needle1Move=Rotate DialGadget\Deluxe%20Barometer\data\needle2Move=Rotate DialGadget\Deluxe%20Barometer\data\needle3Move=Rotate -DialGadget\Deluxe%20Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Barometer\data\useOpenGLFlag=false DialGadget\Deluxe%20Barometer\data\beSmooth=false DialGadget\Deluxe%20Barometer\configInfo\version=0.0.0 @@ -572,7 +572,7 @@ DialGadget\Deluxe%20Climbrate\data\needle3Factor=1 DialGadget\Deluxe%20Climbrate\data\needle1Move=Rotate DialGadget\Deluxe%20Climbrate\data\needle2Move=Rotate DialGadget\Deluxe%20Climbrate\data\needle3Move=Rotate -DialGadget\Deluxe%20Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Climbrate\data\useOpenGLFlag=false DialGadget\Deluxe%20Climbrate\data\beSmooth=false DialGadget\Deluxe%20Climbrate\configInfo\version=0.0.0 @@ -601,7 +601,7 @@ DialGadget\Deluxe%20Compass\data\needle3Factor=1 DialGadget\Deluxe%20Compass\data\needle1Move=Rotate DialGadget\Deluxe%20Compass\data\needle2Move=Rotate DialGadget\Deluxe%20Compass\data\needle3Move=Rotate -DialGadget\Deluxe%20Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Compass\data\useOpenGLFlag=false DialGadget\Deluxe%20Compass\data\beSmooth=false DialGadget\Deluxe%20Compass\configInfo\version=0.0.0 @@ -630,7 +630,7 @@ DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Factor=1 DialGadget\Deluxe%20Groundspeed%20kph\data\needle1Move=Rotate DialGadget\Deluxe%20Groundspeed%20kph\data\needle2Move=Rotate DialGadget\Deluxe%20Groundspeed%20kph\data\needle3Move=Rotate -DialGadget\Deluxe%20Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Groundspeed%20kph\data\useOpenGLFlag=false DialGadget\Deluxe%20Groundspeed%20kph\data\beSmooth=false DialGadget\Deluxe%20Groundspeed%20kph\configInfo\version=0.0.0 @@ -659,7 +659,7 @@ DialGadget\Deluxe%20Temperature\data\needle3Factor=1 DialGadget\Deluxe%20Temperature\data\needle1Move=Rotate DialGadget\Deluxe%20Temperature\data\needle2Move=Rotate DialGadget\Deluxe%20Temperature\data\needle3Move=Rotate -DialGadget\Deluxe%20Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Temperature\data\useOpenGLFlag=false DialGadget\Deluxe%20Temperature\data\beSmooth=false DialGadget\Deluxe%20Temperature\configInfo\version=0.0.0 @@ -688,7 +688,7 @@ DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Factor=-1 DialGadget\Deluxe%20Turn%20Coordinator\data\needle1Move=Rotate DialGadget\Deluxe%20Turn%20Coordinator\data\needle2Move=Horizontal DialGadget\Deluxe%20Turn%20Coordinator\data\needle3Move=Rotate -DialGadget\Deluxe%20Turn%20Coordinator\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Deluxe%20Turn%20Coordinator\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Deluxe%20Turn%20Coordinator\data\useOpenGLFlag=false DialGadget\Deluxe%20Turn%20Coordinator\data\beSmooth=false DialGadget\Deluxe%20Turn%20Coordinator\configInfo\version=0.0.0 @@ -717,7 +717,7 @@ DialGadget\Groundspeed%20kph\data\needle3Factor=1 DialGadget\Groundspeed%20kph\data\needle1Move=Rotate DialGadget\Groundspeed%20kph\data\needle2Move=Rotate DialGadget\Groundspeed%20kph\data\needle3Move=Rotate -DialGadget\Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Groundspeed%20kph\data\useOpenGLFlag=false DialGadget\Groundspeed%20kph\data\beSmooth=false DialGadget\Groundspeed%20kph\configInfo\version=0.0.0 @@ -746,7 +746,7 @@ DialGadget\HiContrast%20Attitude\data\needle3Factor=-1 DialGadget\HiContrast%20Attitude\data\needle1Move=Rotate DialGadget\HiContrast%20Attitude\data\needle2Move=Vertical DialGadget\HiContrast%20Attitude\data\needle3Move=Rotate -DialGadget\HiContrast%20Attitude\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Attitude\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Attitude\data\useOpenGLFlag=false DialGadget\HiContrast%20Attitude\data\beSmooth=false DialGadget\HiContrast%20Attitude\configInfo\version=0.0.0 @@ -775,7 +775,7 @@ DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Factor=1 DialGadget\HiContrast%20Baro%20Altimeter\data\needle1Move=Rotate DialGadget\HiContrast%20Baro%20Altimeter\data\needle2Move=Rotate DialGadget\HiContrast%20Baro%20Altimeter\data\needle3Move=Rotate -DialGadget\HiContrast%20Baro%20Altimeter\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Baro%20Altimeter\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Baro%20Altimeter\data\useOpenGLFlag=false DialGadget\HiContrast%20Baro%20Altimeter\data\beSmooth=false DialGadget\HiContrast%20Baro%20Altimeter\configInfo\version=0.0.0 @@ -804,7 +804,7 @@ DialGadget\HiContrast%20Barometer\data\needle3Factor=1 DialGadget\HiContrast%20Barometer\data\needle1Move=Rotate DialGadget\HiContrast%20Barometer\data\needle2Move=Rotate DialGadget\HiContrast%20Barometer\data\needle3Move=Rotate -DialGadget\HiContrast%20Barometer\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Barometer\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Barometer\data\useOpenGLFlag=false DialGadget\HiContrast%20Barometer\data\beSmooth=false DialGadget\HiContrast%20Barometer\configInfo\version=0.0.0 @@ -833,7 +833,7 @@ DialGadget\HiContrast%20Climbrate\data\needle3Factor=1 DialGadget\HiContrast%20Climbrate\data\needle1Move=Rotate DialGadget\HiContrast%20Climbrate\data\needle2Move=Rotate DialGadget\HiContrast%20Climbrate\data\needle3Move=Rotate -DialGadget\HiContrast%20Climbrate\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Climbrate\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Climbrate\data\useOpenGLFlag=false DialGadget\HiContrast%20Climbrate\data\beSmooth=false DialGadget\HiContrast%20Climbrate\configInfo\version=0.0.0 @@ -862,7 +862,7 @@ DialGadget\HiContrast%20Compass\data\needle3Factor=1 DialGadget\HiContrast%20Compass\data\needle1Move=Rotate DialGadget\HiContrast%20Compass\data\needle2Move=Rotate DialGadget\HiContrast%20Compass\data\needle3Move=Rotate -DialGadget\HiContrast%20Compass\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Compass\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Compass\data\useOpenGLFlag=false DialGadget\HiContrast%20Compass\data\beSmooth=false DialGadget\HiContrast%20Compass\configInfo\version=0.0.0 @@ -891,7 +891,7 @@ DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Factor=1 DialGadget\HiContrast%20Groundspeed%20kph\data\needle1Move=Rotate DialGadget\HiContrast%20Groundspeed%20kph\data\needle2Move=Rotate DialGadget\HiContrast%20Groundspeed%20kph\data\needle3Move=Rotate -DialGadget\HiContrast%20Groundspeed%20kph\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Groundspeed%20kph\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Groundspeed%20kph\data\useOpenGLFlag=false DialGadget\HiContrast%20Groundspeed%20kph\data\beSmooth=false DialGadget\HiContrast%20Groundspeed%20kph\configInfo\version=0.0.0 @@ -920,7 +920,7 @@ DialGadget\HiContrast%20Temperature\data\needle3Factor=1 DialGadget\HiContrast%20Temperature\data\needle1Move=Rotate DialGadget\HiContrast%20Temperature\data\needle2Move=Rotate DialGadget\HiContrast%20Temperature\data\needle3Move=Rotate -DialGadget\HiContrast%20Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\HiContrast%20Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\HiContrast%20Temperature\data\useOpenGLFlag=false DialGadget\HiContrast%20Temperature\data\beSmooth=false DialGadget\HiContrast%20Temperature\configInfo\version=0.0.0 @@ -949,7 +949,7 @@ DialGadget\Servo%20Channel%201\data\needle3Factor=1 DialGadget\Servo%20Channel%201\data\needle1Move=Rotate DialGadget\Servo%20Channel%201\data\needle2Move=Rotate DialGadget\Servo%20Channel%201\data\needle3Move=Rotate -DialGadget\Servo%20Channel%201\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Servo%20Channel%201\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Servo%20Channel%201\data\useOpenGLFlag=false DialGadget\Servo%20Channel%201\data\beSmooth=false DialGadget\Servo%20Channel%201\configInfo\version=0.0.0 @@ -978,7 +978,7 @@ DialGadget\Temperature\data\needle3Factor=1 DialGadget\Temperature\data\needle1Move=Rotate DialGadget\Temperature\data\needle2Move=Rotate DialGadget\Temperature\data\needle3Move=Rotate -DialGadget\Temperature\data\font="MS Shell Dlg 2,8.25,-1,5,50,0,0,0,0,0" +DialGadget\Temperature\data\font="Ubuntu,11,-1,5,50,0,0,0,0,0" DialGadget\Temperature\data\useOpenGLFlag=false DialGadget\Temperature\data\beSmooth=false DialGadget\Temperature\configInfo\version=0.0.0 @@ -1027,7 +1027,7 @@ GpsDisplayGadget\Flight%20GPS\data\defaultDataBits=3 GpsDisplayGadget\Flight%20GPS\data\defaultFlow=0 GpsDisplayGadget\Flight%20GPS\data\defaultParity=0 GpsDisplayGadget\Flight%20GPS\data\defaultStopBits=0 -GpsDisplayGadget\Flight%20GPS\data\defaultPort=Communications Port (COM1) +GpsDisplayGadget\Flight%20GPS\data\defaultPort=Serial port 0 GpsDisplayGadget\Flight%20GPS\data\connectionMode=Telemetry GpsDisplayGadget\Flight%20GPS\configInfo\version=0.0.0 GpsDisplayGadget\Flight%20GPS\configInfo\locked=false @@ -1036,7 +1036,7 @@ GpsDisplayGadget\GPS%20Mouse\data\defaultDataBits=3 GpsDisplayGadget\GPS%20Mouse\data\defaultFlow=0 GpsDisplayGadget\GPS%20Mouse\data\defaultParity=0 GpsDisplayGadget\GPS%20Mouse\data\defaultStopBits=0 -GpsDisplayGadget\GPS%20Mouse\data\defaultPort=Communications Port (COM1) +GpsDisplayGadget\GPS%20Mouse\data\defaultPort=Serial port 0 GpsDisplayGadget\GPS%20Mouse\data\connectionMode=Serial GpsDisplayGadget\GPS%20Mouse\configInfo\version=0.0.0 GpsDisplayGadget\GPS%20Mouse\configInfo\locked=false @@ -1256,23 +1256,6 @@ LineardialGadget\PitchActual\data\factor=1 LineardialGadget\PitchActual\data\useOpenGLFlag=false LineardialGadget\PitchActual\configInfo\version=0.0.0 LineardialGadget\PitchActual\configInfo\locked=false -LineardialGadget\PitchCommand\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\PitchCommand\data\sourceDataObject=ManualControlCommand -LineardialGadget\PitchCommand\data\sourceObjectField=Pitch -LineardialGadget\PitchCommand\data\minValue=-1 -LineardialGadget\PitchCommand\data\maxValue=1 -LineardialGadget\PitchCommand\data\redMin=0 -LineardialGadget\PitchCommand\data\redMax=1 -LineardialGadget\PitchCommand\data\yellowMin=0.1 -LineardialGadget\PitchCommand\data\yellowMax=0.9 -LineardialGadget\PitchCommand\data\greenMin=0.3 -LineardialGadget\PitchCommand\data\greenMax=0.8 -LineardialGadget\PitchCommand\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\PitchCommand\data\decimalPlaces=2 -LineardialGadget\PitchCommand\data\factor=1 -LineardialGadget\PitchCommand\data\useOpenGLFlag=false -LineardialGadget\PitchCommand\configInfo\version=0.0.0 -LineardialGadget\PitchCommand\configInfo\locked=false LineardialGadget\PitchDesired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\PitchDesired\data\sourceDataObject=ActuatorDesired LineardialGadget\PitchDesired\data\sourceObjectField=Pitch @@ -1293,14 +1276,14 @@ LineardialGadget\PitchDesired\configInfo\locked=false LineardialGadget\Roll\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\Roll\data\sourceDataObject=ManualControlCommand LineardialGadget\Roll\data\sourceObjectField=Roll -LineardialGadget\Roll\data\minValue=0 +LineardialGadget\Roll\data\minValue=-1 LineardialGadget\Roll\data\maxValue=1 -LineardialGadget\Roll\data\redMin=0 +LineardialGadget\Roll\data\redMin=-1 LineardialGadget\Roll\data\redMax=1 -LineardialGadget\Roll\data\yellowMin=0.1 -LineardialGadget\Roll\data\yellowMax=0.9 -LineardialGadget\Roll\data\greenMin=0.3 -LineardialGadget\Roll\data\greenMax=0.8 +LineardialGadget\Roll\data\yellowMin=-0.8 +LineardialGadget\Roll\data\yellowMax=0.8 +LineardialGadget\Roll\data\greenMin=-0.5 +LineardialGadget\Roll\data\greenMax=0.5 LineardialGadget\Roll\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" LineardialGadget\Roll\data\decimalPlaces=2 LineardialGadget\Roll\data\factor=1 @@ -1346,12 +1329,12 @@ LineardialGadget\Throttle\data\sourceDataObject=ManualControlCommand LineardialGadget\Throttle\data\sourceObjectField=Throttle LineardialGadget\Throttle\data\minValue=0 LineardialGadget\Throttle\data\maxValue=1 -LineardialGadget\Throttle\data\redMin=0 +LineardialGadget\Throttle\data\redMin=0.75 LineardialGadget\Throttle\data\redMax=1 -LineardialGadget\Throttle\data\yellowMin=0.1 -LineardialGadget\Throttle\data\yellowMax=0.9 -LineardialGadget\Throttle\data\greenMin=0.3 -LineardialGadget\Throttle\data\greenMax=0.8 +LineardialGadget\Throttle\data\yellowMin=0.5 +LineardialGadget\Throttle\data\yellowMax=0.75 +LineardialGadget\Throttle\data\greenMin=0 +LineardialGadget\Throttle\data\greenMax=0.5 LineardialGadget\Throttle\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" LineardialGadget\Throttle\data\decimalPlaces=2 LineardialGadget\Throttle\data\factor=1 @@ -1361,14 +1344,14 @@ LineardialGadget\Throttle\configInfo\locked=false LineardialGadget\Yaw\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\Yaw\data\sourceDataObject=ManualControlCommand LineardialGadget\Yaw\data\sourceObjectField=Yaw -LineardialGadget\Yaw\data\minValue=0 +LineardialGadget\Yaw\data\minValue=-1 LineardialGadget\Yaw\data\maxValue=1 -LineardialGadget\Yaw\data\redMin=0 +LineardialGadget\Yaw\data\redMin=-1 LineardialGadget\Yaw\data\redMax=1 -LineardialGadget\Yaw\data\yellowMin=0.1 -LineardialGadget\Yaw\data\yellowMax=0.9 -LineardialGadget\Yaw\data\greenMin=0.3 -LineardialGadget\Yaw\data\greenMax=0.8 +LineardialGadget\Yaw\data\yellowMin=-0.8 +LineardialGadget\Yaw\data\yellowMax=0.8 +LineardialGadget\Yaw\data\greenMin=-0.5 +LineardialGadget\Yaw\data\greenMax=0.5 LineardialGadget\Yaw\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" LineardialGadget\Yaw\data\decimalPlaces=2 LineardialGadget\Yaw\data\factor=1 @@ -1439,24 +1422,41 @@ OPMapGadget\Google%20Sat\data\mapProvider=GoogleSatellite OPMapGadget\Google%20Sat\data\defaultZoom=2 OPMapGadget\Google%20Sat\data\defaultLatitude=0 OPMapGadget\Google%20Sat\data\defaultLongitude=0 -OPMapGadget\Google%20Sat\data\useOpenGL=true +OPMapGadget\Google%20Sat\data\useOpenGL=false OPMapGadget\Google%20Sat\data\showTileGridLines=false OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache OPMapGadget\Google%20Sat\data\useMemoryCache=true OPMapGadget\Google%20Sat\data\uavSymbol=mapquad.png -OPMapGadget\Google%20Sat\data\cacheLocation= +LineardialGadget\Pitch\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Pitch\data\sourceDataObject=ManualControlCommand +LineardialGadget\Pitch\data\sourceObjectField=Pitch +LineardialGadget\Pitch\data\minValue=-1 +LineardialGadget\Pitch\data\maxValue=1 +LineardialGadget\Pitch\data\redMin=-1 +LineardialGadget\Pitch\data\redMax=1 +LineardialGadget\Pitch\data\yellowMin=-0.8 +LineardialGadget\Pitch\data\yellowMax=0.8 +LineardialGadget\Pitch\data\greenMin=-0.5 +LineardialGadget\Pitch\data\greenMax=0.5 +LineardialGadget\Pitch\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Pitch\data\decimalPlaces=2 +LineardialGadget\Pitch\data\factor=1 +LineardialGadget\Pitch\data\useOpenGLFlag=false +LineardialGadget\Pitch\configInfo\version=0.0.0 +LineardialGadget\Pitch\configInfo\locked=false +OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\Google%20Sat\configInfo\version=0.0.0 OPMapGadget\Google%20Sat\configInfo\locked=false OPMapGadget\Memory%20Only\data\mapProvider=GoogleMap OPMapGadget\Memory%20Only\data\defaultZoom=2 OPMapGadget\Memory%20Only\data\defaultLatitude=0 OPMapGadget\Memory%20Only\data\defaultLongitude=0 -OPMapGadget\Memory%20Only\data\useOpenGL=true +OPMapGadget\Memory%20Only\data\useOpenGL=false OPMapGadget\Memory%20Only\data\showTileGridLines=false OPMapGadget\Memory%20Only\data\accessMode=CacheOnly OPMapGadget\Memory%20Only\data\useMemoryCache=true OPMapGadget\Memory%20Only\data\uavSymbol=airplanepip.png -OPMapGadget\Memory%20Only\data\cacheLocation= +OPMapGadget\Memory%20Only\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\Memory%20Only\configInfo\version=0.0.0 OPMapGadget\Memory%20Only\configInfo\locked=false OPMapGadget\default\data\mapProvider=GoogleMap @@ -1468,7 +1468,7 @@ OPMapGadget\default\data\showTileGridLines=false OPMapGadget\default\data\accessMode=ServerAndCache OPMapGadget\default\data\useMemoryCache=true OPMapGadget\default\data\uavSymbol=mapquad.png -OPMapGadget\default\data\cacheLocation= +OPMapGadget\default\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\default\configInfo\version=0.0.0 OPMapGadget\default\configInfo\locked=false PFDGadget\raw\data\dialFile=%%DATAPATH%%pfd/default/pfd.svg diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp index 287479d8d..d266ec18b 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp @@ -73,8 +73,10 @@ GCSControlGadgetWidget::GCSControlGadgetWidget(QWidget *parent) : QLabel(parent) rightX = 0; rightY = 0; - m_gcscontrol->widgetLeftStick->enableOpenGL(true); - m_gcscontrol->widgetRightStick->enableOpenGL(true); + // No point enabling OpenGL for the joysticks, and causes + // issues on some computers: +// m_gcscontrol->widgetLeftStick->enableOpenGL(true); +// m_gcscontrol->widgetRightStick->enableOpenGL(true); } GCSControlGadgetWidget::~GCSControlGadgetWidget() From 3d5244c4b817ad617f1dc893010046275168a2f5 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Thu, 12 May 2011 18:57:16 -0500 Subject: [PATCH 09/43] Fix small typo THRSHOLD to THRESHOLD in gps.c --- flight/Modules/GPS/GPS.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 80fb044d9..7d5ce8e5b 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -63,7 +63,7 @@ static float GravityAccel(float latitude, float longitude, float altitude); // Private constants //#define FULL_COLD_RESTART // uncomment this to tell the GPS to do a FULL COLD restart -//#define DISABLE_GPS_TRESHOLD // +//#define DISABLE_GPS_THRESHOLD // #define GPS_TIMEOUT_MS 500 #define GPS_COMMAND_RESEND_TIMEOUT_MS 2000 @@ -154,7 +154,7 @@ static void gpsTask(void *parameters) } #endif -#ifdef DISABLE_GPS_TRESHOLD +#ifdef DISABLE_GPS_THRESHOLD PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n"); #endif From f9212cda7b8268843d74dc0ed8183e3ce0ae13c7 Mon Sep 17 00:00:00 2001 From: elafargue Date: Fri, 13 May 2011 08:24:34 +0200 Subject: [PATCH 10/43] Last minute default settings refinement. CC Attitude UI improvement. --- .../src/plugins/config/ccattitude.ui | 164 +++++++++--------- .../src/plugins/coreplugin/OpenPilotGCS.ini | 98 +++++++---- 2 files changed, 145 insertions(+), 117 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/ccattitude.ui b/ground/openpilotgcs/src/plugins/config/ccattitude.ui index b6b00126c..09065ad0f 100644 --- a/ground/openpilotgcs/src/plugins/config/ccattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/ccattitude.ui @@ -6,8 +6,8 @@ 0 0 - 400 - 343 + 415 + 349 @@ -159,86 +159,86 @@ Attitude Calibration - - - - 0 - 20 - 371 - 111 - - - - - 3 - - - - - Place aircraft flat before computing - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Click "Zero Accel Bias" to start - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Launch horizontal calibration. - - - Zero Accel Bias - - - - - - - 0 - - - - - - - + + + + + 3 + + + + + Place aircraft flat before computing + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Click "Zero Accel Bias" to start + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + 6 + + + 4 + + + + + Launch horizontal calibration. + + + Zero Accel Bias + + + + + + + 0 + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini index c9a898c34..a37b328e5 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini @@ -70,7 +70,6 @@ Mode1\splitter\side0\side1\splitterOrientation=1 Mode1\splitter\side0\side1\splitterSizes=304, 433 Mode1\splitter\side0\side1\side0\type=uavGadget Mode1\splitter\side0\side1\side0\classId=ModelViewGadget -Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X Mode1\splitter\side0\side1\side1\type=splitter Mode1\splitter\side0\side1\side1\splitterOrientation=2 Mode1\splitter\side0\side1\side1\splitterSizes=293, 64 @@ -151,18 +150,18 @@ Mode1\splitter\side1\side1\side1\side1\splitterOrientation=1 Mode1\splitter\side1\side1\side1\side1\splitterSizes=64, 376 Mode1\splitter\side1\side1\side1\side1\side0\type=uavGadget Mode1\splitter\side1\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side0\gadget\activeConfiguration=Roll +Mode1\splitter\side1\side1\side1\side1\side0\gadget\activeConfiguration=Roll Desired Mode1\splitter\side1\side1\side1\side1\side1\type=splitter Mode1\splitter\side1\side1\side1\side1\side1\splitterOrientation=1 Mode1\splitter\side1\side1\side1\side1\side1\splitterSizes=64, 311 Mode1\splitter\side1\side1\side1\side1\side1\side0\type=uavGadget Mode1\splitter\side1\side1\side1\side1\side1\side0\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side1\side0\gadget\activeConfiguration=Pitch +Mode1\splitter\side1\side1\side1\side1\side1\side0\gadget\activeConfiguration=Pitch Desired Mode1\splitter\side1\side1\side1\side1\side1\side1\type=uavGadget Mode1\splitter\side1\side1\side1\side1\side1\side1\classId=LineardialGadget -Mode1\splitter\side1\side1\side1\side1\side1\side1\gadget\activeConfiguration=Yaw +Mode1\splitter\side1\side1\side1\side1\side1\side1\gadget\activeConfiguration=Yaw Desired Mode2\version=UAVGadgetManagerV1 -Mode2\showToolbars=true +Mode2\showToolbars=false Mode2\splitter\type=splitter Mode2\splitter\splitterOrientation=1 Mode2\splitter\splitterSizes=734, 631 @@ -181,15 +180,7 @@ Mode2\splitter\side0\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Ho Mode2\splitter\side0\side1\side1\type=uavGadget Mode2\splitter\side0\side1\side1\classId=LineardialGadget Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal -Mode2\splitter\side1\type=splitter -Mode2\splitter\side1\splitterOrientation=2 -Mode2\splitter\side1\splitterSizes=433, 347 -Mode2\splitter\side1\side0\type=uavGadget -Mode2\splitter\side1\side0\classId=UAVObjectBrowser -Mode2\splitter\side1\side0\gadget\activeConfiguration=default -Mode2\splitter\side1\side1\type=uavGadget -Mode2\splitter\side1\side1\classId=GCSControlGadget -Mode2\splitter\side1\side1\gadget\activeConfiguration=MS Sidewinder +Mode2\splitter\side1\type=uavGadget Mode3\version=UAVGadgetManagerV1 Mode3\showToolbars=false Mode3\splitter\type=splitter @@ -203,7 +194,6 @@ Mode3\splitter\side1\splitterOrientation=2 Mode3\splitter\side1\splitterSizes=395, 236 Mode3\splitter\side1\side0\type=uavGadget Mode3\splitter\side1\side0\classId=ModelViewGadget -Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X Mode3\splitter\side1\side1\type=splitter Mode3\splitter\side1\side1\splitterOrientation=1 Mode3\splitter\side1\side1\splitterSizes=@Invalid() @@ -266,7 +256,7 @@ Mode5\splitter\side0\side1\side1\side0\splitterOrientation=1 Mode5\splitter\side0\side1\side1\side0\splitterSizes=@Invalid() Mode5\splitter\side0\side1\side1\side0\side0\type=uavGadget Mode5\splitter\side0\side1\side1\side0\side0\classId=LineardialGadget -Mode5\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=PitchDesired +Mode5\splitter\side0\side1\side1\side0\side0\gadget\activeConfiguration=Pitch Desired Mode5\splitter\side0\side1\side1\side0\side1\type=uavGadget Mode5\splitter\side0\side1\side1\side0\side1\classId=LineardialGadget Mode5\splitter\side0\side1\side1\side0\side1\gadget\activeConfiguration=PitchActual @@ -299,6 +289,10 @@ Mode6\splitter\side1\side0\side1\gadget\activeConfiguration=raw Mode6\splitter\side1\side1\type=uavGadget Mode6\splitter\side1\side1\classId=ScopeGadget Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes +Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X +Mode2\splitter\side1\classId=UAVObjectBrowser +Mode2\splitter\side1\gadget\activeConfiguration=default +Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X [KeyBindings] size=0 @@ -307,8 +301,8 @@ size=0 SaveSettingsOnExit=true TerminalEmulator=xterm -e LastPreferenceCategory=LineardialGadget -LastPreferencePage=PitchCommand -SettingsWindowWidth=780 +LastPreferencePage=Roll Desired 1 +SettingsWindowWidth=921 SettingsWindowHeight=534 [UAVGadgetConfigurations] @@ -1256,23 +1250,6 @@ LineardialGadget\PitchActual\data\factor=1 LineardialGadget\PitchActual\data\useOpenGLFlag=false LineardialGadget\PitchActual\configInfo\version=0.0.0 LineardialGadget\PitchActual\configInfo\locked=false -LineardialGadget\PitchDesired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\PitchDesired\data\sourceDataObject=ActuatorDesired -LineardialGadget\PitchDesired\data\sourceObjectField=Pitch -LineardialGadget\PitchDesired\data\minValue=-1 -LineardialGadget\PitchDesired\data\maxValue=1 -LineardialGadget\PitchDesired\data\redMin=0 -LineardialGadget\PitchDesired\data\redMax=1 -LineardialGadget\PitchDesired\data\yellowMin=0.1 -LineardialGadget\PitchDesired\data\yellowMax=0.9 -LineardialGadget\PitchDesired\data\greenMin=0.3 -LineardialGadget\PitchDesired\data\greenMax=0.8 -LineardialGadget\PitchDesired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\PitchDesired\data\decimalPlaces=2 -LineardialGadget\PitchDesired\data\factor=1 -LineardialGadget\PitchDesired\data\useOpenGLFlag=false -LineardialGadget\PitchDesired\configInfo\version=0.0.0 -LineardialGadget\PitchDesired\configInfo\locked=false LineardialGadget\Roll\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\Roll\data\sourceDataObject=ManualControlCommand LineardialGadget\Roll\data\sourceObjectField=Roll @@ -1444,6 +1421,23 @@ LineardialGadget\Pitch\data\factor=1 LineardialGadget\Pitch\data\useOpenGLFlag=false LineardialGadget\Pitch\configInfo\version=0.0.0 LineardialGadget\Pitch\configInfo\locked=false +LineardialGadget\Pitch%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Pitch%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Pitch%20Desired\data\sourceObjectField=Pitch +LineardialGadget\Pitch%20Desired\data\minValue=-1 +LineardialGadget\Pitch%20Desired\data\maxValue=1 +LineardialGadget\Pitch%20Desired\data\redMin=-1 +LineardialGadget\Pitch%20Desired\data\redMax=1 +LineardialGadget\Pitch%20Desired\data\yellowMin=-0.8 +LineardialGadget\Pitch%20Desired\data\yellowMax=0.8 +LineardialGadget\Pitch%20Desired\data\greenMin=-0.5 +LineardialGadget\Pitch%20Desired\data\greenMax=0.5 +LineardialGadget\Pitch%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Pitch%20Desired\data\decimalPlaces=2 +LineardialGadget\Pitch%20Desired\data\factor=1 +LineardialGadget\Pitch%20Desired\data\useOpenGLFlag=false +LineardialGadget\Pitch%20Desired\configInfo\version=0.0.0 +LineardialGadget\Pitch%20Desired\configInfo\locked=false OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\Google%20Sat\configInfo\version=0.0.0 OPMapGadget\Google%20Sat\configInfo\locked=false @@ -1881,6 +1875,40 @@ Uploader\default\data\defaultStopBits=0 Uploader\default\data\defaultPort=/dev/ttyS0 Uploader\default\configInfo\version=0.0.0 Uploader\default\configInfo\locked=false +LineardialGadget\Roll%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Roll%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Roll%20Desired\data\sourceObjectField=Roll +LineardialGadget\Roll%20Desired\data\minValue=-1 +LineardialGadget\Roll%20Desired\data\maxValue=1 +LineardialGadget\Roll%20Desired\data\redMin=-1 +LineardialGadget\Roll%20Desired\data\redMax=1 +LineardialGadget\Roll%20Desired\data\yellowMin=-0.8 +LineardialGadget\Roll%20Desired\data\yellowMax=0.8 +LineardialGadget\Roll%20Desired\data\greenMin=-0.5 +LineardialGadget\Roll%20Desired\data\greenMax=0.5 +LineardialGadget\Roll%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Roll%20Desired\data\decimalPlaces=2 +LineardialGadget\Roll%20Desired\data\factor=1 +LineardialGadget\Roll%20Desired\data\useOpenGLFlag=false +LineardialGadget\Roll%20Desired\configInfo\version=0.0.0 +LineardialGadget\Roll%20Desired\configInfo\locked=false +LineardialGadget\Yaw%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Yaw%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Yaw%20Desired\data\sourceObjectField=Yaw +LineardialGadget\Yaw%20Desired\data\minValue=-1 +LineardialGadget\Yaw%20Desired\data\maxValue=1 +LineardialGadget\Yaw%20Desired\data\redMin=-1 +LineardialGadget\Yaw%20Desired\data\redMax=1 +LineardialGadget\Yaw%20Desired\data\yellowMin=-0.8 +LineardialGadget\Yaw%20Desired\data\yellowMax=0.8 +LineardialGadget\Yaw%20Desired\data\greenMin=-0.5 +LineardialGadget\Yaw%20Desired\data\greenMax=0.5 +LineardialGadget\Yaw%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Yaw%20Desired\data\decimalPlaces=2 +LineardialGadget\Yaw%20Desired\data\factor=1 +LineardialGadget\Yaw%20Desired\data\useOpenGLFlag=false +LineardialGadget\Yaw%20Desired\configInfo\version=0.0.0 +LineardialGadget\Yaw%20Desired\configInfo\locked=false [Plugins] SoundNotifyPlugin\data\Current\1\SoundCollectionPath=%%DATAPATH%%sounds From 3964b97ae551d0bbdda7e9464ce29e40ba2c9a93 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Mon, 9 May 2011 02:56:52 +0300 Subject: [PATCH 11/43] OP-483: Update Windows build environment subdirectory USE_BOOTLOADER now deprecated and removed. Scripts are moved into the same subdirectories like in msysGit. Added make.sh script (for advanced usage scenario). Few misprints are fixed. --- make/winx86/README.txt | 10 +++++----- make/winx86/{ => bin}/make | 0 make/winx86/cmd/make.sh | 1 + make/winx86/{ => cmd}/sh.cmd | 0 4 files changed, 6 insertions(+), 5 deletions(-) rename make/winx86/{ => bin}/make (100%) create mode 100644 make/winx86/cmd/make.sh rename make/winx86/{ => cmd}/sh.cmd (100%) diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 9677e9368..6024dd118 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -46,8 +46,8 @@ Now you need to copy two files to your msysGit installation folders. Assuming that you installed the msysGit into C:\Program Files\Git\, you have to copy: - make\winx86\make -> C:\Program Files\Git\bin\ - make\winx86\sh.cmd -> C:\Program Files\Git\cmd\ + make\winx86\bin\make -> C:\Program Files\Git\bin\ + make\winx86\cmd\sh.cmd -> C:\Program Files\Git\cmd\ If you have msysGit installed into another directory, you need to update paths accordingly. Also if you have tools installed into different directories and @@ -93,7 +93,7 @@ software and flight firmware built in the end. 4) To build parts of the system you can use, for example, such commands: user@pc /d/Work/OpenPilot/git (master) - $ make -j2 USE_BOOTLOADER=YES GCS_BUIL_CONF=release gcs coptercontrol bl_coptercontrol + $ make -j2 GCS_BUILD_CONF=release gcs coptercontrol or to completely remove the build directory: @@ -109,7 +109,7 @@ or to completely remove the build directory: #!/bin/sh # This is the cc_make_release.sh file used to build CC release software cd D:/Work/OpenPilot/git - make -j2 USE_BOOTLOADER=YES GCS_BUIL_CONF=release gcs coptercontrol bl_coptercontrol + make -j2 GCS_BUILD_CONF=release gcs coptercontrol echo RC=$? 2) Run it typing: @@ -170,7 +170,7 @@ to get rid of git bash welcome message on every script invocation. Currently there may be some problems running scripts which contain spaces in file names or located in directories which contain spaces in full paths. -It results in in strange "file not found" or other errors. +It results in strange "file not found" or other errors. It is recommended to avoid using such names with spaces. diff --git a/make/winx86/make b/make/winx86/bin/make similarity index 100% rename from make/winx86/make rename to make/winx86/bin/make diff --git a/make/winx86/cmd/make.sh b/make/winx86/cmd/make.sh new file mode 100644 index 000000000..70ff64114 --- /dev/null +++ b/make/winx86/cmd/make.sh @@ -0,0 +1 @@ +exec /bin/make $* diff --git a/make/winx86/sh.cmd b/make/winx86/cmd/sh.cmd similarity index 100% rename from make/winx86/sh.cmd rename to make/winx86/cmd/sh.cmd From 50f2d0ea76d7a3688beb38b7ca109bc8c09ff6e5 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 12 May 2011 23:21:56 +0300 Subject: [PATCH 12/43] OP-483: cleanup: replace ';' by '&&' in top Makefile (shouldn't continue on error) On Windows cd doesn't mean that current directory is as expected since there is also current drive. So in some rare cases mkdir followed by cd doesn't change the directory which can result in Makefile overwrites by qmake, etc. So it is safer to replace ';' by '&&' but need to check if it still works on Windows under cmd or from Qt-Creator. --- Makefile | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Makefile b/Makefile index e7e0bea48..127d031f9 100644 --- a/Makefile +++ b/Makefile @@ -265,8 +265,8 @@ gcs_clean: openpilotgcs_clean .PHONY: openpilotgcs openpilotgcs: uavobjects_gcs $(V1) mkdir -p $(BUILD_DIR)/ground/$@ - $(V1) ( cd $(BUILD_DIR)/ground/$@ ; \ - $(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/openpilotgcs.pro -spec $(QT_SPEC) -r CONFIG+=$(GCS_BUILD_CONF) ; \ + $(V1) ( cd $(BUILD_DIR)/ground/$@ && \ + $(QMAKE) $(ROOT_DIR)/ground/openpilotgcs/openpilotgcs.pro -spec $(QT_SPEC) -r CONFIG+=$(GCS_BUILD_CONF) && \ $(MAKE) -w ; \ ) @@ -290,8 +290,8 @@ openpilotgcs_clean: .PHONY: uavobjgenerator uavobjgenerator: $(V1) mkdir -p $(BUILD_DIR)/ground/$@ - $(V1) ( cd $(BUILD_DIR)/ground/$@ ; \ - $(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro -spec $(QT_SPEC) -r CONFIG+=debug ; \ + $(V1) ( cd $(BUILD_DIR)/ground/$@ && \ + $(QMAKE) $(ROOT_DIR)/ground/uavobjgenerator/uavobjgenerator.pro -spec $(QT_SPEC) -r CONFIG+=debug && \ $(MAKE) --no-print-directory -w ; \ ) @@ -306,7 +306,7 @@ $(UAVOBJ_OUT_DIR): $(V1) mkdir -p $@ uavobjects_%: $(UAVOBJ_OUT_DIR) uavobjgenerator - $(V1) ( cd $(UAVOBJ_OUT_DIR) ; \ + $(V1) ( cd $(UAVOBJ_OUT_DIR) && \ $(UAVOBJGENERATOR) -$* $(UAVOBJ_XML_DIR) $(ROOT_DIR) ; \ ) From bf8939eb306086470b0fa95b54d20f520b9bbbdd Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Thu, 12 May 2011 23:53:20 +0300 Subject: [PATCH 13/43] OP-483: cleanup: remove unneeded test.bin from BootloaderUpdater --- flight/Bootloaders/BootloaderUpdater/test.bin | Bin 92072 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 flight/Bootloaders/BootloaderUpdater/test.bin diff --git a/flight/Bootloaders/BootloaderUpdater/test.bin b/flight/Bootloaders/BootloaderUpdater/test.bin deleted file mode 100644 index 4b1f21a614c66544a29d2136fd8d551efd74f5f6..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 92072 zcmb5X33wD$)&^X?BtKOc{b<&j0ce{>NV=4#AP@|3AM4)33>A8m{T{zvLUiiZA`&;o~8n z`+uZSjIe3fr13wh^Ix}1B}2cEq4UH#7B84ttuHW?#X3q-+Dd*sX{gY8gsc)tKPB4H zR^mOWVP6IsOUFH=F(3iknppW`%oc2+9|fVYRQPa6+4UFL>~Ex&j=_$>6+bj-urpIcINZB3F)qaiNqV7LQw(f4p)>K+^ zwC1DQsJbDwOKNu3d{sNBZeiUKsj&NqG_`wP?Uvf!+CNDth@IY@P&cpc{qyV*;lnj% z!S)$GPg(?dH*) zv#^Ps4jbMVK7_QvdT?i_mW}h)i(0lv+9lQ7lMZE8BsC83XhtUY?vh+~?MO{ecw}Mk zU`Og&&6pE!rZ%Rn)sD1(Wn#|ycv)>wRBpu)i;@D4N-)pB29HL3m?H zT93uCLbOzPQj#Q1`i7K*MpK1m?6#6iz2PgbhjqsN(h7SOo2}a~H3<8qJM3EalSHLi zA*FX(-zVMg3Tq6v3!y6-L2J1FLSt1cN_`NMM7n9iPuvU!6 z?~(8>sj@n;{rc$HeM!SMh&kdDK$j_@2M}6al+>ObJ*zJ%yGgW(k0bOZCG@564dU?& zf@ZN;B$fle7(9DH$Vy^A2CZynD4E^jYZ8k^yO_+D1&YP%T5@o;6juXUY`9t!7}#>% zUM*YZPw9OBeB;x?heHo)*~6%lhW#8iJ9bGL+n}|(B%#|_wxwi+*n}%f&zQW_M#EQQ zGE*BjBV5bw((w4vQ8y_u3`pN4%B);TnpsVg;Ysm`cQ0dY3M zCSaLWuR=%TCCzKei1kib%ce*f$p1~$dx8DB*0kuEeO6l%`y^Do=OnM&NQ5l0?~uZ1Z1c$1mhOe*D7lJCoS9P?NYzN*AKrh3KNbBwGtYDUHWM8-OPZ`fG4%tp`FQ z=N`W>M5FH?q|M$tWZzh{iVbOHz8cTY_;*RmtSPOqJ6mjYrlYvenlY#qWnNp-XU!Z_ zqp_j?-Jlz3zqjAHs%BX4E^oa(YGlS)#Xf}r$b-Bo=9R>X)o=FL)B z=Vobs%VueXXS1}kd$Uw2lrKj;TZApJTI()pR;LD6t=8j`u|vJL=BhNg{;j| zb@za0)1TQatr2o|Y?fZMZI<%w8uodJ^mSM0dahd<=V-j6vCe+*k5l zj*z9?=1OKid6QX}-&n3`apLX=+`ZyAlxtf$aQ6-F_V{%zuzfC59E$3+qn~8+b~;va zHO-fKcm~q+K<)_S9^+}+>XX@fxNG8RI&pUpck6hXPjZ=o|07N7!KXSk?9osR`kptK zQWn3jM-n_elD>O`>xk<(u8-qdyH&R>p8ZpbcgM9Rvu4TY*0;ps>LJPGj%qRBYMm5U zt{0^L}RB94Gl8j9Uz0nA{B<(}UZ0`kxOqQa> zQ8fp>alp?@7l2Rl=Hh#lq!(Az6rq2PMSVc&MEGQtQM$!x2ywF~xbPq+r#lNVwF}a1>;Lb2J=89P zm9hL4Af-KWS`&C$V($K4WGA?wBtT zS7uyY^ksNVj#QUsOsX^8BYgOJ>ACxp@4mH2`R%@~@TT1R8%7r?zul2_&Kk5!6F%!5 zi#BP-ENYVb^?nJWfqLoRaFruCf%V|ZEKooG6jxS(dhN%!N)$-fhjE4G z$JKk@yUO=VnL;A8^9gD=-@i<$%N~Ccs|(#x9wR2TMm?Lv{)o`o{#%vM?FgM8x~)7K zb7Ax|N$fR*PVnEPgg%1M*`c$rjF^`FQeM+pX-Uic%Cpjf4u?3%i1B_d#{J4D(c{`L z<$LyHblxwGv+kEhb?leMptn0vJ_E0jh^shW`eN@cX^MTnWE6yvuHHhlTF6&aNvo8O zhNM z4T*mSqp_|@VxMve+wv?(OoGG_-w;J2@fwLmkoYWEvpj~|WLoI?gLR0gxzuaYC`o#?8 z_d{9}3c|RV)MsfNe+?h|K~47NPQAx?NW-r4X~wr7&9|)ebQ^p)a@IJtIxgB?pWBud%-I9;JhT(9ZIc?ad$Z5fW4_; zZ-)$Sk24;~J_Xqy65O^L9gq$Mc`;=^}X3uz%21!S{=Yzf)0PBHQMh-^G! z@3eLhhHdT?hVK(!5l4%AMePpV4*ia(9dC)RRfexT9`10xiuPC;(uiaUw+HvaPCXbu zTtH}4SQ6Y*j?t+;i7f@9MV>bXJ1Vs;&y{x|)=j{uwB^CJa$O6_RRW>176o^d>sv@} zCJ-v?#9(~CCO)dgi1rb3ih7=|Y{5(t@*lu_0s9HoG$gU>L(fAZGpG~4a~{A9quG|k z{u+E9A-2#tgj^TYikUSBFp~&dlh~hv=Ma(<%D}fFsA=CQ4ib+_$=x|3&5E$qfY25t zCWvLIhZHyqY`s_`R^zTepqa2i{A2$z%fpu*c!TVDXHYL@U~Qkoc4O5L-$F8NxQc6` z_&Y+&%4;iPTb7mySu^Wytb3yFNUg3ezRpp1vNows7`|{$_{w*oy)GI-4+o$ZuRNc< zzqMrxVSH~rbgCrG|wioBBcGM-&tp5yL>{< zs-CLKDp*#pPqwT#0%Tc2kSy!6e?2V3*h03I#9j!HW&IK$%R29m5{GfiLO%V+Ma^%nC(Ll61zPe-|^cA z0x@kLfNRV4>u{a0J#l9;?vl1I#+|Tzq0~~T-M$Fl`t1ww9liZF;D+r>@Ey1P7OCaI zsGY`VZKJ6ebFm!lAc^r)faPj>~rzEv!f?O&xlUk5wlCP zJ?fd5XH7d3o=e(&eY9>zRiEBv*(L0R1UOgBa?Nx4-Bo>24PxKG;o4og-IaaG`O!P) z_FXrsv@dyB)NaF0%`>r z(Km1;JUZ~|Bzun5-dyuHcy0=t4ofK=hrzWDOZHBzamVNjbR!?WH2saV%Jg!ws;B*_ zSVeT;>UaKu7#jZq`W^7wYw5aPruVo{`@QmU2`f%bLt0UiK&0ONF7X_PY^n+5@qF-wYL?cU%$L&r+jg@#z1p7&DR2a8P{LvnVCO#Q|H^5 zOA^^ecn97_4}V-NDoJF&4bj*}{uc{-B$&a+nnZRA{ixMztBk=MMR8~~)8R^FYeQqi zDTvt^l*h9~b_6k-z0sK65?Q?xS`)M==^Q}l8n5BinUc|zB5L--z$qQ=W<2k4wiqr1|60XC4iU@(NhLY4-{2+t6(lOC1Soht%tG zPfCWSZ(N#QO}5^XyjGi^{GpJo$^LI9l*Dv_cmD?yN@8BW3s|*1No7Y#>_7gVevME_ zK0lAfHrpZe>Gf%Ab@1&8HiKuTL&#Ww@#JeY)^X`yO;ewp_RL3bhOf-?FY6jJT<>`f z*ABmc^+sXE>LH2i;tmO;F7=Lgq^(OY(f6i#!dIpu^yZ+wYRWoc6eY2DeHQk8AVZwg zG8Jo(E?**h42;quPHWA;sJRdK4+rB#Ef|X(t^OO#OPi%puNAfkSs7yC-pSkI*cNHb z>%+PVz%h+wV?~|Ej;jK3tSCIAVPWaIy&CqlG@bg$df~(GVV6fPrynNY4Ye!zaj1>$ z2j`T}shC^YD;Yh#lC?XjezR+f>x64_r)}+VDF`ChEL z6WM-P7<_ahyinCitlAg7Pb^sBOA!`fUQ69vI=!i@RKVOAIFjHa1Z8 zYk2kIw6wIh{EX>60?P~Bo^}w|NvQi^M-^)--swzYCcoiOA*@TcR|A&YDhb&G9jWUk zcMYgWT&vB~^}@@wa@Hl!nk1m9UGkl<#_E{G3iW9&OPQry_lmGRmi^?D*RaFNw`P|& zZYiQUi1bK(oYv>mPpIFMPD#h)qin^8^h|TrBjt})Jo`boQKX=haJKH#64c7SWQT3RsY7DxU=(c(8wA^-NC9E?(VfhO_1>v60bhXrOU zEl_VIfQ3LM>(&qp+?X>oXi0 ziZ;s;br>%`2n*TM9FymyxF$PB)w?m)Ern;G39<{rh2=IzeJRyv?fOWvHl=!sfPd#7 zu9RU6%0*tAMD~?GOTluu&C#fv$Qsehz76HnWOHw4tcS{gb(h!HC1e$5%a&)m#xgu> zQm?ra)(mu{xRM=%pn;^Y?iHPwSbkj@SmG8 zeD(R2|L}F=|7J&IH)KOFuVS((vL)D2>HQTCIE3s)HTOFn?M!csW4rw}F^+xgk7KFW zrC0`k*d5Xu_|paUrgwFjz=nFAnXAfIm&LJGpG}Ns#r%7?FCIR`c=llEuJXIf%uEQc z05e<{3|)zWEzAyR(4W5d39JXJR&S5M?hV{tF0eg7ej8YZtLJdFCQyqjH?EokHMrW2 ztNQ~>arHEhcU!rTEwIONeG6vt5&jXPz?{Ap#NpyFG0OAF#TdOP{`q2T%qPHKN35~{ z=3J~}ZD^Mv;U>{DD3PVYPKoPfN{;eG&i`-nZie3g{ohyevvqB!Ut;h0*_F+bsZn6L zzL^dnQkv_4U%IqeG8b)@EOvoq_&Q6P#E&lu(T0-(8{n(DbpPtxX1?ubzwRFti<+7g zWSrxd6pSXn{FJgwGT26%OZuWRwOcn!Mx^2OQ|Y$*^DCBRCAzA94K;4{|I)AXCuHgR z1i^49j-^0z|MJF&;VUC0f&J)RFNUt{4O+3IWOJnbwygv^Oji~KjMzyVv^H&R!fzJ8 zsT(=t*9YGC=Ddz+4Th-jl?(pWKZdWI4>sa^Z167Z!Zm$()!#1I#^(x#WY_`m=RLqB^Y|~S&z^0Ou;Z1A3-=)LjI(bz>hjwi_q9a^Sj|7t#p0}(%zVS9SU8& z{@EY7j%O>pbggluIB75NN%BXOHI^C%2sU6Y!gA#6b&>1FgHfW89p$+RUaKUwNYadB zO}e>b*F|5P6}_|Mm$QvXk7TaDAk9vL6%TRYJM$ZM-DR>cok?A%ouIo|qJu9K>#8^~c_-qU!_Im7 zakl&u*uO|~#dqb1t)=gum$08m`BK@b9;4{`pcZSot?-zd9Hxpv>$EoQMNML=)8Nqq ze-ysg7)MNn-j?c2TW4fX`NCIT#5zxduuVSF3#E4q`eg_2aYTuIZ*J>MU3nL{-H#G| ze=jBMHL|6CAzO<*0MWi#DlKw368EJpwvA0$m?7z}*N-!@D8DWLm)@#N-A+x0k@aAl zbC$(q3H>&W&|jpDy;WG4c&mO~JbOHB%kS@v2b+q=S{3oL;9^J)Rx+suHGOAd2wUI@K$r@^cRhNnyjcjv> z?zV=E%o8@UAMp7)OswGzTz$!}cH-&;-;*xv(z^1xwD;>Af^DXhY1Lrf3ELY>TVR_H zAB>x$AFdap`U^B;M2+3dB;Od(IXJ5Su*S@O_U(`=3v6OmqrS88eTpw+#Z+i7?_GIp ziDs<5D}Lma-mOw47Qy8Gr*c!A)dvSxZkHApWOWIwz$avF#I-OiUmQ4h^};8*;@Dwd z^ySxAr`}pY>z|wA;1Bh@dGA7jS$v(P8c!Vjp_*~}@$vaT^wQYT65ezuwz4H_yL8yI zQR)`V{TlN|T|h2q{@tjL#~PhmyjEKRx>HVS#U^G&@5FZ#AV&+%o&^HT(Fwbi}4FSUB&-^hc#5c3G!i^^QRM9aycqxKXzi;YQCOmu6gX zmp(VTM>DB9eULNZkUlfj`KLGaW8?DK*)&HpVh!_blaAUnDAiHhP|twM)N*KFNXay_ zH@vn(RHMZip4y?P%b#r9VKJI98*z1Gml=L%Auk&GNOh(j+6e8B!9GQFW&B)WnD9)F z7-_?ntbf+Vv3Ejp8(LmkG}Q@b{Smh4rSs??)TV}mIZ2155)Sf{@Y-_LXwy7qen*+WtyI6^n~)#<`hh>?VIPYiOCa|59|b)YNiB zN@kZA)tnM#n88ePZdf@3z|EPmycemcD?LQx*z5LW~w3oN9(O&L;0K66P zwT9utznFEmtywa(G{ckFEZLfd)(u&q&xz`vkM-m(>2K0bduz#*-d9|&-qltzv1bR)f#^r(ouc)bF3OZUND#8JJt>uW zcb~sY-@i;FusSK)ldRk)<9>?N)RlF2R*f#p*m;gZd&D9%nPwbMOgW9$=5Qu<)pJA>I|($F9Sv%1 zh3`*=oCBW}*y;aU{!-|w{J*jPpD9M+RMlHt{zX;3PLUTfY201EM90F$C;K!;eYs}L zJSpE=mbbnyDeLFnQ!^V&A4FUMe98cgKe@N#s3bJ~=sYYn;;s;%l;;mi9(XUM z!-u7Ad^X`zjZX(8Tz@(W|I|@Q-*jiqh??(e_S7Ue66VaTO>lf8E$M7_S{)xbXV!E} zDV?*OQO+n_**d#%qKo>8Z3xCLn_%0S1%E&)+5vk5OB-Vg@_`@!ta92tiOo~qTaz@6 z*6FW(G-4utiv^*h=>3V&EGsS*T$VwGEx{Q_MhDG_cvxN-(#SMCW0r{K8<<64E zeL7pxfBI{0wUpVdD~A`RTQjC`tSRrGz4rGhU!2D1wjQ)pqQ2d9Dg(9XZgO=v4K9zf z%w?;2+*MPP;CjAhp6guA7FR~?30G}xs_TW?MXqma+g(|8bmoG}E@ascrix~a%Yt#1 zr2kAaX0|l$GyS-6(V*eYD-+FYd5%3>l#ZbE@7vUYHG~}q|{hSdME5^PFJzE8ptAE zYHed_B)$KNhdjtK_g~(0S99m!7RQzp?BS(vyMAjT8zG&Q8aL*&6pKPuqQ}H-REt&6 zJhTN)2mNfieBuFPo&$bz_LXMrxB?SAkf-15`|*rqEIK3Ywc5n7TQbB1<`1R26PX~L zkpyc3yA&GhjuLZP6WA57-W-Hq44sjRY-c2E^-OW5G%h|@w2I=^A=?tzKfrg=5%b&d z8R@m|Gm;)>qK#A#Jm65HnhjOD&Lk z2>Dc_w5vj2N!h@&A-hJwT!{a!CmkodIz0)j9w{EMWr(>*Z*gc6))@JSdmGUAx?@n1 zT%`COQoIS$g-Ed+(%l})Em|CnuGS` z$FhNeJMhx^g6W7I#t4h{59Xu&DXlA^THki(!2Kt|V>lT??bah`FK<}2qdv=>BmTX9D71GplnHrC{X<3it>DnM@$Te? z1onE6%1VUl;Ts@|g?g3r{O6?(~1gn(t->anFfb#1#gWHec3p~I3P=j7fLrGlS2~4AeTn?O(>>e*dQW3HYWxNDkkj(kOq~&^X z5Xy2+me1$iSd6$k_Jrh>d2m;%JUJOSrHWT{;N(#H$XL;}u7XCaiz z+7{HdwX9Bs5XlN$D|b+vhQ@*ch7J7>hs-JQG=Ge3GJX4_tqz{YDIDuYOWVuNWD}+ zrl97C17x~_j6u!yI1PdRuOPXoxgLAh2`pbhY`o^f&_fd7bIo$=kPB%$J*a8ZV>Ga$ zTmzK2ae>i@6~pUJIman@$WL{roHYt^*-v$+oTY%Qw}1Jm?v(R?6y!TUwfp&iwp}BV zhR^t^XLM+Em;2Tn!&vi$l-`~1c49OZU|C-Ta#6MpUbfFwnZy3kKy3|F;v*{hwtp7I z<>?LHmwaA&;VGB;T2;Dm9#mQ~* zaaH0$|1iW|=g&~f^MD$5H}n%JPos*~K}V7D+^(Vvpr=TA7OChQuB#gY8jN1lBD4L+ zq%Snb;F+A|rkQg#tPlMiH9RKeU{*9}37rfJOkkr?!(&oD(5W094J*WW?>~c6o5v)( zKr?BhR_(#=~c%shElTd`r}H{^gI<e-X^*W5N8V{(ybdsJ5nPn+=4KM`8Nfr6aahI zLn%F~rnC+zUFxL#wc;p*w{}way=r(pFF~_79Idn5uMroZEtf)DG)LF@$+isrJGJos ziW4ArgKvU+NL!h+$BB8`Hdq-8s$h@Jm_5@4tOt}drulBA_V;D-5SpiPc7>;I_hoR5 z=G8F@Hrz)&59bH@EH~6=hs9BP)CX)RYqMCu`+ces-|QQurfXF&y>GahZnT2=ymC!K zKDkdD`g?Q}k>6H$+$?PX4DOwk6NQti41Q6 z;toMhOE9Ws@U_N@ZYoE*8pncACod(R<#{PhYN&wFWsvnY@R^>=hP;t6y-UcW>cbz&zU`Fqtgj!MIUHuBN@V--Cl zO{cgV{iBM$E=>c59>c^Fm%|-b-3O8-#UC!m3UaP zBkqF|jr?+X9#X?rN;LAz#xrTvvNJI!r}VxUSA~G*v}STvs_< zR~8l3a$Uushgw-6OuE|3brk}mq**dcnI(UfWP7l(3*k|S`$L#?C70*C8g?d3x{}Lt zRz-Wlq${~RIOm8FAVsv|**MabT%JFx=pVvlS073dyXslBV5=2-77Mtp47IePxT>pH zC9*4dMe&lFMk`7fSy8m9=;kolmAs;OT17X6$*$xT#YPpqFHCkNuPD~3=!!7e)k;{2 z70(xuuH+Sk>woCVsY=`!9*(%x;Y_tWH>hE=xvu2$l&a`tt}D4bQ&n^{*OgqJ0u{~X zy2@2`)wk*v=xR{-7OtzZ+Ua~;c^S+!?76GyTqUR`yls zPInV#Lo4>1Xs_JLdcZR`VO`Knvt6@?+<~@8%oN1IA3lOhd}lv1#=^|?HsXl0i|g}is=Qj z-Nlf460y^*IUysd(xBv6 zh#Xfa81X%-FP?K$Z2Okbg!XKAtMeG2^|Sb_Z)Njg2TgpIw&HmZSvMu2C8*&Hur>;@ z3079Dgp3aj;aE1Xi3&E7Yup~50hwW;B3P9?=UcHSs%b+#kdu|!l-S9kNouMC6f7=O zsHSREFhME5UM>HX;Ka7<_Mz?;XG+cQ>OZZwVjR$Hjf2*H21joa<51h5AVsZvE;zLP zPR#W22t5N1(j>+s^dBL4rY{nW!2cSgx)_08Bo<=sEJtaZ6nqVE`{6@);;0<~p57#up%k|&$UN|LE4vvy-O3zbr#j?K_BV&u5@QK!SE|IF5=0BKLZseegH@wE zsj$65B{U!Sc5wA3nUSMBBbAV$2x$dZZ^Ar{wYJB~hA1J4ygY+Zp6e7OmTTUu>PQou z!*$eBGe*@>80BcftZ8LF=#=#T?*M7LvBApv7380Ra*6}wyn=ikm<)sg`9?ub2Fifg zms{E27333eRk8<~Z;o=VN~;1Z`xsmmy_;*JTZwxhP=r`r0kR#+`GA7&1t*eoepNws zgAd6$zn~z`zy~4c>{gJ?;OSQQgCe%^NMN4aM{D}(kq<^A^nYIOy{Pv?iqtAzZx?d^ zje^wkdhZ3YLP4Co-sgeTDab9n-Z`lEA_bYt>wP2ohZX0FA{^byDtNt#qg&Z5C2nB= zw#vrydQ;AY3ZBpFO*xNNkStzr%6Yhgr1E-G&Vv;sf!BM0TJPAvg0>cCc6*UKrS@C& zY^rw*uXhLPtyQFc^;3VdA!RSPK3Tv|eroRyAWT8N_fva&fc&T+XZ+OOHst;f1vvp0 zZpCx`L-73>SdTngTiNH}pcwOcy^kqz-}4tD)*UAn{s|$L3V%#WBgb6H^zJaEtrL}+sfV5wKTtNhBmEiga2l31)FLo^I2~LG-_q{ z`Lo+^YAeI|cZ$co4_ZZg`?K5TBMoaE=8>j+H)*AT`!q1431r1}YHl}kuLfoij^Co< z74R|Wz;3fS?ojdRes~4g6mZk|1?ld=NNXAxeD&e6n8)mgt!xyYL)a(|M(@Th3Z4l8 zOFl>Gq*yC~ZSqj=*=lM7kqG#Z&OmQ_J4$zrOt|mzCY1go!-N%EQY1 z*S960@6A%e3VB#E51S0Rg$SFVgys3DKaJ*o2J$gjah_m;TV7}6Dx;XqPpe|oh}+m8 zRaZuoFTE4|#JvEXFDo;uAz^PmBqD1GLB)Ro$L3bVQ@W%uM)Y?t`Rr)DLg}1W@iSoH z6koRPuT}i7Ub6br3f`mQN5J>3?3iy1zTfu_c5g)c$rk>Buac)E*Wn#i;uSEJt0j6> z#h(M)yPETE72gWhl>jY00}lmxl~M$<=cj$+u8F-#jr{;T5;~NDYV}(cZS)SgCeM{B zzRZgnS*^?k?*!Tyxh(dI$YlW^Q*Q-_rxM9ExLK7d_hw&{T7`;F<9SDPH(kXGkV`sp z8L#G&!&8t;naBM_lneSl_gPq3igzTu7&P`+aSmDT6K2$bFj`Go6-@7Sw4n{HEo0_F zCsAsSk~Fs+c58+8!eYJN>)U$qdl|kI>RlIjs1>0pu**J#lI{MWgr4T1$p~El^bA7h z;rB}=^i!}+@Bz-lW$XQuG_n1ZbAo$ly8(Wshy{P>Extx~?<#E7%3hUZ3ocSD_*Erj zX#1IZGuo_OB0Dzoab}k))gn#0M&nylnY0EAWY$Y$%N8!vtjgRg6>=HblJ8Sx7B`q6 zbEic1Y~nKYs>~Abd@HN*5@)#?eut~pe2e#5Ypzx$aMtdclFd@_iPE*!jPs}M@;EyZ zT#u}IH1`ZetU1Sftu<$;v6Hz!L$;FvDjF+YYt3;AZUNsjq1;-+hv0A|QNM0`CN6-aXC|NT2KTr$KcU-mP zg9^4UeASX)Rj}P*N1MfcV9Y|;@$+hK+rta5vEv<*Y{y#^nMZhN#Eu_DDB1A_CG=h% z8nNU15K4BuS_!=qo&c-|IPWJrwqU=vl-qIrt7SDOC1=J-aN)C3#}U-0DQ_$7tXajA zQtRQ9()JA6={_kf!^c%njPY(K{NtZ>+qPD~vPxj#+2}o~m~o~mx!H*!cb;j};W=1a z>v%q!<2gre6BeA2m1o!S+!`}g{JQWVtjtnjNm|TMH0mWw*V>6mjVbWfl3PKmqL;xx zsm*DOx3FIoZfL>z-E|EX_HXdb3n+nA9E8wsLNsHKz>IBS=TIJ6U69Anf_EN8%6S}I zuki@gVJv1@@=#jv4x>ou2jJDTMo8mQAFBA9Aun=!2f3Y<_I^kC(NkO&_A<}0g6Ftb z$#D#qeO{H_jvUwU9A_iP0MBu&8v2Nm;|wnKsEV%(OpLaZm)J*d64xTu zX$AQ_I19+TKzbGAqu^8^5|CpG@?LNXkV0sm_W!8_Z-J{?*t-f>wXj#QhiYMa!B~$u zC$wd`TWY9(QOuV^dG0E_2f@Og4~=jy;#WIE7494O)w7{W_l^8&EBqHV{Ax4KQPlFQ zO`%kGT?@67g>692i&`z%@0Dj78=q-#ua==6A+{!+I3DYN(qz3FvLx7r+SG)`@s&n4 zRvH$z2`$qc2rz-wIpbM6FL{0B)?Au1tdpB5% z^!5j+56J1gp~}4gW_h)b?NRY(0tKjXyPDop;NKRu4fZ4N23YVuh&mt}0wUz)KCw}i zz7M%Ka|^s5e3*L2-PkvWKLKg3>)Oe5Zs39jg+ofFsvWLj%bd2xq(=LI9 zeWIf8^SyoAB|!gI(Kq?tKJ5}%=sicu2>N?JS;UKA_!hPgEn{KN!D|p%Z&}!G)GJ~u zZdK|@KehPd{tKwpQ?SE`eQmnNQa7lvf8!@BUgh71*!L+r<`&lAr`}B~d<&i*tU`<$ zzZ2iL`LFh5r<%r%{(7|Y0#(`pPew#~PGAw_O8m?4J;Og zxv<5c!U8RLmk{-x%PQxzupfO3+9tI3I8$mDxtC$&_=cEo(|Gq{Zc85j4er}oZU=tS zm*!r|vA_FogmvBl>@U6c2XQJgLe(>?3=6(3b&?tyksN_-NlswrTAD zi?^Zl4Zg*Qd8hAr#9X1uFZI!0mK?JNF-a#k`IaK)4Zd@Td5ape0$eu|vl1~$BSk)H z#c93_XuU*@Ii72MvcC#tck*>kzAtiq#sYs(q%UOni1T>hMJ0QPpaXo7Q#BSm2N*%) zIq#LrX;M+aHwzZffpY3lB5I2(-l;%5Kzy7lV!h{`0>p+A_AAIgIisX8=)8h_4K|PU zfWlKP>EdP$du!41=)g^y4Q3;Toj=JpBhQ_fAb zgZTLN2Oss1H@u|F*OZu@zNxr-$vXi)x-sq^_~@tB55V6c@55NY|7C0?v3!hs!_^W^FEQbnZ`XBaxb2tqGP=DE{2KR zdr`(modVv5a=ejhydkRR0^@;-CUMV2B(G!@kMR~GRioNcVd?4`SHt}la;g0)JN&mq zy)%;1e^mTi&N1cEe6ONkN(+(x*D9C%E0>n-t{3%h=34&@`Xg)WmPWeQ^RzAOPr#@} z-Udru&)ejXg6x;bS7BjYN-lHTPfErXtoNjH?BJ2ii`-LTVIAJN?bLQBB`d4Xi<11@+g z77j?`6)2|<1CCuJX2pJCZLa&YV@|;NA(j+%KpSJGgH_w#;W$^mjbZNLijx z@rS|*NWWQ4|6bKIVPR{zXM!wD=Kp5A|Boz|Y@`7ky$sKO-G)-r$Uz*!39Ja%{BR=D zT&U(z37^7T?0WRNPPxGUxIcpIL5@8wys&LoQA?5f%aGZ5oR_3{)m*CiSDu*vei5{l|C6~Rw89IE0S6|Gmf=egy%%~ zzZvgNl`T@{Ik;EYrJ0=%9cnPMpI`x6)LpaH%zg}$XF=Ag8PA)_W15+r&x4T9fUNyLV2lg! z`(4nEejuS-KLDYS)9@Kk&oHyI3ep>-IkgaJe*uI-j&Y9xl>qIpU>^jBBi35PI;&f1=$mvNohmxFDpnJJO*aGmoB2?t-%7^KOLOYX04gnp5<=k z{eeol86JaScz2zdZGxqZ=2y+IiF|(b5bB!Cuhzk1P{ps-Ko?8+)jjAN*-feLTd}q^ z^Y{OaZZ+fmf7kXU+^eOiLWr$}dGGxq-rP-8kbXl84Jw*t9K^%R)dJ*spq_Y{y7-44A_pI8_eg&tr>noEFC zNHshKa-X98T-@&QzJUQ6EESarHrhxgI z*AGPy%_bhHVKfrS|x8+9QUxD+NaO`V;E-bAY*k8f{4RBk(SvBt}n|x ztH?azBRkmyo{#Zgm1zRcm-W+(cym$S`@luf-eCD=JP#sU@Lk~ea;!!mq=99=62z(j z!#CrdkaDa=;P-N@TY*sB=lQ6W=7Qau*^Nr9Qm)%d?j2i%^*P!fTofD}btzWjjOS<3 zJwOT-B%hz*w;{LD3X%mbDCag@K~jCw(W)JYGZ+ZzIKej!hzCfrf*5==f!I)TABf=r(E#OMaVzAq_H#LKk2CRHz)VtHbty3q zqSR)*Z)H9&!BBTfT`yLyy`0MzA><|B(6$XY0a+%VfL)sLep7ma)6BMbhhpc9cop9N z)%QES!grCr`?zAk%2Mb{!ntoOJE?)Tk^wC}lw*PHQooa!DfmAMFoDZ^nDbBCF>gR7MXzpfGx@2cbEd z1Ha^qo?7xW5VFG0IiIKY=v9!9q+;BCqHxxQ#O6ED|D}0g^AzuW&gRYRkauA_&5>a9 z2!BNl-;eNx?Fo1mB^mh3NR{$yQ^R+0Hg9HbC1f+$Jl6jzo5%Psm9{Scn6-wF7Y^g;4TUlo{Dmq^xp0p4a5SfW? z%u28yT5X3+=_*Ug_L3J;PJM_fksw{=NJ%Oh z&7W$JOKeb36Z40OBMD0CCiYACDo4635l50!$9s;^CMkG>!?)q93@NhzZ^HY9h#|?T zf2GF#EKCfkSK-(uc2wo?7!OnqZ-zf8lKNYmh0E#SJ;zF(dpU=fOY(|}?g|q>dO=N{ z_`mEe#(I#Svykn7iz=}ZEIv}oM^$v4>VGh^2UPU#FtH=>|2Eo_GvWL{S<`Y}YMI~O zE=AZ8@&5&gGe2B}QI*)yEkMeEIKb1^b8DKbASK~R?hTwB%?479IFrDuH*i~~{eMF2 zVLE$D+-NM2A|NBebQY7iQJ#Vf3Da3j;zk(?a$T6tViGq>Q4k}Z7r=a=)=3{OcAJf$_k91^#NNkQ z|7Kp_ZUs3I>S{3IJz=!gqSmJOeQ5C9or(P(9GT`l6MIF8`y5!UEd9KK>u>a4?V&%G_RFV`VCRBhr8P!z6;QA&;_8>o{ zh4v3k2l7i$L|UY0+W#k;?!)u;WWgrB|4$+3a58@b_>KwBgUI%J3e1%(*u>5#$Y1$c z{YJ!*&;Ofn-djFBPWB+%^!q`wV1_t2|Ieil1m)A?CcO7aMqUNGH{p4Zhz|GQsR0w- z|343Yu2MXm*i(Zi6Zy`liR}v6+*4qECf15pUe8n9hIX3Dv8SMYTDh9o;~~=hL#XLY ze!rgA{9e?PY}drrg-EM+Bd2L#JSLn6k=Ge}>uH@q_8`~#Ry+qGvmW#W*fpL1CymVm zW0%`wzJioN8^n4r9w^8RXoFafiIphG1Zaa;55@xpxgOde)`RgtL9*cwF|iD;li_&Q z!^F~{c`aH;v(>}~!!l&sNm1e(;ZZTM*x&`!!VJsOAtqU$f!iI`Rj0(f0;XwVmje3` z)2nb@6Z=^tmSo0tc@TF&Xapj_uK1NA6*g#Vks_h=_gmLz`=+CNZ^ z{Eh@<)ApsFFM2 zvuH-1Xn$~d^#8yteE$yq3E4I`Lykh%2XdiP@PD4l{b2tldj4M-=T`+5aNEK&Z?$CY z4S}KU=r|Yl zC6~Wk$$1()04DIgbI|z=c*r8Po&=AY9CMr!Gl#d%u)y<(nWxrwF!yfAIvyI7nU9I3 zDl%qx6HF`~@98%&t16>IyU03w*&NEN7XdQ4bKR_ZQgFH?dxS2K4)PCDtc+9)RqD&IwNe^D(i*{$ixwfw~-3 z;=JoG0^$MkM+JGqKM9BpxxJ|%FN1;0W!k48yYPGh{tE!&bO51pY{&Bn8^C<%|K-WZ z6L>y>{^NoP`~Nbs0gPR?hes4-9lQt_4;1!{{*I>-(Et5-s*cZ+WwmHu`2MKBEDuaX zn3L;__+C0{U4!RCOgQg-b9_JmGXVe>KfX|#67pu z30!w$m6#LpJc)_r`{#38#A)feFC}{?S$$sMO8Y`Fza>SS1YKs~-3Hd93&q?PdP>jJ zjrIpJ>-&XbX-gxJ_dF(+0KeTt?0;hXhh5tFRZO75UB<7pfypiDtzTls)*!|&I9)uU zr4SnYl|NrWJ)j?DqH_Mz_a*F{o)DF7?w<;uHnCF($-!P$9&|)4d`b=Z6i;^J`6rz5 zFtOt*+U;|+O?ICeGYq5FAHdosK#L#vhqYI_7rUYmv(vW`{}qMKg;SZjz?!dbd)yVh zWu6Q3zh5Ut!;UEAMVzDG0<1$x*#S;*%C1KWPy2NEPb+e)Ep*x*u_FB6#EAcEQ70NT zH*n96T%!lo65a#uA1U`r6L?N%~0u^=mF1ODUixG3K z;#Wa?`{?XsF?RS(Y$ncFoWgSy*egeCJ?Nn{C#ll;K5v6g9Ljr5Wd9%IKTZXh*btvh zErm^$Nb(UckxOx%iW-ok3GdjBjBx@l!BAcTElObg9;Y{X350W00!iV9Ch&hM0X;v7 z`Cmmn-cpp{te1F(tcP#ZuoGU|i;+w4g^KEM52DqI!gy_a+_iI?CoKOrHvz#mnK z*Llu`Jm*do-GjFhpuN4sLFAlYP{Ve3iG#>F)ARo_U-_MPA?p6Ln)3$Ef#p~meUa79 z!>~f?A*;c^D&WDqgF8x3K@@cG zGsb_gCp!Cv@jyX-M7-<{dR~vpbzVWg#-6YI{JaVNpoqqM5tl{-n=%^osv$?EJjACb z>oNbU=poKmC5}d(|2MJM!E@#3?J*vxara0SKa(*|cY0Q>}0+sVCRnf^3^G@NDR0A0e4a+@$3=lk1jpw}`Z3PX1F$I`4 za@73O!Ub)^aE4%^s~WAIjxz)c@hkIxBluoH`!Jk8*y3shYQh-;nk{3M6oWV;Zem*X z41p2*z4O{zYjD;YZ%L6^l@b3-*T#905&QpR!HB3V=g~IAm5g{EWH9GkM)nW*BaGPp z7x~K9$o?L-4X*;HVViU`QT|Mq(^7 zvbPoV6`!0sP6w8!S@!TMvL%- zKHjqq`!eEx71G!vKhb8y`Tu-i6*y}y+nAA6s`<=NeG_C4k=)0DnHurFx5$o$k&RWu zhKK4=+mU!%gzV!ovSHy|#7+&-SVK09{|}_bwuES`p+0V82`Z`wvo+#K2vOlQ%(MI;38umu;0!nj0EzR%w`E@y`eIXi4o`V-6l2hdQen+P2H_Z)C9?<a0969F&D(b*94@SJ_cOUGWp8uD}ry{UIdCWJ0|H~@_Bc1=}<3j;LSiR4_6VWGM|z(5{XO zMy5rpZb4`We2_wa1|K%EE5XQG0_`1G&^`y}C=9i^?rE(?b}m5u6ek<7qi1B_1}C?a zx~BvG8yI>y$4&(&Vx*V?>{Bp~=^XnUPn%3>nF;K0fO>uhG(zwHqdecm=>R<44TRqR zN5~u4m!)UIjr{$8guIMgX&e~G$ARA~@!A7^mp(+BeUaw?-_9(WT-NKVm?4mi&#vqDwB@)B}B?T zL`4(8{Ef^ER%!(QKZlg8igyG3Js|h$SqWG*V8wv;56Zndr0`!O_}(Nn-(TQUiR2qO z|BwGK0EQgN_ghu&Z+_}!C$OJyWPgPZz=-$%MJ)c$>Pc=R`-^(=1M`6@{kH#VuZq0? z597W6YOjjC|IY}%N4;v7|9M!<3u+!a_z3`cjChtm4@**H`f|^`1qg*Wuvahl z+_~J_fd1~MSz`vCBhP5iUVdTKDD>PSwJc-(!`enE^Evu|K<>GA$WkB3_K#|#=S?=@ z|6^hNN2nXW8A|AN@U&n);BPym)2o>O=?w@qbKsS)u0`*`?yZrgpRmx4BQqgn))5!b}D*5YP!14N7G)1BXkn3E(AMY$u`W z1Z|Dj3sPGr8N>vz2JjLR+XuY#!Fv*oEq$bkqE7|&c`~9E6rYaTRt;KDAR#9+$;|s* z`<$5sYoE{i{yx7yX3jZluf6u#x3$+=d!2n4EVHUf)2l-~OyAUEHma@B_$1iVM!t(wUkqXP2 zJeWPV$N!A|LK9BEqk3%u2PL?EFZO3xL?&ht(RWrf=o&yrZ6C-3-3GT~zjqLp^xS9lv*KDCEwPk&BBk7A#i#zRULyn^Uy&HIA+4^K>LMjlS* zXd5C4sg>N3hCYF}3oze@NKR-aKb}r|7`8L)LRRv=G<4TcDN5d*E_oa1rb^ztoEBPmBXb@JUUAb|HWRX_#&FQpt%-^Avyde!OA6kHtuSu7@bckfC*4oR{ z{tmn1Pv^LdMJ8w^m!zRZuqV;qL$n%cC8zfPvEDO(hgR~GbdK@xci6H2pK5I@i&D_A z?1*CsgN~iq|1=xou;9aNt|eg86XXnR^e~%a+WY@l|6z%T*_i)Q$BC+>>wSbcdaVCx z3-Ue00HpfheLX?|>w%u|%Uq-2Ey|yN-D}wAKix zp+9Bzy~f>^H1w9Vr^AkT5Uo9JN+3zr$&G35D$|}0*n{c}lw6+nbl83oZsr$Z|l z-#Kn252X$J|1`U`lCMldFG+hkpbw^@?j%_&h3S&>U`3~_m5VSd=^I$1Hp_%`K2zG$ zVTb*nDtVY$$J9PH?Ej~rear?XE^UYhNkRXfc(TR@e~>0u@Qru2n@wEX5dXgnCBLUz zGB)J|tnW(H>@DotlRjiq{u_{GxE{eCEzNlw?0=f`Hk|)Im(6*ba+uldHk|kN1xk7; zUGkF&PfKyDiTOBe*#9S;$cFbpXhz%c9db`=af^xhIBZI5lB^jUv;Qe|Cwv?>_=8fC z!iM*~D_c)gAzrqc<~_w{+hG6a!Cs-epQF{uUa?{S|6P1xfV>;p`G+>V|9>@TRl~!9 zufT)D8+8uWqTV>Eev?hvphGGWn)H|l>0v|szsBhj)ZGMI#ilINAq#;=(u4MvZ0!7h z;<=c`C`5rb4|vp$g^9sUVR+~%b*2uR%-&RR-a-(kt<7)i}go3au<5`6y>`@5RNvnl>`?#t3U zz&4!!m!et3+EwFfb{gtrt)X#MkcLiVHhUHN5BvYj(_m9xk$ zKLGMyx0lfWu*zv%zYKd?lMh{h(5!m_@d28AcnJ_1i%-F;Ksteq;{TcCIDkEE%>Q)B z`-Y2QGo|E1%ZMf)9s)My+A(}dOEKmh*-VfJNZp6)y?W};;qAcu$J4@Q8{)n3=4#a{ z*jN?S-@)^(!#|_57ume~kzRWBa64e7NTv9Hnzw85?nDTd6Xw4TslfXRA$cYs6#q{+ zOW`9x|HHF`{vW=sbrp1#hU!`Hn?U}<1EJM$p^ohtCbjLC&!K&d6Bp&Yagav=Vn zLGn>fJx*b1*z%jsEo#w4!*ar;(hZisl z%Le9^<3Zb(wkh54647q74g3H9sF}L&iY5>4JBQz6 zc2@zD(a-6nKN^28t(n=B$8_k!fRf#%y}JhauUpjU|M=IiyYiUbh5k>&e~DND$b0P1 zqyL9JtwpfAE`+Su9N#8isM}pO%I&0KjJO~^fr}jO2_Be5dWW|(;rLeZRmg9QpEQ= zacVsJJ4V_Y>4i4s^K{yWY!_N9Id%RY^uJgsN`6n@Z^nEF-BiiPSnbH}vMH~n>HIF1 zvb*q|&@}WJ#K_z59rBdjWrO{n;`KK%l0sU^sr`SOvNyH>B{!!_-U(kqs^t6Fc?ep` z_onG=jgc=)YwgtjzYXWT(+YTNjO4sl=O3kWRK-X$*Gf+9|J#)7Vrx8Y4OCiY*6hdYYd} z*u_rqlZU8{Fq5Pg=y|M&R;XhoVgH|{@aQwh5zvqTAs$rhXloKE9@FI2*Vt!<{2wYt zYM*Xf+LXUypP9zPs5bTC5Z)1~ezbyT|IGY9V^xtT<{2T+nZcLJKfKg>KiHf5_0{Sn>Emhws6Qq4iFcp5t107s9Nzl{#c4d=*-6lbizXnBWgT+G z5NSt?m^VUOX&10je+i>TyEu~T1_?kANoGtLf1Ia;{R=k z|6ieVLh=99s{aN1RU6?H|4)$DRnm-7@&C~O5I>!oU0tx(ZLs%f^b+@E|5Ki)nSX*t z$a6a6QRbhZcER^|8O}cDpP-(9M29rNKFY%L1G)u_^*$YKj&B*WvHeSU0<^N~^jtrI zb+64pdLM*JzZG`8R`c6*$VS-eTFr0LA?sAqd%mA8X|?|DxDD|jw8E^wdlTCHyBax2 z$0>y;M4Nw$0ioKKz!Rd)zbgTu+FlAz0e!{Frpy6^YCByet)~c2#Murd-bK2j-H_r!*Hkkl-;Dr)k2*h7`fPyC}z zL}3so30RdcVTGHRuJbkaj7#v9_fKK@nwYNhcOCLU@=53ir0aa7Ln6s90C58Ht`2zv zap?FKGHPkX``*{JR^lXL@*z`6ui`|1eCIX!Jn2wO(>jD)UX=AL%EE~Xpwp&99!FUr zrtkc_4rxVMA)GG<{a=UdVP!px_OrtNzqZ9uUCI2*RMsx|EUZc$Y;z-P({0G(K}lOs z5+I=Ra~*OUN-{F7XR{8u2_+fjCBUiCAvds+s?|lHd3~}HdXTx=v2pq>3s}9b!yK8; z^q5sRZ_>l=R;r(EdKY?1ag%1tErvhE!1{X;XcmH#x$q>=7uamdWjbUg*`fOlEb0#Z zuS2H*nh#0lVv@`WXeDw_NKV^Ck-3G)e}N9OCP~A|R4-|rhbUI5&5HQ{OIo(!R6cE= z`W@8_Sdv-QR=f|gR-Oz^%!+uBvR2Y?ASqlp37*dX!+E||A>Q(q0Xx>@j57KfSf?Z5f%&NSsL)zGz0n{E8 z|4-cfd!iKo&**lm74Lhe^aZPO0A3!gq(^k@ri2G2-3LF0R#KA=-=;_ZTM-YU(fv7# z{-=`Y`+ro@W_;1ls{AZn(k7grFJiP%oo>a*(Mq~m$6lYH(OZf50Ij6;I=ozeKfsFk ze~qrp-VdOXmg|u3;QQ!Sod2h3G*)Fk^Qe%vVa56Xq%lw{;r)Nc*K`)MP5Ec&kc(JL zQVY}h|E&L6jY|NzP>0wUXEesg=@22Y3QwkVsWHUCYf{*%41)u$)IqivZN+(Sv^!0u z{zHd+0vkqagTLvJldv{ON?MguI;02h8IzQ>A|6EJ>`x=h@${B%t6CB7t?hc#c+lRE zvEqFYl8;uU9kI;ytW50xvo<(5qFIGjM0il%p zMrPoD51uM<-HtaNtndeoO1)obu$4{4qQU21qybKXOs6Zy7m&@7K)) zJrZ?G+`cpqdA{{J$3P0RJI71gs_ayIU+DFoL4z*~g=hHcwiJ*DN^eTB_Csy_f9 z*R)>Ovafn}Yu3h-HTbSOygOFddnK*c?z^Vtjq2l|VB46ri6|V#Nt0H@dtcLrmE9?=L^SVmX_;XK_kcS1laYM(ec8qMw(2$bMk;+{mA;d@x9zaHrGlF( zKFICnab{{ro-T_mt7FEq*$SV@DZ4`4v`gj3WW&?+MLxoFI-8J6bHn{AT&A~*$7`DKMwF(zi0)yd-N?N)Bu^(cGoTB5#mgz%QCg|>kR zPDyP#E^`+g(2qLo zv;TIIzdYkoOW!<;t*_9=_l$I$`iyTCex0*+##$@(dT|~q_BOa_>(s(L;?Kq?632=7 za&S&uC=vcLX`b~GbKgAk-TgN`pUu7=%ys4DXzf}r-{00Kn}Z*yg^mfJ@fW<&JvoWPUEVZxIcPZ6B(=J0%=+MPIsrUGXX1n|~yExk8>Qnj}k_MXI-U<&|qIA_S! zxK41In;s1m${b|g;o)Lg#5!q3JV>c5A!-cre|UjRJ`1bz98&ApOn-71^SX&(j{|07 zcmD>Mo#kj5=2|nFCc(3g^*?TDGBoqJyEkrw9cV?oG3L5%qgj=0!*)P37?jR?vtSf% z)$L`g^24}@REeeD94Glz4T~Cm9bb$8o6>k| zsvP7$QVC0mS(N(ZqQ{PZ!MQEUl!O&~sK!3dZ`>ECqIUfp^{mI2+Mo|I3(~5*2fMo- z-)6HawEtfLoVQ}-%3Z6hhzBW^_g7KM+wmE|G2-qG9p`11i|BOekaj)S?|>VvqLhv} zQKnqa>Np2t#j=T&Md$xhYd@stdL&*fJF6+z!^m%BID3FYV`_WM2+hje$9b(v17IZ4 z?$Yyx;+#8B{aCeo z5IL@9ISSJ`VE^kmW_?SJJmi>{;4aR4`s7-wR{^k3Vy<5hi>{I`pLgk*$P9VhQ%*TK z=t_9x3-BfOtT;E#D9?xF8TWK0F!@;F(~0RO*Xai*lh(IM9@7F{+R8M!Vh<2yuH?}swL z!&;XAx}nUb%oand)SO!lUf~ZS8AiOXLcTf~^9LiZ3^@t5Xh=fND_G72Lx$F3xw4vS zcV&#=9=u6_xzAE(qHaAFK|ZSHa0^f)5u6mp?7+%nrROlL3x}jWuGFyGw$D0Hf5%aE zs^cTnLBtv9NAX?0qxeqbzN!zZ*5a)iY7ujc+HOR(;$MZGfb}1Hf|SEL@W{`(f+P4k zc20G>&?i-|1DAKLqLtz|>Cy|i61@i>V6ZpUS>TyQ@-D{noA`ceW|I@o z+lDeBCy%PLz*`|l^`jYkC&M}lEF;Tx`;eu{qVrMc#Mgyej;S7SF{_Pov>>=v)0@hzsRF`}V-_<65T_`DoaZ2`o2FiA*<%+iy`XEw{;k(s@ zHIC&L^%T>Pp|8nmMVs0=bF&5CdtVN2ZMajC=6x3B>!e1X`0rDTaY6%)`!Cf}*@E-l zu{I&zyO`0Yx<=Iu7C+8%yph!Sc}ulnomvL0!>p8-u`eri zW7hPYFa@e!S5I{RAt2#t*tj)dYfIpkKXaR>U6z=b?+5evZfYk z-|O&W9Z}6~>jID}YhG7F#jmS9_#G_HVscyzl7#Aktm(nK=RG))=-!&_fIle7YXafm z&bGaQPlMy+;{kWg0y(>CV@-*?rfMSi{u%fdS?_Je`4R@~iemmF-bJ%hgGiMaY@@nB zHnLg%J-|%tZY^MDmU@k9X=)2nt1L}gU}c$``Mnke?|Qe=&c7A$|AJf_6!s9tWl1A2 zObo-5#+a)LEfh0sLHxgnbZ9f6;DnWKQSy=!T0JLO3=4dUs?oGy|KG6hV3mlTv?W)e z4kT?H;D|g<(En7}NQ|RI!UPM-NPQ0*zzcdK$vRo%R)LL3)|Ev$t*3pBzNLQqG$A1u zQ9qR+9zIOm9<(s~pD4Tw+xhdV3f#TT;P0ZBO|k{pe@YYs?=4Uvs`S1$#sDbLm)tGN zOQ32&{C_)e{-EPLmnf`$EGRz{z$5Q==^_z{1?mhCUQAZ7Ug=IwIOL>G#)gp|6rvNr9bMBHkR*s zb3pIMRL@lJf=e)WVs#~F%0yu+PQ*6^MM4_h1&RjoqF8}^#|qL zu0yu4oIlfRN4f4~d{V9->o`H=(&oc0fKbW}EY}8BJ8jH-4{c&%V`eRIsJ>UDO~@l* zQ7Uu@eeVtZJtCG-?Os<;6(9aQaX-g}x*(;NE(yMa{e_5Xj>0FmKcaG>)xq*$bK5rf zac4kZeOq1J{kH0jj^C5{@Z0Lj{Zjxb30V{uqDZ)q3;M1T)N@f5l{s#t6cFMyONSUn zEZ8S8Di5j_yi;$4hDE6_!3#B^sStPVxSNP|(V{$)xN7BJRQrLeu3jb2lr#Dq<_iEn ztcC&?KAar964JqkvXX-pBZcy1SNoxF&R@;ap#p^LkXB? zi4dMj@RX01s7RRbsx;;9r=p^AEj^^O5l_nox4k9b3)PlY>n|=l54^IMrVRuo#U{gmpr(f)cDI@p0tpKOB0)m>S=556YjnEp%ohN$mo-H>E1n1Ob;AReSn4g?K- zb}K!Fhj9`Co^s6ebk{HzZL#8Vm9NY}Ln@W>{Cn4+3jHXq7T7lnYu{rm`fOdBNO~$#}qhL z;Ltou#0V!IJ6Lsq@tTOcf(EpVg~k6(vffj8q^Q47vcd;bf`Z2&|9|;dP@wOKEv_A&-HTb1yK6%Fl6{Anm|dlwazQ%_xIvhb_ZSNzOprP*v~(r2hy! zBK8;UQv*!mb$!een88{%fVM-NG19RA&(f}r)ncR&_UiZyq*1$Gt*0%DwFOkj4N>+6 zYdd-QH^GaLdKLOtVqDYyKS|-)G5C-em$d&+kf|{< zIFH=aCilcM`lg!AeRk6o@+w(?rIH+6l`O&kFOyia7&m2!g*rVu=-nEzH`7Q9qD|~g z8PE_n;*M-@$p5(b+#DIF=`oIGCyCm+Bs}tr&c%tDj7~3df2MMUOCw_Q4BY$S4-(-U zpmrwDoB?+W;^w{_!2mA3pkanR6O@hcu82ulE{t;SjjL`@4Gs@#P#X)ZqVMC?%L<-q zFfV8Z-2i_G#b2F(HU++P=xXLAvCk$y!XnSI_LeSCy>iqX&EhdusT(m7t2Q~O^% zohV!O;sTOSMjGv{9OTf?f+t|l7-Ty}JoU#+SfjsO1^s`B^ldk+!Fo0q^4aqwJ@rD^ zlRP|+nEMQ#p~G$L%E5DDQ4B*C_y{Zt4;mI_SX~8q!lNAy$8*|YhwbMt=AzuiT=OcV zz7Tf+#_bm_UWPuiAnwN8eoPiGu8__6F0KJ_QG#s4eHPZ}uv#y_f2ds93NAk!at2PQ zl7mLgn>So-pG{s#733QoWq*B<=nGp)>RLs6ZV zpD+v$a%d&o#-0n2qaFPrp?_~;kSX9{T99**>=5I%?bX4@f*)i3;Fbum+sRtt(Z(MK zrUj}4j|EaPa7Ef@bBd;bl5B56}-Wntu=IE5m*r z>HxF{a}OQ?yd%V81{n~iMtfuiWnR3FT{p#P56*xyV@SdouvYQd~NCvjj45>W!-)O}2t1~c0Xsmw?9{}0D7Nr;dhf3r) zh4~T)P};}9(#GT|q|pfJLE8QR(Lb(ot)#u?;Qno-dXU1F^ zw;FJcX+!eIF8KB8N9DiNEu#5if*fxE=QNTJs6WEmrsN8jsTufR%sD6cYku+!M z|KOizTJ8?m!g#Y2I}R3{2g$XPC5|x-E6J?BdaniLB}uI$gAxMmcjLJ_Z8vCt3agn`R9g40 zgkQ(VIHvu7YAuTQHq-fkSPQ6a$@VuZ7cts&-kTGBeH~~%6*uTKhwyYL@dj2(ZTzXP zY|K6N#7g+F&o0%Zqa7N#_=Xwp?-}JxMduZ$&7dE(SA!7fPXXg|5sr=(Orb>Tc6Zt7e5KW z3%ZOe2n2o`SRl6qzK=12aSqJ=Rdn}qGH2csfdJ;sF!XS(zjvd*m2w~B@7^|Ak%{wr zb){9VTRR-N<8p|_!FcrZc?>>HO{YrVV^JWs-NO!dic1G@}!0Ddo==QK-i zyY+Fd;LKuGm5oC_xeU3p;;*A7CguYfod>%Y zRXmvJYr5s3c%{{}dkmdJ)Gd)MiV!w`IZtm>@S}b-N)+y4gppCiBr} zPmYj&X3+Va1;~CtB)1U|($Cz0JPa$F`rWK3x@~J_{veVUe;K)0zMko4)WcC&n9Fc| zcZ5dWo$!XB{}YEW6KTZK_x~vM^^uR6zGr6N|060dk3c^&k#?!&c^P?(EYI(l&1%N? z|7cH~%6LwPJc=^RTuRrcvC)H?^?V^THn!2YUXDI}?+fYXw*kcnxY?jg8oF8U-CJWf zvAfsM*6*^m*cj7hK&e`--J-Bkto0glEM_|>&;H$IA>-5oZd%8!>kS*tr zrUfw?jnvi}rD8@&8)LVpDh7klEx)kGZ8OC81D^=^a z3`R%mpW?WLcl75#+cPWWDwRiLMH^j9RH~DNGg)WrbyC=PGb5f;t5Y%RGzWERV$`SU zbuwW^(MG7G)FcU0D>oi8xQ*2^ZunZ1V5WtqLJi*xc$3mef~S4uvm=6l!kA1us0^CHHvHm>z?zUaXp-1+g{ zBTsxszaFM>j$aqoXm00ALLIeBxvp@-s|~Fkdpfwr7GFtMea`XRW(Ie3N{z`uCAo2O zPHw2farg+Z!lBxwYUlO_w3Tc?>c`37Bacb$>UgQ+^7cPYda2_%AAkI(c`tSRHbnY* zN#{KclKgB(a`3IB<52mzWGx?c2P<#jI!X?!EX~;XY=;RJ`pbH{F?vgWYsU+|!Y3E}?iTHg6-i1yexcQ_=}@qr`Yb@mr( z`D+amA!{3DQoBg-QaL6Mc{#-@81(mbypUPSNe^U;hE{7W} z=VWYbIWLbXM_Eec?2u8DCTfY~;FNEalEZ3aHg$D8k5;@?ww#vuuksd7vYs|_SIB>y zq}AjgN?5Gd&B&&?_NGQzpVpXSK5OFu^*b0_CAER&SHSb4vHYwl2cM<#mwkS z&dHgPjx*tKr+ioCT;)pABjEcUsk@4VVTG|Q66E`%Ri(Y6cs$T`w*3CYXUO{%7nQh} zA-j`TJ{snq;a$IQ3OJ|JDGN$?Xqnq3-=~^9)@7hL_gPf})k}t4vT2zBn*dq@uG5E- zgKbF;X9ANSinH@xZUTO0-Yb@gr$fT(;2PEGSyxrN^sb-q=CQC`9cCy4h7-7AB)C3U z$M~bRBK*rc9d7e9$;rEj57SD~eV=Ls7l%hOP8)caD&0Vw{#Bh;b=6@ivs?-JTX(f~ z;Og76>z&*^9rgIQG3O+DC7lMDn<_+;gI^~3dC&N$XVee(4{WV1IXtD4ck(j-jDRyd zoU*8V0h=W`*Cjuznmydqa%HIqie74gXH_e%Mz4r-kqO4TL?t%ll%+NY>Tf8^+Y%$#!q$2rZN$-%FZIqlp4A4m?K8=?Lq*r%ASw<$a)MY(}c zK=LF9KToH(NOAHSF3J5bNtbgr_9s~?d6HaMcy9Ns~k0Zx$C zk!>BEVjqe^MpB+@kw?R^Q|tUdnnzeGN2qpUlV;Zgo4F#bKA_dt6{ z4t|s{1izFGeP%K9&0U{oa)rSfczQ+b*%{hAXxoxbZdxEpe7ph5+IVqYRNfz|P7cl( zkub8Pf%+=#*)@XIA?Rr5T|D+o-Pp^@=bLMIoC!|%Q~8`tJnRB@aLS6j;9g%=k1$Z{ z+v}5h9v%2GuHzzxDCl5}3yL&s!ae8V34-}3D3)P&ke@I1nfaWc2>r|%{Hnv_5tV(Q z=RGrRl{Sj--K8;O>J>ckF2a8fI}mwWp7ynzC_$Z|k$Y*5m{w#5vk!fJ)={?#o+F+M zopm$_EBLwD0c{Sy3qQB9EH^kFwtmuMjPh6H2F4#+9}EMJFeqJ0&p{z7Kn8gowM#dE z_Cow-mtlr1$(JQnvXv{GeZ~rdYmZt|AIW#Xv)>E!Gk?}i!|^2)ZFj>^ah;uRuNWbjpmE-@!VAtuD18__L>c0wb;SWeYww& z`AUQ@H1!C_g~E)8DZ2N5e(v6T&C%ny9=}(LcBoztKlf4mWA@#{b)7=J`mrZ)0>Ah0 z`x3t%{FF}n)h2nCJWkGhEAvk;)*M6xifg8{ys~*|a?k?2jA+$XA0)i&P5aT4b+cZxympj71qxdL8Umn69_1|8T{2~}YZ7hta7 zeSK|i@OU?x))GqR3MA~ugpiNN{4WSTR^tdx+M>-_nn%2HCh-`!f2@jRWw=IwESt2& z0rJaxam*>GqExQy{Pd|v*YXK9=FY4;#o%&|=p}gKFb^Dl6V3yk2{_}+CCP;S zN+QMca|tSg>Z$SdVq&z8(R3X@O5;Dy@JoP?`m>s}CeXK#57ZjeR=o0`Y3#dk_e2eq zcq~y^>(<+nIC>Ge&W&hwA(>9}?qQgnz#Q8K)GuSxpJ3_K29ytL@CfClGD?zVD^`|4 zE_54QevBQuTV6&p_>p+u03VpqAv`17v0u#(TQzEw&;~B_WEjiEGPU|?DaW%#5t5p!hL1L7oCr^sXYQ<3mNRY zk!!G$5GQLA?wXc6$G7t{%OaL&bw@6J7J7-!`I+ zu0o7rlWQ9O&8`CcTU=A3S!H`wpNA`oMe@Eim(`U4Oq<9=-aK0T5g%sj7u|E#YDyi$idt$#llIlq5jLoQ>wf5(o! za5{JO2%9f8j?RV%8dOk?$yNJ$vD1$3J*`rbTgr)9Fr=DWZ zyVK9_vggM1^D*Ssa=xCvdxmk5qW?skFEq%5kx>m`1u#<@z+&7}J5-|`CS62#U!%RS zO7F~uPGsttA@lGRgF`k?T_aZ=Hh1!FaWnaJ%<22SAN*R7sXDD!y2+z_0Hjn`g;n3_OkIo zA)4KnoGbNYHDvX3cdHR2MqzUB?WA*S2)aS-VW*sl5x8&o+-D^Jy}nG0H*RV{G&wjD z7lYZ*X$&%HGr~ZqdautC5lMq_KzE7qE=W}l{g)&?>hWY@ke^4o%a!rM;9oly;_kAz zROXcPwmjy0AKEY0qZlC8;kcpQ;;!uXGg3%}X`i_ldObK0Yc2n^8{XP$jGk zt)#!Jg`laG6IIRawDZHB}1z=5rHtBolX0d&n(3Xxs}8 z9`V)5IihO0RM=~L&>d{~MQ(cz>M0;*1tmS(ya{`E5An(~coO?I*k2}n>-Fbkx;}^B zBcS#x{H74ahsRPh6UB##qR`G?1@4|CIt`%n`#w&{>Ea8THwlnc{{aZiG}ziyBD=dB zcUoJo#vRSje?VK%cq3hW62qjrH)(gM`%ZR8xW7rFgv`m9{eb{GiV&MViU-H21-kXL47d>Eq8H_j!YZ!Ak1qGI1JUQ0WK_7nRaz*7@2 zJJ{3Xc-oIAyc3MHNAT2)r^oShN!o%U%ZV(gEu$7x1+76FN63PLHAPa$OOPO2!D#hZ z%A{-aCQfMse;BPi-EYM`=W6~Thwlut(ZnE)kbU&DZ_&Bx=Q&NTE#$l;Lr9jGNh7W0m5VVmIpr-? zd%8p=UGAH9RW}E_>Negy4>D036aPq(O>2(&gX@E~Lpib-<+ivW3y{wGi@XKN!4K0| zt!XUsAdt);yM%C#rg1*}C!F(r3-2=D!uhaM3`TyHCzAdkw zeKZxG>oUF|x3+ev8TYlFoO?&xxU0*R$##C~eTeEa?J@7RJeMQ$PYMO%1JXl=2cN|` zQat|6-S@$Nb)T9G4^#25wXGI(KgU``>$cVDl0|rT-iLQX?cv;?);bOc%eaE<&fHo_ z=A9XRChR682mgfh!5-0BBO8I;&9Hxsl}l8jVxZ`|J%&@xB6p9sXnxNv?axQ|7v0t) zo(dItm8U}2M!SoC(G$h}>pB98xV(@Se+^0$b=qD8%&Pu)zT8r5u95mo+@qj*3Y!!m?5ahH2 z^11`#W2lFB25|ojyBC~fH~dz+$N0*vz56ivjj0~y&cb#fm{ltT`8h&Bh>|BR3zj7I z1D0GcnRZ??KSFF#l%MnD25v??(&2liYn=R2ZZ@_ITyl#mT{+ zCHbrPsZw-y0dQx1e=;}Ki=AF7H#zu|BsWQ-6}gV$=)RZv6+xV{#WQoL2Y$+^)y2mJfxoPH%Yi-*_x)IC z_~kxJ=Gl{X%&v^6#>_E!FBo%w5#d9p#QG%boKRrjw{MkLYs2~ zHuB~w+}*JrU??K^0)|4oOJ(cfC$@`byxGV_6Q5BZat^`EaY?L*g4ZAPbh`U%-S(jM zPIrIk4!7UmE4clE`rv)Rw}RHPCB2eefPZGioh$M0@AZk{fbFhVH}O{%^w$a>cKCY5 zHAkvFhernclAN0_5Pp0lAO^(S{kMk$w9Zay4+s4UFAC9c(2XlW84P7H7_J06+A$vb z#3a7}y~o|l^QC}MPBY8Fb%lc6XS+EKCXIoG0MqF0*UISM&r%6LR8hOsALJLf`va&| z>0Cc(PC_aEer_Wx2UmhwW_UWYPL?a8-5%$MP1By~n`}44>;q!VKKxp6YOewHwu?ss z;~*7NIH`20CY3H$8E0mkFu3_E*7?hoDRz5I7~bvm-{S7I3s%2xV}8`m(zR6g6@fK5zE#^RhfWiuwq7}v_iFVE>Gcb-`suJW zTAf2{sLtq({-~e!F^Q7iPyHO)pHetKLA5dky-b0XN$u)IyZ-;xX5m|ooaHyXby^UF zIpvDM{!WKIE}XIVk-z5leE@F9xcr< zCM~BS)xJcN#$z|4HTI)iv8?4+dpdjyFSKl@HXfV)_?UEIY&tX;PWdf#9}e#YnGchm z&f480u)4C*j(d3au|8I)Zq$OGJ0Y;sryi%WN!D{3E}Iwn{q3xL4Sr|p9y5}QTH zdCo0Ba`^+{z>&aIwEg5BH~!u1zp$qO_p{mmoE{hMrO2&Uk`%5LE{RTN&mnqNYOAM5 z^VqYQJ!cA&qqIXJMe^CRB3uxi$euk~{_1g28WmDxvG(jUMl;!SrS@E~j`gjX6TJEO zdGK3|UnPFG;upftEFld)4}OdBtHf^yBGT=fY&DBfvz0Zu{+%@i{&=y_b0##h8-Lf(=!NVfoBeN(b9!7 zp{$bC`+WHSdp?PDW5s-auL zzSKp58-laE8v^fEF2+g}sSxnhrHG&J<+$d+i6HNNxzCY#GGL1A3ugKE1x^M_(Z(MH zY|#y>=%D+RuuCX%p{LTx@{{bMGC8-sAbh*;c3K~a51}l##tVFk;h=P}Y<*46d2K>- zyE4tQ0jvD_8qv!~$SdF&#YEn*cyDe|IaRV=r&$#P0M%T;|2U^V(y^b5naw(ma1*5g%DnB}A7MnY#>C{2cSl&mvMFIV1n% zV&oM1%m#k?bN>&y{}x#sP!3D(BejA%Tniu5TrouJ&!~h9>0{%_7+ALs<5Bxk{H*PK z6&IyDuIm+yjMDzl+;CML#$>oATvNN$xWdsn0V6R4xz1%t7>y*yvja>PaHBF3uY>ux z!p^QqWs}N2tXUuA`n~yrG~WL5fOm?g(-g^G=~ikt-WZ&w)ZTbwV0_fkADUw5={_s2 z6sJni2e6mlTd|?M*PbuniB=~+@F%sGW?1+gSel5outHdIylPE=^*fcVh+-?3Sf)T}{l%)wiF;?ZA9tQ_@_P#W@`$P-iO3K0OfMdZlU_^`$qAA%jIN{lX0grFFJuiNHgY?p19YE zIx|R!LH-mEIW263qO}NKEnpocJGYkBqThoPjBPWtEe)g{(keuwgX?m&hbavjniLH;V7=Z* zX%y)XpmtHOVicR-g#^P{-=T*CXc+S~a<@@$IDw&+}0# zmEfcLjHc(LR@-8fb6c<9e_QVwe`^P1Zo_(Mz21K91Kjteh+bc`6V-`h?UZU?Esffc z)ptx9^4^xttG9>N{^#XYoO=D7W9rB4>^^I9j`poX$8n6oaUIgyC#0u^#-z0mgvt#) z;hpFKKkK<@cqfg6kUt!zwh8YL=($($+q`b&Zf}Eb-%(oq4smBw2eccn6DeA|SuUg(%l*vFE@>gLRgcI;0^U^*46Zq0Pe$p&hLqp$@ax*uyK) zs_fpZ(oua+!>R4ujyU%14gA3jnNzxl#C@J+)0IWW%cS8isIJb#K&0Uh)9qm+&-84rYSYn8X1#A3-)7oK-PDyeaR0Xmf>M7`SwE6TBk4hiGBW_#X?q^_k@kxf^O4X*@rL8D>RG(+ZVm z&&G&xhn{Yn*+}{T?(2-qk4gJ~`?vF)xzh$Iz;smy&H2a>^iPM8eD54RAH{QsBN_18 z5R(De*YkAME=}p5PHtRU7j@uX#M)J$LVn+gld+iT|> zf!rE?hEI{OItqwci6ptG6M92#O#y>3ISCpRdkG&wnR&$|*w7L`DL_{N*X$a}`8l+dya$+TlD;g4hG-rDpiezy(qScHIxHh1!PlYHgDPIaF034BU;29tshJkeGSV6=Ha--!Cj&dFj%hw;R9-B{t z1y&P3DO!_YE9Gu+K(2w?Ed|h(a%zdLWeguDQhfA#ePihvp`-DIxwW~qLXT7^MfhkA zBC-w4H}4#iKP35l=&MbXHJKdvd)AZpWf9+VK^YglplqFA2=G|{#6Z@H?6OrsDfr4+F>CFHc`?4PG;mGuwX?#k zZ1`}CV^aS%_WUY6ce`TtzE=XPLAh?u@tnN7FiZP*iVgxloaH+lH-0M@#C{I7$+{Y? zP1e;=o9Mb6@F=ZCPitXm%}lo;8kF{dp7sGtJ8^zmP^0-lkZ7Jrj}z7hdcItiFDIQZ zH5R;Rr_}vQ^at))KbcUj-@+FO5i>M%LsTfTAr2RjxSQ5v4{ZuJH^wQ@K+ zTMWP6U+Fvx__;J67vIAbp6wy{i6mD7KbLddVWDi@Ch}9Q)B8*;YdwDsqU;nOR@}SV z5uMnur^DgL+QjbIcnYy`TF7BOv>?@|I1n|OhOO8O`KGNhdkL!H?abM^7pn#5P2p*= z75|eI%O35RYR?b1gz0?&^d0cEw4S7dwAapxi}UMR>XL)+usE{O^zKyNZ7ti9gGcnd zQd!Q9)*YOZ$#74MA;fG@ z+1QufxX)+k(KVhs#1QF9le|2}iLPg2rC_=wuA{mn)0r4AVu>-B}K?IO}ec+`V;BW6&@jtOVl&~sel zl-RCey!!&p#A4a$&F>Y*^gA$l-o4ZNA@v*bhIcCP?{3{lo-M6a%N0Qsx9tpW-zgMn z@8P}F!AH0Pca%SPe?xL`!$@xfcd5OLzgW1KcK`X-r-EW6&uVp*f#19N7vh6wtr!2? z|3duCS;Jgw0p5$jok;qPaO7;cxTj;^h za-_Uucn=*ppc5edPKxCBzy>M7Gxp}EuMiuWe61bh5y!+;H~Gf(wDpC`ZHO>vp3~$* z3^AgcntY;uh2C@S{>|;G&`q8p%nb3u6-_={DzyhA%GVBEEtM*Ub~c3Xu{DVI*uhU` zk2t_>YzDqK;KkL1YY10Szw!~=R&hHbv&AqpP0ZC<;L`!Qwu|08NZAtNHgT7=k$7;U z$EL0%3qDV(Z!qr6v(pIJ?<0@=9=zj}(U93A4RAl$j}oN;FRmtBL%53iH8;|Zb*uc` z;E&r?Yv{il#a>BT+-o*3?X{cA&&BT`iGVsS763Pc>K`D(>|%kx{M@d)jJ)(iB0 z*s^oUl_tiaaTc{oic8^Moy$=kQ?_7=$9`@zY2;-MlZnRy;_+VM(fz;hcqYksTzM{u zmQ3?F4Q)4<+AzhVc>;KJ!}m6xc%)X;d1S4aPp$ZE{Ao7Wwnjff&}bJi~XS2!YUb`z6`Bqg~nytUT-eYABc#u7#YM!d+z(|*7y zUDFM|OuEVHhs1W*QLH#cUw#6ZTlpEI<;Rs$5NC2vJ)7H*?@BF8ORXM=dj$R%7%N|+ zbw;BP&WMT!?>e?&&KY*i>i6FDY{x9vMpF^j1@F_!X-a{?hu)rwr~H*mdc}!T?JN63 zce(s472f_V)(x7ihHY4>yTqO6mB-dqz_9;AD*|>?+*m6B#o9ZDFWuh$1|C6EefDkk z`~S9{rqay%TB~V6VK#TA^G9nF(zZtB1?g*)ru9!MEzGg5O$ z+NG!8r(MMz-_SuJ$;2J?jaj`S2aBU8Yjo$Ki|MFHr#|;|&VuYA=|nPVKOh%gE$yU~ zgTBW*Xhe+HSFe=z^~6B)e5_@FhOnm5+D2C)GD{Kcd~}v#g}gf}6)>5Gm3jP1_)9Sg z!#tB~q<^H!b(~jj-v6g^O(@rCU#U1C{rRlM4g)yYpL*uK&@?2rG6)6WWzPA0P|Rgu zHqHl^5xIkiz88{+5yJJ3X zt}B+cc5L%CLZ9XaxWG2((=Rf8djCMPXB&Ey-l*J$9@Vasab7>j%wBP)ByjeA_pk2<$~(LgP?HSwLOxNGuql&|YY+jok)8hkH7 zD;nR!4{%itX>I<%Kyz^eN=KA3prU>?Mcn;d1xkm16s1=fqf5^vD@3jI)eb*;wiLTz zd};4EH@JWVd@P(QeQBchFpV>FXJyJC8sJ?C#BjmV2pou#6=8_**r7=b;yhUAkE7+l zGeiU@VO@r|*=~uJF$nF{BnD?EC1-VX8H3PHO#){Rnw@K-iy4G=Y7&EaNr$r{TFM|! z1{t4pI+sSj0|@iTA`&_=7)yYIia>Nh3d%6QCaCk;=sX=7g7-Et_*XzfjulZ)3YS4o z60T!Wv}e$i_fk{?+L@DJubJ_);|H6Fn}FXuz*pi| zf!{Uwur@N@^fglBjc955fp{J*=xv}(+AG%19hgt7_983) zsNrY^?L>tdx((eKR4!46g-UDQ&JR0AS16IKPvTCo|8D>J>lt_=`fOh)oaQ0S=%>gQv$N;658?HB9AjXN5k=ga2C4B6e^wq|)FdADipA3HW5t9xw6Qy78T z>YnYtx9zcd{$OHo`*2R#fyPICmJWND)QU~!88d_82a{ZD{i``4O4mKy58MNDecuA{tnd_Gr*x0ADs9~|Z86w@A)h;_*jweYE@Oh{uv*wax^XQH>|OGy4vl#A}0 z@h0%j8D=g#Es4RGhG(+~7bcn5T&Fb7GbKvi93~goTyLWs&Iv5Kh2b*j6NC%-Vg)Xf z3rsS#5Uzu$KR67zfbzM;nCr{%TZvx<=k+Ro33JFPvO!z$5kwA2S4bYISe$w81X1H=o{IeAv$sxj+?StWyv>A9$z(fm zMLXxtQboLjE_UNBd7m1A566T((i}U^ITNE3R6ZZk(fOhx8Yjt*%kb#W<1RTH$yY>a zqipVa<+NZA_T1=u4d2qSpEj80%H_SstQ%BApuG1r^R>C===G{pK3$e#*8b)2JiLXk zX>7<5XHSorho0z@4EEEa@vBqt3`hGme2lYMCQaJy8#?~-XKPgN%2NE+s0(pjh-(S1 zCAiMRbsnxBTs^qX!gUs|g}4^tIu+NcxH@rl;+l_ZKCU^q=HNO3*9o{faCP8n$JLIj z8CNr|60Xw9d_=>0=X#4@?pu`kOrO{O(kU0>!mr88jIL508~pgKQti0faW&&=##O>q z+K@RbLw-c&`y9O3=MW$7b4Y(Xg*ZkYC(cB_tV9fuSDO31N#YFgv|T#TC-MEK?q>aQ zw8QhF=|lng;}x{SUSB*yeaWGHMVXK4eIOw=dM-C>5GNw?b6*7oG0vZz67{Lxg+6s5 zekJ(L!_R}?Ec^=bn~I+kzkK|1@SA|213x={X8fdu6J_t5MYA67^GYXA&6HmUT@z@2 z6UQ+p6F3g3Ps1_rz>yYCkfk}|Z0gIwQ~#&EFOO^L+Wy_=oB#pBBo3gc49+9Y6G{@` z0E$LLJE$$-P-jK4!)>huhg-FiV=HQ@)!JIM&RQoLL_1h*n>e&8V5wSDliS;qh-nz} zzUw3i_O`$Gd7sbw=Y8JA&+=r?Yp=cc+G|g1aTN+D*JfH$&6Vw_Q>4Vy2W>9hRnL7$ zy@lgfh|SQSb*2#f-`6zSsTdt1DS|+|VgAOQHm>iM1iYb)R~XXZL%uCd%z*Ex#;^|& z%il!dJ3MhI9^9iW#u!oMyRmEd==bKqBHB(RxhACnzjf7cy0~Z^LQsn<}7mIW6pE1Tr zFB5hQbI;p@5~3uQ{JvHN-4kA7RJq#Dgs&V@?)zHypjeO7gBUJ`b-}3)G@)=j>!y~D z>9zKn=77+1j;h5M9aXtnN7w|`^|~QK{KB4?w6B74KIbTv^Ejn5i)vTBGeUSz-K{`{jR(1)JS2gJ)6QD=*EssyFtj$h< zp2F8XJ`X%TAJnY&_*gtXn`{2*@%b4V#3mu1w`*3&K2$2{8xy2|*5rHQeCtW|YE7QU z=e);fam^Bs&uNd(oSK(CK8HO%Q))i5x#FotQ;f-uFx6PG*uklu7FE`-d<5x(Dyp|2 z>1uwwuZ$6(Ki%!#AZt>CPCZVL-mGH1Nb}qY19X2T`c!lSonmB4EyMd=l}t6fWO@4; zPsuME|6^wYKR)_@l}jC$ph`1Ik%?au`qik}~u_QkhJpT)bDv-KTPOX342 z(BHNA-g9U7NIbg3u%+(SxSqE@ji0w=@d5k6Bk>Dc#?*hg@J#%9>*j)jf(!B6o@cA# z?haZ?y&vNy?VRI&?zSWe($j0O=|sBnBFc%*UpanJX?Ftk($eiTeR%h@`EkP4}*gXr2=fd3kO*d zv?WPX@h(Q-xo$W!>*i}be3EVE3OLDG|8FzHYqv_mNA~%hw1ukg$Sz*8SCgxZT+v(s zFIlR8_?t3YJ}Ps|qcXcvnV>-n(7@k#g36S0`KtOil**!csigYXM|q!-%c}6;vA4d| z^9y&!fx}glOZO%Z;N>l(Al>T+sgE$&x>q}vC`#;1v9XH99s$>&9^A(miyanT+K&Ft zx^%>4yw7 z@lt(VRE&_N+?tF2=DnImo7)Ns!uQTZc`rc6#P24HnV0U@DYpt)RJA*zxNf8Oz^2wEY<8tVG)q z8&fVn*j`Mr@X9mDpT%^>%tkyS*>e3Qn$r~G=A;05wpop_I`%qdSS3bGYKny^*NCZz zwK*y2y2_?bz-eh{Xu=eu&a&^Nr*Xao9lpvGi|M5V(@!w&8T4NOU+9CwJ|FbIoUd78rcw@E z|LIqy6zJ#8hsZf?FuT8Rd%mxGzOR{mCO7Zb>7x(g!g?l-uZi+iyT4WO9(S?FZMYoO zFK@{WzS#5i#Jg{Bhu@DUen@?U_%&KweDh$TmgawYrLKOkLqFQ_O6YkzFBED!m9ehs z2P^a6_SEfsok!BiE!5H&Wzu&28aWKN6QpBxRCCfxN~4OGKCN5sNw>R>G{e49L8;H% zhlCbF`q?haLNqrNY8RF1ES;X>#oZ5=L9<1e-)@_?($A)ZHZ#HZBdaol#z(mLEU1Tj zkI4DEdgTZzi$)1?eO`L8&OQH~x95cNQU@35C>EqsRlIaUZjW#8D`{>)%qfq>406#t z^X+{<#9mmHa)|6I$TLs8a)bc;^sLK6)1)!OpgUI!$>XHRy~B56@8Hh0i@_RcvzrQN zw3{+BPs>9S^Ax=DqwmBlZ|Hk3xzF~p7#5A1#|#!_Efa4O&b$;=$2t?0h$c3(ThB7l zuSMN3nO;O$=&Sq_HNETld8ow2 zo>_XsOjx*E=vJ*;UpAHKrsHe%?R!&S7*Uq&m?^y6jyP+EGdlK&c7Tz1sXJY& zmVbR=UTo%F=$w_~8GgmP*T%Be)DCRnFP?qim%gwyF9vs|QqPr-muuw4xo16L+?Zlv zEw#QHHB!V-Kb!>()06O>UYq)eTJDs=^(0M$f7dqT;O--1YuzQjfD-%kq7oC!5VHC; z^H4bl9=1gu9|tFFw_b2}>^8MAkMQE9=6_1- zSKG#u)<;fz{a#zy?XJOry2mkpP(y7=wQ|?QTH~&}xu%(%iekG{uCH^4+?2Hw2cxb2 z+%EswZcJ{kv#F6Cw=92U2zr~!Uj*-8!i(T1$L zOnOJZ`{B};a7#R4x6Mb1{azsqD@5#nhR!ybg1}Q%oHaoh$EJ%}&=1E#62pE78ppP2 zNk+0F_h&Yy>umH9+qB-8M6VuK8Mt9w|22umpj2f; zx;v)O1XxqBO!U)PW^yfnbC_YI#76phjmP}8G@W}`%yHJ~LR)#AfcfY(*6Uhna>P}$ z31w5A-Zr0tR1;x0zQt4T%QYj=5HP@(RT7srTOQI>!Grsc41I1=Hw<(nS z6U{xmbPw;c1H`@NNX)?3J>fUybqvOC9fiGzen4#rc{J&mZE2PdTT9<=Pk7djIbBXkKuUv`dh zC>Ne{gm5^MlX9KO4h3AgD2z)Nt$t@aHFh!NoTEcJ4_$)flkHSHc1N9ajLGJu4B6)? z=P3JH?wsQz_@u}_I_F5oUc~7JAC2rII@9dEvd=l*OJ9ce5Tp^#1bcR$bB@@Bkfr1p z1Dr|ro(s?0IgW?^e=4bmbF_U($a#A>d?I9@80f)W3QStL^vH!tNj0gC0<7`>k^7$3 zM|`3T_5muFPUm6oT_bjs+Ix{kcF23Ebqc-;SZ>f`eacHN*^&S++3LyW46NPD_TCAv zk5GbI1Gj6GqgVPl`>;N|bgP~NhvlW4(EX#N^{_w z!%OGtS+7fwr66M`dRK4=KZS5Xdfur(Z0e618M}GFjxaa|oap-rV)1y_*;xMeNBLer zzVFswHoMEdfU>v9cwPjaq(_FA)*~0f@1KxxE}AK))vksX_JV7ftFeU_qxQV?4_9Lg z&ysy|P`8E_o+A6qa5c8@ld{jVuErJ~EBj1vHMFp|jKOGEV+#+LV-CGtAZ4 z!rf(`zH+aHu4mMlWcFL0mg?mBwnn`&%{j*~5)v^^la9J~)NmSn48OiMh!W>5z=kyI zHQICtBPGN5Rx59b$L%lU3yCNBUZPRxHNph?)D_+P^mNj=v$sM>3%`K+IX^@h+UP=SnG@*@=@72Zl>>+nMokl;oR7dS{-kys7 zdcIB&{VM2udN1XcOMo16F9O2EoFbCT1hI-*5_=P=LZz9*nn4gHb7OuV!ZIAfa}dsG zZ6Sz1n+eZglzbcY*lOf@sSMy*2`uI+)*LA=4)Qq%+hY67d@t-8I_~y6Z*M7liMVdp zCAbVo<^Kq$i&)*#3il{5xt{BmKT~PloBZ0r_qDX!p?>h1KFx7Q&gp$^$1-q}2g&(r zhkjvaDaZ$PLN6SRnj7W%QJPnciS`5y*Xf*n0K(!?3$l#COGE3(-|gGKE-UNV3gkky z@AtlTX*u?#bWh*ZSq z(wt~#kLrH5cBEa|r^K-`o5tQL*dlXN;@Bg9UOG^lm30HHf2dC9SOHEOy-<(1`++&E z14}z*Vi`CR1Y2pcU}8l%ftxCiBjl7Sx)Q>z0nzX zGr2_@VoaCQyddL2sTacf9rA~Kn3eS|>iU9qmDwF8xBeCDLMY&T6eB4~48NN9)Yv zwtr- z{mwbAU_DKBTPvSl&>Fu`tD)aMtkXHiyPh!<7H$kA^VPwt zKEGeRyXgF(qeX@PjvDdlxNUmf()Azt3Zx91Cmj(Ait7=61kahnC3~d6NwejexqHvyTGGVMY3+|AewZ2$Pz!N2vs(1csKuf!I{mDpOTP*3bNjO{V5nv<3#2IG~{xYh}9YoYsx^&DJIb@sDy ze(DE>%kbXGvYJI;S1|k#*Ws*9ztDse?&Y|7wq}p%DYP8D30cH-D7L%!ajn;U@{JrS znW*%Ta;_VbKGWmQhzS_ zND-T_4Jcc)r`)M7=B=wib(~(e^-GwVRBd876YR4rWZQV;z@QT_d09~5n%!LV@^GAV zM{s>{g4wmoI5II{{ko)-n}G$*_NlgTHqQT(&AwJ%xR^NQ6QPi^p5qEcW_{g1V5`nj z;`d?r)-c6JVV!bAsgp72RIl?X6t*$im*BdV{!hJayG(g^fB3cLQE%Hqy-m5*-=^?a z6e#-^Bnj((#=f~?-FK#PXaBXA?orRR%44)Cr}#p)4aR!JSLPm|@e5kYJcPmC9&rJ8 zIfvy~+2-aZqU&n3==jOMwPUfP}@QP5BME!wl-1b1HYR5--nE?Bx}N~cd^|&pLWEH?Rs7?aG>xbtfw_ z+o#Z5@?ins#!J?o)LCbyLYX~H3_(G zhIKAFwR@);@%EB^x9Ru!y}Pu(m`>uH;8=NlIBGBer^0&`)-SxM*6unkl`Vp4VV8`- z<{T$2miIE;VL8<$;zg0HzfJ#@U%g9v2e)*vH|fQRFMuDrIpMR_`?Y_VUNaNk#rD_q zL-!#L=sb8oClc3o_li-~#}G>Zch?v}k2D^8B7U1^fYQa_zhv)>lLl2&9?Ej0_N@dz z4FWd3tJ9L4CSeP7rGScl+o)}@`xi4!E-$T=MGoCZ{bcZ`oVXaJQJNOj`*0UX*y{gS z8WuAWmNngN-^%=kSmYTK%UR+6E#bb~z`J^c#rbaJPp{dNFJ1}r-9j9RT0Lwi>*_T6 zuHSW!88*KPeUZ_{zpxIk{DQF9pUjbB;a;3cSXV1JsY87tdiJ_|`QqF6s1KYm6Mmey z%nbW~Gk7ufl0Rx)jCLx98#Pa2@}42xpOAE0MM!uFD-Rxlj7Ot!y(rw|q-vbOFEEmv z=H~uS)zEJmDIDzgx}_Xy3HLZit%>(YIcuxj<3(N5Amyy~_zbFX@4!O-^Z4|t8RSXz zVpZT)l6+YAq4G%--2|w}b@zrgupCJH{BBEYoD^C^t>KnWp7!MAEAN#;uYOfWIY)Vx zlI6ZyxnH@lOq5UQ-Svs9qPo&=w}jKk1@BZh_h8jcz7GL8OU}ccE?Q1^8}y_7@g>*3 zpE&f!FT<_dy05wS%fu0{)*pKEPTQ|WT+2QS`KMd_N6z4okdXZNR9XJ{0`iYD32Okz z(aLE^`q@$7JlPMPR9wGR8*gAcVIOf6v9ad>ag;JeF>d? zNz^&}1`YH)%RYPS)ea83P)10E@5w$p;6wXn$D=r`^(a+Ay=NyT9eTKBpS7?OABlaw zCGc5OuR+Ta=UfT9mb7=pNqX$9kk2BlA!G5Kk1y>Ca?-52dDyAqqy>**IFlY)qJ(bEH5%{>A`~?(J>M z!#ZH?bFgSCh0CjA+Ck)`w)Nx_jP<3vek~r=FW6H*-c!H&S`OS7{l1notWy5fp7qbq z2M^l>6>n1nrWh(Aw_YFbw}Bg`*Z{dzF&ne|zf?Ue|61ZB`mP&K`qK)&g+5m0#%ZE* z^PPlXE9b{s&j~&o+FhO2dd?QsaYtf+twPCLS9tqX#LiR-`{kX6-%?J5T3rJ}TBk@*EiUnB-Y=8u<4s=LS+e)DQa0 zlII$ZB+u56JWC$x7nMM^d>wCn({`80k|(}47mqO6|A7hEb`2`$x-#i~J>S(26r{2n z%EZ1EPg3q_oPjTbO)k32@e=M0FzExmvH)>qX)_Jd=3q#hYyLypyqq8ONZP!UAFw&? z6E506tf{m)F42Ge`lR@qsx5=}`E3o}%|qUtQ{ZP6e6J*;O_=|dZ$u8#roy_~S7%wS zyd37eQCRD>-Ysp8tW}`bT!7>mRqDNsbyQF*c4+J$Z-KhhKbFXsj^lj3=*&@c)N7)RgrJhZ;kI zjMG_Sx(_kSl-t95S_`KPGUc){HxdV`sf#>G($Qoy>$vwG-qriZn1y#pZk&|wv!#oe z4yp0=TH3{Q9ATplK>IKx!uMe< z9Wq)Cl`g`E(%-K+gFVfEn;`!kG>JbsyDVd!%bk%2sRtI@Z|X@V{81mgmvzF7?L{)+ z8LUIPV&(c2^rLhAIq7Tcy%3*0Q@s-sy|6^5;=QBV`=(Qn>du#E z?M8d{j}P;aZF6G1ZhpS>6FM*&08@ZqG?!)#H=gu{nyZ_TBna)=P5E@&A!C|0riq+yZ6R z6s%(6%mU6wgm-+lEN5B!ltX>iw+<(H?e@vEJ6{8 zUVw0=E&%8x$OFL0Qclpvp|+Q4;O z13t7hS9QexgqQZd(S3@~q<)_K7CP4+V!gvkJKGBPCv=K4_T&JO%D7}6 zAfCbr4eK3T$~x}B?rQTM&~n!4ysf|DBXvuw(!2Z$aU;s-o*DPJk}zZXC0V?^a4Ym> z)>COXC59PT$LnSt&VDnX9m&V4@Y@FaLGJsRyr|X&)6Hg$#$wDVw$-cI!yHx|ME9#% zBy@qwtJ$v{PSS#jKhQFx=Y3;Bb6HX+`P>hh_ zEt#4WV{8*n>0Z~~Eo0qF4AD}(HX3?e@pkLU`(>fF0YTw6(@^#{?bR~M)qT?ndU&fs zJ-K$2bG;&;Z!>AGydQDNJg{FwPO&28g<13lJ@g= zap+$f$lEv%|3IezO@d45B#+_#HtTYY&bJm5;Jjop&Zrj4C$9N)@AaJHr>XDZ=J*br zoF`@$+trD%1J*Vd;p~I zRq!#%K0i3Mj`=v>J_VnzWuI@IiH?rQqgghLHp@QeJ*VP(;B(wXeDt()q&+I?qN7DR zolA4l5vR^R2WjRbmz{E&JVXfHMj>GPdln0dlyF=>%23TNmGT%0(;*_knEwu|-J z=Q*){4yOimw^box9{1cSz?hUzXJNAsCj{}8Qx9a|7WV|tE$(-52Cop?dG2uchHH2k z^61PYwVaAcL-EyvqLE^|3N>=?kMcQb2xv}c`Q1@gcQdund3zh-J#F(c>}#g;NZ$_W z^3o|CCq>IQ0GQMgSQEv*qtkTYihjc`I`lb0XRNc}*AjdHcR-NZg;V>ba_T!~^cOXa zFZuj9i9@gXS3q7|%O2t2M(v0jJzs3k^XjPa!j5HQtt)VP2)b8=9b&!O5a00b1IsEo zMbzJ_uQ2)i-_e9hU(4}V0UVD*Yu4D*}91ZhY+y;)zNqe<#o6Wy^}$mu3QN44X^Lo7dHXVV=TI~TFcpt=4Bzc zg)@l8Vc(6~4rPha(cTA{12qMldZQ+b?&`D|O&~}H?bnyQc z^})SL;&9s7qqOsk*K(ZvipRjAPE=RC=wj3!YKLCHO=CgUSq+JNL_S`}s8S56+L7&` zS1n(NNHHX6U)QSb?eaq)FUI5_sa|eBRGlwv$L*jJTYFxy9VceZAZN07Mfdvsi1ln9 za>fg?>3;?9R#)5NWTn``3c1iE{XVo+;ylDAnJehtRVsxV+(pF`Fwa+1-5?9_WGZcH_9 zP{{EaY^E$g?>u2Ze^Nu&{0Y{z(%AF9poYeR`l4UG)v$;6-~+3`$-D&pHy`~O+ENY6 z(cfc_=`0%Pn@RB6Xz_y0^|clrubjr?KG_85rpmKSo1ABvKAB0k^*YP=@mH-ACY&(L z)2hmQB`hoxMqtC3@GKR18bwJz3lohjSa7Ossr&Wq1x-g)0)7F zUA9QCK*Zv@!N0bPAq{#ZD6BXv-Fjys#%hw!HBch3%*IqpF`njIISv}y+PAp^UesQ7 zB~_VeiDf!VoQifibe6<%%^vE5^wJhR=&Dm1GA-Dp$4fDdRgtc-cyX~snU*w_TBAWe z&^Xziu)J?tCo$YT2TzJbt2|H|BKz&M`3pyEk-X}rs;{z~hfG&uQ}JB2N{XuHZK?|R z@Yf9`wn!BRcO*1Tml>d$h+C_^+j@tALup+TVv82won`yDh?}bZfn^F?bH#b&7+H-I z^=kfs8oD~7sud5Q83n5U{QFFikgp~3@rjIRnx_wL9dA|YW`5Kh%;~x z^&zoEMC&A}UZbhZ;XrW~TSWP{mh+)9A`EmAGSf*O(l!M>s!NGnSLxP zCmB7k61K~2eHF-qPA9mr;KhFx9*pv+&r_Tch@(X--sW_cJ^((ay`dRS-Zn^ix_l`s zJtuiRN@#8%x4Vq2#e{DZ@p7aERy@5WMCmBiucFb7o}0v9bN5!A2eVAey2$oRH~ z2utXMjTTkVCIFLeIeR2x9C=4s($ZrrX&Jy|K$uJ~4cd)vVh%QLui?KVJb$j?fAPi) zRZ%1S0=M_iHNq3yP|q;K7>Nt~(B@Jchjzbd57mnmmoqJ60_SN&tGBn-@@169G9g`O z`65znd3LPM@?Ec^wmQ`+!W&VU_v)H+#FVz_Em zd1)+)^qeBX4HyJ+aqPifeRJEupj-4(6x7W@&t!_oxB=+HZ5sNp7sCj3_hTNmnSK8mcIP) z*3+$mm;1L4ulOMy_Bd|k1E04FfzgKJt)Ca^-MuI7pZq8PjsLd4@h@W&EZ%`(cq!xs z%vwILvv{|}?FeWu7?+EaY>dB%h+-3QVt*4PGMV#$!fD6N+rvyQZ)(i}@s)M^$uHX6*e~)bzt|6#BCj&w0D6K~UZr(^Guj7;!;25h;kc*n z`QnB3x0szV3(tjhf&_3K`qjqB9YlJSih7xfcq%W?+O!G}hGalKPZn3jY)vil3*E|0Y0rGDJV>qg5)uljP{82!uxclR?0FF>H2WX?3CYO zTSY<#!;yz9qRdu5Ip7AyCbU`=^J$i`Ifuam)z;+<{706xLL|K|$`ooFyyy(c|5%4< zh~rttjl)e7;`gfHY85z>Ts~3|W;)B27_u)#V*!{w0DXl^m~*FO_)t&j*AA^)uU1#8 zAdp^dXmbHfzq7l}kCG#xNbMq`Qb7x~bG@EkS8anl?;c}Qpoubx2 z;+v!m@4gDN7-mMDx)R6k(2-B{AlhK2qT*^*n>rv&X=!C1b~F!xGLIjOwri_l%qmth^0+;L7#oh8;7bT?DEl z_3fCsQAWa4VWhcRX~3#Ad98&Dija4hFuOy`t{UqjwcH-fY-~}S0h+3S3)Ldw5jBzD zl$J=19H(-kmiH!V#!yb`NpT2w#^f!eSiP4w8c@V?DUb2EYPiYslc7 zN(~Fis9#h&vg$Y$BO^G$k{+_XhUvH|`W4e(E8ux1{_4XeW3 ztK!}^t30(0Gf;i~jIoFnX6S?eubWVF>;X~fgm){F7j;T;9ex9J&C!okL7Yj8`=yjt zFpUD0l%n!cy2i2R{zYT*ujxF?xWg*&MCnvsXHiEE0-a%R%@PulU(&@#{y(Mdrbo0@f<}3juO1*OL^@>9+zDi?2+B zd%n4m?%$a3Tboxo`2boWA+Iv-Kqh4Azn{C*pjgxK9fG-QoFxM@8I8uL42P`(TV?pV z)nM3D`#A@kOXj`A4|r3iMcu>8L|ox6ertOC++==IirJ#e9E5r4!lQX9=>NjJbonpl zrLX@qFR3w))a!z-=%hld;+stgz^ugNSt%Gj@6R(*Gh4RY54}tX{nMc$e(Rt9{ zL95S9gBxJt#EDGS$3z?WD+KxBHIK~@L`(a(CCK0&R)2=L_c6FL>)kB zTzCV>NaGvpiystU&A15q>hT@mN!MP1dxxIik@zj^^rrX>YXkYqaM_rXe~+ek;L3q0 zi|nMS22<{j|LGrhVq$W8kWICQ_#Q7gK<^H2{J$X(c(PzlA=fj~^Hp40hBBfpa+n@Y&VH)C;b&r-W~n~UEpp44S7>m-T*4k3*ZCr1yH#ZM*vXRpWT|2 zaT$>r<2B>PM~)q*OCF~gJvwzva%3c4Lm;53mmDc6(H$@@NvqS1XBmsL7cHJXEiz}( zf*Fgl=gpfne@1{GTkyj4MY*$Ho<20P<1{$OP0yZ&Uy)P(v3PoJ5T!47r4EFB>vus^?9*JcHqBHrTZ3ypP%RRcIE7x0lTK&-??d8Vc%7yfgheI`$xO` z*D6-sxcqMSwBx=-OAamd>3PDuuB~D1wBXO$+9MCnPFZ;J!7a__D_*^Nv$geZ`MmUF zS1Z3-d1d(%o9BiW@18U5<*F%l|GF@Jjczj6{Kj1GsZ)msRX+?+zWH_J{9(@q&q}+i z$-1^^;fx)oyFy&@RmG^fl>wLM9P`^%z5CdJxtkAbf4FeER9$su-<`SF`#wMUr=;%# zekgl-xM}ac*c+XOvRmo;^dG-&nQb&2t2`PNbN=!RMv^RV?VO-M;UHZ4UhTbinMqp2O!U-<>;c9XEOEy~^}CbEag^jkq2= zedQQ7#s1qS@42t+;@X_8R4#k+e9*%$ZycOH_WozhEGIsHeaWhmwLi5jpOV`1W{U?) zuDmfl?P|?a*@s7emws&MVs>Wd?by>-HM@Qq`QxVR!{?nheOOcZ!6$nBQMq zHRDs`iL9HsJr#++v=#bgrupr;uq2>7ZlTxMJsQ4qaIpX9|BO^!=y+`AlSfuAi1fYs z+{yRvW`7r0b?e#97jATo-fTR0boY;6wHkip>HL7By@pLL`s~xWr-~z&pZM+g5yKYM z?c>6h%ZC;ZNxo(|@Z#n7T68K^EN@ws+suFJofX5TZ5%OsUcl~&vtRcAKJe~)F5eBE z_cOmkg+8w)ZU~Yt?^M1v)6TW4FY%uB%#&08xHx0Fe&N8m;b!kS^IvFlwZ5YJmDLkp zz8QRJWciE*Kb@?q`u+2_5qW zx%aX7Q3DUB-0U83J*|!30mn#TVAjhD&AH#Rewy&pjNQM#HNVe4KA$DNaU}a<>*dd# z*?xIJ$APzJj@$I2>XMM`fBIxgKDu`&uL++IJM~2u|Dwa|Cm!vtn0;jO$F3hs`h0IZ z_Ilxs9&PvEnsl&a+SX3?ssGxxbN2Io8|Lw!c>8XP9~fv|Im2gB=#$KA*+|2t<}aVP zy}$dRR|dB^uG;$6<@EudU;E{=-^-Rn{Z#6I_41W}YHwe)IggajoWJ~L`)^x*o zfFH*%SBxn+A`HpyG~?qxT4otXC(lYPeR2MXk+V(v%O?JC<2nDI)Y7o)gEID?`Q(ej z)3@@zKb(Bubu2c*UR1QE8@zw~w(FC(#v5kbi0Sq6b4N~$ z%s$Vznfc7d?hCpN`rQBM2XCp)wfV_w;+wzoJ&6~}lLh!d(Jye_Wy*N~6X2ISO!@r3 z-E)b|C_MiWf1C9;{_CJ!1f2Ol{tE8H|8ZZLCD;9n{Jlc_n>Pef?u?D5eB55%KEz-> ze?QCd8(hq<;a7fReA&y_Q>iHHqkJCoU-vipaERZKXTz7O(*z$?KtMwXW78imw_&Ej zzTD&G1_ip){28AH|3i<*f0WN(;X@P}&=^0oSu@JJm0UpEMt^c6%p2y^@6{%u3MATD9z_Wuo9r>62bAR`^tKx4@?;V}j{pC2f z-jw{fqKneYt9)`i?sajw3l}XWe6n+A&3_JG(osQrRhHanrml$!SHC>FJ$^^4PuF#X zyQ_Mr*aLpO)svI^z`w70+noLg8=x+Idl15hsM{PJia2rViPwiCUc5SOsTy%L>bb#M z#Mi3d*pYxViRyj*laMY+eep{XX_M8~r&5qURlU4w2TL3?pVfA4!AwtfX65~18l|+D z#T9H~8eCGCnqJRN-`dMQ%l?85o!^079<61m-WAN((u+l`H!*A5de-$&1p9Tw$L!&N zWi0V@FShOe3U;(p4$~~nWIwDM!ZMZ*VcRN)u-7wJur5_a%-MbzyXAV91#R|XA-#WR zeiL73^V-j2-!C1=d@pupqV6+R_*^{eX~|@#IzP{Tv3|vdzhYy54Dn&>$E{&Cb1ba= zp-iTH=1mqWJi%V6#Zm9xIV|$b_iSM07Ix>8w(QyLbxhgj9$Q&3oo#QP$=+1YWO|sR z>YO_omu~y8Z=PtuF6_=_uiVaJbKWRsEa*Z!3rbb9i|?rMTg@_R@Vljk{nlFpe+}z1 zMZ+>)(XgRwG>D^NlXoKQfQBtSgYXL)w*4C7+}5y?e!z8|tTJ%Y(JZN6VVG z)w0PkTDGgJ7I|vfz=2w}G)~LD(rS^vb_e=G6<|4FK41(W5kTD^-Hz1)aEpOG2`~Y$ zjluc@$^pfIQot0zCO`oo4v+v?3(x@S0qKCLfW3fQfYX340NH@g0385S_E3NpFdA?f zPyry>G8NDZfCD^Pwj?~(10n#Fe_H^ycx3k>dQ@i9`GEX5ReHV zTJ;1x51=%s0AB%!PQL(bfL8#+0X_h#=O2JIfN=n#FXb@@Py?VmiME8(n}BBk#N?g; z2!L1s;ZX~qd@0>tfCM1C&j2C;TL45isuQ)_CxANuqA~S{X94#BZ2*)%SfJdmR^m%I zGzV-4%mk2*Zaq$Rz^qWOz9KKoUmtGo1?&WPHBBMI8oo~4lq^yX{2%^{UD_z0 L{14Iop9%V3m=C Date: Fri, 13 May 2011 11:20:53 +0300 Subject: [PATCH 14/43] OP-483: add install target for firmware make INSTALL_DIR=dir INSTALL_PFX=pfx INSTALL_SFX=sfx install installs binary file into specified install directory adding optional prefix and/or suffix. --- flight/AHRS/Makefile | 12 ++++++++++-- flight/CopterControl/Makefile | 12 ++++++++++-- flight/INS/Makefile | 12 ++++++++++-- flight/OpenPilot/Makefile | 12 ++++++++++-- flight/PipXtreme/Makefile | 11 ++++++++++- make/firmware-defs.mk | 2 ++ 6 files changed, 52 insertions(+), 9 deletions(-) diff --git a/flight/AHRS/Makefile b/flight/AHRS/Makefile index 4b0a6417b..2e4e0ff6b 100644 --- a/flight/AHRS/Makefile +++ b/flight/AHRS/Makefile @@ -399,6 +399,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -434,6 +443,5 @@ else -include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) endif - # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index f499d549a..e7607af74 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -591,6 +591,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -630,5 +639,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program gencode - +.PHONY : all build clean clean_list program gencode install diff --git a/flight/INS/Makefile b/flight/INS/Makefile index 8e0423a45..5ef6adb86 100644 --- a/flight/INS/Makefile +++ b/flight/INS/Makefile @@ -416,6 +416,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -450,6 +459,5 @@ else -include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) endif - # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile index 8bb3ed27c..548e6d188 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/OpenPilot/Makefile @@ -570,6 +570,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -609,5 +618,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program gencode - +.PHONY : all build clean clean_list program gencode install diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 21d1c3d5a..876678a32 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -439,6 +439,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -476,4 +485,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index f42211c4c..eee2d6e9c 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -10,6 +10,7 @@ OBJDUMP = $(TCHAIN_PREFIX)objdump SIZE = $(TCHAIN_PREFIX)size NM = $(TCHAIN_PREFIX)nm STRIP = $(TCHAIN_PREFIX)strip +INSTALL = install THUMB = -mthumb @@ -43,6 +44,7 @@ MSG_CLEANING := ${quote} CLEAN ${quote} MSG_ASMFROMC := ${quote} AS(C) ${quote} MSG_ASMFROMC_ARM := ${quote} AS(C)-ARM ${quote} MSG_PYMITEINIT := ${quote} PY ${quote} +MSG_INSTALLING := ${quote} INSTALL ${quote} toprel = $(subst $(realpath $(TOP))/,,$(abspath $(1))) From 45c609100a460078ebd6052c81fdaecea59bf67c Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 May 2011 11:22:04 +0300 Subject: [PATCH 15/43] OP-483: add install target for bootloaders --- flight/Bootloaders/AHRS/Makefile | 11 ++++++++++- flight/Bootloaders/CopterControl/Makefile | 19 ++++++++++++++----- flight/Bootloaders/OpenPilot/Makefile | 11 ++++++++++- flight/Bootloaders/PipXtreme/Makefile | 12 ++++++++++-- 4 files changed, 44 insertions(+), 9 deletions(-) diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/AHRS/Makefile index 24512a5b5..0c8b23882 100644 --- a/flight/Bootloaders/AHRS/Makefile +++ b/flight/Bootloaders/AHRS/Makefile @@ -389,6 +389,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -426,4 +435,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index 7c7d8e812..74b55cb17 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -428,10 +428,6 @@ $(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) # Compile: create assembler files from C source files. ARM only $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin .PHONY: elf lss sym hex bin bino @@ -447,6 +443,19 @@ $(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) .PHONY: size size: $(OUTDIR)/$(TARGET).elf_size +# Generate Doxygen documents +docs: + doxygen $(DOXYGENDIR)/doxygen.cfg + +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -484,4 +493,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile index fe9454f5f..292291609 100644 --- a/flight/Bootloaders/OpenPilot/Makefile +++ b/flight/Bootloaders/OpenPilot/Makefile @@ -450,6 +450,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -487,4 +496,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index 32b889e3d..1610ad603 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -446,6 +446,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: clean_list @@ -483,5 +492,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program - +.PHONY : all build clean clean_list program install From a7833e0120d4d9d818279a2e4f61779b8d480906 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 May 2011 11:22:35 +0300 Subject: [PATCH 16/43] OP-483: add install target for bootloader updater --- flight/Bootloaders/BootloaderUpdater/Makefile | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/flight/Bootloaders/BootloaderUpdater/Makefile b/flight/Bootloaders/BootloaderUpdater/Makefile index 5f48d327f..17839daac 100644 --- a/flight/Bootloaders/BootloaderUpdater/Makefile +++ b/flight/Bootloaders/BootloaderUpdater/Makefile @@ -410,6 +410,15 @@ size: $(OUTDIR)/$(TARGET).elf_size docs: doxygen $(DOXYGENDIR)/doxygen.cfg +# Install: install binary file with prefix/suffix into install directory +install: $(OUTDIR)/$(TARGET).bin +ifneq ($(INSTALL_DIR),) + @echo $(MSG_INSTALLING) $(call toprel, $<) + $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin +else + $(error INSTALL_DIR must be specified for $@) +endif + # Target: clean project. clean: begin clean_list finished end @@ -430,7 +439,6 @@ clean_list : $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) $(V1) $(REMOVE) $(CPPSRCARM:.cpp=.s) - # Create output files directory # all known MS Windows OS define the ComSpec environment variable ifdef ComSpec @@ -447,4 +455,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list program +.PHONY : all build clean clean_list program install From c9fdbd580bc9397102e13806ec8ee6e1d8f9bdeb Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 May 2011 11:47:05 +0300 Subject: [PATCH 17/43] OP-483: initial Makefile, no support for ground and git version info This Makefile should support parallel builds (-j) as much as possible (not an easy task, though). --- release/Makefile | 112 +++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 112 insertions(+) create mode 100644 release/Makefile diff --git a/release/Makefile b/release/Makefile new file mode 100644 index 000000000..0b64856c2 --- /dev/null +++ b/release/Makefile @@ -0,0 +1,112 @@ +# Set up a default goal +.DEFAULT_GOAL := help + +# Locate the root of the tree +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +ROOT_DIR := $(realpath $(WHEREAMI)/../) + +# Set up some macros +BUILD_DIR := $(ROOT_DIR)/build +RELEASE_DATE := $(shell date +%Y%m%d) +RELEASE_TAG := unreleased +RELEASE_LBL := $(RELEASE_DATE)-$(RELEASE_TAG) +RELEASE_DIR := $(BUILD_DIR)/release-$(RELEASE_LBL) +FW_DIR := $(RELEASE_DIR)/firmware-$(RELEASE_LBL) +BL_DIR := $(FW_DIR)/bootloaders +BLUPD_DIR := $(FW_DIR)/bootloader_updaters + +# Setup targets +FW_TARGETS_COMMON := ahrs pipxtreme +FW_TARGETS_INPUT := coptercontrol openpilot +FW_TARGETS := $(FW_TARGETS_COMMON) $(FW_TARGETS_INPUT) +BL_TARGETS := $(addprefix bl_, $(FW_TARGETS)) +BLUPD_TARGETS := $(addprefix blupd_, $(FW_TARGETS)) + +help: + @echo + @echo " This Makefile is known to work on Linux and Mac in a standard shell environment." + @echo " It also works on Windows by following the instructions in ../make/winx86/README.txt." + @echo + @echo " Here is a summary of the available targets:" + @echo + @echo " [Release build and packaging]" + @echo " release - Build and package the OpenPilot release" + @echo + @echo " Notes:" + @echo " - the build directory will be removed first on every run" + @echo " - release packages will be placed in $(RELEASE_DIR)" + @echo + +# Clean and create release directories +# Use dependence on uavobjects to make sure the build directory exists +uavobjects: all_clean + $(V1) $(MAKE) -C $(ROOT_DIR) $@ + +all_clean: + $(V1) $(MAKE) -C $(ROOT_DIR) $@ + +# Install template: +# $1 = target +# $2 = dependencies +# $3 = install directory (must be defined) +# $4 = installed file name prefix (optional) +# $5 = installed file name suffix (optional) +# $6 = extra make options (for instance, USE_SPEKTRUM=YES) +# $7 = optional target suffix (for instance, clean, if target must be cleaned first) +# $8 = list of targets to install (without _install suffix) +# $9 = inner make target (usually install, but can be other to just build) +define INSTALL_TEMPLATE +$(1): $(2) +ifneq ($(7),) + $$(V1) +$(MAKE) -C $(ROOT_DIR) $(6) $(addsuffix _$(7), $(8)) +endif + $$(V1) +$(MAKE) -C $(ROOT_DIR) INSTALL_DIR=$(3) INSTALL_PFX=$(4) INSTALL_SFX=$(5) $(6) $(addsuffix _$(9), $(8)) +.PHONY: $(1) +endef + +# Firmware for different input drivers +$(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(RELEASE_LBL),,,$(FW_TARGETS_COMMON),install)) +$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(RELEASE_LBL),,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects fw_pwm,$(FW_DIR),,-spektrum-$(RELEASE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects fw_spektrum,$(FW_DIR),,-ppm-$(RELEASE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install)) + +# Bootloaders (change 'bin' to 'install' to install bootloaders too) +$(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(RELEASE_LBL),,,$(BL_TARGETS),bin)) + +# Bootloader Updaters +$(eval $(call INSTALL_TEMPLATE,blupd_coptercontrol,all_bl,$(BLUPD_DIR),CopterControl_,-$(RELEASE_LBL),,,blupd_coptercontrol,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_ahrs,all_bl,$(BLUPD_DIR),AHRS_,-$(RELEASE_LBL),,,blupd_ahrs,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_openpilot,all_bl,$(BLUPD_DIR),OpenPilot_,-$(RELEASE_LBL),,,blupd_openpilot,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_pipxtreme,all_bl,$(BLUPD_DIR),PipXtreme_,-$(RELEASE_LBL),,,blupd_pipxtreme,install)) + +# Order-only dependencies +# They are bit complicated to support parallel (-j) builds and to +# create the pwm/ppm/spektrum targets in a sequence of build steps + +release: | release_flight release_ground + +release_flight: | release_fw release_blupd + +release_fw: | fw_common fw_pwm fw_spektrum # fw_ppm + +release_blupd: | $(BLUPD_TARGETS) + +release_ground: + +.PHONY: help uavobjects all_clean release release_flight release_fw release_blupd release_ground + +# Decide on a verbosity level based on the V= parameter +export AT := @ + +ifndef V +export V0 := +export V1 := $(AT) +else ifeq ($(V), 0) +export V0 := $(AT) +export V1 := $(AT) +else ifeq ($(V), 1) +endif + +ifneq ($(V),1) +MAKEFLAGS += --no-print-directory +endif From dbf8a77a948e09d24d8f52c3c2904075c16df574 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Fri, 13 May 2011 07:24:44 -0500 Subject: [PATCH 18/43] Now there are other attitude settings (like rotation angle) make sure these are loaded right away at power up --- flight/Modules/Attitude/attitude.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 599c66b1b..986fc74f3 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -143,6 +143,8 @@ static void AttitudeTask(void *parameters) FlightStatusGet(&flightStatus); if(xTaskGetTickCount() < 10000) { + // Force settings update to make sure rotation loaded + settingsUpdatedCb(AttitudeSettingsHandle()); // For first 5 seconds use accels to get gyro bias accelKp = 1; // Decrease the rate of gyro learning during init From 405cac36ad147e430495c8fa1368573b5c1f1e97 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 May 2011 16:55:18 +0300 Subject: [PATCH 19/43] OP-483: add some platform-specific hooks for ground packaging --- release/Makefile | 27 ++++++++++++++++++++++++--- release/Makefile.linux | 10 ++++++++++ release/Makefile.osx | 10 ++++++++++ release/Makefile.win32 | 11 +++++++++++ 4 files changed, 55 insertions(+), 3 deletions(-) create mode 100644 release/Makefile.linux create mode 100644 release/Makefile.osx create mode 100644 release/Makefile.win32 diff --git a/release/Makefile b/release/Makefile index 0b64856c2..144a0a5dc 100644 --- a/release/Makefile +++ b/release/Makefile @@ -1,6 +1,16 @@ # Set up a default goal .DEFAULT_GOAL := help +# Tried the best to support parallel (-j) builds. But since this Makefile +# uses other Makefiles to build few targets which in turn have similar +# dependencies on uavobjects and other generated files, it is difficult +# to support parallel builds perfectly. +# +# Looks like it works for -j8, but fails for -j (unlimited jobs). +# So probably not a bad idea is to build release in single thread. +# +#.NOTPARALLEL: + # Locate the root of the tree WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) ROOT_DIR := $(realpath $(WHEREAMI)/../) @@ -37,8 +47,7 @@ help: @echo " - release packages will be placed in $(RELEASE_DIR)" @echo -# Clean and create release directories -# Use dependence on uavobjects to make sure the build directory exists +# Clean and build uavobjects since all parts depend on them uavobjects: all_clean $(V1) $(MAKE) -C $(ROOT_DIR) $@ @@ -91,7 +100,7 @@ release_fw: | fw_common fw_pwm fw_spektrum # fw_ppm release_blupd: | $(BLUPD_TARGETS) -release_ground: +release_ground: | ground_package .PHONY: help uavobjects all_clean release release_flight release_fw release_blupd release_ground @@ -110,3 +119,15 @@ endif ifneq ($(V),1) MAKEFLAGS += --no-print-directory endif + +# Platform-dependent stuff +PLATFORM := win32 +UNAME := $(shell uname) +ifeq ($(UNAME), Linux) + PLATFORM := linux +endif +ifeq ($(UNAME), Darwin) + PLATFORM := osx +endif + +include $(WHEREAMI)/Makefile.$(PLATFORM) diff --git a/release/Makefile.linux b/release/Makefile.linux new file mode 100644 index 000000000..02e92c941 --- /dev/null +++ b/release/Makefile.linux @@ -0,0 +1,10 @@ +# +# Linux-specific packaging +# + +gcs: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs + +.PHONY: gcs ground_package diff --git a/release/Makefile.osx b/release/Makefile.osx new file mode 100644 index 000000000..c213fbf6e --- /dev/null +++ b/release/Makefile.osx @@ -0,0 +1,10 @@ +# +# MacOSX-specific packaging +# + +gcs: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs + +.PHONY: gcs ground_package diff --git a/release/Makefile.win32 b/release/Makefile.win32 new file mode 100644 index 000000000..aed3eca1f --- /dev/null +++ b/release/Makefile.win32 @@ -0,0 +1,11 @@ +# +# Windows-specific packaging +# + +# Generate GCS installer +gcs_installer: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs_installer + +.PHONY: gcs_installer ground_package From 32c7f071758b3f15be048391c3f00e84379d17a2 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Fri, 13 May 2011 17:40:28 +0300 Subject: [PATCH 20/43] OP-483: convert line endings to Unix format (no other changes) --- release/Makefile | 266 ++++++++++++++++++++--------------------- release/Makefile.linux | 20 ++-- release/Makefile.osx | 20 ++-- release/Makefile.win32 | 22 ++-- 4 files changed, 164 insertions(+), 164 deletions(-) diff --git a/release/Makefile b/release/Makefile index 144a0a5dc..a1a45de3b 100644 --- a/release/Makefile +++ b/release/Makefile @@ -1,133 +1,133 @@ -# Set up a default goal -.DEFAULT_GOAL := help - -# Tried the best to support parallel (-j) builds. But since this Makefile -# uses other Makefiles to build few targets which in turn have similar -# dependencies on uavobjects and other generated files, it is difficult -# to support parallel builds perfectly. -# -# Looks like it works for -j8, but fails for -j (unlimited jobs). -# So probably not a bad idea is to build release in single thread. -# -#.NOTPARALLEL: - -# Locate the root of the tree -WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -ROOT_DIR := $(realpath $(WHEREAMI)/../) - -# Set up some macros -BUILD_DIR := $(ROOT_DIR)/build -RELEASE_DATE := $(shell date +%Y%m%d) -RELEASE_TAG := unreleased -RELEASE_LBL := $(RELEASE_DATE)-$(RELEASE_TAG) -RELEASE_DIR := $(BUILD_DIR)/release-$(RELEASE_LBL) -FW_DIR := $(RELEASE_DIR)/firmware-$(RELEASE_LBL) -BL_DIR := $(FW_DIR)/bootloaders -BLUPD_DIR := $(FW_DIR)/bootloader_updaters - -# Setup targets -FW_TARGETS_COMMON := ahrs pipxtreme -FW_TARGETS_INPUT := coptercontrol openpilot -FW_TARGETS := $(FW_TARGETS_COMMON) $(FW_TARGETS_INPUT) -BL_TARGETS := $(addprefix bl_, $(FW_TARGETS)) -BLUPD_TARGETS := $(addprefix blupd_, $(FW_TARGETS)) - -help: - @echo - @echo " This Makefile is known to work on Linux and Mac in a standard shell environment." - @echo " It also works on Windows by following the instructions in ../make/winx86/README.txt." - @echo - @echo " Here is a summary of the available targets:" - @echo - @echo " [Release build and packaging]" - @echo " release - Build and package the OpenPilot release" - @echo - @echo " Notes:" - @echo " - the build directory will be removed first on every run" - @echo " - release packages will be placed in $(RELEASE_DIR)" - @echo - -# Clean and build uavobjects since all parts depend on them -uavobjects: all_clean - $(V1) $(MAKE) -C $(ROOT_DIR) $@ - -all_clean: - $(V1) $(MAKE) -C $(ROOT_DIR) $@ - -# Install template: -# $1 = target -# $2 = dependencies -# $3 = install directory (must be defined) -# $4 = installed file name prefix (optional) -# $5 = installed file name suffix (optional) -# $6 = extra make options (for instance, USE_SPEKTRUM=YES) -# $7 = optional target suffix (for instance, clean, if target must be cleaned first) -# $8 = list of targets to install (without _install suffix) -# $9 = inner make target (usually install, but can be other to just build) -define INSTALL_TEMPLATE -$(1): $(2) -ifneq ($(7),) - $$(V1) +$(MAKE) -C $(ROOT_DIR) $(6) $(addsuffix _$(7), $(8)) -endif - $$(V1) +$(MAKE) -C $(ROOT_DIR) INSTALL_DIR=$(3) INSTALL_PFX=$(4) INSTALL_SFX=$(5) $(6) $(addsuffix _$(9), $(8)) -.PHONY: $(1) -endef - -# Firmware for different input drivers -$(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(RELEASE_LBL),,,$(FW_TARGETS_COMMON),install)) -$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(RELEASE_LBL),,clean,$(FW_TARGETS_INPUT),install)) -$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects fw_pwm,$(FW_DIR),,-spektrum-$(RELEASE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install)) -$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects fw_spektrum,$(FW_DIR),,-ppm-$(RELEASE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install)) - -# Bootloaders (change 'bin' to 'install' to install bootloaders too) -$(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(RELEASE_LBL),,,$(BL_TARGETS),bin)) - -# Bootloader Updaters -$(eval $(call INSTALL_TEMPLATE,blupd_coptercontrol,all_bl,$(BLUPD_DIR),CopterControl_,-$(RELEASE_LBL),,,blupd_coptercontrol,install)) -$(eval $(call INSTALL_TEMPLATE,blupd_ahrs,all_bl,$(BLUPD_DIR),AHRS_,-$(RELEASE_LBL),,,blupd_ahrs,install)) -$(eval $(call INSTALL_TEMPLATE,blupd_openpilot,all_bl,$(BLUPD_DIR),OpenPilot_,-$(RELEASE_LBL),,,blupd_openpilot,install)) -$(eval $(call INSTALL_TEMPLATE,blupd_pipxtreme,all_bl,$(BLUPD_DIR),PipXtreme_,-$(RELEASE_LBL),,,blupd_pipxtreme,install)) - -# Order-only dependencies -# They are bit complicated to support parallel (-j) builds and to -# create the pwm/ppm/spektrum targets in a sequence of build steps - -release: | release_flight release_ground - -release_flight: | release_fw release_blupd - -release_fw: | fw_common fw_pwm fw_spektrum # fw_ppm - -release_blupd: | $(BLUPD_TARGETS) - -release_ground: | ground_package - -.PHONY: help uavobjects all_clean release release_flight release_fw release_blupd release_ground - -# Decide on a verbosity level based on the V= parameter -export AT := @ - -ifndef V -export V0 := -export V1 := $(AT) -else ifeq ($(V), 0) -export V0 := $(AT) -export V1 := $(AT) -else ifeq ($(V), 1) -endif - -ifneq ($(V),1) -MAKEFLAGS += --no-print-directory -endif - -# Platform-dependent stuff -PLATFORM := win32 -UNAME := $(shell uname) -ifeq ($(UNAME), Linux) - PLATFORM := linux -endif -ifeq ($(UNAME), Darwin) - PLATFORM := osx -endif - -include $(WHEREAMI)/Makefile.$(PLATFORM) +# Set up a default goal +.DEFAULT_GOAL := help + +# Tried the best to support parallel (-j) builds. But since this Makefile +# uses other Makefiles to build few targets which in turn have similar +# dependencies on uavobjects and other generated files, it is difficult +# to support parallel builds perfectly. +# +# Looks like it works for -j8, but fails for -j (unlimited jobs). +# So probably not a bad idea is to build release in single thread. +# +#.NOTPARALLEL: + +# Locate the root of the tree +WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) +ROOT_DIR := $(realpath $(WHEREAMI)/../) + +# Set up some macros +BUILD_DIR := $(ROOT_DIR)/build +RELEASE_DATE := $(shell date +%Y%m%d) +RELEASE_TAG := unreleased +RELEASE_LBL := $(RELEASE_DATE)-$(RELEASE_TAG) +RELEASE_DIR := $(BUILD_DIR)/release-$(RELEASE_LBL) +FW_DIR := $(RELEASE_DIR)/firmware-$(RELEASE_LBL) +BL_DIR := $(FW_DIR)/bootloaders +BLUPD_DIR := $(FW_DIR)/bootloader_updaters + +# Setup targets +FW_TARGETS_COMMON := ahrs pipxtreme +FW_TARGETS_INPUT := coptercontrol openpilot +FW_TARGETS := $(FW_TARGETS_COMMON) $(FW_TARGETS_INPUT) +BL_TARGETS := $(addprefix bl_, $(FW_TARGETS)) +BLUPD_TARGETS := $(addprefix blupd_, $(FW_TARGETS)) + +help: + @echo + @echo " This Makefile is known to work on Linux and Mac in a standard shell environment." + @echo " It also works on Windows by following the instructions in ../make/winx86/README.txt." + @echo + @echo " Here is a summary of the available targets:" + @echo + @echo " [Release build and packaging]" + @echo " release - Build and package the OpenPilot release" + @echo + @echo " Notes:" + @echo " - the build directory will be removed first on every run" + @echo " - release packages will be placed in $(RELEASE_DIR)" + @echo + +# Clean and build uavobjects since all parts depend on them +uavobjects: all_clean + $(V1) $(MAKE) -C $(ROOT_DIR) $@ + +all_clean: + $(V1) $(MAKE) -C $(ROOT_DIR) $@ + +# Install template: +# $1 = target +# $2 = dependencies +# $3 = install directory (must be defined) +# $4 = installed file name prefix (optional) +# $5 = installed file name suffix (optional) +# $6 = extra make options (for instance, USE_SPEKTRUM=YES) +# $7 = optional target suffix (for instance, clean, if target must be cleaned first) +# $8 = list of targets to install (without _install suffix) +# $9 = inner make target (usually install, but can be other to just build) +define INSTALL_TEMPLATE +$(1): $(2) +ifneq ($(7),) + $$(V1) +$(MAKE) -C $(ROOT_DIR) $(6) $(addsuffix _$(7), $(8)) +endif + $$(V1) +$(MAKE) -C $(ROOT_DIR) INSTALL_DIR=$(3) INSTALL_PFX=$(4) INSTALL_SFX=$(5) $(6) $(addsuffix _$(9), $(8)) +.PHONY: $(1) +endef + +# Firmware for different input drivers +$(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(RELEASE_LBL),,,$(FW_TARGETS_COMMON),install)) +$(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(RELEASE_LBL),,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects fw_pwm,$(FW_DIR),,-spektrum-$(RELEASE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects fw_spektrum,$(FW_DIR),,-ppm-$(RELEASE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install)) + +# Bootloaders (change 'bin' to 'install' to install bootloaders too) +$(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(RELEASE_LBL),,,$(BL_TARGETS),bin)) + +# Bootloader Updaters +$(eval $(call INSTALL_TEMPLATE,blupd_coptercontrol,all_bl,$(BLUPD_DIR),CopterControl_,-$(RELEASE_LBL),,,blupd_coptercontrol,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_ahrs,all_bl,$(BLUPD_DIR),AHRS_,-$(RELEASE_LBL),,,blupd_ahrs,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_openpilot,all_bl,$(BLUPD_DIR),OpenPilot_,-$(RELEASE_LBL),,,blupd_openpilot,install)) +$(eval $(call INSTALL_TEMPLATE,blupd_pipxtreme,all_bl,$(BLUPD_DIR),PipXtreme_,-$(RELEASE_LBL),,,blupd_pipxtreme,install)) + +# Order-only dependencies +# They are bit complicated to support parallel (-j) builds and to +# create the pwm/ppm/spektrum targets in a sequence of build steps + +release: | release_flight release_ground + +release_flight: | release_fw release_blupd + +release_fw: | fw_common fw_pwm fw_spektrum # fw_ppm + +release_blupd: | $(BLUPD_TARGETS) + +release_ground: | ground_package + +.PHONY: help uavobjects all_clean release release_flight release_fw release_blupd release_ground + +# Decide on a verbosity level based on the V= parameter +export AT := @ + +ifndef V +export V0 := +export V1 := $(AT) +else ifeq ($(V), 0) +export V0 := $(AT) +export V1 := $(AT) +else ifeq ($(V), 1) +endif + +ifneq ($(V),1) +MAKEFLAGS += --no-print-directory +endif + +# Platform-dependent stuff +PLATFORM := win32 +UNAME := $(shell uname) +ifeq ($(UNAME), Linux) + PLATFORM := linux +endif +ifeq ($(UNAME), Darwin) + PLATFORM := osx +endif + +include $(WHEREAMI)/Makefile.$(PLATFORM) diff --git a/release/Makefile.linux b/release/Makefile.linux index 02e92c941..c966ff6f2 100644 --- a/release/Makefile.linux +++ b/release/Makefile.linux @@ -1,10 +1,10 @@ -# -# Linux-specific packaging -# - -gcs: uavobjects - $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ - -ground_package: | gcs - -.PHONY: gcs ground_package +# +# Linux-specific packaging +# + +gcs: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs + +.PHONY: gcs ground_package diff --git a/release/Makefile.osx b/release/Makefile.osx index c213fbf6e..d18b950d7 100644 --- a/release/Makefile.osx +++ b/release/Makefile.osx @@ -1,10 +1,10 @@ -# -# MacOSX-specific packaging -# - -gcs: uavobjects - $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ - -ground_package: | gcs - -.PHONY: gcs ground_package +# +# MacOSX-specific packaging +# + +gcs: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs + +.PHONY: gcs ground_package diff --git a/release/Makefile.win32 b/release/Makefile.win32 index aed3eca1f..b1283c3cf 100644 --- a/release/Makefile.win32 +++ b/release/Makefile.win32 @@ -1,11 +1,11 @@ -# -# Windows-specific packaging -# - -# Generate GCS installer -gcs_installer: uavobjects - $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ - -ground_package: | gcs_installer - -.PHONY: gcs_installer ground_package +# +# Windows-specific packaging +# + +# Generate GCS installer +gcs_installer: uavobjects + $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ + +ground_package: | gcs_installer + +.PHONY: gcs_installer ground_package From 7fc87700cc44e2db83c4abe63d652bd75aee4d75 Mon Sep 17 00:00:00 2001 From: dankers Date: Sat, 14 May 2011 15:41:44 +1000 Subject: [PATCH 21/43] Fix the default config. The control gadget was on the config screen to help new users validate their inputs. Adding it back. --- .../src/plugins/coreplugin/OpenPilotGCS.ini | 178 +++++++++--------- 1 file changed, 87 insertions(+), 91 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini index a37b328e5..e444e99c3 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.ini @@ -1,5 +1,5 @@ [General] -ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5V\0\0\x2\x9a\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0) +ViewGroup_Default=@ByteArray(\0\0\0\xff\0\0\0\0\xfd\0\0\0\0\0\0\x5\xa0\0\0\x3/\0\0\0\x4\0\0\0\x4\0\0\0\x1\0\0\0\b\xfc\0\0\0\0) [Workspace] NumberOfWorkspaces=6 @@ -70,6 +70,7 @@ Mode1\splitter\side0\side1\splitterOrientation=1 Mode1\splitter\side0\side1\splitterSizes=304, 433 Mode1\splitter\side0\side1\side0\type=uavGadget Mode1\splitter\side0\side1\side0\classId=ModelViewGadget +Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X Mode1\splitter\side0\side1\side1\type=splitter Mode1\splitter\side0\side1\side1\splitterOrientation=2 Mode1\splitter\side0\side1\side1\splitterSizes=293, 64 @@ -180,7 +181,15 @@ Mode2\splitter\side0\side1\side0\gadget\activeConfiguration=Telemetry RX Rate Ho Mode2\splitter\side0\side1\side1\type=uavGadget Mode2\splitter\side0\side1\side1\classId=LineardialGadget Mode2\splitter\side0\side1\side1\gadget\activeConfiguration=Telemetry TX Rate Horizontal -Mode2\splitter\side1\type=uavGadget +Mode2\splitter\side1\type=splitter +Mode2\splitter\side1\splitterOrientation=2 +Mode2\splitter\side1\splitterSizes=426, 354 +Mode2\splitter\side1\side0\type=uavGadget +Mode2\splitter\side1\side0\classId=UAVObjectBrowser +Mode2\splitter\side1\side0\gadget\activeConfiguration=default +Mode2\splitter\side1\side1\type=uavGadget +Mode2\splitter\side1\side1\classId=GCSControlGadget +Mode2\splitter\side1\side1\gadget\activeConfiguration=MS Sidewinder Mode3\version=UAVGadgetManagerV1 Mode3\showToolbars=false Mode3\splitter\type=splitter @@ -194,6 +203,7 @@ Mode3\splitter\side1\splitterOrientation=2 Mode3\splitter\side1\splitterSizes=395, 236 Mode3\splitter\side1\side0\type=uavGadget Mode3\splitter\side1\side0\classId=ModelViewGadget +Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X Mode3\splitter\side1\side1\type=splitter Mode3\splitter\side1\side1\splitterOrientation=1 Mode3\splitter\side1\side1\splitterSizes=@Invalid() @@ -289,21 +299,13 @@ Mode6\splitter\side1\side0\side1\gadget\activeConfiguration=raw Mode6\splitter\side1\side1\type=uavGadget Mode6\splitter\side1\side1\classId=ScopeGadget Mode6\splitter\side1\side1\gadget\activeConfiguration=Uptimes -Mode1\splitter\side0\side1\side0\gadget\activeConfiguration=Test Quad X -Mode2\splitter\side1\classId=UAVObjectBrowser -Mode2\splitter\side1\gadget\activeConfiguration=default -Mode3\splitter\side1\side0\gadget\activeConfiguration=Test Quad X [KeyBindings] size=0 [%General] +OverrideLanguage=en_AU SaveSettingsOnExit=true -TerminalEmulator=xterm -e -LastPreferenceCategory=LineardialGadget -LastPreferencePage=Roll Desired 1 -SettingsWindowWidth=921 -SettingsWindowHeight=534 [UAVGadgetConfigurations] configInfo\version=1.2.0 @@ -1233,6 +1235,40 @@ LineardialGadget\Mainboard%20CPU\data\factor=1 LineardialGadget\Mainboard%20CPU\data\useOpenGLFlag=false LineardialGadget\Mainboard%20CPU\configInfo\version=0.0.0 LineardialGadget\Mainboard%20CPU\configInfo\locked=false +LineardialGadget\Pitch\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Pitch\data\sourceDataObject=ManualControlCommand +LineardialGadget\Pitch\data\sourceObjectField=Pitch +LineardialGadget\Pitch\data\minValue=-1 +LineardialGadget\Pitch\data\maxValue=1 +LineardialGadget\Pitch\data\redMin=-1 +LineardialGadget\Pitch\data\redMax=1 +LineardialGadget\Pitch\data\yellowMin=-0.8 +LineardialGadget\Pitch\data\yellowMax=0.8 +LineardialGadget\Pitch\data\greenMin=-0.5 +LineardialGadget\Pitch\data\greenMax=0.5 +LineardialGadget\Pitch\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Pitch\data\decimalPlaces=2 +LineardialGadget\Pitch\data\factor=1 +LineardialGadget\Pitch\data\useOpenGLFlag=false +LineardialGadget\Pitch\configInfo\version=0.0.0 +LineardialGadget\Pitch\configInfo\locked=false +LineardialGadget\Pitch%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Pitch%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Pitch%20Desired\data\sourceObjectField=Pitch +LineardialGadget\Pitch%20Desired\data\minValue=-1 +LineardialGadget\Pitch%20Desired\data\maxValue=1 +LineardialGadget\Pitch%20Desired\data\redMin=-1 +LineardialGadget\Pitch%20Desired\data\redMax=1 +LineardialGadget\Pitch%20Desired\data\yellowMin=-0.8 +LineardialGadget\Pitch%20Desired\data\yellowMax=0.8 +LineardialGadget\Pitch%20Desired\data\greenMin=-0.5 +LineardialGadget\Pitch%20Desired\data\greenMax=0.5 +LineardialGadget\Pitch%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Pitch%20Desired\data\decimalPlaces=2 +LineardialGadget\Pitch%20Desired\data\factor=1 +LineardialGadget\Pitch%20Desired\data\useOpenGLFlag=false +LineardialGadget\Pitch%20Desired\configInfo\version=0.0.0 +LineardialGadget\Pitch%20Desired\configInfo\locked=false LineardialGadget\PitchActual\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg LineardialGadget\PitchActual\data\sourceDataObject=AttitudeActual LineardialGadget\PitchActual\data\sourceObjectField=Pitch @@ -1267,6 +1303,23 @@ LineardialGadget\Roll\data\factor=1 LineardialGadget\Roll\data\useOpenGLFlag=false LineardialGadget\Roll\configInfo\version=0.0.0 LineardialGadget\Roll\configInfo\locked=false +LineardialGadget\Roll%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Roll%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Roll%20Desired\data\sourceObjectField=Roll +LineardialGadget\Roll%20Desired\data\minValue=-1 +LineardialGadget\Roll%20Desired\data\maxValue=1 +LineardialGadget\Roll%20Desired\data\redMin=-1 +LineardialGadget\Roll%20Desired\data\redMax=1 +LineardialGadget\Roll%20Desired\data\yellowMin=-0.8 +LineardialGadget\Roll%20Desired\data\yellowMax=0.8 +LineardialGadget\Roll%20Desired\data\greenMin=-0.5 +LineardialGadget\Roll%20Desired\data\greenMax=0.5 +LineardialGadget\Roll%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Roll%20Desired\data\decimalPlaces=2 +LineardialGadget\Roll%20Desired\data\factor=1 +LineardialGadget\Roll%20Desired\data\useOpenGLFlag=false +LineardialGadget\Roll%20Desired\configInfo\version=0.0.0 +LineardialGadget\Roll%20Desired\configInfo\locked=false LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\dFile=%%DATAPATH%%dials/default/lineardial-horizontal.svg LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceDataObject=GCSTelemetryStats LineardialGadget\Telemetry%20RX%20Rate%20Horizontal\data\sourceObjectField=RxDataRate @@ -1335,6 +1388,23 @@ LineardialGadget\Yaw\data\factor=1 LineardialGadget\Yaw\data\useOpenGLFlag=false LineardialGadget\Yaw\configInfo\version=0.0.0 LineardialGadget\Yaw\configInfo\locked=false +LineardialGadget\Yaw%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg +LineardialGadget\Yaw%20Desired\data\sourceDataObject=ActuatorDesired +LineardialGadget\Yaw%20Desired\data\sourceObjectField=Yaw +LineardialGadget\Yaw%20Desired\data\minValue=-1 +LineardialGadget\Yaw%20Desired\data\maxValue=1 +LineardialGadget\Yaw%20Desired\data\redMin=-1 +LineardialGadget\Yaw%20Desired\data\redMax=1 +LineardialGadget\Yaw%20Desired\data\yellowMin=-0.8 +LineardialGadget\Yaw%20Desired\data\yellowMax=0.8 +LineardialGadget\Yaw%20Desired\data\greenMin=-0.5 +LineardialGadget\Yaw%20Desired\data\greenMax=0.5 +LineardialGadget\Yaw%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" +LineardialGadget\Yaw%20Desired\data\decimalPlaces=2 +LineardialGadget\Yaw%20Desired\data\factor=1 +LineardialGadget\Yaw%20Desired\data\useOpenGLFlag=false +LineardialGadget\Yaw%20Desired\configInfo\version=0.0.0 +LineardialGadget\Yaw%20Desired\configInfo\locked=false ModelViewGadget\Aeroquad%20%2B\data\acFilename=%%DATAPATH%%models/multi/aeroquad/aeroquad_+.3ds ModelViewGadget\Aeroquad%20%2B\data\bgFilename=%%DATAPATH%%models/backgrounds/default_background.png ModelViewGadget\Aeroquad%20%2B\data\enableVbo=false @@ -1404,40 +1474,6 @@ OPMapGadget\Google%20Sat\data\showTileGridLines=false OPMapGadget\Google%20Sat\data\accessMode=ServerAndCache OPMapGadget\Google%20Sat\data\useMemoryCache=true OPMapGadget\Google%20Sat\data\uavSymbol=mapquad.png -LineardialGadget\Pitch\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\Pitch\data\sourceDataObject=ManualControlCommand -LineardialGadget\Pitch\data\sourceObjectField=Pitch -LineardialGadget\Pitch\data\minValue=-1 -LineardialGadget\Pitch\data\maxValue=1 -LineardialGadget\Pitch\data\redMin=-1 -LineardialGadget\Pitch\data\redMax=1 -LineardialGadget\Pitch\data\yellowMin=-0.8 -LineardialGadget\Pitch\data\yellowMax=0.8 -LineardialGadget\Pitch\data\greenMin=-0.5 -LineardialGadget\Pitch\data\greenMax=0.5 -LineardialGadget\Pitch\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\Pitch\data\decimalPlaces=2 -LineardialGadget\Pitch\data\factor=1 -LineardialGadget\Pitch\data\useOpenGLFlag=false -LineardialGadget\Pitch\configInfo\version=0.0.0 -LineardialGadget\Pitch\configInfo\locked=false -LineardialGadget\Pitch%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\Pitch%20Desired\data\sourceDataObject=ActuatorDesired -LineardialGadget\Pitch%20Desired\data\sourceObjectField=Pitch -LineardialGadget\Pitch%20Desired\data\minValue=-1 -LineardialGadget\Pitch%20Desired\data\maxValue=1 -LineardialGadget\Pitch%20Desired\data\redMin=-1 -LineardialGadget\Pitch%20Desired\data\redMax=1 -LineardialGadget\Pitch%20Desired\data\yellowMin=-0.8 -LineardialGadget\Pitch%20Desired\data\yellowMax=0.8 -LineardialGadget\Pitch%20Desired\data\greenMin=-0.5 -LineardialGadget\Pitch%20Desired\data\greenMax=0.5 -LineardialGadget\Pitch%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\Pitch%20Desired\data\decimalPlaces=2 -LineardialGadget\Pitch%20Desired\data\factor=1 -LineardialGadget\Pitch%20Desired\data\useOpenGLFlag=false -LineardialGadget\Pitch%20Desired\configInfo\version=0.0.0 -LineardialGadget\Pitch%20Desired\configInfo\locked=false OPMapGadget\Google%20Sat\data\cacheLocation=%%STOREPATH%%mapscache/ OPMapGadget\Google%20Sat\configInfo\version=0.0.0 OPMapGadget\Google%20Sat\configInfo\locked=false @@ -1875,52 +1911,18 @@ Uploader\default\data\defaultStopBits=0 Uploader\default\data\defaultPort=/dev/ttyS0 Uploader\default\configInfo\version=0.0.0 Uploader\default\configInfo\locked=false -LineardialGadget\Roll%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\Roll%20Desired\data\sourceDataObject=ActuatorDesired -LineardialGadget\Roll%20Desired\data\sourceObjectField=Roll -LineardialGadget\Roll%20Desired\data\minValue=-1 -LineardialGadget\Roll%20Desired\data\maxValue=1 -LineardialGadget\Roll%20Desired\data\redMin=-1 -LineardialGadget\Roll%20Desired\data\redMax=1 -LineardialGadget\Roll%20Desired\data\yellowMin=-0.8 -LineardialGadget\Roll%20Desired\data\yellowMax=0.8 -LineardialGadget\Roll%20Desired\data\greenMin=-0.5 -LineardialGadget\Roll%20Desired\data\greenMax=0.5 -LineardialGadget\Roll%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\Roll%20Desired\data\decimalPlaces=2 -LineardialGadget\Roll%20Desired\data\factor=1 -LineardialGadget\Roll%20Desired\data\useOpenGLFlag=false -LineardialGadget\Roll%20Desired\configInfo\version=0.0.0 -LineardialGadget\Roll%20Desired\configInfo\locked=false -LineardialGadget\Yaw%20Desired\data\dFile=%%DATAPATH%%dials/default/lineardial-vertical.svg -LineardialGadget\Yaw%20Desired\data\sourceDataObject=ActuatorDesired -LineardialGadget\Yaw%20Desired\data\sourceObjectField=Yaw -LineardialGadget\Yaw%20Desired\data\minValue=-1 -LineardialGadget\Yaw%20Desired\data\maxValue=1 -LineardialGadget\Yaw%20Desired\data\redMin=-1 -LineardialGadget\Yaw%20Desired\data\redMax=1 -LineardialGadget\Yaw%20Desired\data\yellowMin=-0.8 -LineardialGadget\Yaw%20Desired\data\yellowMax=0.8 -LineardialGadget\Yaw%20Desired\data\greenMin=-0.5 -LineardialGadget\Yaw%20Desired\data\greenMax=0.5 -LineardialGadget\Yaw%20Desired\data\font="Andale Mono,12,-1,5,75,0,0,0,0,0" -LineardialGadget\Yaw%20Desired\data\decimalPlaces=2 -LineardialGadget\Yaw%20Desired\data\factor=1 -LineardialGadget\Yaw%20Desired\data\useOpenGLFlag=false -LineardialGadget\Yaw%20Desired\configInfo\version=0.0.0 -LineardialGadget\Yaw%20Desired\configInfo\locked=false [Plugins] -SoundNotifyPlugin\data\Current\1\SoundCollectionPath=%%DATAPATH%%sounds -SoundNotifyPlugin\data\Current\1\CurrentLanguage=default -SoundNotifyPlugin\data\Current\1\ObjectField=Channel -SoundNotifyPlugin\data\Current\1\DataObject=ActuatorCommand -SoundNotifyPlugin\data\Current\1\Value=Equal to +SoundNotifyPlugin\data\Current\1\SoundCollectionPath= +SoundNotifyPlugin\data\Current\1\CurrentLanguage= +SoundNotifyPlugin\data\Current\1\ObjectField= +SoundNotifyPlugin\data\Current\1\DataObject= +SoundNotifyPlugin\data\Current\1\Value= SoundNotifyPlugin\data\Current\1\ValueSpinBox=0 SoundNotifyPlugin\data\Current\1\Sound1= SoundNotifyPlugin\data\Current\1\Sound2= SoundNotifyPlugin\data\Current\1\Sound3= -SoundNotifyPlugin\data\Current\1\SayOrder=Never +SoundNotifyPlugin\data\Current\1\SayOrder= SoundNotifyPlugin\data\Current\1\Repeat= SoundNotifyPlugin\data\Current\1\ExpireTimeout=0 SoundNotifyPlugin\data\Current\size=1 @@ -1928,9 +1930,3 @@ SoundNotifyPlugin\data\listNotifies\size=0 SoundNotifyPlugin\data\EnableSound=false SoundNotifyPlugin\configInfo\version=1.0.0 SoundNotifyPlugin\configInfo\locked=false - -[IPconnection] -Current\1\HostName= -Current\1\Port=1 -Current\1\UseTCP=0 -Current\size=1 From cdbdfbd8b5c1495c8bdd2a0105c3fc6c83de5480 Mon Sep 17 00:00:00 2001 From: dankers Date: Sat, 14 May 2011 15:50:07 +1000 Subject: [PATCH 22/43] Add Sambas' Y6 OpenPilot flight --- MILESTONES.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/MILESTONES.txt b/MILESTONES.txt index 4f259c856..f4568be90 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -105,6 +105,11 @@ C: Gary Mortimer and the Scorpion D: March 2011 V: http://vimeo.com/22104334 +M: First Y6 OpenPilot flight +C: Sami Korhonen (Sambas) +D: May 2011 +V: http://www.vimeo.com/23637586 + M: First CopterControl flight on a Flybarless Heli C: ? D: ? From fab880a7d270d6ebb9bdc46d881c1673eb6622b7 Mon Sep 17 00:00:00 2001 From: elafargue Date: Sat, 14 May 2011 14:47:49 +0200 Subject: [PATCH 23/43] Improvement by pip1996 on opmpap widget, to limit update rate and solve the CPU hogging issue. --- .../opmap/opmapgadgetconfiguration.cpp | 218 +- .../plugins/opmap/opmapgadgetconfiguration.h | 190 +- .../plugins/opmap/opmapgadgetoptionspage.cpp | 282 +- .../plugins/opmap/opmapgadgetoptionspage.ui | 15 +- .../src/plugins/opmap/opmapgadgetwidget.cpp | 4822 +++++++++-------- .../src/plugins/opmap/opmapgadgetwidget.h | 708 +-- 6 files changed, 3188 insertions(+), 3047 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp index 25069571f..67d1d1f98 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.cpp @@ -1,102 +1,116 @@ -/** - ****************************************************************************** - * - * @file opmapgadgetconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "opmapgadgetconfiguration.h" -#include "utils/pathutils.h" -#include - -OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent), - m_mapProvider("GoogleHybrid"), - m_defaultZoom(2), - m_defaultLatitude(0), - m_defaultLongitude(0), - m_useOpenGL(false), - m_showTileGridLines(false), - m_accessMode("ServerAndCache"), - m_useMemoryCache(true), - m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()), - m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")) -{ - - //if a saved configuration exists load it - if(qSettings != 0) { - QString mapProvider = qSettings->value("mapProvider").toString(); - int zoom = qSettings->value("defaultZoom").toInt(); - double latitude= qSettings->value("defaultLatitude").toDouble(); - double longitude= qSettings->value("defaultLongitude").toDouble(); - bool useOpenGL= qSettings->value("useOpenGL").toBool(); - bool showTileGridLines= qSettings->value("showTileGridLines").toBool(); - QString accessMode= qSettings->value("accessMode").toString(); - bool useMemoryCache= qSettings->value("useMemoryCache").toBool(); - QString cacheLocation= qSettings->value("cacheLocation").toString(); - QString uavSymbol=qSettings->value("uavSymbol").toString(); - if (!mapProvider.isEmpty()) m_mapProvider = mapProvider; - m_defaultZoom = zoom; - m_defaultLatitude = latitude; - m_defaultLongitude = longitude; - m_useOpenGL = useOpenGL; - m_showTileGridLines = showTileGridLines; - m_uavSymbol=uavSymbol; - if (!accessMode.isEmpty()) m_accessMode = accessMode; - m_useMemoryCache = useMemoryCache; - if (!cacheLocation.isEmpty()) m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation); - } -} - -IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone() -{ - OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId()); - - m->m_mapProvider = m_mapProvider; - m->m_defaultZoom = m_defaultZoom; - m->m_defaultLatitude = m_defaultLatitude; - m->m_defaultLongitude = m_defaultLongitude; - m->m_useOpenGL = m_useOpenGL; - m->m_showTileGridLines = m_showTileGridLines; - m->m_accessMode = m_accessMode; - m->m_useMemoryCache = m_useMemoryCache; - m->m_cacheLocation = m_cacheLocation; - m->m_uavSymbol=m_uavSymbol; - return m; -} - -void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { - qSettings->setValue("mapProvider", m_mapProvider); - qSettings->setValue("defaultZoom", m_defaultZoom); - qSettings->setValue("defaultLatitude", m_defaultLatitude); - qSettings->setValue("defaultLongitude", m_defaultLongitude); - qSettings->setValue("useOpenGL", m_useOpenGL); - qSettings->setValue("showTileGridLines", m_showTileGridLines); - qSettings->setValue("accessMode", m_accessMode); - qSettings->setValue("useMemoryCache", m_useMemoryCache); - qSettings->setValue("uavSymbol", m_uavSymbol); - qSettings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); -} -void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){ - m_cacheLocation = cacheLocation; -} +/** + ****************************************************************************** + * + * @file opmapgadgetconfiguration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "opmapgadgetconfiguration.h" +#include "utils/pathutils.h" +#include + +OPMapGadgetConfiguration::OPMapGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent), + m_mapProvider("GoogleHybrid"), + m_defaultZoom(2), + m_defaultLatitude(0), + m_defaultLongitude(0), + m_useOpenGL(false), + m_showTileGridLines(false), + m_accessMode("ServerAndCache"), + m_useMemoryCache(true), + m_cacheLocation(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()), + m_uavSymbol(QString::fromUtf8(":/uavs/images/mapquad.png")), + m_maxUpdateRate(2000) // ms +{ + + //if a saved configuration exists load it + if (qSettings != 0) { + + QString mapProvider = qSettings->value("mapProvider").toString(); + int zoom = qSettings->value("defaultZoom").toInt(); + double latitude= qSettings->value("defaultLatitude").toDouble(); + double longitude= qSettings->value("defaultLongitude").toDouble(); + bool useOpenGL= qSettings->value("useOpenGL").toBool(); + bool showTileGridLines= qSettings->value("showTileGridLines").toBool(); + QString accessMode= qSettings->value("accessMode").toString(); + bool useMemoryCache= qSettings->value("useMemoryCache").toBool(); + QString cacheLocation= qSettings->value("cacheLocation").toString(); + QString uavSymbol=qSettings->value("uavSymbol").toString(); + int max_update_rate = qSettings->value("maxUpdateRate").toInt(); + + if (!mapProvider.isEmpty()) m_mapProvider = mapProvider; + m_defaultZoom = zoom; + m_defaultLatitude = latitude; + m_defaultLongitude = longitude; + m_useOpenGL = useOpenGL; + m_showTileGridLines = showTileGridLines; + m_uavSymbol = uavSymbol; + + m_maxUpdateRate = max_update_rate; + if (m_maxUpdateRate < 100 || m_maxUpdateRate > 5000) + m_maxUpdateRate = 2000; + + if (!accessMode.isEmpty()) + m_accessMode = accessMode; + m_useMemoryCache = useMemoryCache; + if (!cacheLocation.isEmpty()) + m_cacheLocation = Utils::PathUtils().InsertStoragePath(cacheLocation); + } +} + +IUAVGadgetConfiguration * OPMapGadgetConfiguration::clone() +{ + OPMapGadgetConfiguration *m = new OPMapGadgetConfiguration(this->classId()); + + m->m_mapProvider = m_mapProvider; + m->m_defaultZoom = m_defaultZoom; + m->m_defaultLatitude = m_defaultLatitude; + m->m_defaultLongitude = m_defaultLongitude; + m->m_useOpenGL = m_useOpenGL; + m->m_showTileGridLines = m_showTileGridLines; + m->m_accessMode = m_accessMode; + m->m_useMemoryCache = m_useMemoryCache; + m->m_cacheLocation = m_cacheLocation; + m->m_uavSymbol = m_uavSymbol; + m->m_maxUpdateRate = m_maxUpdateRate; + + return m; +} + +void OPMapGadgetConfiguration::saveConfig(QSettings* qSettings) const { + qSettings->setValue("mapProvider", m_mapProvider); + qSettings->setValue("defaultZoom", m_defaultZoom); + qSettings->setValue("defaultLatitude", m_defaultLatitude); + qSettings->setValue("defaultLongitude", m_defaultLongitude); + qSettings->setValue("useOpenGL", m_useOpenGL); + qSettings->setValue("showTileGridLines", m_showTileGridLines); + qSettings->setValue("accessMode", m_accessMode); + qSettings->setValue("useMemoryCache", m_useMemoryCache); + qSettings->setValue("uavSymbol", m_uavSymbol); + qSettings->setValue("cacheLocation", Utils::PathUtils().RemoveStoragePath(m_cacheLocation)); + qSettings->setValue("maxUpdateRate", m_maxUpdateRate); +} +void OPMapGadgetConfiguration::setCacheLocation(QString cacheLocation){ + m_cacheLocation = cacheLocation; +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h index 4b4476f71..1e630dc00 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetconfiguration.h @@ -1,93 +1,97 @@ -/** - ****************************************************************************** - * - * @file opmapgadgetconfiguration.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef OPMAP_GADGETCONFIGURATION_H -#define OPMAP_GADGETCONFIGURATION_H - -#include -#include - -using namespace Core; - -class OPMapGadgetConfiguration : public IUAVGadgetConfiguration -{ -Q_OBJECT - -Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider) -Q_PROPERTY(int zoommo READ zoom WRITE setZoom) -Q_PROPERTY(double latitude READ latitude WRITE setLatitude) -Q_PROPERTY(double longitude READ longitude WRITE setLongitude) -Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL) -Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines) -Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode) -Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache) -Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation) -Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol) - -public: - explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); - - void saveConfig(QSettings* settings) const; - IUAVGadgetConfiguration *clone(); - - QString mapProvider() const { return m_mapProvider; } - int zoom() const { return m_defaultZoom; } - double latitude() const { return m_defaultLatitude; } - double longitude() const { return m_defaultLongitude; } - bool useOpenGL() const { return m_useOpenGL; } - bool showTileGridLines() const { return m_showTileGridLines; } - QString accessMode() const { return m_accessMode; } - bool useMemoryCache() const { return m_useMemoryCache; } - QString cacheLocation() const { return m_cacheLocation; } - QString uavSymbol() const { return m_uavSymbol; } - -public slots: - void setMapProvider(QString provider) { m_mapProvider = provider; } - void setZoom(int zoom) { m_defaultZoom = zoom; } - void setLatitude(double latitude) { m_defaultLatitude = latitude; } - void setLongitude(double longitude) { m_defaultLongitude = longitude; } - void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; } - void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; } - void setAccessMode(QString accessMode) { m_accessMode = accessMode; } - void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; } - void setCacheLocation(QString cacheLocation); - void setUavSymbol(QString symbol){m_uavSymbol=symbol;} -private: - QString m_mapProvider; - int m_defaultZoom; - double m_defaultLatitude; - double m_defaultLongitude; - bool m_useOpenGL; - bool m_showTileGridLines; - QString m_accessMode; - bool m_useMemoryCache; - QString m_cacheLocation; - QString m_uavSymbol; - -}; - -#endif // OPMAP_GADGETCONFIGURATION_H +/** + ****************************************************************************** + * + * @file opmapgadgetconfiguration.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef OPMAP_GADGETCONFIGURATION_H +#define OPMAP_GADGETCONFIGURATION_H + +#include +#include + +using namespace Core; + +class OPMapGadgetConfiguration : public IUAVGadgetConfiguration +{ +Q_OBJECT + +Q_PROPERTY(QString mapProvider READ mapProvider WRITE setMapProvider) +Q_PROPERTY(int zoommo READ zoom WRITE setZoom) +Q_PROPERTY(double latitude READ latitude WRITE setLatitude) +Q_PROPERTY(double longitude READ longitude WRITE setLongitude) +Q_PROPERTY(bool useOpenGL READ useOpenGL WRITE setUseOpenGL) +Q_PROPERTY(bool showTileGridLines READ showTileGridLines WRITE setShowTileGridLines) +Q_PROPERTY(QString accessMode READ accessMode WRITE setAccessMode) +Q_PROPERTY(bool useMemoryCache READ useMemoryCache WRITE setUseMemoryCache) +Q_PROPERTY(QString cacheLocation READ cacheLocation WRITE setCacheLocation) +Q_PROPERTY(QString uavSymbol READ uavSymbol WRITE setUavSymbol) +Q_PROPERTY(int maxUpdateRate READ maxUpdateRate WRITE setMaxUpdateRate) + +public: + explicit OPMapGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + + void saveConfig(QSettings* settings) const; + IUAVGadgetConfiguration *clone(); + + QString mapProvider() const { return m_mapProvider; } + int zoom() const { return m_defaultZoom; } + double latitude() const { return m_defaultLatitude; } + double longitude() const { return m_defaultLongitude; } + bool useOpenGL() const { return m_useOpenGL; } + bool showTileGridLines() const { return m_showTileGridLines; } + QString accessMode() const { return m_accessMode; } + bool useMemoryCache() const { return m_useMemoryCache; } + QString cacheLocation() const { return m_cacheLocation; } + QString uavSymbol() const { return m_uavSymbol; } + int maxUpdateRate() const { return m_maxUpdateRate; } + +public slots: + void setMapProvider(QString provider) { m_mapProvider = provider; } + void setZoom(int zoom) { m_defaultZoom = zoom; } + void setLatitude(double latitude) { m_defaultLatitude = latitude; } + void setLongitude(double longitude) { m_defaultLongitude = longitude; } + void setUseOpenGL(bool useOpenGL) { m_useOpenGL = useOpenGL; } + void setShowTileGridLines(bool showTileGridLines) { m_showTileGridLines = showTileGridLines; } + void setAccessMode(QString accessMode) { m_accessMode = accessMode; } + void setUseMemoryCache(bool useMemoryCache) { m_useMemoryCache = useMemoryCache; } + void setCacheLocation(QString cacheLocation); + void setUavSymbol(QString symbol){m_uavSymbol=symbol;} + void setMaxUpdateRate(int update_rate){m_maxUpdateRate = update_rate;} + +private: + QString m_mapProvider; + int m_defaultZoom; + double m_defaultLatitude; + double m_defaultLongitude; + bool m_useOpenGL; + bool m_showTileGridLines; + QString m_accessMode; + bool m_useMemoryCache; + QString m_cacheLocation; + QString m_uavSymbol; + int m_maxUpdateRate; +}; + +#endif // OPMAP_GADGETCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp index b6f07b9bd..2136a24d0 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.cpp @@ -1,133 +1,149 @@ -/** - ****************************************************************************** - * - * @file opmapgadgetoptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "opmapgadgetoptionspage.h" -#include "opmapgadgetconfiguration.h" -#include -#include -#include -#include -#include -#include -#include - -#include "opmapcontrol/opmapcontrol.h" -#include "utils/pathutils.h" -#include "ui_opmapgadgetoptionspage.h" - -// ********************************************* - -OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - m_config(config) -{ -} - -QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent) -{ - m_page = new Ui::OPMapGadgetOptionsPage(); - QWidget *w = new QWidget(parent); - m_page->setupUi(w); - - // populate the map provider combobox - m_page->providerComboBox->clear(); - m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes()); - - // populate the access mode combobox - m_page->accessModeComboBox->clear(); - m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes()); - - int index = m_page->providerComboBox->findText(m_config->mapProvider()); - index = (index >= 0) ? index : 0; - m_page->providerComboBox->setCurrentIndex(index); - - m_page->zoomSpinBox->setValue(m_config->zoom()); - m_page->latitudeSpinBox->setValue(m_config->latitude()); - m_page->longitudeSpinBox->setValue(m_config->longitude()); - - m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL()); - m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines()); - - index = m_page->accessModeComboBox->findText(m_config->accessMode()); - index = (index >= 0) ? index : 0; - m_page->accessModeComboBox->setCurrentIndex(index); - - m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache()); - - m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory); - m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory")); - m_page->lineEditCacheLocation->setPath(m_config->cacheLocation()); - - QDir dir(":/uavs/images/"); - QStringList list=dir.entryList(); - foreach(QString i,list) - { - QIcon icon(QPixmap(":/uavs/images/"+i)); - m_page->uavSymbolComboBox->addItem(icon,QString(),i); - } - for(int x=0;xuavSymbolComboBox->count();++x) - { - if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol()) - { - m_page->uavSymbolComboBox->setCurrentIndex(x); - } - } - - connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked())); - - return w; -} - -void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked() -{ - int index = m_page->accessModeComboBox->findText("ServerAndCache"); - index = (index >= 0) ? index : 0; - m_page->accessModeComboBox->setCurrentIndex(index); - - m_page->checkBoxUseMemoryCache->setChecked(true); - m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()); - -} - -void OPMapGadgetOptionsPage::apply() -{ - m_config->setMapProvider(m_page->providerComboBox->currentText()); - m_config->setZoom(m_page->zoomSpinBox->value()); - m_config->setLatitude(m_page->latitudeSpinBox->value()); - m_config->setLongitude(m_page->longitudeSpinBox->value()); - m_config->setUseOpenGL(m_page->checkBoxUseOpenGL->isChecked()); - m_config->setShowTileGridLines(m_page->checkBoxShowTileGridLines->isChecked()); - m_config->setAccessMode(m_page->accessModeComboBox->currentText()); - m_config->setUseMemoryCache(m_page->checkBoxUseMemoryCache->isChecked()); - m_config->setCacheLocation(m_page->lineEditCacheLocation->path()); - m_config->setUavSymbol(m_page->uavSymbolComboBox->itemData(m_page->uavSymbolComboBox->currentIndex()).toString()); -} - -void OPMapGadgetOptionsPage::finish() -{ - delete m_page; -} +/** + ****************************************************************************** + * + * @file opmapgadgetoptionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "opmapgadgetoptionspage.h" +#include "opmapgadgetconfiguration.h" +#include +#include +#include +#include +#include +#include +#include + +#include "opmapcontrol/opmapcontrol.h" +#include "utils/pathutils.h" +#include "ui_opmapgadgetoptionspage.h" + +// ********************************************* + +OPMapGadgetOptionsPage::OPMapGadgetOptionsPage(OPMapGadgetConfiguration *config, QObject *parent) : + IOptionsPage(parent), + m_config(config) +{ +} + +QWidget *OPMapGadgetOptionsPage::createPage(QWidget *parent) +{ + int index; + + m_page = new Ui::OPMapGadgetOptionsPage(); + QWidget *w = new QWidget(parent); + m_page->setupUi(w); + + // populate the map provider combobox + m_page->providerComboBox->clear(); + m_page->providerComboBox->addItems(mapcontrol::Helper::MapTypes()); + + // populate the access mode combobox + m_page->accessModeComboBox->clear(); + m_page->accessModeComboBox->addItems(mapcontrol::Helper::AccessModeTypes()); + + index = m_page->providerComboBox->findText(m_config->mapProvider()); + index = (index >= 0) ? index : 0; + m_page->providerComboBox->setCurrentIndex(index); + + // populate the map max update rate combobox + m_page->maxUpdateRateComboBox->clear(); + m_page->maxUpdateRateComboBox->addItem("100ms", 100); + m_page->maxUpdateRateComboBox->addItem("200ms", 200); + m_page->maxUpdateRateComboBox->addItem("500ms", 500); + m_page->maxUpdateRateComboBox->addItem("1 sec", 1000); + m_page->maxUpdateRateComboBox->addItem("2 sec", 2000); + m_page->maxUpdateRateComboBox->addItem("5 sec", 5000); + + index = m_page->maxUpdateRateComboBox->findData(m_config->maxUpdateRate()); + index = (index >= 0) ? index : 4; + m_page->maxUpdateRateComboBox->setCurrentIndex(index); + + m_page->zoomSpinBox->setValue(m_config->zoom()); + m_page->latitudeSpinBox->setValue(m_config->latitude()); + m_page->longitudeSpinBox->setValue(m_config->longitude()); + + m_page->checkBoxUseOpenGL->setChecked(m_config->useOpenGL()); + m_page->checkBoxShowTileGridLines->setChecked(m_config->showTileGridLines()); + + index = m_page->accessModeComboBox->findText(m_config->accessMode()); + index = (index >= 0) ? index : 0; + m_page->accessModeComboBox->setCurrentIndex(index); + + m_page->checkBoxUseMemoryCache->setChecked(m_config->useMemoryCache()); + + m_page->lineEditCacheLocation->setExpectedKind(Utils::PathChooser::Directory); + m_page->lineEditCacheLocation->setPromptDialogTitle(tr("Choose Cache Directory")); + m_page->lineEditCacheLocation->setPath(m_config->cacheLocation()); + + QDir dir(":/uavs/images/"); + QStringList list=dir.entryList(); + foreach(QString i,list) + { + QIcon icon(QPixmap(":/uavs/images/"+i)); + m_page->uavSymbolComboBox->addItem(icon,QString(),i); + } + for(int x=0;xuavSymbolComboBox->count();++x) + { + if(m_page->uavSymbolComboBox->itemData(x).toString()==m_config->uavSymbol()) + { + m_page->uavSymbolComboBox->setCurrentIndex(x); + } + } + + connect(m_page->pushButtonCacheDefaults, SIGNAL(clicked()), this, SLOT(on_pushButtonCacheDefaults_clicked())); + + return w; +} + +void OPMapGadgetOptionsPage::on_pushButtonCacheDefaults_clicked() +{ + int index = m_page->accessModeComboBox->findText("ServerAndCache"); + index = (index >= 0) ? index : 0; + m_page->accessModeComboBox->setCurrentIndex(index); + + m_page->checkBoxUseMemoryCache->setChecked(true); + m_page->lineEditCacheLocation->setPath(Utils::PathUtils().GetStoragePath() + "mapscache" + QDir::separator()); + +} + +void OPMapGadgetOptionsPage::apply() +{ + m_config->setMapProvider(m_page->providerComboBox->currentText()); + m_config->setZoom(m_page->zoomSpinBox->value()); + m_config->setLatitude(m_page->latitudeSpinBox->value()); + m_config->setLongitude(m_page->longitudeSpinBox->value()); + m_config->setUseOpenGL(m_page->checkBoxUseOpenGL->isChecked()); + m_config->setShowTileGridLines(m_page->checkBoxShowTileGridLines->isChecked()); + m_config->setAccessMode(m_page->accessModeComboBox->currentText()); + m_config->setUseMemoryCache(m_page->checkBoxUseMemoryCache->isChecked()); + m_config->setCacheLocation(m_page->lineEditCacheLocation->path()); + m_config->setUavSymbol(m_page->uavSymbolComboBox->itemData(m_page->uavSymbolComboBox->currentIndex()).toString()); + m_config->setMaxUpdateRate(m_page->maxUpdateRateComboBox->itemData(m_page->maxUpdateRateComboBox->currentIndex()).toInt()); +} + +void OPMapGadgetOptionsPage::finish() +{ + delete m_page; +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui index 9869ad38d..913678fae 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui @@ -30,7 +30,7 @@ 5 - + @@ -249,6 +249,19 @@ + + + + + + + Default Max Update Rate + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 46fc99e18..abc51de20 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -1,2371 +1,2451 @@ -/** - ****************************************************************************** - * - * @file opmapgadgetwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "opmapgadgetwidget.h" -#include "ui_opmap_widget.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "utils/stylehelper.h" -#include "utils/homelocationutil.h" -#include "utils/worldmagmodel.h" - -#include "uavtalk/telemetrymanager.h" - -#include "positionactual.h" -#include "homelocation.h" - -#define allow_manual_home_location_move - -// ************************************************************************************* - -#define deg_to_rad ((double)M_PI / 180.0) -#define rad_to_deg (180.0 / (double)M_PI) - -#define earth_mean_radius 6371 // kilometers - -#define max_digital_zoom 3 // maximum allowed digital zoom level - -const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000}; // meters - -const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds - -const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters - -// ************************************************************************************* - - -// ************************************************************************************* -// NOTE: go back to SVN REV 2137 and earlier to get back to experimental waypoint support. -// ************************************************************************************* - - -// constructor -OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) -{ - // ************** - - m_widget = NULL; - m_map = NULL; - findPlaceCompleter = NULL; - - m_mouse_waypoint = NULL; - - pm = NULL; - obm = NULL; - obum = NULL; - - prev_tile_number = 0; - - min_zoom = max_zoom = 0; - - m_map_mode = Normal_MapMode; - - telemetry_connected = false; - - context_menu_lat_lon = mouse_lat_lon = internals::PointLatLng(0, 0); - - setMouseTracking(true); - - pm = ExtensionSystem::PluginManager::instance(); - if (pm) - { - obm = pm->getObject(); - obum = pm->getObject(); - } - - // ************** - // get current location - - double latitude = 0; - double longitude = 0; - double altitude = 0; - - // current position - getUAVPosition(latitude, longitude, altitude); - - internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude); - - // ************** - // default home position - - home_position.coord = pos_lat_lon; - home_position.altitude = altitude; - home_position.locked = false; - - // ************** - // default magic waypoint params - - magic_waypoint.map_wp_item = NULL; - magic_waypoint.coord = home_position.coord; - magic_waypoint.altitude = altitude; - magic_waypoint.description = "Magic waypoint"; - magic_waypoint.locked = false; - magic_waypoint.time_seconds = 0; - magic_waypoint.hold_time_seconds = 0; - - // ************** - // create the widget that holds the user controls and the map - - m_widget = new Ui::OPMap_Widget(); - m_widget->setupUi(this); - - // ************** - // create the central map widget - - m_map = new mapcontrol::OPMapWidget(); // create the map object - - m_map->setFrameStyle(QFrame::NoFrame); // no border frame - m_map->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); // tile background - - m_map->configuration->DragButton = Qt::LeftButton; // use the left mouse button for map dragging - - m_widget->horizontalSliderZoom->setMinimum(m_map->MinZoom()); // - m_widget->horizontalSliderZoom->setMaximum(m_map->MaxZoom() + max_digital_zoom); // - - min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept - max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept - - m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions - m_map->SetFollowMouse(true); // we want a contiuous mouse position reading - - m_map->SetShowHome(true); // display the HOME position on the map - m_map->SetShowUAV(true); // display the UAV position on the map - - m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) - m_map->Home->SetShowSafeArea(true); // show the safe area - - m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds - m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters - - m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->UAV->SetTrailType(UAVTrailType::ByDistance); - - m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds - m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters - - m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed); -// m_map->GPS->SetTrailType(UAVTrailType::ByDistance); - - // ************** - - setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); - - QVBoxLayout *layout = new QVBoxLayout; - layout->setSpacing(0); - layout->setContentsMargins(0, 0, 0, 0); - layout->addWidget(m_map); - m_widget->mapWidget->setLayout(layout); - - // ************** - // set the user control options - - // TODO: this switch does not make sense, does it?? - - switch (m_map_mode) - { - case Normal_MapMode: - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); - break; - - case MagicWaypoint_MapMode: - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - showMagicWaypointControls(); - break; - - default: - m_map_mode = Normal_MapMode; - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - hideMagicWaypointControls(); - break; - } - - m_widget->labelUAVPos->setText("---"); - m_widget->labelMapPos->setText("---"); - m_widget->labelMousePos->setText("---"); - m_widget->labelMapZoom->setText("---"); - - - // Splitter is not used at the moment: - // m_widget->splitter->setCollapsible(1, false); - - // set the size of the collapsable widgets - //QList m_SizeList; - //m_SizeList << 0 << 0 << 0; - //m_widget->splitter->setSizes(m_SizeList); - - m_widget->progressBarMap->setMaximum(1); - -/* - #if defined(Q_OS_MAC) - #elif defined(Q_OS_WIN) - m_widget->comboBoxFindPlace->clear(); - loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); - m_widget->comboBoxFindPlace->setCurrentIndex(-1); - #else - #endif -*/ - - - // ************** - // map stuff - - connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals - connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals - connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals - connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals - connect(m_map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals - connect(m_map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed - connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed - connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error - connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals - connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); - connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); - connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); - connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); - - m_map->SetCurrentPosition(home_position.coord); // set the map position - m_map->Home->SetCoord(home_position.coord); // set the HOME position - m_map->UAV->SetUAVPos(home_position.coord, 0.0); // set the UAV position - m_map->GPS->SetUAVPos(home_position.coord, 0.0); // set the UAV position - - // ************** - // create various context menu (mouse right click menu) actions - - createActions(); - - // ************** - // connect to the UAVObject updates we require to become a bit aware of our environment: - - if (pm) - { - // Register for Home Location state changes - if (obm) - { - UAVDataObject *obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); - if (obj) - { - connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); - } - } - - // Listen to telemetry connection events - TelemetryManager *telMngr = pm->getObject(); - if (telMngr) - { - connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); - } - } - - // ************** - // create the desired timers - - m_updateTimer = new QTimer(); - m_updateTimer->setInterval(200); - connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updatePosition())); - m_updateTimer->start(); - - m_statusUpdateTimer = new QTimer(); - m_statusUpdateTimer->setInterval(100); - connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); - m_statusUpdateTimer->start(); - - // ************** - - m_map->setFocus(); -} - -// destructor -OPMapGadgetWidget::~OPMapGadgetWidget() -{ - if (m_map) - { - disconnect(m_map, 0, 0, 0); - m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit - m_map->SetShowUAV(false); // " " - } - - - // this destructor doesn't appear to be called at shutdown??? - -// #if defined(Q_OS_MAC) -// #elif defined(Q_OS_WIN) -// saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); -// #else -// #endif - - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - - - // todo: - - - delete wp->map_wp_item; - } - m_waypoint_list_mutex.unlock(); - m_waypoint_list.clear(); - - if (m_map) - { - delete m_map; - m_map = NULL; - } -} - -// ************************************************************************************* -// widget signals .. the mouseMoveEvent does not get called - don't yet know why - -void OPMapGadgetWidget::resizeEvent(QResizeEvent *event) -{ - qDebug("opmap: resizeEvent"); - - QWidget::resizeEvent(event); -} - -void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) -{ - qDebug("opmap: mouseMoveEvent"); - - if (m_widget && m_map) - { - } - - if (event->buttons() & Qt::LeftButton) - { -// QPoint pos = event->pos(); - } - - QWidget::mouseMoveEvent(event); -} - -void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) -{ // the user has right clicked on the map - create the pop-up context menu and display it - - QString s; - - if (!m_widget || !m_map) - return; - - if (event->reason() != QContextMenuEvent::Mouse) - return; // not a mouse click event - - // current mouse position - QPoint p = m_map->mapFromGlobal(event->globalPos()); - context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); -// context_menu_lat_lon = m_map->currentMousePosition(); - - if (!m_map->contentsRect().contains(p)) - return; // the mouse click was not on the map - - // show the mouse position - s = QString::number(context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(context_menu_lat_lon.Lng(), 'f', 7); - m_widget->labelMousePos->setText(s); - - // find out if we have a waypoint under the mouse cursor - QGraphicsItem *item = m_map->itemAt(p); - m_mouse_waypoint = qgraphicsitem_cast(item); - - // find out if the waypoint is locked (or not) - bool waypoint_locked = false; - if (m_mouse_waypoint) - waypoint_locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; - - // **************** - // Dynamically create the popup menu - - QMenu menu(this); - - menu.addAction(closeAct1); - - menu.addSeparator(); - - menu.addAction(reloadAct); - - menu.addSeparator(); - - switch (m_map_mode) - { - case Normal_MapMode: s = tr(" (Normal)"); break; - case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break; - default: s = tr(" (Unknown)"); break; - } - for (int i = 0; i < mapModeAct.count(); i++) - { // set the menu to checked (or not) - QAction *act = mapModeAct.at(i); - if (!act) continue; - if (act->data().toInt() == (int)m_map_mode) - act->setChecked(true); - } - QMenu mapModeSubMenu(tr("Map mode") + s, this); - for (int i = 0; i < mapModeAct.count(); i++) - mapModeSubMenu.addAction(mapModeAct.at(i)); - menu.addMenu(&mapModeSubMenu); - - menu.addSeparator(); - - QMenu copySubMenu(tr("Copy"), this); - copySubMenu.addAction(copyMouseLatLonToClipAct); - copySubMenu.addAction(copyMouseLatToClipAct); - copySubMenu.addAction(copyMouseLonToClipAct); - menu.addMenu(©SubMenu); - - menu.addSeparator(); - - /* - menu.addAction(findPlaceAct); - - menu.addSeparator(); - */ - - menu.addAction(showSafeAreaAct); - QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); - for (int i = 0; i < safeAreaAct.count(); i++) - safeAreaSubMenu.addAction(safeAreaAct.at(i)); - menu.addMenu(&safeAreaSubMenu); - - menu.addSeparator(); - - menu.addAction(showCompassAct); - - menu.addAction(showDiagnostics); - - menu.addSeparator()->setText(tr("Zoom")); - - menu.addAction(zoomInAct); - menu.addAction(zoomOutAct); - - QMenu zoomSubMenu(tr("&Zoom ") + "(" + QString::number(m_map->ZoomTotal()) + ")", this); - for (int i = 0; i < zoomAct.count(); i++) - zoomSubMenu.addAction(zoomAct.at(i)); - menu.addMenu(&zoomSubMenu); - - menu.addSeparator(); - - menu.addAction(goMouseClickAct); - - menu.addSeparator()->setText(tr("HOME")); - - menu.addAction(setHomeAct); - menu.addAction(showHomeAct); - menu.addAction(goHomeAct); - - // **** - // uav trails - - menu.addSeparator()->setText(tr("UAV Trail")); - - QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this); - for (int i = 0; i < uavTrailTypeAct.count(); i++) - uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i)); - menu.addMenu(&uavTrailTypeSubMenu); - - QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this); - for (int i = 0; i < uavTrailTimeAct.count(); i++) - uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i)); - menu.addMenu(&uavTrailTimeSubMenu); - - QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this); - for (int i = 0; i < uavTrailDistanceAct.count(); i++) - uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i)); - menu.addMenu(&uavTrailDistanceSubMenu); - - menu.addAction(showTrailAct); - - menu.addAction(showTrailLineAct); - - menu.addAction(clearUAVtrailAct); - - // **** - - menu.addSeparator()->setText(tr("UAV")); - - menu.addAction(showUAVAct); - menu.addAction(followUAVpositionAct); - menu.addAction(followUAVheadingAct); - menu.addAction(goUAVAct); - - // ********* - - switch (m_map_mode) - { - case Normal_MapMode: - // only show the waypoint stuff if not in 'magic waypoint' mode - /* - menu.addSeparator()->setText(tr("Waypoints")); - - menu.addAction(wayPointEditorAct); - menu.addAction(addWayPointAct); - - if (m_mouse_waypoint) - { // we have a waypoint under the mouse - menu.addAction(editWayPointAct); - - lockWayPointAct->setChecked(waypoint_locked); - menu.addAction(lockWayPointAct); - - if (!waypoint_locked) - menu.addAction(deleteWayPointAct); - } - - m_waypoint_list_mutex.lock(); - if (m_waypoint_list.count() > 0) - menu.addAction(clearWayPointsAct); // we have waypoints - m_waypoint_list_mutex.unlock(); - */ - - break; - - case MagicWaypoint_MapMode: - menu.addSeparator()->setText(tr("Waypoints")); - menu.addAction(homeMagicWaypointAct); - break; - } - - // ********* - - menu.addSeparator(); - - menu.addAction(closeAct2); - - menu.exec(event->globalPos()); // popup the menu - - // **************** -} - -void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event) -{ - qDebug() << "opmap: keyPressEvent, key =" << event->key() << endl; - - switch (event->key()) - { - case Qt::Key_Escape: - break; - - case Qt::Key_F1: - break; - - case Qt::Key_F2: - break; - - case Qt::Key_Up: - break; - - case Qt::Key_Down: - break; - - case Qt::Key_Left: - break; - - case Qt::Key_Right: - break; - - case Qt::Key_PageUp: - break; - - case Qt::Key_PageDown: - break; - } -} - -// ************************************************************************************* -// timer signals - - -/** - Updates the UAV position on the map. It is called every 200ms - by a timer. - - TODO: consider updating upon object update, not timer. - */ -void OPMapGadgetWidget::updatePosition() -{ - if (!m_widget || !m_map) - return; - - QMutexLocker locker(&m_map_mutex); -//Pip I'm sorry, I know this was here with a purpose vvv - //if (!telemetry_connected) - // return; - - double latitude; - double longitude; - double altitude; - - // get current UAV position - if (!getUAVPosition(latitude, longitude, altitude)) - return; - - // get current UAV heading - float yaw = getUAV_Yaw(); - - internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position - float uav_heading_degrees = yaw; // current UAV heading - float uav_altitude_meters = altitude; // current UAV height - float uav_ground_speed_meters_per_second = 0; //data.Groundspeed; // current UAV ground speed - - // display the UAV lat/lon position - QString str = - "lat: " + QString::number(uav_pos.Lat(), 'f', 7) + - " lon: " + QString::number(uav_pos.Lng(), 'f', 7) + - " " + QString::number(uav_heading_degrees, 'f', 1) + "deg" + - " " + QString::number(uav_altitude_meters, 'f', 1) + "m" + - " " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s"; - m_widget->labelUAVPos->setText(str); - - m_map->UAV->SetUAVPos(uav_pos, uav_altitude_meters); // set the maps UAV position - // qDebug()<<"UAVPOSITION"<UAV->SetUAVHeading(uav_heading_degrees); // set the maps UAV heading - - if (!getGPSPosition(latitude, longitude, altitude)) - return; - - uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position - m_map->GPS->SetUAVPos(uav_pos, uav_altitude_meters); // set the maps UAV position - m_map->GPS->SetUAVHeading(uav_heading_degrees); // set the maps UAV heading -} - -/** - Update plugin behaviour based on mouse position; Called every few ms by a - timer. - */ -void OPMapGadgetWidget::updateMousePos() -{ - if (!m_widget || !m_map) - return; - - QMutexLocker locker(&m_map_mutex); - - QPoint p = m_map->mapFromGlobal(QCursor::pos()); - internals::PointLatLng lat_lon = m_map->GetFromLocalToLatLng(p); // fetch the current lat/lon mouse position - - if (!m_map->contentsRect().contains(p)) - return; // the mouse is not on the map - -// internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position - - QGraphicsItem *item = m_map->itemAt(p); - - // find out if we are over the home position - mapcontrol::HomeItem *home = qgraphicsitem_cast(item); - - // find out if we are over the UAV - mapcontrol::UAVItem *uav = qgraphicsitem_cast(item); - - // find out if we have a waypoint under the mouse cursor - mapcontrol::WayPointItem *wp = qgraphicsitem_cast(item); - - if (mouse_lat_lon == lat_lon) - return; // the mouse has not moved - - mouse_lat_lon = lat_lon; // yes it has! - - internals::PointLatLng home_lat_lon = m_map->Home->Coord(); - - QString s = QString::number(mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(mouse_lat_lon.Lng(), 'f', 7); - if (wp) - { - s += " wp[" + QString::number(wp->Number()) + "]"; - - double dist = distance(home_lat_lon, wp->Coord()); - double bear = bearing(home_lat_lon, wp->Coord()); - s += " " + QString::number(dist * 1000, 'f', 1) + "m"; - s += " " + QString::number(bear, 'f', 1) + "deg"; - } - else - if (home) - { - s += " home"; - - double dist = distance(home_lat_lon, mouse_lat_lon); - double bear = bearing(home_lat_lon, mouse_lat_lon); - s += " " + QString::number(dist * 1000, 'f', 1) + "m"; - s += " " + QString::number(bear, 'f', 1) + "deg"; - } - else - if (uav) - { - s += " uav"; - - double latitude; - double longitude; - double altitude; - if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position - { - internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); - -// double dist = distance(home_lat_lon, uav_pos); -// double bear = bearing(home_lat_lon, uav_pos); -// s += " " + QString::number(dist * 1000, 'f', 1) + "m"; -// s += " " + QString::number(bear, 'f', 1) + "deg"; - } - } - m_widget->labelMousePos->setText(s); -} - -// ************************************************************************************* -// map signals - - -/** - Update the Plugin UI to reflect a change in zoom level - */ -void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) -{ - if (!m_widget || !m_map) - return; - - QString s = "tot:" + QString::number(zoomt, 'f', 1) + " rea:" + QString::number(zoom, 'f', 1) + " dig:" + QString::number(zoomd, 'f', 1); - m_widget->labelMapZoom->setText(s); - - int i_zoom = (int)(zoomt + 0.5); - - if (i_zoom < min_zoom) i_zoom = min_zoom; - else - if (i_zoom > max_zoom) i_zoom = max_zoom; - - if (m_widget->horizontalSliderZoom->value() != i_zoom) - m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position - - int index0_zoom = i_zoom - min_zoom; // zoom level starting at index level '0' - if (index0_zoom < zoomAct.count()) - zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level -} - -void OPMapGadgetWidget::OnMapDrag() -{ -} - -void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) -{ - if (!m_widget || !m_map) - return; - - QString coord_str = QString::number(point.Lat(), 'f', 7) + " " + QString::number(point.Lng(), 'f', 7) + " "; - m_widget->labelMapPos->setText(coord_str); -} - -/** - Update the progress bar while there are still tiles to load - */ -void OPMapGadgetWidget::OnTilesStillToLoad(int number) -{ - if (!m_widget || !m_map) - return; - -// if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) -// m_widget->progressBarMap->setMaximum(number); - - if (m_widget->progressBarMap->maximum() < number) - m_widget->progressBarMap->setMaximum(number); - - m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar - -// m_widget->labelNumTilesToLoad->setText(QString::number(number)); - - prev_tile_number = number; -} - -/** - Show the progress bar as soon as the map lib starts downloading - */ -void OPMapGadgetWidget::OnTileLoadStart() -{ - if (!m_widget || !m_map) - return; - - m_widget->progressBarMap->setVisible(true); -} - -/** - Hide the progress bar once the map lib has finished downloading - - TODO: somehow this gets called before tile load is actually complete? - */ - -void OPMapGadgetWidget::OnTileLoadComplete() -{ - if (!m_widget || !m_map) - return; - - m_widget->progressBarMap->setVisible(false); -} - -void OPMapGadgetWidget::OnMapZoomChanged() -{ -} - -void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type) -{ - Q_UNUSED(type); -} - -void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos) -{ - Q_UNUSED(zoom); - Q_UNUSED(pos); -} - -void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumber, WayPointItem *waypoint) -{ - Q_UNUSED(oldnumber); - Q_UNUSED(newnumber); - Q_UNUSED(waypoint); -} - -void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) -{ -// qDebug("opmap: WPValuesChanged"); - - switch (m_map_mode) - { - case Normal_MapMode: - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { // search for the waypoint in our own waypoint list and update it - if (!wp) continue; - if (!wp->map_wp_item) continue; - if (wp->map_wp_item != waypoint) continue; - // found the waypoint in our list - wp->coord = waypoint->Coord(); - wp->altitude = waypoint->Altitude(); - wp->description = waypoint->Description(); - break; - } - m_waypoint_list_mutex.unlock(); - break; - - case MagicWaypoint_MapMode: - // update our copy of the magic waypoint - if (magic_waypoint.map_wp_item && magic_waypoint.map_wp_item == waypoint) - { - magic_waypoint.coord = waypoint->Coord(); - magic_waypoint.altitude = waypoint->Altitude(); - magic_waypoint.description = waypoint->Description(); - - // move the UAV to the magic waypoint position - // moveToMagicWaypointPosition(); - } - break; - } - -} - -/** - TODO: slot to do something upon Waypoint insertion - */ -void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint) -{ - Q_UNUSED(number); - Q_UNUSED(waypoint); -} - -/** - TODO: slot to do something upon Waypoint deletion - */ -void OPMapGadgetWidget::WPDeleted(int const &number) -{ - Q_UNUSED(number); -} - - -void OPMapGadgetWidget::on_toolButtonZoomP_clicked() -{ - QMutexLocker locker(&m_map_mutex); - zoomIn(); -} - -void OPMapGadgetWidget::on_toolButtonZoomM_clicked() -{ - QMutexLocker locker(&m_map_mutex); - zoomOut(); -} - -void OPMapGadgetWidget::on_toolButtonMapHome_clicked() -{ - QMutexLocker locker(&m_map_mutex); - goHome(); -} - -void OPMapGadgetWidget::on_toolButtonMapUAV_clicked() -{ - if (!m_widget || !m_map) - return; - - QMutexLocker locker(&m_map_mutex); - - followUAVpositionAct->toggle(); -} - -void OPMapGadgetWidget::on_toolButtonMapUAVheading_clicked() -{ - if (!m_widget || !m_map) - return; - - followUAVheadingAct->toggle(); -} - -void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position) -{ - if (!m_widget || !m_map) - return; - - QMutexLocker locker(&m_map_mutex); - - setZoom(position); -} - - -void OPMapGadgetWidget::on_toolButtonNormalMapMode_clicked() -{ - setMapMode(Normal_MapMode); -} - -void OPMapGadgetWidget::on_toolButtonMagicWaypointMapMode_clicked() -{ - setMapMode(MagicWaypoint_MapMode); -} - -void OPMapGadgetWidget::on_toolButtonHomeWaypoint_clicked() -{ - homeMagicWaypoint(); -} - -void OPMapGadgetWidget::on_toolButtonMoveToWP_clicked() -{ - moveToMagicWaypointPosition(); -} - -// ************************************************************************************* -// public slots - -void OPMapGadgetWidget::onTelemetryConnect() -{ - telemetry_connected = true; - - if (!obum) return; - - bool set; - double LLA[3]; - - // *********************** - // fetch the home location - - if (obum->getHomeLocation(set, LLA) < 0) - return; // error - - setHome(internals::PointLatLng(LLA[0], LLA[1])); - - if (m_map) - m_map->SetCurrentPosition(home_position.coord); // set the map position - - // *********************** -} - -void OPMapGadgetWidget::onTelemetryDisconnect() -{ - telemetry_connected = false; -} - -// Updates the Home position icon whenever the HomePosition object is updated -void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) -{ - if (!hp) - return; - - double lat = hp->getField("Latitude")->getDouble() * 1e-7; - double lon = hp->getField("Longitude")->getDouble() * 1e-7; - setHome(internals::PointLatLng(lat, lon)); -} - -// ************************************************************************************* -// public functions - -/** - Sets the home position on the map widget - */ -void OPMapGadgetWidget::setHome(QPointF pos) -{ - if (!m_widget || !m_map) - return; - - double latitude = pos.x(); - double longitude = pos.y(); - - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; - - if (longitude != longitude) longitude = 0; // nan detection - else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; - - setHome(internals::PointLatLng(latitude, longitude)); -} - -/** - Sets the home position on the map widget - */ -void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) -{ - if (!m_widget || !m_map) - return; - - if (pos_lat_lon.Lat() != pos_lat_lon.Lat() || pos_lat_lon.Lng() != pos_lat_lon.Lng()) - return;; // nan prevention - - double latitude = pos_lat_lon.Lat(); - double longitude = pos_lat_lon.Lng(); - - if (latitude != latitude) latitude = 0; // nan detection - else - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; - - if (longitude != longitude) longitude = 0; // nan detection - else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; - - // ********* - - home_position.coord = internals::PointLatLng(latitude, longitude); - - m_map->Home->SetCoord(home_position.coord); - m_map->Home->RefreshPos(); - - // move the magic waypoint to keep it within the safe area boundry - keepMagicWaypointWithInSafeArea(); -} - - -/** - Centers the map over the home position - */ -void OPMapGadgetWidget::goHome() -{ - if (!m_widget || !m_map) - return; - - followUAVpositionAct->setChecked(false); - - internals::PointLatLng home_pos = home_position.coord; // get the home location - m_map->SetCurrentPosition(home_pos); // center the map onto the home location -} - - -void OPMapGadgetWidget::zoomIn() -{ - if (!m_widget || !m_map) - return; - - int zoom = m_map->ZoomTotal() + 1; - - if (zoom < min_zoom) zoom = min_zoom; - else - if (zoom > max_zoom) zoom = max_zoom; - - m_map->SetZoom(zoom); -} - -void OPMapGadgetWidget::zoomOut() -{ - if (!m_widget || !m_map) - return; - - int zoom = m_map->ZoomTotal() - 1; - - if (zoom < min_zoom) zoom = min_zoom; - else - if (zoom > max_zoom) zoom = max_zoom; - - m_map->SetZoom(zoom); -} - -void OPMapGadgetWidget::setZoom(int zoom) -{ - if (!m_widget || !m_map) - return; - - if (zoom < min_zoom) zoom = min_zoom; - else - if (zoom > max_zoom) zoom = max_zoom; - - internals::MouseWheelZoomType::Types zoom_type = m_map->GetMouseWheelZoomType(); - m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::ViewCenter); - - m_map->SetZoom(zoom); - - m_map->SetMouseWheelZoomType(zoom_type); -} - -void OPMapGadgetWidget::setPosition(QPointF pos) -{ - if (!m_widget || !m_map) - return; - - double latitude = pos.y(); - double longitude = pos.x(); - - if (latitude != latitude || longitude != longitude) - return; // nan prevention - - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; - - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; - - m_map->SetCurrentPosition(internals::PointLatLng(latitude, longitude)); -} - -void OPMapGadgetWidget::setMapProvider(QString provider) -{ - if (!m_widget || !m_map) - return; - - m_map->SetMapType(mapcontrol::Helper::MapTypeFromString(provider)); -} - -void OPMapGadgetWidget::setAccessMode(QString accessMode) -{ - if (!m_widget || !m_map) - return; - - m_map->configuration->SetAccessMode(mapcontrol::Helper::AccessModeFromString(accessMode)); -} - -void OPMapGadgetWidget::setUseOpenGL(bool useOpenGL) -{ - if (!m_widget || !m_map) - return; - - m_map->SetUseOpenGL(useOpenGL); -} - -void OPMapGadgetWidget::setShowTileGridLines(bool showTileGridLines) -{ - if (!m_widget || !m_map) - return; - - m_map->SetShowTileGridLines(showTileGridLines); -} - -void OPMapGadgetWidget::setUseMemoryCache(bool useMemoryCache) -{ - if (!m_widget || !m_map) - return; - - m_map->configuration->SetUseMemoryCache(useMemoryCache); -} - -void OPMapGadgetWidget::setCacheLocation(QString cacheLocation) -{ - if (!m_widget || !m_map) - return; - - cacheLocation = cacheLocation.simplified(); // remove any surrounding spaces - - if (cacheLocation.isEmpty()) return; - -// #if defined(Q_WS_WIN) -// if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; -// #elif defined(Q_WS_X11) - if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #elif defined(Q_WS_MAC) -// if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); -// #endif - - QDir dir; - if (!dir.exists(cacheLocation)) - if (!dir.mkpath(cacheLocation)) - return; - -// qDebug() << "opmap: map cache dir: " << cacheLocation; - - m_map->configuration->SetCacheLocation(cacheLocation); -} - -void OPMapGadgetWidget::setMapMode(opMapModeType mode) -{ - if (!m_widget || !m_map) - return; - - if (mode != Normal_MapMode && mode != MagicWaypoint_MapMode) - mode = Normal_MapMode; // fix error - - if (m_map_mode == mode) - { // no change in map mode - switch (mode) - { // make sure the UI buttons are set correctly - case Normal_MapMode: - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - break; - case MagicWaypoint_MapMode: - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - break; - } - return; - } - - switch (mode) - { - case Normal_MapMode: - m_map_mode = Normal_MapMode; - - m_widget->toolButtonMagicWaypointMapMode->setChecked(false); - m_widget->toolButtonNormalMapMode->setChecked(true); - - hideMagicWaypointControls(); - - // delete the magic waypoint from the map - if (magic_waypoint.map_wp_item) - { - magic_waypoint.coord = magic_waypoint.map_wp_item->Coord(); - magic_waypoint.altitude = magic_waypoint.map_wp_item->Altitude(); - magic_waypoint.description = magic_waypoint.map_wp_item->Description(); - magic_waypoint.map_wp_item = NULL; - } - m_map->WPDeleteAll(); - - // restore the normal waypoints on the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - if (!wp->map_wp_item) continue; - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - m_waypoint_list_mutex.unlock(); - - break; - - case MagicWaypoint_MapMode: - m_map_mode = MagicWaypoint_MapMode; - - m_widget->toolButtonNormalMapMode->setChecked(false); - m_widget->toolButtonMagicWaypointMapMode->setChecked(true); - - showMagicWaypointControls(); - - // delete the normal waypoints from the map - m_waypoint_list_mutex.lock(); - foreach (t_waypoint *wp, m_waypoint_list) - { - if (!wp) continue; - if (!wp->map_wp_item) continue; - wp->coord = wp->map_wp_item->Coord(); - wp->altitude = wp->map_wp_item->Altitude(); - wp->description = wp->map_wp_item->Description(); - wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0; - wp->map_wp_item = NULL; - } - m_map->WPDeleteAll(); - m_waypoint_list_mutex.unlock(); - - // restore the magic waypoint on the map - magic_waypoint.map_wp_item = m_map->WPCreate(magic_waypoint.coord, magic_waypoint.altitude, magic_waypoint.description); - magic_waypoint.map_wp_item->setZValue(10 + magic_waypoint.map_wp_item->Number()); - magic_waypoint.map_wp_item->SetShowNumber(false); - magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); - - break; - } -} - -// ************************************************************************************* -// Context menu stuff - -void OPMapGadgetWidget::createActions() -{ - if (!m_widget) - return; - - // *********************** - // create menu actions - - closeAct1 = new QAction(tr("Close menu"), this); - closeAct1->setStatusTip(tr("Close the context menu")); - - closeAct2 = new QAction(tr("Close menu"), this); - closeAct2->setStatusTip(tr("Close the context menu")); - - reloadAct = new QAction(tr("&Reload map"), this); - reloadAct->setShortcut(tr("F5")); - reloadAct->setStatusTip(tr("Reload the map tiles")); - connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); - - copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this); - copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard")); - connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered())); - - copyMouseLatToClipAct = new QAction(tr("Mouse latitude"), this); - copyMouseLatToClipAct->setStatusTip(tr("Copy the mouse latitude to the clipboard")); - connect(copyMouseLatToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatToClipAct_triggered())); - - copyMouseLonToClipAct = new QAction(tr("Mouse longitude"), this); - copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard")); - connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered())); - - /* - findPlaceAct = new QAction(tr("&Find place"), this); - findPlaceAct->setShortcut(tr("Ctrl+F")); - findPlaceAct->setStatusTip(tr("Find a location")); - connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered())); - */ - - showCompassAct = new QAction(tr("Show compass"), this); - showCompassAct->setStatusTip(tr("Show/Hide the compass")); - showCompassAct->setCheckable(true); - showCompassAct->setChecked(true); - connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(onShowCompassAct_toggled(bool))); - - showDiagnostics = new QAction(tr("Show Diagnostics"), this); - showDiagnostics->setStatusTip(tr("Show/Hide the diagnostics")); - showDiagnostics->setCheckable(true); - showDiagnostics->setChecked(false); - connect(showDiagnostics, SIGNAL(toggled(bool)), this, SLOT(onShowDiagnostics_toggled(bool))); - - showHomeAct = new QAction(tr("Show Home"), this); - showHomeAct->setStatusTip(tr("Show/Hide the Home location")); - showHomeAct->setCheckable(true); - showHomeAct->setChecked(true); - connect(showHomeAct, SIGNAL(toggled(bool)), this, SLOT(onShowHomeAct_toggled(bool))); - - showUAVAct = new QAction(tr("Show UAV"), this); - showUAVAct->setStatusTip(tr("Show/Hide the UAV")); - showUAVAct->setCheckable(true); - showUAVAct->setChecked(true); - connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); - - zoomInAct = new QAction(tr("Zoom &In"), this); - zoomInAct->setShortcut(Qt::Key_PageUp); - zoomInAct->setStatusTip(tr("Zoom the map in")); - connect(zoomInAct, SIGNAL(triggered()), this, SLOT(onGoZoomInAct_triggered())); - - zoomOutAct = new QAction(tr("Zoom &Out"), this); - zoomOutAct->setShortcut(Qt::Key_PageDown); - zoomOutAct->setStatusTip(tr("Zoom the map out")); - connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(onGoZoomOutAct_triggered())); - - goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this); - goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse")); - connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(onGoMouseClickAct_triggered())); - - setHomeAct = new QAction(tr("Set the home location"), this); - setHomeAct->setStatusTip(tr("Set the home location to where you clicked")); - #if !defined(allow_manual_home_location_move) - setHomeAct->setEnabled(false); - #endif - connect(setHomeAct, SIGNAL(triggered()), this, SLOT(onSetHomeAct_triggered())); - - goHomeAct = new QAction(tr("Go to &Home location"), this); - goHomeAct->setShortcut(tr("Ctrl+H")); - goHomeAct->setStatusTip(tr("Center the map onto the home location")); - connect(goHomeAct, SIGNAL(triggered()), this, SLOT(onGoHomeAct_triggered())); - - goUAVAct = new QAction(tr("Go to &UAV location"), this); - goUAVAct->setShortcut(tr("Ctrl+U")); - goUAVAct->setStatusTip(tr("Center the map onto the UAV location")); - connect(goUAVAct, SIGNAL(triggered()), this, SLOT(onGoUAVAct_triggered())); - - followUAVpositionAct = new QAction(tr("Follow UAV position"), this); - followUAVpositionAct->setShortcut(tr("Ctrl+F")); - followUAVpositionAct->setStatusTip(tr("Keep the map centered onto the UAV")); - followUAVpositionAct->setCheckable(true); - followUAVpositionAct->setChecked(false); - connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVpositionAct_toggled(bool))); - - followUAVheadingAct = new QAction(tr("Follow UAV heading"), this); - followUAVheadingAct->setShortcut(tr("Ctrl+F")); - followUAVheadingAct->setStatusTip(tr("Keep the map rotation to the UAV heading")); - followUAVheadingAct->setCheckable(true); - followUAVheadingAct->setChecked(false); - connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); - - /* - TODO: Waypoint support is disabled for v1.0 - */ - - /* - wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); - wayPointEditorAct->setShortcut(tr("Ctrl+W")); - wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); - wayPointEditorAct->setEnabled(false); // temporary - connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); - - addWayPointAct = new QAction(tr("&Add waypoint"), this); - addWayPointAct->setShortcut(tr("Ctrl+A")); - addWayPointAct->setStatusTip(tr("Add waypoint")); - connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); - - editWayPointAct = new QAction(tr("&Edit waypoint"), this); - editWayPointAct->setShortcut(tr("Ctrl+E")); - editWayPointAct->setStatusTip(tr("Edit waypoint")); - connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(onEditWayPointAct_triggered())); - - lockWayPointAct = new QAction(tr("&Lock waypoint"), this); - lockWayPointAct->setStatusTip(tr("Lock/Unlock a waypoint")); - lockWayPointAct->setCheckable(true); - lockWayPointAct->setChecked(false); - connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered())); - - deleteWayPointAct = new QAction(tr("&Delete waypoint"), this); - deleteWayPointAct->setShortcut(tr("Ctrl+D")); - deleteWayPointAct->setStatusTip(tr("Delete waypoint")); - connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered())); - - clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); - clearWayPointsAct->setShortcut(tr("Ctrl+C")); - clearWayPointsAct->setStatusTip(tr("Clear waypoints")); - connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); - */ - - homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); - homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position")); - connect(homeMagicWaypointAct, SIGNAL(triggered()), this, SLOT(onHomeMagicWaypointAct_triggered())); - - mapModeActGroup = new QActionGroup(this); - connect(mapModeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMapModeActGroup_triggered(QAction *))); - mapModeAct.clear(); - { - QAction *map_mode_act; - - map_mode_act = new QAction(tr("Normal"), mapModeActGroup); - map_mode_act->setCheckable(true); - map_mode_act->setChecked(m_map_mode == Normal_MapMode); - map_mode_act->setData((int)Normal_MapMode); - mapModeAct.append(map_mode_act); - - map_mode_act = new QAction(tr("Magic Waypoint"), mapModeActGroup); - map_mode_act->setCheckable(true); - map_mode_act->setChecked(m_map_mode == MagicWaypoint_MapMode); - map_mode_act->setData((int)MagicWaypoint_MapMode); - mapModeAct.append(map_mode_act); - } - - zoomActGroup = new QActionGroup(this); - connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onZoomActGroup_triggered(QAction *))); - zoomAct.clear(); - for (int i = min_zoom; i <= max_zoom; i++) - { - QAction *zoom_act = new QAction(QString::number(i), zoomActGroup); - zoom_act->setCheckable(true); - zoom_act->setData(i); - zoomAct.append(zoom_act); - } - - // ***** - // safe area - - showSafeAreaAct = new QAction(tr("Show Safe Area"), this); - showSafeAreaAct->setStatusTip(tr("Show/Hide the Safe Area around the home location")); - showSafeAreaAct->setCheckable(true); - showSafeAreaAct->setChecked(m_map->Home->ShowSafeArea()); - connect(showSafeAreaAct, SIGNAL(toggled(bool)), this, SLOT(onShowSafeAreaAct_toggled(bool))); - - safeAreaActGroup = new QActionGroup(this); - connect(safeAreaActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onSafeAreaActGroup_triggered(QAction *))); - safeAreaAct.clear(); - for (int i = 0; i < (int)(sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0])); i++) - { - int safeArea = safe_area_radius_list[i]; - QAction *safeArea_act = new QAction(QString::number(safeArea) + "m", safeAreaActGroup); - safeArea_act->setCheckable(true); - safeArea_act->setChecked(safeArea == m_map->Home->SafeArea()); - safeArea_act->setData(safeArea); - safeAreaAct.append(safeArea_act); - } - - // ***** - // UAV trail - - uavTrailTypeActGroup = new QActionGroup(this); - connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *))); - uavTrailTypeAct.clear(); - QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); - for (int i = 0; i < uav_trail_type_list.count(); i++) - { - mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[i]); - QAction *uavTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(uav_trail_type), uavTrailTypeActGroup); - uavTrailType_act->setCheckable(true); - uavTrailType_act->setChecked(uav_trail_type == m_map->UAV->GetTrailType()); - uavTrailType_act->setData(i); - uavTrailTypeAct.append(uavTrailType_act); - } - - showTrailAct = new QAction(tr("Show Trail dots"), this); - showTrailAct->setStatusTip(tr("Show/Hide the Trail dots")); - showTrailAct->setCheckable(true); - showTrailAct->setChecked(true); - connect(showTrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailAct_toggled(bool))); - - showTrailLineAct = new QAction(tr("Show Trail lines"), this); - showTrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); - showTrailLineAct->setCheckable(true); - showTrailLineAct->setChecked(true); - connect(showTrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailLineAct_toggled(bool))); - - clearUAVtrailAct = new QAction(tr("Clear UAV trail"), this); - clearUAVtrailAct->setStatusTip(tr("Clear the UAV trail")); - connect(clearUAVtrailAct, SIGNAL(triggered()), this, SLOT(onClearUAVtrailAct_triggered())); - - uavTrailTimeActGroup = new QActionGroup(this); - connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *))); - uavTrailTimeAct.clear(); - for (int i = 0; i < (int)(sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0])); i++) - { - int uav_trail_time = uav_trail_time_list[i]; - QAction *uavTrailTime_act = new QAction(QString::number(uav_trail_time) + " sec", uavTrailTimeActGroup); - uavTrailTime_act->setCheckable(true); - uavTrailTime_act->setChecked(uav_trail_time == m_map->UAV->TrailTime()); - uavTrailTime_act->setData(uav_trail_time); - uavTrailTimeAct.append(uavTrailTime_act); - } - - uavTrailDistanceActGroup = new QActionGroup(this); - connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *))); - uavTrailDistanceAct.clear(); - for (int i = 0; i < (int)(sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0])); i++) - { - int uav_trail_distance = uav_trail_distance_list[i]; - QAction *uavTrailDistance_act = new QAction(QString::number(uav_trail_distance) + " meters", uavTrailDistanceActGroup); - uavTrailDistance_act->setCheckable(true); - uavTrailDistance_act->setChecked(uav_trail_distance == m_map->UAV->TrailDistance()); - uavTrailDistance_act->setData(uav_trail_distance); - uavTrailDistanceAct.append(uavTrailDistance_act); - } - - // ***** - - // *********************** -} - -void OPMapGadgetWidget::onReloadAct_triggered() -{ - if (!m_widget || !m_map) - return; - - m_map->ReloadMap(); -} - -void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() -{ -// QClipboard *clipboard = qApp->clipboard(); - QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); -} - -void OPMapGadgetWidget::onCopyMouseLatToClipAct_triggered() -{ -// QClipboard *clipboard = qApp->clipboard(); - QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard); -} - -void OPMapGadgetWidget::onCopyMouseLonToClipAct_triggered() -{ -// QClipboard *clipboard = qApp->clipboard(); - QClipboard *clipboard = QApplication::clipboard(); - clipboard->setText(QString::number(context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); -} - - -void OPMapGadgetWidget::onShowCompassAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->SetShowCompass(show); -} - -void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->SetShowDiagnostics(show); -} - -void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->Home->setVisible(show); -} - -void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->UAV->setVisible(show); - m_map->GPS->setVisible(show); -} - -void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->UAV->SetShowTrail(show); - m_map->GPS->SetShowTrail(show); -} - -void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->UAV->SetShowTrailLine(show); - m_map->GPS->SetShowTrailLine(show); -} - -void OPMapGadgetWidget::onMapModeActGroup_triggered(QAction *action) -{ - if (!m_widget || !m_map || !action) - return; - - opMapModeType mode = (opMapModeType)action->data().toInt(); - - setMapMode(mode); -} - -void OPMapGadgetWidget::onGoZoomInAct_triggered() -{ - zoomIn(); -} - -void OPMapGadgetWidget::onGoZoomOutAct_triggered() -{ - zoomOut(); -} - -void OPMapGadgetWidget::onZoomActGroup_triggered(QAction *action) -{ - if (!m_widget || !action) - return; - - setZoom(action->data().toInt()); -} - -void OPMapGadgetWidget::onGoMouseClickAct_triggered() -{ - if (!m_widget || !m_map) - return; - - m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position -} - -void OPMapGadgetWidget::onSetHomeAct_triggered() -{ - if (!m_widget || !m_map) - return; - - setHome(context_menu_lat_lon); - - setHomeLocationObject(); // update the HomeLocation UAVObject -} - -void OPMapGadgetWidget::onGoHomeAct_triggered() -{ - if (!m_widget || !m_map) - return; - - goHome(); -} - -void OPMapGadgetWidget::onGoUAVAct_triggered() -{ - if (!m_widget || !m_map) - return; - - double latitude; - double longitude; - double altitude; - if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position - { - internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position - internals::PointLatLng map_pos = m_map->CurrentPosition(); // current MAP position - if (map_pos != uav_pos) m_map->SetCurrentPosition(uav_pos); // center the map onto the UAV - } -} - -void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked) -{ - if (!m_widget || !m_map) - return; - - if (m_widget->toolButtonMapUAV->isChecked() != checked) - m_widget->toolButtonMapUAV->setChecked(checked); - - setMapFollowingMode(); -} - -void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) -{ - if (!m_widget || !m_map) - return; - - if (m_widget->toolButtonMapUAVheading->isChecked() != checked) - m_widget->toolButtonMapUAVheading->setChecked(checked); - - setMapFollowingMode(); -} - -void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) -{ - if (!m_widget || !m_map) - return; - - int trail_type_idx = action->data().toInt(); - - QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); - mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[trail_type_idx]); - - m_map->UAV->SetTrailType(uav_trail_type); -} - -void OPMapGadgetWidget::onClearUAVtrailAct_triggered() -{ - if (!m_widget || !m_map) - return; - - m_map->UAV->DeleteTrail(); - m_map->GPS->DeleteTrail(); -} - -void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) -{ - if (!m_widget || !m_map) - return; - - int trail_time = (double)action->data().toInt(); - - m_map->UAV->SetTrailTime(trail_time); -} - -void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) -{ - if (!m_widget || !m_map) - return; - - int trail_distance = action->data().toInt(); - - m_map->UAV->SetTrailDistance(trail_distance); -} - -/** - * TODO: unused for v1.0 - **/ -/* -void OPMapGadgetWidget::onAddWayPointAct_triggered() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != Normal_MapMode) - return; - - m_waypoint_list_mutex.lock(); - - // create a waypoint on the map at the last known mouse position - t_waypoint *wp = new t_waypoint; - wp->map_wp_item = NULL; - wp->coord = context_menu_lat_lon; - wp->altitude = 0; - wp->description = ""; - wp->locked = false; - wp->time_seconds = 0; - wp->hold_time_seconds = 0; - wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); - - wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); - - wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); - - if (wp->map_wp_item) - { - if (!wp->locked) - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - else - wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - wp->map_wp_item->update(); - } - - // and remember it in our own local waypoint list - m_waypoint_list.append(wp); - - m_waypoint_list_mutex.unlock(); -} -*/ - -/** - * Called when the user asks to edit a waypoint from the map - * - * TODO: should open an interface to edit waypoint properties, or - * propagate the signal to a specific WP plugin (tbd). - **/ -/* -void OPMapGadgetWidget::onEditWayPointAct_triggered() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != Normal_MapMode) - return; - - if (!m_mouse_waypoint) - return; - - //waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); - - m_mouse_waypoint = NULL; -} -*/ - -/** - * TODO: unused for v1.0 - */ -/* -void OPMapGadgetWidget::onLockWayPointAct_triggered() -{ - if (!m_widget || !m_map || !m_mouse_waypoint) - return; - - if (m_map_mode != Normal_MapMode) - return; - - bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; - m_mouse_waypoint->setFlag(QGraphicsItem::ItemIsMovable, locked); - - if (!locked) - m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); - else - m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); - m_mouse_waypoint->update(); - - m_mouse_waypoint = NULL; -} -*/ - -/** - * TODO: unused for v1.0 - */ -/* -void OPMapGadgetWidget::onDeleteWayPointAct_triggered() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != Normal_MapMode) - return; - - if (!m_mouse_waypoint) - return; - - bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; - - if (locked) return; // waypoint is locked - - QMutexLocker locker(&m_waypoint_list_mutex); - - for (int i = 0; i < m_waypoint_list.count(); i++) - { - t_waypoint *wp = m_waypoint_list.at(i); - if (!wp) continue; - if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; - - // delete the waypoint from the map - m_map->WPDelete(wp->map_wp_item); - - // delete the waypoint from our local waypoint list - m_waypoint_list.removeAt(i); - - delete wp; - - break; - } -// -// foreach (t_waypoint *wp, m_waypoint_list) -// { -// if (!wp) continue; -// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; -// -// // delete the waypoint from the map -// m_map->WPDelete(wp->map_wp_item); -// -// // delete the waypoint from our local waypoint list -// m_waypoint_list.removeOne(wp); -// -// delete wp; -// -// break; -// } - - m_mouse_waypoint = NULL; -} -*/ - -/** - * TODO: No Waypoint support in v1.0 - */ -/* -void OPMapGadgetWidget::onClearWayPointsAct_triggered() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != Normal_MapMode) - return; - - QMutexLocker locker(&m_waypoint_list_mutex); - - m_map->WPDeleteAll(); - - foreach (t_waypoint *wp, m_waypoint_list) - { - if (wp) - { - delete wp; - wp = NULL; - } - } - - m_waypoint_list.clear(); -} -*/ - -void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() -{ - // center the magic waypoint on the home position - homeMagicWaypoint(); -} - -void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show) -{ - if (!m_widget || !m_map) - return; - - m_map->Home->SetShowSafeArea(show); // show the safe area - m_map->Home->RefreshPos(); -} - -void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action) -{ - if (!m_widget || !m_map) - return; - - int radius = action->data().toInt(); - - m_map->Home->SetSafeArea(radius); // set the radius (meters) - m_map->Home->RefreshPos(); - - // move the magic waypoint if need be to keep it within the safe area around the home position - keepMagicWaypointWithInSafeArea(); -} - -/** -* move the magic waypoint to the home position -**/ -void OPMapGadgetWidget::homeMagicWaypoint() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != MagicWaypoint_MapMode) - return; - - magic_waypoint.coord = home_position.coord; - - if (magic_waypoint.map_wp_item) - magic_waypoint.map_wp_item->SetCoord(magic_waypoint.coord); -} - -// ************************************************************************************* -// move the UAV to the magic waypoint position - -void OPMapGadgetWidget::moveToMagicWaypointPosition() -{ - if (!m_widget || !m_map) - return; - - if (m_map_mode != MagicWaypoint_MapMode) - return; - -// internals::PointLatLng coord = magic_waypoint.coord; -// double altitude = magic_waypoint.altitude; - - - // ToDo: - -} - -// ************************************************************************************* -// temporary until an object is created for managing the save/restore - -// load the contents of a simple text file into a combobox -void OPMapGadgetWidget::loadComboBoxLines(QComboBox *comboBox, QString filename) -{ - if (!comboBox) return; - if (filename.isNull() || filename.isEmpty()) return; - - QFile file(filename); - if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) - return; - - QTextStream in(&file); - - while (!in.atEnd()) - { - QString line = in.readLine().simplified(); - if (line.isNull() || line.isEmpty()) continue; - comboBox->addItem(line); - } - - file.close(); -} - -// save a combobox text contents to a simple text file -void OPMapGadgetWidget::saveComboBoxLines(QComboBox *comboBox, QString filename) -{ - if (!comboBox) return; - if (filename.isNull() || filename.isEmpty()) return; - - QFile file(filename); - if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) - return; - - QTextStream out(&file); - - for (int i = 0; i < comboBox->count(); i++) - { - QString line = comboBox->itemText(i).simplified(); - if (line.isNull() || line.isEmpty()) continue; - out << line << "\n"; - } - - file.close(); -} - -// ************************************************************************************* -// show/hide the magic waypoint controls - -void OPMapGadgetWidget::hideMagicWaypointControls() -{ - m_widget->lineWaypoint->setVisible(false); - m_widget->toolButtonHomeWaypoint->setVisible(false); - m_widget->toolButtonMoveToWP->setVisible(false); -} - -void OPMapGadgetWidget::showMagicWaypointControls() -{ - m_widget->lineWaypoint->setVisible(true); - m_widget->toolButtonHomeWaypoint->setVisible(true); - - #if defined(allow_manual_home_location_move) - m_widget->toolButtonMoveToWP->setVisible(true); - #else - m_widget->toolButtonMoveToWP->setVisible(false); - #endif -} - -// ************************************************************************************* -// move the magic waypoint to keep it within the safe area boundry - -void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() -{ - - // calcute the bearing and distance from the home position to the magic waypoint - double dist = distance(home_position.coord, magic_waypoint.coord); - double bear = bearing(home_position.coord, magic_waypoint.coord); - - // get the maximum safe distance - in kilometers - double boundry_dist = (double)m_map->Home->SafeArea() / 1000; - -// if (dist <= boundry_dist) -// return; // the magic waypoint is still within the safe area, don't move it - - if (dist > boundry_dist) dist = boundry_dist; - - // move the magic waypoint - - magic_waypoint.coord = destPoint(home_position.coord, bear, dist); - - if (m_map_mode == MagicWaypoint_MapMode) - { // move the on-screen waypoint - if (magic_waypoint.map_wp_item) - magic_waypoint.map_wp_item->SetCoord(magic_waypoint.coord); - } -} - -// ************************************************************************************* -// return the distance between two points .. in kilometers - -double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::PointLatLng to) -{ - double lat1 = from.Lat() * deg_to_rad; - double lon1 = from.Lng() * deg_to_rad; - - double lat2 = to.Lat() * deg_to_rad; - double lon2 = to.Lng() * deg_to_rad; - - // *********************** - // Haversine formula -/* - double delta_lat = lat2 - lat1; - double delta_lon = lon2 - lon1; - - double t1 = sin(delta_lat / 2); - double t2 = sin(delta_lon / 2); - double a = (t1 * t1) + cos(lat1) * cos(lat2) * (t2 * t2); - double c = 2 * atan2(sqrt(a), sqrt(1 - a)); - - return (earth_mean_radius * c); -*/ - // *********************** - // Spherical Law of Cosines - - return (acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1)) * earth_mean_radius); - - // *********************** -} - -// ************************************************************************************* -// return the bearing from one point to another .. in degrees - -double OPMapGadgetWidget::bearing(internals::PointLatLng from, internals::PointLatLng to) -{ - double lat1 = from.Lat() * deg_to_rad; - double lon1 = from.Lng() * deg_to_rad; - - double lat2 = to.Lat() * deg_to_rad; - double lon2 = to.Lng() * deg_to_rad; - -// double delta_lat = lat2 - lat1; - double delta_lon = lon2 - lon1; - - double y = sin(delta_lon) * cos(lat2); - double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(delta_lon); - double bear = atan2(y, x) * rad_to_deg; - - bear += 360; - while (bear < 0) bear += 360; - while (bear >= 360) bear -= 360; - - return bear; -} - -// ************************************************************************************* -// return a destination lat/lon point given a source lat/lon point and the bearing and distance from the source point - -internals::PointLatLng OPMapGadgetWidget::destPoint(internals::PointLatLng source, double bear, double dist) -{ - double lat1 = source.Lat() * deg_to_rad; - double lon1 = source.Lng() * deg_to_rad; - - bear *= deg_to_rad; - - double ad = dist / earth_mean_radius; - - double lat2 = asin(sin(lat1) * cos(ad) + cos(lat1) * sin(ad) * cos(bear)); - double lon2 = lon1 + atan2(sin(bear) * sin(ad) * cos(lat1), cos(ad) - sin(lat1) * sin(lat2)); - - return internals::PointLatLng(lat2 * rad_to_deg, lon2 * rad_to_deg); -} - -// ************************************************************************************* - -bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, double &altitude) -{ - double BaseECEF[3]; - double NED[3]; - double LLA[3]; - UAVObject *obj; - - if (!obm) - return false; - - obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); - if (!obj) return false; - BaseECEF[0] = obj->getField(QString("ECEF"))->getDouble(0) / 100; - BaseECEF[1] = obj->getField(QString("ECEF"))->getDouble(1) / 100; - BaseECEF[2] = obj->getField(QString("ECEF"))->getDouble(2) / 100; - - obj = dynamic_cast(obm->getObject(QString("PositionActual"))); - if (!obj) return false; - NED[0] = obj->getField(QString("North"))->getDouble() / 100; - NED[1] = obj->getField(QString("East"))->getDouble() / 100; - NED[2] = obj->getField(QString("Down"))->getDouble() / 100; - -// obj = dynamic_cast(om->getObject(QString("PositionDesired"))); - -// obj = dynamic_cast(objManager->getObject("VelocityActual")); // air speed - - Utils::CoordinateConversions().GetLLA(BaseECEF, NED, LLA); - - latitude = LLA[0]; - longitude = LLA[1]; - altitude = LLA[2]; - - if (latitude != latitude) latitude = 0; // nan detection -// if (isNan(latitude)) latitude = 0; // nan detection - else -// if (!isFinite(latitude)) latitude = 0; -// else - if (latitude > 90) latitude = 90; - else - if (latitude < -90) latitude = -90; - - if (longitude != longitude) longitude = 0; // nan detection - else -// if (longitude > std::numeric_limits::max()) longitude = 0; // +infinite -// else -// if (longitude < -std::numeric_limits::max()) longitude = 0; // -infinite -// else - if (longitude > 180) longitude = 180; - else - if (longitude < -180) longitude = -180; - - if (altitude != altitude) altitude = 0; // nan detection - - return true; -} - -// ************************************************************************************* - -bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude) -{ - double LLA[3]; - - if (!obum) - return false; - - if (obum->getGPSPosition(LLA) < 0) - return false; // error - - latitude = LLA[0]; - longitude = LLA[1]; - altitude = LLA[2]; - - return true; -} - -double OPMapGadgetWidget::getUAV_Yaw() -{ - if (!obm) - return 0; - - UAVObject *obj = dynamic_cast(obm->getObject(QString("AttitudeActual"))); - double yaw = obj->getField(QString("Yaw"))->getDouble(); - - if (yaw != yaw) yaw = 0; // nan detection - - while (yaw < 0) yaw += 360; - while (yaw >= 360) yaw -= 360; - - return yaw; -} - -// ************************************************************************************* - -void OPMapGadgetWidget::setMapFollowingMode() -{ - if (!m_widget || !m_map) - return; - - if (!followUAVpositionAct->isChecked()) - { - m_map->UAV->SetMapFollowType(UAVMapFollowType::None); - m_map->SetRotate(0); // reset map rotation to 0deg - } - else - if (!followUAVheadingAct->isChecked()) - { - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); - m_map->SetRotate(0); // reset map rotation to 0deg - } - else - { - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode - - m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg - m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap); - } -} - -// ************************************************************************************* -// update the HomeLocation UAV Object - -bool OPMapGadgetWidget::setHomeLocationObject() -{ - if (!obum) - return false; - - double LLA[3] = {home_position.coord.Lat(), home_position.coord.Lng(), home_position.altitude}; - return (obum->setHomeLocation(LLA, true) >= 0); -} - -// ************************************************************************************* - -void OPMapGadgetWidget::SetUavPic(QString UAVPic) -{ - m_map->SetUavPic(UAVPic); -} +/** + ****************************************************************************** + * + * @file opmapgadgetwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "opmapgadgetwidget.h" +#include "ui_opmap_widget.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "utils/stylehelper.h" +#include "utils/homelocationutil.h" +#include "utils/worldmagmodel.h" + +#include "uavtalk/telemetrymanager.h" + +#include "positionactual.h" +#include "homelocation.h" + +#define allow_manual_home_location_move + +// ************************************************************************************* + +#define deg_to_rad ((double)M_PI / 180.0) +#define rad_to_deg (180.0 / (double)M_PI) + +#define earth_mean_radius 6371 // kilometers + +#define max_digital_zoom 3 // maximum allowed digital zoom level + +const int safe_area_radius_list[] = {5, 10, 20, 50, 100, 200, 500, 1000, 2000, 5000}; // meters + +const int uav_trail_time_list[] = {1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; // seconds + +const int uav_trail_distance_list[] = {1, 2, 5, 10, 20, 50, 100, 200, 500}; // meters + +const int max_update_rate_list[] = {100, 200, 500, 1000, 2000, 5000}; // milliseconds + +// ************************************************************************************* + + +// ************************************************************************************* +// NOTE: go back to SVN REV 2137 and earlier to get back to experimental waypoint support. +// ************************************************************************************* + + +// constructor +OPMapGadgetWidget::OPMapGadgetWidget(QWidget *parent) : QWidget(parent) +{ + // ************** + + m_widget = NULL; + m_map = NULL; + findPlaceCompleter = NULL; + + m_mouse_waypoint = NULL; + + pm = NULL; + obm = NULL; + obum = NULL; + + m_prev_tile_number = 0; + + m_min_zoom = m_max_zoom = 0; + + m_map_mode = Normal_MapMode; + + m_maxUpdateRate = max_update_rate_list[4]; // 2 seconds + + m_telemetry_connected = false; + + m_context_menu_lat_lon = m_mouse_lat_lon = internals::PointLatLng(0, 0); + + setMouseTracking(true); + + pm = ExtensionSystem::PluginManager::instance(); + if (pm) + { + obm = pm->getObject(); + obum = pm->getObject(); + } + + // ************** + // get current location + + double latitude = 0; + double longitude = 0; + double altitude = 0; + + // current position + getUAVPosition(latitude, longitude, altitude); + + internals::PointLatLng pos_lat_lon = internals::PointLatLng(latitude, longitude); + + // ************** + // default home position + + m_home_position.coord = pos_lat_lon; + m_home_position.altitude = altitude; + m_home_position.locked = false; + + // ************** + // default magic waypoint params + + m_magic_waypoint.map_wp_item = NULL; + m_magic_waypoint.coord = m_home_position.coord; + m_magic_waypoint.altitude = altitude; + m_magic_waypoint.description = "Magic waypoint"; + m_magic_waypoint.locked = false; + m_magic_waypoint.time_seconds = 0; + m_magic_waypoint.hold_time_seconds = 0; + + // ************** + // create the widget that holds the user controls and the map + + m_widget = new Ui::OPMap_Widget(); + m_widget->setupUi(this); + + // ************** + // create the central map widget + + m_map = new mapcontrol::OPMapWidget(); // create the map object + + m_map->setFrameStyle(QFrame::NoFrame); // no border frame + m_map->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); // tile background + + m_map->configuration->DragButton = Qt::LeftButton; // use the left mouse button for map dragging + + m_widget->horizontalSliderZoom->setMinimum(m_map->MinZoom()); // + m_widget->horizontalSliderZoom->setMaximum(m_map->MaxZoom() + max_digital_zoom); // + + m_min_zoom = m_widget->horizontalSliderZoom->minimum(); // minimum zoom we can accept + m_max_zoom = m_widget->horizontalSliderZoom->maximum(); // maximum zoom we can accept + + m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::MousePositionWithoutCenter); // set how the mouse wheel zoom functions + m_map->SetFollowMouse(true); // we want a contiuous mouse position reading + + m_map->SetShowHome(true); // display the HOME position on the map + m_map->SetShowUAV(true); // display the UAV position on the map + + m_map->Home->SetSafeArea(safe_area_radius_list[0]); // set radius (meters) + m_map->Home->SetShowSafeArea(true); // show the safe area + + m_map->UAV->SetTrailTime(uav_trail_time_list[0]); // seconds + m_map->UAV->SetTrailDistance(uav_trail_distance_list[1]); // meters + + m_map->UAV->SetTrailType(UAVTrailType::ByTimeElapsed); +// m_map->UAV->SetTrailType(UAVTrailType::ByDistance); + + m_map->GPS->SetTrailTime(uav_trail_time_list[0]); // seconds + m_map->GPS->SetTrailDistance(uav_trail_distance_list[1]); // meters + + m_map->GPS->SetTrailType(UAVTrailType::ByTimeElapsed); +// m_map->GPS->SetTrailType(UAVTrailType::ByDistance); + + // ************** + + setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding); + + QVBoxLayout *layout = new QVBoxLayout; + layout->setSpacing(0); + layout->setContentsMargins(0, 0, 0, 0); + layout->addWidget(m_map); + m_widget->mapWidget->setLayout(layout); + + // ************** + // set the user control options + + // TODO: this switch does not make sense, does it?? + + switch (m_map_mode) + { + case Normal_MapMode: + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + hideMagicWaypointControls(); + break; + + case MagicWaypoint_MapMode: + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + showMagicWaypointControls(); + break; + + default: + m_map_mode = Normal_MapMode; + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + hideMagicWaypointControls(); + break; + } + + m_widget->labelUAVPos->setText("---"); + m_widget->labelMapPos->setText("---"); + m_widget->labelMousePos->setText("---"); + m_widget->labelMapZoom->setText("---"); + + + // Splitter is not used at the moment: + // m_widget->splitter->setCollapsible(1, false); + + // set the size of the collapsable widgets + //QList m_SizeList; + //m_SizeList << 0 << 0 << 0; + //m_widget->splitter->setSizes(m_SizeList); + + m_widget->progressBarMap->setMaximum(1); + +/* + #if defined(Q_OS_MAC) + #elif defined(Q_OS_WIN) + m_widget->comboBoxFindPlace->clear(); + loadComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); + m_widget->comboBoxFindPlace->setCurrentIndex(-1); + #else + #endif +*/ + + + // ************** + // map stuff + + connect(m_map, SIGNAL(zoomChanged(double, double, double)), this, SLOT(zoomChanged(double, double, double))); // map zoom change signals + connect(m_map, SIGNAL(OnCurrentPositionChanged(internals::PointLatLng)), this, SLOT(OnCurrentPositionChanged(internals::PointLatLng))); // map poisition change signals + connect(m_map, SIGNAL(OnTileLoadComplete()), this, SLOT(OnTileLoadComplete())); // tile loading stop signals + connect(m_map, SIGNAL(OnTileLoadStart()), this, SLOT(OnTileLoadStart())); // tile loading start signals + connect(m_map, SIGNAL(OnMapDrag()), this, SLOT(OnMapDrag())); // map drag signals + connect(m_map, SIGNAL(OnMapZoomChanged()), this, SLOT(OnMapZoomChanged())); // map zoom changed + connect(m_map, SIGNAL(OnMapTypeChanged(MapType::Types)), this, SLOT(OnMapTypeChanged(MapType::Types))); // map type changed + connect(m_map, SIGNAL(OnEmptyTileError(int, core::Point)), this, SLOT(OnEmptyTileError(int, core::Point))); // tile error + connect(m_map, SIGNAL(OnTilesStillToLoad(int)), this, SLOT(OnTilesStillToLoad(int))); // tile loading signals + connect(m_map, SIGNAL(WPNumberChanged(int const&,int const&,WayPointItem*)), this, SLOT(WPNumberChanged(int const&,int const&,WayPointItem*))); + connect(m_map, SIGNAL(WPValuesChanged(WayPointItem*)), this, SLOT(WPValuesChanged(WayPointItem*))); + connect(m_map, SIGNAL(WPInserted(int const&, WayPointItem*)), this, SLOT(WPInserted(int const&, WayPointItem*))); + connect(m_map, SIGNAL(WPDeleted(int const&)), this, SLOT(WPDeleted(int const&))); + + m_map->SetCurrentPosition(m_home_position.coord); // set the map position + m_map->Home->SetCoord(m_home_position.coord); // set the HOME position + m_map->UAV->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + m_map->GPS->SetUAVPos(m_home_position.coord, 0.0); // set the UAV position + + // ************** + // create various context menu (mouse right click menu) actions + + createActions(); + + // ************** + // connect to the UAVObject updates we require to become a bit aware of our environment: + + if (pm) + { + // Register for Home Location state changes + if (obm) + { + UAVDataObject *obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); + if (obj) + { + connect(obj, SIGNAL(objectUpdated(UAVObject *)), this , SLOT(homePositionUpdated(UAVObject *))); + } + } + + // Listen to telemetry connection events + TelemetryManager *telMngr = pm->getObject(); + if (telMngr) + { + connect(telMngr, SIGNAL(connected()), this, SLOT(onTelemetryConnect())); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onTelemetryDisconnect())); + } + } + + // ************** + // create the desired timers + + m_updateTimer = new QTimer(); + m_updateTimer->setInterval(m_maxUpdateRate); + connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updatePosition())); + m_updateTimer->start(); + + m_statusUpdateTimer = new QTimer(); + m_statusUpdateTimer->setInterval(200); +// m_statusUpdateTimer->setInterval(m_maxUpdateRate); + connect(m_statusUpdateTimer, SIGNAL(timeout()), this, SLOT(updateMousePos())); + m_statusUpdateTimer->start(); + + // ************** + + m_map->setFocus(); +} + +// destructor +OPMapGadgetWidget::~OPMapGadgetWidget() +{ + if (m_map) + { + disconnect(m_map, 0, 0, 0); + m_map->SetShowHome(false); // doing this appears to stop the map lib crashing on exit + m_map->SetShowUAV(false); // " " + } + + + // this destructor doesn't appear to be called at shutdown??? + +// #if defined(Q_OS_MAC) +// #elif defined(Q_OS_WIN) +// saveComboBoxLines(m_widget->comboBoxFindPlace, QCoreApplication::applicationDirPath() + "/opmap_find_place_history.txt"); +// #else +// #endif + + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + + + // todo: + + + delete wp->map_wp_item; + } + m_waypoint_list_mutex.unlock(); + m_waypoint_list.clear(); + + if (m_map) + { + delete m_map; + m_map = NULL; + } +} + +// ************************************************************************************* +// widget signals .. the mouseMoveEvent does not get called - don't yet know why + +void OPMapGadgetWidget::resizeEvent(QResizeEvent *event) +{ + qDebug("opmap: resizeEvent"); + + QWidget::resizeEvent(event); +} + +void OPMapGadgetWidget::mouseMoveEvent(QMouseEvent *event) +{ + qDebug("opmap: mouseMoveEvent"); + + if (m_widget && m_map) + { + } + + if (event->buttons() & Qt::LeftButton) + { +// QPoint pos = event->pos(); + } + + QWidget::mouseMoveEvent(event); +} + +void OPMapGadgetWidget::contextMenuEvent(QContextMenuEvent *event) +{ // the user has right clicked on the map - create the pop-up context menu and display it + + QString s; + + if (!m_widget || !m_map) + return; + + if (event->reason() != QContextMenuEvent::Mouse) + return; // not a mouse click event + + // current mouse position + QPoint p = m_map->mapFromGlobal(event->globalPos()); + m_context_menu_lat_lon = m_map->GetFromLocalToLatLng(p); +// m_context_menu_lat_lon = m_map->currentMousePosition(); + + if (!m_map->contentsRect().contains(p)) + return; // the mouse click was not on the map + + // show the mouse position + s = QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7); + m_widget->labelMousePos->setText(s); + + // find out if we have a waypoint under the mouse cursor + QGraphicsItem *item = m_map->itemAt(p); + m_mouse_waypoint = qgraphicsitem_cast(item); + + // find out if the waypoint is locked (or not) + bool waypoint_locked = false; + if (m_mouse_waypoint) + waypoint_locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; + + // **************** + // Dynamically create the popup menu + + QMenu menu(this); + + menu.addAction(closeAct1); + + menu.addSeparator(); + + menu.addAction(reloadAct); + + menu.addSeparator(); + + QMenu maxUpdateRateSubMenu(tr("&Max Update Rate ") + "(" + QString::number(m_maxUpdateRate) + " ms)", this); + for (int i = 0; i < maxUpdateRateAct.count(); i++) + maxUpdateRateSubMenu.addAction(maxUpdateRateAct.at(i)); + menu.addMenu(&maxUpdateRateSubMenu); + + menu.addSeparator(); + + switch (m_map_mode) + { + case Normal_MapMode: s = tr(" (Normal)"); break; + case MagicWaypoint_MapMode: s = tr(" (Magic Waypoint)"); break; + default: s = tr(" (Unknown)"); break; + } + for (int i = 0; i < mapModeAct.count(); i++) + { // set the menu to checked (or not) + QAction *act = mapModeAct.at(i); + if (!act) continue; + if (act->data().toInt() == (int)m_map_mode) + act->setChecked(true); + } + QMenu mapModeSubMenu(tr("Map mode") + s, this); + for (int i = 0; i < mapModeAct.count(); i++) + mapModeSubMenu.addAction(mapModeAct.at(i)); + menu.addMenu(&mapModeSubMenu); + + menu.addSeparator(); + + QMenu copySubMenu(tr("Copy"), this); + copySubMenu.addAction(copyMouseLatLonToClipAct); + copySubMenu.addAction(copyMouseLatToClipAct); + copySubMenu.addAction(copyMouseLonToClipAct); + menu.addMenu(©SubMenu); + + menu.addSeparator(); + + /* + menu.addAction(findPlaceAct); + + menu.addSeparator(); + */ + + menu.addAction(showSafeAreaAct); + QMenu safeAreaSubMenu(tr("Safe Area Radius") + " (" + QString::number(m_map->Home->SafeArea()) + "m)", this); + for (int i = 0; i < safeAreaAct.count(); i++) + safeAreaSubMenu.addAction(safeAreaAct.at(i)); + menu.addMenu(&safeAreaSubMenu); + + menu.addSeparator(); + + menu.addAction(showCompassAct); + + menu.addAction(showDiagnostics); + + menu.addSeparator()->setText(tr("Zoom")); + + menu.addAction(zoomInAct); + menu.addAction(zoomOutAct); + + QMenu zoomSubMenu(tr("&Zoom ") + "(" + QString::number(m_map->ZoomTotal()) + ")", this); + for (int i = 0; i < zoomAct.count(); i++) + zoomSubMenu.addAction(zoomAct.at(i)); + menu.addMenu(&zoomSubMenu); + + menu.addSeparator(); + + menu.addAction(goMouseClickAct); + + menu.addSeparator()->setText(tr("HOME")); + + menu.addAction(setHomeAct); + menu.addAction(showHomeAct); + menu.addAction(goHomeAct); + + // **** + // uav trails + + menu.addSeparator()->setText(tr("UAV Trail")); + + QMenu uavTrailTypeSubMenu(tr("UAV trail type") + " (" + mapcontrol::Helper::StrFromUAVTrailType(m_map->UAV->GetTrailType()) + ")", this); + for (int i = 0; i < uavTrailTypeAct.count(); i++) + uavTrailTypeSubMenu.addAction(uavTrailTypeAct.at(i)); + menu.addMenu(&uavTrailTypeSubMenu); + + QMenu uavTrailTimeSubMenu(tr("UAV trail time") + " (" + QString::number(m_map->UAV->TrailTime()) + " sec)", this); + for (int i = 0; i < uavTrailTimeAct.count(); i++) + uavTrailTimeSubMenu.addAction(uavTrailTimeAct.at(i)); + menu.addMenu(&uavTrailTimeSubMenu); + + QMenu uavTrailDistanceSubMenu(tr("UAV trail distance") + " (" + QString::number(m_map->UAV->TrailDistance()) + " meters)", this); + for (int i = 0; i < uavTrailDistanceAct.count(); i++) + uavTrailDistanceSubMenu.addAction(uavTrailDistanceAct.at(i)); + menu.addMenu(&uavTrailDistanceSubMenu); + + menu.addAction(showTrailAct); + + menu.addAction(showTrailLineAct); + + menu.addAction(clearUAVtrailAct); + + // **** + + menu.addSeparator()->setText(tr("UAV")); + + menu.addAction(showUAVAct); + menu.addAction(followUAVpositionAct); + menu.addAction(followUAVheadingAct); + menu.addAction(goUAVAct); + + // ********* + + switch (m_map_mode) + { + case Normal_MapMode: + // only show the waypoint stuff if not in 'magic waypoint' mode + /* + menu.addSeparator()->setText(tr("Waypoints")); + + menu.addAction(wayPointEditorAct); + menu.addAction(addWayPointAct); + + if (m_mouse_waypoint) + { // we have a waypoint under the mouse + menu.addAction(editWayPointAct); + + lockWayPointAct->setChecked(waypoint_locked); + menu.addAction(lockWayPointAct); + + if (!waypoint_locked) + menu.addAction(deleteWayPointAct); + } + + m_waypoint_list_mutex.lock(); + if (m_waypoint_list.count() > 0) + menu.addAction(clearWayPointsAct); // we have waypoints + m_waypoint_list_mutex.unlock(); + */ + + break; + + case MagicWaypoint_MapMode: + menu.addSeparator()->setText(tr("Waypoints")); + menu.addAction(homeMagicWaypointAct); + break; + } + + // ********* + + menu.addSeparator(); + + menu.addAction(closeAct2); + + menu.exec(event->globalPos()); // popup the menu + + // **************** +} + +void OPMapGadgetWidget::keyPressEvent(QKeyEvent* event) +{ + qDebug() << "opmap: keyPressEvent, key =" << event->key() << endl; + + switch (event->key()) + { + case Qt::Key_Escape: + break; + + case Qt::Key_F1: + break; + + case Qt::Key_F2: + break; + + case Qt::Key_Up: + break; + + case Qt::Key_Down: + break; + + case Qt::Key_Left: + break; + + case Qt::Key_Right: + break; + + case Qt::Key_PageUp: + break; + + case Qt::Key_PageDown: + break; + } +} + +// ************************************************************************************* +// timer signals + +/** + Updates the UAV position on the map. It is called every 200ms + by a timer. + + TODO: consider updating upon object update, not timer. + + from Pip: No don't update on object update - had reports that peoples PC's can't cope with high update rates - have had to allow user to set map update from 100ms to 5 seconds (depending on their PC's graphics processing ability), so this needs to be kept on a timer. + */ +void OPMapGadgetWidget::updatePosition() +{ + double uav_latitude, uav_longitude, uav_altitude, uav_yaw; + double gps_latitude, gps_longitude, gps_altitude, gps_heading; + + internals::PointLatLng uav_pos; + internals::PointLatLng gps_pos; + + if (!m_widget || !m_map) + return; + + QMutexLocker locker(&m_map_mutex); +// Pip I'm sorry, I know this was here with a purpose vvv +// from Pip: let you off :) + //if (!telemetry_connected) + // return; + + // ************* + // get the current UAV details + + // get current UAV position + if (!getUAVPosition(uav_latitude, uav_longitude, uav_altitude)) + return; + + // get current UAV heading + uav_yaw = getUAV_Yaw(); + + uav_pos = internals::PointLatLng(uav_latitude, uav_longitude); + + // ************* + // get the current GPS details + + // get current GPS position + if (!getGPSPosition(gps_latitude, gps_longitude, gps_altitude)) + return; + + // get current GPS heading +// gps_heading = getGPS_Heading(); + gps_heading = 0; + + gps_pos = internals::PointLatLng(gps_latitude, gps_longitude); + + // ************* + // display the UAV position + + QString str = + "lat: " + QString::number(uav_pos.Lat(), 'f', 7) + + " lon: " + QString::number(uav_pos.Lng(), 'f', 7) + + " " + QString::number(uav_yaw, 'f', 1) + "deg" + + " " + QString::number(uav_altitude, 'f', 1) + "m"; +// " " + QString::number(uav_ground_speed_meters_per_second, 'f', 1) + "m/s"; + m_widget->labelUAVPos->setText(str); + + // ************* + // set the UAV icon position on the map + + m_map->UAV->SetUAVPos(uav_pos, uav_altitude); // set the maps UAV position +// qDebug()<<"UAVPOSITION"<UAV->SetUAVHeading(uav_yaw); // set the maps UAV heading + + // ************* + // set the GPS icon position on the map + + m_map->GPS->SetUAVPos(gps_pos, gps_altitude); // set the maps GPS position + m_map->GPS->SetUAVHeading(gps_heading); // set the maps GPS heading + + // ************* +} + +/** + Update plugin behaviour based on mouse position; Called every few ms by a + timer. + */ +void OPMapGadgetWidget::updateMousePos() +{ + if (!m_widget || !m_map) + return; + + QMutexLocker locker(&m_map_mutex); + + QPoint p = m_map->mapFromGlobal(QCursor::pos()); + internals::PointLatLng lat_lon = m_map->GetFromLocalToLatLng(p); // fetch the current lat/lon mouse position + + if (!m_map->contentsRect().contains(p)) + return; // the mouse is not on the map + +// internals::PointLatLng lat_lon = m_map->currentMousePosition(); // fetch the current lat/lon mouse position + + QGraphicsItem *item = m_map->itemAt(p); + + // find out if we are over the home position + mapcontrol::HomeItem *home = qgraphicsitem_cast(item); + + // find out if we are over the UAV + mapcontrol::UAVItem *uav = qgraphicsitem_cast(item); + + // find out if we have a waypoint under the mouse cursor + mapcontrol::WayPointItem *wp = qgraphicsitem_cast(item); + + if (m_mouse_lat_lon == lat_lon) + return; // the mouse has not moved + + m_mouse_lat_lon = lat_lon; // yes it has! + + internals::PointLatLng home_lat_lon = m_map->Home->Coord(); + + QString s = QString::number(m_mouse_lat_lon.Lat(), 'f', 7) + " " + QString::number(m_mouse_lat_lon.Lng(), 'f', 7); + if (wp) + { + s += " wp[" + QString::number(wp->Number()) + "]"; + + double dist = distance(home_lat_lon, wp->Coord()); + double bear = bearing(home_lat_lon, wp->Coord()); + s += " " + QString::number(dist * 1000, 'f', 1) + "m"; + s += " " + QString::number(bear, 'f', 1) + "deg"; + } + else + if (home) + { + s += " home"; + + double dist = distance(home_lat_lon, m_mouse_lat_lon); + double bear = bearing(home_lat_lon, m_mouse_lat_lon); + s += " " + QString::number(dist * 1000, 'f', 1) + "m"; + s += " " + QString::number(bear, 'f', 1) + "deg"; + } + else + if (uav) + { + s += " uav"; + + double latitude; + double longitude; + double altitude; + if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position + { + internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); + +// double dist = distance(home_lat_lon, uav_pos); +// double bear = bearing(home_lat_lon, uav_pos); +// s += " " + QString::number(dist * 1000, 'f', 1) + "m"; +// s += " " + QString::number(bear, 'f', 1) + "deg"; + } + } + m_widget->labelMousePos->setText(s); +} + +// ************************************************************************************* +// map signals + + +/** + Update the Plugin UI to reflect a change in zoom level + */ +void OPMapGadgetWidget::zoomChanged(double zoomt, double zoom, double zoomd) +{ + if (!m_widget || !m_map) + return; + + QString s = "tot:" + QString::number(zoomt, 'f', 1) + " rea:" + QString::number(zoom, 'f', 1) + " dig:" + QString::number(zoomd, 'f', 1); + m_widget->labelMapZoom->setText(s); + + int i_zoom = (int)(zoomt + 0.5); + + if (i_zoom < m_min_zoom) i_zoom = m_min_zoom; + else + if (i_zoom > m_max_zoom) i_zoom = m_max_zoom; + + if (m_widget->horizontalSliderZoom->value() != i_zoom) + m_widget->horizontalSliderZoom->setValue(i_zoom); // set the GUI zoom slider position + + int index0_zoom = i_zoom - m_min_zoom; // zoom level starting at index level '0' + if (index0_zoom < zoomAct.count()) + zoomAct.at(index0_zoom)->setChecked(true); // set the right-click context menu zoom level +} + +void OPMapGadgetWidget::OnMapDrag() +{ +} + +void OPMapGadgetWidget::OnCurrentPositionChanged(internals::PointLatLng point) +{ + if (!m_widget || !m_map) + return; + + QString coord_str = QString::number(point.Lat(), 'f', 7) + " " + QString::number(point.Lng(), 'f', 7) + " "; + m_widget->labelMapPos->setText(coord_str); +} + +/** + Update the progress bar while there are still tiles to load + */ +void OPMapGadgetWidget::OnTilesStillToLoad(int number) +{ + if (!m_widget || !m_map) + return; + +// if (prev_tile_number < number || m_widget->progressBarMap->maximum() < number) +// m_widget->progressBarMap->setMaximum(number); + + if (m_widget->progressBarMap->maximum() < number) + m_widget->progressBarMap->setMaximum(number); + + m_widget->progressBarMap->setValue(m_widget->progressBarMap->maximum() - number); // update the progress bar + +// m_widget->labelNumTilesToLoad->setText(QString::number(number)); + + m_prev_tile_number = number; +} + +/** + Show the progress bar as soon as the map lib starts downloading + */ +void OPMapGadgetWidget::OnTileLoadStart() +{ + if (!m_widget || !m_map) + return; + + m_widget->progressBarMap->setVisible(true); +} + +/** + Hide the progress bar once the map lib has finished downloading + + TODO: somehow this gets called before tile load is actually complete? + */ + +void OPMapGadgetWidget::OnTileLoadComplete() +{ + if (!m_widget || !m_map) + return; + + m_widget->progressBarMap->setVisible(false); +} + +void OPMapGadgetWidget::OnMapZoomChanged() +{ +} + +void OPMapGadgetWidget::OnMapTypeChanged(MapType::Types type) +{ + Q_UNUSED(type); +} + +void OPMapGadgetWidget::OnEmptyTileError(int zoom, core::Point pos) +{ + Q_UNUSED(zoom); + Q_UNUSED(pos); +} + +void OPMapGadgetWidget::WPNumberChanged(int const &oldnumber, int const &newnumber, WayPointItem *waypoint) +{ + Q_UNUSED(oldnumber); + Q_UNUSED(newnumber); + Q_UNUSED(waypoint); +} + +void OPMapGadgetWidget::WPValuesChanged(WayPointItem *waypoint) +{ +// qDebug("opmap: WPValuesChanged"); + + switch (m_map_mode) + { + case Normal_MapMode: + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { // search for the waypoint in our own waypoint list and update it + if (!wp) continue; + if (!wp->map_wp_item) continue; + if (wp->map_wp_item != waypoint) continue; + // found the waypoint in our list + wp->coord = waypoint->Coord(); + wp->altitude = waypoint->Altitude(); + wp->description = waypoint->Description(); + break; + } + m_waypoint_list_mutex.unlock(); + break; + + case MagicWaypoint_MapMode: + // update our copy of the magic waypoint + if (m_magic_waypoint.map_wp_item && m_magic_waypoint.map_wp_item == waypoint) + { + m_magic_waypoint.coord = waypoint->Coord(); + m_magic_waypoint.altitude = waypoint->Altitude(); + m_magic_waypoint.description = waypoint->Description(); + + // move the UAV to the magic waypoint position + // moveToMagicWaypointPosition(); + } + break; + } + +} + +/** + TODO: slot to do something upon Waypoint insertion + */ +void OPMapGadgetWidget::WPInserted(int const &number, WayPointItem *waypoint) +{ + Q_UNUSED(number); + Q_UNUSED(waypoint); +} + +/** + TODO: slot to do something upon Waypoint deletion + */ +void OPMapGadgetWidget::WPDeleted(int const &number) +{ + Q_UNUSED(number); +} + + +void OPMapGadgetWidget::on_toolButtonZoomP_clicked() +{ + QMutexLocker locker(&m_map_mutex); + zoomIn(); +} + +void OPMapGadgetWidget::on_toolButtonZoomM_clicked() +{ + QMutexLocker locker(&m_map_mutex); + zoomOut(); +} + +void OPMapGadgetWidget::on_toolButtonMapHome_clicked() +{ + QMutexLocker locker(&m_map_mutex); + goHome(); +} + +void OPMapGadgetWidget::on_toolButtonMapUAV_clicked() +{ + if (!m_widget || !m_map) + return; + + QMutexLocker locker(&m_map_mutex); + + followUAVpositionAct->toggle(); +} + +void OPMapGadgetWidget::on_toolButtonMapUAVheading_clicked() +{ + if (!m_widget || !m_map) + return; + + followUAVheadingAct->toggle(); +} + +void OPMapGadgetWidget::on_horizontalSliderZoom_sliderMoved(int position) +{ + if (!m_widget || !m_map) + return; + + QMutexLocker locker(&m_map_mutex); + + setZoom(position); +} + + +void OPMapGadgetWidget::on_toolButtonNormalMapMode_clicked() +{ + setMapMode(Normal_MapMode); +} + +void OPMapGadgetWidget::on_toolButtonMagicWaypointMapMode_clicked() +{ + setMapMode(MagicWaypoint_MapMode); +} + +void OPMapGadgetWidget::on_toolButtonHomeWaypoint_clicked() +{ + homeMagicWaypoint(); +} + +void OPMapGadgetWidget::on_toolButtonMoveToWP_clicked() +{ + moveToMagicWaypointPosition(); +} + +// ************************************************************************************* +// public slots + +void OPMapGadgetWidget::onTelemetryConnect() +{ + m_telemetry_connected = true; + + if (!obum) return; + + bool set; + double LLA[3]; + + // *********************** + // fetch the home location + + if (obum->getHomeLocation(set, LLA) < 0) + return; // error + + setHome(internals::PointLatLng(LLA[0], LLA[1])); + + if (m_map) + m_map->SetCurrentPosition(m_home_position.coord); // set the map position + + // *********************** +} + +void OPMapGadgetWidget::onTelemetryDisconnect() +{ + m_telemetry_connected = false; +} + +// Updates the Home position icon whenever the HomePosition object is updated +void OPMapGadgetWidget::homePositionUpdated(UAVObject *hp) +{ + if (!hp) + return; + + double lat = hp->getField("Latitude")->getDouble() * 1e-7; + double lon = hp->getField("Longitude")->getDouble() * 1e-7; + setHome(internals::PointLatLng(lat, lon)); +} + +// ************************************************************************************* +// public functions + +/** + Sets the home position on the map widget + */ +void OPMapGadgetWidget::setHome(QPointF pos) +{ + if (!m_widget || !m_map) + return; + + double latitude = pos.x(); + double longitude = pos.y(); + + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; + + if (longitude != longitude) longitude = 0; // nan detection + else + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; + + setHome(internals::PointLatLng(latitude, longitude)); +} + +/** + Sets the home position on the map widget + */ +void OPMapGadgetWidget::setHome(internals::PointLatLng pos_lat_lon) +{ + if (!m_widget || !m_map) + return; + + if (pos_lat_lon.Lat() != pos_lat_lon.Lat() || pos_lat_lon.Lng() != pos_lat_lon.Lng()) + return;; // nan prevention + + double latitude = pos_lat_lon.Lat(); + double longitude = pos_lat_lon.Lng(); + + if (latitude != latitude) latitude = 0; // nan detection + else + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; + + if (longitude != longitude) longitude = 0; // nan detection + else + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; + + // ********* + + m_home_position.coord = internals::PointLatLng(latitude, longitude); + + m_map->Home->SetCoord(m_home_position.coord); + m_map->Home->RefreshPos(); + + // move the magic waypoint to keep it within the safe area boundry + keepMagicWaypointWithInSafeArea(); +} + + +/** + Centers the map over the home position + */ +void OPMapGadgetWidget::goHome() +{ + if (!m_widget || !m_map) + return; + + followUAVpositionAct->setChecked(false); + + internals::PointLatLng home_pos = m_home_position.coord; // get the home location + m_map->SetCurrentPosition(home_pos); // center the map onto the home location +} + + +void OPMapGadgetWidget::zoomIn() +{ + if (!m_widget || !m_map) + return; + + int zoom = m_map->ZoomTotal() + 1; + + if (zoom < m_min_zoom) zoom = m_min_zoom; + else + if (zoom > m_max_zoom) zoom = m_max_zoom; + + m_map->SetZoom(zoom); +} + +void OPMapGadgetWidget::zoomOut() +{ + if (!m_widget || !m_map) + return; + + int zoom = m_map->ZoomTotal() - 1; + + if (zoom < m_min_zoom) zoom = m_min_zoom; + else + if (zoom > m_max_zoom) zoom = m_max_zoom; + + m_map->SetZoom(zoom); +} + +void OPMapGadgetWidget::setMaxUpdateRate(int update_rate) +{ + if (!m_widget || !m_map) + return; + + int list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); + int min_rate = max_update_rate_list[0]; + int max_rate = max_update_rate_list[list_size - 1]; + + if (update_rate < min_rate) update_rate = min_rate; + else + if (update_rate > max_rate) update_rate = max_rate; + + m_maxUpdateRate = update_rate; + + if (m_updateTimer) + m_updateTimer->setInterval(m_maxUpdateRate); + +// if (m_statusUpdateTimer) +// m_statusUpdateTimer->setInterval(m_maxUpdateRate); +} + +void OPMapGadgetWidget::setZoom(int zoom) +{ + if (!m_widget || !m_map) + return; + + if (zoom < m_min_zoom) zoom = m_min_zoom; + else + if (zoom > m_max_zoom) zoom = m_max_zoom; + + internals::MouseWheelZoomType::Types zoom_type = m_map->GetMouseWheelZoomType(); + m_map->SetMouseWheelZoomType(internals::MouseWheelZoomType::ViewCenter); + + m_map->SetZoom(zoom); + + m_map->SetMouseWheelZoomType(zoom_type); +} + +void OPMapGadgetWidget::setPosition(QPointF pos) +{ + if (!m_widget || !m_map) + return; + + double latitude = pos.y(); + double longitude = pos.x(); + + if (latitude != latitude || longitude != longitude) + return; // nan prevention + + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; + + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; + + m_map->SetCurrentPosition(internals::PointLatLng(latitude, longitude)); +} + +void OPMapGadgetWidget::setMapProvider(QString provider) +{ + if (!m_widget || !m_map) + return; + + m_map->SetMapType(mapcontrol::Helper::MapTypeFromString(provider)); +} + +void OPMapGadgetWidget::setAccessMode(QString accessMode) +{ + if (!m_widget || !m_map) + return; + + m_map->configuration->SetAccessMode(mapcontrol::Helper::AccessModeFromString(accessMode)); +} + +void OPMapGadgetWidget::setUseOpenGL(bool useOpenGL) +{ + if (!m_widget || !m_map) + return; + + m_map->SetUseOpenGL(useOpenGL); +} + +void OPMapGadgetWidget::setShowTileGridLines(bool showTileGridLines) +{ + if (!m_widget || !m_map) + return; + + m_map->SetShowTileGridLines(showTileGridLines); +} + +void OPMapGadgetWidget::setUseMemoryCache(bool useMemoryCache) +{ + if (!m_widget || !m_map) + return; + + m_map->configuration->SetUseMemoryCache(useMemoryCache); +} + +void OPMapGadgetWidget::setCacheLocation(QString cacheLocation) +{ + if (!m_widget || !m_map) + return; + + cacheLocation = cacheLocation.simplified(); // remove any surrounding spaces + + if (cacheLocation.isEmpty()) return; + +// #if defined(Q_WS_WIN) +// if (!cacheLocation.endsWith('\\')) cacheLocation += '\\'; +// #elif defined(Q_WS_X11) + if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); +// #elif defined(Q_WS_MAC) +// if (!cacheLocation.endsWith(QDir::separator())) cacheLocation += QDir::separator(); +// #endif + + QDir dir; + if (!dir.exists(cacheLocation)) + if (!dir.mkpath(cacheLocation)) + return; + +// qDebug() << "opmap: map cache dir: " << cacheLocation; + + m_map->configuration->SetCacheLocation(cacheLocation); +} + +void OPMapGadgetWidget::setMapMode(opMapModeType mode) +{ + if (!m_widget || !m_map) + return; + + if (mode != Normal_MapMode && mode != MagicWaypoint_MapMode) + mode = Normal_MapMode; // fix error + + if (m_map_mode == mode) + { // no change in map mode + switch (mode) + { // make sure the UI buttons are set correctly + case Normal_MapMode: + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + break; + case MagicWaypoint_MapMode: + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + break; + } + return; + } + + switch (mode) + { + case Normal_MapMode: + m_map_mode = Normal_MapMode; + + m_widget->toolButtonMagicWaypointMapMode->setChecked(false); + m_widget->toolButtonNormalMapMode->setChecked(true); + + hideMagicWaypointControls(); + + // delete the magic waypoint from the map + if (m_magic_waypoint.map_wp_item) + { + m_magic_waypoint.coord = m_magic_waypoint.map_wp_item->Coord(); + m_magic_waypoint.altitude = m_magic_waypoint.map_wp_item->Altitude(); + m_magic_waypoint.description = m_magic_waypoint.map_wp_item->Description(); + m_magic_waypoint.map_wp_item = NULL; + } + m_map->WPDeleteAll(); + + // restore the normal waypoints on the map + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); + if (!wp->map_wp_item) continue; + wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); + wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); + if (!wp->locked) + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + else + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + wp->map_wp_item->update(); + } + m_waypoint_list_mutex.unlock(); + + break; + + case MagicWaypoint_MapMode: + m_map_mode = MagicWaypoint_MapMode; + + m_widget->toolButtonNormalMapMode->setChecked(false); + m_widget->toolButtonMagicWaypointMapMode->setChecked(true); + + showMagicWaypointControls(); + + // delete the normal waypoints from the map + m_waypoint_list_mutex.lock(); + foreach (t_waypoint *wp, m_waypoint_list) + { + if (!wp) continue; + if (!wp->map_wp_item) continue; + wp->coord = wp->map_wp_item->Coord(); + wp->altitude = wp->map_wp_item->Altitude(); + wp->description = wp->map_wp_item->Description(); + wp->locked = (wp->map_wp_item->flags() & QGraphicsItem::ItemIsMovable) == 0; + wp->map_wp_item = NULL; + } + m_map->WPDeleteAll(); + m_waypoint_list_mutex.unlock(); + + // restore the magic waypoint on the map + m_magic_waypoint.map_wp_item = m_map->WPCreate(m_magic_waypoint.coord, m_magic_waypoint.altitude, m_magic_waypoint.description); + m_magic_waypoint.map_wp_item->setZValue(10 + m_magic_waypoint.map_wp_item->Number()); + m_magic_waypoint.map_wp_item->SetShowNumber(false); + m_magic_waypoint.map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker3.png")); + + break; + } +} + +// ************************************************************************************* +// Context menu stuff + +void OPMapGadgetWidget::createActions() +{ + int list_size; + + if (!m_widget || !m_map) + return; + + // *********************** + // create menu actions + + closeAct1 = new QAction(tr("Close menu"), this); + closeAct1->setStatusTip(tr("Close the context menu")); + + closeAct2 = new QAction(tr("Close menu"), this); + closeAct2->setStatusTip(tr("Close the context menu")); + + reloadAct = new QAction(tr("&Reload map"), this); + reloadAct->setShortcut(tr("F5")); + reloadAct->setStatusTip(tr("Reload the map tiles")); + connect(reloadAct, SIGNAL(triggered()), this, SLOT(onReloadAct_triggered())); + + copyMouseLatLonToClipAct = new QAction(tr("Mouse latitude and longitude"), this); + copyMouseLatLonToClipAct->setStatusTip(tr("Copy the mouse latitude and longitude to the clipboard")); + connect(copyMouseLatLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatLonToClipAct_triggered())); + + copyMouseLatToClipAct = new QAction(tr("Mouse latitude"), this); + copyMouseLatToClipAct->setStatusTip(tr("Copy the mouse latitude to the clipboard")); + connect(copyMouseLatToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLatToClipAct_triggered())); + + copyMouseLonToClipAct = new QAction(tr("Mouse longitude"), this); + copyMouseLonToClipAct->setStatusTip(tr("Copy the mouse longitude to the clipboard")); + connect(copyMouseLonToClipAct, SIGNAL(triggered()), this, SLOT(onCopyMouseLonToClipAct_triggered())); + + /* + findPlaceAct = new QAction(tr("&Find place"), this); + findPlaceAct->setShortcut(tr("Ctrl+F")); + findPlaceAct->setStatusTip(tr("Find a location")); + connect(findPlaceAct, SIGNAL(triggered()), this, SLOT(onFindPlaceAct_triggered())); + */ + + showCompassAct = new QAction(tr("Show compass"), this); + showCompassAct->setStatusTip(tr("Show/Hide the compass")); + showCompassAct->setCheckable(true); + showCompassAct->setChecked(true); + connect(showCompassAct, SIGNAL(toggled(bool)), this, SLOT(onShowCompassAct_toggled(bool))); + + showDiagnostics = new QAction(tr("Show Diagnostics"), this); + showDiagnostics->setStatusTip(tr("Show/Hide the diagnostics")); + showDiagnostics->setCheckable(true); + showDiagnostics->setChecked(false); + connect(showDiagnostics, SIGNAL(toggled(bool)), this, SLOT(onShowDiagnostics_toggled(bool))); + + showHomeAct = new QAction(tr("Show Home"), this); + showHomeAct->setStatusTip(tr("Show/Hide the Home location")); + showHomeAct->setCheckable(true); + showHomeAct->setChecked(true); + connect(showHomeAct, SIGNAL(toggled(bool)), this, SLOT(onShowHomeAct_toggled(bool))); + + showUAVAct = new QAction(tr("Show UAV"), this); + showUAVAct->setStatusTip(tr("Show/Hide the UAV")); + showUAVAct->setCheckable(true); + showUAVAct->setChecked(true); + connect(showUAVAct, SIGNAL(toggled(bool)), this, SLOT(onShowUAVAct_toggled(bool))); + + zoomInAct = new QAction(tr("Zoom &In"), this); + zoomInAct->setShortcut(Qt::Key_PageUp); + zoomInAct->setStatusTip(tr("Zoom the map in")); + connect(zoomInAct, SIGNAL(triggered()), this, SLOT(onGoZoomInAct_triggered())); + + zoomOutAct = new QAction(tr("Zoom &Out"), this); + zoomOutAct->setShortcut(Qt::Key_PageDown); + zoomOutAct->setStatusTip(tr("Zoom the map out")); + connect(zoomOutAct, SIGNAL(triggered()), this, SLOT(onGoZoomOutAct_triggered())); + + goMouseClickAct = new QAction(tr("Go to where you right clicked the mouse"), this); + goMouseClickAct->setStatusTip(tr("Center the map onto where you right clicked the mouse")); + connect(goMouseClickAct, SIGNAL(triggered()), this, SLOT(onGoMouseClickAct_triggered())); + + setHomeAct = new QAction(tr("Set the home location"), this); + setHomeAct->setStatusTip(tr("Set the home location to where you clicked")); + #if !defined(allow_manual_home_location_move) + setHomeAct->setEnabled(false); + #endif + connect(setHomeAct, SIGNAL(triggered()), this, SLOT(onSetHomeAct_triggered())); + + goHomeAct = new QAction(tr("Go to &Home location"), this); + goHomeAct->setShortcut(tr("Ctrl+H")); + goHomeAct->setStatusTip(tr("Center the map onto the home location")); + connect(goHomeAct, SIGNAL(triggered()), this, SLOT(onGoHomeAct_triggered())); + + goUAVAct = new QAction(tr("Go to &UAV location"), this); + goUAVAct->setShortcut(tr("Ctrl+U")); + goUAVAct->setStatusTip(tr("Center the map onto the UAV location")); + connect(goUAVAct, SIGNAL(triggered()), this, SLOT(onGoUAVAct_triggered())); + + followUAVpositionAct = new QAction(tr("Follow UAV position"), this); + followUAVpositionAct->setShortcut(tr("Ctrl+F")); + followUAVpositionAct->setStatusTip(tr("Keep the map centered onto the UAV")); + followUAVpositionAct->setCheckable(true); + followUAVpositionAct->setChecked(false); + connect(followUAVpositionAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVpositionAct_toggled(bool))); + + followUAVheadingAct = new QAction(tr("Follow UAV heading"), this); + followUAVheadingAct->setShortcut(tr("Ctrl+F")); + followUAVheadingAct->setStatusTip(tr("Keep the map rotation to the UAV heading")); + followUAVheadingAct->setCheckable(true); + followUAVheadingAct->setChecked(false); + connect(followUAVheadingAct, SIGNAL(toggled(bool)), this, SLOT(onFollowUAVheadingAct_toggled(bool))); + + /* + TODO: Waypoint support is disabled for v1.0 + */ + + /* + wayPointEditorAct = new QAction(tr("&Waypoint editor"), this); + wayPointEditorAct->setShortcut(tr("Ctrl+W")); + wayPointEditorAct->setStatusTip(tr("Open the waypoint editor")); + wayPointEditorAct->setEnabled(false); // temporary + connect(wayPointEditorAct, SIGNAL(triggered()), this, SLOT(onOpenWayPointEditorAct_triggered())); + + addWayPointAct = new QAction(tr("&Add waypoint"), this); + addWayPointAct->setShortcut(tr("Ctrl+A")); + addWayPointAct->setStatusTip(tr("Add waypoint")); + connect(addWayPointAct, SIGNAL(triggered()), this, SLOT(onAddWayPointAct_triggered())); + + editWayPointAct = new QAction(tr("&Edit waypoint"), this); + editWayPointAct->setShortcut(tr("Ctrl+E")); + editWayPointAct->setStatusTip(tr("Edit waypoint")); + connect(editWayPointAct, SIGNAL(triggered()), this, SLOT(onEditWayPointAct_triggered())); + + lockWayPointAct = new QAction(tr("&Lock waypoint"), this); + lockWayPointAct->setStatusTip(tr("Lock/Unlock a waypoint")); + lockWayPointAct->setCheckable(true); + lockWayPointAct->setChecked(false); + connect(lockWayPointAct, SIGNAL(triggered()), this, SLOT(onLockWayPointAct_triggered())); + + deleteWayPointAct = new QAction(tr("&Delete waypoint"), this); + deleteWayPointAct->setShortcut(tr("Ctrl+D")); + deleteWayPointAct->setStatusTip(tr("Delete waypoint")); + connect(deleteWayPointAct, SIGNAL(triggered()), this, SLOT(onDeleteWayPointAct_triggered())); + + clearWayPointsAct = new QAction(tr("&Clear waypoints"), this); + clearWayPointsAct->setShortcut(tr("Ctrl+C")); + clearWayPointsAct->setStatusTip(tr("Clear waypoints")); + connect(clearWayPointsAct, SIGNAL(triggered()), this, SLOT(onClearWayPointsAct_triggered())); + */ + + homeMagicWaypointAct = new QAction(tr("Home magic waypoint"), this); + homeMagicWaypointAct->setStatusTip(tr("Move the magic waypoint to the home position")); + connect(homeMagicWaypointAct, SIGNAL(triggered()), this, SLOT(onHomeMagicWaypointAct_triggered())); + + mapModeActGroup = new QActionGroup(this); + connect(mapModeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMapModeActGroup_triggered(QAction *))); + mapModeAct.clear(); + { + QAction *map_mode_act; + + map_mode_act = new QAction(tr("Normal"), mapModeActGroup); + map_mode_act->setCheckable(true); + map_mode_act->setChecked(m_map_mode == Normal_MapMode); + map_mode_act->setData((int)Normal_MapMode); + mapModeAct.append(map_mode_act); + + map_mode_act = new QAction(tr("Magic Waypoint"), mapModeActGroup); + map_mode_act->setCheckable(true); + map_mode_act->setChecked(m_map_mode == MagicWaypoint_MapMode); + map_mode_act->setData((int)MagicWaypoint_MapMode); + mapModeAct.append(map_mode_act); + } + + zoomActGroup = new QActionGroup(this); + connect(zoomActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onZoomActGroup_triggered(QAction *))); + zoomAct.clear(); + for (int i = m_min_zoom; i <= m_max_zoom; i++) + { + QAction *zoom_act = new QAction(QString::number(i), zoomActGroup); + zoom_act->setCheckable(true); + zoom_act->setData(i); + zoomAct.append(zoom_act); + } + + maxUpdateRateActGroup = new QActionGroup(this); + connect(maxUpdateRateActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onMaxUpdateRateActGroup_triggered(QAction *))); + maxUpdateRateAct.clear(); + list_size = sizeof(max_update_rate_list) / sizeof(max_update_rate_list[0]); + for (int i = 0; i < list_size; i++) + { + QAction *maxUpdateRate_act; + int j = max_update_rate_list[i]; + maxUpdateRate_act = new QAction(QString::number(j), maxUpdateRateActGroup); + maxUpdateRate_act->setCheckable(true); + maxUpdateRate_act->setData(j); + maxUpdateRate_act->setChecked(j == m_maxUpdateRate); + maxUpdateRateAct.append(maxUpdateRate_act); + } + + // ***** + // safe area + + showSafeAreaAct = new QAction(tr("Show Safe Area"), this); + showSafeAreaAct->setStatusTip(tr("Show/Hide the Safe Area around the home location")); + showSafeAreaAct->setCheckable(true); + showSafeAreaAct->setChecked(m_map->Home->ShowSafeArea()); + connect(showSafeAreaAct, SIGNAL(toggled(bool)), this, SLOT(onShowSafeAreaAct_toggled(bool))); + + safeAreaActGroup = new QActionGroup(this); + connect(safeAreaActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onSafeAreaActGroup_triggered(QAction *))); + safeAreaAct.clear(); + list_size = sizeof(safe_area_radius_list) / sizeof(safe_area_radius_list[0]); + for (int i = 0; i < list_size; i++) + { + int safeArea = safe_area_radius_list[i]; + QAction *safeArea_act = new QAction(QString::number(safeArea) + "m", safeAreaActGroup); + safeArea_act->setCheckable(true); + safeArea_act->setChecked(safeArea == m_map->Home->SafeArea()); + safeArea_act->setData(safeArea); + safeAreaAct.append(safeArea_act); + } + + // ***** + // UAV trail + + uavTrailTypeActGroup = new QActionGroup(this); + connect(uavTrailTypeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTypeActGroup_triggered(QAction *))); + uavTrailTypeAct.clear(); + QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); + for (int i = 0; i < uav_trail_type_list.count(); i++) + { + mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[i]); + QAction *uavTrailType_act = new QAction(mapcontrol::Helper::StrFromUAVTrailType(uav_trail_type), uavTrailTypeActGroup); + uavTrailType_act->setCheckable(true); + uavTrailType_act->setChecked(uav_trail_type == m_map->UAV->GetTrailType()); + uavTrailType_act->setData(i); + uavTrailTypeAct.append(uavTrailType_act); + } + + showTrailAct = new QAction(tr("Show Trail dots"), this); + showTrailAct->setStatusTip(tr("Show/Hide the Trail dots")); + showTrailAct->setCheckable(true); + showTrailAct->setChecked(true); + connect(showTrailAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailAct_toggled(bool))); + + showTrailLineAct = new QAction(tr("Show Trail lines"), this); + showTrailLineAct->setStatusTip(tr("Show/Hide the Trail lines")); + showTrailLineAct->setCheckable(true); + showTrailLineAct->setChecked(true); + connect(showTrailLineAct, SIGNAL(toggled(bool)), this, SLOT(onShowTrailLineAct_toggled(bool))); + + clearUAVtrailAct = new QAction(tr("Clear UAV trail"), this); + clearUAVtrailAct->setStatusTip(tr("Clear the UAV trail")); + connect(clearUAVtrailAct, SIGNAL(triggered()), this, SLOT(onClearUAVtrailAct_triggered())); + + uavTrailTimeActGroup = new QActionGroup(this); + connect(uavTrailTimeActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailTimeActGroup_triggered(QAction *))); + uavTrailTimeAct.clear(); + list_size = sizeof(uav_trail_time_list) / sizeof(uav_trail_time_list[0]); + for (int i = 0; i < list_size; i++) + { + int uav_trail_time = uav_trail_time_list[i]; + QAction *uavTrailTime_act = new QAction(QString::number(uav_trail_time) + " sec", uavTrailTimeActGroup); + uavTrailTime_act->setCheckable(true); + uavTrailTime_act->setChecked(uav_trail_time == m_map->UAV->TrailTime()); + uavTrailTime_act->setData(uav_trail_time); + uavTrailTimeAct.append(uavTrailTime_act); + } + + uavTrailDistanceActGroup = new QActionGroup(this); + connect(uavTrailDistanceActGroup, SIGNAL(triggered(QAction *)), this, SLOT(onUAVTrailDistanceActGroup_triggered(QAction *))); + uavTrailDistanceAct.clear(); + list_size = sizeof(uav_trail_distance_list) / sizeof(uav_trail_distance_list[0]); + for (int i = 0; i < list_size; i++) + { + int uav_trail_distance = uav_trail_distance_list[i]; + QAction *uavTrailDistance_act = new QAction(QString::number(uav_trail_distance) + " meters", uavTrailDistanceActGroup); + uavTrailDistance_act->setCheckable(true); + uavTrailDistance_act->setChecked(uav_trail_distance == m_map->UAV->TrailDistance()); + uavTrailDistance_act->setData(uav_trail_distance); + uavTrailDistanceAct.append(uavTrailDistance_act); + } + + // ***** + + // *********************** +} + +void OPMapGadgetWidget::onReloadAct_triggered() +{ + if (!m_widget || !m_map) + return; + + m_map->ReloadMap(); +} + +void OPMapGadgetWidget::onCopyMouseLatLonToClipAct_triggered() +{ + QClipboard *clipboard = QApplication::clipboard(); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7) + ", " + QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); +} + +void OPMapGadgetWidget::onCopyMouseLatToClipAct_triggered() +{ + QClipboard *clipboard = QApplication::clipboard(); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lat(), 'f', 7), QClipboard::Clipboard); +} + +void OPMapGadgetWidget::onCopyMouseLonToClipAct_triggered() +{ + QClipboard *clipboard = QApplication::clipboard(); + clipboard->setText(QString::number(m_context_menu_lat_lon.Lng(), 'f', 7), QClipboard::Clipboard); +} + + +void OPMapGadgetWidget::onShowCompassAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->SetShowCompass(show); +} + +void OPMapGadgetWidget::onShowDiagnostics_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->SetShowDiagnostics(show); +} + +void OPMapGadgetWidget::onShowHomeAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->Home->setVisible(show); +} + +void OPMapGadgetWidget::onShowUAVAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->setVisible(show); + m_map->GPS->setVisible(show); +} + +void OPMapGadgetWidget::onShowTrailAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->SetShowTrail(show); + m_map->GPS->SetShowTrail(show); +} + +void OPMapGadgetWidget::onShowTrailLineAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->SetShowTrailLine(show); + m_map->GPS->SetShowTrailLine(show); +} + +void OPMapGadgetWidget::onMapModeActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + opMapModeType mode = (opMapModeType)action->data().toInt(); + + setMapMode(mode); +} + +void OPMapGadgetWidget::onGoZoomInAct_triggered() +{ + zoomIn(); +} + +void OPMapGadgetWidget::onGoZoomOutAct_triggered() +{ + zoomOut(); +} + +void OPMapGadgetWidget::onZoomActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + setZoom(action->data().toInt()); +} + +void OPMapGadgetWidget::onMaxUpdateRateActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + setMaxUpdateRate(action->data().toInt()); +} + +void OPMapGadgetWidget::onGoMouseClickAct_triggered() +{ + if (!m_widget || !m_map) + return; + + m_map->SetCurrentPosition(m_map->currentMousePosition()); // center the map onto the mouse position +} + +void OPMapGadgetWidget::onSetHomeAct_triggered() +{ + if (!m_widget || !m_map) + return; + + setHome(m_context_menu_lat_lon); + + setHomeLocationObject(); // update the HomeLocation UAVObject +} + +void OPMapGadgetWidget::onGoHomeAct_triggered() +{ + if (!m_widget || !m_map) + return; + + goHome(); +} + +void OPMapGadgetWidget::onGoUAVAct_triggered() +{ + if (!m_widget || !m_map) + return; + + double latitude; + double longitude; + double altitude; + if (getUAVPosition(latitude, longitude, altitude)) // get current UAV position + { + internals::PointLatLng uav_pos = internals::PointLatLng(latitude, longitude); // current UAV position + internals::PointLatLng map_pos = m_map->CurrentPosition(); // current MAP position + if (map_pos != uav_pos) m_map->SetCurrentPosition(uav_pos); // center the map onto the UAV + } +} + +void OPMapGadgetWidget::onFollowUAVpositionAct_toggled(bool checked) +{ + if (!m_widget || !m_map) + return; + + if (m_widget->toolButtonMapUAV->isChecked() != checked) + m_widget->toolButtonMapUAV->setChecked(checked); + + setMapFollowingMode(); +} + +void OPMapGadgetWidget::onFollowUAVheadingAct_toggled(bool checked) +{ + if (!m_widget || !m_map) + return; + + if (m_widget->toolButtonMapUAVheading->isChecked() != checked) + m_widget->toolButtonMapUAVheading->setChecked(checked); + + setMapFollowingMode(); +} + +void OPMapGadgetWidget::onUAVTrailTypeActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_type_idx = action->data().toInt(); + + QStringList uav_trail_type_list = mapcontrol::Helper::UAVTrailTypes(); + mapcontrol::UAVTrailType::Types uav_trail_type = mapcontrol::Helper::UAVTrailTypeFromString(uav_trail_type_list[trail_type_idx]); + + m_map->UAV->SetTrailType(uav_trail_type); +} + +void OPMapGadgetWidget::onClearUAVtrailAct_triggered() +{ + if (!m_widget || !m_map) + return; + + m_map->UAV->DeleteTrail(); + m_map->GPS->DeleteTrail(); +} + +void OPMapGadgetWidget::onUAVTrailTimeActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_time = (double)action->data().toInt(); + + m_map->UAV->SetTrailTime(trail_time); +} + +void OPMapGadgetWidget::onUAVTrailDistanceActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int trail_distance = action->data().toInt(); + + m_map->UAV->SetTrailDistance(trail_distance); +} + +/** + * TODO: unused for v1.0 + **/ +/* +void OPMapGadgetWidget::onAddWayPointAct_triggered() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != Normal_MapMode) + return; + + m_waypoint_list_mutex.lock(); + + // create a waypoint on the map at the last known mouse position + t_waypoint *wp = new t_waypoint; + wp->map_wp_item = NULL; + wp->coord = context_menu_lat_lon; + wp->altitude = 0; + wp->description = ""; + wp->locked = false; + wp->time_seconds = 0; + wp->hold_time_seconds = 0; + wp->map_wp_item = m_map->WPCreate(wp->coord, wp->altitude, wp->description); + + wp->map_wp_item->setZValue(10 + wp->map_wp_item->Number()); + + wp->map_wp_item->setFlag(QGraphicsItem::ItemIsMovable, !wp->locked); + + if (wp->map_wp_item) + { + if (!wp->locked) + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + else + wp->map_wp_item->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + wp->map_wp_item->update(); + } + + // and remember it in our own local waypoint list + m_waypoint_list.append(wp); + + m_waypoint_list_mutex.unlock(); +} +*/ + +/** + * Called when the user asks to edit a waypoint from the map + * + * TODO: should open an interface to edit waypoint properties, or + * propagate the signal to a specific WP plugin (tbd). + **/ +/* +void OPMapGadgetWidget::onEditWayPointAct_triggered() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != Normal_MapMode) + return; + + if (!m_mouse_waypoint) + return; + + //waypoint_edit_dialog.editWaypoint(m_mouse_waypoint); + + m_mouse_waypoint = NULL; +} +*/ + +/** + * TODO: unused for v1.0 + */ +/* +void OPMapGadgetWidget::onLockWayPointAct_triggered() +{ + if (!m_widget || !m_map || !m_mouse_waypoint) + return; + + if (m_map_mode != Normal_MapMode) + return; + + bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; + m_mouse_waypoint->setFlag(QGraphicsItem::ItemIsMovable, locked); + + if (!locked) + m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker2.png")); + else + m_mouse_waypoint->picture.load(QString::fromUtf8(":/opmap/images/waypoint_marker1.png")); + m_mouse_waypoint->update(); + + m_mouse_waypoint = NULL; +} +*/ + +/** + * TODO: unused for v1.0 + */ +/* +void OPMapGadgetWidget::onDeleteWayPointAct_triggered() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != Normal_MapMode) + return; + + if (!m_mouse_waypoint) + return; + + bool locked = (m_mouse_waypoint->flags() & QGraphicsItem::ItemIsMovable) == 0; + + if (locked) return; // waypoint is locked + + QMutexLocker locker(&m_waypoint_list_mutex); + + for (int i = 0; i < m_waypoint_list.count(); i++) + { + t_waypoint *wp = m_waypoint_list.at(i); + if (!wp) continue; + if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; + + // delete the waypoint from the map + m_map->WPDelete(wp->map_wp_item); + + // delete the waypoint from our local waypoint list + m_waypoint_list.removeAt(i); + + delete wp; + + break; + } +// +// foreach (t_waypoint *wp, m_waypoint_list) +// { +// if (!wp) continue; +// if (!wp->map_wp_item || wp->map_wp_item != m_mouse_waypoint) continue; +// +// // delete the waypoint from the map +// m_map->WPDelete(wp->map_wp_item); +// +// // delete the waypoint from our local waypoint list +// m_waypoint_list.removeOne(wp); +// +// delete wp; +// +// break; +// } + + m_mouse_waypoint = NULL; +} +*/ + +/** + * TODO: No Waypoint support in v1.0 + */ +/* +void OPMapGadgetWidget::onClearWayPointsAct_triggered() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != Normal_MapMode) + return; + + QMutexLocker locker(&m_waypoint_list_mutex); + + m_map->WPDeleteAll(); + + foreach (t_waypoint *wp, m_waypoint_list) + { + if (wp) + { + delete wp; + wp = NULL; + } + } + + m_waypoint_list.clear(); +} +*/ + +void OPMapGadgetWidget::onHomeMagicWaypointAct_triggered() +{ + // center the magic waypoint on the home position + homeMagicWaypoint(); +} + +void OPMapGadgetWidget::onShowSafeAreaAct_toggled(bool show) +{ + if (!m_widget || !m_map) + return; + + m_map->Home->SetShowSafeArea(show); // show the safe area + m_map->Home->RefreshPos(); +} + +void OPMapGadgetWidget::onSafeAreaActGroup_triggered(QAction *action) +{ + if (!m_widget || !m_map || !action) + return; + + int radius = action->data().toInt(); + + m_map->Home->SetSafeArea(radius); // set the radius (meters) + m_map->Home->RefreshPos(); + + // move the magic waypoint if need be to keep it within the safe area around the home position + keepMagicWaypointWithInSafeArea(); +} + +/** +* move the magic waypoint to the home position +**/ +void OPMapGadgetWidget::homeMagicWaypoint() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != MagicWaypoint_MapMode) + return; + + m_magic_waypoint.coord = m_home_position.coord; + + if (m_magic_waypoint.map_wp_item) + m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); +} + +// ************************************************************************************* +// move the UAV to the magic waypoint position + +void OPMapGadgetWidget::moveToMagicWaypointPosition() +{ + if (!m_widget || !m_map) + return; + + if (m_map_mode != MagicWaypoint_MapMode) + return; + +// internals::PointLatLng coord = magic_waypoint.coord; +// double altitude = magic_waypoint.altitude; + + + // ToDo: + +} + +// ************************************************************************************* +// temporary until an object is created for managing the save/restore + +// load the contents of a simple text file into a combobox +void OPMapGadgetWidget::loadComboBoxLines(QComboBox *comboBox, QString filename) +{ + if (!comboBox) return; + if (filename.isNull() || filename.isEmpty()) return; + + QFile file(filename); + if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) + return; + + QTextStream in(&file); + + while (!in.atEnd()) + { + QString line = in.readLine().simplified(); + if (line.isNull() || line.isEmpty()) continue; + comboBox->addItem(line); + } + + file.close(); +} + +// save a combobox text contents to a simple text file +void OPMapGadgetWidget::saveComboBoxLines(QComboBox *comboBox, QString filename) +{ + if (!comboBox) return; + if (filename.isNull() || filename.isEmpty()) return; + + QFile file(filename); + if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) + return; + + QTextStream out(&file); + + for (int i = 0; i < comboBox->count(); i++) + { + QString line = comboBox->itemText(i).simplified(); + if (line.isNull() || line.isEmpty()) continue; + out << line << "\n"; + } + + file.close(); +} + +// ************************************************************************************* +// show/hide the magic waypoint controls + +void OPMapGadgetWidget::hideMagicWaypointControls() +{ + m_widget->lineWaypoint->setVisible(false); + m_widget->toolButtonHomeWaypoint->setVisible(false); + m_widget->toolButtonMoveToWP->setVisible(false); +} + +void OPMapGadgetWidget::showMagicWaypointControls() +{ + m_widget->lineWaypoint->setVisible(true); + m_widget->toolButtonHomeWaypoint->setVisible(true); + + #if defined(allow_manual_home_location_move) + m_widget->toolButtonMoveToWP->setVisible(true); + #else + m_widget->toolButtonMoveToWP->setVisible(false); + #endif +} + +// ************************************************************************************* +// move the magic waypoint to keep it within the safe area boundry + +void OPMapGadgetWidget::keepMagicWaypointWithInSafeArea() +{ + + // calcute the bearing and distance from the home position to the magic waypoint + double dist = distance(m_home_position.coord, m_magic_waypoint.coord); + double bear = bearing(m_home_position.coord, m_magic_waypoint.coord); + + // get the maximum safe distance - in kilometers + double boundry_dist = (double)m_map->Home->SafeArea() / 1000; + +// if (dist <= boundry_dist) +// return; // the magic waypoint is still within the safe area, don't move it + + if (dist > boundry_dist) dist = boundry_dist; + + // move the magic waypoint + + m_magic_waypoint.coord = destPoint(m_home_position.coord, bear, dist); + + if (m_map_mode == MagicWaypoint_MapMode) + { // move the on-screen waypoint + if (m_magic_waypoint.map_wp_item) + m_magic_waypoint.map_wp_item->SetCoord(m_magic_waypoint.coord); + } +} + +// ************************************************************************************* +// return the distance between two points .. in kilometers + +double OPMapGadgetWidget::distance(internals::PointLatLng from, internals::PointLatLng to) +{ + double lat1 = from.Lat() * deg_to_rad; + double lon1 = from.Lng() * deg_to_rad; + + double lat2 = to.Lat() * deg_to_rad; + double lon2 = to.Lng() * deg_to_rad; + + // *********************** + // Haversine formula +/* + double delta_lat = lat2 - lat1; + double delta_lon = lon2 - lon1; + + double t1 = sin(delta_lat / 2); + double t2 = sin(delta_lon / 2); + double a = (t1 * t1) + cos(lat1) * cos(lat2) * (t2 * t2); + double c = 2 * atan2(sqrt(a), sqrt(1 - a)); + + return (earth_mean_radius * c); +*/ + // *********************** + // Spherical Law of Cosines + + return (acos(sin(lat1) * sin(lat2) + cos(lat1) * cos(lat2) * cos(lon2 - lon1)) * earth_mean_radius); + + // *********************** +} + +// ************************************************************************************* +// return the bearing from one point to another .. in degrees + +double OPMapGadgetWidget::bearing(internals::PointLatLng from, internals::PointLatLng to) +{ + double lat1 = from.Lat() * deg_to_rad; + double lon1 = from.Lng() * deg_to_rad; + + double lat2 = to.Lat() * deg_to_rad; + double lon2 = to.Lng() * deg_to_rad; + +// double delta_lat = lat2 - lat1; + double delta_lon = lon2 - lon1; + + double y = sin(delta_lon) * cos(lat2); + double x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(delta_lon); + double bear = atan2(y, x) * rad_to_deg; + + bear += 360; + while (bear < 0) bear += 360; + while (bear >= 360) bear -= 360; + + return bear; +} + +// ************************************************************************************* +// return a destination lat/lon point given a source lat/lon point and the bearing and distance from the source point + +internals::PointLatLng OPMapGadgetWidget::destPoint(internals::PointLatLng source, double bear, double dist) +{ + double lat1 = source.Lat() * deg_to_rad; + double lon1 = source.Lng() * deg_to_rad; + + bear *= deg_to_rad; + + double ad = dist / earth_mean_radius; + + double lat2 = asin(sin(lat1) * cos(ad) + cos(lat1) * sin(ad) * cos(bear)); + double lon2 = lon1 + atan2(sin(bear) * sin(ad) * cos(lat1), cos(ad) - sin(lat1) * sin(lat2)); + + return internals::PointLatLng(lat2 * rad_to_deg, lon2 * rad_to_deg); +} + +// ************************************************************************************* + +bool OPMapGadgetWidget::getUAVPosition(double &latitude, double &longitude, double &altitude) +{ + double BaseECEF[3]; + double NED[3]; + double LLA[3]; + UAVObject *obj; + + if (!obm) + return false; + + obj = dynamic_cast(obm->getObject(QString("HomeLocation"))); + if (!obj) return false; + BaseECEF[0] = obj->getField(QString("ECEF"))->getDouble(0) / 100; + BaseECEF[1] = obj->getField(QString("ECEF"))->getDouble(1) / 100; + BaseECEF[2] = obj->getField(QString("ECEF"))->getDouble(2) / 100; + + obj = dynamic_cast(obm->getObject(QString("PositionActual"))); + if (!obj) return false; + NED[0] = obj->getField(QString("North"))->getDouble() / 100; + NED[1] = obj->getField(QString("East"))->getDouble() / 100; + NED[2] = obj->getField(QString("Down"))->getDouble() / 100; + +// obj = dynamic_cast(om->getObject(QString("PositionDesired"))); + +// obj = dynamic_cast(objManager->getObject("VelocityActual")); // air speed + + Utils::CoordinateConversions().GetLLA(BaseECEF, NED, LLA); + + latitude = LLA[0]; + longitude = LLA[1]; + altitude = LLA[2]; + + if (latitude != latitude) latitude = 0; // nan detection +// if (isNan(latitude)) latitude = 0; // nan detection + else +// if (!isFinite(latitude)) latitude = 0; +// else + if (latitude > 90) latitude = 90; + else + if (latitude < -90) latitude = -90; + + if (longitude != longitude) longitude = 0; // nan detection + else +// if (longitude > std::numeric_limits::max()) longitude = 0; // +infinite +// else +// if (longitude < -std::numeric_limits::max()) longitude = 0; // -infinite +// else + if (longitude > 180) longitude = 180; + else + if (longitude < -180) longitude = -180; + + if (altitude != altitude) altitude = 0; // nan detection + + return true; +} + +double OPMapGadgetWidget::getUAV_Yaw() +{ + if (!obm) + return 0; + + UAVObject *obj = dynamic_cast(obm->getObject(QString("AttitudeActual"))); + double yaw = obj->getField(QString("Yaw"))->getDouble(); + + if (yaw != yaw) yaw = 0; // nan detection + + while (yaw < 0) yaw += 360; + while (yaw >= 360) yaw -= 360; + + return yaw; +} + +bool OPMapGadgetWidget::getGPSPosition(double &latitude, double &longitude, double &altitude) +{ + double LLA[3]; + + if (!obum) + return false; + + if (obum->getGPSPosition(LLA) < 0) + return false; // error + + latitude = LLA[0]; + longitude = LLA[1]; + altitude = LLA[2]; + + return true; +} + +// ************************************************************************************* + +void OPMapGadgetWidget::setMapFollowingMode() +{ + if (!m_widget || !m_map) + return; + + if (!followUAVpositionAct->isChecked()) + { + m_map->UAV->SetMapFollowType(UAVMapFollowType::None); + m_map->SetRotate(0); // reset map rotation to 0deg + } + else + if (!followUAVheadingAct->isChecked()) + { + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); + m_map->SetRotate(0); // reset map rotation to 0deg + } + else + { + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterMap); // the map library won't let you reset the uav rotation if it's already in rotate mode + + m_map->UAV->SetUAVHeading(0); // reset the UAV heading to 0deg + m_map->UAV->SetMapFollowType(UAVMapFollowType::CenterAndRotateMap); + } +} + +// ************************************************************************************* +// update the HomeLocation UAV Object + +bool OPMapGadgetWidget::setHomeLocationObject() +{ + if (!obum) + return false; + + double LLA[3] = {m_home_position.coord.Lat(), m_home_position.coord.Lng(), m_home_position.altitude}; + return (obum->setHomeLocation(LLA, true) >= 0); +} + +// ************************************************************************************* + +void OPMapGadgetWidget::SetUavPic(QString UAVPic) +{ + m_map->SetUavPic(UAVPic); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index 15eddf93d..24f638a80 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -1,347 +1,361 @@ -/** - ****************************************************************************** - * - * @file opmapgadgetwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup OPMapPlugin OpenPilot Map Plugin - * @{ - * @brief The OpenPilot Map plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef OPMAP_GADGETWIDGET_H_ -#define OPMAP_GADGETWIDGET_H_ - -// ****************************************************** - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "opmapcontrol/opmapcontrol.h" - -#include "opmap_overlay_widget.h" -#include "opmap_zoom_slider_widget.h" -#include "opmap_statusbar_widget.h" - -#include "utils/coordinateconversions.h" - -#include "extensionsystem/pluginmanager.h" -#include "uavobjectutilmanager.h" -#include "uavobjectmanager.h" -#include "uavobject.h" -#include "objectpersistence.h" - -// ****************************************************** - -namespace Ui -{ - class OPMap_Widget; -} - -using namespace mapcontrol; - -// ****************************************************** - -typedef struct t_home -{ - internals::PointLatLng coord; - double altitude; - bool locked; -} t_home; - -// local waypoint list item structure -typedef struct t_waypoint -{ - mapcontrol::WayPointItem *map_wp_item; - internals::PointLatLng coord; - double altitude; - QString description; - bool locked; - int time_seconds; - int hold_time_seconds; -} t_waypoint; - -// ****************************************************** - -enum opMapModeType { Normal_MapMode = 0, - MagicWaypoint_MapMode = 1}; - -// ****************************************************** - -class OPMapGadgetWidget : public QWidget -{ - Q_OBJECT - -public: - OPMapGadgetWidget(QWidget *parent = 0); - ~OPMapGadgetWidget(); - - /** - * @brief public functions - * - * @param - */ - void setHome(QPointF pos); - void setHome(internals::PointLatLng pos_lat_lon); - void goHome(); - void setZoom(int zoom); - void setPosition(QPointF pos); - void setMapProvider(QString provider); - void setUseOpenGL(bool useOpenGL); - void setShowTileGridLines(bool showTileGridLines); - void setAccessMode(QString accessMode); - void setUseMemoryCache(bool useMemoryCache); - void setCacheLocation(QString cacheLocation); - void setMapMode(opMapModeType mode); - void SetUavPic(QString UAVPic); - -public slots: - void homePositionUpdated(UAVObject *); - void onTelemetryConnect(); - void onTelemetryDisconnect(); - -protected: - void resizeEvent(QResizeEvent *event); - void mouseMoveEvent(QMouseEvent *event); - void contextMenuEvent(QContextMenuEvent *event); - void keyPressEvent(QKeyEvent* event); - -private slots: - void updatePosition(); - - void updateMousePos(); - - void zoomIn(); - void zoomOut(); - - /** - * @brief signals received from the various map plug-in widget user controls - * - * Some are currently disabled for the v1.0 plugin version. - */ -// void comboBoxFindPlace_returnPressed(); -// void on_toolButtonFindPlace_clicked(); - void on_toolButtonZoomM_clicked(); - void on_toolButtonZoomP_clicked(); - void on_toolButtonMapHome_clicked(); - void on_toolButtonMapUAV_clicked(); - void on_toolButtonMapUAVheading_clicked(); - void on_horizontalSliderZoom_sliderMoved(int position); -// void on_toolButtonAddWaypoint_clicked(); -// void on_treeViewWaypoints_clicked(QModelIndex index); -// void on_toolButtonHome_clicked(); -// void on_toolButtonNextWaypoint_clicked(); -// void on_toolButtonPrevWaypoint_clicked(); -// void on_toolButtonHoldPosition_clicked(); -// void on_toolButtonGo_clicked(); - void on_toolButtonMagicWaypointMapMode_clicked(); - void on_toolButtonNormalMapMode_clicked(); - void on_toolButtonHomeWaypoint_clicked(); - void on_toolButtonMoveToWP_clicked(); - - /** - * @brief signals received from the map object - */ - void zoomChanged(double zoomt,double zoom, double zoomd); - void OnCurrentPositionChanged(internals::PointLatLng point); - void OnTileLoadComplete(); - void OnTileLoadStart(); - void OnMapDrag(); - void OnMapZoomChanged(); - void OnMapTypeChanged(MapType::Types type); - void OnEmptyTileError(int zoom, core::Point pos); - void OnTilesStillToLoad(int number); - - /** - * Unused for now, hooks for future waypoint support - */ - void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); - void WPValuesChanged(WayPointItem* waypoint); - void WPInserted(int const& number, WayPointItem* waypoint); - void WPDeleted(int const& number); - - /** - * @brief mouse right click context menu signals - */ - void onReloadAct_triggered(); - void onCopyMouseLatLonToClipAct_triggered(); - void onCopyMouseLatToClipAct_triggered(); - void onCopyMouseLonToClipAct_triggered(); -// void onFindPlaceAct_triggered(); - void onShowCompassAct_toggled(bool show); - void onShowDiagnostics_toggled(bool show); - void onShowUAVAct_toggled(bool show); - void onShowHomeAct_toggled(bool show); - void onShowTrailLineAct_toggled(bool show); - void onShowTrailAct_toggled(bool show); - void onGoZoomInAct_triggered(); - void onGoZoomOutAct_triggered(); - void onGoMouseClickAct_triggered(); - void onSetHomeAct_triggered(); - void onGoHomeAct_triggered(); - void onGoUAVAct_triggered(); - void onFollowUAVpositionAct_toggled(bool checked); - void onFollowUAVheadingAct_toggled(bool checked); -/* - void onOpenWayPointEditorAct_triggered(); - void onAddWayPointAct_triggered(); - void onEditWayPointAct_triggered(); - void onLockWayPointAct_triggered(); - void onDeleteWayPointAct_triggered(); - void onClearWayPointsAct_triggered(); -*/ - void onMapModeActGroup_triggered(QAction *action); - void onZoomActGroup_triggered(QAction *action); - void onHomeMagicWaypointAct_triggered(); - void onShowSafeAreaAct_toggled(bool show); - void onSafeAreaActGroup_triggered(QAction *action); - void onUAVTrailTypeActGroup_triggered(QAction *action); - void onClearUAVtrailAct_triggered(); - void onUAVTrailTimeActGroup_triggered(QAction *action); - void onUAVTrailDistanceActGroup_triggered(QAction *action); - -private: - int min_zoom; - int max_zoom; - - double m_heading; // uav heading - - internals::PointLatLng mouse_lat_lon; - internals::PointLatLng context_menu_lat_lon; - - int prev_tile_number; - - opMapModeType m_map_mode; - - t_home home_position; - - t_waypoint magic_waypoint; - - QStringList findPlaceWordList; - QCompleter *findPlaceCompleter; - - QTimer *m_updateTimer; - QTimer *m_statusUpdateTimer; - - Ui::OPMap_Widget *m_widget; - - mapcontrol::OPMapWidget *m_map; - - ExtensionSystem::PluginManager *pm; - UAVObjectManager *obm; - UAVObjectUtilManager *obum; - - //opmap_waypointeditor_dialog waypoint_editor_dialog; - - //opmap_edit_waypoint_dialog waypoint_edit_dialog; - - QStandardItemModel wayPoint_treeView_model; - - mapcontrol::WayPointItem *m_mouse_waypoint; - - QList m_waypoint_list; - QMutex m_waypoint_list_mutex; - - QMutex m_map_mutex; - - bool telemetry_connected; - - void createActions(); - - QAction *closeAct1; - QAction *closeAct2; - QAction *reloadAct; - QAction *copyMouseLatLonToClipAct; - QAction *copyMouseLatToClipAct; - QAction *copyMouseLonToClipAct; - QAction *findPlaceAct; - QAction *showCompassAct; - QAction *showDiagnostics; - QAction *showHomeAct; - QAction *showUAVAct; - QAction *zoomInAct; - QAction *zoomOutAct; - QAction *goMouseClickAct; - QAction *setHomeAct; - QAction *goHomeAct; - QAction *goUAVAct; - QAction *followUAVpositionAct; - QAction *followUAVheadingAct; - /* - QAction *wayPointEditorAct; - QAction *addWayPointAct; - QAction *editWayPointAct; - QAction *lockWayPointAct; - QAction *deleteWayPointAct; - QAction *clearWayPointsAct; - */ - QAction *homeMagicWaypointAct; - - QAction *showSafeAreaAct; - QActionGroup *safeAreaActGroup; - QList safeAreaAct; - - QActionGroup *uavTrailTypeActGroup; - QList uavTrailTypeAct; - QAction *clearUAVtrailAct; - QActionGroup *uavTrailTimeActGroup; - QAction *showTrailLineAct; - QAction *showTrailAct; - QList uavTrailTimeAct; - QActionGroup *uavTrailDistanceActGroup; - QList uavTrailDistanceAct; - - QActionGroup *mapModeActGroup; - QList mapModeAct; - - QActionGroup *zoomActGroup; - QList zoomAct; - - void homeMagicWaypoint(); - - void moveToMagicWaypointPosition(); - - void loadComboBoxLines(QComboBox *comboBox, QString filename); - void saveComboBoxLines(QComboBox *comboBox, QString filename); - - void hideMagicWaypointControls(); - void showMagicWaypointControls(); - - void keepMagicWaypointWithInSafeArea(); - - double distance(internals::PointLatLng from, internals::PointLatLng to); - double bearing(internals::PointLatLng from, internals::PointLatLng to); - internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist); - - bool getUAVPosition(double &latitude, double &longitude, double &altitude); - bool getGPSPosition(double &latitude, double &longitude, double &altitude); - double getUAV_Yaw(); - - void setMapFollowingMode(); - - bool setHomeLocationObject(); -}; - -#endif /* OPMAP_GADGETWIDGET_H_ */ +/** + ****************************************************************************** + * + * @file opmapgadgetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup OPMapPlugin OpenPilot Map Plugin + * @{ + * @brief The OpenPilot Map plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef OPMAP_GADGETWIDGET_H_ +#define OPMAP_GADGETWIDGET_H_ + +// ****************************************************** + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "opmapcontrol/opmapcontrol.h" + +#include "opmap_overlay_widget.h" +#include "opmap_zoom_slider_widget.h" +#include "opmap_statusbar_widget.h" + +#include "utils/coordinateconversions.h" + +#include "extensionsystem/pluginmanager.h" +#include "uavobjectutilmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "objectpersistence.h" + +// ****************************************************** + +namespace Ui +{ + class OPMap_Widget; +} + +using namespace mapcontrol; + +// ****************************************************** + +typedef struct t_home +{ + internals::PointLatLng coord; + double altitude; + bool locked; +} t_home; + +// local waypoint list item structure +typedef struct t_waypoint +{ + mapcontrol::WayPointItem *map_wp_item; + internals::PointLatLng coord; + double altitude; + QString description; + bool locked; + int time_seconds; + int hold_time_seconds; +} t_waypoint; + +// ****************************************************** + +enum opMapModeType { Normal_MapMode = 0, + MagicWaypoint_MapMode = 1}; + +// ****************************************************** + +class OPMapGadgetWidget : public QWidget +{ + Q_OBJECT + +public: + OPMapGadgetWidget(QWidget *parent = 0); + ~OPMapGadgetWidget(); + + /** + * @brief public functions + * + * @param + */ + void setHome(QPointF pos); + void setHome(internals::PointLatLng pos_lat_lon); + void goHome(); + void setZoom(int zoom); + void setPosition(QPointF pos); + void setMapProvider(QString provider); + void setUseOpenGL(bool useOpenGL); + void setShowTileGridLines(bool showTileGridLines); + void setAccessMode(QString accessMode); + void setUseMemoryCache(bool useMemoryCache); + void setCacheLocation(QString cacheLocation); + void setMapMode(opMapModeType mode); + void SetUavPic(QString UAVPic); + void setMaxUpdateRate(int update_rate); + +public slots: + void homePositionUpdated(UAVObject *); + void onTelemetryConnect(); + void onTelemetryDisconnect(); + +protected: + void resizeEvent(QResizeEvent *event); + void mouseMoveEvent(QMouseEvent *event); + void contextMenuEvent(QContextMenuEvent *event); + void keyPressEvent(QKeyEvent* event); + +private slots: + void updatePosition(); + + void updateMousePos(); + + void zoomIn(); + void zoomOut(); + + /** + * @brief signals received from the various map plug-in widget user controls + * + * Some are currently disabled for the v1.0 plugin version. + */ +// void comboBoxFindPlace_returnPressed(); +// void on_toolButtonFindPlace_clicked(); + void on_toolButtonZoomM_clicked(); + void on_toolButtonZoomP_clicked(); + void on_toolButtonMapHome_clicked(); + void on_toolButtonMapUAV_clicked(); + void on_toolButtonMapUAVheading_clicked(); + void on_horizontalSliderZoom_sliderMoved(int position); +// void on_toolButtonAddWaypoint_clicked(); +// void on_treeViewWaypoints_clicked(QModelIndex index); +// void on_toolButtonHome_clicked(); +// void on_toolButtonNextWaypoint_clicked(); +// void on_toolButtonPrevWaypoint_clicked(); +// void on_toolButtonHoldPosition_clicked(); +// void on_toolButtonGo_clicked(); + void on_toolButtonMagicWaypointMapMode_clicked(); + void on_toolButtonNormalMapMode_clicked(); + void on_toolButtonHomeWaypoint_clicked(); + void on_toolButtonMoveToWP_clicked(); + + /** + * @brief signals received from the map object + */ + void zoomChanged(double zoomt,double zoom, double zoomd); + void OnCurrentPositionChanged(internals::PointLatLng point); + void OnTileLoadComplete(); + void OnTileLoadStart(); + void OnMapDrag(); + void OnMapZoomChanged(); + void OnMapTypeChanged(MapType::Types type); + void OnEmptyTileError(int zoom, core::Point pos); + void OnTilesStillToLoad(int number); + + /** + * Unused for now, hooks for future waypoint support + */ + void WPNumberChanged(int const& oldnumber,int const& newnumber, WayPointItem* waypoint); + void WPValuesChanged(WayPointItem* waypoint); + void WPInserted(int const& number, WayPointItem* waypoint); + void WPDeleted(int const& number); + + /** + * @brief mouse right click context menu signals + */ + void onReloadAct_triggered(); + void onCopyMouseLatLonToClipAct_triggered(); + void onCopyMouseLatToClipAct_triggered(); + void onCopyMouseLonToClipAct_triggered(); +// void onFindPlaceAct_triggered(); + void onShowCompassAct_toggled(bool show); + void onShowDiagnostics_toggled(bool show); + void onShowUAVAct_toggled(bool show); + void onShowHomeAct_toggled(bool show); + void onShowTrailLineAct_toggled(bool show); + void onShowTrailAct_toggled(bool show); + void onGoZoomInAct_triggered(); + void onGoZoomOutAct_triggered(); + void onGoMouseClickAct_triggered(); + void onSetHomeAct_triggered(); + void onGoHomeAct_triggered(); + void onGoUAVAct_triggered(); + void onFollowUAVpositionAct_toggled(bool checked); + void onFollowUAVheadingAct_toggled(bool checked); +/* + void onOpenWayPointEditorAct_triggered(); + void onAddWayPointAct_triggered(); + void onEditWayPointAct_triggered(); + void onLockWayPointAct_triggered(); + void onDeleteWayPointAct_triggered(); + void onClearWayPointsAct_triggered(); +*/ + void onMapModeActGroup_triggered(QAction *action); + void onZoomActGroup_triggered(QAction *action); + void onHomeMagicWaypointAct_triggered(); + void onShowSafeAreaAct_toggled(bool show); + void onSafeAreaActGroup_triggered(QAction *action); + void onUAVTrailTypeActGroup_triggered(QAction *action); + void onClearUAVtrailAct_triggered(); + void onUAVTrailTimeActGroup_triggered(QAction *action); + void onUAVTrailDistanceActGroup_triggered(QAction *action); + void onMaxUpdateRateActGroup_triggered(QAction *action); + +private: + + // ***** + + int m_min_zoom; + int m_max_zoom; + + double m_heading; // uav heading + + internals::PointLatLng m_mouse_lat_lon; + internals::PointLatLng m_context_menu_lat_lon; + + int m_prev_tile_number; + + opMapModeType m_map_mode; + + int m_maxUpdateRate; + + t_home m_home_position; + + t_waypoint m_magic_waypoint; + + QStringList findPlaceWordList; + QCompleter *findPlaceCompleter; + + QTimer *m_updateTimer; + QTimer *m_statusUpdateTimer; + + Ui::OPMap_Widget *m_widget; + + mapcontrol::OPMapWidget *m_map; + + ExtensionSystem::PluginManager *pm; + UAVObjectManager *obm; + UAVObjectUtilManager *obum; + + //opmap_waypointeditor_dialog waypoint_editor_dialog; + + //opmap_edit_waypoint_dialog waypoint_edit_dialog; + + QStandardItemModel wayPoint_treeView_model; + + mapcontrol::WayPointItem *m_mouse_waypoint; + + QList m_waypoint_list; + QMutex m_waypoint_list_mutex; + + QMutex m_map_mutex; + + bool m_telemetry_connected; + + // ***** + + void createActions(); + + QAction *closeAct1; + QAction *closeAct2; + QAction *reloadAct; + QAction *copyMouseLatLonToClipAct; + QAction *copyMouseLatToClipAct; + QAction *copyMouseLonToClipAct; + QAction *findPlaceAct; + QAction *showCompassAct; + QAction *showDiagnostics; + QAction *showHomeAct; + QAction *showUAVAct; + QAction *zoomInAct; + QAction *zoomOutAct; + QAction *goMouseClickAct; + QAction *setHomeAct; + QAction *goHomeAct; + QAction *goUAVAct; + QAction *followUAVpositionAct; + QAction *followUAVheadingAct; + /* + QAction *wayPointEditorAct; + QAction *addWayPointAct; + QAction *editWayPointAct; + QAction *lockWayPointAct; + QAction *deleteWayPointAct; + QAction *clearWayPointsAct; + */ + QAction *homeMagicWaypointAct; + + QAction *showSafeAreaAct; + QActionGroup *safeAreaActGroup; + QList safeAreaAct; + + QActionGroup *uavTrailTypeActGroup; + QList uavTrailTypeAct; + QAction *clearUAVtrailAct; + QActionGroup *uavTrailTimeActGroup; + QAction *showTrailLineAct; + QAction *showTrailAct; + QList uavTrailTimeAct; + QActionGroup *uavTrailDistanceActGroup; + QList uavTrailDistanceAct; + + QActionGroup *mapModeActGroup; + QList mapModeAct; + + QActionGroup *zoomActGroup; + QList zoomAct; + + QActionGroup *maxUpdateRateActGroup; + QList maxUpdateRateAct; + + // ***** + + void homeMagicWaypoint(); + + void moveToMagicWaypointPosition(); + + void loadComboBoxLines(QComboBox *comboBox, QString filename); + void saveComboBoxLines(QComboBox *comboBox, QString filename); + + void hideMagicWaypointControls(); + void showMagicWaypointControls(); + + void keepMagicWaypointWithInSafeArea(); + + double distance(internals::PointLatLng from, internals::PointLatLng to); + double bearing(internals::PointLatLng from, internals::PointLatLng to); + internals::PointLatLng destPoint(internals::PointLatLng source, double bear, double dist); + + bool getUAVPosition(double &latitude, double &longitude, double &altitude); + bool getGPSPosition(double &latitude, double &longitude, double &altitude); + double getUAV_Yaw(); + + void setMapFollowingMode(); + + bool setHomeLocationObject(); +}; + +#endif /* OPMAP_GADGETWIDGET_H_ */ From 2d6b4dce556bc3c0830f6083ebdb0c1ed72c75ea Mon Sep 17 00:00:00 2001 From: elafargue Date: Sat, 14 May 2011 16:31:59 +0200 Subject: [PATCH 24/43] Small fix to System Health gadget, to make it behave correctly when started while the connection is up already. --- .../plugins/systemhealth/systemhealthgadgetwidget.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp index 7a0d5066f..440ff58df 100644 --- a/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp @@ -151,6 +151,16 @@ void SystemHealthGadgetWidget::setSystemFile(QString dfn) QGraphicsScene *l_scene = scene(); l_scene->setSceneRect(background->boundingRect()); fitInView(background, Qt::KeepAspectRatio ); + + // Check whether the autopilot is connected already, by the way: + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + TelemetryManager* telMngr = pm->getObject(); + if (telMngr->isConnected()) { + onAutopilotConnect(); + SystemAlarms* obj = dynamic_cast(objManager->getObject(QString("SystemAlarms"))); + updateAlarms(obj); + } } } else From a38fbe6cea0ba3dca56c58f83e0db8b0bdff8672 Mon Sep 17 00:00:00 2001 From: zedamota Date: Sat, 14 May 2011 19:03:31 +0100 Subject: [PATCH 25/43] Make CopterControl firmware non functional when using the ERASE_FLASH=YES compile flag --- flight/CopterControl/System/coptercontrol.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/CopterControl/System/coptercontrol.c index 588fa4a9f..060fb3646 100644 --- a/flight/CopterControl/System/coptercontrol.c +++ b/flight/CopterControl/System/coptercontrol.c @@ -92,6 +92,7 @@ void OpenPilotInit() #ifdef ERASE_FLASH PIOS_Flash_W25X_EraseChip(); + while(TRUE){}; #endif /* Initialize modules */ From 7e6e7bb391526de130301329fb2f9d03b9dc4fb7 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 12:19:48 -0500 Subject: [PATCH 26/43] OP-499 OP-216: Simple list of objects saved in flash to prevent objId collision. Note, this will wipe ALL your settings. --- flight/PiOS/Common/pios_flashfs_objlist.c | 261 ++++++++++++++++++++++ flight/PiOS/inc/pios_flashfs_objlist.h | 37 +++ 2 files changed, 298 insertions(+) create mode 100644 flight/PiOS/Common/pios_flashfs_objlist.c create mode 100644 flight/PiOS/inc/pios_flashfs_objlist.h diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c new file mode 100644 index 000000000..0b13a239a --- /dev/null +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -0,0 +1,261 @@ +/** + ****************************************************************************** + * + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_FLASHFS_OBJLIST Object list based flash filesystem (low ram) + * @{ + * + * @file pios_flashfs_objlist.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief A file system for storing UAVObject in flash chip + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#include "openpilot.h" +#include "uavobjectmanager.h" + +// Private functions +static int32_t PIOS_FLASHFS_EraseLocationHeader(); +static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId); +static int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId); + +// Private variables +static int32_t numObjects = -1; + +// Private structures +// Header for objects in the file system table +struct objectHeader { + uint32_t objMagic; + uint32_t objId; + uint32_t instId; + uint32_t address; +} __attribute__((packed));; + +struct fileHeader { + uint32_t id; + uint16_t instId; + uint16_t size; +} __attribute__((packed)); + + + +#define OBJ_MAGIC 0x3015AE71 +#define OBJECT_TABLE_START 0 +#define OBJECT_TABLE_END 0x00001000 +#define SECTOR_SIZE 0x00001000 + +/** + * @brief Initialize the flash object setting FS + * @return 0 if success, -1 if failure + */ +int32_t PIOS_FLASHFS_Init() +{ + numObjects = 0; + bool found = true; + int32_t addr = OBJECT_TABLE_START; + struct objectHeader header; + + // Loop through header area while objects detect to count how many saved + while(found && addr < OBJECT_TABLE_END) { + // Read the instance data + if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0) + return -1; + if(header.objMagic != OBJ_MAGIC) + found = false; + else + numObjects++; + } +} + +/** + * @brief Erase the headers for all objects in the flash chip + * @return 0 if successful, -1 if not + */ +static int32_t PIOS_FLASHFS_EraseLocationHeader() +{ + if(PIOS_Flash_W25X_EraseSector(OBJECT_TABLE_START) != 0) + return -1; + return 0; +} + +/** + * @brief Get the address of an object + * @param obj UAVObjHandle for that object + * @parma instId Instance id for that object + * @return 0 if success, -1 if not found + */ +static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) +{ + bool found = true; + int32_t addr = OBJECT_TABLE_START; + struct objectHeader header; + + // Loop through header area while objects detect to count how many saved + while(found && addr < OBJECT_TABLE_END) { + // Read the instance data + if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) + return -1; + if(header.objMagic != OBJ_MAGIC) + found = false; + else if (header.objId == objId && header.instId == instId) + break; + } + + if (found) + return header.address; +} + +/** + * @brief Returns an address for a new object and creates entry into object table + * @param[in] obj Object handle for object to be saved + * @param[in] instId The instance id of object to be saved + * @return 0 if success or error code + * @retval -1 Object not found + * @retval -2 No room in object table + * @retval -3 Unable to write entry into object table + * @retval -4 FS not initialized + */ +int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId) +{ + int32_t addr = OBJECT_TABLE_START; + struct objectHeader header; + + if(numObjects < 0) + return -4; + + // Don't worry about max size of flash chip here, other code will catch that + header.objMagic = OBJ_MAGIC; + header.objId = objId; + header.instId = instId; + header.address = SECTOR_SIZE * numObjects; + + // No room for this header in object table + if((addr + sizeof(header)) > OBJECT_TABLE_END) + return -2; + + if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0) + return -3; + + // This numObejcts value must stay consistent or there will be a break in the table + // and later the table will have bad values in it + numObjects++; + return header.address; +} + + +/** + * @brief Saves one object instance per sector + * @param[in] obj UAVObjHandle the object to save + * @param[in] instId The instance of the object to save + * @return 0 if success or -1 if failure + * @note This uses one sector on the flash chip per object so that no buffering in ram + * must be done when erasing the sector before a save + */ +int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) +{ + uint32_t objId = UAVObjGetID(obj); + + int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId); + + // Object currently not saved + if(addr < 0) + addr = PIOS_FLASHFS_GetNewAddress(objId, instId); + + // Could not allocate a sector + if(addr < 0) + return -1; + + struct fileHeader header = { + .id = objId, + .instId = instId, + .size = UAVObjGetNumBytes(obj); + }; + + uint32_t addr = (objEntry->id & FLASH_MASK); + PIOS_Flash_W25X_EraseSector(addr); + + // Save header + // This information IS redundant with the object table id. Oh well. Better safe than sorry. + PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)); + + // Save data + PIOS_Flash_W25X_WriteData(addr + sizeof(header), data,objEntry->numBytes); +} + +/** + * @brief Load one object instance per sector + * @param[in] obj UAVObjHandle the object to save + * @param[in] instId The instance of the object to save + * @return 0 if success or error code + * @retval -1 if object not in file table + * @retval -2 if loaded data instId or objId don't match + * @retval -3 if unable to retrieve instance data + * @note This uses one sector on the flash chip per object so that no buffering in ram + * must be done when erasing the sector before a save + */ +int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data) +{ + uint32_t objId = UAVObjGetID(obj); + + int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId); + + // Object currently not saved + if(addr < 0) + return -1; + + struct fileHeader header; + + // Load header + // This information IS redundant with the object table id. Oh well. Better safe than sorry. + PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)); + + if((header.id != objId) || (header.instId != instId)) + return -2; + + // Read the instance data + if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, objEntry->numBytes) != 0) + return -3 +} + +/** + * @brief Delete object from flash + * @param[in] obj UAVObjHandle the object to save + * @param[in] instId The instance of the object to save + * @return 0 if success or error code + * @retval -1 if object not in file table + * @retval -2 Erase failed + * @note To avoid buffering the file table (1k ram!) the entry in the file table + * remains but destination sector is erased. This will make the load fail as the + * file header won't match the object. At next save it goes back there. + */ +int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId) +{ + uint32_t objId = UAVObjGetID(obj); + + int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId); + + // Object currently not saved + if(addr < 0) + return -1; + + if(PIOS_Flash_W25X_EraseSector(addr) != 0) + return -2; +} \ No newline at end of file diff --git a/flight/PiOS/inc/pios_flashfs_objlist.h b/flight/PiOS/inc/pios_flashfs_objlist.h new file mode 100644 index 000000000..945df4068 --- /dev/null +++ b/flight/PiOS/inc/pios_flashfs_objlist.h @@ -0,0 +1,37 @@ +/** + ****************************************************************************** + * + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_FLASHFS_OBJLIST Object list based flash filesystem (low ram) + * @{ + * + * @file pios_flashfs_objlist.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief A file system for storing UAVObject in flash chip + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" +#include "uavobjectmanager.h" + +int32_t PIOS_FLASHFS_Init(); +int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data); +int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data); +int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId); \ No newline at end of file From 2087441006e2a98b52f827e1a7cf6bef04fa06ef Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 14:23:02 -0500 Subject: [PATCH 27/43] OP-216: Make the object manager use new flash fs for objects --- flight/CopterControl/Makefile | 1 + flight/CopterControl/System/pios_board.c | 4 +- flight/PiOS/pios.h | 271 +++++++++--------- .../OpenPilotOSX.xcodeproj/project.pbxproj | 4 + flight/UAVObjects/uavobjectmanager.c | 44 +-- 5 files changed, 149 insertions(+), 175 deletions(-) diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index f499d549a..7c3895534 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -205,6 +205,7 @@ SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c ## PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c SRC += $(PIOSCOMMON)/pios_flash_w25x.c SRC += $(PIOSCOMMON)/pios_adxl345.c SRC += $(PIOSCOMMON)/pios_com.c diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index 45164052f..c5943ca3c 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -678,8 +678,10 @@ void PIOS_Board_Init(void) { PIOS_DEBUG_Assert(0); } - PIOS_Flash_W25X_Init(pios_spi_flash_accel_id); + PIOS_Flash_W25X_Init(pios_spi_flash_accel_id); PIOS_ADXL345_Attach(pios_spi_flash_accel_id); + + PIOS_FLASHFS_Init(); #if defined(PIOS_INCLUDE_SPEKTRUM) /* SPEKTRUM init must come before comms */ diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index cbf2a2249..0fdb03570 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -1,135 +1,136 @@ -/** - ****************************************************************************** - * - * @file pios.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Main PiOS header. - * - Central header for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_H -#define PIOS_H - -/* PIOS Feature Selection */ -#include "pios_config.h" - -#if defined(PIOS_INCLUDE_FREERTOS) -/* FreeRTOS Includes */ -#include "FreeRTOS.h" -#include "task.h" -#include "queue.h" -#include "semphr.h" -#endif - -/* C Lib Includes */ -#include -#include -#include -#include -#include - -/* STM32 Std Perf Lib */ -#include -#include - -#if defined(PIOS_INCLUDE_SDCARD) -/* Dosfs Includes */ -#include - -/* Mass Storage Device Includes */ -#include -#endif - -/* Generic initcall infrastructure */ -#include "pios_initcall.h" - -/* PIOS Board Specific Device Configuration */ -#include "pios_board.h" - -/* PIOS Hardware Includes (STM32F10x) */ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#if defined(PIOS_INCLUDE_EXTI) -#include -#endif -#include - -/* PIOS Hardware Includes (Common) */ -#include -#include -#if defined(PIOS_INCLUDE_BMP085) -#include -#endif -#if defined(PIOS_INCLUDE_HCSR04) -#include -#endif -#if defined(PIOS_INCLUDE_HMC5843) -#include -#endif -#if defined(PIOS_INCLUDE_HMC5883) -#include -#endif -#if defined(PIOS_INCLUDE_I2C_ESC) -#include -#endif -#if defined(PIOS_INCLUDE_IMU3000) -#include -#endif -#include - -#if defined(PIOS_INCLUDE_ADXL345) -#include -#endif - -#if defined(PIOS_INCLUDE_BMA180) -#include -#endif - -#if defined(PIOS_INCLUDE_FLASH) -#include -#endif - -#if defined(PIOS_INCLUDE_BL_HELPER) -#include -#endif - -#if defined(PIOS_INCLUDE_USB) -/* USB Libs */ -#include -#endif - -#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) - -#endif /* PIOS_H */ +/** + ****************************************************************************** + * + * @file pios.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Main PiOS header. + * - Central header for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef PIOS_H +#define PIOS_H + +/* PIOS Feature Selection */ +#include "pios_config.h" + +#if defined(PIOS_INCLUDE_FREERTOS) +/* FreeRTOS Includes */ +#include "FreeRTOS.h" +#include "task.h" +#include "queue.h" +#include "semphr.h" +#endif + +/* C Lib Includes */ +#include +#include +#include +#include +#include + +/* STM32 Std Perf Lib */ +#include +#include + +#if defined(PIOS_INCLUDE_SDCARD) +/* Dosfs Includes */ +#include + +/* Mass Storage Device Includes */ +#include +#endif + +/* Generic initcall infrastructure */ +#include "pios_initcall.h" + +/* PIOS Board Specific Device Configuration */ +#include "pios_board.h" + +/* PIOS Hardware Includes (STM32F10x) */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if defined(PIOS_INCLUDE_EXTI) +#include +#endif +#include + +/* PIOS Hardware Includes (Common) */ +#include +#include +#if defined(PIOS_INCLUDE_BMP085) +#include +#endif +#if defined(PIOS_INCLUDE_HCSR04) +#include +#endif +#if defined(PIOS_INCLUDE_HMC5843) +#include +#endif +#if defined(PIOS_INCLUDE_HMC5883) +#include +#endif +#if defined(PIOS_INCLUDE_I2C_ESC) +#include +#endif +#if defined(PIOS_INCLUDE_IMU3000) +#include +#endif +#include + +#if defined(PIOS_INCLUDE_ADXL345) +#include +#endif + +#if defined(PIOS_INCLUDE_BMA180) +#include +#endif + +#if defined(PIOS_INCLUDE_FLASH) +#include +#include +#endif + +#if defined(PIOS_INCLUDE_BL_HELPER) +#include +#endif + +#if defined(PIOS_INCLUDE_USB) +/* USB Libs */ +#include +#endif + +#define NELEMENTS(x) (sizeof(x) / sizeof(*(x))) + +#endif /* PIOS_H */ diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj index 5dd95349b..7095dfad5 100644 --- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj +++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj @@ -3171,6 +3171,8 @@ 65FF4BE913791C3300146BE4 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; 65FF4BEA13791C3300146BE4 /* op_dfu.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = op_dfu.c; sourceTree = ""; }; 65FF4BEB13791C3300146BE4 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = ""; }; + 65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_flashfs_objlist.c; sourceTree = ""; }; + 65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_flashfs_objlist.h; sourceTree = ""; }; /* End PBXFileReference section */ /* Begin PBXGroup section */ @@ -7657,6 +7659,7 @@ 65E8F03711EFF25C00BBF654 /* printf-stdarg.c */, 6528CCB412E406B800CF5144 /* pios_adxl345.c */, 6512D60712ED4CB8008175E5 /* pios_flash_w25x.c */, + 65FF4D5E137EDEC100146BE4 /* pios_flashfs_objlist.c */, ); name = Common; path = ../../PiOS/Common; @@ -7681,6 +7684,7 @@ 65E8F03E11EFF25C00BBF654 /* pios_debug.h */, 65E8F03F11EFF25C00BBF654 /* pios_delay.h */, 65E8F04011EFF25C00BBF654 /* pios_exti.h */, + 65FF4D61137EFA4F00146BE4 /* pios_flashfs_objlist.h */, 65E8F04111EFF25C00BBF654 /* pios_gpio.h */, 65E8F04211EFF25C00BBF654 /* pios_hmc5843.h */, 65E8F04311EFF25C00BBF654 /* pios_i2c.h */, diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/UAVObjects/uavobjectmanager.c index 50558d411..2d681ab3b 100644 --- a/flight/UAVObjects/uavobjectmanager.c +++ b/flight/UAVObjects/uavobjectmanager.c @@ -562,14 +562,6 @@ int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, FILEINFO* file) return 0; } -struct fileHeader { - uint32_t id; - uint16_t instId; - uint16_t size; -} __attribute__((packed)); - -#define FLASH_MASK 0x001ff000 /* Select a sector */ - /** * Save the data of the specified object to the file system (SD card). * If the object contains multiple instances, all of them will be saved. @@ -596,17 +588,8 @@ int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId) if(instEntry->data == NULL) return -1; - - struct fileHeader header = { - .id = objEntry->id, - .instId = instId, - .size = objEntry->numBytes - }; - - uint32_t addr = (objEntry->id & FLASH_MASK); - PIOS_Flash_W25X_EraseSector(addr); - PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)); - PIOS_Flash_W25X_WriteData(addr + sizeof(header), instEntry->data,objEntry->numBytes); + if(PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0) + return -1; #endif #if defined(PIOS_INCLUDE_SDCARD) FILEINFO file; @@ -758,19 +741,8 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) if(instEntry->data == NULL) return -1; - struct fileHeader header; - uint32_t addr = (objEntry->id & FLASH_MASK); - - PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)); - - if(header.id != objEntry->id) - return -1; - - // Read the instance data - if (PIOS_Flash_W25X_ReadData(addr + sizeof(header) ,instEntry->data, objEntry->numBytes) != 0) - return -1; - - // Fire event + // Fire event on success + if(PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) == 0) sendEvent(objEntry, instId, EV_UNPACKED); #endif @@ -837,13 +809,7 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId) { #if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) - ObjectList* objEntry = (ObjectList*)obj; - - if(objEntry == NULL) - return -1; - - uint32_t addr = (objEntry->id & FLASH_MASK); - PIOS_Flash_W25X_EraseSector(addr); + PIOS_FLASHFS_ObjDelete(obj, instId); #endif #if defined(PIOS_INCLUDE_SDCARD) ObjectList* objEntry; From 0438f5cf664b319c8a109d93ee08cdc651dfd2fc Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 14:23:23 -0500 Subject: [PATCH 28/43] OP-216: Check for existence of file table in flash and wipe sector and create it if missing. --- flight/PiOS/Common/pios_flashfs_objlist.c | 50 +++++++++++++++++------ 1 file changed, 37 insertions(+), 13 deletions(-) diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index 0b13a239a..5e403599b 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -33,7 +33,7 @@ #include "uavobjectmanager.h" // Private functions -static int32_t PIOS_FLASHFS_EraseLocationHeader(); +static int32_t PIOS_FLAHFS_CleabObjectTableHeader(); static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId); static int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId); @@ -56,9 +56,9 @@ struct fileHeader { } __attribute__((packed)); - +#define OBJECT_TABLE_MAGIC 0x85FB3C33 #define OBJ_MAGIC 0x3015AE71 -#define OBJECT_TABLE_START 0 +#define OBJECT_TABLE_START 0x00000010 #define OBJECT_TABLE_END 0x00001000 #define SECTOR_SIZE 0x00001000 @@ -68,11 +68,21 @@ struct fileHeader { */ int32_t PIOS_FLASHFS_Init() { - numObjects = 0; + + // Check for valid object table or create one + uint32_t object_table_magic; + if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) + return -1; + if(object_table_magic != OBJECT_TABLE_MAGIC) { + if(PIOS_FLAHFS_CleabObjectTableHeader() < 0) + return -1; + } + bool found = true; int32_t addr = OBJECT_TABLE_START; struct objectHeader header; - + numObjects = 0; + // Loop through header area while objects detect to count how many saved while(found && addr < OBJECT_TABLE_END) { // Read the instance data @@ -82,17 +92,24 @@ int32_t PIOS_FLASHFS_Init() found = false; else numObjects++; - } + } + + return 0; } /** * @brief Erase the headers for all objects in the flash chip * @return 0 if successful, -1 if not */ -static int32_t PIOS_FLASHFS_EraseLocationHeader() +static int32_t PIOS_FLAHFS_CleabObjectTableHeader() { if(PIOS_Flash_W25X_EraseSector(OBJECT_TABLE_START) != 0) return -1; + + uint32_t object_table_magic = OBJECT_TABLE_MAGIC; + if (PIOS_Flash_W25X_WriteData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) + return -1; + return 0; } @@ -100,7 +117,7 @@ static int32_t PIOS_FLASHFS_EraseLocationHeader() * @brief Get the address of an object * @param obj UAVObjHandle for that object * @parma instId Instance id for that object - * @return 0 if success, -1 if not found + * @return address if successful, -1 if not found */ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) { @@ -121,6 +138,8 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) if (found) return header.address; + + return -1; } /** @@ -186,10 +205,9 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) struct fileHeader header = { .id = objId, .instId = instId, - .size = UAVObjGetNumBytes(obj); + .size = UAVObjGetNumBytes(obj) }; - uint32_t addr = (objEntry->id & FLASH_MASK); PIOS_Flash_W25X_EraseSector(addr); // Save header @@ -197,7 +215,9 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)); // Save data - PIOS_Flash_W25X_WriteData(addr + sizeof(header), data,objEntry->numBytes); + PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)); + + return 0; } /** @@ -231,8 +251,10 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data) return -2; // Read the instance data - if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, objEntry->numBytes) != 0) - return -3 + if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0) + return -3; + + return 0; } /** @@ -258,4 +280,6 @@ int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId) if(PIOS_Flash_W25X_EraseSector(addr) != 0) return -2; + + return 0; } \ No newline at end of file From c689d979615af353afac26fe25f0608f535ff18a Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 14:28:11 -0500 Subject: [PATCH 29/43] OP-216: Improved error handling --- flight/PiOS/Common/pios_flash_w25x.c | 8 ++++++++ flight/PiOS/Common/pios_flashfs_objlist.c | 22 ++++++++++++++-------- 2 files changed, 22 insertions(+), 8 deletions(-) diff --git a/flight/PiOS/Common/pios_flash_w25x.c b/flight/PiOS/Common/pios_flash_w25x.c index b1c602422..624f76ef8 100644 --- a/flight/PiOS/Common/pios_flash_w25x.c +++ b/flight/PiOS/Common/pios_flash_w25x.c @@ -222,6 +222,14 @@ int8_t PIOS_Flash_W25X_WriteData(uint32_t addr, uint8_t * data, uint16_t len) return 0; } +/** + * @brief Read data from a location in flash memory + * @param[in] addr Address in flash to write to + * @param[in] data Pointer to data to write from flash + * @param[in] len Length of data to write (max 256 bytes) + * @return Zero if success or error code + * @retval -1 Unable to claim SPI bus + */ int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len) { if(PIOS_Flash_W25X_ClaimBus() == -1) diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index 5e403599b..4f39125db 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -208,14 +208,18 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) .size = UAVObjGetNumBytes(obj) }; - PIOS_Flash_W25X_EraseSector(addr); + if(PIOS_Flash_W25X_EraseSector(addr) != 0) + return -2; // Save header // This information IS redundant with the object table id. Oh well. Better safe than sorry. - PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)); + + if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0) + return -3; // Save data - PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)); + if(PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0) + return -4; return 0; } @@ -226,8 +230,9 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data) * @param[in] instId The instance of the object to save * @return 0 if success or error code * @retval -1 if object not in file table - * @retval -2 if loaded data instId or objId don't match - * @retval -3 if unable to retrieve instance data + * @retval -2 if unable to retrieve object header + * @retval -3 if loaded data instId or objId don't match + * @retval -4 if unable to retrieve instance data * @note This uses one sector on the flash chip per object so that no buffering in ram * must be done when erasing the sector before a save */ @@ -245,14 +250,15 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data) // Load header // This information IS redundant with the object table id. Oh well. Better safe than sorry. - PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)); + if(PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) + return -2; if((header.id != objId) || (header.instId != instId)) - return -2; + return -3; // Read the instance data if (PIOS_Flash_W25X_ReadData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0) - return -3; + return -4; return 0; } From 84e09031a7a47fda034e661fa8765b2c8d22a9fe Mon Sep 17 00:00:00 2001 From: dankers Date: Sun, 15 May 2011 05:58:58 +1000 Subject: [PATCH 30/43] Faster attitude calc, be much more aggressive with working out bias. Change AccelkP to 0.05 to give accels more influence, just balacing out the 3C filter. Change stab setting to be a better default fopr most Quads. --- flight/Modules/Attitude/attitude.c | 13 ++++++------- shared/uavobjectdefinition/attitudesettings.xml | 2 +- .../uavobjectdefinition/stabilizationsettings.xml | 6 +++--- 3 files changed, 10 insertions(+), 11 deletions(-) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 986fc74f3..4aeea69a7 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -141,20 +141,19 @@ static void AttitudeTask(void *parameters) FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - - if(xTaskGetTickCount() < 10000) { + + if(xTaskGetTickCount() < 7000) { // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); - // For first 5 seconds use accels to get gyro bias + // For first 7 seconds use accels to get gyro bias accelKp = 1; - // Decrease the rate of gyro learning during init - accelKi = .5 / (1 + xTaskGetTickCount() / 5000); - yawBiasRate = 0.01 / (1 + xTaskGetTickCount() / 5000); + accelKi = 0.9; + yawBiasRate = 0.23; init = 0; } else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { accelKi = .01; - yawBiasRate = 0.1; + yawBiasRate = 0.23; init = 0; } else if (init == 0) { settingsUpdatedCb(AttitudeSettingsHandle()); diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index 085c1a123..808bbe80f 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -4,7 +4,7 @@ - + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index bc339fdcd..177d097cf 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -7,9 +7,9 @@ - - - + + + From 934addfdcc64ad6f2d4d07cf739e158822bf3aa2 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 15:11:33 -0500 Subject: [PATCH 31/43] OP-216: Silly typo --- flight/UAVObjects/uavobjectmanager.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/UAVObjects/uavobjectmanager.c index 2d681ab3b..83af9ae13 100644 --- a/flight/UAVObjects/uavobjectmanager.c +++ b/flight/UAVObjects/uavobjectmanager.c @@ -742,8 +742,10 @@ int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) return -1; // Fire event on success - if(PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) == 0) + if(PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0) sendEvent(objEntry, instId, EV_UNPACKED); + else + return -1; #endif #if defined(PIOS_INCLUDE_SDCARD) From d883c8af9f5473a5876bac17b7360a3114ef1a28 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 15:15:33 -0500 Subject: [PATCH 32/43] Whitespace and line endings --- flight/UAVObjects/uavobjectmanager.c | 3073 +++++++++++++------------- 1 file changed, 1498 insertions(+), 1575 deletions(-) diff --git a/flight/UAVObjects/uavobjectmanager.c b/flight/UAVObjects/uavobjectmanager.c index 83af9ae13..ef1774628 100644 --- a/flight/UAVObjects/uavobjectmanager.c +++ b/flight/UAVObjects/uavobjectmanager.c @@ -1,1575 +1,1498 @@ -/** - ****************************************************************************** - * @addtogroup UAVObjects OpenPilot UAVObjects - * @{ - * @addtogroup UAV Object Manager - * @brief The core UAV Objects functions, most of which are wrappered by - * autogenerated defines - * @{ - * - * - * @file uavobjectmanager.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Object manager library. This library holds a collection of all objects. - * It can be used by all modules/libraries to find an object reference. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" - -// Constants - -// Private types - -/** - * List of event queues and the eventmask associated with the queue. - */ -struct ObjectEventListStruct { - xQueueHandle queue; - UAVObjEventCallback cb; - int32_t eventMask; - struct ObjectEventListStruct* next; -}; -typedef struct ObjectEventListStruct ObjectEventList; - -/** - * List of object instances, holds the actual data structure and instance ID - */ -struct ObjectInstListStruct { - void* data; - uint16_t instId; - struct ObjectInstListStruct* next; -}; -typedef struct ObjectInstListStruct ObjectInstList; - -/** - * List of objects registered in the object manager - */ -struct ObjectListStruct { - uint32_t id; /** The object ID */ - const char* name; /** The object name */ - int8_t isMetaobject; /** Set to 1 if this is a metaobject */ - int8_t isSingleInstance; /** Set to 1 if this object has a single instance */ - int8_t isSettings; /** Set to 1 if this object is a settings object */ - uint16_t numBytes; /** Number of data bytes contained in the object (for a single instance) */ - uint16_t numInstances; /** Number of instances */ - struct ObjectListStruct* linkedObj; /** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */ - ObjectInstList instances; /** List of object instances, instance 0 always exists */ - ObjectEventList* events; /** Event queues registered on the object */ - struct ObjectListStruct* next; /** Needed by linked list library (utlist.h) */ -}; -typedef struct ObjectListStruct ObjectList; - -// Private functions -static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event); -static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId); -static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId); -static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb, int32_t eventMask); -static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb); - -#if defined(PIOS_INCLUDE_SDCARD) -static void objectFilename(ObjectList* obj, uint8_t* filename); -static void customSPrintf(uint8_t* buffer, uint8_t* format, ...); -#endif - -// Private variables -static ObjectList* objList; -static xSemaphoreHandle mutex; -static UAVObjMetadata defMetadata; -static UAVObjStats stats; - -/** - * Initialize the object manager - * \return 0 Success - * \return -1 Failure - */ -int32_t UAVObjInitialize() -{ - // Initialize variables - objList = NULL; - memset(&stats, 0, sizeof(UAVObjStats)); - - // Create mutex - mutex = xSemaphoreCreateRecursiveMutex(); - if (mutex == NULL) - return -1; - - // Initialize default metadata structure (metadata of metaobjects) - defMetadata.access = ACCESS_READWRITE; - defMetadata.gcsAccess = ACCESS_READWRITE; - defMetadata.telemetryAcked = 1; - defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.telemetryUpdatePeriod = 0; - defMetadata.gcsTelemetryAcked = 1; - defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.gcsTelemetryUpdatePeriod = 0; - defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE; - defMetadata.loggingUpdatePeriod = 0; - - // Done - return 0; -} - -/** - * Get the statistics counters - * @param[out] statsOut The statistics counters will be copied there - */ -void UAVObjGetStats(UAVObjStats* statsOut) -{ - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memcpy(statsOut, &stats, sizeof(UAVObjStats)); - xSemaphoreGiveRecursive(mutex); -} - -/** - * Clear the statistics counters - */ -void UAVObjClearStats() -{ - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - memset(&stats, 0, sizeof(UAVObjStats)); - xSemaphoreGiveRecursive(mutex); -} - -/** - * Register and new object in the object manager. - * \param[in] id Unique object ID - * \param[in] name Object name - * \param[in] nameName Metaobject name - * \param[in] isMetaobject Is this a metaobject (1:true, 0:false) - * \param[in] isSingleInstance Is this a single instance or multi-instance object - * \param[in] isSettings Is this a settings object - * \param[in] numBytes Number of bytes of object data (for one instance) - * \param[in] initCb Default field and metadata initialization function - * \return Object handle, or NULL if failure. - * \return - */ -UAVObjHandle UAVObjRegister(uint32_t id, const char* name, const char* metaName, int32_t isMetaobject, - int32_t isSingleInstance, int32_t isSettings, uint32_t numBytes, UAVObjInitializeCallback initCb) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - ObjectList* metaObj; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Check that the object is not already registered - LL_FOREACH(objList, objEntry) - { - if (objEntry->id == id) - { - // Already registered, ignore - xSemaphoreGiveRecursive(mutex); - return NULL; - } - } - - // Create and append entry - objEntry = (ObjectList*)pvPortMalloc(sizeof(ObjectList)); - if (objEntry == NULL) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - objEntry->id = id; - objEntry->name = name; - objEntry->isMetaobject = (int8_t)isMetaobject; - objEntry->isSingleInstance = (int8_t)isSingleInstance; - objEntry->isSettings = (int8_t)isSettings; - objEntry->numBytes = numBytes; - objEntry->events = NULL; - objEntry->numInstances = 0; - objEntry->instances.data = NULL; - objEntry->instances.instId = 0xFFFF; - objEntry->instances.next = NULL; - objEntry->linkedObj = NULL; // will be set later - LL_APPEND(objList, objEntry); - - // Create instance zero - instEntry = createInstance(objEntry, 0); - if ( instEntry == NULL ) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - - // Create metaobject and update linkedObj - if (isMetaobject) - { - objEntry->linkedObj = NULL; // will be set later - } - else - { - // Create metaobject - metaObj = (ObjectList*)UAVObjRegister(id+1, metaName, NULL, 1, 1, 0, sizeof(UAVObjMetadata), NULL); - // Link two objects - objEntry->linkedObj = metaObj; - metaObj->linkedObj = objEntry; - } - - // Initialize object fields and metadata to default values - if ( initCb != NULL ) - { - initCb((UAVObjHandle)objEntry, 0); - } - - // Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object) - if ( !objEntry->isMetaobject ) - { - UAVObjLoad( (UAVObjHandle)objEntry->linkedObj, 0 ); - } - - // If this is a settings object, attempt to load from SD card - if ( objEntry->isSettings ) - { - UAVObjLoad( (UAVObjHandle)objEntry, 0 ); - } - - // Release lock - xSemaphoreGiveRecursive(mutex); - return (UAVObjHandle)objEntry; -} - -/** - * Retrieve an object from the list given its id - * \param[in] The object ID - * \return The object or NULL if not found. - */ -UAVObjHandle UAVObjGetByID(uint32_t id) -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Look for object - LL_FOREACH(objList, objEntry) - { - if (objEntry->id == id) - { - // Release lock - xSemaphoreGiveRecursive(mutex); - // Done, object found - return (UAVObjHandle)objEntry; - } - } - - // Object not found, release lock and return error - xSemaphoreGiveRecursive(mutex); - return NULL; -} - -/** - * Retrieve an object from the list given its name - * \param[in] name The name of the object - * \return The object or NULL if not found. - */ -UAVObjHandle UAVObjGetByName(char* name) -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Look for object - LL_FOREACH(objList, objEntry) - { - if (objEntry->name != NULL && strcmp(objEntry->name, name) == 0) - { - // Release lock - xSemaphoreGiveRecursive(mutex); - // Done, object found - return (UAVObjHandle)objEntry; - } - } - - // Object not found, release lock and return error - xSemaphoreGiveRecursive(mutex); - return NULL; -} - -/** - * Get the object's ID - * \param[in] obj The object handle - * \return The object ID - */ -uint32_t UAVObjGetID(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->id; -} - -/** - * Get the object's name - * \param[in] obj The object handle - * \return The object's name - */ -const char* UAVObjGetName(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->name; -} - -/** - * Get the number of bytes of the object's data (for one instance) - * \param[in] obj The object handle - * \return The number of bytes - */ -uint32_t UAVObjGetNumBytes(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->numBytes; -} - -/** - * Get the object this object is linked to. For regular objects, the linked object - * is the metaobject. For metaobjects the linked object is the parent object. - * This function is normally only needed by the telemetry module. - * \param[in] obj The object handle - * \return The object linked object handle - */ -UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj) -{ - return (UAVObjHandle)(((ObjectList*)obj)->linkedObj); -} - -/** - * Get the number of instances contained in the object. - * \param[in] obj The object handle - * \return The number of instances - */ -uint16_t UAVObjGetNumInstances(UAVObjHandle obj) -{ - uint32_t numInstances; - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - numInstances = ((ObjectList*)obj)->numInstances; - xSemaphoreGiveRecursive(mutex); - return numInstances; -} - -/** - * Create a new instance in the object. - * \param[in] obj The object handle - * \return The instance ID or 0 if an error - */ -uint16_t UAVObjCreateInstance(UAVObjHandle obj, UAVObjInitializeCallback initCb) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Create new instance - objEntry = (ObjectList*)obj; - instEntry = createInstance(objEntry, objEntry->numInstances); - if ( instEntry == NULL ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Initialize instance data - if ( initCb != NULL ) - { - initCb(obj, instEntry->instId); - } - - // Unlock - xSemaphoreGiveRecursive(mutex); - return instEntry->instId; -} - -/** - * Does this object contains a single instance or multiple instances? - * \param[in] obj The object handle - * \return True (1) if this is a single instance object - */ -int32_t UAVObjIsSingleInstance(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->isSingleInstance; -} - -/** - * Is this a metaobject? - * \param[in] obj The object handle - * \return True (1) if this is metaobject - */ -int32_t UAVObjIsMetaobject(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->isMetaobject; -} - -/** - * Is this a settings object? - * \param[in] obj The object handle - * \return True (1) if this is a settings object - */ -int32_t UAVObjIsSettings(UAVObjHandle obj) -{ - return ((ObjectList*)obj)->isSettings; -} - -/** - * Unpack an object from a byte array - * \param[in] obj The object handle - * \param[in] instId The instance ID - * \param[in] dataIn The byte array - * \return 0 if success or -1 if failure - */ -int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId, const uint8_t* dataIn) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast handle to object - objEntry = (ObjectList*)obj; - - // Get the instance - instEntry = getInstance(objEntry, instId); - - // If the instance does not exist create it and any other instances before it - if ( instEntry == NULL ) - { - instEntry = createInstance(objEntry, instId); - if ( instEntry == NULL ) - { - // Error, unlock and return - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - - // Set the data - memcpy(instEntry->data, dataIn, objEntry->numBytes); - - // Fire event - sendEvent(objEntry, instId, EV_UNPACKED); - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Pack an object to a byte array - * \param[in] obj The object handle - * \param[in] instId The instance ID - * \param[out] dataOut The byte array - * \return 0 if success or -1 if failure - */ -int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t* dataOut) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast handle to object - objEntry = (ObjectList*)obj; - - // Get the instance - instEntry = getInstance(objEntry, instId); - if ( instEntry == NULL ) - { - // Error, unlock and return - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Pack data - memcpy(dataOut, instEntry->data, objEntry->numBytes); - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Save the data of the specified object instance to the file system (SD card). - * The object will be appended and the file will not be closed. - * The object data can be restored using the UAVObjLoad function. - * @param[in] obj The object handle. - * @param[in] instId The instance ID - * @param[in] file File to append to - * @return 0 if success or -1 if failure - */ -int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, FILEINFO* file) -{ -#if defined(PIOS_INCLUDE_SDCARD) - uint32_t bytesWritten; - ObjectList* objEntry; - ObjectInstList* instEntry; - - // Check for file system availability - if ( PIOS_SDCARD_IsMounted() == 0 ) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object - objEntry = (ObjectList*)obj; - - // Get the instance information - instEntry = getInstance(objEntry, instId); - if ( instEntry == NULL ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Write the object ID - PIOS_FWRITE(file,&objEntry->id,sizeof(objEntry->id),&bytesWritten); - - // Write the instance ID - if (!objEntry->isSingleInstance) - { - PIOS_FWRITE(file,&instEntry->instId,sizeof(instEntry->instId),&bytesWritten); - } - - // Write the data and check that the write was successful - PIOS_FWRITE(file,instEntry->data,objEntry->numBytes,&bytesWritten); - if ( bytesWritten != objEntry->numBytes ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Done - xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ - return 0; -} - -/** - * Save the data of the specified object to the file system (SD card). - * If the object contains multiple instances, all of them will be saved. - * A new file with the name of the object will be created. - * The object data can be restored using the UAVObjLoad function. - * @param[in] obj The object handle. - * @param[in] instId The instance ID - * @param[in] file File to append to - * @return 0 if success or -1 if failure - */ -int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId) -{ -#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) - ObjectList* objEntry = (ObjectList*)obj; - - if(objEntry == NULL) - return -1; - - ObjectInstList* instEntry = getInstance(objEntry, instId); - - if(instEntry == NULL) - return -1; - - if(instEntry->data == NULL) - return -1; - - if(PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0) - return -1; -#endif -#if defined(PIOS_INCLUDE_SDCARD) - FILEINFO file; - ObjectList* objEntry; - uint8_t filename[14]; - - // Check for file system availability - if ( PIOS_SDCARD_IsMounted() == 0 ) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object - objEntry = (ObjectList*)obj; - - // Get filename - objectFilename(objEntry, filename); - - // Open file - if ( PIOS_FOPEN_WRITE(filename,file) ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Append object - if ( UAVObjSaveToFile(obj, instId, &file) == -1 ) - { - PIOS_FCLOSE(file); - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Done, close file and unlock - PIOS_FCLOSE(file); - xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ - return 0; -} - -/** - * Load an object from the file system (SD card). - * @param[in] file File to read from - * @return The handle of the object loaded or NULL if a failure - */ -UAVObjHandle UAVObjLoadFromFile(FILEINFO* file) -{ -#if defined(PIOS_INCLUDE_SDCARD) - uint32_t bytesRead; - ObjectList* objEntry; - ObjectInstList* instEntry; - uint32_t objId; - uint16_t instId; - UAVObjHandle obj; - - // Check for file system availability - if ( PIOS_SDCARD_IsMounted() == 0 ) - { - return NULL; - } - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Read the object ID - if ( PIOS_FREAD(file,&objId,sizeof(objId),&bytesRead) ) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - - // Get the object - obj = UAVObjGetByID(objId); - if ( obj == 0 ) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - objEntry = (ObjectList*)obj; - - // Get the instance ID - instId = 0; - if ( !objEntry->isSingleInstance ) - { - if ( PIOS_FREAD(file,&instId,sizeof(instId),&bytesRead) ) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - } - - // Get the instance information - instEntry = getInstance(objEntry, instId); - - // If the instance does not exist create it and any other instances before it - if ( instEntry == NULL ) - { - instEntry = createInstance(objEntry, instId); - if ( instEntry == NULL ) - { - // Error, unlock and return - xSemaphoreGiveRecursive(mutex); - return NULL; - } - } - - // Read the instance data - if ( PIOS_FREAD(file,instEntry->data,objEntry->numBytes,&bytesRead) ) - { - xSemaphoreGiveRecursive(mutex); - return NULL; - } - - // Fire event - sendEvent(objEntry, instId, EV_UNPACKED); - - // Unlock - xSemaphoreGiveRecursive(mutex); - return obj; -#else /* PIOS_INCLUDE_SDCARD */ - return NULL; -#endif -} - -/** - * Load an object from the file system (SD card). - * A file with the name of the object will be opened. - * The object data can be saved using the UAVObjSave function. - * @param[in] obj The object handle. - * @param[in] instId The object instance - * @return 0 if success or -1 if failure - */ -int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) -{ -#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) - ObjectList* objEntry = (ObjectList*)obj; - - if(objEntry == NULL) - return -1; - - ObjectInstList* instEntry = getInstance(objEntry, instId); - - if(instEntry == NULL) - return -1; - - if(instEntry->data == NULL) - return -1; - - // Fire event on success - if(PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0) - sendEvent(objEntry, instId, EV_UNPACKED); - else - return -1; -#endif - -#if defined(PIOS_INCLUDE_SDCARD) - FILEINFO file; - ObjectList* objEntry; - UAVObjHandle loadedObj; - ObjectList* loadedObjEntry; - uint8_t filename[14]; - - // Check for file system availability - if ( PIOS_SDCARD_IsMounted() == 0 ) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object - objEntry = (ObjectList*)obj; - - // Get filename - objectFilename(objEntry, filename); - - // Open file - if ( PIOS_FOPEN_READ(filename,file) ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Load object - loadedObj = UAVObjLoadFromFile(&file); - if (loadedObj == 0) - { - PIOS_FCLOSE(file); - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Check that the IDs match - loadedObjEntry = (ObjectList*)loadedObj; - if ( loadedObjEntry->id != objEntry->id ) - { - PIOS_FCLOSE(file); - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Done, close file and unlock - PIOS_FCLOSE(file); - xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ - return 0; -} - -/** - * Delete an object from the file system (SD card). - * @param[in] obj The object handle. - * @param[in] instId The object instance - * @return 0 if success or -1 if failure - */ -int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId) -{ -#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) - PIOS_FLASHFS_ObjDelete(obj, instId); -#endif -#if defined(PIOS_INCLUDE_SDCARD) - ObjectList* objEntry; - uint8_t filename[14]; - - // Check for file system availability - if ( PIOS_SDCARD_IsMounted() == 0 ) - { - return -1; - } - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object - objEntry = (ObjectList*)obj; - - // Get filename - objectFilename(objEntry, filename); - - // Delete file - PIOS_FUNLINK(filename); - - // Done - xSemaphoreGiveRecursive(mutex); -#endif /* PIOS_INCLUDE_SDCARD */ - return 0; -} - -/** - * Save all settings objects to the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjSaveSettings() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Save all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isSettings ) - { - // Save object - if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Load all settings objects from the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjLoadSettings() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Load all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isSettings ) - { - // Load object - if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Delete all settings objects from the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjDeleteSettings() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Save all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isSettings ) - { - // Save object - if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Save all metaobjects to the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjSaveMetaobjects() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Save all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isMetaobject ) - { - // Save object - if ( UAVObjSave( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Load all metaobjects from the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjLoadMetaobjects() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Load all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isMetaobject ) - { - // Load object - if ( UAVObjLoad( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Delete all metaobjects from the SD card. - * @return 0 if success or -1 if failure - */ -int32_t UAVObjDeleteMetaobjects() -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Load all settings objects - LL_FOREACH(objList, objEntry) - { - // Check if this is a settings object - if ( objEntry->isMetaobject ) - { - // Load object - if ( UAVObjDelete( (UAVObjHandle)objEntry, 0 ) == -1 ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - } - - // Done - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Set the object data - * \param[in] obj The object handle - * \param[in] dataIn The object's data structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjSetData(UAVObjHandle obj, const void* dataIn) -{ - return UAVObjSetInstanceData(obj, 0, dataIn); -} - -/** - * Get the object data - * \param[in] obj The object handle - * \param[out] dataOut The object's data structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjGetData(UAVObjHandle obj, void* dataOut) -{ - return UAVObjGetInstanceData(obj, 0, dataOut); -} - -/** - * Set the data of a specific object instance - * \param[in] obj The object handle - * \param[in] instId The object instance ID - * \param[in] dataIn The object's data structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, const void* dataIn) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - UAVObjMetadata* mdata; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object info - objEntry = (ObjectList*)obj; - - // Check access level - if ( !objEntry->isMetaobject ) - { - mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data); - if ( mdata->access == ACCESS_READONLY ) - { - xSemaphoreGiveRecursive(mutex); - return -1; - } - } - - // Get instance information - instEntry = getInstance(objEntry, instId); - if ( instEntry == NULL ) - { - // Error, unlock and return - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Set data - memcpy(instEntry->data, dataIn, objEntry->numBytes); - - // Fire event - sendEvent(objEntry, instId, EV_UPDATED); - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Get the data of a specific object instance - * \param[in] obj The object handle - * \param[in] instId The object instance ID - * \param[out] dataOut The object's data structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, void* dataOut) -{ - ObjectList* objEntry; - ObjectInstList* instEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Cast to object info - objEntry = (ObjectList*)obj; - - // Get instance information - instEntry = getInstance(objEntry, instId); - if ( instEntry == NULL ) - { - // Error, unlock and return - xSemaphoreGiveRecursive(mutex); - return -1; - } - - // Set data - memcpy(dataOut, instEntry->data, objEntry->numBytes); - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Set the object metadata - * \param[in] obj The object handle - * \param[in] dataIn The object's metadata structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata* dataIn) -{ - ObjectList* objEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Set metadata (metadata of metaobjects can not be modified) - objEntry = (ObjectList*)obj; - if (!objEntry->isMetaobject) - { - UAVObjSetData((UAVObjHandle)objEntry->linkedObj, dataIn); - } - else - { - return -1; - } - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Get the object metadata - * \param[in] obj The object handle - * \param[out] dataOut The object's metadata structure - * \return 0 if success or -1 if failure - */ -int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata* dataOut) -{ - ObjectList* objEntry; - - // Lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Get metadata - objEntry = (ObjectList*)obj; - if (objEntry->isMetaobject) - { - memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata)); - } - else - { - UAVObjGetData((UAVObjHandle)objEntry->linkedObj, dataOut); - } - - // Unlock - xSemaphoreGiveRecursive(mutex); - return 0; -} - -/** - * Check if an object is read only - * \param[in] obj The object handle - * \return - * \arg 0 if not read only - * \arg 1 if read only - * \arg -1 if unable to get meta data - */ -int8_t UAVObjReadOnly(UAVObjHandle obj) -{ - ObjectList* objEntry; - UAVObjMetadata* mdata; - - // Cast to object info - objEntry = (ObjectList*)obj; - - // Check access level - if ( !objEntry->isMetaobject ) - { - mdata = (UAVObjMetadata*)(objEntry->linkedObj->instances.data); - return mdata->access == ACCESS_READONLY; - } - return -1; -} - -/** - * Connect an event queue to the object, if the queue is already connected then the event mask is only updated. - * All events matching the event mask will be pushed to the event queue. - * \param[in] obj The object handle - * \param[in] queue The event queue - * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) - * \return 0 if success or -1 if failure - */ -int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, int32_t eventMask) -{ - int32_t res; - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - res = connectObj(obj, queue, 0, eventMask); - xSemaphoreGiveRecursive(mutex); - return res; -} - -/** - * Disconnect an event queue from the object. - * \param[in] obj The object handle - * \param[in] queue The event queue - * \return 0 if success or -1 if failure - */ -int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue) -{ - int32_t res; - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - res = disconnectObj(obj, queue, 0); - xSemaphoreGiveRecursive(mutex); - return res; -} - -/** - * Connect an event callback to the object, if the callback is already connected then the event mask is only updated. - * The supplied callback will be invoked on all events matching the event mask. - * \param[in] obj The object handle - * \param[in] cb The event callback - * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) - * \return 0 if success or -1 if failure - */ -int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, int32_t eventMask) -{ - int32_t res; - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - res = connectObj(obj, 0, cb, eventMask); - xSemaphoreGiveRecursive(mutex); - return res; -} - -/** - * Disconnect an event callback from the object. - * \param[in] obj The object handle - * \param[in] cb The event callback - * \return 0 if success or -1 if failure - */ -int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb) -{ - int32_t res; - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - res = disconnectObj(obj, 0, cb); - xSemaphoreGiveRecursive(mutex); - return res; -} - - -/** - * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event - * will be generated as soon as the object is updated. - * \param[in] obj The object handle - */ -void UAVObjRequestUpdate(UAVObjHandle obj) -{ - UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES); -} - -/** - * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event - * will be generated as soon as the object is updated. - * \param[in] obj The object handle - * \param[in] instId Object instance ID to update - */ -void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId) -{ - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - sendEvent((ObjectList*)obj, instId, EV_UPDATE_REQ); - xSemaphoreGiveRecursive(mutex); -} - -/** - * Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). - * \param[in] obj The object handle - */ -void UAVObjUpdated(UAVObjHandle obj) -{ - UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES); -} - -/** - * Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). - * \param[in] obj The object handle - * \param[in] instId The object instance ID - */ -void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId) -{ - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - sendEvent((ObjectList*)obj, instId, EV_UPDATED_MANUAL); - xSemaphoreGiveRecursive(mutex); -} - -/** - * Iterate through all objects in the list. - * \param iterator This function will be called once for each object, - * the object will be passed as a parameter - */ -void UAVObjIterate(void (*iterator)(UAVObjHandle obj)) -{ - ObjectList* objEntry; - - // Get lock - xSemaphoreTakeRecursive(mutex, portMAX_DELAY); - - // Iterate through the list and invoke iterator for each object - LL_FOREACH(objList, objEntry) - { - (*iterator)((UAVObjHandle)objEntry); - } - - // Release lock - xSemaphoreGiveRecursive(mutex); -} - -/** - * Send an event to all event queues registered on the object. - */ -static int32_t sendEvent(ObjectList* obj, uint16_t instId, UAVObjEventType event) -{ - ObjectEventList* eventEntry; - UAVObjEvent msg; - - // Setup event - msg.obj = (UAVObjHandle)obj; - msg.event = event; - msg.instId = instId; - - // Go through each object and push the event message in the queue (if event is activated for the queue) - LL_FOREACH(obj->events, eventEntry) - { - if ( eventEntry->eventMask == 0 || (eventEntry->eventMask & event) != 0 ) - { - // Send to queue if a valid queue is registered - if (eventEntry->queue != 0) - { - if ( xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE ) // will not block - { - ++stats.eventErrors; - } - } - // Invoke callback (from event task) if a valid one is registered - if (eventEntry->cb != 0) - { - if ( EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE ) // invoke callback from the event task, will not block - { - ++stats.eventErrors; - } - } - } - } - - // Done - return 0; -} - -/** - * Create a new object instance, return the instance info or NULL if failure. - */ -static ObjectInstList* createInstance(ObjectList* obj, uint16_t instId) -{ - ObjectInstList* instEntry; - int32_t n; - - // For single instance objects, only instance zero is allowed - if (obj->isSingleInstance && instId != 0) - { - return NULL; - } - - // Make sure that the instance ID is within limits - if (instId >= UAVOBJ_MAX_INSTANCES) - { - return NULL; - } - - // Check if the instance already exists - if ( getInstance(obj, instId) != NULL ) - { - return NULL; - } - - // Create any missing instances (all instance IDs must be sequential) - for (n = obj->numInstances; n < instId; ++n) - { - if ( createInstance(obj, n) == NULL ) - { - return NULL; - } - } - - if(instId == 0) /* Instance 0 ObjectInstList allocated with ObjectList element */ - { - instEntry = &obj->instances; - instEntry->data = pvPortMalloc(obj->numBytes); - if (instEntry->data == NULL) return NULL; - memset(instEntry->data, 0, obj->numBytes); - instEntry->instId = instId; - } else - { - // Create the actual instance - instEntry = (ObjectInstList*)pvPortMalloc(sizeof(ObjectInstList)); - if (instEntry == NULL) return NULL; - instEntry->data = pvPortMalloc(obj->numBytes); - if (instEntry->data == NULL) return NULL; - memset(instEntry->data, 0, obj->numBytes); - instEntry->instId = instId; - LL_APPEND(obj->instances.next, instEntry); - } - ++obj->numInstances; - - // Fire event - UAVObjInstanceUpdated((UAVObjHandle)obj, instId); - - // Done - return instEntry; -} - -/** - * Get the instance information or NULL if the instance does not exist - */ -static ObjectInstList* getInstance(ObjectList* obj, uint16_t instId) -{ - ObjectInstList* instEntry; - - // Look for specified instance ID - LL_FOREACH(&(obj->instances), instEntry) - { - if (instEntry->instId == instId) - { - return instEntry; - } - } - // If this point is reached then instance id was not found - return NULL; -} - -/** - * Connect an event queue to the object, if the queue is already connected then the event mask is only updated. - * \param[in] obj The object handle - * \param[in] queue The event queue - * \param[in] cb The event callback - * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) - * \return 0 if success or -1 if failure - */ -static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb, int32_t eventMask) -{ - ObjectEventList* eventEntry; - ObjectList* objEntry; - - // Check that the queue is not already connected, if it is simply update event mask - objEntry = (ObjectList*)obj; - LL_FOREACH(objEntry->events, eventEntry) - { - if ( eventEntry->queue == queue && eventEntry->cb == cb ) - { - // Already connected, update event mask and return - eventEntry->eventMask = eventMask; - return 0; - } - } - - // Add queue to list - eventEntry = (ObjectEventList*)pvPortMalloc(sizeof(ObjectEventList)); - if (eventEntry == NULL) - { - return -1; - } - eventEntry->queue = queue; - eventEntry->cb = cb; - eventEntry->eventMask = eventMask; - LL_APPEND(objEntry->events, eventEntry); - - // Done - return 0; -} - -/** - * Disconnect an event queue from the object - * \param[in] obj The object handle - * \param[in] queue The event queue - * \param[in] cb The event callback - * \return 0 if success or -1 if failure - */ -static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, UAVObjEventCallback cb) -{ - ObjectEventList* eventEntry; - ObjectList* objEntry; - - // Find queue and remove it - objEntry = (ObjectList*)obj; - LL_FOREACH(objEntry->events, eventEntry) - { - if ( ( eventEntry->queue == queue && eventEntry->cb == cb ) ) - { - LL_DELETE(objEntry->events, eventEntry); - vPortFree(eventEntry); - return 0; - } - } - - // If this point is reached the queue was not found - return -1; -} - -#if defined(PIOS_INCLUDE_SDCARD) -/** - * Wrapper for the sprintf function - */ -static void customSPrintf(uint8_t* buffer, uint8_t* format, ...) -{ - va_list args; - va_start(args, format); - vsprintf((char *)buffer, (char *)format, args); -} - -/** - * Get an 8 character (plus extension) filename for the object. - */ -static void objectFilename(ObjectList* obj, uint8_t* filename) -{ - customSPrintf(filename, (uint8_t*)"%X.obj", obj->id); -} -#endif /* PIOS_INCLUDE_SDCARD */ - - - - - - - - - - - - - - - - +/** + ****************************************************************************** + * @addtogroup UAVObjects OpenPilot UAVObjects + * @{ + * @addtogroup UAV Object Manager + * @brief The core UAV Objects functions, most of which are wrappered by + * autogenerated defines + * @{ + * + * + * @file uavobjectmanager.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Object manager library. This library holds a collection of all objects. + * It can be used by all modules/libraries to find an object reference. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "openpilot.h" + +// Constants + +// Private types + +/** + * List of event queues and the eventmask associated with the queue. + */ +struct ObjectEventListStruct { + xQueueHandle queue; + UAVObjEventCallback cb; + int32_t eventMask; + struct ObjectEventListStruct *next; +}; +typedef struct ObjectEventListStruct ObjectEventList; + +/** + * List of object instances, holds the actual data structure and instance ID + */ +struct ObjectInstListStruct { + void *data; + uint16_t instId; + struct ObjectInstListStruct *next; +}; +typedef struct ObjectInstListStruct ObjectInstList; + +/** + * List of objects registered in the object manager + */ +struct ObjectListStruct { + uint32_t id; + /** The object ID */ + const char *name; + /** The object name */ + int8_t isMetaobject; + /** Set to 1 if this is a metaobject */ + int8_t isSingleInstance; + /** Set to 1 if this object has a single instance */ + int8_t isSettings; + /** Set to 1 if this object is a settings object */ + uint16_t numBytes; + /** Number of data bytes contained in the object (for a single instance) */ + uint16_t numInstances; + /** Number of instances */ + struct ObjectListStruct *linkedObj; + /** Linked object, for regular objects this is the metaobject and for metaobjects it is the parent object */ + ObjectInstList instances; + /** List of object instances, instance 0 always exists */ + ObjectEventList *events; + /** Event queues registered on the object */ + struct ObjectListStruct *next; + /** Needed by linked list library (utlist.h) */ +}; +typedef struct ObjectListStruct ObjectList; + +// Private functions +static int32_t sendEvent(ObjectList * obj, uint16_t instId, + UAVObjEventType event); +static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId); +static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId); +static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, + UAVObjEventCallback cb, int32_t eventMask); +static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, + UAVObjEventCallback cb); + +#if defined(PIOS_INCLUDE_SDCARD) +static void objectFilename(ObjectList * obj, uint8_t * filename); +static void customSPrintf(uint8_t * buffer, uint8_t * format, ...); +#endif + +// Private variables +static ObjectList *objList; +static xSemaphoreHandle mutex; +static UAVObjMetadata defMetadata; +static UAVObjStats stats; + +/** + * Initialize the object manager + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVObjInitialize() +{ + // Initialize variables + objList = NULL; + memset(&stats, 0, sizeof(UAVObjStats)); + + // Create mutex + mutex = xSemaphoreCreateRecursiveMutex(); + if (mutex == NULL) + return -1; + + // Initialize default metadata structure (metadata of metaobjects) + defMetadata.access = ACCESS_READWRITE; + defMetadata.gcsAccess = ACCESS_READWRITE; + defMetadata.telemetryAcked = 1; + defMetadata.telemetryUpdateMode = UPDATEMODE_ONCHANGE; + defMetadata.telemetryUpdatePeriod = 0; + defMetadata.gcsTelemetryAcked = 1; + defMetadata.gcsTelemetryUpdateMode = UPDATEMODE_ONCHANGE; + defMetadata.gcsTelemetryUpdatePeriod = 0; + defMetadata.loggingUpdateMode = UPDATEMODE_ONCHANGE; + defMetadata.loggingUpdatePeriod = 0; + + // Done + return 0; +} + +/** + * Get the statistics counters + * @param[out] statsOut The statistics counters will be copied there + */ +void UAVObjGetStats(UAVObjStats * statsOut) +{ + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + memcpy(statsOut, &stats, sizeof(UAVObjStats)); + xSemaphoreGiveRecursive(mutex); +} + +/** + * Clear the statistics counters + */ +void UAVObjClearStats() +{ + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + memset(&stats, 0, sizeof(UAVObjStats)); + xSemaphoreGiveRecursive(mutex); +} + +/** + * Register and new object in the object manager. + * \param[in] id Unique object ID + * \param[in] name Object name + * \param[in] nameName Metaobject name + * \param[in] isMetaobject Is this a metaobject (1:true, 0:false) + * \param[in] isSingleInstance Is this a single instance or multi-instance object + * \param[in] isSettings Is this a settings object + * \param[in] numBytes Number of bytes of object data (for one instance) + * \param[in] initCb Default field and metadata initialization function + * \return Object handle, or NULL if failure. + * \return + */ +UAVObjHandle UAVObjRegister(uint32_t id, const char *name, + const char *metaName, int32_t isMetaobject, + int32_t isSingleInstance, int32_t isSettings, + uint32_t numBytes, + UAVObjInitializeCallback initCb) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + ObjectList *metaObj; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Check that the object is not already registered + LL_FOREACH(objList, objEntry) { + if (objEntry->id == id) { + // Already registered, ignore + xSemaphoreGiveRecursive(mutex); + return NULL; + } + } + + // Create and append entry + objEntry = (ObjectList *) pvPortMalloc(sizeof(ObjectList)); + if (objEntry == NULL) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + objEntry->id = id; + objEntry->name = name; + objEntry->isMetaobject = (int8_t) isMetaobject; + objEntry->isSingleInstance = (int8_t) isSingleInstance; + objEntry->isSettings = (int8_t) isSettings; + objEntry->numBytes = numBytes; + objEntry->events = NULL; + objEntry->numInstances = 0; + objEntry->instances.data = NULL; + objEntry->instances.instId = 0xFFFF; + objEntry->instances.next = NULL; + objEntry->linkedObj = NULL; // will be set later + LL_APPEND(objList, objEntry); + + // Create instance zero + instEntry = createInstance(objEntry, 0); + if (instEntry == NULL) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + // Create metaobject and update linkedObj + if (isMetaobject) { + objEntry->linkedObj = NULL; // will be set later + } else { + // Create metaobject + metaObj = + (ObjectList *) UAVObjRegister(id + 1, metaName, + NULL, 1, 1, 0, + sizeof + (UAVObjMetadata), + NULL); + // Link two objects + objEntry->linkedObj = metaObj; + metaObj->linkedObj = objEntry; + } + + // Initialize object fields and metadata to default values + if (initCb != NULL) { + initCb((UAVObjHandle) objEntry, 0); + } + // Attempt to load object's metadata from the SD card (not done directly on the metaobject, but through the object) + if (!objEntry->isMetaobject) { + UAVObjLoad((UAVObjHandle) objEntry->linkedObj, 0); + } + // If this is a settings object, attempt to load from SD card + if (objEntry->isSettings) { + UAVObjLoad((UAVObjHandle) objEntry, 0); + } + // Release lock + xSemaphoreGiveRecursive(mutex); + return (UAVObjHandle) objEntry; +} + +/** + * Retrieve an object from the list given its id + * \param[in] The object ID + * \return The object or NULL if not found. + */ +UAVObjHandle UAVObjGetByID(uint32_t id) +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Look for object + LL_FOREACH(objList, objEntry) { + if (objEntry->id == id) { + // Release lock + xSemaphoreGiveRecursive(mutex); + // Done, object found + return (UAVObjHandle) objEntry; + } + } + + // Object not found, release lock and return error + xSemaphoreGiveRecursive(mutex); + return NULL; +} + +/** + * Retrieve an object from the list given its name + * \param[in] name The name of the object + * \return The object or NULL if not found. + */ +UAVObjHandle UAVObjGetByName(char *name) +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Look for object + LL_FOREACH(objList, objEntry) { + if (objEntry->name != NULL + && strcmp(objEntry->name, name) == 0) { + // Release lock + xSemaphoreGiveRecursive(mutex); + // Done, object found + return (UAVObjHandle) objEntry; + } + } + + // Object not found, release lock and return error + xSemaphoreGiveRecursive(mutex); + return NULL; +} + +/** + * Get the object's ID + * \param[in] obj The object handle + * \return The object ID + */ +uint32_t UAVObjGetID(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->id; +} + +/** + * Get the object's name + * \param[in] obj The object handle + * \return The object's name + */ +const char *UAVObjGetName(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->name; +} + +/** + * Get the number of bytes of the object's data (for one instance) + * \param[in] obj The object handle + * \return The number of bytes + */ +uint32_t UAVObjGetNumBytes(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->numBytes; +} + +/** + * Get the object this object is linked to. For regular objects, the linked object + * is the metaobject. For metaobjects the linked object is the parent object. + * This function is normally only needed by the telemetry module. + * \param[in] obj The object handle + * \return The object linked object handle + */ +UAVObjHandle UAVObjGetLinkedObj(UAVObjHandle obj) +{ + return (UAVObjHandle) (((ObjectList *) obj)->linkedObj); +} + +/** + * Get the number of instances contained in the object. + * \param[in] obj The object handle + * \return The number of instances + */ +uint16_t UAVObjGetNumInstances(UAVObjHandle obj) +{ + uint32_t numInstances; + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + numInstances = ((ObjectList *) obj)->numInstances; + xSemaphoreGiveRecursive(mutex); + return numInstances; +} + +/** + * Create a new instance in the object. + * \param[in] obj The object handle + * \return The instance ID or 0 if an error + */ +uint16_t UAVObjCreateInstance(UAVObjHandle obj, + UAVObjInitializeCallback initCb) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Create new instance + objEntry = (ObjectList *) obj; + instEntry = createInstance(objEntry, objEntry->numInstances); + if (instEntry == NULL) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Initialize instance data + if (initCb != NULL) { + initCb(obj, instEntry->instId); + } + // Unlock + xSemaphoreGiveRecursive(mutex); + return instEntry->instId; +} + +/** + * Does this object contains a single instance or multiple instances? + * \param[in] obj The object handle + * \return True (1) if this is a single instance object + */ +int32_t UAVObjIsSingleInstance(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->isSingleInstance; +} + +/** + * Is this a metaobject? + * \param[in] obj The object handle + * \return True (1) if this is metaobject + */ +int32_t UAVObjIsMetaobject(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->isMetaobject; +} + +/** + * Is this a settings object? + * \param[in] obj The object handle + * \return True (1) if this is a settings object + */ +int32_t UAVObjIsSettings(UAVObjHandle obj) +{ + return ((ObjectList *) obj)->isSettings; +} + +/** + * Unpack an object from a byte array + * \param[in] obj The object handle + * \param[in] instId The instance ID + * \param[in] dataIn The byte array + * \return 0 if success or -1 if failure + */ +int32_t UAVObjUnpack(UAVObjHandle obj, uint16_t instId, + const uint8_t * dataIn) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast handle to object + objEntry = (ObjectList *) obj; + + // Get the instance + instEntry = getInstance(objEntry, instId); + + // If the instance does not exist create it and any other instances before it + if (instEntry == NULL) { + instEntry = createInstance(objEntry, instId); + if (instEntry == NULL) { + // Error, unlock and return + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + // Set the data + memcpy(instEntry->data, dataIn, objEntry->numBytes); + + // Fire event + sendEvent(objEntry, instId, EV_UNPACKED); + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Pack an object to a byte array + * \param[in] obj The object handle + * \param[in] instId The instance ID + * \param[out] dataOut The byte array + * \return 0 if success or -1 if failure + */ +int32_t UAVObjPack(UAVObjHandle obj, uint16_t instId, uint8_t * dataOut) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast handle to object + objEntry = (ObjectList *) obj; + + // Get the instance + instEntry = getInstance(objEntry, instId); + if (instEntry == NULL) { + // Error, unlock and return + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Pack data + memcpy(dataOut, instEntry->data, objEntry->numBytes); + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Save the data of the specified object instance to the file system (SD card). + * The object will be appended and the file will not be closed. + * The object data can be restored using the UAVObjLoad function. + * @param[in] obj The object handle. + * @param[in] instId The instance ID + * @param[in] file File to append to + * @return 0 if success or -1 if failure + */ +int32_t UAVObjSaveToFile(UAVObjHandle obj, uint16_t instId, + FILEINFO * file) +{ +#if defined(PIOS_INCLUDE_SDCARD) + uint32_t bytesWritten; + ObjectList *objEntry; + ObjectInstList *instEntry; + + // Check for file system availability + if (PIOS_SDCARD_IsMounted() == 0) { + return -1; + } + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object + objEntry = (ObjectList *) obj; + + // Get the instance information + instEntry = getInstance(objEntry, instId); + if (instEntry == NULL) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Write the object ID + PIOS_FWRITE(file, &objEntry->id, sizeof(objEntry->id), + &bytesWritten); + + // Write the instance ID + if (!objEntry->isSingleInstance) { + PIOS_FWRITE(file, &instEntry->instId, + sizeof(instEntry->instId), &bytesWritten); + } + // Write the data and check that the write was successful + PIOS_FWRITE(file, instEntry->data, objEntry->numBytes, + &bytesWritten); + if (bytesWritten != objEntry->numBytes) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Done + xSemaphoreGiveRecursive(mutex); +#endif /* PIOS_INCLUDE_SDCARD */ + return 0; +} + +/** + * Save the data of the specified object to the file system (SD card). + * If the object contains multiple instances, all of them will be saved. + * A new file with the name of the object will be created. + * The object data can be restored using the UAVObjLoad function. + * @param[in] obj The object handle. + * @param[in] instId The instance ID + * @param[in] file File to append to + * @return 0 if success or -1 if failure + */ +int32_t UAVObjSave(UAVObjHandle obj, uint16_t instId) +{ +#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) + ObjectList *objEntry = (ObjectList *) obj; + + if (objEntry == NULL) + return -1; + + ObjectInstList *instEntry = getInstance(objEntry, instId); + + if (instEntry == NULL) + return -1; + + if (instEntry->data == NULL) + return -1; + + if (PIOS_FLASHFS_ObjSave(obj, instId, instEntry->data) != 0) + return -1; +#endif +#if defined(PIOS_INCLUDE_SDCARD) + FILEINFO file; + ObjectList *objEntry; + uint8_t filename[14]; + + // Check for file system availability + if (PIOS_SDCARD_IsMounted() == 0) { + return -1; + } + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object + objEntry = (ObjectList *) obj; + + // Get filename + objectFilename(objEntry, filename); + + // Open file + if (PIOS_FOPEN_WRITE(filename, file)) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Append object + if (UAVObjSaveToFile(obj, instId, &file) == -1) { + PIOS_FCLOSE(file); + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Done, close file and unlock + PIOS_FCLOSE(file); + xSemaphoreGiveRecursive(mutex); +#endif /* PIOS_INCLUDE_SDCARD */ + return 0; +} + +/** + * Load an object from the file system (SD card). + * @param[in] file File to read from + * @return The handle of the object loaded or NULL if a failure + */ +UAVObjHandle UAVObjLoadFromFile(FILEINFO * file) +{ +#if defined(PIOS_INCLUDE_SDCARD) + uint32_t bytesRead; + ObjectList *objEntry; + ObjectInstList *instEntry; + uint32_t objId; + uint16_t instId; + UAVObjHandle obj; + + // Check for file system availability + if (PIOS_SDCARD_IsMounted() == 0) { + return NULL; + } + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Read the object ID + if (PIOS_FREAD(file, &objId, sizeof(objId), &bytesRead)) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + // Get the object + obj = UAVObjGetByID(objId); + if (obj == 0) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + objEntry = (ObjectList *) obj; + + // Get the instance ID + instId = 0; + if (!objEntry->isSingleInstance) { + if (PIOS_FREAD + (file, &instId, sizeof(instId), &bytesRead)) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + } + // Get the instance information + instEntry = getInstance(objEntry, instId); + + // If the instance does not exist create it and any other instances before it + if (instEntry == NULL) { + instEntry = createInstance(objEntry, instId); + if (instEntry == NULL) { + // Error, unlock and return + xSemaphoreGiveRecursive(mutex); + return NULL; + } + } + // Read the instance data + if (PIOS_FREAD + (file, instEntry->data, objEntry->numBytes, &bytesRead)) { + xSemaphoreGiveRecursive(mutex); + return NULL; + } + // Fire event + sendEvent(objEntry, instId, EV_UNPACKED); + + // Unlock + xSemaphoreGiveRecursive(mutex); + return obj; +#else /* PIOS_INCLUDE_SDCARD */ + return NULL; +#endif +} + +/** + * Load an object from the file system (SD card). + * A file with the name of the object will be opened. + * The object data can be saved using the UAVObjSave function. + * @param[in] obj The object handle. + * @param[in] instId The object instance + * @return 0 if success or -1 if failure + */ +int32_t UAVObjLoad(UAVObjHandle obj, uint16_t instId) +{ +#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) + ObjectList *objEntry = (ObjectList *) obj; + + if (objEntry == NULL) + return -1; + + ObjectInstList *instEntry = getInstance(objEntry, instId); + + if (instEntry == NULL) + return -1; + + if (instEntry->data == NULL) + return -1; + + // Fire event on success + if (PIOS_FLASHFS_ObjLoad(obj, instId, instEntry->data) == 0) + sendEvent(objEntry, instId, EV_UNPACKED); + else + return -1; +#endif + +#if defined(PIOS_INCLUDE_SDCARD) + FILEINFO file; + ObjectList *objEntry; + UAVObjHandle loadedObj; + ObjectList *loadedObjEntry; + uint8_t filename[14]; + + // Check for file system availability + if (PIOS_SDCARD_IsMounted() == 0) { + return -1; + } + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object + objEntry = (ObjectList *) obj; + + // Get filename + objectFilename(objEntry, filename); + + // Open file + if (PIOS_FOPEN_READ(filename, file)) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Load object + loadedObj = UAVObjLoadFromFile(&file); + if (loadedObj == 0) { + PIOS_FCLOSE(file); + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Check that the IDs match + loadedObjEntry = (ObjectList *) loadedObj; + if (loadedObjEntry->id != objEntry->id) { + PIOS_FCLOSE(file); + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Done, close file and unlock + PIOS_FCLOSE(file); + xSemaphoreGiveRecursive(mutex); +#endif /* PIOS_INCLUDE_SDCARD */ + return 0; +} + +/** + * Delete an object from the file system (SD card). + * @param[in] obj The object handle. + * @param[in] instId The object instance + * @return 0 if success or -1 if failure + */ +int32_t UAVObjDelete(UAVObjHandle obj, uint16_t instId) +{ +#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) + PIOS_FLASHFS_ObjDelete(obj, instId); +#endif +#if defined(PIOS_INCLUDE_SDCARD) + ObjectList *objEntry; + uint8_t filename[14]; + + // Check for file system availability + if (PIOS_SDCARD_IsMounted() == 0) { + return -1; + } + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object + objEntry = (ObjectList *) obj; + + // Get filename + objectFilename(objEntry, filename); + + // Delete file + PIOS_FUNLINK(filename); + + // Done + xSemaphoreGiveRecursive(mutex); +#endif /* PIOS_INCLUDE_SDCARD */ + return 0; +} + +/** + * Save all settings objects to the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjSaveSettings() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Save all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isSettings) { + // Save object + if (UAVObjSave((UAVObjHandle) objEntry, 0) == + -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Load all settings objects from the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjLoadSettings() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Load all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isSettings) { + // Load object + if (UAVObjLoad((UAVObjHandle) objEntry, 0) == + -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Delete all settings objects from the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjDeleteSettings() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Save all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isSettings) { + // Save object + if (UAVObjDelete((UAVObjHandle) objEntry, 0) + == -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Save all metaobjects to the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjSaveMetaobjects() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Save all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isMetaobject) { + // Save object + if (UAVObjSave((UAVObjHandle) objEntry, 0) == + -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Load all metaobjects from the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjLoadMetaobjects() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Load all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isMetaobject) { + // Load object + if (UAVObjLoad((UAVObjHandle) objEntry, 0) == + -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Delete all metaobjects from the SD card. + * @return 0 if success or -1 if failure + */ +int32_t UAVObjDeleteMetaobjects() +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Load all settings objects + LL_FOREACH(objList, objEntry) { + // Check if this is a settings object + if (objEntry->isMetaobject) { + // Load object + if (UAVObjDelete((UAVObjHandle) objEntry, 0) + == -1) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + } + + // Done + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Set the object data + * \param[in] obj The object handle + * \param[in] dataIn The object's data structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjSetData(UAVObjHandle obj, const void *dataIn) +{ + return UAVObjSetInstanceData(obj, 0, dataIn); +} + +/** + * Get the object data + * \param[in] obj The object handle + * \param[out] dataOut The object's data structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjGetData(UAVObjHandle obj, void *dataOut) +{ + return UAVObjGetInstanceData(obj, 0, dataOut); +} + +/** + * Set the data of a specific object instance + * \param[in] obj The object handle + * \param[in] instId The object instance ID + * \param[in] dataIn The object's data structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjSetInstanceData(UAVObjHandle obj, uint16_t instId, + const void *dataIn) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + UAVObjMetadata *mdata; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object info + objEntry = (ObjectList *) obj; + + // Check access level + if (!objEntry->isMetaobject) { + mdata = + (UAVObjMetadata *) (objEntry->linkedObj->instances. + data); + if (mdata->access == ACCESS_READONLY) { + xSemaphoreGiveRecursive(mutex); + return -1; + } + } + // Get instance information + instEntry = getInstance(objEntry, instId); + if (instEntry == NULL) { + // Error, unlock and return + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Set data + memcpy(instEntry->data, dataIn, objEntry->numBytes); + + // Fire event + sendEvent(objEntry, instId, EV_UPDATED); + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Get the data of a specific object instance + * \param[in] obj The object handle + * \param[in] instId The object instance ID + * \param[out] dataOut The object's data structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjGetInstanceData(UAVObjHandle obj, uint16_t instId, + void *dataOut) +{ + ObjectList *objEntry; + ObjectInstList *instEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Cast to object info + objEntry = (ObjectList *) obj; + + // Get instance information + instEntry = getInstance(objEntry, instId); + if (instEntry == NULL) { + // Error, unlock and return + xSemaphoreGiveRecursive(mutex); + return -1; + } + // Set data + memcpy(dataOut, instEntry->data, objEntry->numBytes); + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Set the object metadata + * \param[in] obj The object handle + * \param[in] dataIn The object's metadata structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjSetMetadata(UAVObjHandle obj, const UAVObjMetadata * dataIn) +{ + ObjectList *objEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Set metadata (metadata of metaobjects can not be modified) + objEntry = (ObjectList *) obj; + if (!objEntry->isMetaobject) { + UAVObjSetData((UAVObjHandle) objEntry->linkedObj, + dataIn); + } else { + return -1; + } + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Get the object metadata + * \param[in] obj The object handle + * \param[out] dataOut The object's metadata structure + * \return 0 if success or -1 if failure + */ +int32_t UAVObjGetMetadata(UAVObjHandle obj, UAVObjMetadata * dataOut) +{ + ObjectList *objEntry; + + // Lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Get metadata + objEntry = (ObjectList *) obj; + if (objEntry->isMetaobject) { + memcpy(dataOut, &defMetadata, sizeof(UAVObjMetadata)); + } else { + UAVObjGetData((UAVObjHandle) objEntry->linkedObj, + dataOut); + } + + // Unlock + xSemaphoreGiveRecursive(mutex); + return 0; +} + +/** + * Check if an object is read only + * \param[in] obj The object handle + * \return + * \arg 0 if not read only + * \arg 1 if read only + * \arg -1 if unable to get meta data + */ +int8_t UAVObjReadOnly(UAVObjHandle obj) +{ + ObjectList *objEntry; + UAVObjMetadata *mdata; + + // Cast to object info + objEntry = (ObjectList *) obj; + + // Check access level + if (!objEntry->isMetaobject) { + mdata = + (UAVObjMetadata *) (objEntry->linkedObj->instances. + data); + return mdata->access == ACCESS_READONLY; + } + return -1; +} + +/** + * Connect an event queue to the object, if the queue is already connected then the event mask is only updated. + * All events matching the event mask will be pushed to the event queue. + * \param[in] obj The object handle + * \param[in] queue The event queue + * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) + * \return 0 if success or -1 if failure + */ +int32_t UAVObjConnectQueue(UAVObjHandle obj, xQueueHandle queue, + int32_t eventMask) +{ + int32_t res; + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + res = connectObj(obj, queue, 0, eventMask); + xSemaphoreGiveRecursive(mutex); + return res; +} + +/** + * Disconnect an event queue from the object. + * \param[in] obj The object handle + * \param[in] queue The event queue + * \return 0 if success or -1 if failure + */ +int32_t UAVObjDisconnectQueue(UAVObjHandle obj, xQueueHandle queue) +{ + int32_t res; + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + res = disconnectObj(obj, queue, 0); + xSemaphoreGiveRecursive(mutex); + return res; +} + +/** + * Connect an event callback to the object, if the callback is already connected then the event mask is only updated. + * The supplied callback will be invoked on all events matching the event mask. + * \param[in] obj The object handle + * \param[in] cb The event callback + * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) + * \return 0 if success or -1 if failure + */ +int32_t UAVObjConnectCallback(UAVObjHandle obj, UAVObjEventCallback cb, + int32_t eventMask) +{ + int32_t res; + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + res = connectObj(obj, 0, cb, eventMask); + xSemaphoreGiveRecursive(mutex); + return res; +} + +/** + * Disconnect an event callback from the object. + * \param[in] obj The object handle + * \param[in] cb The event callback + * \return 0 if success or -1 if failure + */ +int32_t UAVObjDisconnectCallback(UAVObjHandle obj, UAVObjEventCallback cb) +{ + int32_t res; + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + res = disconnectObj(obj, 0, cb); + xSemaphoreGiveRecursive(mutex); + return res; +} + +/** + * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event + * will be generated as soon as the object is updated. + * \param[in] obj The object handle + */ +void UAVObjRequestUpdate(UAVObjHandle obj) +{ + UAVObjRequestInstanceUpdate(obj, UAVOBJ_ALL_INSTANCES); +} + +/** + * Request an update of the object's data from the GCS. The call will not wait for the response, a EV_UPDATED event + * will be generated as soon as the object is updated. + * \param[in] obj The object handle + * \param[in] instId Object instance ID to update + */ +void UAVObjRequestInstanceUpdate(UAVObjHandle obj, uint16_t instId) +{ + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + sendEvent((ObjectList *) obj, instId, EV_UPDATE_REQ); + xSemaphoreGiveRecursive(mutex); +} + +/** + * Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). + * \param[in] obj The object handle + */ +void UAVObjUpdated(UAVObjHandle obj) +{ + UAVObjInstanceUpdated(obj, UAVOBJ_ALL_INSTANCES); +} + +/** + * Send the object's data to the GCS (triggers a EV_UPDATED_MANUAL event on this object). + * \param[in] obj The object handle + * \param[in] instId The object instance ID + */ +void UAVObjInstanceUpdated(UAVObjHandle obj, uint16_t instId) +{ + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + sendEvent((ObjectList *) obj, instId, EV_UPDATED_MANUAL); + xSemaphoreGiveRecursive(mutex); +} + +/** + * Iterate through all objects in the list. + * \param iterator This function will be called once for each object, + * the object will be passed as a parameter + */ +void UAVObjIterate(void (*iterator) (UAVObjHandle obj)) +{ + ObjectList *objEntry; + + // Get lock + xSemaphoreTakeRecursive(mutex, portMAX_DELAY); + + // Iterate through the list and invoke iterator for each object + LL_FOREACH(objList, objEntry) { + (*iterator) ((UAVObjHandle) objEntry); + } + + // Release lock + xSemaphoreGiveRecursive(mutex); +} + +/** + * Send an event to all event queues registered on the object. + */ +static int32_t sendEvent(ObjectList * obj, uint16_t instId, + UAVObjEventType event) +{ + ObjectEventList *eventEntry; + UAVObjEvent msg; + + // Setup event + msg.obj = (UAVObjHandle) obj; + msg.event = event; + msg.instId = instId; + + // Go through each object and push the event message in the queue (if event is activated for the queue) + LL_FOREACH(obj->events, eventEntry) { + if (eventEntry->eventMask == 0 + || (eventEntry->eventMask & event) != 0) { + // Send to queue if a valid queue is registered + if (eventEntry->queue != 0) { + if (xQueueSend(eventEntry->queue, &msg, 0) != pdTRUE) // will not block + { + ++stats.eventErrors; + } + } + // Invoke callback (from event task) if a valid one is registered + if (eventEntry->cb != 0) { + if (EventCallbackDispatch(&msg, eventEntry->cb) != pdTRUE) // invoke callback from the event task, will not block + { + ++stats.eventErrors; + } + } + } + } + + // Done + return 0; +} + +/** + * Create a new object instance, return the instance info or NULL if failure. + */ +static ObjectInstList *createInstance(ObjectList * obj, uint16_t instId) +{ + ObjectInstList *instEntry; + int32_t n; + + // For single instance objects, only instance zero is allowed + if (obj->isSingleInstance && instId != 0) { + return NULL; + } + // Make sure that the instance ID is within limits + if (instId >= UAVOBJ_MAX_INSTANCES) { + return NULL; + } + // Check if the instance already exists + if (getInstance(obj, instId) != NULL) { + return NULL; + } + // Create any missing instances (all instance IDs must be sequential) + for (n = obj->numInstances; n < instId; ++n) { + if (createInstance(obj, n) == NULL) { + return NULL; + } + } + + if (instId == 0) { /* Instance 0 ObjectInstList allocated with ObjectList element */ + instEntry = &obj->instances; + instEntry->data = pvPortMalloc(obj->numBytes); + if (instEntry->data == NULL) + return NULL; + memset(instEntry->data, 0, obj->numBytes); + instEntry->instId = instId; + } else { + // Create the actual instance + instEntry = + (ObjectInstList *) + pvPortMalloc(sizeof(ObjectInstList)); + if (instEntry == NULL) + return NULL; + instEntry->data = pvPortMalloc(obj->numBytes); + if (instEntry->data == NULL) + return NULL; + memset(instEntry->data, 0, obj->numBytes); + instEntry->instId = instId; + LL_APPEND(obj->instances.next, instEntry); + } + ++obj->numInstances; + + // Fire event + UAVObjInstanceUpdated((UAVObjHandle) obj, instId); + + // Done + return instEntry; +} + +/** + * Get the instance information or NULL if the instance does not exist + */ +static ObjectInstList *getInstance(ObjectList * obj, uint16_t instId) +{ + ObjectInstList *instEntry; + + // Look for specified instance ID + LL_FOREACH(&(obj->instances), instEntry) { + if (instEntry->instId == instId) { + return instEntry; + } + } + // If this point is reached then instance id was not found + return NULL; +} + +/** + * Connect an event queue to the object, if the queue is already connected then the event mask is only updated. + * \param[in] obj The object handle + * \param[in] queue The event queue + * \param[in] cb The event callback + * \param[in] eventMask The event mask, if EV_MASK_ALL then all events are enabled (e.g. EV_UPDATED | EV_UPDATED_MANUAL) + * \return 0 if success or -1 if failure + */ +static int32_t connectObj(UAVObjHandle obj, xQueueHandle queue, + UAVObjEventCallback cb, int32_t eventMask) +{ + ObjectEventList *eventEntry; + ObjectList *objEntry; + + // Check that the queue is not already connected, if it is simply update event mask + objEntry = (ObjectList *) obj; + LL_FOREACH(objEntry->events, eventEntry) { + if (eventEntry->queue == queue && eventEntry->cb == cb) { + // Already connected, update event mask and return + eventEntry->eventMask = eventMask; + return 0; + } + } + + // Add queue to list + eventEntry = + (ObjectEventList *) pvPortMalloc(sizeof(ObjectEventList)); + if (eventEntry == NULL) { + return -1; + } + eventEntry->queue = queue; + eventEntry->cb = cb; + eventEntry->eventMask = eventMask; + LL_APPEND(objEntry->events, eventEntry); + + // Done + return 0; +} + +/** + * Disconnect an event queue from the object + * \param[in] obj The object handle + * \param[in] queue The event queue + * \param[in] cb The event callback + * \return 0 if success or -1 if failure + */ +static int32_t disconnectObj(UAVObjHandle obj, xQueueHandle queue, + UAVObjEventCallback cb) +{ + ObjectEventList *eventEntry; + ObjectList *objEntry; + + // Find queue and remove it + objEntry = (ObjectList *) obj; + LL_FOREACH(objEntry->events, eventEntry) { + if ((eventEntry->queue == queue + && eventEntry->cb == cb)) { + LL_DELETE(objEntry->events, eventEntry); + vPortFree(eventEntry); + return 0; + } + } + + // If this point is reached the queue was not found + return -1; +} + +#if defined(PIOS_INCLUDE_SDCARD) +/** + * Wrapper for the sprintf function + */ +static void customSPrintf(uint8_t * buffer, uint8_t * format, ...) +{ + va_list args; + va_start(args, format); + vsprintf((char *)buffer, (char *)format, args); +} + +/** + * Get an 8 character (plus extension) filename for the object. + */ +static void objectFilename(ObjectList * obj, uint8_t * filename) +{ + customSPrintf(filename, (uint8_t *) "%X.obj", obj->id); +} +#endif /* PIOS_INCLUDE_SDCARD */ From bac95dae110b2f76690f14322c18b38640a4045d Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sat, 14 May 2011 23:17:08 +0300 Subject: [PATCH 33/43] OP-483: get rid of -D install switch (doesn't work on Mac) and use mkdir -p instead --- flight/AHRS/Makefile | 3 ++- flight/Bootloaders/AHRS/Makefile | 3 ++- flight/Bootloaders/BootloaderUpdater/Makefile | 3 ++- flight/Bootloaders/CopterControl/Makefile | 3 ++- flight/Bootloaders/OpenPilot/Makefile | 3 ++- flight/Bootloaders/PipXtreme/Makefile | 3 ++- flight/CopterControl/Makefile | 3 ++- flight/INS/Makefile | 3 ++- flight/OpenPilot/Makefile | 3 ++- flight/PipXtreme/Makefile | 3 ++- 10 files changed, 20 insertions(+), 10 deletions(-) diff --git a/flight/AHRS/Makefile b/flight/AHRS/Makefile index 2e4e0ff6b..d4dafd68f 100644 --- a/flight/AHRS/Makefile +++ b/flight/AHRS/Makefile @@ -403,7 +403,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/AHRS/Makefile index 0c8b23882..ada1b99e3 100644 --- a/flight/Bootloaders/AHRS/Makefile +++ b/flight/Bootloaders/AHRS/Makefile @@ -393,7 +393,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/Bootloaders/BootloaderUpdater/Makefile b/flight/Bootloaders/BootloaderUpdater/Makefile index 17839daac..25de8140b 100644 --- a/flight/Bootloaders/BootloaderUpdater/Makefile +++ b/flight/Bootloaders/BootloaderUpdater/Makefile @@ -414,7 +414,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index 74b55cb17..955d948d0 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -451,7 +451,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile index 292291609..735a63003 100644 --- a/flight/Bootloaders/OpenPilot/Makefile +++ b/flight/Bootloaders/OpenPilot/Makefile @@ -454,7 +454,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index 1610ad603..e1d2e8156 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -450,7 +450,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index e7607af74..43e8e514a 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -595,7 +595,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/INS/Makefile b/flight/INS/Makefile index 5ef6adb86..1b27d8cba 100644 --- a/flight/INS/Makefile +++ b/flight/INS/Makefile @@ -420,7 +420,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile index 548e6d188..290dc438e 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/OpenPilot/Makefile @@ -574,7 +574,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 876678a32..3955d1929 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -443,7 +443,8 @@ docs: install: $(OUTDIR)/$(TARGET).bin ifneq ($(INSTALL_DIR),) @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) $(INSTALL) -D $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin + $(V1) mkdir -p $(INSTALL_DIR) + $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).bin else $(error INSTALL_DIR must be specified for $@) endif From 67f084a9e1add98cfb6aed77b6b9ba9e819ac3aa Mon Sep 17 00:00:00 2001 From: dankers Date: Sun, 15 May 2011 06:19:32 +1000 Subject: [PATCH 34/43] Amazing how badly it flies with just missing one full stop --- shared/uavobjectdefinition/stabilizationsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index 177d097cf..b11c0f1dc 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -9,7 +9,7 @@ - + From d312e876c46df25b85f45c887141ea38b704b4d4 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sat, 14 May 2011 16:11:30 -0500 Subject: [PATCH 35/43] OP-216: Some small bugs where things were stored --- flight/PiOS/Common/pios_flashfs_objlist.c | 29 +++++++++++++---------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index 4f39125db..f574169a9 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -77,21 +77,23 @@ int32_t PIOS_FLASHFS_Init() if(PIOS_FLAHFS_CleabObjectTableHeader() < 0) return -1; } - - bool found = true; + int32_t addr = OBJECT_TABLE_START; struct objectHeader header; numObjects = 0; // Loop through header area while objects detect to count how many saved - while(found && addr < OBJECT_TABLE_END) { + while(addr < OBJECT_TABLE_END) { // Read the instance data if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0) return -1; + + // Counting number of valid headers if(header.objMagic != OBJ_MAGIC) - found = false; - else - numObjects++; + break; + + numObjects++; + addr += sizeof(header); } return 0; @@ -121,22 +123,22 @@ static int32_t PIOS_FLAHFS_CleabObjectTableHeader() */ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) { - bool found = true; int32_t addr = OBJECT_TABLE_START; struct objectHeader header; // Loop through header area while objects detect to count how many saved - while(found && addr < OBJECT_TABLE_END) { + while(addr < OBJECT_TABLE_END) { // Read the instance data if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0) return -1; if(header.objMagic != OBJ_MAGIC) - found = false; + break; // stop searching once hit first non-object header else if (header.objId == objId && header.instId == instId) break; + addr += sizeof(header); } - if (found) + if (header.objId == objId && header.instId == instId) return header.address; return -1; @@ -154,7 +156,6 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId) */ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId) { - int32_t addr = OBJECT_TABLE_START; struct objectHeader header; if(numObjects < 0) @@ -164,8 +165,10 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId) header.objMagic = OBJ_MAGIC; header.objId = objId; header.instId = instId; - header.address = SECTOR_SIZE * numObjects; + header.address = OBJECT_TABLE_END + SECTOR_SIZE * numObjects; + int32_t addr = OBJECT_TABLE_START + sizeof(header) * numObjects; + // No room for this header in object table if((addr + sizeof(header)) > OBJECT_TABLE_END) return -2; @@ -245,7 +248,7 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data) // Object currently not saved if(addr < 0) return -1; - + struct fileHeader header; // Load header From 0005729056e0980a859a990455f4823960851449 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 15 May 2011 04:14:17 +0300 Subject: [PATCH 36/43] OP-500: fix PyMite dependencies on autogenerated files This is done by separating PyMite-dependent sources and making them dependent on autogenerated python code. This was tested with make -j on Windows and worked fine. It failed with errors otherwise: In file included from ../Libraries/PyMite/vm/class.c:28: ../Libraries/PyMite/vm/pm.h:198: fatal error: pmfeatures.h: No such file or directory --- flight/OpenPilot/Makefile | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile index 8bb3ed27c..677c3fbf6 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/OpenPilot/Makefile @@ -52,14 +52,13 @@ endif FLASH_TOOL = OPENOCD # List of modules to include -MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP FlightPlan - +MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP +PYMODULES = FlightPlan #MODULES = Telemetry Example #MODULES = Telemetry MK/MKSerial #MODULES = Telemetry #MODULES += Osd/OsdEtStd - # MCU name, submodel and board # - MCU used for compiler-option (-mcpu) # - MODEL used for linker-script name (-T) and passed as define @@ -124,17 +123,19 @@ UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight # List C source files here. (C dependencies are automatically generated.) # use file-extension c for "c-only"-files -MODNAMES = $(notdir ${MODULES}) +MODNAMES = $(notdir ${MODULES} ${PYMODULES}) ifndef TESTAPP -## PyMite files +## PyMite files and modules SRC += $(OUTDIR)/pmlib_img.c SRC += $(OUTDIR)/pmlib_nat.c SRC += $(OUTDIR)/pmlibusr_img.c SRC += $(OUTDIR)/pmlibusr_nat.c -SRC += $(wildcard ${PYMITEVM}/*.c) -SRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += $(wildcard ${PYMITEVM}/*.c) +PYSRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += $(PYSRC) ## MODULES SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} @@ -317,7 +318,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc +EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. @@ -481,7 +482,7 @@ LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) # Default target. -all: gencode gccversion build +all: gccversion build ifeq ($(LOADFORMAT),ihex) build: elf hex lss sym @@ -500,6 +501,8 @@ endif # Generate intermediate code gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h +$(PYSRC): gencode + # Generate code for module initialization ${OUTDIR}/InitMods.c: Makefile @echo $(MSG_MODINIT) $(call toprel, $@) From feb9c027804ff708689fd4244c97976dbd33af12 Mon Sep 17 00:00:00 2001 From: James Cotton Date: Sun, 15 May 2011 00:18:15 -0500 Subject: [PATCH 37/43] OP-216: Small typo in flashfs code (thanks Zippe) --- flight/PiOS/Common/pios_flashfs_objlist.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index f574169a9..5c8248f54 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -33,7 +33,7 @@ #include "uavobjectmanager.h" // Private functions -static int32_t PIOS_FLAHFS_CleabObjectTableHeader(); +static int32_t PIOS_FLASHFS_CleabObjectTableHeader(); static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId); static int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId); @@ -74,7 +74,7 @@ int32_t PIOS_FLASHFS_Init() if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0) return -1; if(object_table_magic != OBJECT_TABLE_MAGIC) { - if(PIOS_FLAHFS_CleabObjectTableHeader() < 0) + if(PIOS_FLASHFS_CleabObjectTableHeader() < 0) return -1; } @@ -103,7 +103,7 @@ int32_t PIOS_FLASHFS_Init() * @brief Erase the headers for all objects in the flash chip * @return 0 if successful, -1 if not */ -static int32_t PIOS_FLAHFS_CleabObjectTableHeader() +static int32_t PIOS_FLASHFS_CleabObjectTableHeader() { if(PIOS_Flash_W25X_EraseSector(OBJECT_TABLE_START) != 0) return -1; From b33d093a7ae6c2d5bc570534859335253d6cb353 Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 15 May 2011 14:54:24 +0300 Subject: [PATCH 38/43] OP-483: update Windows build system, provide install replacement Since msysGit lacks the install command, simple cp -f replacement is provided. Don't forget to copy it into the msysGit bin subdirectory. Introduced CLEAN_BUILD=NO make option to test packaging w/o cleaning. Recommended for test builds only, not for production run. make -j works great after PyMite dependency fix by commit 0005729056e0980a859a990455f4823960851449 So comment is updated as well. --- make/winx86/README.txt | 7 ++++--- make/winx86/bin/install | 15 +++++++++++++++ make/winx86/bin/make | 4 +++- make/winx86/cmd/make.sh | 8 ++++++++ make/winx86/cmd/sh.cmd | 3 ++- release/Makefile | 12 ++++++------ 6 files changed, 38 insertions(+), 11 deletions(-) create mode 100644 make/winx86/bin/install diff --git a/make/winx86/README.txt b/make/winx86/README.txt index 6024dd118..fb383fa17 100644 --- a/make/winx86/README.txt +++ b/make/winx86/README.txt @@ -37,17 +37,18 @@ locations (but any other locations are fine as well): - QtSDK in C:\Qt\2010.05 - msysGit in %ProgramFiles%\Git - Unicode NSIS in %ProgramFiles%\NSIS\Unicode + - OpenOCD in C:\OpenOCD\0.4.0\bin Also it is assumed that you have the C:\Program Files\Git\cmd\ directory in the PATH. Usually this is the case for msysGit installation if you have chosen the 2nd option: put only git and gitk in the PATH (it is recommended option). -Now you need to copy two files to your msysGit installation folders. +Now you need to copy few files to your msysGit installation folders. Assuming that you installed the msysGit into C:\Program Files\Git\, you have to copy: - make\winx86\bin\make -> C:\Program Files\Git\bin\ - make\winx86\cmd\sh.cmd -> C:\Program Files\Git\cmd\ + make\winx86\bin\* -> C:\Program Files\Git\bin\ + make\winx86\cmd\* -> C:\Program Files\Git\cmd\ If you have msysGit installed into another directory, you need to update paths accordingly. Also if you have tools installed into different directories and diff --git a/make/winx86/bin/install b/make/winx86/bin/install new file mode 100644 index 000000000..fae28bf23 --- /dev/null +++ b/make/winx86/bin/install @@ -0,0 +1,15 @@ +#!/bin/sh +# +# simple install command replacement for Windows +# +# This file should be put into C:\Program Files\Git\bin\ subdirectory +# (or similar, depeding on where the msysGit package was installed) +# to provide a make command to unix-like build environment on Windows. +# +# See also: +# README.txt +# http://wiki.openpilot.org/display/Doc/GCS+Development+on+Windows +# http://wiki.openpilot.org/display/Doc/Firmware+Development+on+Windows +# + +cp -f $* diff --git a/make/winx86/bin/make b/make/winx86/bin/make index 4d475bff6..d4bf11224 100644 --- a/make/winx86/bin/make +++ b/make/winx86/bin/make @@ -1,6 +1,8 @@ #!/bin/sh # -# This file is to be put into C:\Program Files\Git\bin\ subdirectory +# make command replacement for Windows +# +# This file should be put into C:\Program Files\Git\bin\ subdirectory # (or similar, depeding on where the msysGit package was installed) # to provide a make command to unix-like build environment on Windows. # diff --git a/make/winx86/cmd/make.sh b/make/winx86/cmd/make.sh index 70ff64114..a2ae771d5 100644 --- a/make/winx86/cmd/make.sh +++ b/make/winx86/cmd/make.sh @@ -1 +1,9 @@ +# +# make command replacement to run from command prompt under bash +# +# This file should be put into C:\Program Files\Git\cmd\ subdirectory +# (or similar, depeding on where the msysGit package was installed) +# to provide a shell prompt in the unix-like build environment on Windows. +# + exec /bin/make $* diff --git a/make/winx86/cmd/sh.cmd b/make/winx86/cmd/sh.cmd index b3b276fb2..d82c7ec99 100644 --- a/make/winx86/cmd/sh.cmd +++ b/make/winx86/cmd/sh.cmd @@ -1,6 +1,6 @@ @echo off rem -rem This file is to be put into C:\Program Files\Git\cmd\ subdirectory +rem This file should be put into C:\Program Files\Git\cmd\ subdirectory rem (or similar, depeding on where the msysGit package was installed) rem to provide a shell prompt in the unix-like build environment on Windows. rem @@ -56,6 +56,7 @@ call :which QTSDK "C:\Qt\2010.05\qt\bin" qmake.exe call :which CODESOURCERY "C:\CodeSourcery\bin" cs-make.exe call :which PYTHON "C:\Python27" python.exe call :which UNSIS "%ProgramFiles%\NSIS\Unicode" makensis.exe +call :which OPENOCDBIN "C:\OpenOCD\0.4.0\bin" openocd.exe if "%NOT_FOUND%" == "" goto set_path diff --git a/release/Makefile b/release/Makefile index a1a45de3b..bf9817b25 100644 --- a/release/Makefile +++ b/release/Makefile @@ -4,12 +4,8 @@ # Tried the best to support parallel (-j) builds. But since this Makefile # uses other Makefiles to build few targets which in turn have similar # dependencies on uavobjects and other generated files, it is difficult -# to support parallel builds perfectly. -# -# Looks like it works for -j8, but fails for -j (unlimited jobs). -# So probably not a bad idea is to build release in single thread. -# -#.NOTPARALLEL: +# to support parallel builds perfectly. But at least it was tested with +# -j (unlimited job number) on Windows and Linux. # Locate the root of the tree WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) @@ -41,9 +37,11 @@ help: @echo @echo " [Release build and packaging]" @echo " release - Build and package the OpenPilot release" + @echo " release_flight - Build and package the OpenPilot flight firmware" @echo @echo " Notes:" @echo " - the build directory will be removed first on every run" + @echo " unless CLEAN_BUILD=NO is defined (recommended for testing only)" @echo " - release packages will be placed in $(RELEASE_DIR)" @echo @@ -52,7 +50,9 @@ uavobjects: all_clean $(V1) $(MAKE) -C $(ROOT_DIR) $@ all_clean: +ifneq ($(CLEAN_BUILD), NO) $(V1) $(MAKE) -C $(ROOT_DIR) $@ +endif # Install template: # $1 = target From 2c1caa957ce5abd6eae6c852b667e0346af388d3 Mon Sep 17 00:00:00 2001 From: dankers Date: Sun, 15 May 2011 22:13:21 +1000 Subject: [PATCH 39/43] Add some more sounds to the complete sound set --- .../openpilotgcs/sounds/Complete sound set.txt | 9 +++++---- .../share/openpilotgcs/sounds/default/armed.wav | Bin 0 -> 73290 bytes .../sounds/default/coptercontrol.wav | Bin 0 -> 84106 bytes .../openpilotgcs/sounds/default/critical.wav | Bin 0 -> 69642 bytes .../openpilotgcs/sounds/default/disarmed.wav | Bin 0 -> 76106 bytes .../share/openpilotgcs/sounds/default/magic.wav | Bin 0 -> 61834 bytes .../share/openpilotgcs/sounds/default/moved.wav | Bin 0 -> 81292 bytes .../src/plugins/coreplugin/OpenPilotGCS.ini | 2 +- 8 files changed, 6 insertions(+), 5 deletions(-) create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/armed.wav create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/coptercontrol.wav create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/critical.wav create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/disarmed.wav create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/magic.wav create mode 100644 ground/openpilotgcs/share/openpilotgcs/sounds/default/moved.wav diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt b/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt index 14bea3094..e539e6d24 100644 --- a/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt +++ b/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt @@ -21,6 +21,7 @@ alert altitude amps aquired +armed autonomous flight battery camera @@ -32,8 +33,10 @@ complete connected connection control +coptercontrol critical disabled +disarmed disconnected feet figure eight @@ -58,11 +61,13 @@ lost low altitude low battery low gps quality +magic manual flight maxium meters minimum mode +moved MPH navigation OpenPilot @@ -122,8 +127,4 @@ hundread thousand -Upto: OpenPilot -critical -battery -point diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/default/armed.wav b/ground/openpilotgcs/share/openpilotgcs/sounds/default/armed.wav new file mode 100644 index 0000000000000000000000000000000000000000..22678cf67c93e10e8b9a0cebdeab28f95d6bca5d GIT binary patch literal 73290 zcmX6F1z1yEd);+o8>3;2jnUoRodyVEfQX9S-QC@t*exn3C@l!6fFLSTg3{gp>-RtB zIrpCPcAazXWg8LxK0Y3rM8YKZiQcnPmTC(K1OgG7*Bt_3=VT&*L=X^y{3D|#0^C2u zC)D3PB1#0~sM(3yp$ik|hb7Njuv9y2@q#&tGnW$lJ%gi+0PDFpar)Ba<%!y!3sO=R z%wM7%IXz|JyyW>w+F|pSEzveNG1Cr8o|!m*Ng{!eFn#Itw;Dv?A`vJA8i7vW5SRo6 zt|GXK2@>d<1a*QoK?+Tupdc6!j0mO#6M_}Nf?z|iB{)EHBRCVh37!Ohf)61Gt|5dl zLIfe4Fo`gc5JQL~#1dvgOC%%_lA+Bfq!1Pm77>;ZmJwDF))LkbHW1bmwi7lJb`o|F zb`$mz_7e^h4iZifjuTEoJ4-lCxb|Pa3isRpwMT?|gy)3EglB{o&|VWV3F(A9!aG7C zAs<>Xv`>T*LOJ0Z;WObEp^{KfsD;)&EL2pCTw zh7+TRQ;Cy_NyK>KEVw2UrxRzxbp|noIG4DLxB&VR;zr^c;uh%JiR+1bh&zb8i6@Br ziKmDsiRXwHi3fR z5iy6DN6aGT!ZnxpnOIKzMyw?^5`PeX5gUm0#2Vsnn6(i*i0woYsfWlUjS|TuaGlgo z93lSebP}J$BZ){tk}63BMk*wXqy;lAl0Hd~Bqu3J1|(aOG07C>79=y01Id!)LUJPo zlYB@XBs-ET$(Q6!3Lu4&!bp=yv7}kh;z>!Q1X3Jn8jPot7Lw*b-$+_ST18q(T1Hwz zT0>e&T1?suv%{oqq%)*_q*J8*q@$!mq!Xm`q$8vYq=TfVq`Rc+q}!wiq*T&P(j6Gx zAw7c8D^eEe4XK!vNy;a^CcPtNklw=m11XzSLHbH6BYlKkOsXaokZMUkNIyxxN!_G+ z5{cYHY9)32H|r(!k|^Xc5}C{(3&_JH4w*t8CyB{)GD=n@BV-M-lB`2EA;=u7>`k^LyOC|6JCK9PPUIkfOeRN=17H?L_9ssuPa)4FPlvXcJeRzj zoJd{+*LmbsMNx;5E_6SNC3GK(oMH|X1~7J}cvAx5K9Mqul0u26tfWLx=23zuQ9u<-nNFEa zSqg0p+!s(1DN~^*Q9_~5qO7AVqO7K@rL3YPzQIfS4pe)p9@T(~QP)qu+EHz(p41>}EH!{S12D0G zi=bM;o+>SF2=fN!C0qaL6hrY@&$rLF<0z0{-B>;JVh z>Q(Ap>I3R)>Q15+A@vJf+o{#mHtKKc zOX^2z4)juJL)2f?Mk;~UO|7NoQ9EHqqh(OZv;iuIhS4ZAJz5`?4tFgYgVs-F(3mt; znh8w;-GZj18PIqzSA)3><}NgQnm)~gW<@il8PUvv|KG@gCZz?^Cevm?bECxr#X?#T zZ8}_+(iYL?&=P6$X%}gJw9P=32y|0v^JsHvYiT=a>uLLFDYOkhGmW+%sISBIB<(Ei z4DAu^3T-!S8*MM`1TBqr8roUfd)f_JHSH3u4sds1oJz|BTmh|!R!qyMmC>qbH)%g; z4{5)Frj+)A_JNj7YX|Cj+E2i?(LT{yX@j(0+AxhvXVKN@s&o;(gEmCVqV>Q*h|mf2 zQ5uu3Lr3XMI&1}W2EBzwrei>-PWPZ2(S>w3x|pt@%Ya*lZa_Ds6X~9GOZp_h1p!Wv z?gTI&`V9I?dN6%C^ttqjz!^(lL{Fq|0C+roFMS^U1oV~kWVp_yC(!56*U|UTchS$% zPty<4FVYVKWHUfE)1T3w(C-7}1^pI1o4%WV188>AGw9doS<%|-b zWixLAoscPFvY7(r9|p$6nPeuB*$a!HmLXx9G3}YAObezHQ^@2q4Vi5WG4n6OnCZi` zV$NbZGhLV}Ob2E+P%@aBKxM*Q%uHq`0^Wid#*{FSjACwNK4iu+*DxaiY7Je+ zOai%6fo?uCnz@r1#GJ%*W2(U{hB*hQXEBd4S22A7Gmm+QxrKR-d5U=*dKU9F^DOf= z^Ahs_a|LrR%pNd{m^Yd4n0o-0&OFJy1LNZWPh%2U<;=g#VrCWdE;E<;ikZrM4!Ez( z8fHDSf%yfv%7D6#*~RQ(_A&dJz04t|39AG~KcNX(z07eYkHux#v6L(hONS+5;Vf5H z7gNGgVcD~sSmpp%XKAxE0H()MWqGmWKs%om3bhVa)_T@splAjNiQUMmVtr(lvoct}0bj>D&&q^(AB)N!2J9zR zI>ufMz2*j2+5e4D-Y6W9*CUh3p*mO!g!8D)v71cA(zGo({9i z>{j+Ub_+X|eFNH2_8y=Z1$*llbrP9e-HfoGiE&oF(l{?TcR8;(4>%V%mpO|$$2iYH#$!%1!0S1u zV3q;bETB2YsRH8Iz5(RWHxhsxGTAbxm!W%N$vygQ|>eFF77Sv8tz8! z8}4rI74CiRBW^nPC%2qi!p-M?=icDva*uN>VOGT*ka8(=y-A6^R2lNZTL;2H3GxT-u6%v^bK zz!}b)&6~j6#q;K^fpIuMC-Ua-qIv1O>%8;4$2?o!GF~!Bz7LXD^H#zAH19R9j+Y9f zwY)suWZnke6J9az94`afI^J2(6~OZYu0uexo0kSyBL5}t4e;LJE#egb#eLp0UImZM zzsdUm@G9O;-U(hlubU_5Tkr>Y#{4flb$$u20dVhlKX?XwG2e(E%n#+u`SE}s=VkFM z`Te}z{C3_TZjo@u&0k`9gj;pU;=_yLnoC0>6W| zoIi(uhChQpiLb(+$#>*i@ss$I`4jnD`BMPCn}3wQihqZn3@wDef}hBb;$P=C@xSw* z@vHf40VXKnf8;0d=>ly*l3)+tU63J&;@k5*z%ETeHS$AX!&}9_ha44{^6&DD1&x9u z{B(YpAW*;(+~P|F9(*qUf1)KQh z{2+k_k}Z(%%lV=P^mTdD+N#18o-C>C6W2($`T3epAF1Oh~cOhh^bx(E?T1#KGu z`dUycC=yf(z6tUKI>;`8Ir2jAT~H(F7nmVm1)Gu2fgXq3}GM$@>^hs@DKsgE|`gUAYsT!#1C;pl!z_TCvZY2NQXcR5hJlMvP1%qUI85` z7dRvONDLAL)cVL$WHO?G7y(T(auC^%%t9_8OArYX1$x{OdypeX;*lB1I%F;4i_f6d)4x z9pZ*AK|dpN(ISM1@=e5-4`>fsjpm^F=mMa=hCWA+pi1lkYKn<4GWHI=i?*R((8p*o8jMje zW6U0FME$US^xc0vBWMG_L$NcM5Icm0V5V3$+Kc{0nOGF&j_t<6v0GRQb{TWV#!(X1 z2l{Yq6mgU!Zr0Fwc@v)E#62X+u!j~&LeaDVIw zwgOv)EyMybDRvHffz8DVuym{l>%*R5cd&NM1lxmM1DaxtfYb0eyb9P8r6=CHPlt6ZRX+13Mb9W7u`98DroBSPWi|aq%o{5m>Ms>w*X2jhH(A95cp) z@!7Zci_|UiFg3Ot#BFM zft6!p(C*^qxLkM+-;OWCKjZHBVVnijLHJ613yja>7x4r5W&9~F08RsZ7<{w9<#_IY zSQ(y%hv6=uB^oclSm0X@@H_`i0r(nR7xx6MwOBYV2Iv;RUcfEjDh4t%7GyFcj9}mX^flG#O1DWHP z9>mTCY#zmu@i_ol0eXpeE7pzGViH^*^nU_NO@yoQMEoH>37?Of;1QtrHS_}f2R;=f zTY)ZXybY_s^05)j8rK6mlK?XtaPeT7H!cMl4}3H31^%vp$hd;1X1D_I?Vza@cvK*Q z2O zVyHM7#AGGJ!v<%9hG4t_JPZY^<3M^W#3mGU2LneEME)G)vJCVjL9YH)ku})p1wODr z&o8JiF~ok;e?D+QDhFad2C`USfd}x;!*4-Ea)4J4WH5m)1fZ%AuT=117GzunY?6cS z!+=%%m#a4L%mw1hfK0Lh6AC`50LL6!zT=K)?+VxyQU{t{|S0?~5=Ni5JX1*E)$jF0_S)fP}q z!C?6mz~%z=KTACT9|zE__#GIFAx7sQMmZpVE7-0EQStz3Q^9r;E`&800#E|@&H=su zB4+@0)M1s_PpAqOSRD%1|C4ToU%+0&TK|H{@h{jmz)XQCxdERWSXhbuze z+g?y9JgBrTsO2`y3nIJ{A~G8)Z7Qq;B~FKYegPZ@V0S_PzlxDTTvPzU0&CAgoi2g6 zsX*LRA-{f_r5?D0_>c|T6;0cw=1FP@D?qv;756GoE>^WB8YbV$`j=BD~ zifsPNnH*wK0Z=QT_!qr@b>WE`4@!a6{?Aiuh=T+w^cS`bYQq9NT>)$D7x;D?c6JtEra-;?+b?aP z-tNJgQ-hp!W1C_BJ_LCTfe74zxUK{nJVD#P6=n_N6@W{IoU1}C{;k=6)>lGy6rk@Q z_z^9<2tNFa+g9u-)Ne38irp9JE# z9JGFcs;`3+uLH}4dj5=E0&njE>;+h^hhKt9xChZu0ssC&oVS9v1Uwr~x^_$fak~qV z?*!d4@TeVR)`K;jU_m{M)4*0KoHVYWXAXGQg>8oYbPQz0!P$@l_F9529@usiPSx$8 z=@P`^HdLDg{BFR~AQt7Yd&nT3%b^{_>tU}r3@acSDrFW_!nXfny8^6Ng(rZ|m>Ni5 z3VUNVoZba+c8=j~I7@g5e-D)r4YjZoBt%2@-(!&&8|y}2VQ~<{PN>k;a4s8wH6CCa zU3dhdq!0Do31cgvNVpAFcRqMkfrdjY#9(t9c*w$EL5&APWCDTm4nBl8KwhQ@&qK}* zL$1C+P0a>*FTi_!@P95=j($Mh!ABKX_vT=e3p~Btf=s2t3aG<>!kH8RxgCOvyYS!n z@ox<=q25}tuh?Ixy_aC~3W!o2D*tZ>n+mbK3tsJnlQLGAgWrXnCkJ$GgWX3@XenfY z=30pE5mW&YCSZAJC9I`#i1if6McrSPSYM9J&)7N4G(Jv4mpbGGVqbRpcNp6F(7WiA%*)@lx>y zQJwI#aJld<>{C0i9jFJ|iyTFY5D%1(<-*f=4y@^wutU}1LBiRhV$mV-6>*4oK(tiI z5-k*|h(w|n!r4M|VI5T3IGPUcN0*U*nyt}Gs0XZxD{zY37hRuG4XzJpID?q zQVAAgqA#E`6dyzHqw~-Q=s4ntj3En<`SAXETwpAS64)SX;XT9~Oa1R@=-$6dK)ung zh&sGA%t7N(BI=FU3r@j1d;+}LtAWQ{)C=B})<6X2qxDD%dJnw>asPLA+dy1)A|#0F zm|zLKLlvTxXezuzu&~Q$I9PBI%f){RpNTe#h9M>%qD-*%naE$fN&H*fDlQTCi#Mt? zs?a4nC4G_%)o#@t>MEK)H1}(3>840~^u}dV^ylfb^zX~O^d9PN)K%9B)h^a@)23>t zYFBG7*RIsblDf*s`e*gK^t+{W?MgLNydG)cJf%Gt``vTx&(&H&wO^%mRq9WpX8q2F z9<>4Y0hd9SkqMN=f&tAa<1+i*uB+UZI8C)tHH$I~mJ9TrXxpi^WBMG7{9@Rn&$N4K z=b6rTUF6=5{?=g;v4l3v=|ahp5Y5$6YyG8)RC%2KE?sxc>5?r%HI&BR!q%j-Nb5!n z`?5OY+m^Q-?kMQpGBh?`M!CS0nU|#?GnxF5kKFChJ{~+qkcS|_vFRs1YxTP&`a2~xAx7X1z95g>=wa^N;*lALvw35f`QFVA4{vusoAeq>2 z+*0~Iy1cgR<>&EgSwmNQz~BSILTV&qD=V5Cj@nBOY8B~TksgyxQj{nOChcaEENo15 z6wRtG?5eTEA*Ye?abHFplBjZ7El$l{bW|YWh}q{k>-aL^RCO=u97UGGN9LeCs4^E7 z^7eCDxowz{TCa{mf3v(+E>`SU3>)k;JZUU8)iA9!nP6OK_(S=`;Ftah>4-+Fh$3iX zuVi^M5ZbhH-=3;Jn|>R&JnOtbS|GV-n&?Du8*v!0SZIVOYYn=L+|2h_Ia&HCZ8W+C z1GKKO?tVdcb!%gD?r*ifBkkUO562?u+1z_*8a`QkL_J-qtDI+SXFO4PQU8Okt5$>R zK5;%)#7m%;k4+tj?=v5?A3H-{N8idCXH9~?0{8N?&`6aFnuXFF`D}$yF;_oA`dO1K zNkNx#l1YWV_J4g_2yMzA5tj@Z^(y-7##ga7;tw^%GFO9a`AJk!*TPEGL-%=9DeZI{oVIOU?9OS-hNtoHy_9yz75gpHHnI zwfmX)J+SRl9#s$GlnuT6ef_IZaZ~QJ+@Qi^ zWy`*8{{6MLlsq3fuOT%UuvqSp@9O1I>e1*P=PGmbv3_9uKyRHy$R&=ucI>R1_LW$+ z|HJWIqnwxdS4zKpD{ijuPbF<WD(W~A>ge=Q$SUCG5RN^Q97Tr%(Z4|8A=by z=NTQeNV0$IYV6hQJ?6I0s#yCKyP{{skGUV$=Ckr8g=;^qC`&0*eq2^GzgSuJqeicj z!#*T4agB}4ix(x@Cf=CQ8<#$5D0Gisy6YaRIQ_k13jIM(&95b&wDY1fuVzfiyq|lu zWX`w8EwzJ5;i7wycZ#37zmZ?B_XYPY4nttS~V`BUSLXjE6_Z=OvIO5RePq@DcfUMXDYJLwJ0;sHa}qQ zZnnZ?vEehtY8g+@Rysl2C{>r`>lNvm=)Bje)r{7x)EH8qp|)IOvGzl$1lDnkfsf%E zV>5Fj8++%y-X{W);Q4+tovV!2Np6$WTep4dEGsTHEhZP|79Po)nVtB)D*I2-vFaCX zDwKJuM3Y{Zr9nOuPfW3$S{LU!Wz)ojP`Y=B-2nrNq>-^=K&LsqN~7d*Ud#J|_m}gk zJ~n=R*;v%`gB*sIX@4;;wA<#^>s{!#Gr%~2>bJ!6lOx@Ho%9^Oks8^%tdaUv{bOOi zJnwM9!xEp$KR?Ayjeny%J^DY4pJ5+RS)!k68Sc8yo8>#(gXOr;LdP&(Z?aZ|+FO+a zqEJl8+rbc%Z%AjamVw4|jW(?e-QRkX^)uvl1~j8( zW>MBsr+uDHej9vmI`1+J673qR`MvO~McMJPX_cMd=6u^*E-KpdKK$*q_dCn>{@zR} z*1l}(>RS=&5V<^(8MQgmDH4sa3O(l6;@oM{uA#@-G=#R?tA1FrEq`}TWUj36Yl*UI zUj5C^-f=4LtJ-2ks>Lt+^)4N5`5q;nhdeDko;vwkN#)B${^aGI@pTPV8!C={eOYt7 zR#4As=&MVv|J)>NtL#spd_d~e;`L4%E;oN<_0VRn?G+oUm51q41Cs78^9M5Vmb$3&TCX+`xD{*IbD^-{Dcsyz(qtCO|uCAgAuXtP$TT}X5t?we~ zF*jOepO%-*Nf~EaVo_qX&BoDYo#j2#e&tT7rs^#2UBcDgHGi`kQ|f~om;QEWS@fs9 z^>e4*fE6i|_d#`)o=7>(@GR`&Yfbyg2Y+(oPL~slkOo+TQ#!8S5;4Qx|FEzs=rqnpjo2w z3f;_2W+|DSOe=ONCyDFJuNJ^t0-h@TDSE78rb1@X(K@ifYD}x1|q?cNA3QuFf+ov8<7` zHxSfNJ*_QrRg-U4Z=H0#I|E}wEkgYL9=ar0o|oIJ{^86RU)L#U2&%TIm{CssDz7f6 zx>i|J(OYT$gu`*`2yt!<5AN93k;rr5UWGxAttHH z8U;%sG#D^QR8BJJ(pTu+(*CT`rEabnpmSJOX23I^Z+ykbUwKYZDxYL{)_j@6ey^C2 zy2z}E_J9`WizY|ZZ*kp8&xRiLtZL=e|1B@fS&%mI;ozOf`+~FwxyF@fi|=RxAJf`p zdfEB9pKsWbiJmdRu~TBpq8~>(`DNP)WTB|W_{BD)*0ciocrTBdqnV>$5MO$vy0&q5 z_qy>(oR5+u#Y&r4ua00sgkjj(z*!z&?b=K&6_d24hz_u%qm$dwx&@UxOGXN}7P#lD z=j(jvDqB`_^3Rf?D#ii)h(@LKg8Y=y+Vr>87yE0@KCWwB%pF%-3rx!OY}H?44DM>i z44NkG4^5xp#~?Bm(iX#ay^b^ddFO>@nvF7ov75yQs|hw7+c0~&;~r<8+e-IC9@{*Y zyKB1&oUYobS#LF0m^?N#H@GEVtskwgD#w(grn_wXoS%DicwTjiG(D~Lp34~7)c(0? z?XPXsW1rOWeA04mKe`fd>G<{NC*1sjT8H8FNWJvE)ke?$u+G?{vwqD@m|s5MFeNW3 zcmcE_MJ8HI;@$$Uiq@@MD7)uL#dne!Gi`}oZ_JNV}tVxnZ zijy{5JT3?P4tW-~IW!|E*BAG!ab9h^%+x^to?0Ywm411A&cKZB?9Ppyf4aW*#tlpu z=_2^jSe$u?lXz4^A=_mXZCPTU=wjg^@jUIh!gG&jx#u@exyM`AM^0Y$1=gjOrWQHo zcTH1_UMT8h-g>X~Udii?O0B$I;(b(nkGbBqh}1d6#fPf@G}J$+ZTqpMy0^6WecSUt zcO7pU-@0o9sa}NXevxFXTN|SQ9oj~#y*Vs6lE45aJprv zqNc$nj_hi)`88NB`>;2wO1Ja zFmO{~r{8%GcZc()h~5+NGR_yG%MiJDU5{hWo9>A{2EF9Ik%6_NhsldsPtjDhh0=aQ z2g}3uSzw4TGAVQhB{^x{zIh(WansEsKf87sEJc$>7B*K^85N((e*Gr< z<+kUiUR0(}%+>wOYsl~GVrHoAG@9(B;-3|fIXO5cb@Et5lK*;Vj@dPx6zn9$uy43= zcjfYejEtSnsvpmJy8qRLY*Oj-n%3qWJ=J3undgLtdN(Z!-8Kc+MlG3qc!GDx2G1RK zVJ4ok7n)Q_4wlBfOglN&-P_SdYuVpq)~w&QqtAxW%?!l~RsU$$%MuM5Or~4KI;6XX z`%DOE44M~g7IfJ^&?n3NuoKHB({#BqSie!aS2|Uysb?cK)A^!quewmhK&@K0%Y^Kl z<0}a{AKdIU)9R6~2R5B97=JwcdI0aJ`Nb})d~@pFqidE|<5OQgH~aAYr)G}>eTIsg zV!LgX_i#kaRD)T_9K*RrbJ7#}anFO3?Td6baVq;6jcw)T1@&)pUWPnh^z3q)DC>EV z>o-d4>oHA4OV`2Dz#}MR?!+rG4`XIedJ|ggWoPSXuv>L9XT#{{HqlSZvL`uyueUu- zcy#h{N?Kdi@sH8p*ZgGfG#Q9B?p58r1Ip!l%AGmM*o+UmOKAZQ(^@D0Pua!KO#haqF$@HLeoF6@0IJs>K z62EQQu6X5?u83g|Pt$MWgQVAOSwF;ICKUb7&3vEz?)v+Nyy+#e)oH(%_uZ!M6Rwd( zT1B{z2M&enMo}Z41_pZ^voSTirKyRcRJDPomTfgDCF`@lyxq(<%D`>C$?O}R`$T?mc@3vwJr>=`F@I^&=A+q51}7|<$*iBGhNo$jG45{ zy``o)I@+yTZkioxx5a01Z|o}CB zlI95&``>?jBER$SmgMfY7k3I=zPEMOkbBU_+5!`rBkp%SYH;d=M9Kl@8;kyCQPS2we()&g`R1%ErGj5(T`R}Q%w(iYa!zlK zg@;>ju+K!x=<=xP0W_xqlR8dNj6H{)kWH)`tGJH>@7U+1r!H1d0RL%8GY1diZb~!wh1kN{CdxuUpGH^yxeww zRchZIvu7pmV!os{-R&Qw9>kvMB%As>$M_$JS`oWx#;1fSGb5)uMxFNRx5(EVU{4+N z`Lq8=VEMPA$XwTV&$1TfXcbSav}_P|N0Z=tA=(-y6CJ;KF9}WvV}&jXsPPDQcxm!L znkLF-29K1r8`K+D8h<>RyFHVWp`9M~_EPTZGUK0z+a`^=vCfMY=$tkrS$}ud@b2*w z2HN;1`*geeIXPN4823mYNwRn}>cGg>e#hRho`9ZXz1;q^!3CpJNLLs>$b3nO&UXWm z*=g&)_R-Gcu7^EJJ^y;yd#&<3^jj@nB2K zoNxU_lFXr}ckkETQ+*Pjv7(@_;z9k!PP=gi_lVjorG;IdXLOJC#UI_%T8A{VHQP07HLj{&Q*lyhl1Mb`_3}+k9nX8N z^G)?0cUogMMK4RT16|BxvxdoO1IvDwecJU#{vhJk$y?3$174dK9;>eZGiOM~xGR#% zy>0V+{zl!3SDO`=oSr;9D?NTVGR^acS-1K{Cb!?B$>%FxJoCLBtiRG%?wKn2VV}!u z=XN@i=3*IoK2|m!nL(!`k5BN5x)%D}m*kRbo~M^2;xlpvwOcx>sUP>h+xKeQ^M+^X zX-6{_Ww#Xhe$8%t&{svwVCQR#a9wk7|Mw3h%AcO81mlN)^&o_XL*6D34bxA zb?AEc+}8cgqNYzxADhEkox4&8?-I*d@R^sUuE9FXHmBoW8v-VWgoVG2h>P@%XbU9< zRe4Wy@wF*19?{>gBi5j*-Vjg0dy#8A31=&d!R*aUcb1!aaAg$(&TcM7mr zrZCnvm25-S(}#w>w$Li4=Nx!`?at(z8mUf?3f{=eY#PoFY-Q)EKUG@UhIm>9-=B0L z9#5>CHFs9$G`9&J9%~FUu&v`7ZPRL{6(2q-@}In)lWCD@_I^|0+45KQeZ6XoV`@AT zAD8ifDfnU8B!`GmXNt1=$^wT59dk%GcZcl5U z)mhSYqKDVFd~nCuK3az0qI$G~W=V5i=j9)uAL1U`8Ttiw^pFs4(1_1;H#fUiW*-gK z=s9a2);Olh5RapKdCTG3xa;^YM0>PP8s*u2aZmAa_p$T1>d3adXrz!E>Z+^xpl_+g zJyE~rmArZT<_YUQa_{(~j+g1VXUbigD*Aos1LE8AD>n1JQzFabrX<8Atx9rE2#q6$ zH@bzJd{xz89O>KIXkU4@NHaVA4Jl*pn;-9uif&duZ+PFco3dSKs{h>D-@`L-FjO;q zUx?hl%WbEvfl-@QCpwWD(ck}D?c3Fl>$5eW9*18RzwUUOl3P&f{KK;SJaIm{RtGWW z+01eZ@rd!)3$vJ@I%!XoX7C;NQp?-=4ywNVK3XT?&+xteJ>Bl@VXcv^wQYa9UJMSC zmU79GN74%8-`2*?D?DO-?)Vo6Jq%?;oQgohy8_R8nK+hN&Ptv-b3aPAQ{bRDbv_33BU-=|OS zt-SN%Ufm1F-0F(O%>%=1_BzRCMU~BOud0Z3Qx_(losB2kCzi(Mh5EYo7~WLrrN#Hf zHim!QSiC!XJR|6}YKCQ2T*2U%RrS=K8cLw3LO;cNm3w(WK3IAr>}im?&qSvVGos!( z;X``s;I%)k-{Z=T<@#nwo~t~X^>F=@MHx{=e}6pf_N6vpI$9jLyJ?u+EYGgcuITCU zQPXC|K8tMkv9>#_@KRgE|3>W}x!T*>{=G$~DWXB8VRKW@U-jPJaZ}EKq(&~YTJ4hO zLkUg@x1F$S(znSWlkZHZ2`lrz4!^zm`s6E}bb6M&(D_S7 zolWlo#uv3dW3Ee{KP4h^(s&FhHhap77{`g0A$<2wrrv4^RBAV&eqE(!>GBV;`S*AYhr5wqOdu_ApWhQtnzOEzt+G!;gd8JV_SQGeuI?$- zFCb@6&HR(O{Jp5)YU%x|@_N+{)v?2zscPR9i{UR3FFoe@#QQb-sreoB{_Y;*6lGOx zcvAO!i*x8 zhPQ`43;OOm;(plSodss7D*LGws$M1eDcXuT@$a&_>5&Ya`&n43HPLX5jneg#XR+5^ zk4G+d?1nAaCI#{+?PX#Y&h#;Z*3Rl5g@$kZUxYukc^;A8pOaR$u1gq}o)& z2zy=M$Vl(lZPPE!+&LpA4v(7aQ)K-{*HJJw{=O@yG5p)IPqBs5v%h2xXGP?NmbQN% zX*It}{lJxld(}n4gxpzLzs7>n(B>ff$wGWw^xSR-lF(EWA zbGrS^9n+0ty(8{;wpf&EZ{VF6z0}t8>)6-s(ocm2xqEVU<_3JI`|SHOylwaBVjfd# zzVU6l2kyf@asEgBJbV{>oOhaP{n4;hYaIDZZs;v*l6*@kt;feFpmKIK1W>3q=PI@=O)ey_&W{oyQ&UZYs{NIHPhDS!xqUyu<2fO%Abn&*P!0vNS zt4r;qin;hUwm{Iy-ojkKq;u5Klae>OhDI~2XF45s_w`!p72}cQw8pyEXpU@H^OpD# zKbms6cf8*9OGZx6EADd_c+*{&`}fn*pWFTt26^-fTunM^?&Uf;Fd}L+S{BzBdn$Tv zI046yI+vzq2IMHn%uXmaJBS2 z>v_TbkMlXZJo9zRb-FakG#;OHxcB_;pl>_NWCe?}i{EX?2`F4$)=-t!Fw*gHB$jy} zU$6B;X>XMPKlyYCd>5h;S{&Hp?ch9Uc~jY>b3-*3ea)&N(?&h|vF_xKq4r;$`Mn25 zs1z0ML{X4-km9ykkxirX3Qv~*K+sTVYgk+8t)RO;cCINl0+UJdgE~PP*Cjc^ZRkFp zC3_zHCh0t9Icg>$>9CYDEI&GpcuM?LgMJ4#`zkz!?DNbl^rxyDpj6tIfom`E;wr^qN!nkQOKPGNXcs^Ag73Sq@zC&{% zw`Nqg^G@UJnsc9XKG^2OW<_T@WuGeEUaj%>!{}muwB{^jpXE}=3OAbfu#c`E$7ipb z(C(&jhV}!jm!>x~wROTT?@FW6<`13l^TQJ*r_1Ml`%s(G(9?3OD`o5%H&#Pne9!i} z%PO}>S8ZpyQ=rpFr!!7V9R${IjivfmHBRGP&SOf^*sS5w!Lh+d!+S>K3C`pIS{n;R zcB?q(qJ|DuTO8-Ozw)65j0dU*v4flf0)0n3Qk{-je>GXG*e!L|>Q#L&Qb*r&53$CX zo$R?tlhrkD8>)zw30VK16?0=M1zq4SkuAo%Zt1Q{l5S zuM*y0FTPYgvt@MPA$^&!TPm~I?z$y-)1)&~SIm4l(`_1Oa$CSJhnWUTR5;9Y!|iPi zb$crfi>JJwlYyqQGu!i>D~20rty&&?85*UY zsF-e@;uhq8D`ZEQMd+GY?kx=Z7^19rQ_c?zIS)Z&OX;D#y=u zrqnr?vkH^4`d%l$y!p!Z?cuy_pC8pe@1Tu6W2uR3btV~pu)gB9I-ow>c|y#D+VIhU zP!EY+rE!#0DVfF3qZ<>nhS1(yotxVu+XCCqb-f?hMOez(fjeq-C|b;q*c06--ratZ zppU_`LzKa*0#12fa_zL6Vy>lJq^nR*6#1Y&{8ac|kt=r}{8s1@KOJpWvDZCm6l>e$ zmf=?&^dh(;aEZ6C(;V{vxu?c2ET8q7VA!MIc>asyyOzgUx0R_051zl)EcX97)F~nb z^3x?(^>odvU1x>RVwDL-vp*$y&QwGb{0nT3>8-|$DUp49n`>+2pJo>b-xX$%Gu~&W z=l}UqU$5C4Noy6A%YrP{Ik|c@`@ai{4bBf(;61~|$ckm~ORa;OHvXcktwB&_QyNyF z%<0d*oSXe&tn6_0!+LRB#Q;uSiSE}fG^(=kfp@wQpIv@4{Wkgzcs01LvOQ%e)Vhc3 zaGYqLiPy%mhCK$9y=S_TQHSEAQX z&pfwOr_0t?OtST}we!>hRGdVk|Gx1B-(A`X-{~3P?Lb__bggzd)4bjOp8JRoEg&*r zLO{LWfEVBOlC9F@nhsl}%GfsO*W&(dL($mV!e>PfmfzEU9F%^&(Dqy7-)W=UICZL_ zazpDF&lh1Qr!1M_nHZli9B(`Elkah>0G+>F@@RZpQ>{-WwM0L!J9A~a-fPL5hq<>u zTQ-^x-sa?J&NIn&SnOpU$Otg8DvkI5X7t^l%ocr@``P5UC;86wBl;ZlSm(OdxzthL;fl>CGZ&@3 zj;XkolST?0dfaQ+J=mSm+cr=#qDn|3O`@G+WeGG?&gk4wB31_-)7&+D9Q@w-F9mPD%*w7G!7@ zYt(TE+SrFRt{HaO9(BJL&>sF^q9A(XWGre!V6#h`nZM3D!Mt(Hc51EU^X!5p@7822 zdNuH(Bdz>Re8Ff{dg~4X2es0?t-s!gVyW-A-5U+jjJi7^G(r-naGM05m|avKL$|T7 zQ~JhE5AE#J>OS25x|Q21=~&sjWb_Kn2zjMSm(DlvHMO&>vTbp!a&`6e_5R?!!OPm+ z-&w_eg4HF{Zw6GoLG>--T6C|VpSO|M55G@a1iwbR!QX+@WAi0vwQngz7N?vp`4okm zjygF>Jc${}3zB-;*j+XjNS(#5@O__K9ZP=Nef zRZ*Vwis=XE%s|#;%CuVv)I`zrJ(G_FJhVL~eJnUScCY8B<#x@MPg@Hs za`tD3=Fy55l@I-R(yY^MGE5|VqgZh=#h$X8mh)Vl{MrI~{Pa93?PO+ul#>)GvPj)@ z4WeWXYQdgD8Xi2;HQctV4ePA#rH&jV5gDPJH}K7#iJ~3q#nK4F&la_I@Hvnh!F{e9 z=JM9*vqOb#mgPzlcf}i>qiTnQWWf=ZfWe3VaqyL9%_`$oAfrOATC3J={Wm5_c4Hn- zf`TT@k4c%ja@vw<@Mn?eli><@7t2-bQklVE4jgVW`Lg2O&qskb>@K=p*ml`6_15#N zdAlmxn$8c{F$`6=8&lln5zP1x|0C%vz@pl^K2FaJ({WrccLR#8h=7d&f{1i?e#`fJc;@OAm^tU{wO8%E|Gz2EQ^d*BCcckbJ)HD; zt#gn}Vb1M)TYKqec460Z?W4vAwGVwCXTOU3^spkZqnUCZ|6yk2^4#xGSjMPlvFY(Q z;^Jfc!wrX4x&&FgB}UL|daLSUO7<3Qc%cum)9c~LM@G+Ay*2%)`ElaUa)<}fEJPMz z8{qvhC~f%i@Y^FC!fJyEze%3Uoz_~ns&TQeV7lpLy%QbB8*WuO{ase&UdM0o?~Lh3 z3};f$vFedU;xcu$b+*$g4|2#yKV85P|L1-dLv&uN-7*}f*&Hx8P&J54us7TW#yV=9 zv9WQk$!}T)tAh6&Ws0^*zo@gVGMr|4CkNdc@oAJ#oO^<6qJHB3G1}-&AsL< z=*#*B8zf~Xi(cf8zJZ^~J&GSyoy@q*$nhu|QL(h0V{#PvtkOAMAL=?vJFb56q~wYz zyb0E$?+sh%`cm^kaLI5&>(`2|FG2Y!&&KAA&bpE9`RrW2-uHJkllrzZlO+{8nb(kE z=*aJ*OXFw6D`O9iRE0VZK^?BBrVF|ZYg%9Z>G=Bd-IbR+o}}e6bLTvDe;J)`_jzMk zWj&|=BIA#!*8G%{k$0n?(a@NoO9L4G3BHfLl^!xjspVbiZoV^hcf-hr z{sv`pZY$B%-uKBMfi{dI!7obVv>UB2*e5#cxp}#VyVKkq+?ri7oC@p%Y^p5Qt25;5 z$j5j(vYWe-RZm|``$}a%4~)b8fGj3AC)Qsse)4ksonhyCj=nrpdg$8G{ks$kwT%WT!d(^-AF z>2J<{cK$XiVN~% zpN-5Ze7No5`kaO*%-1K1R6n28-0c}o-$?jr2wjrHN0+;vj($f2yMty8J>YfPAwc_F zWGNWO9-!w@rN-|Dul3IAqIE9r^y#kc^VPp;a*-k86`?al=OuPBcll#QvC7-5!%}Ng zX8Y2%(dMM}P0MrUvF3-&_gT!d7-s%e)1simUcV>UE5RRbC;K#ODsvgLl*Qo=;j7W5 zI6>Z%($zn#GMx;4_6FaH@Q5u+jGH_&nVs@8Y4${`*umhF&Ks3-_LBbEn&qE`xu36y zjwNOG@0_xW+-rDLbU7#IL}AAN7b5u(8_=4z&K)xeQ zT1*+!oc6=wjb8S}TgvO~>-x6~vMgSPehRNl>*-+aSIu=hADR(YIpIrEVoG}QhRMuv zg6Lhrt*%AdkAj8zng;V9EAqzY+`YB%>h;Tut}1W7dhqipSriK0vp<8&+4sbrmIKZK zet6iSs24HK(YqpwgA;uUou=v%wNlwL*ybNAqP5r^Zc#2hnt=+ ze7~=3ZmX3^u&~Xt$1^P~Gj_^&e9E6BN)lyKTSCrAB*4zWRUXee)61)oe4CQTe!LC( zYrfZ(UAMh6KKtE^=AxdG33bMO_vun%l_twp>9*ge#y>AGBxro#?EtN>w@0Bvv1PP! zJ(0(~Z2HS^;h<+9+LPYZ+_|uGN7u3L&fd5Et$JMJR9Z1>1OG2hNUkXu+G_LfRt%d} zb_X5)I7ysOI$JoOaXe_xu(7giRd1FVh}H_k?8mfrqfL6d`xo?9_Xzr|25b$|Okx

I-IDSp$zkH0*sMUprdRN)+wE7& zn^*TAUWz!m`ry1hLwCI2c4f!ay(dnp?&%l3tM)UPg>SN+KEx(!{=}T=sj0W-6sEqO zaeVUF(Om)O?R+H{7+pQjsx695^A7Jo?5cP{DOVDi@w`ommbH{_Umk4+T>Y#SdLIzkmlT*CQ-10jrW@OPt(*9r5{nf&YQ1o{MujS*qsqo1d*Fw8I()2vzPf-54f@;}Q%4mBP& z0nT9$NA-+ZJK@=sy(u}S`V=?ACUOu0M8CdAr)E&8+jVF~eK>-AYD-t8;j zv2082rg@v*Y!2O?yI=o;`D63qq}IL6aI?AoGsYB7dpfs%{?-K%^Y_jToq2AGf84_0 z(T-yzLn)@s_kLW=%X_rxUf}J_JDyo*p0EDc_@}w6kYOvYatIn495r$5%t_0Wh9#R$ zc{NTq`b)?mkDC^A@qNY@TRKW_6(r|QxpUzv_wwb-->&byhd;TUAMt&2&4um?)6>GW z8p0;palMO;=M~?*!M-EzM;siE`^y}3iqE`jw529NCYID<$`s=)J=>nmZOKj38;hDE zI|}<^j4|eFz74h<55^d12Qmf^CGF)OVCS-@#ZU7_?NPO%imfbGwksJbrJ`E;RdgF` z;xFOK*m2Cerpu^?#*GG34X6h54WAnZ8xJ!vpvKb=vK;xNafLKe?XPom@fdPHczgJm zsOQnD(c|NmBp8nGo79>Vof42TGKn`yFm6Ts*HL(w%zL@TFo*rGn4P7TuKU` zm=l*1mg0HFd^-}U-(P?A$Cv(Se(Y=h((A~G3877oWe#x~G4&L&4UXuVt4W}k&#^Aj zU8q}(R~TM4IB%c2(VqE-YT~aV~%Q zhQw8&51maEGFDkP2tIv2`SMBD#ydN2Gae*8tt>MCy|JB54I+#z4|zNr)-Y;yf^Pio z36sak;$KAyhUz)*QTOxL>Az@9E4fh+|K#Cahij)U?YfwG^~RmJ+`4zEC1y=8^^ftt zs)8LC__Yl`5q&SNEbei1;qZchVV<{~8f`o+cnTg)nx5~ruS)o~=!5TveP7+nDr+M< zWCMJoJH{JLIw+-dLtZ3dsA{z`cGPz^1nJ{uE%}* zH;O^}u%@8*dvCoue0)c4hWF-oo9nk++CF#B_(M6TV{dGIdhOeT&QffyyG{I;nbQ|k zFH$ZME?M-{~%Nz56yD={wq(a7t;jqcwqJn=50t<71Ks8-q7|^CK)Tis?V8dsY|I>DW%4ppp7`s@Tsv2Z8mEte~%E8 zt%aSti>;^Ge6TZcGK1Yb3;c%$9}JBP+Y-897&|c8pW)l-&GJt2#)fcxU;5JgoBaBG zGl%4RyLqR2U-hZ#6SR#fExgMC|J@JkU9sHE!nQkmRM{tOv$lh;0wO?XlAQ0srs7 zwrYznu`jD0?6}UjRCj*(#qO)y@7g^Le;-*fwJVMJNN(e(3%C?f5!;mTKJjK^Q-Vnx z8u8iplg%e_H#1xBSjV_VZq>`uz%P`7=dVw^ZY%g(tgY;59n@RRkYQ!gsTylbM;nDh zlk;MCGp{i3AkPWTd#v*nG5BWo9_nqQod)wkV|1!sXMbVu&Mv*q*PW$3iwAxiSeksL zIWYdR3b=Rp>yaC%4|WEdBwR}#l1)=5nQyTAqq}5-**Vw=?33+19o{;2JN^&3+d=L*j6y;|_#>YK73^-ZD1 zl|oDFeD4Ec_o5xgn2haBm=M2X)Sj>{z79?-?OF7k@!PhO6@g!_}u)M}1{b*ZnlNaWwXz_$2w>^o{d<>~qtr-2H*`4cjGV8zqRqm6km)s{M1l zebwrU_KJ=wy~dO6oqb~rQcWr;0W?3;l}v*FO_(8bQExR*wY0Xpr|nQwi0G&zcN-`R z-C{>^BS87%5%&y>X&OaIGujGTn>|KRloPbWaDK{`nZy{wpfaX|@|YQY5_37nN01>b zl(woZEyvkBvES@e;j+rz#`BEVdY{T6biX5hB0qnhGWYL}bentTP3pJG>&gJt74^RlUIcAHvh$e=YoVmM+3(Ossq}*uG(HC%M3?X`MjNc-Q{R` zrt|JSd-C@?9Nl|n_0_? zAkf3%p2UUry>&(D^8BbA?^}sic3f(`l6X5Tcj)`0e<-~koZ;#{u0g^3qio{mk3BjT zNq9Y46PY;dtGA5#-RAqwkJr6=^&#fh&c@1tyR4Ps z$yQTcU;0Id{1x1?f7rWZ(irFcwGO2`d;-* zRG-zM>Yd%UvbU=L6r~=~*IaXS_1hDAF5F@Gx1l@SX2P6^5UoNJd7B}F(a<6cANQzQ zo$7{E+5Qcyo>pJe_O9=}p`+;v)&pKCwuYq1bn*kTd9q>B-I4-nseGYwq&h);Q}tR= zFJGbb<5KgE94gO@Ffd;k$d%`#D)xVgHcRhufui6J1}Azfn2Y zeu7VSu=$8x5ziv#g^NbK30V|4!^h3Vz*0x-GfHgiF2O!Mc;ENYy!gb=k-xT-k1SvO z`+Rj}+Y5tXoQvc&*e|ugDbMYx+g_Jhj{UY1tQ@pcWcm0_jtlj;o?TC3hjIJZj=av> z-A8&)_njGdsTXgULn&i?K++^L)W5U|+6~I>(siN|tQ$@28i2jq0Fng(sb-e3Z?(xXGd5DXjr+>KLNuPL+Jx+w}cZ+y!kZPi=g`7Y(W%i-$K4|2bk{M05C%@PosfL#_`!>VDg7BUi6u zVsX;L11Iu!hi-4%-o9tc(X`8wtjRAnzujN(;sdV?>CGbV``(-Iea@ov!wXlWo2Q+c zxo}EP!nCMAfe&5$)&FsS^wR&ve>8Y0$x%Njxp)4-Vf3faM-L z?RQyrDSO3X$ZXoSu9iQU1xM~SpU~|$+57N-?diI^Px6127}lI@uxVV^G^{6$g_vy~ zx-4^#zXh1`_yU=+}{w}SloxUeAqVE)Mh;U~KvGb`RS z+~^IWqG+>fp5xIWF2h=fXN0c`3lF^Qz1!K}#?EZ1JXrXQxqC3Vnf!hGi+e%un^$kn z<2GW|aNepSj z-ePfA6RjGhI4ip(ohXfv93?&QEZ!yhFyl9aTYI;5J9qJWWdm#UKY)7mXhUDaNk->P zOlb+s3eFK^0+A#!R%EMV%%)l}EMHj+T70zJZoN-;-sY?A6Fc1giQN_31YL;bd##J= zj;u`lM$|@36vp6bXtIFh@8&+{d}q6H7IV!6OR*@CTxz8pqup$IP1kLA(<$CP)BA+) z&48hSO@U^CD*^_5GkxB9t@QZh+UaEMAktCIXDPjxxc3B2%Gu!qP#3Qi2S7m_Bl81E|(QIy+2iWz3}M!RiFF6+5Jkb`q*sQA3*a)EtCPeO6R>^ zk9@NO*g+A&V}~UV8xtf5DDXP%m|~VqlrcW)U+&u9LT_5wFsjz6Lj0|&;OOhCuOkZ$ zzRRn=wO8o1QlByNxXZDN5_@g2ZkqF9Pnw^P|Jxy>-FMg*TNtXPGBH_$p5};XzxBp; zWwiXMpDhc|LtA9tMX+1#H!;4;{vXKfroR|>9+Cdsd;r)dwEQO$>&f3>(^Io9fo z)duVJ)`%YcUO5{YoWKtyk8`O=QC*L&VwS5wcj6MO?rTS{|+3sh+P5wJ_6#+8em^xUKNY^OpJy^`7i~##8IwPxznj!b7;$00V)EDmW~)az76%EJ;0rew4YK5q4@ zUjA#%57%!M--sXb(lg};{(h@}&|#?e!Sp`jA)jUG(*S8ezdzM~(08Nv zaCaa3`&vgbhFxS3)bX`ub?KSUUyGRU&wiTtt+*_?YDT@H`Dg32PJX|Y$zJYn5;2Q) zkb9c@e)g4kvs@c&Z7g=HD6;kBTYM*Sol{0XXzVwb-d)i0y5UbF?siZsc1l=k4%9V0>Y#C@na=AkOC&Uu}Pc%j9rgVVw zVT*J=_IsR`xLSKCz4Uw@Lsnkqfw_mf40Dn>ytiZ8YIJ<7J7&AoKNL&lWfHY`EcuPN zg-N*MsQq1;zjO0RIG2_7kn>{ICuYUIT25_d#q%GxzfLI?HiR2Q3K@2j0_KG`k1UIH z8SydXLQr+UbibM2>s;sCb(ytDD1r^9Df&J=y4IA&s=C(Nf?84C%=)8^neEpGix?il zSxUtGfcYNK4JaU{5n%ArPFa}DNfgO{MGMetYj3HKts1O2`TI*n8O&d-sjYoZUzx#I zS~Itb7^}K%X<{Gae9mpqUFxayq($c%AXm zxP{vHm^7q=d!?1xQ9F=Yg3wq2TdzU~A2WZlgI#JE+H<5?TJxo1Y1#79`z2dTJb#V-ZnIL_w>!1C+;hL{vC+%RThH6kgXwIbTcZ4nzhurfqW0hIB0HNq%sVf4c(pxk z%=%mU1OK!ZuKwJwsSUUKB20Y*?}*`~NL(hik!#fbW|;1X!v)vlZev{ zf}e~bMs0l~JEL2b&10JCnrJQgt#0l2yJGs@=$$o+qRwYT@V*O+m6g_=j`6N}ZZBPI z9O<@KtwJsA%wQc){aX1!79zPx%tIMGj5QCmneWp}86Ipy?i#)iG8$h`JR~nmtYq(H zaQsFllx>zCl?KaVW#?h_>WSQ4u}K~;nP~%L-@2}rcK3FoBcgM#Yf{guz6FEjhAPto9AoSc zX(gYbUaehWuCv@@H62#&KH9Q%x#nEu8)7>D61~Q#vmfuOYrz};)=sR|uhVNlni^Ub zwg+@A>GLyirk&(?;&Ry+^-{})x^Ua6HWF)r#V++yd4za^@VCI6dx^oI-ZvaNFu$AI zE^WQtV%6^5eQRKpQ7~;JYbmV!2NSQzcxkHqkmo#xu08;MxiarF}m+;*?yAD2eAl^!vkPra6SS9{;|HuqlbdEU+1 z3ANYgep%RPd8$qFv66DpPvJXEg;G%(avv14&hb&M8zb9bPkZ{Gk}s^nr}>p|x_@oO zkJ@#0Q>st=zE^5lmQ zf~Le&(O1D=W)Y=Z|4zT4XMN|14(E==oqe6<-M4$Q2Ob#O(LS;$f-ORtoxdb zbcHh1bTV@}doNeTcSdrsU{Q?JT6si+n44Jin0K4CsIRD=fLf0ZREw;X>r`w|?3t}l z$f?qB@k26;bR=hxJ4ik8aB(G>Ce9Kc5q}Z26F2ZibS0>V?SS+6Q;|DpDn3c*N)Vz{ zk-cb=s9r3PFH)76g--<&#T}>kijUXMt0T!%X{0;G;)bMO%E<_N#2= zFUg-mLyRq0%hj>RFcwjI`rVs1|Bm{a`2KBS+NWPX*ZdvP;LtR+@muYq+7XRe9mn+N zuS}(BwUeCuav#!DR z|Jp6vX0;D=o$jX?IhvkfU*iqozvErt&gGi&2Lw;BoA_+u7VM*77B_^+qGcH0H%Qd` zJJ8WD9=JJhd2p8AJ^e9;ttNW(R`#Ia8-A61E}0^?P|i?q(|UnsO0H$Qh0yGwQY6X2 zzwsV3gJ_S8XX<72)pv0^CblNE#IzW-E$Oi7xzkTIIBl|qp2K;8R1#06Z&fR_{pL{? z{pS14u4)JsMeZbC0_QLycvkFnbb=CL*gxn#5HJuucwXPpXr{?f*zY`=eT0{YY`|xV zK1i(P@08{0a4p4*Zl=^4Xr`)6l<(wSGNo*}bWr?J+)O5tmqo=Qf?PnhkxAlkIAe8B zI$3r|)+sBL#mSyZO{KUvK*S|R3XAaR!d|=$pNCuH#<-DiqL52m7Lnp%Qh`EGm7-Nx zl~+{L^fv zsa9Xw_ObHv_ufzGAL2gw{n%A8r{-E+aqY9}cU8u9lUnL}TPb%@J(ZqKrPD_@I}b09 z`|c|D1h>U5?T+{D^sQ60Pi0ob1Aa1dmdS3tgT30WlQ=1Sd+ZoNh}ViQlTm~ZO7MJ{4zw*MAx7y2G=r;p4}qxlTkopg8vT2Q zk4&0Px$F(RDd=Ni7AcTEmwi)YtA1-JW~TAJm*_h7XC4K!5G70Q$Wpx+U z(=~nC8uLk(ORT%+%s1RR4;AFU1D0wQ)koC&+6%ti~rqB$xD7Q?uK4dM>U9#@5+F+GyDYmMz zi~*G;idBSVzxi1+hS^m0cO_FPP^3s4$-klm(QV-b+y<21`UN-HE>vD$LetjDu(EHZ zspax&RZ~doW~k-@>OyKx)TTGt^!zenb03oNTB-F)+nsig?SF&KJg_UVn{JESEVG(t zwo$2;EW>B;KG9DbN9tGhhxM-Ny4ilR?QEM_M_Bj4{%87S#uXG-+Gk*Iq%e%wSNI*6 zy9gD(5#J}T6GhksK{U6MHH493Dy6f zS_{93N+rwXt;%B6Vs)9yOKB*pB-?};SQBD{%;LY~_Ok34f2fUyAN20@yY?6L<@LWC zu-CtD7-%w^>O}iw+Q6`6Tk>8Abod5QyqFQ-^d~#J? zRo+%a$%n|gBxaHxF)5x;W|DT|S>!_^4G%`Gc*&;4daFB$rja!}s!mlusZ}@ZZ2VlG zTC?D9>EGJw)s4G4BlPVU&(N(hs#XR%Q}gUp4qqIfI%PSNE+?J59OyP%EVSwb$rLP; zbB*S0xOBjz=SD|y>&2GI&A*!eYs>Da@39!r(@%mu2b(DN^bEEgA|X~wZpjMeljV1% zYsKaSg8fsw*}~ewSa0e`O)@bu%GUSQ+cW5@SE@h4NJKF(-N)R*QS;xUqlCxEi;@_5 zm7+~)2AX?p)ns{yY>Z?VNs8QsIxL$X$eGWmphZ!Nj8lO&HOH7|vee`oC5WVV@ z%3v%ED?zuS-e@Sg14%~GLFF|8R3GOeAJJ+oUl=8NL4J}bWEnC)o+SCmNY!B;*O=3_+a+cp2G{*#BvdL&214&pqLPM#7S z7deuTM4vncN`^J!6=))L(N!HCcD#L}d@)ZOMHoxR-?hkU1pE{k1B0PEA~llBELw`isYeVv1?cujA@4Otx!zd6iS54a4*aYbwFP7MSLx<8<-2B zoW($KxDI`T?E)v{4EhT#!p7r8LSIpYI9@tQhA0**ek$4&#)^FT3)yVhe3_A~PkL5* zOhS>&Bu@|?!etnSJ{Mf$ui>yx08&*E|z z;nm^=;$z}uu`Bsd6d*c9oWdQ^0q$qIvGI@oSDmxlGFo*l@0;&54{sV-FRihw5>&0I zzSO{Nm-THkddh4PWC|~f4Ix)OYc93AXLH#8ox^^|Z;o<@KAVG6q3<>GA13)3;}^(ZGfBfU%pKg1!~LA)kv0$pZ0uvXxjS z}CVrZ*_HM$ZjC19{Qcz{_Z&NhEcl=`)6smCgCX3qd`EN6Gt=RQVjm zTg61hZF#D^S9(rLllqCj61VZENHMRSeTezdbP>&kx`|>z=>%FCmomp>J+Qnk(fsJ= zn9JB3xRLxG!BOM_vJLS=xyv2X4bsPA+>A>jg8FITpw^3mGOrgyF*u@b8@U zy!i+Pn~0wg786X;SBy*Sq@!gk-xabr=Od0mrW%h!&HV#G#UO z=@03B=^WWs*<{%;`EvOTB~P^g)H0jY42_kWCAel<$6PCic_zL7PcRACV`d&Y*udZuC$F=syZChG@G-o$d z)^cm+SAVJbTOZhZxw}bkCiNEUD}O0wO{9pUIWkm!N*=6Os)z#pxOT;Uxj?2T!9_`U8q&-=!%1Z=U_1bd)>Z0eN~MY1AaJSZDlauxvs$ClR)C)D z3H5AMx)M>Gkr&9kHNDn7Ii1e!_RY@q`8B$l{2Fon-KLoxlKyf7XR4C4Y z+F=fE4xtXcw*I<<7E?9Gifxi{A_a~J4zmxMcALB~NY`^8xY1|ZOY3>w?bz+v^SpQZ zz)1ZVqh*xsrl!mZ>C>6f~o8N(CphwUH=x`J`6MPOYkJHU|W%Jp~*{6WsBL-f~ ze?U!%1l8X@{-B^5jl&~_)`SbOf%ryTC4LZ}i4LMw*p1g~hX9 zUI~AsAQriggreurJJ@4fCd>!r;AYWO@qGzRVk)hdY?Jm%OQg242woT2WJgrR*Q)RlG%zy>IG&U=C+nBt1Xr#<}|Io`mN%btXDEd>?R7tcM8PZ zbIft3`qT_#*z2gDskeL3b&xrDYH)#`z5(Cxnb9PZKa|dtbgjZ#*{_I{F7$I#v>J#}FWmZ2^wiKE`@x4zrxK5v+>`9G{as4d|LjfChLX zuwqEiz-|GB_XtoSZ{}?VW{?-hfU_6aQkASQ_BYmOwv>GnG!~7(ck6)~^>k1)AA=l3 zw_vyNKw&EJg%~P|5b4A0Jxb=0YRH|Zl9A*U=#2~|-U&PKx%eE6iVi_Q{~O-lg4Y79 zA%eS{mB=E@$xmd2cn3uAaxn%Y{z<%5 zk|^<(G)Q(z&Pl>07h%)~$tIF1K0>m^AIK=k@d&8%Uz6+LYW|SF$dTX=9>Cwmh(D3* z#7UB=lI>t$-I8=kkwhi+hMJ!bnMsKBzC;MMe<3!F|Cn9QD5pK9EH#;HL^nJ(IJYmn z>u;NFt2^Wg`&(akeCp2c)7P_wkz8srNPWSW#nB4(;VjZt+9lUlX*4giJGAlIb((a| zSar6l3Nn&;GE<32Bop=^S$tPuWSKFNX%uRuak3HB=sa+G1xBTYN?^YB8KnYK_NNhI zJliCQ@`ZW=vTz6bd$uXo@#38EiyI2jn8d)P43!3RwoMN^u%bU54(MVrFSJQW!rU0$bl>UkSi?Na! z4ClQjLcd@pXB6m!&*U8ib@G)!rfC3m{Ar*%KMqvFp^)Pz@)AK~d?xUx*xa9NlJkR| z%Wems5(Q+YRGv4mfKafb;YdAl7@dq6Ds^(b$eDaC8YeOk4HAzD zf6;Y#ZcB(ZqLQ!>O%wgA3BHH|$erX>GFhB0_L4Y(ZT*%!mH0{vB@F2b$yiw7Iw^7! zu0$hYH>ir$O(#vqQRkSL80G1I8Sw0*_V{);cII{EcGLSR`X3Ey^=%Eqj8aX;QGMw@ zneR9bf~TlVXeQbz#-%dZN*N!b)pEI~+)^P>WXeCvtfhOzgQ9E1JiHSH)(78^w}Eq( zJ(|U5Va!+{B0A82o4yAA=3?qsAeMj>3Nk-w*-hZ*qb7rT77KKaPk$!<-pGwu{P%gTi8b6=s7@ z75MYBxwpVhwzA$a9hh}MY5YkaOMgzkL>JOgMmjx?;lt>o4~I%@9`hjUF)J3Ra-opZ zZ36n49``Xf0C-{laR<4xKx4j&n+*&uXBfE_(2xH|_ArHAP&v+xgCH1-^gMdu?pvKsgwzu_Hnz}{SecD9F;%P|86SvIi2W&%@d z5pNN&7K*{*b^(p!l7NnE1zq|&(CrUF?|^qYi+STGaTBmJF0qu*h&l0v zBxEOfFzXV@6mbQ)8hX&rC8)Gs`a>2bXDe(KBNZWvNJXQ(T}n#Eki|p+{uF&F(1UC* zgk?&%q$C*?8JyC)GSJnZH85#FZ*ct}Q;(^~(0`zBXL#G_pz&J@-Emqf2~puS zbUPjj?g%vKQ{+87x#jqNJO+=346+L{h^>&tIRF`AIxr|kAWGP^%!fF!8P+C4u>HUj zu)&65^RTCA9GZY^5d`sv^MbfbI5n(utSQVFz})mL;{Op2M{RUBPz5A^~9FLmpk4As~s1xYV0lsyGc__GFGfm&H2)J?q^9CF~e}iXspl zR{)0~7qh`9V+XM!)CT$xchRS4GFZZG^ddS8{eY;^(a2}S7N`_z#2XkVA;@uLG%^iY zfutiVkugXdau{g@ridqeFAcGW@0>%lNGUv56wx5R;5)039>gBruN3vhQsD_a!hXRn z*aKiCq_7SjDa-|*OcE1`Y@rDuBF+feM6Ph7@Cj}xoQ$VJuTY0e@CNK1b_e6*`ymT1 z#CW(I#&S762Y-x53yp-cz{a9LNzO=^j|U3_g%YAl=mPQeE3ro;B*&2#$vtE_=_IDZ z374IsAkiXXv#!&;mWgpWni3hVcjo*27m|M9knt0oCt2hs*I`XRt;C1@ktLD>CmmY4y27AkYEoc*X0$l?VVZ;e|x3$C1Z83=z&U|wWG?3&H>2WsL5ASRvyufzg|;V9@` z@i-@d$T$x8jw~*Z8wnZ6dZX+Wt-0ZSbN9GNT7+e$$0z)OL=0Xoez;DTL& zKC+Ns%!}vW;L(9wk_FG`IQ+Mn7XbXbL5NDBg0F&FsH)?UI9QDfLARl`V0|U zZOQOc&w#z*1HTc1&WAad22ZROwZlBHF024NLLoK@pM(d4jfH?E_TX;NxtRkV?L7V$ zvM+aG71-7+;btL6xL3#%P7s1dj4%pn(LcmV;s#jkUdSf%g~7s!_yMRXXrK};2n;9a`HvtG-~;jIQz(P|*ecp-GSqxW!c^AReN4eY6FK%?0M zq>&(?Lk0s&bP_OG`AkO!!gvL|;orajPG*!b_{{^(&7X72`9cIaAW%6+5clUEdXnJ4z+{{>WfZ9 zFQYfm5l~(ALnLT|d_oTi0VWOxjI}cUNa!}*;1OW!mw|!O_`i3X0X}IB5NUP-!N&<1 z2IF)H*$y+^2mDzh__9?%&G7+>4{(JbTmA%j`7s##MgPl5{!w(M!S9~{dQTg#A83yW zyuGlet%CEEvyQWsoyk7HwqS1qc5E%w!?W2>*h_#sn#DN-F>)kSgT6pCIto-Pd+` zwE|xPHsgvv$4+BDm=vR7Ti_%`9Mliz;3Wq?eHUsyFO-JDsW`L_a_l?UZRqM8z&mgc z@Hv}>kA+`_IwFFQ5t0AP&)UEXEfbysoB9crM;sOdezhKKFaw_NE$Hyx1p-VDWO4uiv?pBVE@7vm~Xb2J9ZCd zV<~bJ>4B?@2g2D!pf6nkw&y6`d)^)3a7Od{c)%$Ft60w;0Ys@Z{sj2Et3VqQ0vm2D zaIpq}!t@dDQV4a}aUd{h1OxEW3Kjs5X*k%@Yp{-!JUZ_t*Pi!;>&!jH{R-?Nv=h+JI0r9=`X5D*;|n4pNGh@PRS3c3rwfoi1^ECIUMP^c2K zpz`yDd+ru|K@3p`$TQ^lJDdZ)=8dpc7)gvGSfX*n1fp1|1Miat`O|sGQq*954`6nV zfjr>|QUbHG5MiLvXaXt&-**r*!VB18wp32BUyrf4803{Oa2hvMj*z{fae(nJH$iSn^+&1 z1x!=s3Pu=nJ7YQXB6LIML7n8rrm#1%Z?QYrL7W@VH_3sha~*iPgWM>{dw0XQ34yJ( z81m8pApRW&qGBv~pm<<-JrK~4e!(`#GiYcx;sCKP3{IJ?1aBS(XP#`(m%x1Tfe4WR zUf~~K&>5Jj6+mP97YiN1_JKafBcaaE0`8?2W`__gMg{ZaA9HcRKUx_0D>c|76%>0f zf~_;bSN-8J_#1f|o*S@jGr_L>fwXlTX2CkR#w?&7ZU^$(cHoJv13uP2!qydFeU0U3 z!K^R`CX^*No6`lnWG~KJwiR%v+My4y6bMukfPGBDeOvLi^EUH(c^$kS{$I!lro*$n z1XtE1utOHWd!7Rxrq4f{foq%!_n!bUb}bO&7J)~0gn##ee&k`nLxBxaDUcy=fj!qR z_z0Ck6Z8USY%~Jr520sZ4>9r%c%yFc zMs<)2^6}gMi;m|ZD^y|vu){E@D^Re)!;sJULcSt`{&yn$ITd{A6Ql)+Ml}#O-b2Kt zVxC@g8w2IYyj9mODgL9jhMtISLjBXzqhBdz-lxyes?^;BBUXt=Xa%APeY&YZ!qH z5lrW=gKTImHv_okcOb{}VEtk~WtcJ&=w9^2bQwbf_1GC!0edfJB=szX&2|G4C~a*N0pq7{NX8)d!ZhmL~!~@(^f^dXOLQhWd02auGTJ_W#TH zZ=)&ba(I4Q!3M{m2-*WR*9G7u4*BOhz)Gfp?>Yga3f)kc5xc;SKJu?a1$hE0gLKII zrUHj|5xo9UGXJeHSHS1YfShq0c*v7*Mb7X<2B13l&E3ll`5^QR)`N9bLgxDK zr^Dg5{xPC~=?UD$8T@#lA?}2k;>v#kUhNC`a|`Y!&PnLT593?~mU|>rL@v;yoeG}x z%K!Sa|K3LfpMMb|>0zjV?cg2`2^NEe5zx8lg9xwyUQO_cJ9(|(hj;K~yqEv1o4*>m zYYkvc_rM-5A}G`hw&0ysf;DVMQ_)K>6JLN$Hp0`;0|NAJVD!BNU;U5G`j6{t3eTt! zqDcZ&u+7Ls)CuM=1{og;F+2!kVBgSbXbfr!@2P~k>K^#FILKwa!P0^M0>0)2^jKFw z4N(NvOT#8&YRnouWDG?8F32WtL#0mvD?SJ|d=B$~Zi6w@q1D2xgb{R0nB-eg7->an z$giSoSih{s5>Nzr$QMIh=D{5bIo(%|4&v`}_IQ}1|8g%U$aH=QguqZt20vSe42SDd z{i|bO&ix-t=K&VgwY6c5iAtF{Gp9@gO)P+#reaBQ6Q!6cB5H1815MEYnkphDH$}yg zV%Ibk(NqhXu3|}UtY~sm1T1MPmNZc`&4T>zclaNkfnnyHefC~`t-aRTN0APfai{5j z*tgYq%y`w?*ZYwt#nU&oGUhP3u@A+5<9WtA)9^xjyMSOBv=9eGHrm_a>0)%s8EdNf z2j|n%OU?fx^5K3gzT1!-orn@)Ct}S_Mbgga9L{QzuQXPo)|5>d3NoMC>*y45|UbS0QBL^rdG1@>~03WvdD2~=5v zPK_W5$C8sW!@tmf6KC7s!#R_0;-|)P`g@-Fv$+bnI1D{@$qJ(7hvH*oIJ?kxTE}Lr zg^}pCTBQ7Y-T;FSc}84%wo`?(P+_3wC;4c zp{tX`Z=K@1fRi<+!!rx9W*1smM%E>y^v`CL)rxmD>@9h%!{kKGCVrNHkGmXc`~_#i z>tx|wP*(=rx)?7c0bLp6&@%)Hx&}Eo0eKw*hepucO|TpC;GzlWlnq!^ZJi!?&8OL0 z7DaanY$qPI9?g6an=cm+xY9YyyDH}g&ddDBX>k5_pdGxE@o3#)fzNrpgKTnwuiz{E ziR|2p_q>D8YXeu{W6*MpOxr($tAkBL8KDEAYr{{6zYF)kTbUPmF0vzXZQRnx;K-(M zi|~JfwOHph%rgy~l$y7}&3|G;zvy3zMA+%S9s5iXhPhZwvb3_X&EkMr4X2FGM`taA zqAL8qaH7;N@PBK5J~OWH-NAm?KUkB`dTq|s9A$jLu1z2O6)*CxKj(-J#k-uxxbhN{ z@h|3bzUWje$`1I7V|i7ZpSl!KMf@aSx3=%MTRZ=?E8IxHD73)c!R^?*+lda%CI;Fv z_z5=QHX>@LkS`wlBp5u6=eq_;vJr_=4mX6640Tu%nOJTkpzu;Kkzv09wHnOeDJ#g% zPPLguXh>Y)I0@=x*>3*a6?4p zvhc^@y6`QLxe+riCe9bvB<=(elwZjO9KufAF>rs4S>=Dg{~xkse(?48t@BMs7Oo}Q zR&Q0?=j>8v5pwWmB09a0&~xMy*vqki`Vc*M-}koB-1x}5&C}P@*^^70q%8KC*ci`U zo_54#{X}8j*#7MLxa!$FcslQfJY19 z!CB;P%_d6FF7#<|2fo&@;EBMcz|(m34zXNvL%_i)~vyL zSH#D0a-6^I5zdd;;w`bY9)jZP@mfWfw-U9{e$Wu}E2!;#w0IwM`4+P`cEbw1>m5k3 zi&%f_h}`c$nqFjP=kZ&*B3-hrQtXB_tkz`cw+?%T3xoEwOv zEJr?0#HZMR&)ot)r5*A-1h)+!+R)v;h{e1VOG78gOWw*-2)pMlCnGm@az^n*Ub*gb zpL5FGeTS_`w;zGvop^F~pwxNEnTCg%3LUQ?^8ABSPds5g^t;tL;*4`bF1&+KmxJtU z6G*`WY#(UBE|>#Vv1)|P>6a6RR8*_V8P8 zXS>~jbBarmggddn{@~Q%LF5J9=KI_*jimh`>K9wQ?4 z408K#r2Y4SV!Y#}oQYfxb$F0U6Oq={P{IH+4j;DMoQ9-bNKB#=XT85+pTu&P-!hvR zS}$U&bFd>1A;J1u_n1fgAEJL>#R7bqc*%d!0-q5lxtl0RsW}3gZDn6)zhFOr)wUkr zyc?e6X|(7LwCNL^WxdY2%-&)CiF|(wsXLZeC;a;!M1KD;51}uwhgO!5-*}#=_Jiyu zJOSm+WZ&Rh&LQ6hJQJOD_9lBA9z=>uK}UeMqLw<{Jq5jU0snn3+FR#?hw(Rlw_fE; z?W>X8uOPF(z>eKd#G)GdU&FiZta=(Wxe;FGv~c2%)kxO)><@L~j`zXA7Ou^*nqa*g zH&3Hymax8Fj60rZ$YM;w;~fFlE+eK^h+ZF!>>Ny%)*<|zm8@e5l-&)lX9TN%-hRg( z;N0W%2#gFY+=#PDCiuE@x4!S@2o0>2<5zeh&e#Br_*Y=pW?fd4q~_7iJQhGM7S zRi49>c^yCe9H(M$4UG(cL}c)P;in>>5pBGkJ&u{7YlFRl&5`8~VKqn4*JFY68gn3; zVF5ALJXVa)kF|%bkN=iR&B;!n*9D1_VI5>QqP3ah|H{|V_q%bo@eA?fM~vUl(^ruF z{_Mh~x z@OLpyB5ds#1Gmma-b}_uF7>~~4wBE;+_=wJWW3@n^E~XG>RA-q z+cVfR%CpjQv-f-NyGBR$lb-T-AYxNz<`MHc1oZ9#dgHBQMC~>ruSRmJ`ky}2cZ2UH z-}}B>iOudZ4`87+!FyPb9bh>V;GUJp^;jr17wYMShu6Nehy@)2%6Q@Z==7y{-aN-_h?yW?mP9W!7|2d*8ZSicX?M3YTO8&@e9cp((!=|HOi{ZTz zJcm^Nev8KW*zQQwr6V#al^ww0SQZ{TZQN{y(52xSk!KGdbGXU{>H9D0$1`= zi0sMW>ICe8X+-R`m(zruz9j7CBUm(Rv1ekDsTa*wjMxJ^c0W8i5*a-Rd2yRL%)FfU zFJNhHa<7g1COiuy$rkKDY)xNxGRU4?iqI5=-0S2Uc3fw-;E;ELZL_MEZanV` zUCz56?R1kf0(x76mde6UOLI<=i`ff{d7Zn{y}!vBRdXSxxPodR=?3f+!UuKR$>qnbk`FC;m zE7*>k{db$u=C#Py>1ddvNCwe(9q$&JDb{^v(7MqaZ{Cl`{slJcTC`ET`7jdrWit~A z*aWVKw|axQLNHhbz3c>66VSwKi93$4msrc8yDBtp4IF+N%l0tuP7+sq!WjdPEQPD{ zz{*f?)ecU5QhQUJnM=Z5UIBO@f3tE4gmFTv%)>YPz=6}t8SfNwQx6p@v_;D@KosBNeB1o7D zG*}IDD1!^9;}hIKY;%yc3*7g|+b#m@6L`&Kgt=H(75Fw^n(eJUe80o|#q3MITOzdD z1W(Ce+z47S9Xt32Yl!ukr5x7)meqPY5sPvP^uGaXYoha*^CbRB7|;F!J0cgbMs~P+ zI1`YOV~D9_!rPVB7FYl58tHW0j-3luLxwj`-G3- zo4$li@C0-^)6J^LKrU_P{Sx+R&aq$fRiHh4mTiJ$Mg~f;C#umx^YF7$fZ0l(kxMk8 zn7y9mc4x91PNCs;LsMsw>jQWlVApvp@w$0<3kDkdOR^j~Az8NY{y5P^MK?ddXS#v- zM+&q-!wF~5OEbW54%XxZIIuUmrx?0RLO*AM!`V=>?75E}+5P3bFNdNRIxiC0 zyBWAo;`^VF`B6wJ#d`OW4f-5%Y!uebEOyvFM?TGD|6~b~h|&E2AiCvyG{whAty!*| z`-Hs#ll-#l@L^{Xi+(Klle^peWAH{Y(C!Z18#)(!CA5TySs>Uv7zoJvtOUnZ_9Uq5 zA$*%kIIGCs&fZ}yJh>Jt_daW-*~W}AfAweiAMl>2;xh#ucg zwC`yo*R{TDh@srbRreAx{K{WV9K~y9kT-6IGlV7d&L*QOu5yK zOo?pd+$k_t1GWaZc6~ayIm&1iNWyHag*qf;F&eWBiYvqmoQ(XugdLHCREk5M##tMA z#lqV|(O5&7V=gpu1lo##?RfhFl3hMu85U3hdo;b+Pn~D~X1{Dd;4EY}(!=w~P$9xt z!;TA7Ow@N89`96qnf2I-r;tgL!S+&i^cOgfvlBanXx32lNGf!&-);jpw*)7L?J6YJ zO1vPy^Nam9IXMoT8HIh@+o`~YTkee5E~+7&j(ehBq<+7_6`i_$UsJDnf$p!sBjfAH?sY-T*x@*!9>;f&Wt0 zoC!_mUQXrJYVz({XItjYyAbV&kh>`CL1I%zDY` z=v?P?cQxk`A_v9f7VhGXF^rLk#Y)byD;>+g*#vm&Ju*>}_(buN8aVc#nL$jf1a0@e zb=5;)Nbo!JGWptp5lpk z8~8-Sc=|4U>7)3nU!ZS#fIa*Kyw(L^Y(BnrDLS(pnWcT2Ib1ylSQYThVy>G8Wxs)j z@%iwOcqtW( z9fj)}$WUM4#$<+L$+m~%N}yjw3qx4C8~MrS>eX&Mya*d=EOw+1TcZbeH(*&Db3J&C zGlB0`5vSCC`v$0`4t?E}wRQwnmw3WH;tW4qA7f)|Lx;!$y39U@?zjM#1X+XfE}pVq z0vdCH(ik{4ogMp3BE@-7O+LPkGN!AMNZLnIG-VlZ6K;<{F*SByvSRLZyzuZCeB*rN zs&ec?&_z8QpMmx+fKs}+S&~KIrmF)coPF5#!?1M1+%q2xHZV>I>5#~M!?~gdW2DmxDx{&#RQ5E^gk)Qoiqo=kTOG%Km~Kip$tl z&L*#<3)cqGvXwxh811_oh^29DA)_Vp8V1%2kzZ5brh86y#kEvSlA$XZ8QXEsA}jo#1f*`u0iqaW0Z*HhLx3>P`kjDr4?L zyUH4xi1zldU)Pm5(l9?lFSDYJppGVH`X$hzflVYG9`{@ec3{?h)?e$n27 zFTWhQQUw<2BSN6hj+wh~8z>CB9hRhQ9a4GU87mN)9bJ1Y7g?$?_)}H8=9JoG+ z>^uT?E+UEgIdgfxfjhDpc>*J35FL90X*-N7JMiCBwB#!0Hy4V?vTd|U3#S8eOTJ_t zly#bC?&5WZx<+N2$AjHZ(Eyv_v_iC?K31oXL&B2jYfL( zwl~4gr@1-=x12;u9dVp=ej#?+40o4x zDDRK(`7Rf;tHFduI)ZJNfTr4MHNhSjfW_5dEkz<%vGx*HkbvYlO-w?zd`G^O?N8=C zf2H3<;XADE(1BtmX;6EPq&&2?6l#q{8Z|}oox%Fv$4a+AAJeU58iTGbfj-*UKVy%Ez?x$l%s7jAq@($k z!3~#K_b#;IVxYKYpX^fD~xCyLtC6KBFFI{=+Fur++u_vJu+F`HN z0NMTUU>cTK9G21>#3lwIx#tnZ`5ifX5{j6QRYX1lF;Wj0NoR~qo;LyP#ld&-Fw3EW z3bqmN_P|o?_rV7`-$Z2p>n9cY>a$^UP9y>Rp?1 zKi-1ku_vJLiR7G?ap!#SJb~wm2MSnQG5V_zD5pX{nfz2k)v@**yph$+<|vqW56!Y0 ztfWFgslatC(314u$SViPL^Gzmkr;TSE7+Zb6(bss=KtY*-Va*Z0smImE5M|(U(%U# z9(O7CWfb^GbookH%LNu)xW56qOlPef89k3N+ar-QelmZ1u^0X?`)ag!cPOtGNQujG zz{5ml)PYa3!NM3|ycwFv0o(JTr7UPB;?m$5=slj9hFMVx5+jY-lZ)Z%=^$4m^ZeOB z`6QlJ0TG&0Smy(=xhFCb{sHUm%~QH?MKrW>1WBL7INHhH1!mVy4J8vM*h z-meBj?^-uO+Yj1T@_Rc}BWrKJJDRdQBg|(f6p@QeDFq8_iO4j7(|On$tD&;ZT-n{F zqkeGP1t3WEFe9I4PV&qn)Ed`u=RC$;%}ZWHG;&YgU^IDPDZK9o6xxBMzP#GO)0NyI zNiq=&W1!vK{*nxlV^DD-x~elAD2xVyxOgaxEg{`4eH%fZr}Jq)#<<>|!SgPGksuIJ zzF!z!Bw2{G02}E*qK>F;3ae3X7gdQS@K^AhuxD>)?+(m)Gl&Hm`MxUXa5GRw1<|uGKP31 zlaaeZts18{Fo^*Jk_eJ%0U$S-Ph^uEv<5R)6l2$0Q{k;{$mCk^Ckot$9dR03$Y3qX zW^BikhuLdf2xTzFIC~9xIGQT35_mriSaw8;HDO(f#Ej#vA;3_4unUaK&bS1Ywfk5I zhDO8vUHBvxj@t=eDjHD2y(5sVg7R^mB|aU`oDx}2Kkf;j5fkt>>cG}qpfiLq9QzUb zU3BbrA_wwA%BhKwEtaU?MXqDN(R67BgE@pS)g?2{n9D-Nn*H%ND)$A9Z#;%p_ zO6FZMbBTxJHzQv=x=@WpdhU1S;6-pY1dgPN1gL~qrS{m?Fk8u!d~nnUD5dkcEV8!t zpVoEkX?y}jl<}Q>iY%bq3<-9({Vb4J#avUtUnch!z>ft$Xghx=^M4+r7p1{lcaiNLQDT?rv7Tmg=i zcQ1XL4V`y@Qi*YJ|9oE3UO{^|`gk{UONZWaf$L;oHD|*v8rk4w{El+vU>5U{kJHbcXQ3;P1=k#?aiMLahyP1mq>f~WdpsSoLW|89Z`gCS60U4gh%%%C}0tsq`z*ZUbHkXlAAvA{98K4zGM#<(W z0AEA-FOM09x#lR?i}0=hY2hFjqj)dbGL`Q`TqiFv!c1lLDW`upcP7Kpsy&i+>cV&r zxvy?qqkMnj2RwNcy7M_`@;A747XKHrwhBgA%{3wJPlo#spnntLs#VxLof)ql>P`c` z>C8)1uUN=b);odMaGouzGh|Cg90i{JTz-?46ASk!ZYX;;llNJ0)g#bw2cFU!N^TEb zrnuBm1T}PnvQ(RJhMhv;XFnr}jH!Ef=0#0XEmc?WcHJ(1p@mpq~kLr@;f| zU}L_Ead}VUz`rCz3ip<}PfTUKsf<{Ul)Z>9=*p~y!Jo5`Yj_=Kf|J%UI3XXoaRf-I zj!;==l8bSS+l@J_VNQw*i88e>Qi;qs4aRz4JIkBw?o!}U;J6j=z2Go|#b7e*6n8H*Y}_bCl{Oxll2gq{XtUoUp`OCnE^^;m0l=Stb%jk!~@ z7pvj0ENFEMt!QF%5iu{)?sfhtuW zwBY~c*FIJ!$VmRlQW*xUW`m0wbj2HZ=c(|Ky#HKAugAXIh)z6;+?9WOD;%_&)%C{4 zyB;c$+-QujsGdT3?UGe#ye2TNA`TA$;qlC@8+g3T{?_^f$u$7Hra|G#p+1c*C>unX zD)gaY?K#ld2we$iEi%DvpxMxaF*O6`D}- z9wv3JsD{o_eMC)e$hKEdO=iv z^j1%f^{-GT`pK z^0iKR9yUH=7dPL`cAg47A9*lz*#5vb(|f{e`wv;OgSXK&A;*5ixFPC`=JC+oJdSiV1q~!_UwmxGuY4KOXf19oG^bFqJ z>i#Q>TD1)R;d{+Uv;u)q!3t}Abo%9US)+XqU`JSph#t_ac#2Njcxt0J;Zyj$210+e+Blps%m#U zaZuX_!p|7lQD0wiW%DOIokRD~ku0{=Pl4&?6Q26mg~rcjf4U{?rBLAsXN7UM_eKA^ z&NAEJe9jk)7panxX3H%-$6h0f*B>tt~EB#kp5x37h-o&8KCs@0(QhREBY9@cN3({S8=-vWDjcuec(T3->VFjsPJ z<%8Z2d^OgCp(b%N=rVFs_>@&1yFL1x@3LTB;B)(QaA{0yVkrVaBrwX zoHyQxz+qs0)=*cemWV)su zj64<^9PAZHwZ5k=Y@&6MJi`T6NB^(JpT2(1z({qgfstd@Amdu!aQma+*3h0%LNLSr zxBoxJP2>@+G0#{(IvHe<<=GpliRx?DIX{pIGTf#<5Wk@-m48dD)WE^e522uA_yeAp z=&b0ce4RrxTi0Io!Gqp-pGac&mvz323VbZL%dHL`>dCOA4JAdW%Nq$OY@tU&sxSt-DA8NzP;U?q}$s5 z7P`#%yhYCzCp~Y4W?l71+n=s#8rRYPX3J5RpJ=|sb9wO5_-|T$6sfg;^*j>&bATl?38^17p@l?T`M>8{tgt+W5QUDy_+$xabX0V`I+x&IQA*PPKY8TwxZ_ z@pi0bhStQ5h;JIHavt#oVjH4g^LXq9k6L1^U=^Faest!odfW}e5&VKI5p0-{)p_tIJ5A+V;L8+B@lv(5#s0k)HZ zC#~DalR(gn08k`~A`@1%N${J;3~#{%2wI#eH;3`GJmgsn!eBoP22B>C}@^G$HUV z&`7X4QOlBpu71i)A}=J$nqiv(`fh|@3Uvt#x85Wdu{9YXh0a@{)>KG3!367edJ=Rr z)9lMb_tC#`Qs^G%do$C2hxvqaXE=-Qm;Vd@6WDFO=zG)n&Dg?8Aocc1v~f1syIrh> z&WK=K@D-;cwEhP9i)Z}Q%(I7jiadG0znSkbD$^?bXRY6y60)r`om}eys?LA*N85Jr zuW%XNS_j093+7sv`}g=-o2#u}fsaFd!s|m{2GYnd3s4xtY3upV`??0Q&FJ4>-x%O=q54$$cudzokB_ z9&6wPxtaM^IUL$9_#0U~qXLD2&&Ve|L6664!*_=c1%C+);e>%1krRgT`7HtkIA&;&c$y4kN4X|2@7Byca#+d%AdD_uS=u*VEG5#`^=^sjo2}qaMbfUxSzEry?SE zIfc}mo}+5)eDI?HIo*|cRHu6H`KjAw=R&b6J zwmnu8cA7V{%NU23u0DQys7XEuHFu&{z;-E zAMX&}`V?&KXflS65RpAXrrj8F-u57&exU~JZ{HVG7q=oCZ#vb~Rm6L{lA&-58G>!8 z*4=Q31)Xm2_}fK~?EpRNFxj~`u!)TB<#e`aNw(dK!FQqbpHIST{KH~j<2h0Fox$?U2})05~G|3KgMzBu1!{v+l_@P zv=Z-fG!e7IR0OQC?{#())vqEyJP1~HKv_%38F`K@=hvwbR>zB#KuOif-SF&=LF4<` z>!>5Ecq$!OHbX&E@%IAUHHB)C{!r0)@{6LJV!H^hTy+bI;M9_jGM5Y##ZWwWLlvy# z5Z+1^vD}_ygKzdBz6_KddL0LSP~nU0G<>DizQb*g{;xV)ZW)J{zW9+LsTtO zX-t->Y9UI==}5E>JHH~c%-~LXm}ZlovzvUKHF(-ZXvwpd`t_)1xLdsp&XD)~6dBUD(sL{xY1xO&uXw71kHM*hWa-WVMu(x)1cx1J_V~iUvdqn_ zPjQs}A4SH@HmYmhrC$GWlXrII59fE&8jF^a`c^UZH#9^F| zZLjkUokLzn;%s$N0}qg~sfwIO16hI3oB@2-2vc>HErJ${@Yn^N`MiiQ5xGnR4#$xU zBkA3?k8IlgSO9ODi>b-FKz8c}^DRD!2eQhaewhlHC)xef9-^`)V~BOB$}h#aBH#%e zbdEV!fuBiqD!87?@Q{gN}5Y6sQs zb|s@_9yDJ|u3RR$DgCjFs)z-Y@w_*vVVFS$Um~?5!>k_Ag6K9A%A3dUO7?s+f!A_Y zI|6+%kC?>}dl_p`zO=MN3fXg~7^@fW4)L^J)Gz<;D6cXeKYa?3y{*LYwiB7?Pn?0g z33f)FV+J3SB{SHG5KGCXAIxUzA<|8QZ1!W!=M|{*d8)eA6J!{2X@#3NwvnimDkxXM zO(n!uO3+}-$Qs^FjcyD!pP;#fYRwIFSlbo&5GiE`@>MO#s~pKuiu5|lobsW+3M#AK zqyI-UPG9MRwX_@F@IY@1kR%hSA|F7$bvl)Hsph|_QBnqNwYdN;YmDG+0v~jUv3~^0 zKO(UgyHfNaDivEGQ6|}Yh;FEpmvWftqCw-@hqi^baC*hx^l>@Iy261)swYAs_5y~9 z$f%KI^ZiK%_Ah=9UfweLinZcYjQ8o&-4vew8J+J#3oeAiTbWI$U6fwh5A-;Z5ZP9T zCM*Usqp2Z$f|?lhb~zV(HS{Z|EWJsu$Is|`buV2gwz1MfWV5UPMjPcm2hz|3(~)zD z?8U5Rec4Fm9@MjRqmMx~+30JKaCe(we}S*g_=%2co&5LvPx;?5Z?-NcGjKX_$SUHR zlZgC2Yu`tdZGk?3t(O5PAb+ zg-nD01^O)h8W`2C52DPE|(HDwEt*^XQ~ z15D?kb>W<|$0qwmJItasS4^uU8yO|94&A~gaHJ`T5o7Y%vtiP;lZJ+b1 zQ%VP*S~n+tJ$95T`?``vH-IQ&JkeKn)!dBfoxnwVQ=fv}_gq=EnjO6#smT1qdV%bg zk?0lmd&r}HDTQt`tEgSp&hWSNJbH%yoYzt@^fg-kUh+EIIEK@ljP0wa(|w$72rnW_ zXX8WkrXq7N`r3g~3&7MjK(IFvL=SPlSYn2WtZX5xX@-R~lG*~*y8PRkWwo}3qSLC) zp5`X{&>f|cBG-J{tfl5=h;+*OQ-^`f*$4} zX?jruFpKH{^+uTO=9!+xLQzaw8MOPT!P*5)1g!h5>#hH>@`Ff$3aCMOkY}-m@}Z64 z&|N?JmTV;QyA(avf*j&+un3p%bmcD|X1refRaIRA*)ORsj_R-!`a`|q+-b-ub)8fl zL@Ao#6r45zKG|S?6d9gatbrepypx}8h9vr zCd>JR%-l&l+2&b4@wXSUdoePGW2V95PIToo=QU>!l5~Nqh3Ar$nnitp;noQ74l2#2 zrX(K=vlMAH-Rg>^+rfF*t)}-X*FYiG{WA=5Ne6{LN5!j zSu6N^m@Kb)u;j%iOGDbUL#ls6<-lw()gRnuqh+Zahi3Y?`*;cPttz+D`0)UrV^|u0 zkatpqq}Lv(_Tr=L%fLq?O+=u@otElym1&T`zD_DvRAQZElH=ZiYNH#hF6?WRv%5T% zy}vYj3eaoMr*p|-Qyu(NFjxTo+u82{*+JBv-)~JqJJa_Bt9Bl_luhx5vcT(9>=<%tr$Up;(5Pj{@HcuYsGEecAhd_C?2!rlRwwbL?E9R-O4tv~HnT2SaB*-f zXJ8QV|CIWi-Bj+brXqJ9+_WG2i`W*jA;#*&T1SFqWl3xSCIc*0A;#j9kcW%y*&RJy$KPXkaueyl zF%}!59KE1w$PK{iFcN$fJfym>wNQ@sp|Zf?a`7;G=RMGIvJREmp`4Oj@UffyzpKei zsDLjXvIC+(~Gj71cL*RIcMp0 z(?HB*vRl>Y^K5cJ zz9APw8IGs$W|V_DmAyUX4R1m+c1KQ3$2Ld<&vW=jJL7TK;m5H0=0XXR$mYM`-}qLU9t2Xs$DGSIFinTj!>?Qs!mGafKgcTpSb>*GTECT zxi@2BT|$y|V-9JoM(a%nq7k%36Z~fb>9&k(l|?oJ54?!EDeEQ+DRP=`Wu15D`Z7yB z57l+MIeKasqx_@TQLNNd%20Htc z(OJF}YqFTx&q9;8aW-S2NYYfGIR-L=?)Y+9SPg5Lp|aiwvy&{HFpq2G2_0vKd-!w& zkeB{lg%(w}N>%y90te+s_psNYNty$XmCP|8>QsK$TxMIvs+7yR68JR6j$(n;GUi%_ z#9IxouYxDqW1&r^0;>?4>=KlrjPD-A=E}IcA8#e5flBx4W$;xK z^j0+UE(8LFSb)k3$w9KKw_hjr`1P#)Q0zXe!qvd3fthZ>3i7+XqH6dr2dOlHnMFIw znv^yQqUTl7A!)pd8A)OtMqVi2nphFkTneO1`AoS?sYoH^lSpe8pzX&~=aq-nlkOL# zvail{=b>%&Vp+;JS-fI^s3<%d%nS$ijlE_TB856Ic0c^`Rq~UG5R8W>qn&JMW*Kt2 zko&ZbojkuCpJqC};MQ3{Kw0OR%w{#KsDKJog&ua)`7e=~SMaUmpE~{3LUCQNlXpTF z%J5OO%~2$G1N6EHY#-+S#ff#L&1vNEU}NkNVkVaup4Wjwa4x`+$`o~IdoBXhe17CZ99k>G4C z*G%HRZ=t7k#FExghodf@3$cHcPn8JdhBNC7sHlbgK7G06qtN3I2^kC3zF~E?Z-54U z;Gz$6SO2n&NJ!aG@vNaKqc?>vXSfjn_5M%~rs3Q_0ePANtd!rP8eA`Dm23i=%dq-X zha@{kRzea~Ivrj40=C@@^wUJH9)KmcpF79!3d67J9Mq4w1hE~41CMzwS5@=+r`}P5ntOVv(t$IT`J;kx%BM?PP1M<)!|WHAwLousjWj z#nB%y3`{mMhiOQ!_rT0ro~@ouWF$e0`@miibbpDF756MRdm_t|pluJ4V3CqX({6_BZ{dyh&9YxS=jAZTLW`cu4f7Kv<^u@4lB?dY&~O*gA)4T zuZ4hR9r4uxSY+}|Jj_>_?#hggW&~ALwZ}`@js>Z{#M9vK{lMlZ7V#T!{rhnJ%iO1| zRppnV6edK~q^`}f_e9cVNNXlVVukiEM4fad+AHY-ik%gq5 zTP56af!B6c-T@w%h&4EnS#$>udC=G)-nFO0x9W?fFLp4G<#1R}u#*ODt%UPslTKmI zIv=AGpT|K1@;Z`Pg{pZDk^OoSj5N61a0)N(IQ2=wbO%ODhH@37QGb199c{o1Sq*d~ zm2+I_Rt}X{LNhyDT2qXC7}Bp8>Q|1SDw>8dw|Vg2J~WqXn=n3dDOIVLkascMcM*OW zj;2x;WC;>jxwJjN(v!@%J2={p)f3Clb|_&AP|3$vQ6uWi*_Mx#~|B>vC4PRjLKPE4gQaV&pyCQS$jvYSVZT`(QA^> zPon2q*{U3^MK3ExauitZb8VmHU}QhgKVjWVmCr0@5CaCvU5-~}lr&EwKdN}!fDT_O zi;~C&RW{f#jlHu~#ot{z1AglaPj-ci!^kAn`=~zk3_GHV=$9gugd=5(9)%wjZSDrQ z3$Ejl;ft&*t<4N&m2!fYwBEZ#~Z&-E2J_?bshxxP&-&T38s#2H_ZqyaH z4|qx9lipxLJ#Z_zq7I`r+5&RBkMOnlok3&Ps$1deA)%>YGFT#@};G}}_ zL&(DdXoOk==yN<&pbE^{$j;Y@y$Iha=;YbZ?YH2#oa+nW>d9DsjpqYI19N2}PGjvw z=r(2h(K{a8F9%Ahq*ms!WaNG*HV^no|CVDd$R5x-yzuk{s3Zm1au*b`0$=QUVw#_T zQB@2~V^+niaV0*8>X&|ZF&#@Zu)DJYov(yv=4?6oPt;2(P-^HSz@ z19ItMWb<+OPf{TXid6P%BCt>w#vJCm3^>h)GPSFDk>@JkU-b;C#*E>P46xaT8oPhN zHGR25`IO3V?MPPaNUm-`x2bBh-j$MZXz?O2sVr&b&R0Vp%DPpC`xw^M$^M<$EFq>K z9W@N>?n0Ny&QnE=x`V5pvH)IJhOPX_I4E8{JodvQgQx+$ks1`$MM|FZ;||GERT!$y za6GRP_pkQnv=aTdm{{KvoP@55_EqdLEj5o?>Lsoon&;^Gy$XK32!vDU@Rj7u2E!-W zV>*TO)c#%*@Tcw+r=k5_?oVS!=Z)}0M`9DLu>?l226j-HJ(;TL^g247MxmRN=@2@C z(bfV@)zr=fi;}(@?cX?2^jCWUy&8@oX?h}$;^Ds>aIuUl)G?wS+*I>dvG_7z&?p;Q zI1BKx*8uTCV6HfTdVZ)9Q{KZGw5j@pWU>>n+Dbusug4bcg`KPJMr6)HHSIaW;Xx#N z4E)l-t~(Vxu4E6>A-KvJM;}7^qqA%HnDemn9JrU2TMTz(qYo}YGZnx>m2>NuMHlEk zm$e?jcMTFLuCd3#6aT;)B}n!(?p*+9KgDj!lhDlu);5k$hCrj|(CnSjJ^kGZ^_$sm zQqS{mctQ|qUBxpRyPc_CxFfpsRwynL{_4$B)g3R0yf3l3BWJSsrilONqw!>^i)vHh zoqXo3j_~S!kq;#%*vsKBX=v3sM4+rXaHcw{#xBg`nbm_(*dpQ)mFTjLNdB|LMLW39 zQr-4Wu$%*3s0MTslr4WH7pbrcyv^eI<9Tj(*Xlq6qNAeF6~$=59oS%5?fYTjdBW9plt0#XrqV`v@4U(=km;y<*XX2 z8Z01H3MlfYSt-+9+5GD2Pzo(K)0qOLk|<=0C}tMXPgW9nU`UJ&D< zI$=W9CbAqZa-Sk}IpDB68frUxF+UJnD*(=A;A9?f8i0gQZL~baO{}sfa5>6Idx7mN ze0urcsveR2XaHN2(AKZnZy{S=<~!9~4B)zB*aq$0ZWmLTNg_|^0mfuYx)w33RbKco zMwkqCRO=-<5Ts9)s?fTCxo!CI?^rKj4JcPiRX(csz!$fAB0YY#zQu}6W|Zm7cRp}d z7Iy{K(^*TE9Eze&fm<4-nrw@1E*^#EED7BBKYu*?Fs zdY5)^C8i<*lYz{6Afu|iZdg&bGBfqgko}U(6IF>UJ4E&Iis;B553;Yk9w@4^Z8cX^ zL96x1xW=w`allMmn1(!D#=7$v_YhoA!j+0htLjQSjI(&wy--OM5L9oTA}Fp9*-wu- zFrYra+8Zfw;il?1?e}}#$j3#VHyr4V1&gZv6SYRWe$ad%G5~&)|APKwl>R(VUS1)v zSKYgMzGd@&D)%URY6+IycsJ4}>sHb7;jFUGS`3$7&+HaMZTRXgY=`l!&i^?AhjrmO zsu|HqJ*9AvD!o+e7|j^66tkGI=vUPMqN~xYPyb;HLCM`%7j<2Xt3DN{`M(SHylR#^ zvnuI>Z<&Lt6VrL}1nyETnPLw+k*=z9QdcJRC-QVj;DK~583X01 z2Z(ALA4b}!J4zqE&q8MILefEfB!@26Jv zeQe2rJUz@Blx=lf#bEA|)-O`ZZS8EBV9_M40+ z{i8Z7)j6teT0L-z@wQd>CH_!<1I6gH5>dM9q{WA-e^aM2+4?(qdXXE;+zww?VV5kh zzs3Vx!B}OCqx!d{T(gE}U1G+2fr)x!Nj|EMvM=_&diqo{x}>RUebt|#4|a=olLxS} z8djm+9~+s6R@NJeCu*KkYZW_r;zee! z9%UumpUgP&r{?hAGJbF1z3TB*`KoGCd2U0oeq5tUeOd6Tc5MQc4&>RJkZk3A zSHv7fqT7oYa~x0X%P4g`U#FM}6(3`k3|n8 ztIVE?cG6Q7&)UvwCD<&0!`kw+UOYL^g_Nj&4v>_0QvgLP5+aQn0phBpTL4B>#Vsxy z1Fe+s995)BZZGA@Roo?xOk+G@Mv_;4mFnCVyShiQdvy?1?@?)z>8#DmY?2vO`Y@WS z#T7eQ?RG|1FAC`()d8woQg<-jh*f=}HDz+;Y^-c`e3sTy1)6p!j$7@(Tn+bVhe}bJ zWl+d`zLiYSZjN>U4?&0ZQ0P=%TD_pxm3K)zXBwYL8c5>kBs_Jk&gZ@Gx0mZwXDM4# zwZ-#*t-Nm84cdFY$hXRjI>79uYx+W6?Ra_=a8r$8J(Ro25|4Iu$5*_+lyO%=Bi{l6 z)w&Laa@5EDFe_Asm*h=0Pf?6f9UIg|VF2FHLS$s4Rn^!RB*Z<6BJ5;Ld9kWnRZrXT z{5OmzPq$yk$5_nl(~x=n(VCN>&bCAcKH;hKV&r;Nh^xCO8RqcDB6~C3J&jSdcG++8 zK`)UPt?0Kjyd=G6*=G8+f+5 zR!Ix0g1N!cOFK&0aFSrHyhe4ZRzJ6g?1R>5v}_(%#^C*K0FvtJBblqtH+1yidPz#{ z45tA*?ewW%YS>-hEO>J^G)0WaqKhn*o9YNatv~pXl{1VH=RpO_7*}*v%D5Yu;dXfS zCn6=q%ruYZs|SIoKypM@tU5+?cNlz zT-E1FHkSO$iO8|mbTfX7Y=d~#n8>r#V?_ID8N8SMS_5?rff^R^8UpOaWr|A3Gf?~~ z134=hu8MSg2xMbhv}7L7Dgyo+ftUIZXoo(+|M%fRJj_+dK^MR3YtR5iO=Lzhp!$h$$ZnviO6R+X=iEd$ zl_9`z8UHQB{vU`Bp>C5+zyk3;_gS)2)PF%ya?M@;X)mCj?{%J>x+JT^LjjO|kWmU) z-2^^SBt$V~c{}O}puTps);v}xxh%hQJiHafbwp>F-RnSfHoQ^|m%a&n2ja`CdRR2S z3J-F&yCOw;)pbGKB+GUu^tB4;D<5Jl)@dC$%jFL3tt&>MJ_-?}oMx{R@EW_5sBc9o z_EuvgOuAFHo6d++HbN9SL^hrFKICy{bFFkx4bdIlLnj}esQwu0#vm`b8zY3EWOe({ z^NI5SWp$KF$4geFvAk2wYB;~!W8bJB!y)8Ux~rqdxm-Ah?*z#ZQZ$CAsGHKQKtujr zgS*EP#|Vm}t!BQ8;mWquJmvrAFe6zFvgTGWm&3qVUZXNM)r&zLEfqJ&2D4hbcB7P& zvy#~+_R$o1@VK&g8}j%Y)>?>MT8k8tMJCH$aTQt3qH|?` z3voocxo^UaF+KabCA zi7EBPs^4g7C9Mo z1?&2)?h=h%;n*=|r8-NmoufPoSwoT^AwKEC`enae;`dyrZycRI?yz4Vhv*pJuLmC6 zp|43itsFX9;PSQhc)IaS#ki&Imoi6n>d8S?%feAaL47T>6Q9SLJK<4X?b@%()sq#Y z^PeO^IHY#tP{f@sue#_Q(NhT{L6^ax(nu~C`fiuWw#o<;T}?4Hg*>Zm*IL##Kz=naxdvZ#6R|_>!5+2B883|XQ|7aF z8rCrrb%hnDD|S!_yk}sA9Ai9j_cY+sA5Kt5q%P1)Aym7H`_)w`&idjEn~(H0|PHGQtu0CCE;KFsI=cX0|?LOGj$rD3?`L{ zBwt6}pcHeFS1!toVV9%5bCkKyXLR-ASq%Tp24>1?(GHM$H{}Bjb=J-0$@5wN0@f{A zI}X~=`2_XIxL$a*Lzu@V{O>RA2kb3G3zYe#sshy{c^$FPy z)b?T@>inOO(`a!gF%xBLNgB%gQDvH94NDkV9c~jCU*|&YW_?G1syZ<#=b;Q}r$e=k z-Io;U(mCz9z+3qivhT8a$)A>7TF9DZ7dFO1`*9u7C}$0`s^qGDc>R0ef-+_+OEQfJ z$9{PCIG?X&);iNuc+@`PB*qiO#v#47(xoqjd5IU)ckGO{1p1f%wSgT7%}L#=dcY0p z9iuKd_t}5J2ius7R-+D9>eV9~K^bR??JZ^fD_NuZ63SXvKO^mL$v2VAl8<;6`EvtMaX+h18)`=X5E~H50j{=+gwCsD4fA;3qjQ z&aU7Ib-Yf)aq7t_f4m#_^+j$CVJ=J2zVcJlH@vY|x-_eLBPnu5?jE17XWr^%u2_#S zvYwf4Wi4zO$4|sZa ztk*j0C{}9(E4D51u6Xz(89j81{crq%@1Rn}0L$qS|BW?(UHU0p{~#Fnja`e&z|x!S z{p_$T`)~H7d$6)p`zoXxkt1w{W^hym*3ReFjeP#I^*CdF%U;JA>uL7d|HG)8tgn?V zVt?rFNbDfuKNk-q%ev8ehw761tgm>g2mI`2AH9nG^sDU;tPhCr&EV$`c4YVQ?HOuP z_7G8h#CnCSpatwCPT|fa*0a3EQloK#r>Qq{6TUxX-edX6N9jn_O0M-Qzo(G7HQsuO zclS`$aV7h~Gr99cGNSHdF8So}vMy`%vfDk-VZyW*2K4 z8Q$%!b7VT-Pwq-OE7bYrU9AB12EUPWe}doda?L5zAs42jN~&G|=U+;#=N|u${`LNEsKHlV(9izaeA>Wy zWdEhkca49n|A>D8clPy9q0YE~^V#t`uKbM zuVkbHz8`&;`M3K1@@@8A?LXtYo$J>!Mgi4)?KmCI_OJ2P_&)Jn=fBF|gzgq6cz2V! zIB@NkzMK8O`F>^8-u^c@Yr2|KLRxa&R^L|6pI+qq$Tz|FweLmWXZ&pP?d9E@z5$$w z)Xw*|FN2fppXRFfeed{Y`X2Vp_Z4zN(tkK>WV!DJPKh1j+s!B2eE;^1^X2+p_l@#R z;{Q*4LwR1AuZXLj;m+Z{^}as7J2-3mHs9mCE9Cwsd&kg1 z5BMHpq{n^fzN>xr`fl+>`P%zJzQMlVjDbFzPwI_djlsU}jaI%BMl;`+MvU)gql539 zajP%i*OVu`ZTx8bWgIlBI7xn`;pK$+08ee{JIiPPGm7a~QE6N>YK;h|rd;LQVw~Xp zS4Oq*x$%MVvoXu~meXp#Fn%y@@EtUc7_;fj^n#IMOgDxb%Z%m5H^#fh0b?E4FEw5^ z1{#Zv2aT6_y>HAl{xM!L{%fQe3yf|?jxm$-mKPbTx#}I`W8-0Cmod$F#(0FTI`kYZyB? zZ?fJy&D+K}?fuPrn-OND2F~aW@&Et4wcZM@Kj3Xqo1-#Et@JGlEWoku?NUS|C6 z{gS&YylsuG-gBHM*uwaZ-`hB6HP8FHcc-`1yVd)-x6-@CTkI|IW_rhZbG@Uz+1~Nq zLT{OOCEqtUe)X>QuAwi(XzyZgftRz=y#u{pb8ivjO!c1i-r}9^eZsrU`-pd=cO+MA z@-Fo*@UG>G)!v1?GrTu?yU;meC?h=Oo#B0y@x9(GZw#NG^jz)znOAS`mEOVp4)EFE zo@>4PIQ=k&>;Lhr@`jn~4c_a#4=~a>&t=}UpF=A6ra_{E7-5cbN-JTZSvz|75 zcEWSk6VE3h#{P#s68q_)G0XFTXM<;fr`U7av)c2u=Of;4^t|Dj>)FnCi#=a>KIGGK z&kvp^-YuTrJX82|uIK+cy3Qz(&Mo@&e)Sq5h&oDiMj18A6J-pEUPc#!L>HoyAVv+r z6P*wxdJPf;!4O^a;2}!%km2oR?X}O@=bU}cogedO)|z$il4vkI8>0!>*%?ib9!7nm zlgKNh;h1%b4o5?y#ke^n>IvsyZ1s&ki9U@!i&{sGF-wd-ikd_tq6X1>QLZR9Duh{k z_^ZL+5}u5xvPNYhi;Z$o@5n?Vl5pjKKO1spy!&Gaz6Ci4*BVFh_%`!fQPn6-lsn2E zl>n;Xl8k(m9A1VfIuuGpS3>5<;pX$;qU#}TbSk_GKZOI~es~^Egba9V$%#OtCm~0) zKb#6b1DC_?a1*ZM;aJ!ZdWAjs4)l?*D*O^2hZLxz;X>FI)}nqGW`=oTO_&;{h0S3> zSQmDOZ;Y;q78Y+ed{+Yk)uXz_PLHY1jC=p79*Z!>tpbP23 zyWya(6z=;1VUxe(`}xWKw7=kg@!R}Gf6IU8Nm%E9@PmA^-{kjT!zHO#&vaHfg@aH+*;`Ry02X$*9YDfF2NOZ#a%&H*44qaxvo8)kmy>v zcvryHa*A`oN-m#EvDuw=Ib1eZ9`jGY58Q|Dl`Z7%+EeyVd&ZW)R&AFX zSDkC(Qn|>zwrMbZY%{yOE+;l)opl-9Mf=h|wd(S?y7wmSs0`+%xlwEC)*v)pQU1hh} z^>!aF^|NE`82hcA8ygm)M0i3G?o@7ckP!u*r6gJ#7cud2o-h9c@z^kKEh# zvHfvzn4Ms|VKUH`w{fe1 zv9_TtW*ebf22U<&6Kw%o7A$4ovPEnm`^vm$E86Ndo2_B<*wWUb=k0T&Ewg9LBlFPQ zGAUrN`^}$bmpN~io7?7+xoWc58{kp%z??PD&1SRDY&C1m4YLI9Rpx*>Y<@6P%p5b{ zj5D*%A~VV)n`LINS!!0BZE#LSXE@^bW)is7tT#u@LNm?$7yVwyJx!9CiKl&UzQUDH z%onDQ>56LuaP3Q6{>F?odrT)dx|l>$!z7rRrmbmh;!Stc$P6>>aXsGjN2jc*Y;u@) zOg&S}bTe^q)i&>%TqeDF+Z4nvK>>po3Sy@!7@1g;(cqLA z=+x#9{ZhXMwMo&L%}dQqZu3}YFgNveeM>*nH}qM3TnlquU)Im{Nno#Dq&MhmP!HfZ ztFP*ddY8VW59x!L9ns+08RdX{dXN9nG}3$Q;x_tE{{Y)(dgUpLatb)xR1 zd+9Eyhv;T{CcI5`V_ikZ>FT!Mrgc(@DbYUpJ}ubj@T^Xp2ws!qTYO2J!M z=g}E;QB5#OqjLiJbawroPElE*Un#0Dsx#`II;hfWr=?D8sLOC|RlC&+%yz4VYMELDy;iMLKdGH+w)#Q6FI|mujuvR`07)s)}l&>R{SHRl>ZMic?w9 zEv)jX;wn}Zg^oeasq@*4E-m@JhW7l1eEbibvv^xFep6>*AjH8_s9qvN$DfiDYqJ>=1j!FNpia9`J&= zjhHNc5L?Akv06+87l~bBvsf>-hzcl$tkL&PM} z4;U#%K_!X)qK_CP+Kb+zr)Z0AH_=OcAv(d`47#DHBR&*0MFP-7w1T6nXb0U^R771_ zR23COHBlP5D4cagb@UpEB5&$KqL3&oii-lGAg0AdHc?Du7BM0>)GMA^5U5P(qyo}H zz2GVQC4b6^_>14?clcxegr^b@xe$-heZ}wbyZj+P!LRb)_%VJODw&_*C;1=z3O@(z z;lJ~Z`~cs;_wp^soA@FAE8mA|JKx5a^YwfsUxK_6Si`@2lb7)+P?Pw#d?Fvs$MG-u zWKd=I6>rI# z@cO(i{}2Cwzt3ZNZC;(n^K!f)FTtzuI9`eu=J|LGSQN~TnC?xd7-CMIk>}u^r{|VC zZh-7OVE&rnSBF1j|FV1R3A+#81Ya=1AF&6h|Hm${tL!wp#Li)Ij-5nxfh7aS***A57(LHqQ8}6d}={Dd;x{9u&D}Y6GHC;|u((ma~R5R%;I+cD+r_*V4GE@?s zL8kx{fU$Ha9Zd(&;dBt#mky(S=qPY7?Lqs4oq&!sk+!96XnVxA(5+|-uo-Pa8_>Ey zZCZ!cM6C3N)o6JdN6Ud_X>sHjT7(v)MQL8B>@*jUo93i=X)4W1)6+CGEp^mWOH(06 zpho?g2>Oz|A}`24J|t`lJD= zN9q8zNOhnxsX{7{I8p|&Bq>MUBPB=?Qj`=#%uQm*J0w5JM)H!(P?<>=|~!a QKd*@)fe1v3`0Dll0r5CvU;qFB literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/default/coptercontrol.wav b/ground/openpilotgcs/share/openpilotgcs/sounds/default/coptercontrol.wav new file mode 100644 index 0000000000000000000000000000000000000000..f41ce70b2ebbd472f953353bb0df43f052cd77c3 GIT binary patch literal 84106 zcmW(-1y~ea6y2JBGqcIkAfX~EASM=w0b(JDs3;x!F-2a3Bm9;3Zhyi|Nvyj2t_ekw{8C5j3~6%IyO zr4W>?QdAn1dZo3}7R?pSMOhz@Zg{M(^inoMYm3%V8H5(13|4kic2V}iV=rZ-vX648 za)5HUGEO;BIZ`=ZIa)amElHV-HbXf_Ia4`bnWvnmT%uf{T&Y~9T&-NIT&LWu+^fu2 z7AOxYk13BR4=azOol;&@UQ*stUQ<3+K2$zZzEa-BabNjH`Aqp4twdR>EK*i0%as*M zR;5x^C}~xxlBo15Q6;FXR63Q5%2riZ<)CuKnVYJC%1hM}t&7TE)j`!!)k)PAt%E95 z)f>+PR0CCmR3lZfI7X|6tKwB7RFhPbRjH~B)eN*u)dE$HYN=|fYME*wp4Z{nq}r<5 zuiA~{glZq!Q5>gL1*)s6W2#%K3#!X_zOH(pdZK!vdaQb_dZv1+`k?xz`mXw=daf#0 z{ZN(RVARzrUd^cmwWK!Tuv1&8?bWr_R(P~hd*IAl-BR5~-B#T~9e~%qIP+BdsoSah zsr#x!)lupJ>i+6c>XCRIqmEP$Q%_b;P-m&9s58`Q>iOzy^>p=Ob&7h4I!C=iy->YY zy-B@Gy-!`BKB(TK-l^XG@9~uSg8H`ljQXDXk@}AMhx(=Zz51E@ES|sN`Iq{qx>#MP zHfj_aUQ?>3HI;a;2G^)HoJOZHYHT$Ijh)5{=T;ggGzX2F##7T-(?Zi&(^cc5>7i+@ z>7ohI_-KOhX2*{WHm*`hg)c1d$y^IUUB^Ir2(b4&9GuWxCtX|8LYXkMcg zYkq53>a(T>XN71q^+Thf)RauwQ!bPhbZF z7PXvOO>IWoNv)?&QhC&2Y73Q5t)tFSOQ>tqcIpyZ0d*he|4|32ThvAB4ccp}hWbhU zqAIDc)F-NxdPY5_)bwYHqm{HwD`*u>)84d1ThQMrhPI*&bY0qw?m)Moy=X_;pYBS# z&_T2(UiYV)(0%CEbO0Sghtl2uJ$Itx=rDR5S}Z+_o4|g( zokDM?SI`^jne;w-34H?BZKZe78}Lp(ULT;3;`JH&5`BbTO&_C|(Pz<~(Pi{g9PjBj z^e_4~{gA#$SK!rex*E;MRM1XLEvA}wXJm$BOpKE8V(K#unL12g#)*kQi(&kjrpz$L zm+8ukVCFF)I3LKQ;CwQ!iDSZKucpcvAfyR>=X7TyN5l-e#a-z*dy!%b{%`3y~JL{w|=t4>?igWTZvZA z-p1$m*(%nF^W>bkrX0nYIUmjz=f7ErQ*f4ezaH0u3*y?~)4^Oz&KmDIAs5E= z;3Bx8I3K~qb3?dRTwAodToyNgTa5RHaw*(=E|(j_C2&i*1>8t(CbyE?fnyK1m0Qo9 z<_fqiTsn7vyT&cy^0_121MUP@g!hi&`xV?xygI{u!8`9bhX2gT{A;ch-#Wux%-3*c-i5E=?0AW{=kbYrChy0u;^X-Yywips$EV}nWPTT}-^g#^7xQy) zwg~5G{1bi~zmwm~KjriJDt;+{nZLr%DXQ90? zUa%EB1ZTlPs4KV#ql7s^oRBGu5he;tg~53C7na~IIl?kwt#D2FgI9Zm)xsuxK3zx< za)r~ve&MCCU3e@M2xo=6!hGSVkR>b@<_X(`i^6l^8Ls#u{1iS4#lkAw;j&OD6bUNw zRp>>OqyZ@w1X3Z~5}x4RO5#B*Ne9xHbRlk}9dRX2L`xnCCeoU8ByEX3X-Sev8c8A( z|6S3abRuCSlO&KhGM0?QXYs_J^vBiFWGL>`kqpLlGs$wYl+4HX5=n2;nZ)8+TQUXD zUGN({NILG^59iH@BXRiGgUO^9`p}ZJA>QP&P$ASuKlQk;4fRe@Be;{-f`;&T zO_86%MzrO^1dM*IkczRl5&8%nh0!?HVXl_o)mouks1nKqTYOKC@7xgH2`4eHmxMGS z9oKsad-+m+K4c<@*YX^%=buAvXFxKCaJ@JUbmjcO_F}AdoW7m$is`(0v~`-zW*cwYJGKLCyICtOKbzhd47%Ua0TRd0XSz^C zU97yRcv8dEIMhVfv{QUnM5#Wg7gKMU-h5+mlk`F!r+aL0G<`AcvAAY&#G>4!FpV+V z8Z`zBU4X2Wc91<>0aHeAqjTxrbRqQvUe6Ne0jxJ)#BURNi0$RA+9tYEU8R1J@tN_8 zK`{8}7wMdJEwugQC*n<#ChX??SQXQQ3ec=khXcp-Qa@LJQZLbzYNk@T^l@ewJD2M& zq>yH!gA^zAkXlQr(l04Ta*!s8ZlXJh;P0@$>_TQSeU7T4B)ToFpj%? zKG{Cjex-dY`*b^Z+ebF1tvxJ*O#=<#`Z9SNISJdMKF>ZR)b znlQ~es*=9NR&d+-iNYe%Q93Ix*GB6`=qbZ*!%RbSLxny>-$LJ0zgpK+`$p<7Jr`xM z3F#(m;9K%zxk=nK*v;LX3O0}thCs4U3kyk>_*85yc}Rc6cj6aug?OLDkh4NLtlC*_ zCp(xqL>B{1BvF~bIbKvS)t~yLT3hwFN>K1M7S%th`XVZrR9#RRSna0xqBlPq1bM*ami{)x5 zU9K&M$}#d=*-aauwbOFiBH35_RQo~KS6_uI&*>a=e!3EEiZ)07DTPT&u`^jNY!!%b zl5fUSToC()31&tyf8fLQtckn8t%gUDh4bW_SW6zLovXWpo=nlF8vIN(#%ad>M$S0O z&`$qRH(WnR@2op7x0GdVJvmnTPn;k%l?p|pB*-VEE0V9Q*M8D|!gZ7N3-qPBRl0+^ zADH>6dMkZn-B`JU6eRkPLBcTDfHLkYTbE5{#sWEfLqBT6w_j%8uoF2Cel_1v*hKn> zUScUMnMyn?P7|M#2V^0v-D*K04ChDu^Heq*%~h~pSr_g#7sY?!_Va7;JvVW_cvtKw zImy*>p!SP=SWc6d$dhFs`HgfzijvgQ3P^jVFqMyh?@EIw)$={!59h&4P2*p}m-Z0a z5l;M1be6oNcG7t9F8M_Uiao^)^k^4Rkto59-vLarpY6sS=k{?)+&wOX^WsjjM>qxV zAZ#W%(qqXe9mPE~Qm%ARS|f$XmfAvjwfs`*BhDbb#rNWD$kZ`$iC8S=OZ6qSSVz1j zt`~j9XJVyjmO`ab(q?Iud_e9iyUQwFg6_TiM?5RmmLj3EtuUH6d9&1AIxTwRJ29}` z=g3&GnK*>J63)Qm7)cOW1ds7axC85};)@td+K;MDdo%9PvkUZUrX$;)oxr-WrA#}n zk#K)$tg277m!h5OxT>2{sp_anX0%v|rosxbyS9z4i%zM})SuJOG;}q#F|^Y8 zX??ZN{!)LSHq(nCQ?t2t5{{Utgn**9tNR4VJVq`p6WL!}KYj-Hgzk#i=_Esm*4i_2 z4J4q6D9MZEeX_IcEeFZ_<+|FhVhR_5$RmMS!m61l>ZHb#I!YhsHj_{?0e*0cFAbgnbv=1j~^|AAOemMWES}nxm>7$|2P;<$Os< z@rU9zrN_&9RJzw}QuU#hu^otyJk+qp@}Bi@+f@5)4!0dcYAtpAV4q>v({_;cTGM%X zD&LqX(M(sl*YH)7DqfZsmyfB4tIV!StBz6CWBzdQ!fmNY-^3!%GSix}NwnT<)z&(| z=CieE6=6|n_@Ub>!8;dY11InHDir2)VN-+(2v!x)&JHVm+lI$*;FQlHq-AY6Fr9-r&+IdP`_5s z)ZEu7=;2HiyMv!8{1Dg6b~*(tW1c=t?`BwTO-2xbOb}O{_H|7l)s4xrZfMZ zk02h>e!02!hTKygD7_=OKz_b(UXk2%#5o>pIz3X;Op~SAN~vfy^OUs*T5m(fN}YA{ z^#O*9h9ic0Mzv9GaM9=L&l){IoH&N;=3fC1u7FSO#5SkhHT%@9 zG$W|)bbCh4%%m^VLs%v2&)9LXBujSD&DB}!thDptp%mJO+A8fF`5alt^<{bh%{->J z&=q!8-H*@u{Sb9Hm_WTl*Z|bguM8yeD=gllVBkgsaEK z)0?Py)P8C&{S)I@sy3+BDViz^)gJh68@8O8$@8l+i-<9&khGYQOjc$#+%_VBICQH>;c~!Bf zW<%Bbiol9{6(cL}RUcD+SI<&^P<>WcQFmBc@DYn-h5n(gG47I&IWN;D>rI9;`b#=q zH%Pl&PR97(XlF|O$trS5dN2QyUP+=ZKtDuRu6-`QAUPxz-ff)ph-ifG>?7KWYDYDt zhtglD@9I9PC&+HrQT|ffuos2jQgf}3TrIwm67`%Z*Hq7Rz+$I)wS~KJk?s`yiiM~Z zzVR2hY3wYv8E}Xl7sITjLg+x|7;B5j;InX9O4GiVPf63Id^tq7#*k>bZZXWFmhq;p zt#-QXCfAq$di0^^>>y)}7IxF27-3Y@HV`pG(#-uaO*XpGW z(jK{^%!rNnK5PV&&Fo+|aV^;Y7+;Qq9kJ$C^X&yeyf1CkX6bD8_km*iYM;tU+9cf@ zod;$qTlWq~;;`6HYy}iei&uq8M6Qdt`^+EOikZUxmbewSD-sLG{P|TV7q2dA_uKX- z^<(Y#nD4INZ+)}?6}Qyfu$ZJ zhJG%ng*aZpZ{|E%Z)OyouL)G;*JM_Gsr0MLtK3sD6MnBvWxpz+W~w3=`S88!t#ku! z1Akh$E3VTP>N}evEQVObTJ$yduxw@3&&tzMu&8g0(pPG0$zR1eqEhN8t{0-YJ?vg~ z7?;5NAbZeF7%p@s=fyQz2g6d6v$@dx!Ti|V)y$YrS?J79%^~JxrkMsiT~E0{9;)@y z?v)3~4sx-0fD{TB$N=ex*505n3DB4!_{|Sihiw+yIoP+ex3jOb3$lM@zt_R+*xzx! z<21+J4jP9u_C@x3hk*`V9FpyG?Y!*D>_QxtIl&-CmbRAT%mLY<^*#y3)yti5MU_OFV`pN zhH69Q2GUh=nUp8r*S^;+HMB%rkZ!2b4>l5u7Uo$N#3IvFXc}O_nKR4<=B?)W7VC@; zb++;$v98oY&X?>ZFVUO)%>~p!j--xwS;~@Yd_KEhi_L@9L-X?t(`-)LO@|F1Y;qnC8Q+AaDv4$3N~c0zLw5f`vKm`Q9MpIih@)} zijg+SJ+$q0y#BfFiuSga(+|MRoYQwR>@_ShI2xwt4rsRk3&-kiYnyAAYq!b6r3vCh zvK!ebYqE<>6V=jQiIGimhU}%a21-0=*ktrHEkkQzdTM-W>}&jL2r-T{dK;hXC+ThU zW!m%d5cFX`(TgTAR%|HN6R(PI#5~DQo-V)9X6eHWrwt#lHvKKGnZ6p=8YdYkV^8BR z;|}9P!$SQ6ou}3ymq>S{2U46|NBc$FUq^J)f%pgN$LY7}Kj?q!gACh@78cnSO)VN& z>@y`9SLltpD*24`P`ph(A}iKa_{m2KuY|Q&jk?lBX}(-4f7Z6rIpe#Xj0a6mEUL`0 zmiw%JSrO|?miNpf&CSgo7M{j>hDnIxpCWdBAP<&rORFFo!-2>n#D3B|#AuhL>GB%w zHGPS(z@oAFrDad+A66@^oUF^NORSq&H?lru?PLAks-Xzj42cFuV-w>TW1R7qL1nyPJY{-rdT6R+and5tY;B%zUTQhSYP(f$tK*hmEyFB# znm<@{v$$-U4pex-*w5I@*w8e`^vJZsG|_a-xZU7nm~W_r)xDwD8+;6*hD<|@VV%L+ zsDNxdHwIvJZksYp%S{(7yv^Ipoh`kr&RQ}qw)D#0qoQfIl);;Jdz7;9*$f2R9_ zxGGR9YwG}K)R*nF`?cTXG4fdL4{eRMo^G;!z2U1d5t$(?;}&C}(bABizY3IEpj)Ji z*6VejB+S!P+@w0vTD*m9|5 zcgu#BBawgDXo@nvF)TKC7!V`_9qf}+fDo@~&)Xg?bF=|cqEmAFZT0Aqg zhh_V2erv8}_AyU2f3oOq>Sl~HjMR73y2=B@Y@r(Y?D=dG^B-N0{)9cACX|Wd>1gbH ztfcqTudt_agPFxHpA$^9BbYm8G*=h@B&oSQkna!PV~QmfkWonwgO5{G>IW_G`9zFDud>SSrQOgA?%vlgpN zVW!Q-4u+Nb<+|P4mvXQiDRa^`5>C1Z0{?~m!E|8)=)Kej>~#s)H?yLCVu$aG`nsw_ z6`}H0HC4`4O3LAixSB`RE2_M!URLH-hE}Fmwy%t;{8HLU#qrP zU$1dfEKn3GIPAT)!EWOs&3vF{XJ!Et!X^VNP3C7IU+Y7>#n)mdX@X=eUz6KuUuxIt zeDz8CK*M-Ld*eN0plQ5CXS2K28|xdkJM9P5l3Z5RX<2W01HI=puRV=^H)_-9yqB-n zU@y{$Zq&9>mRG#z;s)F6U99t;>o%82=cP`|oz^6_}g|5d21P-4!%3@6SF|$Ya zh`%-LLG*)&Um^Pg`?YD^w|RH(qK5C?7rD9D9aXo|?P@)t!E4X+P25{HZ5I_ZFXUF=j#1V_ z?hk(-7d-08=%%Ch#SI+f6!6+%(vKGhJLM{;yJdK#e@=Uwb~bHVT8FecX%=a^H0!iB zX`j-*PMtV6Xj|gtEAPLkr`KK)T$I>4IXLx9>Z8;rspnD`q&7?4lVX)JBYF3f+{yLF zEsuTP>AOQp*}VsAkJjCEZ;5kWan`C?`)3@TK79J8>9=Q&$hw|au>8iBS^Ezj3p$s1 zb?v?U*YAt0NpEMj=0iI6>hd}0K__*)A8l&;J?vE8y-~Q-KWTsz!G^Ev>D?_fD5>+Z zz-a;g9oqS3w7AviYW>{0H(kA4`?+3qedRjIb&`w5#m?oq>twfZ52jgZ+hu{4J*R}P z?|(dM)Zpq^m*MFn7mu7i%seox^WwVO6{dT6TR+bIJ>%=tX&I-}d!?(>_ot0Z>y;Lm z);%pX&5-^vW5TS+T+VK9g*DZcsQ8>v~)-N6JIK6TVvp;F~+rF)nQ1@X&bJKaPWWR0xEj!fh_`1`I z0Ixtfa8p2Tr@W5k?XCPh{Mxo<+gP+3(_($o&yAuyj=SHg+p~6}>$}?X>)rN9XmX_` z)$T&Tq;BD%fBO86Y#S3bym$PTQM*R}8r2{!HafjqOv5Zjd{Vx1LSCntc~i9+W73_{ zucf7=bxQL}b4aV3=99K8?R9$Kj1%*kZ?C=>@Sdf<*9!}~HRjb6A$3XWL9}J5gHy%S zZ7HECKayJ~XC^hBaA?Gb;M@jDe9JG2TYHag+*Y|#y>M5~%gk@H8qaz->s;pKoIwi? zEo+fyf5-eY?0YwdkeNjyQWvXe!0J|?dp8RiE=$! zZ@pJp^9F5)cUaKbr~CL&v0rjj#*p(P4~^=Wcyjc*csf=NY1U+|cE$VZBUa0tv${?% z%qUHtk*-ZYnl>b@V_L&B_cXt>DQOAmIn$DJc5nE0X4>l)3bRXkSBr$iqzx%!Q+K59 zPhFWBmui_>kP@3>o3buBbxP)>_|a|qck&r%>Qwmr;f>Ru_9SiSyi7a4d(OZtb>{oo z#;kAIOXjJTPG9q7bIfk9f?CHKoa=GZ>bc_k#mW%g*_dYe#?sTg!t~stzwOT2yS(Fk zxu7q>gF?53mWM14;d+(!_UN~_fBgZ)5&Oa$hLElYI{oKA%P+sJ*xI4R?MA=r-F5P` zU2TpsU$y3Iy{YrmV`8(et$qF8cHGld=(Qxma`1y;>bU)Jnvp57)BC>aFudMge!}}T zCk(58%^@>y{Rj7Mpf0%_U>g4Ap`kyZ7Jn`<1Q@YorM;AAKfi zUdn*f<*DmZGgJGeDpD7xIHzn&emun^>C5;ZBie>E^Jp%t{QUX)(!)=-R<812{3`EZ zcJHiXv+ZZc%)Xx)p4~GqYZ1L_*QSX4$46&hJaI4n&Dh_4l%3^%R`InK)c#ZNeZvUv z9G|H6uev3K`$tv|IvedcXmsS4h(mo3_BqpMeV_dB@4cLZ3p=lBZ{22W^H}d#kG<}@ z>-=%n);eYXz^=bTQ>Rt6ee0j_p5Jo4f9s&%J=^zDMpg|+w`VW12WTAzBqpM#nP%0YrmFh z{a=o0I%P{r1gu?d>e$rUsYg=kq-;)hO%9$CKRIh$<4RTN|$( zx9rb?gxn_Cp;_B9&t@LT8j=x7fJ-f#D%I{Yixn~eN*fiKCIzG}a>|KX` z4F#R^xAo_0uPe#vJ#)-7$EoodW$6>rtJ5~8C8v!{o0lf1-^-XjYs`|GgFPO1D(hlV zr^$e@jtPAyS0`JfCZ?uie-QVKFlpx@NMa&)z+J`cRT%e`O595J--*!OpwM|U2-gT z$*vpKAhNMdo2o!AOd6OGdve(9;U2?!4e1ecK3W&uHhNR^twDDOHjh}-%e(9M_HSFy zYQCy*Z!fB$sUE34wbpohAKPHNx=x$wx_bU;Ho|vcr?@URdjy0w2n+2!E&NySAt9#& zb6dnZvvkw9F(>j?Q*)=z+BV&NTEf&v8QP5A>Ce;Frsbp^PK!>DpSp7P=%v;L~q?9%(pD}iuDR(D&k9yP3-lwP8tu*v`^ULu^ z%6AT3*Ln$;yD2km=GW;{r+d!unRPI$b>8&F(W~ljirUTncjQXc^ZkGNvRABSw|0%{ zHyiFFx7p!u2znCIHDdgrvoS|wUkn}>HLCxbJ|$s0dwmRD8yXRk*~6zxyN-hIE1wlj zrN+Y=g?oMSboH!kXxZSI`)>D%4GwtfoAz)0+kZu1M7NW{F(E-AmwT=azTds1OZ!e0 zt=2X0vTC3h{yOsXiVdgd#b(}^@on1Ksg6_UWPDDKO1Da<(_5q~GFnaZ$#h$y-81)k z_@`;A8e3W6G`MvB{RnM*h2==For0*|}DmK=&N zzGQA}IsSH+<=WUqRXM{lAJ2R>BP%X1CjzJI(Bx6`U0EtfyCx^dQnPxphyE zI<^<77oYqtJ>GI>flrn&vvL}l7Bh8y#{KkG>95lY(k`UcNgtb`o-uIlq4i@=^?hMq zVP#Hkx+82)T;RkRQ;aE_Qy!FbCjL?~bW?z}JFYo>0SF5jY4K3Ju&f>wlPpd085v_Gk zm(2QpjhnT~?7;Qd+9xV%NbLEcb%xmtT^ef_^EA3~v|V)GphHo|BX>mDhnqvTbsZTn z(tmtgb?b>f$C|HbI=pdAqf4H@Jz9INZB*HGQOm_`KeppKPvG?&K zk5Y>g^piYWbZZ{tnHW0JFKN}3@Z{6UmC3d##*|mdQOWJ6)J$?4H+Y0k-a zH0||(8!5*|>^!_ixp-D??i`0q``Na$OJ`rsTAibuKXU1#bsh6po|Ny*e|M>*FB@nc z>>_vuwLH?nvqxB;u~El{v>(|e;q9o|qYsVpNJt#nXjoBy-)hxbmi2c)B9#}3odUcKbm=O z($C}K26si^{(<-7dyoG#=|xi6ls(CoDZNsLr}RrvruZapPue_DGv?w@xlh*)l-Ei- z8{t)H+xLaHcbw?9tIe95i(2Nz<*2d;&8a)5`y6w2@0_CC&I=o_*thZfp7Y18uXcUd z{Oz@$#Z`}mY%5b;tET(>xgPO-TMgPWBymJh+@geyqvntHN!*qAJn?*D(P*nt+vA=O zPaBdLt&F_TH#p3<$Joy54)@!hY+0{)$0i2vO`gdOzt+!jr|bQx2<)*7unQrjMAmW@_K5^QHz&n>u~`%o&-vbGI&D zx?$46rPofrJ6h#yF`@n(zmp;FqjrukB|473JaOFQ^dwEtHm*5Nyx_Pi|Eajf>a zJJHLJxjVB4Eh|9+o4Un#cc~)x%iB3_PX&kuc-|+?vv`wcY0-K zWqC&KM`f2+e;e|$>z$JqTb<}wFn-t8&9m2hTY7bYkasYrO?Kg&$m|I@Kj!+)+rCh@ z+_2tdm)C!;S35o}{Ssc$l5c34?#g+Ww=EAE5H=&yGd5(zp!h+f>W+Rs>PCWd{Q40K zhE9lyi@F+75ti2dUdPL=A{#ZRd)uyyvAeKSb-euN@8T~m@3y{Z`gr$!<(=}Iem6p{ z+g?w;{^Z8^TM2isKiKj#>h=APNk4a%x+>>#H*`wtg|$}IHG4d4a=+zQKPkZ2tsrD^ z?_Yfb`tKTWen9AeRs9b}*!K(T)1>#;P-V{z-L`d(@7S{4qt=I8q%~>b)wIC~w@I#v zwNBc$vOHsWBn9(7DMr<(`e&KBxZCfx--AD2dcXTk)T<*eRzCmnZ11y0&o)2%^vvhE z`Nf|XlV2shv3dXPV~?*7e|-OwTr#I3u_j2J$SfD0$%65$d6JF2LuaSAE<5ThaC32g z@7}q-w*KpSW89k5-C0}fy3)CklUuDChhqC8yDZzqHh$L5R#BFY=9d;>79Eg_n{JV2 zVQGG5He0$`{j_>!U0^fQHrsBm{U3*vTA!U>I4^X$;*lpZY|S30S*WodM&TPctCa!Pua{4U;C98k;@I~IH5 z@p;kUqLD@Qi`nFT7P~DEhBRUp&6pqa?26VM)JIs%&VP zOZlAgc@@tp7FN1eEv-6K6;VC7I<9(q^_uEs)%Kv&CRcr|>|MDId*O4+gUf_6=h96j z@g)f*F(pk)PL%vCnOeHEETQ~F#rI18>cX1Wid)JHs;%k?*p;*cpQn-;$=+fq?haeQ zt_MeCH&c)4jh&gDn(u10x~!lO%u%k%}#K#>rfHM zixp5^!5rq1>EYO1Fk5Xo!nNj7v7a`U&jpilI(b1#2`gHPTC{MmnXZbNVxV|~{1GIu zpgwaS!B;)Q=CRi7PNqHci0(n}0khejS%_qT>;FgyFBwI?B9dbR^+^8~q0lvtI8?Q<9I|WH;dlPlTKNY`z!234Gy! z+%GnpJp}ekFguA|4wm!|wvaV)9l2fHS8gDBK<`sh+a~*bXz)!ETTqwCicJ{OMti$%%+t%4-_|pk=pnl z+m$8(q&XQxx{(pYj<^#Sj5vb~Cwb%un5!|QE4Z(xFay!zXzZ<&l1)TI=3-U;@HPB% z{xR5gcKjV~6vy1}Y^taHF)FQLUHBt+*cSigU zE?2nJMVck`lG3FJX)^d#_TXQv5bKH;G5cWafCqelUxr_J&kX~AyON#CMzSl}#q1a` zjoyO!?T@|M+E|6%d=oH-9Y`Ot4*mW{Du^IflQQz07{oi|GpQyQNddVD`Q1Y{V3m_G z&Qo9wj{`TkG5E^k!6~c@HlC&MgqMZpU?}$!T7zBuNr-@4NTRdoDjp$wF;`CHHW7$5Zj}NQ^2^JEbaq4FjLGDCqXVAl4oE+8%PQ`UlR)PnRA`O&gNNuIA=;;x0Dy-`R z*t7&#m3x@w9zr$0oL`8QI*Z>)=No`=I2>pDz%iW&TNOj5L)v%2G8f?N19?e0iQ~kk z*jWw$=gD`P$5ys2Rn6}@JM(A&Uq`a{T4#r6&PE!Xac`C z3Tx0w`YOH=_lxObXE6~{(O9e`+aQ^_tI2at(<~M(vKY{gMz!yNqrttm1 z>Ho-|;U!@adi)S)bp%IY4fyKq(AQVk^K%uOK*A=ApT!@dUMj&#y%0Z%3jAsz=I03H zLKc5v_kA?9yD=F;Jjr*k{8q}3aj)E z8nKg%!_IFG^k^I*=<#-p`ZY%E47(W*Ui{zVuO;dLKKx0@qY_p}3BCSnKMun7{Ix5c zVGD+X_dWrS6Ua(@auOE!Hz_3X;#U$RzK5qcK_0>~@4`IxCwGKH!ek*#$ib=wVlIyH z>rv%!n=j+z(Ek%c8{G8(Y@dZV0=8-cJj`1$0Wxq{+9Le~r)xKK!4~}3Jz@lQW_f5{ zKG^m~k}5=@Mj=RW5|UASkRcp_oQmM`KNmc}&yOOfVY7RSH^ePsf%pX9evVnZCSDO4 z=@o3)b}(U+!SQS-eg`*aHCDR;Y|BI8I{FkO#6uf~2>Zal+yVXE4vmrB=|SFli?4K1w36()-0V(1iri zA96v7Hn6n{@g-Jk0pz$3q^cFF7M=($KrcFCLCU~>orKDdo`OMWC+vo&_Cg&+G#LPi z&nESt^%<~;>tGEA{`1BK7}0b{$!17X1F~4~6VAYgWb=-E7id8ixX3}MESU?5or5*Z z6?cgt@E-l)@z(%Tv;v}dC%=^M$}hk{2J;8Y*BubA5p; z+VS4d`XJ1~1HLWB|4!&ZG-4+)N!$w=IwCHBr+P0MFtZadi*>N(i^O~}TRbH06t_Wp zlSBsiAqO%Vi@8m~cyb{9Jz-@Y3lA~R1+bt$!92YTkMS6Gp;V|AMu5wA4pw0@EWkDJ zhiBu_3o>*W@}B~Za0Bui)hP)=ccBKd-VYw7nhQt8&qY|O1AG)}INHElKO(cyLmR1u z6fI?eG4M+=fPEDwHv$*-B&6O}+Aj8i#?62(UO|1#Ab}FD<8F2NuKXxe`Sd_tkq$O5 z2-Szr_#YEm6igM@ng!&r|RqbHVqlz&u=mtY7pK88rQ%-Su*wyv;>zHnxjv}l+Q)hF<(w9}^c22+sIUdv zxQo;gr;BT0Aw`Tk6_{i-X7D188`3)1kfzc(^tA;v=pp2`6KaGk$OB<2tj>Pm;blUe zFbkTV2P;^c1furGB>n~xuMbS7)m3bTdwuz@e2=^3IO)q#KDnu6c;2UvA+>n8lUIx?~EpEk_X9M+&fOS)e=P~j&ko0g=kFDi<^B$-_ z+JlO`bd0zbGzr+t9~S8=xc0pK5bT&f@(?*)wnyE?Uif%V@O&4G z*3iWXK(mJgPiXjZ@I>nX*;H|**jdUmFKzdgokLjqXdJkz?$=?GjRUs_F44&Yf;q^UWgT}+}H3mYq#=7>y z-LB(K7E(j0gH%`2Nmi0l+VpR==K*%-ra={ zK&{>r-cr~l91sE!1IX}%5n?F(&sz}dI2gi{(AEp zSdX^Av86!Wj<6z`u#^jg8L(_h{Bi+&w-OP6A66m>esTxa<|ypQVR1LCS|rv*5=X)7 zDPX@Z0|oto-C7DfLI{k3yBjTxlt07VLA>X*h^KAw!|0KB*L(P){=+btpx^1y8X$ z+jt%DSQ2dIU7;oXd@uZR0Z^PT`f*gGfLx>C)$+h%T?)UkND9PSZ5GoYou^0^sY5Pe z7LADVl7J5%q9$%Aw}RWw1;TzT=kB1M(+57Y4v=2CFdiD>1H0$~YjF}WX9qc4ZYKN6 zHn74orP^4f$%vdDB9d-^_-frhRJ<1~nkarSER)+`KDJOF_&o={cb@P|kWe*v2w3wu zq|;IQg*840YdaQ5!50!c0Jzy#+zISd1Me~bID4QF3Dnsix=0|Ub+GoixJQZ5oOlrt z_^Uqjauf8j9ki|h)}fY^3N&+BEE1ank5-F?ucIM_ z=_yD3%x2(iKUAEyfX8UhPlSc~f>nAcBqPR}hyJ;OZP!OyARUm7N-MDL6jtaC-VYGR zfJ26A1Xy=(L{94vIX~b}LmT@*8)xx{fZv?Z_c0j#2H~La6g7^k$V1W{mSQht<{LEU zFYdmBvaIhdrutZM~fwzljiF62=j8njwTOp%$q?hoZabg?s2|T?uX+mZp zw;~8H5vj%^PV`6Y5(qo|o%aA1iG;U&2%EGGe(i4!(jL)QdX2b>NO#35*rT=LCNV|q z3Pzz`e2(}f7kH`)I(-*o94j0b&I$EU+gU2eghBI#4PbBt0!geQbK!aN$Wg3mHhf$T zqPOReRbS*^=EDaK1Zu4zJ^$&^4Xn`wItt~B?EEHA> zez@mLGVtH}P|!?!c*lm&%+De#Z9&b$Xjm4Vcn|o;9sc|%)~Byv2Rm^Gy!kt@=L?WK zGUJZ3@Yy9`gkI!4?9nLkJoKmSzlg0pRwe=~^A&b>;Av+-pWDM42f!LR zLfVI8#W$b|_8L%T0!Eq-kMj^dG61-A9yIbPH2p0i%l+up2w*xrM*b1e$Sy=Jt>M$^ zBMQ;Mn}2}5D9PWt*nodg{cT9L1=y6fh-W!uyjlR?%!ikLOMW312!;g-fE?8U5{!jS z9w){CTL`AdJfs_msr)ZjFP zhJQlr8v_sd19$ryX~d#dI}ACfx>$1utZW71yq`idpn()f#X-o;7E%qQb{^yV8%h30 z)QA#GkpV5iqY9|NA8~9Zbh1)x3w+%h_LD}u)fE~aA^E`u_5gx92U``5`S25W;jWkd zH~wWFZ{q&rAvbZDp9QdGzYyaLg05)!#oR>XR%;`h z+7b1ydB6x^$cHh=T>Q0RkuHeE7-VC5qZV)$p1VtLVB4>tADNinzdcy~FUR){ zd6LV5f!sp;bqmqD9{Hvu#PaWm6|Rd${Gmji;%~Er#I!}0;2Sh*A?9W*^d$^Y`Z_Qp zGcj{xP}S}UFEJ3A!o$d^Z9#@$0r|`6|C?7B0vU>f&xu8Zp8z?&PPURWh^dP3JB^?@ z?SL>^0SDW_qN(u9j95$j29Gxq+E|agMc@7a3#S3OxIw=sBQvo8{}6Cqa74ZQa`dQ_ z^nsKe7E8oeh?(1<>Sd5LM=~QiGa=KN2e}M~RFz=O3m|C?Fz+|vDHkEL)*Za)CjyVC zv=@nh1g*q1f2Fw$EB+9@%sL?_71F1$MvV~xj1{4lO8yxNG!^aR%IBCdXb z?|p;KzKR(h3tWBynzIt0>;M{@gZFkqXa43$g7Ezq^yIH)ScuQwkx$4`SV2C9V>VRC z|NMl_%0>^y;fhv}(KkR|pM?Klg-#>h;b4vKfvf6wk9!?+YPa1Q<0g*6z5Y^@J@3d^^)kpAN&6>~k0%*KkY!{bCq$^@KG#y2m)(q6)yyv!kZ@}B~Y`On2~J%EmSVr?hF=0?IN{V=@`W>$YMNxwHspa z3Glrx&~g0%o9&_S?qdw+g9Hd|-uFb{hzQDr;0F!P&z42A-R@?*9v4OvS z!aZkx(Z^W}L@0H5p0C3GjR#jBdog|3<4j%FmCNQA3E^b1xI?-Q{fm?mfcjFUCeluf zaibUyxm<<5_Cm(M2hqtc{OiIKIC8%Xi1JX{D=7|ZU74jjr_$Q7Dn6;*m5*HEB zPn?A8cPAjQ?Lc~mB)uFW9|VqmjW}l=a&dZbJ3g-qU1Fj0+0ZO^%++il9|?GW9sWz> zEs*_8$VM>yXj91*Rny7H10^6w6$$^+6k{|?ddWwsC24`DFN+*9MfD^n)Z}*q3JM3R zek}Q;TKYQLJ=B#j;K?7u`Bb?*>MMUr0a5{w!w}r32yypQu>rnwKq^GFL^iI8k=x0( zavfmlrt&12mV3$lz|3DHC!#)K6Lw8aB3 z(s2r?cMGzipAkL!BDxKhctmEu;BQl5hlbs=<#3F9EM2pZ_em8 zWLFEXHXJ^7m3R@E>l66yQPeL_N7gO~QrrUgUIC3RM!wDiT6B}_hg?NN+M2+kg#lx9 zgCwqk9%Mt(XX2iju%y1g`OT0wNrjCZ2m7}i-ey0f_Y$;h54^^B^dbd4nhWo_5t3hk zZ$|>xIiO$X5g~m=WcK%;O#bFD|K^rd$h8DP=IcTJL+~qO{z?1aU92(iI&RS7p~%g7 zl6OKZ@=$+qXAi^<6CjU&_?!G6#C5F^KS;t=?CgXiFOr8g3cs-jQQ-e9T?JShThoqg zvXb5GZrn(M7HE+QEfr{~3w6D9y>)kYcXy@kMqO^b)Lo!T4cg*v$^VA$e|VrJB)fag z%$YN1-gjmgSoH>2_I=1kZ)55Pum)wNC&Oto$KiDIysv@ANt6|eyn3og--a?Q0!5s*&IaGB{(fy z#k}-K-INISKiJi1jBXGj82(r_i%?}J6en|KE_nwHyAO}!0M4f^Fw<3VB{_VYWbD$Hum@~`x7Qev(_x4= z?ZYP@Vvl@?Yvdqi=h4_{kion1GtLHFaUv}G9_UDK$fyOpO*0~MU*Jc!R8e>`HDZce zfS1j}$?GIeV1sa;n~JJG$C)E|(g=9i$1y`Mu=0Q4`(Nl>3VdD>KHg|lL0Akg^9roT zW304SIFVh(JT&Ki!ZLeewkpK@cR^q3K|bvv>yJ3&?8bcNp_Y&n=N}))eG{%OLZTsv z8b;$g6zgOnY;cqEHSrHS7@B$;r{JyFvmU@3Pli5~Km$t4zCRkNuOuYNI(1 za{CLb(}Wf1L8)tE7k&$UoQIXu15e~Zuv_3B7oa_c*=pa1jSezGfnKwAku0wUG?T9&SXWHZcM{p)v0;wNmz9ZiBm#GQ; zKonB-3vs8e@ZFAK?Kt5J_C|#8CQd4eK>dCrN~plsY22|D_TiuKk_KXh*s=PLKtJPw zf%U`rF`a3H^*Ix|&W!)Z=iDO5@;h|k8^)9XZ8)x~jn6PR)igl;r}l^h zG{XuVg*|8sH1M@565i`v$aEuo%$x9ceYwUMWf!0Z>!6RGc^HHGS;tJD&L;gTq^%>)b2vI)9eH1I)OLYMFbq_>~UNfYM!JWsBKMxX)J1?PT3TMOgQL zR5aG_4fyOTSi>IB{3q~HBXRazgY&ls)u;epuP)X?1ug+T+W@>P7Fu`;*Nel*mteIA zs7RF_R+m#9gIzm;_=N}eX`o65-jT-y;`KhTgSAjw%TpbS$L=wp-1pOQB{&P!!j;=& z$D4uJ^(d@^Ay{c9th1+hl8MmWp0KzVaSq>rEA+%p(h?~8N67v=t~?4~tMSS#2d&5n6ZxerZLV82oUW z3&pIr1m@&H)Bi)v@hrOu`^HSHriQSWrI_Jcc%sF)?r!XDLl7bHLnNyo{=X6D-R-cS z^YQ8={JsSkaDVyAitovdE&yPm`7uEQ^7xiYpIv`qmWs|UYz8l=lBXOzmE4601FbZTPJ~Ia~-q& z26L`JHJBHuP<9``3)s2lVdZYbn)(m&{14;)g8hNPGZ37L`^zQ+S-1_0_Y5bG7qIg) zvA28Bh*z-iV-V{c3SD1{Ill~Cuni;vsxR(66XW&RrMh^=o{+_T)J#i&ZT0vJKM)Tm z5f5-9;yS3@y8eQNG2)a~z_!Ec?}PvC0Z!2iTJ{qj|5NNZ8{y3~!i=-fwXcxm3CP$J zo7s>1oy2&zU>-d4Iup8mAF--~knJL9r6-o0RKBLKVU<0He&1JxV$bwcJ&T34U5+(( z6`s&*jPDmDkk0N!g{QsTb$F&D@OQC14$}jXwS}CHlXFvXx@m>T+6>suzS!}WASybR zJq_u%h6IM-^|p}f9?Zr{Ncb4ekn0ig@E`ylDR^QX2ccb_bCM_0aTXqM0AdlVq33+6XDr-_RZ>S7H0MWX1F!hnE~FJj$ z04u#4&UY0MS+0p!G}!Ac`1Y(j7QP{Y_vK*yWn*k1c(yyx?IT##yUPEkggyQS?R$o5 ze?^#^2+ZRqNcbmWe?M6hmx8!_3;5&nxq+}WcK90-y#5Swc?Pd@2F6?$ey0avOok?h zqn2P0R&aG(Z68+n0<1I!Pf-!4eGB|YZ|oSOu|_?9&`WsLkFg(~faY$8hjj-t=!pci zgS3~!L)geZ#*X2MVUXNg*!vHV_Hq2>0Ct>l{B>S3!fpoZ0s=|@bfRMYBDU{2F%+Gd^$$;02LxXqUuYk zvXRVDc#+%H6&@mf%6wSuaAh4q?d#gCKMzo_y;@-4u<(n}w?qgk_-%VKT? zepOx0%K1iqi%;JsBg_+m$5$R*X^Nw>x@}od*1ohA*#*UMl10+Xu5HB!@*FwV!j8&7 zlP2I$a7*7!+NZ=%7cE^y&QL$sj@IuG^O)JhWVcUga`92uFQT$yRq3v*%jxZM)|Bi~ zb~U#QZ4lm6`{FP0G4JP_?4;a#MKh>F#u@gxKBIyXE8cfjWTT3o<(3rbh*82YTW9~T zfd_n-YMSQLpGGGt{a^hAnmUDZQr@N(7S?C~@w!xDQ^gmRu2jg?pDqdgZTQ=wSj#9aw=2}FG{?`OeJshz z8JxAFcs94svBqz)*DZY)p@eE9-Q|ju2XQJxs%{WBk=&?SsdH%7NgC&NC|jtH4oV1` zWNuHaE;?H_mAcCx*J>?Q>>~|}l^seOl~s}LBJPkkwab0yR_J0GOI?(Fm35=PvJ=!h zbd{{BhRM`aNt_~upDQ+`nn_7g$*)6AwnAMitH~%+9LOyw+{I-&{_&op)e_4jv#6(B zp-M@YF^h3l9m5wH$C=&=r`b!QU4L7MrV^#iWoxP4!f1V#wwZ91j}nu(TxEdb6rNed z$Lku|Dmr&qYH$x-pNh{Z%sQL-v&gGb)nTR|#vbZNbcXQP@UO-nbyr)9C-uuTE%@)6 zzo;G1RNGh`pjx8*M}o>|%43E}zKbgK@C&tBv=Vx;yG2>P>=*lwTV~4*FI~)ivRdqG^+Win;vRjB&`J8HaEWAtm|>f1 zYo|ZOt)`bUQ>azaQLgqfE7MMQ!`|F}RU5&%g=U7z+Co~P97Ru~?<@9@vqjo$F;3%+ z)OcB6$q|KFkef0sd#(4)IeI_-udGGMQuj(GTHg^hGNBtM#-eclTIa%Zta}s{Gw=S`n?6cz zHQw?z1azu!+ZnIESj=WE$=xa$%o$B<93!32%-zM2be1%>_+7!?vTS;RVTFC1x5_?5 zlOQe2znI@aQjdRWz3+57PMRO`Nzy&}>3PjuXPN1`SEhf=D~*$Ro9tVD-@-t7qTuv; z=`-K%rz>TyD_Tf%OIMbRlT=rw7QGY~pI*L^mNQ(L{08dLUzD6A7O+pXo6Ntx-1d{^v+Uoq-X7(hZ=YnCO13PhlessqI#FoItB_miwhtr5%U74}E>@S!l|->$OnsfloG#N8 z_L}5-VN8DiQY)9~mFU~ZUZnrRO;UU*dr;J{G=ki#OSE?Ol3EDuBkEEKk^MExuVgnX zI(t=GRZ(uQ$22NzmNqDDa^WNuYk%rn*V>L>OWl*Qh4XT6l#S#*S+af7{HiqwWE4R=$D4a{=2 zfSMFx!ewp-Ib0ed+rxa;%+pm6Qs6~&;~p{VNta?a6{>D5rty{7=kzQpii}e%QeIM3 z*1Xrc_;pNMYClN{X>e?tnRoxQKk6e#x<#&h-MJAo4Zigz82gQD3Eg?mfNQ6jN z5_*+}A0kZE6DlX_&8`queErRa95)6qgvs+s4_qTe@iasrFM=RYM`tkZoyW zt!I43f1>?JUb#{^l=0S_GG&<8>aVGvQVOx z@(r0qC#rq{v`X^r16R%~9 zr30jqL?>z@6NPxuY+$6_=`P9uxlA@#UO`!jp2ozJs8=u9=$6PTDUQ( z8LD}eC^({uVl;DH)7aA1e!xp_UZJgtdL=g9Kjvu1I>$k4h`EO)#oFJzQ}9 znTu)~0}S^xd2CCCpKEH-Af;WWYkYj`91gN zh%eEJ!`>vle)oRx*SOTk%x5`gawBurXS&m_r#;IUm77}B$o)XRPH{^SP4q(t1E>6w zVjab><9Hv<0IgKN&!9GYTYGpV*ef`ed2O|JFfG*Sg*oai{1$Dvv6XqWrJd!dd8T=v zS+r!CvJ5ia2r-u543s4q)rHz479GU5 z*TWJ+PlwJ4Yg47TTE*(A5!WJOt6!;ZsPU=#&KiNWdeqraJFe!F$kw&C*8E;M*e_5M z(?)zdZ> zB2aTgCdLV8`6O@($D>|rC~DTuFXcSekeET|O{H8=WobY%3qsC7|QqhCg=>q_h0iuu^! zd85TmUN+SgaYFHU~`mHU+TuK%kQFP^_le-o0l@bivu zeSR)TNlRUrnvhcM*Yuy>DG_NM@`k(bG6(e`_Bfv*e$Rb5pEr)%wm+to+JS1CnL&Oe zkE)hyuX@D=POSX9`i;n+5jVpkE39?s&Hw1aP=k64m|mTM^W-7UwHCa~Y3v*3EGkdqXF#+||Is-j2DLCnfQgdNw?w+g#880%bXYI-*iU&(h!;)vHg9W$xqbiiDPPCJ3 zDZ5_MutZaOs*IHSDvTm2?esxCHERCS6Ix1JHJibbk2)33aCaTG#*g0*= z+Mn$Btz%J#_Z@C`c-*0=-ME&Q>QAUL*egk~IgR}=?DdDl9lu%^sOSvyPG3J?i|vwj z2@~xenjP|O_lqqz(@!7VpS&|`XNLpHXWrjz`)t;G^_RlrA76WZ{P4c$-ITYNUKKz8 z`)uU%X)h1HHoY~yU!N5AvF@ic$%FnJ%xfU6%1MlM>}5Wk{5$)v@a^E;$UfS1Tx`xL zh;z~fvUswZc;B8;abd)<+HukUMb)cWt!nQ|Yy9guROW3OJ9i#Y!dI$qTsnVGd@3Fg zeR!b1U?=$^MtKb9u6^_*xA>>9dW6?OgkbL~1PZlvc5KfhCxMytzDkF;`8Ur%n_6 zw3+%Pro)yFwvk??URG3^{D6P-$4W%Wx5{xtQ)%6pFM z#DywnC!UXj?r(Ur-9M?@!-38@7BMckl5nGua8?lFaP3|%zSJ5eaO%A zDW89j%;=c+phP04m@R@szs9u3Vz;u^c9y=z0PRw)8tqcdQM9E_s^1v9d1nV64;dDA zDRfuGJ{7Wjn%b3?FNRUtUP2j=-ZXYQ>R-PUHi%iMPFa<&#f?z0403?Tm&!WIB;us} zt8}~Mw!6NoSILvYLHVb1-{qR~OA1GnWlGZ(14x0Kpg1e*@8(PWiazF_&8vpI#9R5U z!d9hyB!`GJvOANldWKkRsLIL=N0*31Y7xDKIi}jkb>t_AC$w!0v8HhrADhPhz^-r{ zw7>V_z22bWR8{+HM_r%yz6<^J0bUiZS9le;Gw6Bnr-~0lK7#On3Mkb8=JWMrTJOOqZ^M#KkNN={ikQi|Na>9 z>qF|s->Xw&el7hm=*NlgS>Gyu8~&~2`=Fmke>qdCrXKsvroGEpn0+a~eMy3(k|LJA z$FlqZAs*+fF!e;$S8^K>D}O3qpjb_T2dwRC=Ir&o5Bv1=ed*K7$$K?4w=|sAJ{LxV zM}LevpxzD~x27;q$U|rlFgBHa_@A7x|I?_ zwjC$rB?!w^oGJTQ(xLcW@r=?Ju9MOv`6ESF>MfnmG)3Oi9i|$S zO1($-loBORouMi+H&qU9m3j_;l0PY&7jJ4u>9-q)o9|iAc=3)Fj@tIOwroB2&f zCT@#>kN$4|AN~jYxB7MQo$j;Ir-x5hWa1w49prn|yN5m85~v@?k7Z^lPawN9ifE#o zMuyS*&@o|vs)*@NZ&vn^J0wA+mkZA2KFsc#)i1MtW`|5=*2Ao{oW=PG1xpJX7gaCr zTRgfbwcvSvxBORmL|#;Gi#${QuKYsX4&%fk@g^j2?A1Zw2oqSi| z@+qiDybC!|1;s}AJr@R#|sf=TmJ z6QNaTgEba$op2si&q+;BR3ScxtcKs}1h5H0g;&CMaiO?bI0_GCAJ_tM{9i#tMZP9t z2gvPO!gMTGDm3wZ0mc>KtxBUvxhJX z<51V`A-b?k04DkrbxDiqmdL9;!*l}!={RFX_2x387hM=~oJf1m>E*yg~vJo35+Tx$e+l3YgQZa89?tq|$Ej2L@2 zM9XUc2MPfjqc?E5tK2@s3_U!ZD&^6}fxtzg5f4p5%+J%`WOzA;zbayuR($6mVkiQo zuZ4JNFyfid5j~y==4Ul9K6?R&S%CCQjS~90bbV+Xz3?#Ef)b(IRPA{70{##;4K)z-5#t`V7+t$etHc! z`gMFC2g>^z*y>p1XYB*Vb^wfm1SXlOhv@$-jB_1u`(?l*TB>BILjDOzcr~C91$ZI{ zB%lBz;gzZ~7)~t_wH*fjn+Hcd0SR0}>^K5X+aDO128g+b%WQ!r%mXfz0ffefyA00A zKZpw-2SaiJ=4m`)_?d_?+rVD$hWpJ1#^QiG~mzn2NtpboY}W35A!7% zEXUnIO?2!;%y~VGa4YoPlL`C`vFA*nP(fg{keK`0Y$C9fUicmeO|;?n6?ifaXX7ib z{{lD=1$;Z|@gkF2{7KQ;Vt*wh@v31{hsK= z2uW7M(;mka8sN!W;nj2CQMg$L5aT?2ZXD$5;qUsEzwa&9x*8d@EExC!K!7|vQx7X- z7(Pj|8CWNifXqw!dz$!evp|$u+JD_tn${8XL zp)o7)tYv)Out}DvC1gSy8!ITgHBv1=k|TVQ-=Y0 ztP4bDF!aC(sTBYfu8eiwANTGKepw3J7N2SZxw%=focX&BsNr0ohB3HaIFMQnS3HXm zM*)F|Vt=cq0&&TMtiQ7w$oCy)a|7nv!^rmFG82IYTETg|P>vi`FX!`Ag^$L9VXz6m z6+=Fsu>w39cikbOe=&klP@h3=YWm9g+4un748r1Z;0PBSRR<<7<{z>1E4J=Pz4J)5d5i8&-8k|AyL(AJ@7W-lT z&f(4;uD6FfGaP$kcZ{mz6c1?}1BdM{>`6GD*nvGIjI(i|%t zt1;KpA#X3BWUEkBdN7#6k(l8wI5%x9w~Livwe{%!5`vX99rJq>zD+Rf{8v>hG^#x? zzIdS7PRKT;{7JfFOzSajPdy7yMTGj8!TXTvGt7+%`h6EOo`O67MFoLx(9s332Jv`* zBqS<@ls%tx_&DTr9anjWpWA`a27zmD1}axl-ifO# zX8t91#C-fc2rP;rSVv>90vbRkx`Acmja^QHXZ5hc&jEq-aH=0+{BOZB`vXfo2lj3V zKED_%fbsqW7?Y ztuUS*;Fwg!Gh6`I!ox$5;EC!%>NlbPtuf2zAm^WW-HB_G+`q6^tHB%cWVGB;HGu99 z#O&LV9m?S^9!B_a?AiU0MG}NPJOD`U8mxZLbp`G^uI+$j9gV%bG49+MI_ZQ)O5tpxhz`M9qqpHl$u<_R>a9q{EK*w?MFTDe#=xtO7)_`MHgeGtEwKt4lZwQqox@D+RA zcF2mxzHY|%XXxSo_}o)r39n)*0@R{U{j#0=QFMpzBCv4?mN`Cia_53A|{{FG$)032+>O6(KgVFwRlMa7lB z!^0QYTE2d&VlJORCz|5fVjvLT77)SzKWmu67SPkcxb* zuGo<$W3D{8!Eay-%p!c3Ej6-<+8+7$|`QNKyuk_?uZ^V3h z*bBd51JA=6>frfzLS2{M_=JZQ^DiVj401e%yB@(lR}Z_Q95yrx^X0Jug|G`W=V5Vr z>_r5=Jh?hu@$O%+@)Ugjf^ts80PG3X;O$fbCv67)ei%0G0W67!UvUjq;R>6LF*m{J zauFq#LQ;Lf#GQhFdF-rD!A8nf4ZwSYFc)dKdTm@O4qn(+NUA?ZQ2`5dWsqSnQT%atkz4G3D~SJCoTeN!G+G%_nCW!tx9KNGY5bEndM zd6h1%DLwW&rClO+q>F3BkQUPZQ&qj#xVtFMV`^&0b3%Q5pN!ztku-H>oe3f$GDG4gA~ zWMwU~FO@-GWIGBWI&Wi7Q-m>G*G`bJ)#)}=2x>!lP5?J>5~#)w<;;91u|0YRG%yOr z&$>jRhWZnv`a;EEEuMpwi!R?EdaCD(w7#0@hPk)pj`^kOF}hl;HZ0cMraqP|%wJs4 zDRSpQGc?|o9s za)y;Xp{ME%UI(3RoIsLItxP?wU#)RQQIL?G+{cTT6qXjPkoIJs8D81WJC-`vdV6`# z_HO69%+Jp|)*7j;O{ z_T)cI9ri|XKkz~H>%6b=nRTTTg&nq$KDj=1op~uEuA6GFkBs%!G_hS8MYI>QeFu(9=X*Jnws;>GYUsKp2ChO*!HiJ%6l2gq;Hmgk?2ldzLHs^gDbx~SX3#yDZfuEqrC=A+ z(d*$qp^)##=kvju`Px6aB|1SnMw}yd5Da`M=kdV(;SZdGh1}0xRKMmg3sSMJxJZac zJg^UZs}y!8`p{VDPn4Ce#SB(;;r#d(;x=?a{Hr0gi#4x>1?m;70;uI|>LIm|e$2dK zTk-=1z4%SoB#cL_<}?35cqt4LSiTikm+b{M+HT|~bmiLf>-b^(a^#65gGsv(_5G)z z0@gzH6XZpQsw}|n<*LoB1zE%u)n14QJ;0pE(J@iZ4^%f`jpz@!iM~wTB_pY)^e09R zo7oB(;q}q2(1)2R zIFZ)_J9a+o>JHc%2O?V^u;XmQ&hKIKj>gHg4jTiXAs@Dj!WrN__Ub`l9Sz>=IeHB;^cJF5QET{)W7U7vU68jjSv>}xGRyYCiTesp9$I)O zBf%l3%kxf&5=NvgXamka42-%xdJjRN*&c7RDkLm&q)oW9eKv zl&P&6%Z94EL&lBO=V2#bGhgY7sJ|A5x*ij8%I~j2o(H=Gd4LU(Q*$3VHbc3`u)~Ad z5S(_3)pO8c${a=wR7FXeNFaSD{;FWkl%qYL-IYZ8Z-CkspiQ=?j?9 zT7I$+i_RBk(A{!6zY|d&2RwvR$iLuF!{G{8^*g{VU&oAAEn`V_TmFjhNqmkDRttc- z%21!;sd^`R%j^&}n*E|p{4UfMM?qW9Y0SFox+l7Ax>Q}9ZiX%%omJNAUTRxu3GG>- zE9!ZKsR!YNK>)vH(QQ@KoEOK7O9hG#<_>||T!-m^?8qe4UE4+-r+Ik8=h$dQ|5&s({Ndzqs`G2YT~usw0(684RcHi%Q#D%CEa|))X{XwG|*IlZY|@@ zf@L=P?=}KbaMCx;ud)Ak|6;$nK3yGh`ysD0UiZD4+7~%uoa3Fnof_{nZ^37glXA4T z^*6`p9|*qe7m^|FNo=kIW%pdyB=1nI@v&?YSZ0~U`FZm*ebWa0UHfO(@9V!S{n`He ze9Ewtyp-XoXMQ`=zNGURW74e|5t&^w>u2@MwHI9|-70a*X3N{l9!YArLQ1a{3njMF zG}jW@Yvp`Z3n4~#*BEP7o1W;di$}O5s+PhbKPG!4+ekDdgBYXwu{c4u-0<8mz!0Sy zA!t-16`7LAvg5@^ivAY&DJ^noWgisxNH?9YQgSocN6b{}m7-9llQwdXbp3T1C4;1| zWdwTYO;mP8PxB<|Bwc{Kk{T)k%y3U!au*`2dr`F~g;vwOsCcRdGfuSz*@C|4bQz<| z)6?jF)7mgvw_VV3lbGw&E;66|zzpL~2)%WOj226V^{%a(EzlBa>a6dh{VFsC9^4J< z@Pc?=JKB(Fd}Qijb=lt7y4tSVzFX|3`{)hQ+}O^jGRIl6tn+NEy@uJN?X>-z!{uGc z_miJAhzt1?y0&suM6VicYgCDJ)eNmQH1c+hl4`wxLfOo|;%&+#J1L{++iJTe$yCkT z?fb*A&1N;<;VTh`it41D`%*X2@6F+-PaYXxxjzJbdHG{@W=X+6CG*^Kq+QBl^24+C z{2Bf=^!?knHIj(W+_$E`2j}c5nIH?JNUjZf)MROI8UBj*xo`YhuyS508)H`P(Q#Zm zK_ljAe2hQMe&#dAS0;n)g-vT2XBuuIjJq^#)SXo%HCfq>Oi+#>{w4g#%H%c0JLO}_ zn@LuEz=>ik6GyF37D#rN{4Qvj8=JE`XGWg0u&JvPahA-bZLkxYsT<1qvb?gLr9VpO z;vI#piV};iq7JN|>@E>P4@12)U#>a3oKaGjlzzlj*)Z8Dd9Y#=IwS6&`=|^(20WP*2pLmuNNZK25ynz$*HPojFqTUQ9+OnG3>K@w>)^E- z_`x#TYm0;NzUIBg=eci`e{cmd=y9+mL>+#iN^Z518dM!gJ+k4MCS}dvwA|E+Z4uNU zq?R&llyjokm;5F@;A-ZYF6%-aX9tL*^()c8I8W1Ch@fw}+}Zk+Lm%cp|8Vch%}%!} z-_t)H`zql>$&Y4f$Fgo`@5=ViYLUJ=b@X@1*Fm2TeWt%w{+9gX+V9rc{zbc8Qbjtu zT~pD}(74Aq&Uhbv#%iJSSVdilUTeH-@HfoYyY=e~XAJ)ux0!*=**iFzIVL;SJI31A zSVtLq>gI_{xoEnnVx{blq=V$Wq@7eNpQ@ZeH-?`-Sv8y4M|C5%x}Fsc&1Z7svu>`qytOOU*m9w3U8@l*=k8W_eB zt|jU>1@TMy=E6ilKrhWW#Ivfm!{?# zIoK%$sGm0xc}_Gh7msPe^c9W8CU46Fi__A>tT5Fu9M<*K&eE&`{<&Qordgpqr#qsr zW^fx@nA=&Rt%0`twm-I$wqaJeWvjW^e8&9V9A%C1>g(9%&G-ceXo9X(nq7HCbxG|3 z^`aW)W?#T~vQU_$|w7d2ssOk4N6>KWcvuDGHzt8E$*usnEH? zPVYvh3+yh*h0N+7((ipaU-MY#{w{lW9qMwfW5Uf3v;ICQB;~8AgXCm)aPIQoX=I_Z~mAO8vPhL{d zY8OHHFx~m9;uN7LdtQ0fwIjb_`i@_HzwiETO}Y5DP1ctDiKSuEC&Wr}IPC(9*Tt~3 zob0VI5}ReMWfAfdikD|KVXbbx zG1)ZVT#OE7Qw=$~VcJpRO5rtnZ$EMfX&WS9DZrsHTivT~l-3FyGwDO53_vLoAcb8%;T;U*>n# zB(LfAvtE~M6D+HY19f-M6MZ0Z)sOKz#16XV#!^ciyUcrnZ(aXA=&9rOY2c*123zE2 z()8YR(MoyOs&FmjN3|w(7Sw;-cw@5_u?Jf1Z{4Qt+ICF)rfqjLF;`y3ulrMwFz)!G z-IwOPr9|Rugk0x zY8!Os7UmmF*lrS+;mJbXGxkvi{x?_Pyp1-8*$Ya~BAE zGb)7DiYp8+tg+6^zD@iF_>J@#=18};HP0}{7^WFM8r4_>lhNsBLa<-xn#x`gZEEa| z>|Z-3xNG9^WiJ^wRBnbw6b0oTIy1Sl{WsUiNSLmrM`IiK3FC z6>e6kVCQPejMvQ#4R82)RBKtLYn{s_)zZgwAAFjGovu+>>q^Z-)lO7Qa%|I#RE{k5 z%C)8a`z!0mq110#Nu~4YeB)KWY9Ya42ZAR$(=-F@l{{?m5CN?IRV?|8j%-1gb+zo)|0pyFWPO7lbRhWdveukttIPh__`Cu2$*shiJ_ zwYPXx?@~xd?b|%vyP|7hXAfSsJ%5m%Ey}BOYW%zTq56v}Pd53KHB2Esl5ZQmtoCx# z>pE`+y-I#r^tQp*25H@k&y$Zunf{RGDwnCe;m#~w=#D3K;%BqP5#j7<-6^_>QN=a0 zYi4}QTwD+@U80V$tqL4jB{uSK&EeJk!lL|Y8#<8%Mej3L|9ScQclx9Jx9%fUJpV@5 z#B|>5M(uxvX@Jfy7**#9Uw6mi!UA_;c!|}0PWF^|N34+bc4>-d6m%?@Upz%}fSkg& z*IzI#G@-AhkVWUp7r9);Eel^2tStOk>?)fkDrU`NbQ+*7WjhA^j)Ygbq0MgLUXmc>ib z-AZW>!XM22H@b1=3ATG)^SsVkSu z?u9*+dc#Kl5uvX_{emQRE%&21I<4xD3d!ytn)I55k0etS0ZM}C=zd+8mgAQ_Bl}?P z(!%tz3UVv?k!hvAFG_XSbQjU1kmg+64@$?MzXg^9_Qc3w);(F~o?O)N0|4%iM zUQSj;E%qXkqY}w{Weep<#R)~G@+@_X8Okn0R$oV)BA!!2QQc(%y+<{OtAVO5N7$Q8 zDp{=ffzwMd@j#KI98SiNKb10NB2h?8QOs2~B^fH3+DH=0Swt`SF4;p_1Nk=Mi(-UQ zsXV86O>8Cp65+}v)Jm0EJx_=cgV0y~f?CbBP*r0-(>G8p^euIV8jNeqr~1+LRcWk> zA1Qnib_&n={^~^35K3fHasD&`Kl4;NIs!D$U!AP(B|H@k+I_mw=xp0e-$KV~a}X_T zE=~~>M3d&K=C+1|qzAz}jzlNlD#i#?r1`YjYWZQ_XzpX#V>xWSWm{>V3-58h_fPL1 z=x_YZXTI-2-{HOzAG71U^|0xVE(yKCBf&UqFZiRw=~l6Uu!`Tv{l%Fo0#S{joRgWO zdGtX zpVHE`nVZO7k5o0HPbzE4EmEyykR%6Z4~C4P!Vw{&6w_t?(%0xnpD#N^tWsQ43?K?+ zWs+F;E!TXvm$aF@k0MF=n0!ilFbh3ZkABF!LrhNu&+R+cpZ&~ir>mo)er=|;YCNRn z25X=e>KaIZjeO)PsT=Wo5lh{SdZ7J~nLY#>)(q8PXQOAZT+G2Pn_BGV814`%UYhxBn%;V+-VYsh;{=;} ze|bdkJUvAD1OdgJj&64!|p#5Z|g`8Gt8{E177GGz$0mud=5-%aIt<-cSDx>U7EJxjPD9z(=*7~h)< zWT$~kJ`*|V%JNG8rHo0XMJ7DSolpmXO*>005-34~yp+GF{J0A-%>Iav2lGW>`03Rf z)hGEW;#Bxb*9^OjJ&acj_w^lNgP&_sH5W8l8mYFO_7A#tFVZg4MH}>{o#skbUt49{ zbL&oPsMXhc%evWC!JgoV@*e5a#`lMBHh8a7{fd0=`L^-d=BR92VIHL4D5}Bhts=e? zleCw0_cbPQv|7u0>SOmsosj)>2)RPu)IGO&LBaEal|^(}8|hl2mQt&nL_C(YkX4Wm zQ#_~sBGSK{VaP>Nb!kjt-Ga`A!6mWo>9Rlai}Go*)zX$yCv0`GY6mYMd#t0nn7*ty zDP1R-Abn3LsXnT`;3EaAn$vQs3e}$J%Uu)-GzHoTnhbS4)m^fWB3Qv8*0z_~q`Jmb z!V@VK`SKv*o}vj=z`SMKZ~?4~zCo5M_9EuGn3AFT&R!;$s;&%|zmmLlca{8>&L=J@ zr;-E7Rf_&{nY5~elq{Auk@G;~I+78}OyaHVfOL}7EZZXQrzleXB1cp0s7c^x{=?|l zS?XOvH_aNbQrGcIxLK;Fu)89-f6rCB*(flISkz74!!=e{h{(uY*lut7EHWYv&bYU+8G(yydO+$@kgso8fEpKZU-pef(?r zvW}tF!-m=-YPA5Pc%VKZrf6fdcf>V9EA@7)nL((>5YL<=ljX&3Wl2)Om4bdnElTT4 zKFE_4X60C7rRtOd&oXP0bsoszVcmP!UnOQjp- zBgx9_3O+?#FCJ9SXO<{jl1Z*qSD~aI(SXWf1_Enut(uCex#^6+$@o8l8@*^AaL1Sd zO_qs z4=Zxz%Vqs!8L|n;>U&H6B$Jfw6an&Z=`2ZKX;WD}VurF4=_Dn}y+l{JC>t*84Nr+C z*HI_vY_M-9(9h{;u$>pE1JNa(5I^#()OXq0sOn-;U5cunv>c)`U0FvDw_ry6AY8}S9Djj z=d@R}ceM)LXYCnuDp%n^LGwV#Evs4R^wpDi_QTfAo2w>a85 z?>P^6H}d)9^U3#|pWI*Kuk;(}P22Zc+8Uc`Cks7=aY7CsFSvjR4hHTvUcCWKk+Iwf zcBASJ^_KV``LA?$(Z|B!#lB^iB(LR>is8U48p>Ws+DNa+z7osGmGobVSEk7(xsDer ziyjyH6?ZS~>mnsnB!%u&cN+;STccP=kL4(S1z&^fLQ52@q%GaU-6y1nh^?fInFVg; zS>_NbtAD4btNL-X)OXeQx&5kFxT;$5ftaU!KpL1;OlxL7rBHSt82NB{gyJ$ejM>4? z;qJ49>J4Qi_bGQM-;uki*7P@O1^JKSmVByggG^3rSJa?pfffCLda0~Wbdoic60+9v zwTf|MC>=ouQBRdu6+4I!WJg++v&c)xK`91{3UQ{eo7or=iuWfLerkO8Wcq?PI zSh|_Fm>QW{nDR_z<_yai$eFS|z%JXtR>A9@eUS5tcVpk{z9v7T?>V1I-rby}eXTX! zl&Y6$`tb|E*gwHNQG0sPw-@(|7GbXXA^VUyf+%>2oRgk$^(cK;e7yK!$&j-D+&82~ z^t)<7e3n&_J(LcYj*wlDU%(!fEq^ClC0XXGUlvvRt7K{EgtF(ZO!rZVS@ufaMv+SP zWwgNdV%SB@3-UYBMmALvB|1#=!4amyidh4gTNB5saj88p~9#Ml|$P+md|P{vUIqJPk8)IFU`-62nq)5&94@tM>) z)JJcE`bEuD(^I8`IpO0>xuN?W3_YvsDDKw^$#J-#tsHWnEI40*^@@YjBX@2k`P zqxII^*PYUTL*MmcLjfY*fyP9`cpzm>^>=j={Xk%6*9_C~NwrC7+HC4<+HHz8FE`h; z^t2wZ{6LI;#aQIvKsvZUJRaP}-Ga(cx^E!iDZ#G~4 z+o;>DYpQ#Ms8~yFW9?LJzBWn6=*R14>gVb6adzyl8>j22YY#knCh+K$x_LSuoxiRh zyykRh!8Lt-L!f~%9M-?mCt}~8VW@1ZYFuX=V;pa^8(SJ3#%ab^#?hucW4bZTm|nRn=I*K%6 zHqj5?E~1g*u;LTC<{bt4JW*MqY)%GKm#Nyc5uF)EpL%SLt(H>kBIs#9Wk0frY&d&>ZNt6>X63B( zj`T8&k##U$9)o9roINZ3ApIp3vO%mXJBO9Pm7XQ_mA+?o0|(QOX#;dZ52lblN>8GX z(-UAl+>_bEd}KyRe=!%C6_BL&i(W*dpg58NL*WDK`y?ig>BbZ>pP&}vA)P8sloC=L z9{oS)6yHG|b{WVZ4($dB2{#~HW*S*f zj)wW#iC#(nrbB@3SjogQ2~0;O299q!td%d(Yv`@?RJw&JTExs|7BMH7pUiw_0MiN1 z7N7Y5<0KBwm?u2G<<)nBB5gfYN%~X&qk2&fC?Qmw6_BrIfDz_T2hmb`7pMq#!OmQ)Aygk~FwjafU`!r?iqK5RmXSg4HwSd_IQ1S9 z#(t7_$k(JDRBz*{V)6_4<3^Bm;FNe5SlyPNz2KNQ0T|ZapoVx4{Q6GtxT*)@@;o>k zz64h0FzihBiZ6?4$Tu1yUiIHG-h=i+lVQK9Mt#tW$Z}*7QY4ZhKSUTJKt_pHi1?y& z!ePRN!lAI{QHef@I>VkN9PvP^MH!+UqEm3qR*Npcbt^@Nz=&FpTt|9A9-$o6eO_28 zdJA>Ms?Z;3B2*Smz?rSUzQWH%NW)nG4y6=O%-#R<%AOBiZfC%wE*Qwt7C!zwkoYHn z%j^Oy>|5~p4FJ#ITJYQbOQ^_qL~HU35dfKs&w$Qvp~vn?3V_)^4^{s#@Y^i~=i)Q} z)hGslgCY;oiY7qXhJ^eMtkZkK4i0Y{fq3FlVo0ho!)~`9)rHza?SMo`cR0$kfU_zm zTC#|yk-6k!IO55mWgHG(>uX`1wi(XF8c4ew3ZBcWfpZeT`929h5!6L^CIz$0FVI%s zhUXB}JxDUT0kqf!c;q|KM4o_uM}eDXD%9&H0GGZPIQJxQ1kM5_K@PqjoZ1Rtht$GM zodU8l2?%2kpunIB095aAsKjJ|mem1NYwMuK`bMG#3Rpy52K_=i;t#OVQQ&y?1GxNj zygRU&&w*<;|387w0lx1WXo)6+$LIe*A$IUTueMI0${7S+|1G|a$^ZGD?*K(!H8}jH z0~y=mo!8=Ay#rY3$)E>lac?^Z#4ZDspK-tphY(+2)|E=e!z(QN@0EhUA?*XG620Lw zc8BqH90=R z&jEiqBdFevfnQ`S@ccON!8ajOLPop-I^O|E@s@<2&A>^!6M3N2YayAJgL=S`91nWD z2Qa_mMd?@1#nfY1_pl-km(qFrk4DJ`M?4e0I9tglsz`c zR(OWb2kx&7ZwsvSV$fIwgI-Jyl{{zAGPDMDNM~TB?*d6a2KFL1L2+>ueE+_|d-?)D z)CR`dd3gPIF#a}!rl&te<4LG6VFfNRsvATYtNvbSgmUqJg80!*OW^ z=Oz@+T1)!rcKC+pL0@uS;s=_QWiYep;c;(34^{*`;X@)l3rf56Bt2X$LZ;!Fyx5D$QcVgXR(H^8s^ z8>|pc0rxio&H?xf;Vz&w;6c@TIsA4xII6>$1JiAqq5%m)5`?|+(t7Ojm5JWYGSoh%CGt` z8m`aFFsi-b)fU1}AUvlf5u*=i0vqA{wtY*=0O4-} zolr~C=T*2y>%aqd4|rjIg*(b_7|RRbQ*?#n*y78*0W>QunGrW(K1zX=;ySoqKH&pl zR4j-2u0>Zl3m)H+M_>fif&z}IKKoPMU6ea^;?`i@Stv6g>>7adh3$JsJ+dzURv!_ z8C#WH``*$|G?7+naK}aNRbHdLKDmh;-)VX=CCCf=kjCiRR@Iu?&5f(<_eHzOO8E)h zEYmA)g#pZ67w6rB@EKxN(uy(`{EjD(%u@^s%J`)}g zmLO-vQ$g)M4!28|QzY|**-F2LetaU3%GZgfzJ0W#XaEa*Yg@yupHzB>q;Yzr7dqMMjF}kYCx~ zin*%OO108oUd}v_+(icP-8m`tX`Db_fWR(H7MIW!itXw`1tqN^r%~19e2E?z#z*<{ zguT#7;^mSWGKhAA{N`26dv-San_4fv%)f5AUhiHVSGujhy>NLczq+7qy5%!}jO3Rr z#njPrmrthq7;}3~8TC&%+xonYs@hVasF`B9BrGADh6kv#P)R9vwqWz@K7cMTB6G;D#_2 zs$Kr#UBqDNN98Z*oTX|Rd0WCu5M|R_vMqn??#K^%pgfXorYAFY;Lu|6?|hB5!Sai9 zT-1lYrXAvtZJK7TaGa|zCjMACwb9j)bv-R>xEkI=ZlcJ*NDX&976kc)RQuLCUDkkS z0+*natlYqz9gRT-62Yn$rt^+|=2p5F&^rjAHlrh( zhgCRMwzmw!{wO{=jrMW%<#`fr$xb75XQg+=cX7{!FD;QUG7i`v^i zHJ+_`U8m!^;pudH*;hrOYNF0!c5>4=IV&dcK2#1XF;xpKUY3XTXPZzoLUGh#j@xPX zqfY+1U2>X^6#Z(rQX#C_Y$HV)q1nFOI)=Yka-2P+*~0rST5Vwd9hE3c^NvQ?s2Wez8@pVg-8#Jsjh!x zlVBURL%2;a91mBvcUk5=(c~}ktv*qjS~N8mDHd4&QBw@*u3v$WNb|@x^_9LAOlmq& z^|pLWEp1hCY@7q=JDIa)ku+9#$P#C}CwxqNqX)z8W{1Mnx!iAy?-rv}tgZJcT9Lak zFS+1fiEHyR`NjZS?Az`OViSW6##Q3m91iE3#joPVpO|lJ{`9PTCRi!+)HUmZbyJL| zoh#fd<~gcHrad(VyUzWe<#$7E)v@A~qHopP`Pb+WtR&kIQ-<)zuzY{jCCN zioxG$_d3)V--4O0{(n}uDDj?MNqFbD{8hvC*uHRNJF65P*s-0p#Cz+}# zbXZ_|tp9BItM8{=LE6y=d`Z*e>Y6$gCqY~<3)Uw&oHNXn#b5+C(~@cV$Y~`!iLQ}E zNxRDqk|)u-=v^v~Eg{SC>%e}d674}@ks>fQylpry%3+1_BGiSz<~#Tw7^e?&j#7>C#PG4$lbVk87A+ zv7<7jiR9FCWTJX$rGBeERdG)`2KX9JYzY~y?4~uTRxq7#g^0^BG5qPb>IC#^FB4mYT{xFG?fBgVM|g#HPy1}ac$^2x*_5oUcBJ8_KFWB& z)KmL_)`?TFx7Z5dG|o@XPh^mlBGx^8b@7}pHf{_Y-WCwE2vUp59HO% zqi*4sM9$nrR-LUYzY6__%V2dkM$!hz^_i46!-wwHciB1ROm&K4k>rT|WzE(KPW8-& zM4JqWWbBF@)kobUb3d0HV;VaVsj>BL8r5vJGkgR1xURx!(v?^s#DqeYd~4D zkSY@=^FB6))OD=i((K3Ch3;qcDqNRovYKNIjB=iIm1HS@sm+HwS#U-;5dB2`R(~{Z z(Jzs26d&TSP1*HnjVjJ;WH@nxRq3}lX5c86j(-TS4l?dHHdjTJ1+} z7UII0*e7v0k_8>jS3(^&ocu_&!~ZAxg%nBFP~KD`eUP=tk1P0!?lK-_M9X=B4QzU;i$n` zBp%r*Oh7S;mOCj1u#YH(qzxJ6BFgT*h6bJ^BwSn@_|F zdKZhUmTCEV(hzUFt$hZLWPQZ9M7ufnEyHaN!YVwNxyQDbw^yE3ETCnu1DH+nsCJIsgA~`jcoX3TJ)|x8Xpx0Wah7mj@EZhX z;Thx+nX7Qp6==^ZNHSD-&|YOdYOA#U;Die`lE17*c}f0;DJ90@|Ik@NJ>M*xAnr~Y zm}jh`a-+&i`GxV6d`5&&kN=2{!L^_`Z;N-4T!Wpi2D+4o$fclz+rbQB-D#_MD(Z;3 zW0~T!lE>6U=_>ZF^p*6qR6wPn6}5%`7G^pV-2|8?l1=H#wyn`nfNfl9II2a&6X-y zig}WQ$OMNux12!`14N2^4o0R@mb$pDoWg zRl=6F3#nSAPEw^Pqm-4h4^k^NMRE=MiF)I6$QY=rW-yhs4>Oo)qG|Fl)?b*&ujPwS zNC;<&*m~J{MZ9XEny>Dt*v4c_vXD0<6+-Z!{my=;3ZV+n0JX83coo!JkBa|+4(%LI!;69*?GvOz@|k%ibCvIwe^%5h zrzy9x;oxF?PY@3(vu^g$yz$6E$rqYp`^mi6V#WbF4#Q}SQh*;{2VybpF{^HLgu7cpyVh=00&005@tBzDDI2=f^O{=Ay+t6 za7Qp+B*muV`LI|2C7uTfNw@H6P#G8^*^g1^HuN5rh9zR|;(ws&|Aie9Z4>n6r*lSH zn=SF2YJn76kH>3&um{L#GiD$szA9 z9C?KH!i$JZsui<9dSA9nnWG9-RE4(h;C<;Kh=o5I>O`xyxpaQiL)B~05 zYG82IvspmTO_kF0ABh*XRd|f|kJAb|<+;4B!kuV$Nn3g~`&hnAc|egM%VcUP8}y_x z@d-$dHedsQ2t0$nKzm^Q#3^_J@rS$%9*U!=kHkKS2yeiippMvfaWGLxB{Mz16>pNX zfqq2JkaPlHt$UJbkcamceD<0_IXi{X)9K_vI0_q}ny3G-N*e*y)J5b|>Ljg%HGT=y zktTzy!UM@;Vh8yiDsXe48-oy!@hspLZ-{60mA>8K{e$$KwYeQLcD))|PtJp}Krd!E|Du&B{O7~C>z)S4`R%)AgGgQX= zgB#R0e1rH0QX}}zTgpAe*>1mKKg8kjw(`@38_-#JJJNyKAv>(ps>i7JsfrYC@?Joy ze-JN3_`=EjaQ*}SSz#ISOZ<|!PbDxTr7GzIU~|f0&LN>+q-NGIJcg!y$ZWh2n~o-m z;siT*^SM&42ROlg=l2$-Af%X2+@{_#1KF9-FzP)587*AQBACAAs6i$_UcNXtOs;LMa!ZOFag+z~^BLd|L8` z=r+O1i`LOLau9igSS1;TGvW)tw2X$X+G6Yi<{+*Rt0YgLHopZbjE5k}r8Rg096267s40Z7Ic@2@oQ7^@*J zk`B~ail(Q48$blJ5&CF4=#RxPk3a**(08Z+Dg@Th{ozVoicc4}!A#I?8US4)EqGa8 zz*`Yt$UJHoy%y3M55nU{i_=g6Qv6>Ju@C|2n&dSx8|u1eh`o|r@G|$rE@RbVGohjs z%pqw!8^sExQz;#x#_z)%z8ftD<-j#Kb}e}^Esj8)z`NrpkR^QRCY3l=T%a?tOHvJVpd;Z6eWvMz zp43p&=IV>H@MzRLhU0OmfrS#MbB14jdZvI_d|3zY#RJ7-4pixO zgO|Wt=*s4TGs{?TQWyp4!X2!8Z_KwCja zyDRbq+!&6a`Peb>aa;}~H5$A_e^Je#8#@KspC7XGvOzKvdr-Qck%N!vDylQJ2$+w3 za5uI=kKrUfN}P@cA=gChM42KlWGbq_4g-1C;zU;g{fL&d=@v)FQ2d9upZGkMj7Ecc zelm1NgGC)h=a4m+3=fgqAjW}DL`$aVUdSMw3tkmXbPPi<$LTc6lT4Gi;FZ9V<@k3yGufcmRhkk_|9Gn`6aL7sZh0cF4Bo4)aGZ!VA1THbEDqrSs!Y93&4>=V%VB zVLX}dutKEiQdn2DxXtc@<6;93uT{_;I*B!+ZdeU4F*9JSofC~hyGRD&!RTOAho^{Z zk#blOy5PNlJ4}FFQ44rq1j6}h#D-zf_)bV?JwcGv0(v8j)2pdYRB!SGF-H=Jzr;$h z1gs1wCY1tg8m1SigS_$nG^Oy@U>49L%p_(4D>v{mB(DYGYs> za2+~YYoOEqocuyiNS}Gbyib+%rH3FQ4uh7pyEBlu|2^_@;Y8q66KS8g2m-rOc3Xba%sGj`;KbSDc z(e#vTAUcyqDhe`uClHS%kcuTfhm;GC2v+mHaaP;E+3r|}SeIF8+hp4oTcKUcodvvg zYvDYRJF*vf0ICQHq7bbU-W1Ff)bMZd^LTG~Q~9m=hxoIBUXnncgD;N3^LOjS8SN9(QbuRhLj-!KW>(M$Du{cBA( zRj6W~tfMrZ>M1G59MD+MYfa(4wJ)_ju}ZDA&3BqsH%(~rZqhY!8#5Zh8~*<27W)ek`LrTdaTqa>mW~57OJw;ahkUp zt~OJ{YTTjj@Idh%)QsM2HfWL=DwIqHZ`@mAy*LiDAwfuhC{PGaEc|x7bnYt-%Hi9i zY`b9xv(U2H(!r8unQrZ3`)mv3bO6=IY{6pDGvorc7)Qt&@ZCz5E|kd>Gn57uu3o5q ztL~-wq#3K3sQIDRX}+nqsQuJGf%CnpEKn57F?l|)rLNLk*!gy#4#1W49XNwm;9z(g zxQRW`SN#dy@z&5+T?XqPJsC%SfYj@gR0kL}U4b7nutlJ;yCPqyh)~K^p6b2oYnmTg zfxf39+t}7Y?)b>b!8Oc%f#)UfFu%L4tU>QX4~HL#9M^7c^rvWEduim&5QFbgCxvRf zxXQApA}F{2x43sNGqg{<(_hHQ! zrhAUK%X-)KZtvYDyKQ#myNq`lZ|-lZ(I;sWRT;8yCWqK44n^h&%)FhP68kOtNBbns z5iY^+FUS%;2hD6Rv=-*4E~pwb0hnMk@44O2n$$!$WYxB<5mkS!+Fg}Yy`W}A-MWSa zO&Jy^dlt_w%*UWYO>L0I$d4=Es$A5k)t;Jl>dUG@%1GdMmwhS1fKH&%)!GU zA90)HDiJ|CQc9@o&zF9L72ZuYja>qMMxN3HCLc1(hY`2&RZnML%K<~w=z4|~#oU;cBV*TK-eANKI~EkAhp_}z=!@72G`|L$CLuKovKLUQGQ zRChE6jaoHd=1p`|Y;f!6bD>pP@S?EHHV>kn zww>ONY!}qFD3TkY3Ka&t^XlsCt?MC8MkZUVm2L&6e>Z038((SW%8yVfn2rAeikks7Ra1g(HMfIc5>k!c0}Y4*?<=;zj(Mmcg8Ry*wWKutYdF{Ny`g)P zrFn_%DW?ZNM05!?;!lXB^g8Kw*--f<#WdwvC8ms4YzGI5JM3KP3wj835**jeVgp(r zR0}5aPIJQTr)*q%m3;?y9{;e=gpL%eVefPVUSka#AghDb@GaFSv>iO!IsyuuD8io+legKXCqV)c~TBv!Yk!xpb&+AU;9~fdx z)6G|$;@qk{OZ~iqcSOvO?%&1K>wUlS_^AVGKS@HtSQ1TYG}K(_9NO4XzLkqD5#sa z)m)+2iH)={(i>oiI$SwYxACznR=a7?-+ngU(+_8LlwHmwz z$8jlPS9F=!85p2?SW5t71%7ldK$pEtxIwr}xK!kbyaDz8SB%8>N{pn84ws&lT~(B+ zR%(R0MEz((n9;$A7!wUwbZ0c@%f zstI*Zn=)*Zc~3-{;viDMIJ3`WP4alCZfO;%a*M1$R>^)~N3nz1>8uyq8dOMf*g>_fFcbn$E(fyd4n`>KVv17hNoWm=J*Jh*B3+L&sv2NqsJ9`}Q zoa^1>JD^ovz{kL-z-|71UMlCl+7r|m{=B-J!hJtGe)#vI*ORvoJ3QQ#-sK7L;_Tb3 zPe*>m=bx=8YOLp(@b%0KMLekTj_Q>9EL~6ic)f$6#87D*VcKqLYl<@Z7zq7Pty&YO zS_!^Le-&;@cU3R7T02MA+u&(xa5&)@SimS7}Za7nmRiCQdTCt&`uHt>Atg4`DOLbhWrS4h1TjR$jrA26~v}b?{_PAi6 z=mxp~|3iGC?lb+_EO{^GKUJElST$O`Ky6XQs-~#6spLGCa6G*BvyvBX$5S=3fvTd~c9^NQ1l_ml4;JR=%_ z7GjVcPvlYo(m}GGidCvF>LBeAU9Nt;A;7rS_{Mn2xYyXrc);*n@26j&V{}WkgSFn; zcx|Beh4z@1)y>e&(yiBB(Y@8l^kpz7k)}L{%TBqjsh&&xM8V>SKJDAain^@mvacf@ zS?oL1@EW^R_3FFx(`T1O$3piW-%-0QVcW;lLpxXOcRRWNx-28+d;3z3Z7LC|K43oP z?(XB`SLZj%-{{Z!r~3y59DrP=OCi@oE(Ses_1Nczdz#ZC;~1Slb57M8V$_{gA6389 zYqS$#-dp4{#Us#Xrr#333*O;weN3ogwRnVeeZ{(*;a^=dpFK~1)bC;3!=aC!KMi;( zf7kf=^6$O{11g6!_2du4L!@D(<60H^z42M#*~N97 zd8a-@bzC-+!6}TmEcq*OB1w9dG*aH6Y|<>(pEMSm5*!Ssv3f`KCDtYxA}qG%)m2yI z7h?t4xx;d5|Is;VIbM0a3xbNrlqsreYZXn`ZRdF@qATLvWKZc&`EoU*mzZ+QkTut!-3yP>oRhl@&>cGZX3Epdj#|3ZSYo1S)T% zNf)vs)P2&R{#OcmmugzV+y{pRS6CrZ(19&b{7_m|Kh<@bYuZns5S(Q=Y~(q7GuxaZ z-1>UO`acZ*9kC#KLl?T2qR;eRZM%$$dg3e9cIAf_ug$7Xzi~O_g!O=Q?}^(XG@pk6ND2Q^lsw41aCI|@7?2dm@tqs$t&rQQSm|JO?5-`(rI(0cLEX9|=nxa2PC6D6vZJ8l`B`*UI9YItujD`B{ox7u<-85NXIzx~+MaG(Xq8x0 z%>_*%&2udatZi(0wp#mKZWWiy!+CA_FNI3X8Bc|EUM4e#T`4PK#j-5fVfiuG>)4fB+KK#eB*Krd~X?H1UXO(MUF6@;~`H^J2?Iv9j+Vz3YP9Ded2Ki-sNS+|lsz=B^`Q=9 zTz+`g`}PlT5AGF~7j-Qrs_Uy>E^%&g?!BhPR0dsf_=YX6%>IHu?tkgd(WJfK)3$G) zzx~>dCA&fnl$~_A{`P6F&ujAo>sJU@Fw?ZG;}Lf+pXvUG0>_1{4C6(9ZHLFah!u1? z8zXAFE_A+cqVrd+OqNOx!rMVlRt25dN)i-d@;7QnV-F`6_YALU?@nGhuDHW(rHSz6 z?ye0jGG=f6>hTeM_xbICw~sQb-#z@`oHg&W_qV2>Z~qQ199D6@A)LDt>&HA)l^J7Q zFZj$4;zVp|XNZ{>YmU9u;d+$1HP_$KZLo2w@*EwG-$MQ;{3{3(dW$X~o>-RH2ae1Z z@-|eEx6)3ug*+^Q>Z7QTcg0>~>DXM_*aqgUxAiXd>uWbu2UYeg-&-15GOVOSX;OJ% z)uj4=mRep4HlA)&MCohI*{(yp`uleExB3tCpXWQsOW?M{aipP9y;j~$I*!Vg5O^@w z73m}F%unK8vGujoG`_7L0lQ>d^|b28)oW{f>b})iHYQna+lFv|@s|jDLW=EA$e2=t zc66>NP}Cln;MXW7rX?A~M4Dl*$buAM%5+t{W}P-%o2NOYK{egM-RF?}IOx)o*`87> zD5s><7UB{3nk0#i@B_G4ZEr2Tn|V#U8u6y#&0;HNKf)QvXGIUdDZ3l-gmRG%l)ZtS z&kUtZwM?~1RRlF5ktR=b9acml{Vn}heXV|tK2O)A&DIDsey}Q8t^BAkgAcY5 z0Pq4%2Yr@1MS}D7D(DZbfSyt+CJ`&eoxq8xfJ|dv$p)w@wF8Yk9bH@#J;(XJ4tNmy zq>VT_wNpZmZhh~^PaY^4aK6v%*z3Wr4x`ZcvaFB$?{zwR_TYtG#vMtity52J@4vHV zZ|kGn3lr{*eWUm_u(YV@ny8HSRePFFxV-e*7;rvpX**-*-#x1P1jKFXccT~8h1>RW zprd;L&6eGkK@6M2*mD^>EexG~$@!)26Ptt;uAY!s0nQiCK}n>)aJXO*Ka;l{ zSl=65A@>evB*&LCk#hh%4?Mtw;~}h}nk<_d&(x|aHO> zNl9i&H>ob`hnc@Rhr4(8Jmn?w{^r%)bEW$ymkW+TraWDo`jC7uQz03LuHpZ%O>W#< zy|!#o(YySH+~STo=)BxM{8R2`5dEh>9fcR2QkAe7$mjrn_#WfimgM7r@o8 z(0QXvfXfZ%r%qqYA55bRnc5!eJ&GQ(I;IQV3Vg)(kwd6CbZe;&c7)3yWAm48mcd}k zFy%W$n&&vabV_s??Ka%Q%X^OB&wyPayTc=+9<;w0vp+VxxLN*NKhn9Yw>J1? zq-!j%XLQ`~fwL1z2W^cv_Oir$Xr1QW$9z{Mls+d`gSXE$aw0G*@7X!>3$Oy{tXioG zQ+<(h+5N;jNp3*YVui zvc-)<1QArSTH$!lb3?$_uzqcKbm-U7C$?Qo_x6EpriLW@fA&ONgB*QK2lb1!PhtH% zQ#OtMiq8`{ab19?PpbJ^b*1WlHBlGP@T`flD(#sZAD$0?55J1vlW*Z(v9GhtZVau9 zuI^YlsUoU!eRVTrN>1Sjg!LFgPGID+FvVBpZS@lE68(JR6^HkZ$DL8vm#zn0HLfe2 z>&+I!F7*mFMDmsI(LA#%z36z(u0LCUzWH(fXNNzZ{uSld7Ei7)*Dh%k*&c8^2rr^? z$v`;QPvrYlTeZUtIVP^-KBocB=bRgzb~*NRSZVm6kt#FUcJy3AAn6F%5Ce#Gaz7m? z9S;s=FXcLgQGS`d%cN4zB=f`-$Q027!A(%fx8j+3CqYFY#ZBad}U|NQvG&^5iajMTl>!l&JS0#8y|D8Q%u+X-L7{V*mYsY zMQzsjw$~3uH&(p(TzmiJnXLz8yYxHqQUkWzb~x?cx-aC=l;d;GzrN-69QpJqr>WYV z|Akpy%j$PEVf`@E$Z;d_5!}QV{VThUk9_X8$*GOzCle$wfEN3hH~=(m zCBz)4_&g@wO2*-R#A`4GI$bnN(2w`T?qyxxR8@bqwr%y+%5&x2OFtBD%ys$`@%=`Y z)4QhEQ(te&?EDG+J+6>j8^XO!Tu==%XM6neFA8DXtZI8Onje!C;}z2seW~4<$jmTh z2pjOor=LfI(*@&2HJ5F~odp*x+iIg>_prK9TG*jzMrqf|d9}($y=9ZFJ*S4F;3jiI zIYst)K=-V+{j#Q7w_0PYTda4jr)+!d1snx$0so00S$GIk%FSpf{+O7^)XN(+mrOp+ zkKIY{5Z_b2zkPOjg}Zw@%T24)I6GGIUijVitD&sQue_mTQt^S_3>D%k3XsS-JERRWKME?@3`L4 z*HLc1Xrdt(mIusm9^II`p5Kz%ZCQ;e!s(WyLx-v4r1q;-COpZ zI-GuL{*^lq`n-Ak<7jba<7lL_yu{(Tk0`vbWA{GT;2R@;C+!x7B0!@2~Oy*tp6+rn-4SvHzqd})a&bq z)(L9wRawiD3(Noh{XQzIQ>M@Bj<2_5T0YhOW{b47$Lx(*u5^zk!C|;-vezB|f}q&2 z*KL?~yP~m}12Lmw#&>XUuZeOB?;QNh@2vY>2VA|43Kp%mrq=E#|5@x^G`py_czxN4 zN~$KZE~D3X~xM?rmLHIQ=o%bylT_eM~rEE`rB)&t`G`w(5x$ z;?mke=lsh#jeoPU?SC$356?jhJW8Hb1~p{aJ(0DfvwWWRoT<)v zi`zY@?DTMK<&a?Pq>s_gRV|gTkb+;NgeM+_Y!P}34)MqGlliFvSD+mGV=Kfs`1ll zvP)05h3@@5#(O9{8290>AMb zvun(*j9vC!=$@7P>JNFG`hEG?{a$aVU-QeR+pdwN#!5e7yF)!kCNz&cHBLKm$i#)? zuO(@Rb?Z-dDQxp7V7TWyr$*y@U9#q`QX`9?&SSu0*>W5D*R-pwC|_71t2$njQNN*S zgmsO54QDrZ7Py)Wvkh-fuk)`QSrq^8{EuUw_kV2uF#S{Yx3FwU;h2hE^#iTPdE<~b zz>FV|-_#B;hkE?*U*Gy*+e;l?yAJIU-1A`%6RfVDw|9v^1NV7`n#JloYBKUa&afuD zPF($~;!C+p`Pwo;>D^-IqObXNd7bn6x=`>bqF)^3Ed${5G+eEP_7n5=pgK zgzZ5LqG)g*N)w>MlcK}G*!CvFnANgbK+(Qb1*pe?_tRWOiri5iDZeA11ncflRgUt7 z!X&#&FT|?^A-1ym`pVQ2?}8z@!kkGt({s<~-6`-Z5m(4-((9v|pW6ijS9Bo$Kk|{( zQ<3y+TYjT!FQzRXqQnAM|Dq>QLK>?5DUQtQU*K4y};bKitY(a z(CPdD{#?nNyPQ?rY#uGph=wCh;-iuWARv32XZmb-fkcIpT3}zW*riU2d-(SLhuT$;4zqpryIyPkCPP z^P=g+6{YpdLPGu638|1oa!Cm)oN;4idJ5?Mr#> zL}B9R5xZJEX`$m%Vx+IDqbsX%5kbf zRX=q%^$>NoYMe@^ic_9ZP>M=i=9QxXm)R#4^&Z?`??=^HWt}xy<+Kic|ZVn$E zCYt9vwsHFFbQ?U%m%CnfQ+arJ{`OM&T=EtBO9M^^J_())De8y9mW7^a_1u+ECm;uF zwq&PdE=y0iS$?_n!uWHMXC|M@KT&&Z(UAd%dmITl5qf_5jbD$wKBWEis*2|xrr#Ug zeJ?~fbnezypD=W2!tnfIjfpoBn)|ozO?E{){%WU;TpX4WRPJ}ug_r62+EZ{A-0 zxb#vHzo?|xvrJZbzdE>Xb$xyPn)(-Y)9Pl|*4H34o2xrjeXqzb8(I3k#Ho}n`%*r% zYIMz&I%7k0!-M)S^;a6MHKo}^f;RYCwvVozbA-1;;JVh05!|RgQ5lib+f;^oh6RPr z4}KlM^MB{n+Kua|(nDX0h6E;lg7tk}XyxnTcllFu-ek+OyJb)Rmyo9`Dk%M0Sz8lb z@6s67yw9@EHlEXy-%e!1MibBJVQeS)EX6~`LU1^(WCuZN(;;d)P?HORLD@iz2Bs&F zSttF+isZEXA$y3PC=p_(g^9cb`zY%P%WLZx8*Ov5`dW@O{c1?9ji@?W5neH%@_LoF zwo5~!#lXENJdGuglcf_B1!_v4W2|@R;aKL#b1HLcb}DeX=wx$x=seDOgi~wtOGthR zRq5H+#3}TvppyH{e%p2&SbRC`TT3`rjw@Hk6>)>O(Y)dO1;SKhtN1i=i6+?(@>-=@ zb6ooyDhWIEQvCp3sCJKvzMR;W4UM0||YN99B$2UmK& z(p?jy4NGz#er$O5=3eT}!fW_d!{uQY>}SZ6H;$AY@ZVp*KjU!X>40mZCrMdsp13{< zQ7V&MW(V@yd3Wp8PdO-f2$DE$NO8i+fhYT?_YLTc_k7ZAM`v!#<;eNLXS}wXKCrEj z+s!Mg!%AI?iVF7?-z@u4nOps?Ccfra6}aXJ6f1pRN|d`-{H(02%CF9^*;)I$ zZdtv);Xc&EAJ$K+E38>q&8wMGJGiml_FVXhxFq+{KXfd2TkcirGu7{u|A1D518xUC z4rW{1!tO>Kh&U215B(8v(0ipzz9B$4lInvdaoaWDsJ&I;TZ$FE%wLxGzuc#}UGtpt zFXb;U$SC+*7+suNYN{Mr+p%d0XNIT|*E8E>jIv%i0TcwS<%ea5*hID$dx7Q2cCwTd zm@v>~IEuN*KmG-7U(Q7PI$Mc#xy=v!aDDji1qGs|P|Mv1n*DxI-Ki7{#S}ILJ&mpd zH@?029H^%`69Xi1cpA1B86kYhxAFGyvjhu7$3fLGl+30*K!fe3n5*=I+ESBBuHLPF zuigXB!=u#`)jIV<)nVmQ#ZuWb;L9683$H~w2v&g;T0B%kcJp@&7od;C;8X$BUT2s; zo!B6mO*R>v-kzxEX&>tD>z5b^<8p&VU$0xK{;0)alDw(<=K_!xXKjEYQZ+uZJP^u!MQm~|bdM6Zu}5E|^= z&G0}{-_)t_*wd=RwPv(DH@ zR*#0-$%eI6%gZavbQK3GS5@_>`dHyxt}R81-HLt`-78U4bf`|Ld)>GI@)z3tA4yjM z7uEK4XXeJ-o=&<`P{c$rFrM9ojf&mf{kQw6*xlVNw&=546ctbj3F)5s*6_ja&fK|q zVxN8XIcM*+Y^Tw#J6Fsrmw<^qqGVa|jG}IZy9#y`$cr|V7%Q5~O2}Q@V$}*=plP`^ z$|b^mp;v|P_8@u9k#+JKG>j~5THY+b>GVi-!+YVoLbCm`Jf1oYGZw0!^5JxvY(mB1 zBJQupA7h&NXKM1{A0a=Q{)kO>OKtM&Qu?5*W_i7e>B^q+xevr?Jr z7jV2s8NQi1S?$h}yQf!A-~Rrq0zL(t3#jGa*|)xzv-@pltHol7S94-KyPTF0$7LgI zL#xJA)~nQ4_N=^H*#INe4Zu*0Kt$UDrl)X69caiiH*^ki%X4q-`N31|RpR->v&wV7 z=Oj-*&p94(?)BZ?yF3IMI8Aps?KTx2J1zVpf~JQ| zuQernM!mibOB!u%64|_Civz9xwi?xCKFaD%-qgpT)n{Q*5z*;V6)l;b0%BZ5Gze97Robv38*`W`y88V)#Hlo8 z%es}XuGn6cXOB{_)LEKlM{=0kl~!o48l%9!=oGL#G`SAhaC+mFkui}Q8}(}7T$c#j z95OJ-;veC2!(+BfmdUCe$!Ums75;^nvUTaIpSyo_|Mui-)Yo%g%ai8)h)FH}9r&k1 zZdyT;(pi;}vggDuVwW~ZtF~8E%KfB2%mqwJ-zC?`?|=io~8r(AZ?cFk;n;G z*f6FSMJtr{iIqFcPnEVWc~%@;(yuh3jIG#H+1j>C76S`sJJnP9gwb-L@Pp>y2c9J~ z7Q0FVRCUy9O&866%?-^6%>?zos$|K8r~d-dq41qY|^YQ9Yu*KnJ1SDS-VPRnnsOYr`Xo6$S%wSoA&=wgTuJ&lr@8zJ-p?8u@My5kh>_ShrS^OM&= zuYO)Nz5eGJ=K0KHfX5d1Ms8o6lP&#>wY3|>L99E~PZ4k5XX|21wmq@0lpT=umA$a{ zu)Emr!lU7{eX_g*(Se#m&tQ_-D$X5@lsU|7Whl*1v%vS6D*qriD3at;4xYcHheEUut!xFB)`XHL(1`ELrdPbIO1D2yOb6<+j=v*jtGny}m=-%Fx^DOA z=zZ2V!QT+LGw@U3h`_l4I{$UPle`Ce8r&Bmrgn_Q$z(8G*Oh8?nl9=?z{Q)Uic}Y> zXKBCd`p@O-0B^3_gy^Zf6@0&_h%lTd{UR^EG(N%X|&DU zb_73b@TFy|&YgRY8gM*j@i6`HIl~{vRu0`d*uP)v9&YWa=AreT2A}e5ZV@!z-2aG# zs!Js+@)Uo1{me{y{3-5z!*{RVxBJ}n+n1kUz|9LQ@v7)y3z8+sS0WPZf69;S79n3M zSI>c`{VmNnmA{zDmeB^XwtTE@W95K~1?7XvjTH+jpJHzM5OsuoATnBS<8+I`g?86_ zMfvs*XkX)KP5s-+OT!QlzQgyoR9?n`ku*7UkqK;J@}opUB0WzUfRFVFLz63 z!0*Tu)%TRIy04L6?_lMTAt*_H-+Af9u)M zJH%(B&t{*^-n>_&`$(5zmevON7>lWFI&CB`%Srp$%I@XSrA>?D3%?hvDEM8FU$~)| zEA3kzSJ~d)S^kQU(~p?${8sqt{MD?}HNfZ~!PwR0X-b2)Scvhg;gdd0Uj+ucAk7rj za_A^Zm~BqRdgr{%b&y+Achz#%?O;Ek0U)gt;k1cs$Fg*85Mpg3VPxD^H-M@CV$Jy=2 zA0J6M((br;=I*79xBfg_@VwRgi(eO|uKkl$V6xq12O4U4qz2!sm)6v`&E-z_yHkCV z`WEyr?H}BKOZ1hV)-L1PHjFwL@iqKMjUvB?9*Is94Wx9NvQ>U8sQKq*YI@S~#8IC| zCZ>KJ@Wb`zpR|veLiYKbxZJA0+JZ+#cghyo2r`oWDPGa!>pFvjp{ahI_O|*4VzT`C zPl&_Ipg$lM-kYq12fCR$Of^IV*#h=Hw_cbg={0+GeN8UloX+*4{aXbmhU}=BTJuTh zl^PEM%l&?Pckz7V*2ks5sy4UPm#WTlji?&-*s`<&MQ&E+sPr+vSO04K>&~y5zn`Z0 zWn^SJWxM8H%X2Q;QF^xWx$Fex&8?QwwZ+E1*7Ghs-D`P{^_u3j&ug4#m3wcug)V}# zul2n73L-EC-3Rp*@hw|Gy^)97)D<1eGD~bFT-lfMZIu&k+0bn@6)zS3#8KiHIiBvr zJmN-*gVdqAPKJHPO{R;c=B9bZMTRl@e=u^OG<6{}|VL z?#1QuDp|3tRBj=nNHu*)xt^_oIGu$+yqhKws{6pVYOWckb<(-&e}TDVr(uKsn{E$A zxh8cQ_=R7Keu!jAmhz-<)kbKk6F}Fv0spsd8ih7oH%))kkZ9a)DgaADYxweKT1`%O zt=+7%(PwWmX-qAQVTNYEIJPj#r-eea3e2@bxu!Hzq{CsQqqjqA6ue=Jvu(_Bs3>(|fOhA*T9| zn;dF2y#15T2fGFKbm?`sC)Y#jI)%1?AZDvG?KI4nPee#_Y|*f-fJ*+(GR^dNMUMLB?*Cyvq#H6&U#yZ-U~ z;hP=MEVyos={0@^n}dlUDX@7!BmXeJc|NVZzPPP(qKroMI(8Frv+8&0y22BAb8{Q# z{K_i-Gvd#GnNFF%GHPUA$?TGKF6Tzxn4)u7`@5u&E2H_rstj#_k+w{AstG?Rvs;u~ zmFqrNnQN5G0q10=OV;|9MAJ)yzfM9t_G5M>olAU^Z;@r&pW4UCHpq6!YRmT9FWX{m z@2jR%^{uL`ar-arV| z0sYmCSgfg<=i2$Y7y4U<_eM|n=`^-Zu-39ZvIJU8W|=9#kfQskb<%d#e84>F46sUG z=hN9c%6gQRXe>Wv|7uIHx!BFJt3YSp4Jr0e-b6&`YyKvX-X3dGbZd>lmj5|rVfJLU z$2-ptUemmfdOz_V=Uu~lwATmE^B#-b&$+F4z3cM9IRpCdp!EZyPkbzw&8N&S%&#r| zow~TJb8q2&)vtE&)S83Cx7X9wzguT%&E^5u+_#%=YxF{I#zZF)7FlS;^McsS@E%Px$`1yJSya;d&^bJZ1niO0dJTmxepw7Rxx5}-brKawx$T3%lz4jxO`^&nO zEGm@en{xMMWoEQW-~YSY@6fc1>A`b$hUniIHJ0br z+0KOPOV>?qMt9PEiQ8#c+U1wE%GAtIUt3%CN@&2XWcn%h(|URjWuRt~PZ6!gD~8Ee z%c5l-GD&`1@teq}jw@qWIS{b-0Acbq5HB|%MlS;Vz_$oHP{gWC+1yk3k+4L->3DMOrh3V2lb)fc@ZV?cK zE}BToLrbAG-{}DSxt&}~U7NePxh-=obZO;s-sy`q&{7IS^G$}DhBDnYL?*riA6Sys z!G>bj2J7DFmgo(}Ri;;#1Sh*I<2l3U2j--<)HH>!tk=B0sa|Joi54>FO{hSU#-$a#3d9#N6WS)U3~0HL`zaug+2AHpu02OLC^{fcR zY8H{mc!jyP?xc$jwUL$#k(TIsCd%6oB< zOf5Q^tf7dJ?XkI3HLR3XuC6>&rLd0z0wa%=b_JNpYqKugFkT_&PI2GC$LDmYX++u0ip6FaC1Gds(um} zv%3+yzd1J|cDY^pc3b8`8+{|9&*TuK4e4!ly@#9&LV{^`z&sx-VniJbm~0 z!;w!%zT|&j^?OH7VCinfY{Au7?sC!lTfqB}+}i!?uWWR(X;svqmK7~`v^2D6-@Jd* zL6NT_qy`~%TGV_P@XoV?Q2)(2?>R!4FhK}Z0)?DX@uE*W`cq+X|`xyNE{2K8+A~z(H2^9wd6-($NW`)<8sI4zRCUYw|oArf`dho zC0RgI4Xl2`Wl?3+dh5p;mEgbdx6ZUmP8HV0*6)_}=G~?+<9dBdomN|+ zJ_y#b0HC8x;eIlsf%&kS%p&Rof2kocop2>DkxQrr82#5(zE;*nJn<&rEvUd8ummW> zUx4_!O{fo)gSz}FE}F|=6In0BmrhkGls$oOpGgg&H`6Z4B+L~?L7wxu!(e3^Cr**( zL59jTEprhZ88Y>K_09EPb)4=I;-P1&8>$wGJV50}F#y zM9V_#S8P?b68i{wC!&nJLf2*{vu*hf;&~OXH5kU3f~}pM>$>vpfu44+5Z?s9H~t^} z-}+tmY2nq&eT56{l!sZz1&C|_;%r8tark=*dhPL`u zx`Emm8qBn*e54M-PtKR!q-;hj5qD0Ie~3EdR&p>^Lj9l{0~bQhxG^i4i_Bbh7`L3i z3>=g#(jL__V6sdALqRunka~t{f+|~jD6N!E1LvWYEm(K3pF;`9pWCqO)ajWSY8dpOK)cL-4U+SD^t}=|%odMF;b}omq+kMNv=5@?` zkQ$d1{wez1qu1WACchl^%I{73+a4dRpSFDNmpJ6>uWyRf59wZiHrj{bmJEuLXF z&`$|Bd4}z7<+h47<=4w@lsc83DQ;KnT)e3yw(LnI*ip$f%1oB#fepd+=EicXxw?EE z;4NGiUx=;5eL@Q$&opLk(UoKiLMxwc_p|-N?0z5HN&6?60c_-L$bQsBI+iJ7M+z6D z!>|XR8lx@8oP1p8xF7cH=snpd9&<9Cy^}mm9*y0Wy7)Tpwz^wdn`DM)Evvf84`e2g zm*k^uUhv&MSNgUjuh^}`tE5B8*^)k`eM{?s!E$rCTP0!RW#<)BDLdGh;)T6ZeRUnp zM(uLl7+|k>z)w2Nkc2&FeYh@7yAvagW2%c%U9pI7!yRA(mF*}evNu?s?t}j&mUu{b zkcngoxtO|4-J%yN_b}nyUY-G-6@%#VeVU(|o?4^!EZ8+Z1I^(s_#*Y1m0-+isj4A; z2aD2fc#x#PBjFNwL#9wGsMBEE3#EtANpwABq4G3yfZfOK;D-t^K%iT!QmMyl9%*da zSe+L*&4%b}>!<2Vbr-?F;tw7>wXQW{NWN>lH8<3ofY6XBE)gZ*IjY1Rz&*b%b-`%5 zKHAP?^-*=D`UvD$scV3U=7q-Lrpe}XbFAgI<%~r_^k6S*SL;Qqlhbjh?}$;Yf!M8m zu6x~K% z)oOv@l9a!x{^WCoT{hd^qUsNP;|`XGRrpuw?Qvk&@+1e5xkRR7up(ArB(9L1==xw@ z`OMZwG)F$u5dGpGnxuoNFtRK0OEFaOTMg zNn*hbc9Heu9|)tQZK`lHA>~V+Pz;hE088B#%&Y5wEU^*mn>%b*ZOiQ=Wlz9{6b!`H6xs}w zq$F;sa6{~?x~9(8bkJq!?;7$Etza}y09%)f`Ic$6>7Z${sjq32$;q_Yc+2oy{~05j z$=cm$BgtqZJ=M2?T3cK78HhI1!B?|gx&kb~aFxI63{ck1>hRStwF<&=;8uPA;zT?w33>z4!S3&)*o>I_N>ry`YbQ zrvvW#{p)kyYo^CIH&2&yR+agw;g)ugT9j7s9oS{y!+b<^R=CM~%g%sZtkm8{<}9Bn z|0Zv(h*L}>(g-~m!fJriOU=Gx_nOK`pM}rZpFFTF<&hHY30JE#Uc7pD?{siWsgH2B6gXXrDkCrLc|5?Xd z|AUXmER){2MW3V%()3dqq#(>q9KSS7Q~utnK9 z*&O+N#dzX1`Hs4*%wqZhnX0+C2G(C3@WIM8d$sXE?dhkzt?|(e1b$_j^bMR312JFS zpPLLWtDiudY(l?7oOVr&x|877=cVk5I51Dn1l*I?!hJDW+N`o_QZ&Wv2F|C@rJH#2yT{-;#|yV zeE@r94@BNC)m_t1Ghijh{MRBtGJCpCbUW+5)}yZH5>LVNsK;&hes1|LQO=94apt?m z>AL^ai?9~{h_cJ0Y@N%07yl_p|Jy6)_n(%To6}R%j{pAtd&TeWzyJGvEG;Hu@Skq* z%l%Q5P!?a6CO=ILWj_gD)Ft{E<~xYs`Q#Df-QD+@pL@Wnzy*Pcfn5T-2AuFq_1Wb` zc^q)9a5`n_X}qWVN8Lp9;mpcx;;4MJeQVX#igo2*OD&}acw5yexm$9)w5aS?dB@6# zs`0i@_PX+)3W3U{OPG7yc#Jyl0)P4eSpKeR{Iy{yofORj%|eY<^GuzLQT<5uEma2i zQrZCDX&q)_whDg0(CuB#EAs$s7e?>~y_GhC8!8%nU8hux+68=3sj8!xMP7|Kl55~b z=_>T*4{;BHmpF!*g*ikyy^ksG;SRkmBW4m_qzkF0`cl2pv`s4PP^YI2c;|^7zIzjd}?w(eooeoA|PHji*C@l^b zrsJ)f*-OkpWfm|rcT(x(XYv906Rd4xsVYiOAAp8^shr8Uu{5^{d_nic4blo#6!Lvl zV*&fwcWoGtc?`lq@(@Fv`-)9FgJA=-1Av6@NhPC!rGq*|hy3Rx-ym*+|# z(;UF}J8WNoDj1|1t=gya znXBc&;`&kN4BRIrVnDKWCxOP84A!^(n#bxRs#>b;lBaY897Jb;qZZ4X!S;29JI)ON z7SRZ9I@b&9VflzG?Z)+k{XdI~2M5?kpknsMc`W^NcY&#vi0vG(Lx-}xfirgkoM7*i z=aegzXQFMd&4Jr03Ed)mqr`OEjM~&9&Qs zRrU_{e0^O@T}`k>higsRx|*J9ovM!1RvaLB^CA}jKl6W;XX#w3KDC_OMRp>~2^Vu>UMInAHl5 z_4&p@hI=}bc8U6y^cqZ>ix@YWAlJ)>*#oQkR4B_%muxI+2Y{Ru2{i3YkMK{C2mra7?PhN9#r+!*3!Ef*PEJIb|ZTByz>Jv#q3TwV$*a-DI@YwUDkD zofR=gr?l=^XC1AnQo8|h=$@1ZrmCAlF}S@{;MRQ2@?fDD1fJDZK)c#Y=hGYLc=|s5 zm;MS&wE;koe5G8D85NGb&i3IxfCc6aKNTn?BgLB1SSeLfsghMbVChR%yJ$LS=7NoU zHR9vf;(sh^v7M$Tkj*-)cR?rqkWwUI>O+U-fN7@}U&2j-%@@X=X2vn?nCHrmu>016 zkGVvd24wDHwz`AS?Uh3noPRs7;UcBGlmI8M~QG=2m7`a}#rpX_G0%m~J2p2QmKrrXHah2)k0v zHDyBSAhNci+&Ln)*5%~=j%MR$JNPFGx0S)mAlIH zR$A%(@#Ib#69d*%p{hO@$jEIq`buZ%l_c< zVSVR_FQp^U!P#JpS7_^L4}tfx3)mUh5*i1b%6;He`~>^>CB}$u z;Po_t9eaanxGDx$M5xMe&&X;P!Mot{nuP!Fz{j2gFDnP)<`AIcy#l}4F7Yjx)YnV7 zQi4iQe^Adxtuoq5ZL#)_ZVfnjj~LvHZH-@y2aN~_2rnM&8G{Dr!6l>~Z$~4w9 zy)`BoFBo?iLyi57&kQRJW%?2Ne!4vEQ_WHJ8dVP|OgzrJBbsB8GJsZ5%?U=)T;^q0 z*^XA;tLR%%QC?7f0a$gaid7ZED|%Npt9oENWiOWPP<$hXQ%#iPm>OI>e@bisv{bvs zsOyIwP;Yz*i)|)YVE;9JH-0u2VieO7C}BOcf7RuxzS2G+g`3D0DUZ`El|rbA&+?*b zEV|{kyei(dwo0^_Y&UFsZF>7H`&`(w0~D=^JJ7*;r61$M?gCb2x=>f@qY6{UW9Fx= zwnAGUeB%A|hxM2A2QlUtiHO8?V7*?VjmN0$6}S{5rFNpf5Cx=wZR{Yh`i27w@iNt$ z$|R%6rlgFlPg==!L;^NIjx=7y1IxIb+OBS{ z$yVnByTX7`kD&R3IfR+&?chH@qMD^D$Jpp9^usVnhfZ>nQW1wZ2)Lr-F&kD_iUg{5 z2IgMwi$0Q{GzKy-4;<>fq!v<|=n3x36fmMWSnYOTMXXSCg^ZoWs4EJiFK<Vtf8L4j0irZ!QH?ZmgryV)p`L zAJR0{c2$|m1q|`8)mh*sy$*~~mHMQr0J%Pi=uBQPVqHnkjsmaNRiM^30k`&3;sjwN z)`F2>sG@_Svtlo}FKQ75h+7LpEp31;`BFK883#seC;k+_NU#D&*-*`G*;h4NRid)1 zV!>V82*}fn`aIZmyI}U^ERYBbVCU8n*TNIKfbYnsgPperC*uaNA#4Y5`(9*@!_rv9 zjASk_Z<#_Sm>tRf$GT(QY#a9<<|0S&2|NW9+_mU6(!hy08VKoNd=XnneK79mBXvLu z_DN~b2H~oYk~6S&523AhgFQJG=%Uf84j41{KzTdk>>secKE-(2Arm3^C#C0*lxLWk zyNJ9z5|?8gezSO0+%3KaCt?;PBTWnfZtgs2j!5X2$IyTQh>)pJ$7-f%)}t2*0~+^e z?O<>$?}SbI9DOAV`{O10EhnJ7Oi)i$KSVk#z&G%Ogsz9~+5ow%E44;FOhnq3!}4D! zUB;FmIjLr<;vjDmRBDX-*8vNaLi*l{eZXl~3}n&2K!o)LbEXqKoF)JP_y*&_6anRR z3GiPFz^it0~>k^Wf@&Z`3Nf{7I3_7#t{=U z2iU6*m|o!M-3Fu^Ef9KZb5A)f-;@dmgQ_kb(371$z=gZKR{W>0zebbSHa;8!3O|AsUKfNyX)P)o1y z?|20mB%Oh2`bKaD!s%X7CGlWqJtY}|TRcOR3gp;G^+xqVFmv=bE-6oKQ3;y@_}_HUWk7PYt*I6LdGPTn79`ocrEEtqE=qnIPGU$sEBZ3hh9 zDXL3Anm(htjyCcRh|{Ogd&PtQ_nNAg%18AQ@16=IW37}R-T{uYDBgkWj}zoTRbI~f z@wwbhZWLDsNEKh$P_6(o^jq0$Y#O_WZO*#0UD;@`WDf^6bWhmvW7*E^WOgCgANB$@ zSq?OlC@vSX{ASGmpM*7hiOb>Mb4~bqd=s$n`tu?94CQHHLLcN#a7un9cNL?C0k}Sh z`_8_?Q$Dd*flspzD^u&Rn&1sd@deB80DKQ+|6wn&G3+E@C!Yc{T{_D_;@X1e^)}WI z)1foEfwl4kP|S}3X*wTVj}?3{cowID+cFl2=5gS0JPPi}dB6}}0?x_Nz^d&JW{98s z9iT<;gEZ}fjGO_+csZC=Ghxw%fuHdpw9tF-Kz0NJYXaC?)4&PbP-=j7HUT>P2yENO z7+L2+Hv~WvECTBD16T*e_@~vgfEO`H-A3I?9SvD&4vFxCel7uXvsO(2Lw5!4Xp35# z0*>G)%)R}USk)itrBnbW-{0V2egx*uCflhoLDZ7GH-GVNNL!Z?Z64h5?Bn9{);=$ky9~I#GhlmxzTVWK+ zWC_Y>G)lyQ-20Y)1%}Qz{yL(-?}4B9Dat}8B=aut6o`Z!Q%7izb?i7Wybc0uXG>T& z4pz<%I2r}3+0oV>;0ZUt*ZKq{c?2zQKJbdif%!9>?+O(6HsJ3qL3;}T&qHT^5MRXA z1aG5(|I1B;XJr`lb^*H?^0t5tWIfmbwki9XF#!pC5VrBGCs5t{qQR`tk4QM zGYU$<&cEPq^JAg6#`9-^^gNtb@+2?A8c`ni1|_?Tn+axseHbBq;3~1^>kGX1B<=+? zpbj?l0RA9)+^J{>+tEe`p|#r3ZdY>;F^;c;*d~%IMT@`3c4t?x;cO!Fn+aqYR?F69 zW7(E$fA$!>agMQJVqQyAR;kEfN=sn_w###VGL`yy6}s zdTTDUfJP|7jPE9-?;hlS1kkH{gE=7@Qo9g1>GP|5n$JMfwm{C?q0VN*l0Sr+$`#y1 z3;55cisv8&bzq4cgBRy=w9f=+=mb~|ci?lk6}|HRfRPp=9fy4MhHdm0Jg;{U3qKUR zw2Y7qo%0Xh2Z--;Af3bT-38;5mFP7?QL8f{yZeBx>AuixQORS4GEr6c5 z0&Vdf5!@NjMaO^@K0y*;oj!oQ*$KJViN}Gyy+%-hllcP%|bfdv@&>f$RV1;>t)#x!e&}X5S zR9EY@lcEyL-It-y20*X3g#J$k|Hu=R?t19+FL>J-b0DFEJo~nhF(EvQa9GK4Up}%l&i1$WoiR8Zn zr+*7~AD(Q#AhQqAa^3@3$rpNL1+H|UtveX9pFl@N10VYYxF`z2P3#N%%Uk*fdbt_+ z2|kDmP~tJ*8~+GykX1lQ6T#1L6Vf~yZF3m3WpA`t8`^9UC!)=UKvMfao5jGk+JJMt zA+0rVd@CfiBaZaJ@oi{znb49)(VJa`W-bTInjUiJ4NcM&@h1#=zjBV9W0q+%Ub zVPesnFN3eZKIF#n*6}z#mCvru;Zz2wB>EeC`es8Mx9c z)uLcwJo0`VnC}&kOS7z^2Hg#0+84-FL_LjxA@av_ViBH!V#{G(8YV<5e^utJuNRMtYv^oJaE#~5z6 zxD;)5HEJdbrO83Ig5V8f5fg-yxcVXF@38O~vYv~T7zZzV8TLvcm*r>~A8{m0c#5kW z{rP%f74~l-H;%j~3-7>pv;)>aQgv%Ng(tm4Uy+FN&P0ofKrS3_T!pk8K;F9`RsX>1 zu?z0dUqc`Rjlj(E1eU}W=(p2oU-O_vHbAe(p+9VdWBrluIj|~*V(&0ga0zWQ2inF@ zbgGt(j*yR5(Ap2gr;v~oXsQp;@LR-d;w6lLu85Z*HB&G%Ns69mN$-KFxDhR3F~(VO z=s^V3n-AU-0p4;BI=(xO4T6O^6QAdWXTn`b<#$N-FT~sw3tjPq252YE&{Bq?R1d+r zx+VUHR`VQtFVNTg6yKqz*@z=;t6PEzy3vB!*)a4b-%)0pA&p(J))j#qX;G63Xv`8m zm$&iX`4avjdKQNT`V4)I9{NQMISv7<`X#Y9@Te2&0U@h4JDu=)z<~_36=SYCx|n z#&~)Yu5;AyLD&j8DCtL-b=nDE{L5Gsc!Kh%L~nascmSQ43td@?+Lq8`*AXLOnb(1~ z(24ILf$?Z7MtQwGwJBQz5K2=ic*?m)RtKyB|wfBhC^{Xhijdv%E)fClRWoi!TPs~T-K z8>Ouj9rCgsX_yYnG!A;(7kMS1`OyjC+fna5(OMmhI7gBHyO4Z2+Gr=dWfV&9All-4 z$n7({=_~AI2NT^3lz9=}e+g}ADAM8qd-)|~e>R@q6}20M)?Qc0gMS!_p0^3)X&Bxf zBa9Fx!Cq*GcPX$fL2lO}xAACw|G{4Wi8hvt_L7Ws;xt%J6xyf>k|sl2@kLv$4?Cd+ zT1q$Ma1?q4o6rI!&55^h*C(__0{ZAFT73|#7f-bAbo3{=)pe906v1EfK3eHc)bbWc zonz!P20HU1M$j!V1JxZpT3eLTVrX?oy0)SeQiKq^)ep7$6Qyz+ZTb^x;Slt}F4Wl? z^n$}+`8clLgL=LvP~uhS2S?BO8d~8p-uw}|@-O6|6uKk{`rsmDWfz`31#jCTbi-#m zXsr$?{nqFW>!Iu-QC8C-p`G!2Ax0Q?ao=Z1L87o7>HiP8_=#5N4?8#o+T}X5&J&D5 zzT<82c*kvcD_=o>z7@7{Ygh@rF%FuEmb@I-ZL8K&Ct%IpL`k`dYmv%-k)wFjfJ3Lt zP`aG>6}kIftzS-6=PLrG(*d>F9d_9ep%Z3oD9DQwO3?~U;f3$o$VGSLV;UrBD8`v{ zur~(MdkXUK7%9)hdsDC_qUGE}ul59I0-*`gQOjj$2?Xlaiuw+PJzgbr7Yors&LNi@ z&>ot?La_1mg=o}L4@mBONLG8ihrp*dayc0}TZmHGFZ@9(DTfW}Xpd^hMku7j4{|9- z8z@IzrX!ypk*ebA7>8x3qk*XFUMOWZ*tSOWD&3(6)6t*g!=8A9xri_P556Ai!7&Qm z4la$E&>wZHThS@#=rXj>Qk0$zMnn#*M-fu$4e1C*4OH-sG2?jj=EET? zaVU=kxN{8B(*o0Hk0Nevd@SO+l*XpcY4i_f89$ zT!x(Qf&8CFeh#BeoI%;gL&lDv-JZsgEol2IP=_wKwl+SS!!kOGQQ{7G4!!0VVGe3F zY~>D+Z7<<1ENfD@j$Yz3?*mzDih466wP9!rOYzoZ^o7&V7jMD2_DFFZ=z`s7^UDxP z(_6^pCD>m*(L#oz)y&0Q!2d7vrJSbc~D~b-oNe)fikatJYQnkfzOO8yj(ECEERDXs2B$nbnYJ z4vcOaAXCX0t!40)u+!ILZ1oiTh1f60*g%6GIFav>kezJ670}fc#kL~ zV4mX$-hU4xoHrOB?88{>9^VP$2S;BNjB8W)_UIdYA?X94(+)w0#G_o-3kM+a4X};I zn}=c>0)5gMGQ1O|I~DH=ua;T~wgLr@d@tbva`+TEe2P+kivQObMR6$A6pRtxAuWF} zJ66scpeOYhLzSbfqtK4pqfUCF9Yo^&HBb}YNR@+k?J)A$9ahF~=w5BujUB=H%Z=omds;E&^J?-BE?Kw8g0whrPs0(uW;NR^0O_(1*% zl=2gdf_nB!7GM~EmbZ`2Wova;g-0jRZx(5szLvm0UiEP`$D9I1=L?{m;sSCO8} zNYyEPI;6QDWULEHe=gPwI-r#_#1n&rH_(`lF?|8v7YM28h7<>5{K2E7f{->x&pr&f ziNL;NT#|x1U{P*5q(#6pD3o|A{yorY8{pkLQBwb+emOiP6|M3YZ^k>lP`VB_%N3aU z>cH>BSauQg#vs(x9^_GtHXMcb^gs?Bl6VGX>gfF*;dwdLXOF0f>ew{d5wdH*o~{(pzn%CzAm9%Ua4+5Jz;0m!BvhK;puqN z9cauKkcyAE-hqtdn1|_(`@2H_cEw1p23ms=b@?CCUIt0@KuOoe-91o~{c$!Bx;whM z-S@+&A_hI;D%dS2(es~xo?e8SYXiCI1{og;DH?+sae=-6jb|{s^%wI3cI-8QjFiCc z_d>Zl^j~c}xh2ZgA<+(f?2vd4X>w?y7|31>($)y|I|f&E#T&XpCqKj6pJD$w-ZU5Q z8vxn8gB+PKKB+<)X9-?nI#yG?&>!#T^?Ze}UTlS#&6Ch24`6*Ukin1W@vcE<+~=)$ zhNCAO1f6ykDLIGvnZdX&4!V6N`n0B^Giv+{+HoNyemHt`U&z&D$n-y$iFm@-Kw75@ zFVO;`aqKz9H?7fjnqquGVT5o3Bk^pszspGDRg5@hp#EB+EssGS4jLC$3rce*+O@;xnFc8x zjg;2KyGh|F?%RcV+~2S^et~x|7f(8gK6xQ*jc>dkN_RHOXaVH3F>(`zyK5mOO;8eR zkgC>@D2J}@1SyY#MbQyQ|Dr{ipea@81yWHrYP149-lT#CNx~B=ct`8|3~iN!`D}Om z{>axvdR3^|8<6om)ic~1&`*s;4PM3EYc#ZZIro55;62NriI1UN!jQiC&~~*Tb8(RA znaHI#YH$VGcQI_ot0;{^lt*VERwRL|qYU{Q$Tz?Y*%ZDR@5Xa{6eIXq~svC73;4A)`0?eXRHPI z<0)lWr)a_l@o-B-4!R(XGG2ox{e!3X!J8xT#sEGL>;38ArqINyO>hsZ+GoKn>+lztjMa@r_6Q%HT)jm z<4OCldNPC?3~z)s@Fk0YkK`0?JytuHz+-73*A?p z{lbcQ4%-%MtBtspxNaEN8l^lFX&Q<08V*0rMqDu07~HukT%XQnu|L@d>~HoZdkg>T z*}3d&c0YR%Yp(CG-tv>p!zas$NKt#N&(z}xt}gOauX=qZ0;_4g@utD>0C?0Kx|o`Ju`ZLAL+hwtZ2_72vHp0aPiA-|v9hifk4O%K?4SpB_%-;cmJ{DIBE zTGLgqrCh@PFRb?@BSjZ*?X_yZ&?&fX3fm5`X3=bYtVp+J*J5pGF48;?Ot@X)jnDyS zW7vOj#S?Zrp0N*WMd#TUSiM@zw!ys}aMcK0(+w+HZfpa1igbqGb5pEvcgAYg2BhsE zyA0nO5VHnG9;EaHR-{*h6L|wW8dt>NJrQ_%-|AFM!nGR_{k969E7)mxMijVtG;9s5 zU*99hPME>|dsg$zWt`D4WMPvqrpMg_X`)Y%4r#Qg!+Vvd!2&Y!%an z6&!{!HFJ!)#(ZIRGWpCCuw>l9(HBeta~Z#1 zGMUUTCL3q}GR2GyJdqS@K$>J&xntllm&(Z5UknWo$JfkW<}>q(Nygpp@#Krlcjh*D zgm*FznHzZCPMq5To};ty_PEIWVB+z+0DCO^2v?tm@7@342{H>Fk#m@d%p_(RvxHg7 z3}kvSU6^R5I~cVGz>9J)j<02g<2l2S@=eSkW)!oZ8OzMWopW$}FEbRscQbpK&CCjB zKC>K0=i}WIm=W;aX~Tpu5sZnc4~Ao3JT(}cmu;9@*w-^GL&I}eVru4=-V885~PpG`TKaO7YTq2Sq~hrgg*S+2aI{E4XCKS~8dFlF#M`Kzo@3QU1g z&op4PjGA#~c*ck~7#W5U@XLY-paNwv?l}eazA|2U7ydA(;bnRP z$bZ}M)MGfh3+LmocO1ud;LIU-4!VpC>!8uzRE^m{`AF_zRHm5U(IoC zw9;K!8ywP6N*`d8l+wTHY+6v3z@NwfKeP~~N~u-ql}0?Xl%{apQ%NfWls4K12skzF z_(;o?gt8C}RyT3)ZTcJi32}P`@b7#?zlIkurA)-{WJFh|(wVfu5xJnurU^Xh9j9c!yqxkLW`1$gHBz7jHxx-H$9j-rFF}LeNUy>5W9e9WJnmV5JBQ-Bar7X10^O4CPPf4`2H?s_oa=*QV{l&# z-mwH{2h-i?t~eHq?^H!ZyWw~Zx;5RN_Q4q+x+5J%*QdR(`GG6GA&z+>vd$ex zJZNv)g?0sE21!%E^&n|AA})CR=HQ`Mia00+F;05gPO*4~imr|8JJS;FMzeG=^^1B> zU7*fUN2o_s0`-_Wi_Zf<-8f4fNBrIw>N)kB`b1^m^ELGi$N$6j0NjxGaL+>=J4w9( z_ES7{8=p6*gNVVrfa8x5k@S+vr^<2PABv)r@%f2*hcl1B#Cn&yLT$z~mQXvXb<|dB zE$-WdC(XwHMyek*h8j-wqQ)T-Wi>ULnnrb}CQ*a14a3n%IJX?pp8Ju?6L`u#pgL}# zrc-0F4WnXl&rIAijOu~=W2y1DejGIt_cfvXsVK?|F#~m|dQ^L=E7hE8N;RfhVrxXX zQxQ}+zQd{7ly~*9C>(DH7VdVqs}>rNPawA8A);sYk_X819}$d*^m4mITUw}B!`jFxMwV`?oIY3 z2ap5F5!m{Zoyp8S*9;>%;Cy$YH_;K_{}4?P z-PN9Ggztt#D_qeQ_xHs4t~lR_h$141dPFm9t?=KFh#;C1Aw)RgNw^Un*!&0=?AIW? zaV&`NCu$LZFv4#)`1`sLDncUk1WU*Wo+wk;6mp^novmG=z;By^z#oJf$8r?qieg2j zqEwNMEe~5E_DU3g@tuKRDT;53L`9O~qas!D0pA}KpA_#D@3FmBe8rhm{7zB4!u~7# zdWQ3NfZ%djaZGUmpBE5Geob*paT}irigSvSiu2emD-J2HC{8PmDh?`+;P)EEdc`Wm z|M0&~v0SlMv0AYSdn>T5R4h^~#rZWjzYd?9ac&o`-iWJKDHbZ`D`qPuDHbTkDP|}} zC`KU)dXOSo(O=OU-~ALr;PX5P=f}g-ItDm!L#uy}#<5sj(@)V!(M!=COjk`6Efo#^ zucIpqi82bK=iI3*FnZ8Tv&^=!)DTS)44cfQ(I6t*n9-~t+YkzZjGAx>a;C&ctCxZn zk(4%^OrtWiB#AN$lxUwM?4^*bl&tK`a5(3D_q+G$f1UZhBcvLeG)K8UxhBPA1dyg% zo5|LzOk)?b#00&JH&&(p%r^>SF_C7jnI(-dQ_W&j&g*<{LOFtCH&xD@vAyR9OM`J_(pp?d-nf<5ZLRIev+*Q%b<>G@b_7dqI&W;U^rH+fa+uHy+U=}l&CbtP0TrQ+DS#=_ljViALdmv3Zi!@mKdD3} z5hdM&!@~O@Ke$Jyp26*VhntWNkB)Na851?J*O>8>raJVRJZWsyh^dm`ppbA6lm<=p1;XT49$>+N8LsBLA zBauo~2pR+q(IOS3I;jD{R%#`6kUB~0OI@WN2u-9dr7fgB(x%epQg=LCN?S?2r5&Vg zr9sj_X%}fnX=glpOM4>pmWE3s>tdvIxO9Ycq;#}&lyr3r!zgyqsz(kyAFG+Vk3&sBBL)zZz<9nziBz0!ZBNAWx=-7h^REvO5H z(lgRq(reOtcs`Wgk={qVhvx%4i>1$`ucRNO-=w9|3h5`r4|tYKtEFENe@iQ+j7%yM zWTK3f@iKx)@zl$#WcD&wSv|x?vL>>oGEbQYVgp$-q+7|_%lu?rWWlnoc=o`vBc5Gk zz47cJ3zK!1MajZtqh-Tn17-bXBN6+{M#zT9Cdy(FQf0GcF|q_%x@>_gQMOR_H{ue6 zOxZSsow7}`jfl1B)v~R!<+2U<+9lg3J0{DMU6&QeZphBcuHs#YoP2~cvdgklh&N>q zWmjZ(WS3+QkiLshEc+mPFMA{Vg!m0~+@HESR${gfWZjp;}E4dVJ zwOog%R&J8J%InJ;A$Z9f>@a&K1FYhW3mWRlP z$VbS>$@|EoTcs_==TB%BLZ<0M9h}9K>ZvFP5*AC&*_bB%nsBe5(8}l&q33 zMb0Am{JK=8e7$_9{9pNTc`n|ErASrCWs1*ov!YV&rf^n>3W>r-Ayvo}KjbEb zwL+(`SGeJAMy?g!Rtl4XC>kl6DLfUfh^-Vphyey%fC^0~90hJw_3$n4ySLj8_a&j8w!Z5)tMo(iE!|a}oYhtW>1pJ4LZxk*-*v z*sj>3IH$-`9Km~=;vdCMq;nN(>r($HvK57jy^7QLI;7Z#{4bzy9{|UrCP}<<;r?W zrP5aEtkmJDQBr(SB~iNItBKNA*;3g?>8fm@G%3B69?Hf_CuKWjpfW@`P&r6BSUCx) zc1X8Wj#YM7Mkt3VhbX5hd*iDwQvH=Mc|zDsz-c z%5}=Q%K1nyL+Z5hh;pa$sB(kytny#w3gtfK66HeWdgU&J!^+FbLd28G+sbpw6Usx% zHK_lO@|5zX@_=#=@{S{%LiuIoQ-msIjj~8tp?s?>MoOuYt3E4<$_8(hN~020uaqB^ zpOkXdA0?wws%%lxTqUTiR3=p`yj!T85Syz4RgG0`Rc4i2U0D;Aiz-4DplXj8qUx%O zK`IQPuWG1jq-u(4jw)R>O|?=rS2bESLY1HzuNtF@Qq5AuBY&}KwJIBBGgL{)n~$

|D zh^2ep&hqz+W~Ru5E9Qx8>7P>)uRL#rTlJ+-fTgu0J98MSNkr=mrKI!ZlK zJzE{CUZze{uT=l5{#$)SyMZqDb%uJm`k*>aeN&yT&P4t)JU5^;Uwu@4 zOI@ITh!*?R|EZ57=dSvd`WJ$lDOVeqU+S00tx;c5SE#kjcXe|{$v84q>bL6GY8i7% zEn!&3nkiK`U`&h$^BXmPs7ux5>hEeR#?1IL^_VtH5JCv!jnI(MFfEbOg>hrLGk#1U zV_=$~RwI=3M@bUXnwi2hV-lD(Od6BS3}D7E;Y>Pej$o!T(M&8eoax8R##abZ(M$}p z1Z}dJ4a^?Ioy8%;AnW!1B3DOKh$tcYr zq}(-rniePz)Py0oo91uL5KVW~j?{G0Owx4J%+Ue!&YhPvsSEy{iOM(`GdM2H9FS7c3^8X z5hx2_|7a*{Vg-bHtekDg+Ou|SH&)5^VYMt_eeq>RNk_IBJBRJWE@VScI+-2EHf7th zfk<~|BiL|u3c_sm5L!)Ur?C@IcNiPW_C?+rc08NKrnAS{xojNk&kkkVu^#LQwkI3O zZeusGNvJcGjbfLw(d=G!3ww>-$riCI*jsEio607$z0hhYyPSQ-UO+5hpQ2U;yOn*# zzD5u^6~}Xgt6^=p_bla#Sq=A&eZ+oX&!UzJC1$Pz*M{rFHRW8m#(3IsEw~4)6Q|+o zagFdL<&@kpR>qxVpR+gED%OGP%k|_MqJ<-8;TZJ)gRO1Zm+QhU<1)GS+!$^s*PHXf zyFM3*)LQNcm(9)RmU4r+bzCAhjT_5laIH~)8aIU7#D#F_D4mCrp46Q zzJ&jezl-|Y`BVIS{xH9WKg&n)Jr zxxtt6$N5dXUMS?Nc!^NP`w5TmuIBF`=!GBrdHx&!oNp;a3jsoN;Wyt~FbH4K)>DuR zReUF;!v!y4hA>R%C?p9J@E$6J2}YrhFj?>s<_QtPLSeYjRj4nF7RvedLZI-G?;!}n zY@xr^P4(Cb2BfUr_nBqRz~gfisb z7M2T}g~ez&SXhPD7leG_jBrOdFXRdTqUBIwn=n_{je6IFm%>fKOzsGWgg?S|p+d+O zUI@iPLn0>}=|#-MM1G^BQjjC$8Am1%C(@17L!KvzAps~EOD2&x5{(v@ zgjQ&;Clo!6M$S00mTVw{Fy>U$oK7-GIN3(7kPGA`*@LnL=rNBhBkRaJa)5j$1>^zw zO3IOXLynP$-BA>{A z?L{w>T#`?mX)akxmXL!)q?P!(KmzGb5V!EAqrQk9M7C5h)@jdW3u+I(nU0(~HCrEuCn6 z+LfB94Q)PE6+FldGr=wxdfOQjdvbeInqMn zO?~JmtiJ_TU0c&k8`BSD8tn;)Mq#Wd+6sLQrh|Y16XIiX6RWv_c^^dT4si0DR050j z>2LH!04s`7Z;_T5vvy{i$YHGW3pqioFz+dte=GD=LCk=m0xPZ|997ZY7$X>~?o1X|X07F10eA?=U(hhxTl=t4RM^9`e;QQM66w-EA4S76Em^+VBb zf9is{Ie{u)k=vvgH0pvpTg2y>)pK$VbAJe`d<3eam_;|xOE~Ci0R2Pk=^eEBfjVc1 zE2z90)c%Wj0Xo)nAoT(!Da`>jd?7sA1Yq@Y!0shU0(|<=E`Wpx7#{*BJ^{7@L96XC z$H#SCbQ}08B;i3n)tWvg0hpUT?EzXI3WyA%O0?$bTVe!l!~#mS z{R{y#FM>B(0g|(^`T$_c0$Npo1D)%rasXX}c|@RYd#tGy=1{xZ7^FPVi$CbL6QDH$ zkZnsts6Du&md`7(&dxNF?ncekXg?RUKLBMd(C#L1B(LkGoV3R{wH#joj(!U&i$MJV z^qWBAK&7MWLRUxte?Z+0P_KlPdIhfY0EDJsPT_z;1Yk3@Zhl>`#>W`l0jqcnd^=JF zAX-K)5+$V7A;`siQVssG!fIP#hh`AUe2XiSPEl@9pBtT-HCL_Vyz0uwc-=WYpG3Ysi z3?O|;Gw79I^m>P+kZ;fjm!Svdq5sX8-)7AD5E%$5KL8q}6G_MSEl7})SmjRCS_mC9 z336%+^vNNtv=sBpg0|^~G14)UY}8(iwQM9~$VAeZ%tTHc*n(MRoSCy?cU?qC1$k~_)WvOn^BgDXD(ng0IQ5b?HuIa2BvZ_yHsefG>mc! zE0)n>@NOpNZbn`fV7H_WB6)c3!F+;9M_?-z>nnvGsHL>eprI+4@ez!-6n#9dTl-Sb z$}Eht3;KKs#;>KtosiudG2Ro5m5;tJ0+u(>W-#W`9_tzd>_?+b6rgkh^$M`|(mIM! z(-Wu{gZxkuf!Z+`v6ix`Fvl{`QY}570>wN*n{xDin>+$$GSOxyAov>j#l(SrfizRl z-Dr~ydYD4a6I)2n+gREE=5q@*OVHvrIN~56yQhw0qOjhcz}Z6RDLF00jB-#v539<- z8Wz`4Kn2EKNQQxi3NX?I!2S^+xC+S%lRT8;p_YeCON=AYI2-BBkvJcfzNZ0dk3|j0<(wE%T2)H3FaJ+ znzhva81Q-sYMF!i7NJfNXy6l8aRU^S33zP;v=;*wo3O(Bu%Oms+$hX{7V6c~a5Pr1 z2b5O^EPVyN)$++5V6B*R1}xp^R&pJ^)YAWAj7uSVpF*EJgKobF+iE*mgZ6RgsT5SP z8xog7Zoef`NSZv%sDiYho{&=+&=7&JVH!aG9mf3bK;Kwn?f$S3YITtrlI{-Hy&P8B zWyrDuU?-3Kg2c;%##(}T9zy@0p@W=I^M97lYpmcP;IIS`Dh5SZK&Q2Oqr6T|)>4T- ztQ}8`;Q={m!YGB9^=ho^6lzz%j`)h13;}(Ip@xFyfYQnU&tmkKht{<;{u&slg~dt0 zXcyL30GuDGgVI4jcNwHwEfw5Gz5}h5KLy~f8L*IRsbdr9zZSMjV580gmKLJ^Ou#Aw zoZXrvlkTJ~Bv-9Wn+RKWBk<}DY&a4DRNxLiiNe<`$fHTX-V&syAT<}X69EoN2ajyV zEH`7M1X$?tXfv=*Vr7F84rAtor3XJVI^60+?a>=E=Z4Dtf?4!;|NxF5nApQ zYUJ19uXg1-!N=aP1+1XkD*#OyAZ36JYJ!&XhhA$5xCR4a+0+Pa`G5pL54*!|8VpT2 znC^l_vk`VfC@|liaB6=A1(O$X=@gU8EP7Ol~2lQitUDOG7Sqhy_SI~2?b=Sax=m1Nr2W^9AM`+pl z=(#Jj_7KEC%zG5sOe58LlXypN-lyf4r0X$)Nchz;DM4_ zOU$Z{ZXW@wi(vWX0^_xkv{sfZg@p14%;y5;O99J6;FB%DXdlSW0OSmS<#i2vqgqMk zPb|<5B|;Q%-ygX7F1XZ1BWkt;MyrLB!Y5&wU?gvZF2n=-G?uuMKSGVbLvD0M+peID zGSulx9t)GnYr%?q5{d*fDHW=O`s5bUkFdvkjI=X(C9Ebt1tn_S5lm=Vj&@#Tzu-%* z34K9-W9r6q#vZK|D5^1Lq=pO|OuSLo2t79e^m-8TClgjgD5&ftRu&E_83oGPh`b%3 z^AlM2X7Fnn;881AZ$SRkTE`;rZUa0&#!kTmNEV=^R+Bw}HB&`uEu2BXNej@200;|6 z&jDr!)5V~JTwwhIJxh<%t8_noN((^;mq1ZE@dxc7UZ*9FQNZy`E~ujm_E zNtaPxd`pd@v#1pP#WCVQF2z;;JBZFP8DF*n68AhjRRL-0-Os;?Ov}HMxMI|tA z0WN=20eJEdW5lWA2ywpHNbD;{iRr*-xY$aJ6&C~Balq;_af8@L+$oL~CyL!sS|sik zZ;OY-O!16(Uc4vn5_6E3Eq)f4il@X?;tKHqC}EPgTx^SUbJ0f}1$t>A24RFZ81oAK zST~>BG#2Cc7QI9{-UYObUW81VgqfeBCqa=Hv6j(Toge781>~6(T?A?459#TSJ??Gj z*QLO4E^O`d*o|`ZDJ;po$e9VPyaU$z0r1*+#7VHWYpujcKrssvWeREp0P0I%pIRf` zl2i#&az=OntnCme%1rRXC`gV_3Xf1dVgr0+*GZaoU>x?1Yxnzv&h5ppAHvszpJJ0Dn#qd2t%Be+BrxBaRkJ zf!jRbvH-Z;3xOW!=KpFmGF&zbI5Gz*DFkts14?bONSBL>Z`{Hzb6MXeY8_Cs8X_QH3aqj_9=-)LD%_Hh}^* z0skkVuPQ*rhv^2$jth_wpFtBkF&A{a2UNU|reb&37Mf=y=t2(tS%@{i26tSsf}iWH5Cr~P0&BnoFWzzJi0i^($oewybf(Y>UdnmG zN8scFe3K86&J+&98@LelLV^1%gvH?N5#Z~eLOA-Y-TlNvA9aDw83|oA3!Ix#XK{qX znn(v7)>;>}c55DHkqwSN2*GnCEmI7-DMicLJ?d^~-yPs6H%N`mkR<7_GqRvPJVbBE4TIQJ z{6@!v2DIWY+7*%`td5^cAa4@rO?sNXqTQiiYUO`xIs$Y!5OOONqt*JvYNgX@YJya_ z2-{^hxcwlcbvz`01n6`h?AvHqvC)uok+6^oA=h4G!;? zqYApQJ*=W|Xb3BM6S}h(ae){0G8qMZ*cCQb0s09L`l|OThija;hw4;D6iyHuc-yAJ z`>vt~wN{3s#(aaVvB0#|Sf=Z$JEbeoPSzdPT@>F41Nd&-ahyB#)?{iPv;H`*NZ>xP zi`h7Cj!;6<#1ic;owKf$Eni zg>LYxd&AnfNKVlhu|&*=>|ZLTiGgB0ajm!!@?fx-2|4QzS$I;|14@4fp2!v)g&Xk9 z&xAkvCP@I7T8p0$TVS+F;%Z0`i#7w2(TpHjf}r7DEm!0fkWPU;Dtjt|K1=EwrW&EU0PFiu+(KIf61C z(H>&5xInareG(u#h(|z4MUX(VV8=cJcSM34=Yj)H!YY`ET|qlY)C}w1TMyvcNgDJB{7ohIsH}B-tSZVii8HIw&|}5E&x0gPl-o3C2Oz z1b{wYg7Vl!e`i!OVMWn zB-T*OX)^dA3_LIdw7suxUh#m{9`OHUoI-pC#tHOOD6GXtz}{_GwYwoFK7)!jW8L#0 zF$*C*^P%H&0K-A>j<$ox@+7q8SMq=y1q6?vuQ*7PL4ZvjN=mTba)PC3uH)`a=w}qT z#lLR%kp_M12yP3a&mmiau%mBGI)JD8z&_suDHaFG(;jw75$14_SOe-5dya>&&^JKR zD(QJL6gwd=a43ab4hJ+TEcQvz%h%w`83DXpM9bP;X9euJGQ?Y4Kbc+i1la_IQL;ih zN_~^9-I?!T(>2G*bYr$vp!EjpV%weeqFo281oJl2L8GhL({fjzPkQq_>#qKx?4r7^ zKFIKzgPP7bbH1S&&4%))sE6TP~9g(}8>}Yp1@Ym?qySpQ-o@ z_fodY)=LM-dDRWoEXK@x&}?m)zQPb~7-Q^f@w91cJK3g(%{{AZOJCD2gOC2UHc#uR z?M#OX!}+HyhqK@;?xqk7O60}M;w^2pZj2$%aMyU-e9hu-d1l&dDARw@eb%On{`8iR z!yRYeXtpxT)Kk=X@-H>=KYgSZYgSh`ule@pfb=_VY)zMal&3PKoPg7`QW~rC(#Pwc z8A?sx%u6i&tr9HZrX=GnLxygyHcaQEPt&Qj_2^;Y1@8nqb`WfhG2#JjU+o2G-yAVZ ze4|z9*XjrA8AD5bS8Wxwg4MVi5+V~i{S&;$R%9oi$L|vAgVupXSV+BbqUJ5M5Hf@d zqzqiO6Q_hfITb9dG+4xogmB?8U|oe%(^uRfeuD5DmepK@?SeCG?r^djQoaIqMIUj8 zI1Eye(ee7$hI0LCy-NQ}*IMtOzo%2^C+pI+j@m;a>|N;FVratvaQI?DDO`k%IspD0 z1zk1|TIdvL8Yd96Sd?oUh^uHg z`Lg+l<%}iXVrLFEUNJn@`|3`@p7InqirovZ<}cs`cp&ydv&8PYU4{jw-e!~KhE+S8 z2;1K_8*LidEHYlv#L62h}+tb{qTZ8tLo}@um!eD28&sn2zdl|SquQi8hI?5W)os;xrlqF2W+!9T z{9vp33xYGX+#j>&EII>!<4DbuD$jp{){lBllV}KvTs`U@od=sy--Vl?{{; z>ZY76X(qPT-q60)7V3)hjB$@~is_2Eo5jbpMJI^!VDVpuez=U2^7ggo+FS)wqaMPJ zB2?Q_n=N{4_vzw$?M>Jw8?hTHrE%Imy4Tt*;M4+b4t*_b<{$7n+Fu+;4Z>b%T2Gvf z4}#8z4@`8@#-mLaahcYli`II;8urt!(qD~+#L;TjOs&-?n@!`8xKSSM^EdM7E6YLI;br)>*c$N`KjqV7YJ8*v8sCMi(ZQ z!IlWr2Ai5&Ke29WEzPU$|0zQTNFkYc|yNwTA6-tPs!r~Ll;%k$^gZ{j!AciqpazuHufuhB?n zN$26tv#qSYGKDGP4hY?#{RczaeWHiO0$qu*fn}Jv(BPxpNMd1Y4dOGo82+&kLD~s( z+2fi>K<*Ur6RWj{^tTNz#!bc!Mt9?Q(=GD?Q@&AR8f4TMFB(^v-&l@X(k*>0L#%wQ zuUZeYQQL*qJLB-)eud2&D_g6{=03(ueRrKgJDR@c>uaVfqvXS6FC_~l4J0X&57IVr zxniB-g5tPhyK1*)qoBkL%Q2>h)|(~>ZE=@l03XLuc099N)dP1X7b&Icnd$)C`q~V9 zJfa%i5B&n8VCrZpG>tF^TdrA_ST(dhXx+uSi#f=sgcfnu6J2}VDE(iMp-H*{;%sRD zc-l&wBaYM7*RM8)m`9tI8=mMz<35vUUTv%~78~~HoWxpfe~?59GCrCc$mVM<;C@+@ zdJ&V)p66O|8*t-jFef8>AraE`KKlCFx6t|7!azQc+XzZK34ZRcY%9N@;59j%95fyv zjG{}$_TnU3qpdV9vR2qMx7uX73+Z>txZF5c|C);AJnpC*=VCRiI!bv`mBRV(>sVhd zm2Nfmvkr%>*<(($`D2@8v(#$4mD0vwlV}}jT&A5tmU16d&1L;0t0brYEUZ3K74lmy z@sU23ER$x+j{&X^*(v-CI$ZBOgwbo{tm9P1rVV*9O7IQB(8<|k%qiU71gHnOp zr-jOqs)y>{Ec_L^HM(M5xqg}<)6m*jYMgG`XsT!Gum3}5a7x@-%hf!FboEd*#_dE; zVpZn6(4{* zFP`way`vxKUD`tY0%@?tFxg;ja59Ld%VsC@a^n(1jc$;xv2KTGE4Xrdxmo-TwupIv zyP+~>BJ0UD=kJh7;%Tj*6CpL_sjG3hAz0^5;@B3rUr5;<+!Nki$mCD3 zw-|%^rb^Ica^Ac`NTV6L_QuO5A9I9RZ}GHjGygVL87^sC(m6sFAH@!2cH##Wm5Ldv zU(83g8~1_RD|E)r#GkvNA-qy7G9;Q$Swd{?+kUmtT72}2#WS$e(}i3CCoud0#vM04 zo8w;RNbU$(1udCiI&JA;z1jM@O`%O^n_X7xEl#E?{Zs7)u@C(rM6fGV3dLFZaYdoJ z1N(>9({tJzdOPDy<2v(iYZv>4^@lmWtS4HB=pBSqW)ALBhpCz~4$KbKOIghyzdvIn zZgQjg7dKn`*!aMbWo2j0*i5x$?dI9mSbwu>V2Lz+1vgfSp2Br@5z||_75C_$E0<^{ z!4A1dHq!v?U*{P&8_$>;ShcrlXPa%y*@T(*=?Cko#KZ7EO@oi@Fm@3Zj?+}Bd#R2o z;^n85XPJAPnsmYL_>T6qE>XY4h)bL{pRIaXa?E>;I^8y*ujZTbfNUauf6-hrtY%%! z`I=`ne@kyFo+`UBGx#8}QuoamX|>(vjBO8lJA0kYJo6A!m7%+CCn@HdYOK_*s!I78 zX+3FM*#PAUO*TK0tkVuO^fZ;4zM8jM>+FWro9Gbaz}5?~*l~||ra`bEJoJO;V&=Mhy~OT! zpUU~)4}bgm!=?J0#H>nTqiK7+r)ir-Z8gQJt!+lVB~C#urOwt4=dG>G>AEbzUgNLs ztQw*8Q;d}zkc^X@m%Nv@P`pz`vz2@fZJ-kjiH6&T%Z4h0FC@-i*7I%dTDP%MnstU* zv?bd{`9yB3=z{y@?NqLPx}|PU#(T<482yI2wzYb z?mBhnSvE_Zs`>%RHiC)ZdutmQ%ZzJ`MaI4+EAv{jkJ-zdZR%i(GW63u6hpLwv`eXi z_zNxg&zcFi75q!HT^J_Hv}44@+Qa%GhB5jueS1SXEPN~TA3dk-K(7f~_=T`4IDYp|gsRMV5lf$kp#67$@ z@Pp!vOdO``qQ3%bqLpZdRIG&e_W(`?_6wKTrkYEPUQL;{Y%J%-Q=vE6Lrb-LF&7`x zGGmo~vxs|l+)dm*{jL$g@k`-L%M(`eZ@7=#MJ^9FTeW5dz|WM3Yp92u&MC6Y}8!9O<`BYLvw;%LL#)Kx-3|ZgN@%!QRWAxCq`dmV`IG0 z*RV+ILRaE6fFp&RoPEp|3xfDYoTMG9yP$K`{w>UA^|(1}Ol3qKER4I!q(y()gXw%yFW#K0}|S|DumH zUNse(C8kw+wN_5^co{rBW}%RzQ$HdK&4k(T$8Mui_*$=t6739aKkapG6Mc^1oiWQa z)>x#=65ErRIB6P;KAqqTe@!wdEDiWH%IR#ekjlv(t}WM%Z%4G^W9?ME!r0v?8l8=v z#;=A)`b6zc?7Pf_a3dKv)qW+fd@dJccm8DmDUk}w9ne99egMf_IEwAWNT$HiVkWm`!}CXFKOKktxf6XDdxuJB9p6mlev-k zxZ$j}9gPqsaV^*j>X%BH{E8$>vQ0WmK3ZiWzd+4%>P*>*s!)*o70vf zMzih>dB}RJ|5Ln@B}v;z?EWnH^IdXX-bhu*9N<>d-g;ltQL7@GN46H*m)2da<{1OD zzd&!ln3d{XDptj-{8htLu_}A!v8IUIFU%KD>KB-+tY6w5woSJ6vSF--n7Zn_i5Gc4 zb~H1cnar%iP5R-Q5_SNuBvkCG%Qmbq4K{x;M_c~2OtnOqml-|v2dOB4-WiQ*lzh5W zgWu*c(q6KG^0mrr^?tS`PvFm&1LEy;O?1D+F4UQH=JPdvsvvp1wCqprpFV#YO0G(G z$a^X`s%ENJGHIFv;Jqc-Im`L3Y%knxKhNCOtmN9`WMBz)%Lm|zeuVw;X7UIg)kjnX zkD;@+9CpEC?QE?=TMYkMJWlq1fm?%x*SJ?aivPuzViq1kD9`g1+zI})(3~b{RfZv^ zvE~5F3X`K@w`e6yz$#{_{FMFiJEK%ZKgBKia`{cg4)|R*lZ(2)OvP5oHeR;VZA9yL zmIjsz(^+GIUZGn}*YkTdUsaoxrxp2%r(rwdq)J@m^ zpihNW{6H>-&DAVq^3~VW^_fTbeZ(&H1$8GTN3)-MDohlQ>f-b^h8%sMt`htEN4jCy zU9}Q7VWpYG1Gji1;oC2uhv09p5od~9;D>Xdr^!OPPc&)gi)O90Znw6Zb`jkstmS<9 z{+tKy$>(bh;Ku$ZO)$F=IPt^H8&O<>Q%isG6ubeMWUerf3xnPEQq8NosLtWHIqy_q z>V{0DCK+@32}mD=g?a-g;UnO`{t0`mm`)^L`DR=!JCU8F>C9YIA5%v&eKp;2i@u0^ zEDWNy+L8K3#sQ|87EkN>R=$=~=0sDmaf-o1hf`TXg-`5jjZCA^Ok^i>17Ov_r%#=9 zu*;3Vjg8H%AotgpJdLn}^s{wESbw$ffFHwehtFXpXMyeS08h(Fp_+^qiMEe6RM$fv zV^{{8D@XSRmbZug4rn0_r+d8Em}Uz3{A0cxcG4|)C*ZY**NN&Pbp^W1y4U)5hC)MQ zj2dCuVvIDr(N$@curx1e{k50HTu|1wQCM(Ngy zBMI)5bAD_N(@#^tj^eI!@XW$v`3aurVt7DeML%IOHxqd1#Eb;i->dS}6PXqakKdp4 z$FE^lGK=6FxC%R&!|#PsRWDUBOfUROU_5@;umCcrGoOcFK~T1y#({YaD2J)1tEh!Y84BSQ?#BCZjaYY9#+KqYE;pH(_>IUTMy^TK3}WX(-&pW_g_|7Z zFR%wRznBg13)W{_Xd1!l{;A1ly}1|;J8mHu{>(c#@#zLnY3<2GcX)sHX`jGf=w+O5 zF0ib$j%Xrypm*C4n-h|9(X*PU)Sjc|2u)U=_0!=DWw zG}z#H+3vY{7O7NDt^V?L_XpYQ7sY=)n0xo=t^6BDZp^(o|8~`#ruXMRvMYZ0r0j9w zlefkFix)f^bAQ_1HFpl(PQMv=J^lKrn^SIYzI*+C`lG_)FE0|yu6}s`Iqv&|svc4Y zWj$sW_n9PUpXd|eY58JIG=>{a>q_An+e|OucF`c5`6#t2KG~!P4`^iDau%dDq8{M!0YGXy;ks zk?SFNRJu91wQH2=`k%|J26~rYF8dqqbj$R-)x_HSjZaY9X@2VhFL#{QC8Voo_s1c8 z&xO5uh31AX=>07;I&@C&IpN2{kN26{pXoOxba|IAZ7Lf+(c1mG@!I)8;+5%VI_0m( zUsQ1XOmX3jYxnOwc-s5D%h&3kM}K|$CjD^xxp3$6=??$KZr-sbWtGQ@Gs_#T?7MpE z=Fa~O%vWAH`sD4W(=|n$jd_{9*=byZP{(`L7TsgEvob^$EGhV7B|EJ2Wxtd2`hk|b zddnMbZIaijhhI>TSEqelws-zJXu02RpEFJWX|$?-H>)k$&fE@VC&}txAHMhgdjCuC zw`)J{RL9A`Gh>NK=c^Cb<%^EODrT7c)$gnyS3mE6_xa_Tl82A94_$!!cF#|g-7Zh6 zJS}~uxk48iQY|UgTI+q5eWtmF&AN2)C;wa1m?=@dQG8a+RISoXrcNfEozZDPqbjeg z=5Je8`^@*vXnoIjnNL8=EzNp+6}mNaed%<~VQRgf_6ZK39shF?+yj~{@!sD0iJyO9 zc95x~v9oIz=T1z=e>=Pn8rOcE|Iv0q?Rxl21D!g`yMF3f9kG3&-O$jH+oP|JYd0}t z(xwS-qcnY~Uo+e4uXnFC+W%_9=&u3SohxMh`q`v zk-mCec|K-Kz888+viw9=!~Tt?5Dy>WkQdROtmqavyDgLEcaqU~z_VC8SwA~sWg{o(%ZeDUsE z=|vmPwmoHEu&AKt=~?HZFNNQ!d=^{o`X`p?Y;{ z@++lkcJ+mtXR;zDOMBNQ&h>M%M8AU0-$S&$B6{Qpe+kn2ooOXB8{+BGsI-fDo?dttCRdYwDBqsMx9*~@$?4LUAui&kH z?pJA2n_2a89x-veFe!V&;L#KM-S%^8o2PQ-SCcjoGspdy z%Fhg%l`%`46*Obb6guI}&>10JTMV5WCjI@_-`-gso7V3&6s*2}?5XP0*QyxxN$q;8 zXxsia*2abGfnTm~p5L8y;r{WWBkxWez8L->@ne$mfz71G`he8#z7hKd3>s`2ys`iE zu-M@AHsS8o)&YE~>~hT}$uPA>Z(Dy><6iArbrE|_kC@zVX#XyKXNL9fF71%vBlmE% zKd7CfKKtig)%&VHl8c%(hGC8k8ke`e(P3Hl_q{5@!Xp-hKM4EO`%2G#-K;wo1?Kp_ z_8ZmyW2g1K-ws(aZpl=iSw6EurwXIK1)7;_1({3f+>vtzr`60~n?3zh-1`9jszZG@ z&OOr0+V_Effp>B}TZ!wEJTKKCZ*;le3>B?3=|-Sriyn7*-Rxez<(_q>wRg}Jb-J)6)|UR``T`)*~? ztAdoHF~{1SpM7uZhh@xar%t{tyUgp^uxDh~k3nT^BAfer=w0hOdf9F@9;9jPcFh^$ zW;L(joYqbuD+X>E(O^{L5xE1)d)ftd_kQ7)>$JtLhn3Q_PaDd2Ru5FZSG5a zv)S8bSH`c1ZQU(U+pBQ;f=(%GlkX=tPA&cG)PeUu_{NGp{YGa*PZ$#4hlDFSe{jD1 zW9ON-ORG}4C5y@GWFfg*a@d@4IW=FC{fCcFpV=$!&-D0l-hC#t&bQ_&6Ygy|<+X&9!V)Ros@u{z)T}jwarV4~dBh8`W&8%`G;hdhC~?^04wZpTa8Y z*Ywi&ZEWe8KdO1G%~Y!?MdKIrf8t$D@072;?{v{NKlj-8V>3<|PQEz4`3O0Zd7@$A zv3ncJ=KW|VpU7NPHu!b0EaHy$`TfUF9tk`8&xx!v9}CN_oVu2OW6{097k_^X*QZen^JI3Lyq)5cI))rI;smz-RcH4`{*7;Y_iq=~>3z4wJyJtTx_tG|Zc*N7 zYki|#H@kAjbMD_;9u92X(_;V`-ZgsX#5Pm=&1@HMn!R_nB4OMlsej+f^i3o+AlWT> zXmaONK6`0-(qwsJV$$KHeM!F) zL*pukq`2yTZGYbI$@k}FpJx6sP(Pc!PKP|+wY}AQ&8YCng)<(`tUtZ+_;#U2=d`c$ zuQbf{+D`we+PnVv&cfxlG9DNoZGCX>VW(#v@AJNI|1&|Z|I?~G{XytSk8MSnjw}9M znZ3dL-|Od+A3D6<`(@uxV|9)65LaYb?9#H?9pBTwWle`WWr((a?o_P#^!jV1EWwoT zzRb@l#1xU#*VH$-PgQtc1m8Ee@9J>x5Zm_cn_jWkg4mj??+CFrYdq?=UE7K6rtF## zG{5!SW{*5udNlI9)OcjmuZ=r-%yPANyl1!2evMOiug`6nkVONcM!1gYHr`{x!wGvQ zg-z)`BRTG6yfm(OY(|UBx5rj;Db~rB`Njo9mYv@+=-i8!=c;-!E&1je2gMAzNu5cS zn||9gwOOPaCExkk{aMES6_3K-om1>^4(ga3IdAN(3D3t>j9fIJU60lsZ2c13Olw`= zr**T$MxE=OGLJFdvsv8ebDO0-e+_OvGHrNxzpkBfnrySJrUzJeVVVB7ZJ~2eBhjs& z+h_O3UIi`e{SvxvjR+VtZpg`@Er%Q#s2>nAxOC*+3G1hQkNc8vC;raF)y=1toLjsc z)T>P%n0$Di;YCKIbK-`itfZjC%dz#nT%W$(dpB$9!j!aYDa(?bA!8`C?A)~9m*;nT zkgz=IXp&b_(2SApBTlxQH#Masxns)aIqjEj{&&dTuV0C-xQTE0`Iwsc{KViSX_9Jo z*2F1In!fI_PqSw4rdMY}YWlXmA5}CZVEXwf9uwS$2Mz2o$a~n9k!~X&44f9U&aV1v z#kHfkpLb5&fBgK%;*9T6Oqn>4$mOlRy1lvZ+Wqa2^02SZDki)>bIt3&#hEP^E|^y` z|6#_%e=OHZzLn^L9CMwo*!kzL*J$Yr?gL32H;Qx2EiPqeu1Q|>dxJEuvi$1Tsz&Gr8MLvHoIG5p%-{?XQ>=8pJx zc(;-K*yWQi%^VP~j{9e9JGXte_bx~S?dp>kCfCbwR!OH0OL~~}UsBTSoslKg4>s?c zcYaQO>g$x=DJNmiv`e0q{3vyG&T`Q`_D15`q`pbL9G(n0ka?0EC^$iA(6_F3)+8GHAgG(9k3L&A+& z>tpyq-2z>jUu=HNPtvt#54X;9o8$_k-v(U2arV|lpGQ5vEfRk^A9TB9>n|T)I`n$e zQ_Tx3mu5fM`QrMk_m5tkE7(y#Ys<326%RIcKAHIZhBOa;0znhGS-KW$A=DBU1}f*QWkR2~0VfygNBN<^6)ntBrkn&n!&T zCrK05g!Fq*F#kYu!%{{s?o=4dZ}A<`qgPnlh~53dBlV*S$G4c|5pC(7XuIeA ztc!gP$DBR?p{&uCs3CE8XJ42-IPU1!3qjo-N`z*_+aap;!H}Ij!~7HK@2u(h;x7J( zN%{4u_Jy0erN0+7&iiD#ev{J7tJhDAKCyE}#nyhTZ z)=#!`aqxGa+D_TaXHeInn+BG3b8bG>=A&kZypiUrm3NcoUB>lK7#1)Tu zt!WkDJ*ByKvptQCZabXL*gdoT=@{2^M9|-T{vCO7{IE%#C%BCMZ}7XYX(9c3ob8)2 zQZcD)+Rd5wrzH=&?mX>&v%gQJUQGUw>@~O9;eL)YVjs*tlc=A)ePSQ?n7e=eCUZxo zUQ0<%X`j*{B_^f$oFj{}j=k5k3D2LJJ8R`sS@-T0Q&-!~Ihs5tIUwbCx?)$(#~lrN zcAYseVAzkL69)I{m(cT2`@kl*Egh>*JX?DE{{6B~n@vn7uW^6Rd=#G%-(<$e(PHPb z4JK<(Fplc?8XK}$*9xZ)gLTV{NeAg!s~T(R?A?#t=LL+*CF(&*fyf(Zqo=askWm)2B|(N3?w9y0chGjID! zJfUQNTmPK*!{rxSGffu2wlrOI`qWhFzc9F4&yBs_bRXLx#7E}&(`lW(jh&r+io<*7 z828)Fez*P+IKEq2@5H{c0Z01X35)4w)83|~*^_TLvSGM~sfC;Wf591{-hGz!pE2;+ zpxhxFN1Pi~8r^AZr?EH2>>FD;zGy<+*p&lUw*93|eDp16--7Mw6$>m|PrOz%9v9Vp zTIsYgV*~s<|8mXsSz?*HF7;W8ORDRf+_@JPb;+qLoc(32)uHBrt!KLV$$wsMzxKfV zRdb%F4xg)7HYYc!^oOawZ*=$B;r)9z?((eFeV2cYe<{~~FL-;r)VF-9Y`bk@TRN!z zgs)SkPx~C(Cd$6sO}A)zr%Lz5=h1fKEp z^4Z*EyIY(~#|C~bFB&fO5Sl*o{y&n=0=$ajYvb2#efPRs+z4?35fUJRLvSsHAjRD& zt_@C*;_gr=F2Sw1CWJtU5JFt9e<%O%;h}}FcXwyz%$eD{?|FYaVnf@{Na@z4yxW@| z!9CKuhNnD@-xOUPzA!u@YE9cW$(y?d_uVph^6-C0)Q$M_x7Wk23_Uhv@SyR74h%am zs?E3|fg3)eZD!<1bEPP~GU3(Mi9VIp~q9o(p>j4Gd0w@#=vc8T`yEbKRFU~Rv{-8Lum47qN;t39W=qdBWe zRNhnn)c&Cj(XtF5&1~;#UxQzhxu04=pA<9f&bG7lbL)20pKd(Zw6I}ry|{67li0Dy zJ(K;NTf%SP{^=y@Oy%uL!itKDM*Wym>DBbo^NIgjT#DL=7*N@~MIVU{a|e3V4sG*- z<_1@d@D`&tKJ>rS`bpHPm`9O^TD|aVwtO)DZYVG)%;&uDfXL9Pk@I3Uw;S8utK-d1 zt2%w}fG4es4{kd(CL@N4{Sl`~UY$C#i@f`io@}(9#U714cV~3$d!TP_U&{dH z-~mJJ!=C)sdgO}Xr@MX*)yf_>w$2^()cL$?L3xvn3iO!}S{6*2cH#4!Q+`}{nSOQT zQPxi9M&0`T>wj#CIy~@hQo*oVFGoo8;IdnbKwdW3x%CcT-X#XfrV|v5z=KJmm zq73SavM;<(9g2@-_p6hXwkrtvf)>6mTUOWPY{g5JOadk1X?!4tBmTl8Y_@Ak^WDaf z<}=QRTz_n=Vz}voZ}-4ufk%DYnWHs#q&9LGbwCPP+Wg9&-`XAhtX*=#ht+al#?Ds)JenqX1JDmJAr6xVF^P9Bo9S5{8h~FB&BSD|olyEQcUQ$j+ZQAqB z1>INo>e$EKm+X6?_tKv2yWLDXk-!f5Thj|E=QMlVo@~K(X+KMC;B|jQe;nQ999-G` zYvP+pkFom$9;7{)^fd2Thd1l*RwAf8OE0?4P^p ztE}We+4mohir0J{_IY>SqWs1$O`mt>bch2 zT8WxF-=lYbbc^Awcr5!IXCnW+fGhG94@Emb{7&%9tr@Lz9`Y8f_4_qI#C~&UtD$59i zTiaLLsHF`9%u=6yL2p~%jo#UIb=>>-0qsMQeUp;ny<@*bt%!IM9@KhYNKj~I#N8NC ztgxL=;-=(2$phkVMdr8q68Oz4&oD+iU6Z5iE0y6(K}GO4?+4#Y(w7Kef|zJ>1oD~l zq-lNS>{7pyeI=Zd?!{SUlWI2G&ag6tG9*yEl0Bn-W8uQLTc4eJ^5*&Q-0Yt24#s&ys6H+HA~8Q75`Q( zuPJNzU7Ro>b%^*NP(?so|0WUOLO)vx_y6mm-Ov>g9(t=k%dQ+E}6gPj^(qSN$g+B3~)b zkh|n#loi@KW3@HZXQJ;&zar4t&9YuK_S1>9Pc>V0YQyiQA}h<+>8JBQ>ATtMyJfTa zg{hnIjNzuC%+SGbUAJGoMzvmjSl8A#-Tcb(z#8hc*V@4{-n`iS)x6LA)g(8n^%u1J zwb!+Mb-VO`8af+~7zY?P=fv)B|a#N%UpudYO~?7mpL|<}gleZBdP_C0d~tEnm*`yGr(bysza^A>|GB*KafjIK+Cu0OaN7ijgs6D#=%?j zWI73-d9TB*|%&t+ANmRTxG)<{j$%?7jH($;H_wT(%q z$&jn$3pKk8M|G)+E>swPiHMYbP---r)h8A2K@*rk_o9R8OwhPOEfyY*)gV12+rUfC zB+3b$mZ=F1yaN z*mcM;+}_nT+IGbD%|6|=+f(m($hyxt&)+9V=Iv#-VQpr8XK&^#Vs{5eRRyOrdmy_% zcd_6xsG0Ulngn{z2sh=NX}{Clr}=N&GxtT_chL`IEqXxGO^EXJtl=(}JIVdrKD6<_ zW`+$vp47K!5Wtsz3bGe||4VP||y&)fq2k>X`P6%&^@&t0;-~2$yK*Wyh zCwenZCQ7=2iD0fU7zW7%?rYS4T5dFG_#ANwk*p~MZKe7Zrs zT$4neX3exGv+T%5MS`L;9xHwV{&*1(kG;SXaxV*7|Ou%;%=fpOa)nRZAA4l!w&m z%pSo5_f%)D`@Arkd8QC5oXlU;d*+VH*T`r&fzvwD=JP2jYEn}$ld5Z*K=%KtR}ryEUN<82dfRu=~J3sIT0@-v#Pescn(CbgQ; ztWYnI?!g(-UlFGrsz0Y+rC+FBA-}Kf=6liih}ZAtB-MJ^JNgxx#H8ynW10S%W(p{n zw95I?QS?38GG#x_Io%E&TNkaiD7LD(#$~#h(v_53JHc<8r6Zk$kCgwWZqIZ_e-L8b zAC_M#18SG#Fd9vsX|>M)(`m&4dA+=|B3g9@^mt#@2Jg&(GPA$DD|J-y%`o0N(Cd>` zZ++!k6IAJU#PmXc#4^&m(0o?^r~aK`iFuq)ytkj%?2u;>gF+_<4e;CN+au^paIxQb zubw_t!Reu<;2SND~SZI>)*r10%d5-EF!g+>f8yMiXrb-ya^E@U}y8 z+x?;DR+A$>#Y^Fh;LL=Wqm$DY$|;r+QIn!o0qL4X zRjjq2>684StcS*FK#h~-^N9%QCRLVd2lW>=UlyY&*A7!HrIVSqv{kr3;7!J2R>6E> z7gT~o@c&@jg!AZZVm$k*^Mr6VQ7ie#TPpO&=AuPnP?lnE_!-VO++%o}s0)`tXZin_3H3(y%&VUO}r?;SrZzlLm&O%Oun(!ijCA&rtD^B5gIA=&) zISrpKOcnj&Hn~Kut-L&BiTEY^Jg0+bh$zFe+hO4SE_}ddSgk$NT!{Ov195!iD0#PS zdu+bo{du>!S6!G>0*Z2?tRn>unr-B0Rv))2Nl$LFTDjoX?YI{Ua-&2O6u9X_6q zZjCLp>9+lbbC~^oLqtVnSy~Q8bEUFMy&Z#?8 zo%hR9<$zy;s)yxcDvXt6x!0+^PqT2r1OdFIT;f83I!Lfq#>g=-TUU!!JNbps#tWxl55rc#5z;@22>K$eR?a10{RJ zJ;1}YL4XTOuqV_qbSD2Oo6DocSHv!Ev+JCvAHPPhP?#>>B^bo*CX9x2CEw+K>AKIoA(+MWuuFNg;3m(9JD&5M-2*i9aqQ);)=po} zEK#Z0i@VnS)lLmGS8pufl59TI5_)r&bWLX?cEr!4adiRsQHLzH?JN0loNHece6dAoNc^A++OS- z+z`nE(RTJzkCLb5Zg%f-Bb@PU7ONXa#(x2R&!L=|oF2Th+~e#cp1bU9{zjghQ^>yN z`P;pi%NA6CCwL+FD}QAF&gsCv!AXXF#(0m%gK#>4=k`o~PZ-ON0u#T1S0mUg=*exx zodaIVIPV;96p!IfHW@_$X+W*ifabhYBRFc%V2>tdblR-4q@ZNcd~P`P?X2 zE1b!n#5*EfCNUuoC8s1Ekw`Qgv5Uh*7x@vkza9t=*((_& zDG?12js(ZyMu_C2{9-{TQ8TCoPe9E;JZK1)fQE}DN)t^NUl#ty_XmxqAOAdGA*=#V z=XFrk9S0u0GBGaxF0zQ)fV1*Ta5?TN@)PHa_lPlY*Bu1zylX-EtQWr(%fUIfT0Bsa z0-ERU$TDOxauInf>5k-ppX(@aLLCVew|&4lC4^W9wXS72O4MS0(3bV$R44Wb>ecri=Woe33$_=qrCB8!C6ngz~R&tWFj# zyDlq{eUoL%V&yh@4+Tf@hhn|rj-rd=pnSjlzKkpTCA}pT$TU*Ev<}*HTY6eHR(?>i zK=DO(MJABHmnxzDas&N})=6*47Rem4dO4+V!joybB3V91eqP>Dk)p_xY30k|xn;Ec zvLadaRu!xAQbno^sv2ciWrFgEvQ~K?c4f5oux6uXoVJyQRGm>?QB6~otAv_Cb9^XL{`>Pf9xsJW*V>1P?#Mt{QweWANw6nEs)6a{iZ(J0?1 zPgcx_O0Q{3oobu1N-;qG0<`BO)abmG*2^*!?UmD&8PN6`WjD}GUQ^%-mg22^oP3?E zpY%Ahi1BAGgVLRlZ<3#s@01hr!!lgC3+spZsPR2Ef6?Wf*?M!1q@ zF?OhXUMW2$O_pXc7J44F7n~ZZh+t4T?xY?=<;^^1o-|7Oj%oQdgjohkP%mmR$&eMG ze&vAs!zuD1^&hD7=S#mzZPMw|flLEsByn*6l7WW?xbF}P$(LjZb%XMzdqADyOllk* zLDx~WR4=NGl#{1HF&G4O!1J(n;L~!0@B+^f4cs3A9tq2+1JqE^^5@Vwa9?A=8?-C_ z3ll&+?;C=oeo&F%#85}&Q*~4nok`83Zc{Z>EqK?g18;+iP}z8ixJaf`CDd4YAKe*h zPcKl1sq54NY7Qt-$B^g2CnTJ3K}ALYv?CL$7{f_|NP)`eNO1RP(G^c7GpNy21T~tp zfve^Kybrb*T$P7n2)GvTz<*;lRIWdQ`#DaGA=^P+v>mFZpHco)B9%!_f@=G4Pzh&4 zFC~Fj2~9SW<Q3k*~;)P+h8F5@7b1N#{#Tn8QpM)1RrJlj%Qimk(k5T#^1 z)NL$_nC066>!}J)Hdk7Uf^*PPo{yxK{k;==EHdS!<_Y{R#UN52*lMvxPK>E zMGBz>d+{qoYpQ}`(VHMf&e40R_ArOr(-BZboCVH0w;`6myOiY7cW5PDK$#hf6g)l1 z-o#)S;{swcUWlI~LaAJ`J-&x{53?L6N8^FyAW+Qz11>rHsUc()R0?p26)?ZY;v=A% z8L9_}R7wDqJ85JvT}`i`9^rO0zC{%db@-#827EiIqH@4JVeKw2O0ns z^|!%GJ&?RZ&msRJtn?Df1&U!S%+B{jBk~hXX;H9aXC)!1j2weMfG6>Aau`IH6TcvC zC)t6IBzt4~kY0Eog%doa8#;sNiX9Ni#B=b$qy^`I|M+!qw||4ZA@(6`;eN@#%rIFs z+FkSo6G*f1wSwcKf8ic_fiHh8wL*51dIGgf`QYg^2s|i8qEN+yt07vy;J>3Aum?mJ ztiO1j1bi^56?8uMawJlN=}2skFkB!*#Z)M<3kg9-;Abh6rtn=7Hu@C4Wg3MA;Y-M| zc%f*Bq?%Yy8PQk#k-{b9W`#|fgWM4OE*T2d136Fu8%gj<@b*G%E%o5&MC1}4NIxax z!Tq8Pe2}EXF!Y0Xmw3CVt4N5;nR>FN?kI≀XxJR+wP4biR_0bpx$iZ&|Ih1_|K> z3I4#Yf-|+7`l0wK9U!>MG9&5oVX{22oVyiSDZj`FkPpIdh=e>xjf8r4BLdZFqAF6$ zv_?(5ZoE|VAbp!r!Lx28x?5Z$^b@@j^+c4!9Q1$eJbHm~9J(cUy9NnSU7_Skg(0RySfngO+&7*ohg%RSeLpTDtxH!bp> zM=r37TvO2fikIr!s$KMRZnCYBqg9Tl>mQ9q}cZI*J3Db!K>PN$Gmsm@Rx1i0um zRM%Ibodnl8aacD^nkt(3n?Jz0(>+Z-+uvK;r+Id1BP%6fdE^3B@9N@`YIIqv89wW{ z>#EoC<<_yLb%N6kADoBj?S{7Mo_K%GQ4UFFDK{zd#0MIDY=aoYaFclGna;~#`Y0cv zYn&ULeaHsOW?dm`e)UyeFQ4u~OC>!@;w$^gxuNZh?Hy4S9oRm`S>BJ)54MTIt2(j1 z8okfT6W`F*7|t^bgeN$a5|QGGG+g)@#$twcGAZRN1j(YIh)F6lKd^QZ^M6r}M_yRe zDE$)Kn)>ckq|Y?3`*IKGWAh>IKGWXtFkM>H{JJG*4^y;hEb&QXl|CUhv1-tPzD-_h z*%vCf0oQ}pp=<+-y(&*QtMO;zvt(l_rAo!Q}Phvm%W&ku7;q&~fN zb_o-7c{iu#U|@FaRi%uDAZJJfn~wrm_!ZZOPqb}nG_TV#dh$;l?}pbs{a~_Ao}|4a%O>RF>)cV22Hhy%J9;<0 z7wI9Yk!=&ZzRv^#$@r;GBcPd_@_wp{eddyBV$$FE5shsE%MZa4M%9?neb zcr9TT{^_0a{e5*+&qeX`?XEYfYKgghWUnx`d3j^~hfR(-9YcC4siJ~yKmQb5QM^|_ z*Bmj4O_RhW<;ogLJ}B^v@d|obki}cYTc{fx{25zPI;O6_K0I`lj9c5*HL%tB*fH+; zPkqXUhPL!l_x#zf69mGPp`Erj#oZxlmbZ&ck5p%s&H5oAZv-g(R%j2<1hJa$>yq;S zMLv@$-ua=yve%^{1s8a){g<^`ShB1n0P$ZUzw;TsR!InLQ<+xq!4H559Uzyk9u}dN9Q5^1d~}>f_!5A?Ybb*8(MkA z$~W@*I~KZcit82KeOH^$xq5te)Gbh53T3?FSe&Z8oJKv^mXUDOZxCF0vOCj8P^1$|Z{jTz-GYFjSU`p}n#l$+-H(hnyb2Yge`69X*@7EMiC6u*FTo}_=c<0-d z@>pt`SFARfZLLsLv78V1C8C-9QGzb~hiqT|d~%0jpuP!Hcmkbsg<(iI_ix^NY65kU zo6(ffWW~LG-uVY9V;Y9%Z>V2w{Sb9o$FE8LBrgL;V{fzC=t*sAw*Sqqm+MR`v;o4v z+CvSoyk1cC3l(2<6Mu$tMe}ObGiH@>Cv(zPU(+n`HuVa8r%>1LE4)_r6OW2}(5_JU z=*#`Gh0<9;ziA&p?ejpyf^)HO!FS$VG)h@$+`+u5Iax-??x9Yul+L7o7EFs2UG*inF@?gbEZm<7!D~PihFowp>ppd#?!VX-wSLb zt=Qpqxxi)$Z;Xkx9^H z2YO{9PMhBKRY64bjToxf-mtt}#~%~=KCV#zr6IfIu2XNZh9~N`xvCm$o|7^vG_O@K zv&zZhmrHq4A!Wq5!V+|m{)l;-*!Htu-D7o8MBji9xY~8zkt-ah>1Z<1RV;>`kGE$A zf{WNtdKNaBzm zN^6;5JV6XXS14*R)N4=pPt%)( z(_GEmx3b|%o8+kQ402kqQrtr|)O)3WjbRo;;a9jlT*dUER)?*hJl~r3Q*Zq1O_d%; z!wPDE-$tXG$ybD%pIZd<49^R82{Bz6t$fR{y3Pvj>N44D06w6_5Kif;* z9mQVX*ZwYLruZy3*L6gYXI;_uMY|8y4aiH%-+;@)xMGf0KGyJA*uJS3vod;r$XWKK zG7US$bV`3;(ctqec$r+-xT12CV77Us@wISnT|@IBWogKHFE#lG(jPk{$`TL8ZcF>? zw=*HGVa;}NA8n(?gq-8f=08FL6^LRwb{;><>?Do|^z7}3Q+*mwY`*TErW+C%>vL5- zTkONR!IlZess{M(HHV5>jT_uMrQN-*SrYIw%^A%U6>a{5QrcG6TUilUh2of0Bjj^T z+=Z+ob}|1?%~Rt5c^4#z-`VqD{RU@0rPeSP*Lr@rFQR{F8!c98nRBuGB;90Y)I#^A zpPcesms8e8&*t|ie)H=;O-!3guOpto%Jkav?9QtG=7Ev}KUbG5Xgta;Mkr<>@8r+? zn)|Bekap%)oXo0bmp^qx*~h3;sq8z;mefi;C$asq9261sCKnk5YClI|=`qhyb9D%# z9a2BB$k~vEoKjsgJeT)jpKo3*_`(!WM#*{4u*PAIb%HFWzvdsRh8N3S&08ksppW@~ zb5&>@H3SK9WL55RP^y2tS19^4t|?5YIYq>%Q%UgMgJ-&}^h#jujXGIlJ)Ikxsq zqtTJcY9uqY^H99RVV+XuV$*K^ zq#vAevpCG>df-fDu$ylDotq~ATXve&*relsR3Ek0$-XvqDsnaaRBbXJAd)?!B}aU= z2erkb%DNQ3v`sUI#OyMzsG6EDX|7w-K0uIiD5HVm{1l`Qtb`unatjKnMW5$G=6 zZlgbL=UX-YUNYXWk1q?h%jbp7Ck}lb`K>E^x~|gvOr<2^MRG|X5r~}S_GHy!c%sltu6ivEurR}% zp{{1}Sotrr$)~5B>j|jYQLS}eB%5>v`V;zi^#ahbbThpRkp;G=YU=ql2KFs{gJPj> zqrsprRfiC}c{e3bW$@PYx&icffah2mgkThU}{y*W#_~t93f|r z>s8ZRj@$Sy(yP@?bu#)vXyg8}Pps?Vej@MbH`6j=9C53UE_}-QmFr! zd8&@;P(=j%9Vrvrwg^3%t3~1Q;uOjGOu#ix9ycZ_=9ENsC%Nr1YiHzI7zl$ zGEib+j_NmA=Xwh)KheL79zX5yc{Va6VoO}1pBGurq8;ZP_t>}5ui8)%(;)Nj8*`G(rHtG(_^O5VK9MlGWDSL@s zvUT)6VWX!ld$(W`Hecbhz7g- zZMQjb%ymOY<6HR`M9a-}ws&n8tF>=@7I~jjcHk^2uPGc~DU{HDu`#C5vC2>EvG!(; zgP5u)lc$l##F@wt*(UXNx((Y|JGBw!x@nug*gBo|;{4;7=I+6_qnD&Hs;3G8Fx;B<#{W|7?;H763 zZw1+2y;E1IpJp_`Cyr>oDiUNLm|Nh~7cJkZSfS7;%T(7i^EBt=$A~QC719%5M9bB; zO^Fth@t|(FrZ1=y+bcK9XOjttL2MGe5d08NAXiGaOQYyg@Tb`ago0Pt4&s0ij@EXy@3=AobP%FkQ0F@$xZ`(2I1m?t^-`>au30xx3$- zpz6TEzHaM2i^kGydSRa6{g0o*U*_||vd;X(ly2sGhXiy8N(gA{H_O-0j|ePor3t?n zb~)5HBqvZB5ad6?Pwt2MR|oh9<+RF-I^V8KdmZ4-gX53J_KcbqJ|*Hw%$9bV_Kiup z_91b9#;M~sNA|I{R?LCQmZUV~8I0UfM_4eWqpX)!i%9R$(D#|azDxGzAn=UnlHd&js&8Hd{G`?->+wi2i zq#~zsRMopmyryrxyh9KMHSc4`O6F4s zl-~`N=IN$!y7vnB4jfr1FmhttGhO#sCQ&t+r17)1_B-X<$I_%;O!r1#iPwq-3BL;l ziXxFb{41TV7^A9CKT&VeTvcT$7RiiEBDo)n2Y0$e@R1)*9;37jPr6GwSk5R@RX5ag zG;3AivK>SmQY73jl%VjgN-;~bOyAD9&>+%x)OFEmv_6^@;Mmt*mZkVxv(Xsl6&Fz2 z%G~-ut9`-7pdo?3{P}@@1)m5l2!9qmw5?zK&-jYO#E#CC_vvw6E_Pj>#%goQn1m4Q zIQJF%C)O@iPSlkS8xsn`j(OKA4~XX4r&als4lX=YfaHySyW-vP;`a8%-2d2}JS(01 zE1!QD@nG+**joc~mOKo6arTYno&M9RufGZd3nu3kfA05H_w9JWf`YAI#}%IVeywOy zkR&^Wd6d2<{0YTjt%q-?7(#`@5B z$6&K`vzDv2Aji2sJ^n7I^ElT?KGd%CRtGl++k6)4U5Xld3OZi+SjYzFnSAUCxeQ!i ze`t>D__}r~KPgRyp$g#*PCu?vyc?~TEEIhat`U|q)?6sIjG2h!{wDq*z8P^NX zuX^(SCF>hi*VjFsy@vhFar)=F*Wou0Us!Pd!#~R}OK;D4xbMIAZ|;6f{`@@eUT)*( zs|6Rn*gu?m`Ok~kH_PAGfB5Z_=*!7sq+(djo0{~RDUIhn4+O>H9Bek@k)Fra@w$2X zxvn^7IM;A6Y?UI(*wZ&Zs8h(T0E4xcN=tkb_2S=S|6-Slm&*EsV~O7TWWcQ8ZT_+5 z5alhrS@6ko#)-OJyd->-T&mruuh0i;|B#KxfA#{p5iZP*> z>*x94I_m1`%yE=D9iAGNh;`3>!c`9%)sHQ&c7Iz|z0lr|eU!bSvBUTGud^TC zzlB`?bff7`{(b3#%*Rt+4gYj4fA`ld#gBh%EqU>ERqnKpV?TO6HGbaxb#2k-A6b=k z^;C1`=2gztyc-e$b^%{b_hwSa_oyFuNKcU9$X?=?G*#J7cg4Eje_L>AtJAIJt(N&& zP1EJ$C6B=ObuNDmRxV#{t_)@(w?(WEIqtjCG(vTZa0p{LKCJQVFy8N?RKlfb1N)Qf zrk~n_vOv6(P|q%ONjz&f$M`0ZMEn#yPdkYMM0(M2{zzUSZ;(LD595B~?BTMx6|6R% zJ#H`0an?0%C4aUgii%KjwZ*z@txeS^t0F#&dhij=o zc!(uvlmBGj1|JLf0M)i07xN+EK*w#V{nCTdlTtn=|4eF?JR>dfPGW%6p0#Fl_>b|m?OzN}cJ zUu8Yvea$+<=+X97(~4}W8o0`H@TcHM98IT6S@Hz=0@=UP`HY=9NE!(rqJh|r+$ z^$}#`*T}5M#K@?KOW~Tx(x^>sddGH)9TWSm&BEwW;cr`|g>YI$w~mik8FQuWz4)1l z(~@>|*p<97?s2PghFU5@q+_>oU1x>kf9N~hz3v`d``6F4#i3un ze|}N0_Gd%mRkm3?0DUYO&t6~uxiq-ob#CgX;*a}t=M;=BhD=sjSDVzd-1gBXY;;Tshjb>j^i4V&~cbO+QQrPuK>l2yQCKPMi8&ZfiECykdZQ!NwW$#{pZwQ7m% zFjLGlFc+9s(g4{D`4=Uv)~N$j6P2@-9{CR``2I?J%lgPJN;ROxUJj0gqtIKDO0iwC z1ib~{f4`^N()Yocx(_}Gd=-a?Vgw1_4OQ-xIbcT-33`qY z#x8B~>g%CHYHP9eob|fbTJJqxEUUqC&5~!` zZQW|^;5ER<=<}!dd25qtzCoss))(ui7zUe8oBy(WH2-1xXkZx+n+966)?$mu($U<( z#2CwUU3DU(%{W-sB%ehs1D{l>xE5JQcT<*X7ORWpzfrBxK(Vjz;{V+8x^wlcP0nAA zGwz%0e!Ok`MUV?OaY0Y&Dt8`sZgd>7FS1RsjkoV|HL_l?zjL~AzyZrW%pr3Idr~>c zykedo{}Xo>>`X`U{}D8UUvLF~Hk|o2ZK zN$SBLdIhjOh{DCVWU=ItWG0jP5wiDBiR^%q+kRPoKiqVGngLDtOw`xI#BLB zCH}z*&~A7+u>^E78elDXQ$49=pmWIrT~Q*nlmt!+I6uqLd^DaoK=R01V0K{O2fY}Z zj8-u^XE_$FXw$av`6^Vn&iGEKu56Yqdaw-`uzez+Q60(zClSRi;6 z4*{}@8)p%Bfeo`9kB7L;BC~)svK)9gbAdbpZlV+yNFA4elhVRUIR#X$7AoT<;KB?7 z9p@h03y5%OKn8%=U5i~qrva_L5y)Muu`$R<(Uv1mLWLs+Zi9J9I`F^<(2c#shGW0bXrOAm1|QF2 zP?Www2g4P!Kv$XxUY)bi^;ma&8r)eH_8N77R%a~STW4T|?E>abA~;cJ!-^LG|Bb-k zfNyRw#KB&?4x%m#*e#$YfuDE*?d&uVS>^(1$_WH|B~Z;S05kC>mW2T`2ABZxz^7dT ze7l?INwgTpg(JMkizb&=arGQyA1V0?lO#=!C8VwX}s8ycXD5CM+Byp;yxINMP@+0K)fw_;jGQ zj)%VIK^u1fC2K#7jz7?vieVItz#`+3rNCw)Kp%JqX!HL8o5zjIh%2~+c#gMl#n%8A z2LY0f0e-&({_8zpwSB{q;hYQb3ZOT=f|hQBv)X~s7Y|ht;lO1h{&#P;uoNKk!8=W$ zVf6%7&NeurH{AUjw1v!f3)l&RU<8K1QEyQraKHF)mKNgf17Q7xK{ZDJ@RlN=)jvRQ z%>~Nj1mM=p0u^H%^lyubXb_f<+R#84&D;1K;FBE$MOsT=q(eNPfS;uYh_Kim!xt zXb=OK`g*BE2 z1SKu;5m>*mKpG4Kozn~WT><{mHXs`f1ZC+&(4k%eq8bJFegdNRJG8wT&nMmj@9;g) z)~4f|VHE#_+$6^ZKqcD+GvYA(tQ>rybMV)2KR>{A)CpetLi_>d!VEyE`V5S>7V6_1 zpfqua_nzA2kW>4 z#`PlJLY|uk_xKa8nE}L`0Qf$x1kSM!t`h{#{s|DJEiB3@kX3F23q2CD?si~G&IJY- ziciJ#Fpt|pzdVLHTZeD`9~~+YXj5-NfoX*^sel-D3(l1Zv@%so_636I5I72jehnv{ z;(5R=Rlqs3Atp27?7iW52YkvOn3Q(7N)+g4qk-Ud3+5JF4~|~}{GUi*%FO`|Ay5Q? zC-Dw?cQnkZTR@9#q3LErJLW>W2LZ){fFtwa&$A&uT8L8$7|k4rly?w;LBu5J4<+>G zTNr&4%(l-2IOG!PKxthDKa)YP!r%T!C!Ilf14YFStj1!|z-IKw$I* z!M#p}$Q%T*TLjtaB(ygN=He*m*EG;Wr$H13L2P6}u84#7r9v#Jp>2JjC(_`m7_{X$ z%(p)w2D`!R*#hJwB{0Vl;Cf0Johkn#OWR;YDaNfZb{Rw`Vjf(th59=Nc6e^6ESU<7 zwxz&%{7$q2zTauc^+9mIL!ey(@GIXAW78A}w4pGn%desJTc?+mgm!SHsGptZwU^QF^ zaoR$1{}+yRLA-o{yp;m0Xg=sXVReQ7rs07Q2SL!TH;~!?e+=Hkj$#G;)B&@*g=F1A ze7*n~C;;xRH*h3d;yBHYfp>Xsqpq$Ny z$TGw4Ea>M*_*Ba*09pUKpEH7{OXto1x68WtD=nmf&}wS8M;rjf{sGHxE`( z5#)Fms8jdiG!T_n5eT^eA}$B=<1)wsOX1iSYI+>Zwg<33Sc~@tZ)_RlmuAqcKZcRZ z28QfyEE3}69gJKQjKO1w{&wUzvLAUED62Iv8iOHrrsL0nk~|B~f(-chf0Qi?IL(*9 zsGWeBp@fl3gd8#%R=hM=4}w9LO#)5Y4CJ2{-uy&paTPGiM?%JU1Z&AM*rEJ@Jx4DX zFB7zEFwBhvpa$a5)<77WzhF&h(HXzR7Q-GuMvQ~;42GUt2W!+?s2s4voX#LBVb&an zY*qqe-@?F?AbDxa^UlafoFOE*4zCsic0)5++!G=DG&Vi zaqJB4v z3!?rO%-DE{`Na_PtAT6Sgfj#KJFjEVlPQq-N5RbO4WxK4{5r6uN5bx?2596fa0BG+ zo3Nf{!M^McRFXu&(bd=vSOHeR*u2LE!d;g@ALYU>>;goN0!Ht5ybH|ce8Nf&gluVn z9#4V{DS&ax!PmgP@e#1x=RhtTNBm6`0+qXkn)(^`ST|vwhXX70Hbh7^>@E3ZB(OWv zAi-BMG8P=B#kXP=**d-Aspbu{XXW}3H8|*RDA3{bb?q3tl&Ga z&X0i}#DP<3gnMq`mP9~nYp^9SJ6iS*2cXqZVF;sm4Hprs@cZ~iTnBrkU>NfgaGn;j z<6GEYT!QOZU_W#Ta*hzP|5Io~3mrZK+H(q8n+@ZW0=*6EJIvq5uwT3YkyHX}d&|zI z6bOFG|E*0ptbV;9tF`3id>GY0*tKOtuIUc@;Z87$DbR<(Kv1S(moo)2PzkKf2O#Q) zzzlJ~lhaI~e)q%f!Q34Lvta>8&V4qp9aUQguD_B$KVisS&#?DLT<=_T|vtV zx)aX09@<$7@$wh+WN+xBoA}iK?T_?29#uHDVMH&B#JnVn{k_oZ>3VzZ9p6-^yeBi_9PC~D@Jn!v*sGWzmF!5$Vq%DCQ z*0K_|P))bOp5qgK7Wain9suj%T8N@KkZp!QzEQ${xMjAigLxYSqoRggrwgJX16tOL za6`w_8s@tW@BfqEz|1&v&J%Y%cU<=iSjL^v74&C}p(`x$U~ue6 z%(@Wsn*a)|LpSyVxO<%JCs4{+yb8sxb;Z6MXp#7Sprs1%c{cQUWXrl7#J+`syT`-U zsFi&H-!i?OneM(aT$hFvyo0M9gO!+%_3_8*M?-fdW7VNq$^OvgC$LH}I7bbl*wi~% zXR9Em)2P`%n=zoqYYVhDq!?CUiL5Q_0uMif$N5E~Lc-tnvcwNU) z9*5bdLI>>z)y~EmOoE-J$0stOQ~#0uE?X*df|p`Jn6)qX9y>@C*t2q)Xg0Xc6g>1yTsh}qr=(GTP z%h&}JcxVD_k8xCy>=#gNUtD!3bl@TE%?Qv`F4pP*){W`SoDZ7_-8^tkpuqvI)I9KS zBs9@C$hO|p7+ArBsMnDCX`p%VCa%PEv+V$R?TwnRjo2N=@;Z*)Vb0m;9*A`jA*w9` zH6KFn@kYp&j*#I(+$$CLWV&nj1Lyf-r^Z9?50MR$sj&jy;87Lic`>BA1(b3E-lPD` zIZM`ss*m#D|Q=!zZr{Yw9;|DAPLcvm(`o{XIG z+q_<^LzL2%Xda*+Yx-zRR-_2oT(zhp6(VmGXlqWF-7TX_8%r-XpQbswd8p(KHV9qj zIof&U`wkBp5HjEEu%Strj11Phgk5q+aF$cm;8wM|{71EkbBOGYio-!Fold25AS*J( zZK=m1kCBey#%YRXVjEFUmJ|C#>rr+8zJ5sU(^}uAN&J6hKPhgZe_fXPSKZI1UeqOjm3TPwI6$a>hUe7VJO!wai}}H1UU|PJ@NGq+1hq* zyT-6D-e&Vmg)jM7bccJ3_lED@e57i4S<|=j^1%9sOOJAec-|}2U-uf4fI&(*3)s>o@>8m8LNM*m>`=Z zX)AogabtC1b!P2xJ_52@Ja4RU4Z71kr>oS@G?&!R)m1>ZbJadWjb#BcWXic3S@s-LHd4K9WY|8PlZok4i`&D+4 z{EHBh^{DO>%IoCsm9y1_>bJ;yUZ5JIIjG*E$cMkxie7o+h;E{3f;>?!>gv74X`&QK zU(_3>L;lR7!&IkK>8QZ;S8CDO6+TYc4s^l2D~%L?5k(PUvQom8a3POCe;+3Iqx$fe zlBJ%Yo}=EW7NAS=0>x=L2UYZ4VdwMEu@7At#m9sPB);gqG*Ud28~{0Vjh=`e%WG9z zG(U7}GKbqmQf!lA5@7(qZjx_Y7u03GP$29g|F`dV*`^6!qjo} z{>i74QTwk~mZPpZ9Pto=>>L$`KF^D&^F%&yI1fuaBn9HR((5uV?I)|3MiPr;DX3sw zs(hmUS94btph%-H(d*?N$~wh+I-I&nCQG|AebOY9^l!1N@PS|wC@YGbDO*kTlixr@ zXf5I|o0ZL~en1zD!`X1qn{>OgO5;0#qUGz<~Tii?1U-DEOD(w$nlsEmmGDXuzlcrg! zjniZ({Si^fl8=Y`7|eW-~BmI$5Sc54%J1&5Du0|4LOU)NfU-mBZx) z&=IX*KfgsUyos30Q{Y8(lguaH;q2X>>_}`Q(XXDCqg&+>R6oyB&Xo6~Y|vb>(3#)S zD=(hRlyZOx(GL-~Okh5c^4Xx>O|X7L=_cByEW)S`(7UOru(;1biyt8$O1DVbOA$Xu zY-J;HkLZq*43F_JQ@_$R^k6w#{(v+TLFk zT!n%5q0-1LxT}y}iSx#H_%=gf<@%z|{jjo?%1wEmJ|Rm$)L;fQ;CI<2SYZytcYVn^ zqCd|6v(Q`W9sG39(0f}zou_GF5a{KN@&;5->nRc*fKlWf^r2b{>$?+iQ_?6!XF=Hk z`07{424XC!WEkQpi{WugCU;N*g-jWtu*<^{U(5$hdy$iI;_F8hkOVP8k}HlypTT;P z2Oiu6)Qy44jpz*Sqi&;VR2M3B=(KzY5-A5AkslDZh}P0&qDkT)NfuE@rpnypNlF(L zN3mF*EuXE>D*sX3kzYsMIwTqV{c>`zv`WH4H`^8H9~FuYU8^PEB|F9KfKLKU7W4|V z5#Vq6PM|V$N9BKiRMjt%Cjeh13@36OZ2B=a2HawU9KzCR6M@PpBbp@iE ztJJ$y0~D{R-LT7N%H9*j5_ic_L;;71Ip~qKOMFyXOb(OBs79ju_Y&Pn{S9>dj02*_ z0M%%DXW3w~Cs8E*NkWM`3&Z%Axg>8YZ8_@9gY|{_4?2Zz zrh2K;s)&%UqI_i;h;qae-6Xe!GX!kmQ}IglaNS0HAVUx*>ked+L+TuL4{cB2SCBy&m!Ns1)@N~0uiL~0QsyaPn3TA>Z=I)liN-J@p%v7{We_Xh0qC=`PF z16$ypBAGrYYlS$@ctq8nAyT+Ss+1ZfgT=|B^^#fSMs&p837@JzbpR2+li9zes@?BwQf)LvT;|c zIZ!3i%+R*ej#uwdZh}?zLH>sR0RP-O+<&MzML1Lt45Yrj!cpRz5+NdxcFIkDNAXel zR&`NRqJ679s%cQ)S1(r2QU|o;$7Cp6ffBhBy5c!`QCiIrrE)&Vq zfHNRdv;tN`Dcwx(1OA2#>%W=aiAZQ8;Z2kR^G8KokdBjNiA%(kp=6M)8(KyAWTfAZSeP}Q+m1^J%A?ZU#Vk=57CGfj77)G02)0~;i21! zvr;xm;?yt$o}?Kq9G$Uo3_U`8yGGri!ak+abGFi#?Y z4&5bH!@KpBo&+B0rZ}X?Qmlkt;X|_(0yAWwLJRzYk@CCp2%t>JWVu8ubfB*gKN9x? zn$k*1s`M(Pf<#)0X#N7&?uc{K3m}Vk0!4xb7E2>gPFBfhLAN1ZfS7+SLHfAap%e|?EWInN8+8rHS9|P%(jUIppfB`ifhy(k@36c%cg~U0`H55Egkwb|A zL~rs>oSU{F)}KbKA(9ZS%>;^C0P$J+PHL5wN#dnG=+_s9GuAsq-u&n&=z$njvU;hu zQTGsCx!V|98-F#5OruR^Qxx)cb^v=QU%O88TzyjgUNu`)uZ&Sn04ID^G${ zkD}Z2f6Ybpzt^0v2q?9d%qZOcbzk23&r?5IJ`DcA{^0rE`VvUfQR*c6I;Zam{O* zkKNBFpnp(y@SmaGTKyBgCE`Qt<~F8wruK6p|Lw55!!J>zqr9STM4yYI+8Tm-xg{ER zDCP^zP5SDb^8F?D{5|jXWW56xV!$02mY5&psYFYY9(?0V}tI}3#j&g~2nPrw*Zdf&r|J*P5 z1pD_0+#Yx`@M}PQK(~MyzQep@y~cZfaaXzZwbAC=hD^;aMLkg~V{gbZPpb5+4xUG zjQ)Xc7I31Ybb~bY%4S6!y2Zy*4xqMr!w%7ia*^46j9IDnJO z1e|-yX;)a-7nSdTV|+y8rxj^w?E_7P=9H!Yy2uaxs~yPkDp&1RO;Q)Bqk)@Mp#52Q zAGXYI23H_^6`CHq7%ja)DSN>&#nwDqlg-!eu%ECC9Ayp{wto?=5_lRSJ0=qU;Lo3p>0R}HIh4mH7Kw9#|V|jL+w%V{03EdP7&)% zo7Wc~e7Kr?V$GrYeIxgMOmHvy8G8hYx`Ua=MyE#JTb6sE$hV^ChoY`mlNWCR z(V#kO3Ucl1{nhWDUy{!PZ!e!2e)fRj{^{Pq?h<>VWwE)hIowibKjt~ne?gESq&!$3 zQW+c{aw>R6@be&T$cK=7Arpfd{8ZjM+(gz>27&4zc}1|DC8#@9mRKvJb_I?rYs?*!F&l`#&%HCGZsq5MNg(DTcC6ehwsy4cOeWJdVt_bqN zUwc_M((uqQ#qa=_WlZ<*3(!t>bcmh^M4`8G8YkEz>NqW}8>Da6A2v)iJkyJG2F-I- zf$EYnPti->h2A2QksRq$p_Dh4)wy|2!#Mn)EgT-8rw8=a&BOoc$s{a zFjoX@azYQJpd+d^+M9+RrmHT8TtZxCq5E%)akk;IK0?1(R|Px!zG?()ym!E`@{`vg za;AYz;EliDa(~!F3$z+Ty0O%h<#Not)-uj=*>cn}*K))15_sVQE%VHB^FtSxFSID)dV5aHkl0Vy`=SA+p$A5U zj{bSfgwe}}AMT&tMIIVsU#tAW`?Z!T{qnWXJJ;tU?ykNhJ+3+M_nsTO+U^{d5RM;@ zows+}52%lsQm5bj>-ENhjEYaSqnnaADsh(lPvcluSHJdQ<~E1gE@>0gIzD1-gueCR z@S+f}fDG?yH>u-Ki`i0*tnlUTHZM+om3 z-1WUfRj2yf&ZGPj()03<+A}T@HksqSW1*|iJ=vp+7sscS&ubsbXSwHGw?x|umwkqf zy4RW~s+)@QK+UQ}TyQx&`F-I{w87`T0JdKv^3iOhA98F`5q0&EWs)6;6_Vk?WxVa| zi_ZB?GaIKh3_@-ytKLwTQ|n$gu#VkO&~Uz~qce~7nDZOYS9n|8pG=T1QOD^Y7(1DN zvwXDfw_UP(JAOFgU6;D1Id0g!Y-=q;%zI5)29{p0y`j!g&XWgHW620&9?%o}6Bfi! zza#H3i8d%G$*7pU_4$NJrxWBq2`V-2=?pgt$jWrWL96W`^r z>AuS?b5BdH^|XD3E8+3otH6&FJhs)Lwvy<3U6%Iv(EE759RrsP@*Ff_z_C8Qu~XXQ z`id>@~`O?`F`Xj&Yo3`i2uCBW-?p(PmdQba({SRL_PF*~5 zhxg+7m!z`9x;@TuqGI_7Bj0Umz?X=OsE=I)-3>jYJ??d@?sm1?#@K)uc4TyfAoz*z zbk9$YY1XNh59X_8fjPwFFbveWX&stM$hdHgNEdEMG!`0Jrt5}Z^(VCz$hrMhc2jae zAmGF{j;cOXwxBpNKlaO`j~m`!%$2;3dolUhsHcaYG(R2n-2L_X_kZWP7Pl`Csc|$H z@Rk!Fl#`9W*p9lt^{(}+3@i(|-zu*4#Wu=z_uDGk&WaF*l?7^j_j$~9&z&2|ap!E{ z1aV8b%{;vzM)*whSTd2Y%MQ}niZ<#@?IS&9n&&dWvfV1Qr`Y8Vn($LS!QVINUdX9dg{__Ks-p&Wy3zHgICk&ny}$H2)x+FrZA6IA zJWHNZFCN3XRO?pOrXc*oFVENB>Ga>~Gu@A$I4VCsGY{owm$CTy(jqP1~!Lq!}qoB&~|RSQSC3c`@L;;M6a-}L9P6rdIq{y zn_~J#)by_A{+L$9sk&78zG_kR(b~-ooaQFy0ZtY7 zApdv4PGK)mw0H1fS`?6aAj}(}B5xYl39KJwh@=XNRS?Qij_jdbWvacPX+Ys!zwbm?0gV?H7jS zdqr6GsMHb*rxW5)PPg%PxU%?^}nRs z7qfePh$`G(`uC5;4edF7#f#`E`p%AYU*E7LZPgvNL|Hri7kj7M_3rN7AIF+HzliP> z*|T+g=%RocpK$L}9)50H?b|E?E~5-TYu_rKkyfDk&J(5xYlU3VdQl$GXTJ#1TbU>3 zh4PMaYdC+iJ~hVFb*$b}6;RO#hhVE>4$V^JMdXE+*7o4lyn=ICXNZt2$blid=9+dWqiB z`;s5xt>UF3zUXgMZFUxAi24GNcZ<|Xl*nR{^FL6tQ+Lz&$$Zqd-*uY%YtJn25?^J2 zBxp=XW|%zU*ESE^U5wloofC7j^O@M4-9~l4*X>D{$B|{hVV;Giwe%Um24_>v?5a_f zso(SRieJ5b5P!4i>e-7+Q_h@^J?D9@_a@A6OQo-v70F&!SZd*8Z8*usEwKC8T6d$#w8 zbh~bkwFX*(%xjH*YC`2X*v93C zxvO=6EzBO_IPN;ceV&KabH2wd_XBQ!xz2D*ws~2KOg#$%2QQD$5!Hx~5N#=i;=SsiW~kn39PScl`C(17A8~!- ze%y12ceIbnH{9>F-+O=WfI|U3fina92Q3WF3Vs`MA}l7HYW=EBK|5*t4sFJSKJwk{ zsMjB%=ZaTw2RnajUe{Dzd%QwdH1)%n7por^WFEcK{Z^-&VK+T*cwb|szfSunBl))D zapkMBj~@&6e79H1Yd+P#Xgb@kugJ;tAa8iBb)bBuy2!72f5w z;hyK@a3*k%a?Y?VtdizpR1iI=i>n(_XQ;nbmsRUt-LJB+EUMK0J@s4E_x_~|%av8} z)xos^^_?0$nyXo_xo=RRI)QY^XRCMX2fBQ>4sreBvETciA1^Q}m>;qwv@rx_^no+| zxBI^J_VCK|aCblN2(rbv{H{Nt3ZuIdgm}6@%KMMK3>Eid8-(@Zx}CLwwPR{4Yvc`gKufN>TxoJ*wUse`-5%)PyD7Y**CP;!uITC$plZ5+(_eAr=&m>o*lZk1B zKXgVCHJVP64^pgB9#QEvOSFe|gAJ#R=tyaCvvskv9lab}$7%Z$+iu%-R4}tFEc0Pg zu|cSpYa`&#k5@#~Of-g)JQ5`d+VO|+_HiF^k8wNmB6;q7fxusQMATb+P*NrxPCk=m z(g}*z>RB3hz1(=qBsZ_HOtvQ3;v8C6Pq$%iLGJ19FWpl-&U)wvJ(fUcfSi%4fzBop4E*8-d11;^afRHZ3?^YNcold|bY z-R@7%Je0XDbIslLx6j`^fAhH$^*@G;L4X4%n zX#?3F*zc1hd6N04nJFgrN_&cT36?;E{K0$8Uny8Fm@Y62l6aT7VH^V|fjye@l=Fx) zmG!deXnjPjTXjK|vFcjYpdXPn-gO(%52>;4Mt$3c>y7i8AF?dm^@0@f4l)Z!6E`%K z`gSgBtveh&-8Xv%c{_aH_%`^C_x2uF(y@%D!#oore)ZnL`gziPF z=#jGd(iBmUAe(!g{lz)Bd3IC#rqzw1jg9q*bsg&-)*h~tHq30yZn8TQSeMwtI7c~G zIDNQ%xl4Juyb^wbV7ahP*i9TPUI=euU-3r7L1KY!ua>@*a)}FshSVdkV=?Umq+p(U z3lPhPY36Ep+Mj_~{y?`&Uu>8HJu}+)!!XbwHe~8L>%MBvs5h$Q$^^MDohgeY2M}hd zL(*3~USt(o1;6p*dDYw%+^O8N+%CNF{C@?x!g1n!NuHFC$n7FT?0AZ;N`ZQSW}vP} zx6a^hY-4ho#=4vWmS!8X7+UOuDadrqSYo(f_`@&?s2e>ETMf$$y9`GSjfOKu4^y1W zHglC_xoxPU*!7-PaV5lOgbQPPy>iS@jc!@ z&2&xA(%FjK zKdKw9aHkVT)FQLD+c}>_f$^ce!n0dT+wE-MrNfx0M^SU4e(Nx>{qJonBNn#09&#_x z%g^Bbt9y!ltNDRGPVFN6oPzm=5 ze1$&?76QrNTlf~gH}J1;U$U<{J2qcwENqzCu%}^b!@mua8dlWX>L=74tovM7TtBGM z(!7{e&S~PG6#XQfESo7$R!!DkGPt?aqK9Iz+c*!6S6}aRpMAb^|Goar{$2qS{2P3a zdB=K=cXQg5mZ_$-`Uve2)h77~*&Au8Xg>coXDsWd=H|v;4b62YYpZL@tAE2|YR#_N zrFHU#!HtPcKbk{WQ_w%kok#Nb3BCx^#5*NH#8UD%WM0+7U+#mPupOu=2t|%|0jh2C zk$(`1=x!cpZnc;#wuzI_FTh(IEAB5I0vhZfeMJnCNvPILg`>h%Nvb5O{VESgm1~+I z+UZ)0HcZn?a{@6JUsVs~VW3wFg{lqm0Ffb0lj;yHTPg9C64Gu`Zy^2_B4T}n zTrYbMl=4iVd2dqwu8LPbP&cZZG&i)}bz;4%eyRSVex3e^{vZ8G{X_k8{Re%uzFhxV ze@!m}_Wg6iC&LfpTGJz!AdAxavu(Ux;mUJYd6s#t@X7SE1vJ7c4iD_>U+&HJusDvI zpXn8v1ciX+kzd4lyf#i}?ZS%wCC9$b`*`#1nAggeBXgEMoAlKFWXa=&PiAGG$*Fk7 zdpG6dh`h%It4kV74_2A$f3W(9)=}FuVWx{V!rj~ZxZlP=Lr6u~v+$DE`nEr}?b!Bo zo2{+aL|krlH#8!6WNIyaSLIHGWSv2uj@=SbG#1mTh?YN2Te_6k? z9~q>X)9aJR0{6dMyE+1FS1pTOT#Q?F&(xO`sKg>Pk}}~R{CI8^sJmx# zug1X*qw7D`-K@J-XRbe0-?Ks7$Z9HTI@i3Eb(5XO9m@|Bs>JUkLx@x4PqHIaBx+_y z%2QiV>f>6XO6iCKmI2j!CGuuusG~fH$bA@Hh+H>4@WmG(;taz%!rhd^84~9iqp!Cs?O?2 z%|p!=?I4{i=<}fA7vmyREV_ePEJYTzO=*8@KkJaVeRccGJ=degv!C~GKD&Ik`5yEc z@15wuc4b>H8k@B<)i;0`zgZS59VYzFF*UuY8By`b?EdJpt0a9v>cw{$i=*H>v8RB_7b@+#^qxmzk0 zPZYM}d-G~IT{tf}cQ`}18@T(pL%165XO4;6pBv4a&1>RC@y-0tJRjZ|UKH}Zp71#Q zk30u&H#eK}fIXeVm~av?_EE}3O11>wd)^S97uKj9KaZaXE&G$mRq}`AIuP7%)76k7}8Em?lU&QTs{j zuj`5K9`3pa+GK58ZK!s=CRgpQ&Qy(5-B1o!-bdxP8+u~>L;Z&w+OMd4C?@~K$y5u^ zb8FP5mqNm?#m0aBel$xR4qwB8!$(P{>6h1^|M;Bp`S&k7^Hli@3c3{qm;Ckpb=k|x%{8|hX0ulF zK8pOvavE3CDU4Ih`)uu8r5@Q{w|tuXzWC1yyccK>;syB!ZV$-zdyAg1I<~r)8RSvbYKnp4(hE?rKg)^pIk4B%ID{7P~Y1Z{XKTI6ra! z<<8}u<8|h*;tv)q5O@in;3rnpR}?AwD*P-Q0qcCb@G9Q%673Y-5@jNS8zue;J&x3p zXOdr}{zPZ8Co)=3(*R;n?osVmbF{hI&pO)RX>2gQHeGb7hWA!%8DwEw-kUd=n_QN; z1etajB?i9!s5V@arSezC%Ohx;tc>U?%@dCk$%JG1^LSF&7US7DtUTv#=QQUw=XGa1 zYYA&V>t}XXj+2wi1x}4%g>bvbj-E(<#C9@ER!^1FCy|@5Q!z@ZRlQP`s@kYmt1m!j z?obcK4@ zmUopukN<@qB6uxG5WW)Si)zJM$sNfmWCngEQD=%=icXYe>rWC8XseV@7#(YMrCnKA3F?xaKKwkT6kHD%Ot8ImNS);~Z>!&Tz zcxwr*m-cUMg|<>VN4G^M)VJ2}(Vx(}7~%{M410_(jo~JZivW?7-%Ya+NvY8N&~CvV z^jB8MccMc7E^&RJgeML zSy+`-y|;FD!}lf=JC?UxxIi)kxsnEDh57+{gzj~jV>xU4`4jp#mpX;)WAI$I;imH*z!rEd@|KY3dKpO_q4VTDl`~by;MH6L z7UL0ppdrFI*0{^~$hg?(V$3lNHV6%K^hb1ybnCQRk!et=@IQ%^y4z*S_zgrkPx1vP{g$tTEj6~lqDa$S|8mS{4Osqg_kh_30{>euLd z;Y5;S=w*Chj5C#(db<2!{@K#m8f+VDPjqP9JlvnU|Lewf{AK;kMQ4y|@2G!QcT@k0 zbJcTYI#n;O=00lv6S>bXf2^!ZtgNZ%UCu7OUp%zn_1CvwU*-=e>{Ilt$Xpy#{G!NN z+~=F1%uv<3ZcOt^PH({s(RoQ8A*b&$oi6otCO_Lq*FQa?z4Lsw`)%=G9uOBWJRsh` zhyNqL`+h6^Huz?GKl0q}-q*Ft7Hp|DWf<1$;x%!~0%`-XQ2Yr9DwlbicoDq*Tz}3E z){Ev(jUOA9Hk@jB-00T4-RZ`9!WzWx%cS8_v7;E)Rl@|EGG5#tl3e zqnoT7qmMJZGR#8vsCCAFaKikJBTl3B4N6mAbd!0jBM_Iw_$LxR5XVHT{PcQ?$XctIQ zq*n5R%!kfGmluCT%ma|c5d)52r!(rW>s5w{hG~W#hCjji;n0lN&=ageZB$QG?Lx07 zcZCfWBrr8lZIOpe%6g(Jp(BP#XCkZiu=EzH3|1n;I0L^IAiFdbc{Fd4V-p1ogw=`PVfeKnS4q9hpaXmGR6uBPtpN9bQ@7f)BscDI}k9^@$H4gdSVo@f_R54fK|YR zKu!?yxTd4hgUeLhp#D1oJ%*ms_h>)#cDW%hmA^non;z&%_8xXcjv^P21BxXIQZWSx zic8SdCR~vT^c5SjW38yyJPx0-FLe<06A7r@y^B2HaYTW1yL5uoN4i6jFBvCEm8^$n z;0>O$q>GWSlrEJK7NS3}7cz+ztL4@ADAW5V`At57Q(BD^5HEVPRx(7YDp7I#CJxh&~zU<9v}Wy8lVLw~DP z=;0(+@zqNZSKOtUt-Yj;(#_Q!1S;u8-Bz6wyk4xEty`jV)os=G((cf-)$BmN#VOT% z)mT+2`YG9gnX^lA4-a4DwrxdyfS;-(@&V$YKMk76=*qTOo25Oeb=MVWk7fH9Ty13GZWX=Q0+XGmU$dKTN0*=SsqW3R6z?m-j%2vm=^?x)S{qaOPbnY+5uK$O;(4O80-%)f zhI03Der9{KAFzh8ik#=1#m=_q?D&ZF6JkkMI77K=-WA{}edli%Bnhpe@#wI4O!5p8 zp&P1`HINB4G8fbY%%ujS#=aiNGtZHuEWO?r(85u-z7V{}M{Q!7On~~R3{;f;f=o;jnXJC319+>PqRK{JzeUhi zr!;S&MMh({&3e23qu$*x3%MXK4Lywi8Y_*}=$!YfDbcjqbO&*kAErQ;K`uoui7umE z{xqF2h8wDNhqQAvv!LPPl#z-iI!!i%m?8N^=*5?E&#=sh1Py|Bd0_37>V7}gRhCwG zR3w!TEUzysD&v&@RnD#GS-H8&zgk!uSU;!nY_o`ckh_*2EqWq3Ko(LNig0x=-7Z6K zm$Q}}Te^L%Ym{3@_k-@!JcfE~^qA_g%Hs;Kxbj?s9Dmr(S>C#EOxgN}+Ct>N&6H1~ z_LCIy5t2l)sA-wX^WoB*;phcE*V)D?bxy&)4rYC04Pm!O>>&*u8j|>L1a(3}JW2Am z^e}N1d89LuHQGbYQ)~e)Yd>TiuT~yLty3W$yKquyZpr4HA@`LpK({R`a5F5Z{Y)m$ zkp_|=`$LL#B!Y-SSQfdEA;a*KL##)(>I~#hpaPt_L4T&l%4^UAidOod&)Gs$W(2@$ z3qUvaL&}cIZpzb&jp#?VMxFtxIgQ%EKY=Y2MRp}Rz!te6QArkwJBtsBjv>pj132AJ z)J8Nw#9*owix#89(-dTs&y?m#R};ffXXXw4o`Q<$6y#N%lAo2U6u%%B73j9$-+W}I zhJ&BqgPUh5s(|IR8yTv@OyMBIbOy;K8;D%!x_8KsO+}vZ zamaijIfr;eTtbb_P{>CwR48vJU1g=PcMC`cO$9Y8sJ+ZZCEprU*X=~+?P|z$U--;Q zQPa0i7K3Wea9lr&oDUhh5p^)rkrg@z1dena=v{XR1!r9ItOCqy@ zvc!cp>kIjRKoXDsoVUf@#b-p%gv*8B1^Wdq0*xSz|BZhYC(JYaRQ{j*1N<6(tRPpg zO{hV4(_h5#z=R}_B}#$Q8j#_BNB)muys}D}s#>F-qan35no=!GcS!e8Hw%3lBXkv7 zr*g&(J)}kWIc99HDE&wrB?q8h@*2*$mGo8l9)-8^v@%|`6h1$trkiGvW-+>RCTcj^ zMD*MYfJ~+|IqGYu4)_WgZdLWdp7&E^q2l8_J(d>JOr1TCI*c0eH9(?>20qM3vV=4- z_)xNCc>ITYL|7rHdDo&7;C;jyeUX(l9sZ}|=vp^TK1V)R{!*@yk3l6B>K{<`-hoa= zrEdqsaoeNzG#m9BdQ`1%BqjmBsvl7X{Td~0C+&c>e)GI-NbJ#Y;uk`WY=_b4Mq31r*g8;T6)I-mgQl*ccJ~ePbSdO3b3yCnsJk(t z#?uW|=ev=$)BtPZDQL=u+Jr^KYhna&!R|;M#CPNbqu2x9R2zQF2&V3dsohB??!wXz zMMlC1&|@mT+X{6T44&60*n12L3-GW|tr~_ZX{LHw1~dRZYG1U}WJ(RWKOa<=-jerU zM;T#nN1%sfSLCRN&YLC3q1L7jl_Zv)E4UF2BZ!x`^5 zPIhIe1lQ82d%-(2Di0Xs2?DrtGGI9fkq0lwgGSB$VMNJiqiS|GEVV^ACyvKB&cR=C z50&rNp^uItPks)v{-ben?2gYa!MPE5YtRiDsC`XBo%K&GdaDgJ1o#UURAZN+5}2vc z_C|%P7986e6|6n6s&XI$yu+;1kPXJeNn#+Xe7j-Qr&GuRq_)Fe+klGZ9l&D9#_LS1 z*cMoETTs<{5>@=qAPMGU*TzAjEkzxCXVeW3Mg4CuD!OZd-jNHL@eEn)&w*v&3T%*( z;QisKm(4|G`4ylFjmKRXl#N5Eg#8LTdmMCbUtl?8Lr!Es>oF2)Jg~v~fS0-f2ThME z!#q@Ecp*2wJN7dH(j^15n2NuL$g89feMK8d#%sR`vVlOIFoD{71~aGvH3&_xJul$i z8K|=T(1Omx;Egf3D)|`G0obQ^z!#5XCdvzy-5RWZ9WwG+)DoaB^#n%2K+KxLwL73D z+JM~n0Mu|%(AsIh{ka2+!H(+d*+8do1JBI@h5fHmosYVn5x7qTFd}Ya-#$RvJqJ}V zhy~YC>6{O0NCI}j4j?BYyPsy>J&wJc3|+qqcsah1u2HC=?+&TQU?4I3%*fo4j258A zQTHKrFQPWT73zrMasOBbzXI4QS>$UV!_=aJ=>pEU`Kaq>YWHu$hT!5l2^iBsT$QOy z-vpVu5%(KP{YiPEp4z)bDl^zj?{Vz{(8gQTOn1Xfx!4;Y?4mE~!k9aSVOJRhu1Co2 z*nsyJKsOu)M$jdkLw$ii@fp?Wui$h0g1zOTs=5;Q7ot+EQU?DbK5-Y7bN5ig{~RmN z+-DPf$rD@Z*F(Xhdenc|WPH?_TmT(0Qr-vmx1k!_hR-bk-DI>>a@$b9QV%L-5IHK~ zeP&RF`r&6b5GnowR>4x#rTIc*Xn+Rdg$nKV_}dq=_Csy@0MwUGM!kOys^cp_&v_W> zG2kjC0^wpGX5@#xb3-Gh7o1^x%BA|kLCK?9e8{nZOtQH9X>b!4=x z3%*|m+4~f>>>XgU`QU1^apm73{n?Q4K~zW!)_))10hekW7Q5~#1kOtnKjvo6=ZM~ zqM*mNf*Kj5g>61ityQdqC4kYrzO)P^vOu{d@(w)Fwzm18mDF7#Hwda6db2peW2R z9kiH<>t6>R#SZ9+bny5CV1E?iSu%bOG4dFi=sh&ZH6Z8xpuPc3?k?!*FgSN2>@Y2r zfDz=8M%h^)_1(q2W&q8Khx(ZQsKT;C{}rHuc`f-jPQJ`&dH{!I3+BpTb!CD7`N$F1 zq0(q1B2N?0`?ec>4V`V@qDSpQbgK2E%P0pfY2bq1MnDc7!n`j5-^@vU zflok#S|=Z9*#4;R>Iak~GhK}OrWmYy572D{Bt`?c^bPiC2jsv??5q#CA`1IHTJ{YX zlvY^<8Htr(&@LGSyzkgaEtQQrE;e>>LW|dbKeTi@ByA?{o&n0gh}E5i9q0nNFdd@` zpv+VtbYlSSrUUh#hlaZgI$s4{l?t9M1;EZ=YTV;dvw5BnBhdElQgQS~)WepdPOJ_HM>}Bu zjD(CdKsPb?g*!o66EVW`ki0WsHOS!8wcynD3u2K;sJ^6ddO3mmKy-*k5AkEDwq6P8 z!=Q4qWlcEC9LM?QCs?3QAeR^{U9IdL*$*>Y16dk}GaA(*tw?Ah5;|ZZR-zJXriB%J z1y+Iz*gYK}tC{mlAyo%tyMOUcJa&H_bp0Nz!71$ZYRI$U;M5psfgt=WrCtHAg|6<4U>`y}l{% z>v){(vcau&SSPLgB8?8zc)l2ZiCN&~h2W%qEyz^{=$I3*?HJw9*n&WQ!TN2(Y2cCU zCS>;qtl~SYC4+4>9V<|Zxmtmq7)hOkoLB>@xB%);2dzb5^bEFSIzDj>-&-zg0{sJ- z7yHH_>!4#a_LjjRoP=2{!K$1F4;N$S1#|&=aQ~pL!sf}qI8rdHJm{hGc%6>tk>GL$ z2l0P0o(rUyXzEFe_Djde`a;gzun*m#lMUbvrheK1zsV##m}iVt#$=gx!DtUay4?o) zN-e&98;DKJ*haK)UIrxTHb@)>tBH|6wS>!Lm&_O;#0$+e-_|#J8-v!c=a5g zPRDvN$Z0b42Cs)CYXm}>8!9^r|L>f94gd4Bg&to38>|9X-;e9&f;KNvzkpsBfGTI< z?sklN79XFle|iNJ6IGHXgg!70($h$6zY@L1Obk@1sDoB|t#B0m@*o4mDII zbXX})5{$R(rR;@_MSX0srs83BO=?-y1(3TZunKRXMcz;b@bi1rx$gqP!CGjv1+a;O zK_jvFY)9PJ7qiu1yo|+Ug>3x-`OCzWkAniAfaVxfu&jBt0_$TWXwn8; zy;{)Z9b~2DlIXV%O%)01Wvti^kbDe!>LgHgM_5Ux!9^EZBuq5Mt%Ho$0!3{k^jQSt zs|}<742>F#?=qjB1MNKm-(~P^Z9oO+k9i#d;!qS$$04wLm`^MRAGZg3##?p`*-^vEt>iKw2iCw-l!P;OMavnx1Fjf`Z!@takib z9iY_{aOVx!&FQ#SE6B7tIJL;(2Pgww5ZLoFXyfOQf{fnr1toL@wfKPUpI}rMKzR-- z8~%ff@XcLov9e3CldEv$?zrM;;P&puN~U5rk7G?vf@`L$i&DNf|3((O*1g5f?!F< z;&UA!IX8laSG7nEhTH#VR|4q*&lrug2#=ZY2rR%SXM)zZKoZS{&OQnGlz>-#@y(Ht zj^P-Y54fZh_u^8Ap$FdKeiX({!Uj?U^Y0B-j=-3@zyg_os}7{5VchXpzt-UEKv*`> z_}?M03id$;PNJSb%l!c~%d_D5?~tz~{T^ezfcMuzO5VVy7!<`Uy!Q-aWe^Gvz!u2E zCmFf%1n)GooLiGI%l_a@3aeIubvT6aU6XaD#MDFRv)_Q%Hv?3%5SAiCU#nnC&BJc= zfp$od$uJ{yM8N7cVIQ7iZb{H$B+fqFv9^=378w{p5-id;lpFj!jgZegpr|}*!Q{Jy zRYToA<_eT(Xpa*Z=N8z;Qy?9}sbs9kDO_(StfQ5n@^oBxCn&ZRM#A9N-NTp|ytnzF z`B|Wl#W=l8#@HB}jya2PF`MC_sWMPUIOf(JYuOKX>xySSu$kg9<9twK74S}tkV#RX z3C6Yz!{0Eh2;(=?LvHIan+dqWLVRWkds$&s_XkB$&_MaHr*etYRqMe*$Vq1wCc9j3gKK_1%`|X;_mdI8WTg zxVRK!A-iI|8I0RpjJE-wrhuOLzQsZez%>JLItaiy;sIvSfYTmhi(J8@3w(0RVZ-`T zcVKsyfMS0FN2G!44z+j)6JQVBfZhDQ#h17aHo*~~(#7C0oBE1-=F+i7!P}7CB~G1aU^498GjM8>#aapR`7JWOpDd!;1%OHO~Jl02$0ip zPsXQr5psMt#&!WCV!UFDq3I6ce{%5-v$~_8m#ct`-V;cbBXJLgcDyl56;|gJb~qfb z4r4EOLGE3EWwi9I;DSb(h57)^ z&cjUY*kw2DMj^(-Q2GbiA2`#L8XqGF09`S*upYGa12X6Z><${7vkH198@R{J z8Rr6IKXdX;hSX)S$VWh$Wg_QiH;{eTBC-fnR_Y>7@&>Hi0Z@|$GbzB1p1|+rpcgOf z+IH+r9`>sM=dwy5^dEp; zzKO8ob2Fj0>!J7WVs#jVkeS%&VVF%9>;Z$rG8OCi5P2lWK#S|aQQtw2GMpy1(#Plr zv|8Q^9w@mM zwyhK=`w)5x9?ZFrMkdW$tmQ^LW@26AuzGw*(cw7VcYxo`j&oWhY^fEnFGA2i<0^cc zSK$-v3tMCbISS{wnb746AXQ^Q^TWUsb)dojPmjyN3yjx#BR<7oY@dMkx`37CVO<$4 zb;i%L67$;zEA%ydP7Tm7jCWrIv|l~uFbVOeNr*$m;l0_I&u097gEQ9*cqk^}wE(`7 zWFUj30WJ3&l>@%5Y(elR=&hLNUg``^eCt8Q8^JMkkRA+T^i_P@@DV_6B=k$`V8b_0X@itYhe zUj}!(5B$O^%w!J!_K`J{KM;X(qB=0N#afdh8?!BJH4AKWCJM6(ql|*h%Xk$JLt3nX z=AMr4wvp|HCSQbk9ml-c)G2&A15~k~)PyGgZ<{Icl4{1CBRLAhVDe8{7hjBjr74|pd zr#y_mo3a0)u*lWe`!>M)>;y0BZ}>zP_%q`1zdJy$hp?jzX6q`r}&Ex`XwE-W+(=C_@h+*ewiI&ccYh z5qqn}I%+7!24Ug^srY;o&YjFjY%@mSi!m_c(6wkK26ve8*G|IN8T@W0lGg;A zM}QS5fW~9IomXV7;qBrhbBMvyJqHVgu}uDl2fhlD`ylpaJ#3BhxOWC#XX1{HxJC}N z6{A<5gU(t}j9mhpS$u{;R?cZz`|o(i3X6k@KRki{ItDvv8}>aFl7=}ge#QLKzw#CnU*?}uh&>0`@ExR^w1e`FT`p=urllmxM>_ zHs+BBT1v+~HewaLV7W=4wa;U$Wq6$kFVPwB^R|}L8#5**q9cSa;1y`=Kg=r!RG$NT zfLXIbtOq=T8Bpv)iZgQ-ZJNF_->xy!;)?(cfOKuynw2rX;-}(JN^O5TBQ81<&XFSgS5mXStL=5=Z_AO4dcUJM>4@pl&EA2kZjq1CDN zX*)8P`c0ueaww0|Hm+`UI0W<=@T>*!9u=k}q*wS)wa%OY+~w5qDc<84=~%QsHM_eN z<jyqbQiN@MWth+vmGU!Ue5Q{@l~ZUTuG73 z;nt1*v67n~rKVCT!>MpBaEWk=|Ic`Cwpk)N_+Kg z`VDnU$pu=+1MsitSB>j0L(_$#t80n}nT&(gE`xNid?VWGVt^mZ==G;?5LpTK7C;4; z;T~4x2AEWmrHkNA&1aRwyck?HiSb>>$T`MPTZoy)->7-|Jg_)}ud8|Q11Nnk;d3dA zY8Ow@|7ej%&`$yMpweZ4t9!&`LIdjVs2p%L0SZkg?K;Y(Gu9{u-Klloo#B1-kA*15 z`;nWZnTgi%)vRDmf-2OkP2I1s0vzbd~+tW@JqBlf=EHQ zD0HzIKD`1C#*G}{g?o+Q!m3|tP1}i~L^Gh0b#SPrVDMvllbih2e!jecHgF({SH(9@ zf_J4~y+uUzGW)}BWHt6`xHfaB!$4RH%@4$Wgly7-)Gap^6_|V#f3{ zbhVjww2m76lYbVGv*E^(6XB|inw6v@47XLXUo~@jijpRRrPDyW3^kwRuMIfzb-qxJ zp0XsIRrQ<(b$g%KE8tDdI@PT(Nqj8~o#%lwHNVRvz9c;OFg2s-U>RIsEEMuBxzr6l z{Ta=qGMY)DWI2S~=ZhEk;}_xW=nak31ZV2LoN}~~erPjo!Mr;GZl6pW{1*)V4L@8D zL?snbJ!B?-aEA7Q_FN!ViKtr&)Xt9j^kn0p_^r&{htrG9W300WnQFRS%`4SvR8GYIn44 zE4h}M)2gxOcxvJ%W()0U8dyl99jX-+b?3rb=t$j(Fa@3Nt)LCXGscoCi`@sK7zGVQ zhBTPJ>PpLc1~gyFe!yl;siBaE{sN8A`8q#Hbsj)H;#DSmF+&rSs9YBx%`7Gry8P8E`yPb(wJPWq`I6Z+d|I zMBV41Xk!RmvkFoRb*oA&T(&4ZNwDnGg1hM*g97KjiyYz|Bc=C{B5uKU6CjvHXQv z*{g|-MB7i^m5?$`KpNJAl77oPc>uGr4~eTo4%P0| z9tXv{-)C;2R!95shl9y~2fk30@+cYRQ&6nB0W2pRORUUys|L-Yu`A#U!}-qSq$qimL`i-gz_A-e_7ig+JjGK7 zwSm_jPE-zv&r)0OQcr5tdmd$3%2@n5qtqM7=ay4~uNldHN3JAlx)!r>b+?w}%K?3f z>Qzk2qxg#21yVqN{xoT7fuEXSpg#F7gcJBizbH1lMlm{sG7mz!^eI@VN2(6+%6!Hr zYTZ}ixf*rWJc_|Ys9UY+Zou{c*G;L5Cz(Z8U{qL-d;vV`1XQZlFb;;*UIuj^$>s37 z(6O@D=?TLTHD;>}ZX3eiUWMy?#cr=&$cu&nsSEAsO)#PE#c2RVmxY?^uzFks>d+{~ zR@zbl{a-%qB91cE08$Njo}y({VvQ1bNYE;hwi$R-@@z$gYEMos*f;`ps8y8WP_dHr z)rThHkZUCHXIH{y_+J5}ZopJ~Ak;cdCEATnSuav=TcT}Q$+k!E9}TGe1mddTS1qqH zZWTi7Ge&|4fD|t3wq{DN!Xjb%d{R+fx){t)W&8EZzy1=8yAe!Rx}! zB5JIqM!{;&P!;%q+O2g7zOz4k77SX1sv9Jq;Xe||T@6~j1)fUrH|K#H3w6C7xlM1w zc?#s5)xenvm8}j}pkCF@lb4A(4nH^)u0yE0JL5E?%W3rR=}7HP@}()Hm=EvVO-MGQ zxEYMGH_|H}WJJ4^-4$fPX~r`>);immX!)xbLpx84u`Q8&wNrZ-JtlsO&#K7~}B z8MS;3tlrGGeqzKtm-OBEY7-;{3G}qB!p|TptW3Y~7V?!U;YY0Sl;=q~pfJPN9^ub@S!6eoi+gIx9?YUE1bYmJe%l|`fZ6*SJSVF$HAz6xma zYDuZiv0pJa(1Ce7_$5dWjs=GUCzQrnmA%2HAV0`PGPfg`j(-{2byo$W$v-Aoz#Y9` z1ijeRIy#6A#&a&ERq!eC$-(hpSdhZbhFQTx@~sT=fO9smxKDIja1JIfgf}V zM9@39>c5CKVJ$e}|KtDSKlJZ%+Vi+yl0CI=23~N_|BX|1d;Q1Q{o9%yx82aU{6^3< z_&lfk==qtObuj6L^L{cD^}%J%2_J$X+;1NkVP-TlS>7yc}Njo%CN4!8f#kMX|oCXsF|JF{1Nvw^siZ>{t8l4FlIp4{!c zSzcLh7+RK+y?4A;?B?#pp6&tOv)&6{bI*KgNroDZ9M)m{-m_@0wngYkL`P zt{d;&cQ3ow(FeZSz3XPWhuwYdSvMay%iZGs>3-p^b;r0P-Fdh@IKTM;ryTmb-Q7X> zm$(z$pWGkZG-4OHGe|MhJ?aj3SGXI{UHgZ-(cMP=S)|$ErjTluI}JTBYjD#@`L(;l zT~3P4?kIO5x;j2{zjJ%J-vehz6!ILtF_*Aq=;)r!a~_btaX)q^yPvyV@FkJD6Xj{- zHgrSinYqK6_`+@_G=3yqGAPDiJ>Q_HEuIhHq_ z*MOztM;VE84~=%HyyO=2Le6blIMRtYE=u?D=Sl+Cj(`>@Itoy&c~UJI(&t&Lrg(Vh@vUF)=^d-`f-LZ9zNS zdixikZ?ONef3TNvmTnc#RC_fret-nI-qiBV->?dEBZE;7+WK0J%0(6pz@(tNg zc9y+m7ujCEE#H%UWLI*vm!HXj@+&!tx2eEsCtsB>lP*ctmp$bBymjEczVu|Qd|W2T za+pT4Ht-VVOR}bHDI^%Piwm`m0pGy@bRBt}Yk%gV71S%!!8Q`VHMNCpiCe z&RT4p;tbHw_!n83#AaCgtUs({)@5s#mBqQB)z(^Tl{KB%t=0T41GG!>lx`k2TwxYJExUr`AAgkTt;SYW1@^65hvZW3{zfSnaGt z>kaaCBCfU7-f9{RZEd|`ePGoGW;4Rxwi2wK#Jp=&x9VC|IsaaRu$oo_Qq{Fyz&=K3 zaqBsBXH>UhEfjHC#Vngp4{KOgP0PA&=A(Ti&%BRoTK8~Inzzhs^H1|<^OU*UJZtVX zkD3|gCNszUk(2am%`L?2K7erA4cb~lHZJd2cDO#Cr%s0*U=4-fh&6*~v=*-GyBF~r5-}bus3aOqqtD9BL zIP+;tF=C%EOPNK?vSvxMoLSm@(kx_p#5^=gn6_EeeB6Zb@b=KK%zuqMKOHmc>MK@ z)32Yp08RK!@<8XB&#<-;m!@w6YiWp(zK9@3F(@o$}i^vqR6+ z_v*X#U-fnRdVQmQKwqP8(zj!`>Ra?x_~z*=d48v-=~M83r%%>r>(li)`gnaRdL0Jq zU+4q%p?ZIO$@&0%pXfvML4@_z`|92G4tiI;6aFrGXZ?NN+URd%o9NB-M%X%fbNv;b zP4w4zZ=u)F8|yXoy4VJ|bubO|1bnq|pV#B`ih3Env|davqKB})UPuq?F}g%E$|J3i zeqVc_{i{9HEWH5VLoHvstKHQ8)-Gu`v@_aS%mr<)c3L~69oG(Me_#)4S=v!;56=Uf z*58NC)OKpy2-$(VS=*p((l%;qwR9~_Td6Ha6U0Jofi_Q@uKl3R)fQ=~xU;m$+5~MP zx~qn3FSXC{f1(Z6KGc%2eK8+v{j?;lr`A>LqjkdlkMq3UQaVQOhFV&XX$T}g}8Dr29;RKUdHe@ZK(71oMq zG3bzTHD7ZyE)v9QxI%j%3dBF+j>r@D#NXnUxGt`WT--C_lE@J!#c6R&oDxUGadB82 z5(m-Ul_fGUyTx|gpT$nGMQjtBa5rGm#cGizR){5HIl2y(iuq!(m@Vdt6fsN8#H5Hx zVyc)dCW`T5g7~i(Cq{^o;w#J$F-&|a28(3TANvvJL(vPPidRK*(Nr|!9=%4G`XW)hBXFxDSLw$M<8ax!h zd-m%V*E4qDU?MnI{=R;?J~JjwnY(BT1Wlf>ctX4v1MFf#2!ufd z#D_$X1X4j7$OAG$X2=5hff5XbLy=G{C_O;w1NDanLPMYt&?smUD6^sI&=P14v>aLr zt%6oV>!6L$HfRU58`=lTQRo=pOV8dI-IPUP7OtFQ6tt-=P%f z7nBO+LxoT!R0h>UwU7g9f*PP!$OT~x9)n`g3^^zUhMJ*cSisZ5urjgm=P!!H404@KN{#{4abHz6bvYKY_2qSK(XmL--l| z5tL8x5BNKr1pkCH!7~F+fq%hya1mSzH^6l;%&dnQ%x0LytN|5aYM40F6SM|q0Mo+s zVA`2#rXT3XF#VamnGwtZ%pT0{%s!y@V)kba1LK*@iOi+USk!Xx}h@F+VWNL0iOZ z15XC4mFZwQnJ#7%lgYwZOqPVDVVPK3mW4&J{8(0&ilt{6SmCTFR!3GRRvfD*s~f8; zE1ETs)d%zkvIet8v1YMmur{(bu$Hjav6iytvX%qL0x(+6I>b86+Q&N1+Q!-oo|{<* zSSMK*S?5`gS@&6ASV^pptoN)ttXHhtVDy^xiIv4-upKNn3u2dnwvJWFYGAdoC^p8{ zu{CT9I|x)?&@-?lY%^QTwzIYDXm&q#M|K}}I6DUP{Xvak_W+}D>{09i>`Cm=?EdUI zV9hl40`?O2M)qp{e}TQ1{SW&%`#Sq6`w{yIJDHu%{=!ZL?GyGV_Ivgl z_C3(gW>>JY*ae^zv#Z%T?0V3;*$y@zVIw+3k8lwlB1e3YTDA)TA}L5Rl8U4u4WR!K`3a!kkrt#G5pmQU z0f)yCb7UMZ4hs|>2j%=lQWOA zkJFzs3(QUCOyz9l?Bwj`?BML-Z08*1Oy?};90Q}h0DhYj40yTu&0j%@pYPh|)G2G4E5#0UUvE0Ml(cEd=S=>?FL)?wrecZpe7q|<#m$)yu z|8lQzcXJ;A$N}zl?kVoy+@0JHV3fxF#r*;1Z*p&ObHU1V?mO;DZYDRCTg0vA)^Z)( zByI}#Be#;9!Oi0ec)z*zTsN1^v-7ICy?A_H5Rc+%c{(1<>&ElvP386EMf1FQ9eLw< zU3m&#FJ3GU2cr(WExfV3$-I5M?YzOfMZB53NuVy^jpjY!ZRTC&Z3Q#ect?0wcxQM| zdFMcV$h*PI;U)0i@|<8#I`1*>883c)0i)MECi;peM~itd`ib|I7tbpPm`ZtV zJRKT__6Kk=>f#Y7AH`7~6fI1Vj{ZT*E7afQOqubH7=x+2BdIsH( z{*B&8gV14U1bPg#d(pG#H#7l#kG?~%p;hQ%^bNWceTx2zenju0zfmWeh*qN{=0Y>j zC+H3I0{R$DMr+Val)%bR1Vbst7vlc77|eO&dORF2!oqPMJQmFE#y8?)@J?WUAwB~i zj?c$0;D6(1@fUao{tkZ)$^!f_z7?N`Pr^^(|KaKQef$xA4L^bJ#~PdB`aB2)?rgW5*svt*D2-S}gQ)2;S9<_&B zPtBnwP(!I0%7ao<-Kf6QVlX>|GJ@H2)Ff&r=!a7i!JggJbm{?ho+_tKQ6H#}R2g-J z`cAE(wo-=x{5B|6R1=j=X=##9qOMWR)J7_cdJ3RIx|Z^zd2~1(Ky&C8N=+wH?*NX$ zlz{$0ap+d6korWC^hqk2+5&b~Q1_{~)CsT-p}T@vHZ7zVQx~ac)LO8w9;_D7cfk59 zR5f*y%Aod9nN%W`PFxZFj_>79VL zcFI=(tQ7Fa2c?u^f!add0@A$!+~1-i>Ei!$SWRi@cT_F418|l_rBQA`O9<%r(*l|X za@_**)KHf|tplrSs3ZEWQuBdibyQcN5tRN8`1=8B zyJRGt1vu$Xa{*2z=obNrPf~k0}_`73v1{g1Sky{a->OutO_l1Uy90F3S9WTB$&$w?Kjn zfVqxR0UH$onQ8%V8>s8RB98&RcVMQ7@}kcHno9tucYwCDfi6D+sFK#vQrZpZ6$3fh z0QWPh7?gH==KpK47HF$os_y{rpFo1!z%I|gY#Ak^?*m!tsTpABO&~3sZUgxEfJ=mq zqAyT9It}2N1uXiUa)BKIKtCFq1t>Csy)FVfWdYCR(3wDHGi?GpqUhs5r?-IK-vb{l z0ocsITCG4Hn!XEY{Rh_nLp`DHQckd=mNL;QIs?qU1JLt83-1AUE}fd-FKL9~NH!5$UBSOuW%dXEQ|F9s6u=}Z5&bQProa~}W~-zkWG19~nX zjTy|^fj8TMX4$~jH1NfC9k>2pCcpptl8{!=?Qv5Ja25jno(CFf=dBJzX9`8oDZsjy zfi~LhtpXgj^Vza=QFVO9q_Jv>NCXzF&GDYuH8eD0hB|}2N}T(YAw(l0zB#mkhtCRih!K0 zfNBls)4)PP`Uc1kKLE5CtfzqeDM0f*h@x7s>OEM07f3Ax@g$_*f@lo~(wXRIK+X)H zZ7;e2P_G1fYX<&?fb5V6`1?Q|1D=pT-TQyEKLs{VrbdJ8uoc)k3CwBe>i+e8se}kOAkopNugrC%JkUw#n0rdDU z;2{yn@c#ead>e330&tuF?J=Ooi-7)IY6Z3Y|FP0erw-UL9`NxO(0DxH=_1gY5=85J zfTb1qTO#0f5STp*vKos%NOhvMK)MgWN8W+?TObQ4fajU$2*7a^(3BhaP$sn>aB%?8 zZqKfTKuZch#}8;P07RY|g9)KCy-tw3vqz_vdC&eH$KLVJW8K@9nV zJn8(uecuBJ2jq|sz%qA%&XNH~ZXo|X5R-R+jPF7IGXg(v*ZvW3hMWf{WbIjLJvdS0LH^DHK6MwwTqeNV?hEa{d;t0=z{xFeE+vB98KBkx*fYTOKVZc=Fp~tJ z?PtXvz~x?QDcF4x3Zn@SlW9PQ?Yr8ub_?K>1+s|?;A+oX>0tF%;7@zN z*?%3JBH=*m9ALF~|Iagbf$Z&moCq)%gFWrKY|oq*0dyOX{~efV1-iHm^m-h?Td76B zi;e-0z5?R05!kF4NYVn_rATrmx}=xcL44Efa+|(?`+_c&p{Ts0kU5{ zINxY`8{lLmupxxr_etQRKd_8^9&N?`>dn6y&5q^m(wiJ*T$-3tRw_ zUIt!W3?$dnAt1)QKu*j6{4WJO`~&v10uI`>TMRI?Tl+Tfft>*RGr&W;&+Pyn(us0| z_q-%>4iyaKSq9$cR+1-)5aKod3opgCVO3}n?<=<_;@^6roSjpbzp?Q>He3~AAWTz? zv-InAv6`py!TfXF?nn~vBo!l!5RDVQ6UK=5iysSxf`c?kJtcgI1vrAg#ExNZ>;!S0 z>`FewEvStNHwV@r4X<0zBIBuB!W!Xe!CLAPcuzh{uEeF-6Wo`s6ONX8%df~*%O@+w z$Xle7Bo9Pa1TcRWxdp$DUgXvDBt&oFR{0*~Y}t0{Pf~jYBtYspDDOzH)zS>kL6e=f<~f zLGs_me0c(Vy}_gHEj3$gqt}oN_!<)CxrmR#QT&Pg^)iKQ0+GRJaIIln!2guEq(g*_ zbT4WiFNS>r4^f302FcH}0^4#q{m@O!7UG^E&bWa4sXD%CqVTDqO>=>-BAf7;@Ja|4 z&oN&VudI2MTVGki8RfanS1B>o@oKuGH`T5BJ<3h^B+g565IWFR!LdSG{Hv9>H7%r=piN3BJ#~-Lgu5eKaM%bz7X zSlT)5tusa6HDF&rvPH)Ks|96c>gPw41n02D*RVeWC&tPbNwbLUyuQ>d#Xq`Y{WQ;7)mmY>XpX8%y-Tu&xPVk3 zZB&wEo~*BE4v|g`)npr_3M211yG7j9TIjn)UCJzOOn`9lZtW`RHf|Tz8B8h~D$nuQ zY?<%5T;zkDMIYgOaw=NNS;4L1=HUb6g`P#4SyTdRJ7&=MnFF;=V2D#he?cjp`%Gl#f-_n2-2GOS(7SZumz0scq0MCcCw{aJi>M+kxLqBBChuT-7!5 zlt^Ix&ul^WxsI_$bEAL*o$dai<7da;orhp~HIa85GqRmn#{*jj@dZ>t}CvzfbRGp;wK=HUGOqiIf zS|D#?er#|B`&E zOo%7Dce&SMW;%%}aju3d=n7GHDdtgPbb0uTlc9mlO3n@WaMfgy2wlc7Fo#l?CCh}5 z_@n7XL@8A-u#kf>HTjYFi4Ni3=Iy~H#Bpkt@DnZJu3;yNH<%CVR&ZO|9Ow<-hVG3~CW8n)_R6wm#MK@X0M*TDGFS6&%$ueqUZQ znnRu<9&qRI;zTp`6HV_lTG0gBK#ikP$ahH3=6`ChFnY*&MxDV|vrO?^)uc!vC$iAzdV)gnKa)a|3e}8ja_YYrs|ICS{!Nf+|t`S;CTi7q1o0 zC08=2rW=lv%rOAEE(J(HRC!V zPkr6vlq?A8>zzKZTMS0j`tMZ-nl`>BeAiT$aCaaJQ zC0NWd<`MJ|?xb(4z8f!UyvT{n$EZy)a8dMWx=jdT{qC8RcL<-*ekq_>v%xS_?j3C!+_AbdU^*~V=D&>v?H>-a19_3l>7WFlW3AeCjvpFb*HKETj zE}G3KcN}WXB%(aJTIT3x5(`;V@k5e7B)jP^XdS%UIo7cmg3xXJxuUh=`vMjD8eNBl zQs>0)r3QKiOVRq5+lpNlzmu&N?Zgi;yD(Sa1@b<+D33zr8fq6K!Ii_biX)9tW{1*D zY7i%~1iMZS5+*21^anI15yZ!Yk)n9XV0nS~13yssMwBPcQB@e9=oG>cWQ~wkX-$Qp(U;jonnzEwTxCJ14g%bBgN5!iIW_|{_6z5PUL_K8}CCR{A=iy}bL-Z`T?~CP~ zVLoWv;ficEK~5%vbA`Q=xf3L!?(AutPUv`UIsC50+F+`>TK=K>PiGQy8K;ds1lG4! zHw89lxsJdz`zXArb#3$4y0F@3^**jo%vf-Xo5?o06|JY;LRJ?06uS!E=w`dU;r>Vi z_@OL@e}xJlZiD;7Fp4J)(5}~{OKtc7=Q%x~N7R$>skW;g ztF*JdMuf0pwuK%vy;SCEUVASN5`-)a5cyrRxy`3F8H&ETOJ1*h=6YRJSP;UQ?DnTU zbz1Lkw$7I0YBANw40nHMleu5D&Ty@94s!;!y@Qu>HldI4VBUEss^yeJ-@LmfsrYhE zaF$PAX5~fa9w@>+-r2uFRHLp4E~zRA%nvB|P%x>mb8%?d?aG!KzlPiRTZDgQel{87U&*NXuo}RxvzIo{NL-l{^4r%g~aWb)Vpt91_XloA2k4T9UM#TGP zde5;~eMG(;eb$-=cwR90Tl)m=jkw&Qx{KKll#Gz+` z<3pxIs$!>haz%d)*&DDjC_m)C(5A50VSm`tq$sqf%1}AYWfo;wzjZv*&lK0KW3pw3 z*p9qwvDCgU^vRf)IySR=k*Mxw+rPZ0Vyk|dWuYNf{Im6HHvVe(_4Lc*?$v$lmhX1F z;LOHCIA>bl*AJ|@TwPt!sd!uFrSH4n{EVOXW<=uNqA4xUcyh{u4Q-QEa&z-CH|7?V ztf+A`oNg*@oKc%makBhv&3%U$p340PTZirEiILH)G#0@z@Md9BtTX2Y+0EzZs%Gh@sVodcadDoe1J(6ZIL#yis5&$`*V%IBuv+~BvNTS65sW_ zXDIY8_umvm1%C^HqtA64->|F~fVT__Ettb}Qpz-c#o}`MHRp!xhus zPMtPvcIX=ZqN|w)c_9De>>NP}dBak;IZO>gp7{v_tYf4Qc)T+mnK8u?EAK()c6gL$`4t?wb*21~Xf zOw(C1ja-I~#3s>p#Wf?#Ulg_@{O^!m{zI*QnLc^G^L%5vZaHPW=)Ko#k2%|X)I!+? z`Rxhl5mXga89?}5v{l*uwD%0y8sZn>jJO>>EL0Y{Ibuz0Wv}!>w?=#(Ue(7l^oW|l zdRW#oy=P8$$1>T3(1Za?CoGv1Heynzv&PBj@cOLtwaOX#WS^LHPNO}JM`G+W^AEGsO8Dq1-XZcS^!$&>}}`aRk3!0*YB z_rlb@75kiD+=f=Xac0HJf`sgvoXf@9n%epU^}lOUD}EM#$&W3VP4x>kSLj!t#FObIfl}@Wt>cQC?9G!%71``yUAG6S^+4e}`VN$2(u{I3^-0q;Gh9 zCqX~oq1#9NJ9taiyS6;R-;NEX5#@W@9?E71n){eW_Z{mPNJg&JDX>E4m@2$zIf%L) zX`|C8=P#?T<*n62A>k1TwnzM(mG1Y&SIno@pPT!@o|s&kCjwS2FveN-dD#qA z%D+Se-^w=%_JCWUKl$5*S46j^C7Lx}{r&d^2M3kfb{L$>4$>duY4T;d{a$Z;i~MBv zht{oLqs$k)j{DgCe+7Amj1SKBFR?i+;pQyU2+KXIzs+WAwk@;&=g$nD9H+O?#mn|12C+HLUhzwYmIAQK!7E zIi7jvN_=ZaIJ&m_xKf(#RqrhJ&(2S0WUa_wTF!0ChqJK*0*;`qu6! zonL&W!qT*o^+TxFf3kkDm)N;B%=y|$RZZDDgegm;PUKB!x2=QACbM{Nu)u`BI1e_=>ohl*akhnyNYYE=A?e|w$` zee3xjdDeZhsC3yBAh%&)M@c?Z=y68}hf+9bwHB z|EtMVZ4?bcuGfU6z5AH-azwoOMf}@|-=otH=Es#@uj*TSr+WA#MWoPpJ(y`S3nTp~) zbpm(-|F!z8C)e|a66ddC1vb5`cwOAB#JlRRmSo-)iKl*y&$7T5fnoNu<_GG0fe-I3 zYYegpe<0ee9%w#bKN#o*vRj4y59=+j(Pq1Oj~VkC0?JUY0(dr-;xsGtEI*LAtt>0@LM zzuEfXqKTYU4po^b`_k_NX|oCx4Nc5k(kOZ;*pDgPd#f(w^!Tc?sDYGbd(*X22OYGdtuI=OKj`3KaR4Y&!kb?|~UXxjPHx4&3v1ABgdKFPzE=wX+6&fW?ETc?B7TnCxtZ}%5&~@csGYS8(W8Qt_muZ zlXSQALeI;(NM*dZR*)*til@tWtDk89@W4GqrgdH}ug{hN;N;!m!}qDSzVa@xO!vOv zlWV(YTjXQ3B9@2d5$0Tr%a<8UgnLGoMT`ww7C6E7(FBA0u-6_t3_7nf)|)I&C8*2D?!2DIx)eu*`uUsJ zDGKn>hyd*?EL5c%fBUHHuYC{r^fPDc&dZkyW}^Gu{-1orU*7 zrqx2*~}KKfkC)>D7|V0#)w8?CIIY>~%SD zx$|=8=Pu4k%Ccttne{t+Tb`t7S@DX(s)8XU`4#z9Pih|5M>HRBENZ$_yR33s#mq{o zws&((8=L9iCK3b@3BGwA6EnzELQFzb02zg!!AH{Jl4r`x9=l9lUe66~UAeYU`%LF! zh_qa_#rQt34fG+r$9nBD%e_uovVH!v-wNm(ygpPDQV?MAJ7pj4KR2*B0QXDtfxXjB zCk?o1r1g!THpme$!k%mG;l0-!Y|!hEc%1cQm`GCxz0;%7h>qeko#RhoiBvvAtuuMKuRG&G(g`#Fs=SNtIG%R9Hw8;+gL$Gx1C_JYzMh z#W}oDE|0ps)oW_H)jezWhW5f)j46z1@b|W+rjND%RURt+oZpru&8SR2m{FZ!%u?jW z6=Ef&rQT)o;->t;1=V>yvJIJQvghZ;uTEV?$KI&%AW(TAPPA71dpKbeo1Y3wy9OVCA9EB-^&B-$%}C^1QoD%R@Wo4Q-7ye4{0 z^BQAWZ|Pv^V&)hNjQ^Pb@>*hjZJ!@-J78cyLO@#3v*2w(CH64ye~eDgABM$VO(3gY zv9I-6Y=~ADsK=U)T0PBWy0hw3<#%~0xVbJ+LxyQ)+^|)dC`{vD6C?^pi*a?h@r-$Z z@sNjI~L()^YLFAlj7SYg{_dE(V*P4*Xt^$3gdn`2t2 z+wM_n{@@*M)_VM@A$40ku45#`Lygk*2AQWKUBX?{a*b0ZqBuuvyQEeoXX_~n@xE$F_daC%!_KzPwcYa0 zH5Z#6SmJEQeK_VD+JmxZ!ka>i@|&@<^|IFp<3n?!`G|3xsnzSaNues_uOwCIuhw}@ zSJ)pkr|l!`E<=CtCACyC#B+`HptrZ7K{kiu*A!O0zIF=~t0b&`I+TFGz4~EWX<%oY zLG?G;Pq0Wk$iSCvWu1d|lY}N#zsKW?(PTd#dMI*wIPUkx(?gM`IAz@Ezc2tdCCe7j zI^rnZs@P&V6ti~a60%ri{27jx%TKhoy0CO>~GAD65@-}krG7mC-vdhtI>=rf% z-OXxp45*vh@TFy=+tf0lHom;DWJK|c;+>^Lh}J%@Uu`{M2aVL#RKoWAfF$V}n}sr9>n7T({Bs%(PYBpNz%s@SdVSWV=k! z`aqdZ=Ba(|nWSvtwYmb~p7L!0>Y%~$g>AE(q0B$PjrbVw3t5tGu-_u@AgMQ3$qkU4 z(r#2eQfjr8YG1`DdKy&jI6*o6bg>Cx_sq)`@shrZpSnLR2HRL;q*RBG=Ry3zTDhfO z|3bDyW%F7QUFp}HpeHF49FR&Ry~u;y zql{%uJ!|GQMWVfwujDn{g62=PBcbdtKC0{L zbyW8X>)c|2YosUjE9KQBiY-P)va+bZJ;wP2`S@y1;qMU?8$-)QBIO$OcGY_&kN=Pv zhqh_vTecbeWd-6f$}^%MaL>&kF1R{@_pcR#i56?v37Z;=s$bCh1wSo%V0HxY%>um4 zJrMs-6vOppz*LL!o~&GORpiu$`s>2t)ZH6;R&}6OTHYDD(;u1nNCiDybcydJm4g#w zo~#T0g11%Jpu3~c;=!0FUoQ9{Tqx{J@VT@3O3&-Y4%(G+o6wuugD)aZiZ?60m0CH6 zUg5~A+Rp0d@y7a8H-wtP`~r*cRZ^xtzc<_-AelH;IkHtI$2*mRlrz3Xf?UgAi0_NsDxe5avv5?%EKIbWsRAdMFR@YlyCr z3|%JwP1!$bik7an5gkMxJ)1X`KXz5)qxtpx9>Pmvhx~?mmx%3l)WkaFfqF>D``_kkTqjCs!2LKcrfplBxA>XYea~x(8T`8(FJu~mBG0H0 z&1mxq?F3g)!70WZ+a2E_oUvti^B(Cu>l@$QR#+3(eBj&6pNG)Np`&6388^5emk&K@27@W?yUYrdl+_TMCy74!aH3xrXfmM6|y7vuwZodf4RRTS=PRksqVH@ zEH_v}QZ zZh3QEjqX(!yI=R}?O!fcobz^eK4Nh|U(0#T3k9*(#E@RPx@Kot1~$d&<*}CERpj6< zs9RFcB7PcYd56lP@wNPU^e=K9b_7jUnTZS^;XBM z*`8lPL`QxP_{pv+c~jLzw@OUo|cdKVCQQpb75VKkS)5bzO(A?Myk`@1H03 z;dhGj7|=^y`+N19fo*k>TLx*na$V={2)+)q&!5)VdwV_ey|bjk+O_Km)54~2C7;;y zwQj{_te3b>Hi|L4Wf}j6YJlK0_bs}X;EPHnW4J7akbEMwQhw~-?4F1RmEKfOk957Cq8B)u7oby` zqH8i$S3-Yai+*j*J1m*g=~8SQ_gf-dc+bl(B8=D36{U_;%&6^A$`O9EyZ8$BI$gP-Trz3tZ2>pOR0!2wqs@)Mj2RzrBCzq~Mg<q=+gF*{$IgW3*~h~`wKF$qDD67WN2}$QnV&#W=TM}LS24- z=ennJ_Kbns%6{J-nTqJ%hUfWj)IMOk3-^`mR8)2MjO>P*3MZAS$PT_fzHf;Fhm0LB z_*)a_cigOmOqJkwSxT^pX)M2%IgA(=sqoKY${J76 zw|zYHC5==uEqdSMew5r5k$Ti|#j?@b#u>qu`DcYTv~JIcOKbCmc6W<Hlj^Ys~zlxVLAd<`HuT^b+n&V-*9t z`$6EAVwLZGMVhm<<`sWM^yq#!%+{<+?@wUEM~wN*dChk&~DWrnI5FV0@;}28K^4_bv z+qScCHt$Anui?jydvaza;Ka?LzC%CpPo-uzPK{mE^%_)Pa8dO->Yi*Y@=>-%y-9n< zT!$?xTFUIvVP&^vrWEd_##?O;?TMHr(VOUPdB2L4o?ZichpTED6Wf@MC}r4g(J$X?`mtB-{B5l zJ=mPXEiYP!V}724LN0obYRk#VaC=9j4e__Dem=a_i!Gleou1@Oz0~$T#;bYm&#A(i z@&7T3;)Zu0{Tq+SErMKz$qHX)vsM~&9SM5jsJJ|0<%BEs1I}DeukCM|waBOFv--n0 z-KC)qd_2qEm+FO9U4VcRQ2HCn{q?^}w|XJtD?;{twLkC>N6i>AehL(GBRuh2ciCKy zU(BoJmuYt17<6O{wd$v#aZ&^twHbD%j)k|!$b(G4aifzB@m;=l+O;<@v!*Iti{ZIR*mJ2xv zWQ$=vF_(FP^98$sEp5Y^@5$1;O^$$zuG|_}HlugynESf5DI4OS<@C{a9o(&NEvwse z?w1n=`?%SG$A1m~a*&tmLmFoD3M%F`9WcrLc~D*6e&#nT;m;M>>*OUL8}3tXV~+n{ zs%b^d-=OB4;Ca0fec|uRkMGo~yB?4GM{=}Kkv+HkZ|<26XZotSymx+?3F@I;&Ie6w z-I5>S;NgF=2O~ety#g-Q`#%J^FUT}?V{p=U=~I8?Mffb)hQ>~8E$MrqQVcFEzGtkU{5B9T?=4Na9)~v^POn6f4QpxR~OB2td zb@o=DbOQV-u{?(5EBMUrhLEQGfDMcr?+#`5Fpr7hD`r+Bl`B|(V0W1=!qeny=?H)P z?vkPcRmA4BnaeO0pb<5`0CO=Ow!|Oxgm}%l;xyOHB zgp%zO!eMET+Q*d|-W{z&+zWaP$%tn>H}fp{NEste=KUp*Ys~J!DeCH#p(%YnlFGMB zzwb8xH_&MoS63Czam;`#&@*P1KS8Ax)#e?>!=gL-N7Q1!hamGp0*qnhv+|0GP|bF! zSsf`ET0gcR7TFk-M&l!4nyed#%!Lrfr4HS9J}}0dGh8a5NA8 zdpAx!b5Ln;nFA{+u8neBAk>yp>tN+&_J`_8)k&Ni$_Q13G)Luune%s+zx15fN7iK! za_6Pyl?Tr?@Q>kI!M|T#f7=761}*A*#6w>2=iBog$ zS^fI&Py{EKKU_mJabpKhXv@C(`&)d+|7OQ^=$+^LWJ{qo_{@O&o?}a<!haLk_Pf`6LJmDBC>wuqBoT9QQaie3f1x@uPx7JZGa zO|dCEDrB$fhC0JV8&x*Rc&}ByzZ_Rnj({fUm1Ndf8ae;+q*IS2h1#qzjL>`pl8ddJd3Q-^S4*kN7b1q&%j;y zx}u-CL-~g~Z3-LBD9ul06$PvcPn8+K9f1!o+Vg>@QF2)FL8p`junsY&sxy2XQbB74 ztH4+sJX%@ZaJS(f`BWcs`6rR3j=9N*VZDyZH9P0-)=>EapAU)VgSey*q{GC8`Q+>mE%y6Be>b6O^G z#&Vu$RnlcpU;KU0_vj`3TLpvLn4y`WS)5089fgN%q|S^Fp$5qh3wAPFi7U3MhzfN< z&EvYy9;#4GQSI<@$taPW&w?NPr_ z#L+*QBU-9ht30O$ZO}|~*EL_mY3rgemHa@__N=euicUK_{i1J{P?hJ22f=50wPz)#ek5 zVwSySD!#&_MV`oMWZ%NN;ob2v!70UH=@3pGd{TxQZIV~y52-?Mp^a)ii&h9;E0Z-C zKMfuaEtYi-5Sk>cJB_aqh316mhV~+7UBzzaXj^qm6zTOVsd{P%uTNLczl)L7V*TjC$p>w5fOHCO3ZdL&JKjAnrZ)d5FPp|HY;VJJ1})B=xDjBSeF0d}IRDZ9zhu9fV>|4XWT6u#TXAbdpOSW*gauazd_XV8=VrD9RpmInv>|Gr@ zRxVE~{!N%ZkE`y?D?{%tD_q?-dipeT@W-jI$|ajd{L`ZuRwZuB+oFBh`)b!*+4Zu{ zS@*#0guZ)~-_aKQ_w8nP__02H2xtY*fW-en0r<2##*vY!EOkv^xsc1+@kKTbd>kAI`HOt?HBu=yn~+fPn3VV}@1`pzPr2-H zh}Pdvponih}y-7Btvg`g|>~aOvQ(Vo{6YLJEd7l23k)JOtnSjP5U;Bv$#9E=LI4tRZy01ncH={ za(rc$^O7i#VZ&(!$%tX1tpUa|7=74#%Uk}h5{9Z@hg2_{)O`hFHIs4^DL zrQh{B+l#^K{N-HD*N!p$A=)qLP==4@XTLWQe8)ziiAw_sqAGyx-P|yH7aXyR;zoZdz;M$bo~Z8s|S* zol|Lbbk}*0cUBdVZ4Dkvd^_p7A^R)bO*-wjkne_H%+S_@>`>~2=DGZ<^L*1YRjW^x za6!xC=HKiz%{i+>tatTc{4Lln9L0UY9WH34m}~Rg0&FSMhE{TI9j8qJc`hsmwh_u9L$uu zSFO3^FFKxg1i8ms!yhdFLllI(LfiCntlb2C%aiiB@NeTJTej#xTbO$gmm!SRDK&{~ zR_%=DRJz4rS7=~Hn;$t$zt+%~^PqHh<7i!DfRJ9Ef4Tg-@=;j1@kCpEwI{Ps9%WRk zdm%TPM{@3{hU=0rRgJrLpHS;jUo9|jl<)1a>nJz-kZL1`4V5+8V{I9JFcf?)9z;Ws=IFF^lB5>S!2 zT6$afT?h+Tpo3TwIlZZUQi%Ge@kwJ>RbuFKeb<)Cy1(f|{?olu9f1Wflwus`Eg%gi|+33 z9GLHXH(bpH&-0$M&%5_t>$g6F%cictPmA^okqE#xPTr|JD^ScB4ZLFX+breZ8BFY9 zql5WnykYu!>?SxH9Yb=X4{%h%DBP`~kJI;L!=~HFU#2r4JK6T^NZ3bECi5tu^sUo) z>pa1oVBh3^#^FHq=mJ2Kc?Ek0d{+Aqn!~_z!r{6+7+y5Ng3@I*cH@ElNw#&y&n$hZx`l!b}G4(9TPmt24EW7!x%uFo|@HY zX;{%AvJ|&Pw9)VlrDgDFpCzNx<+$nlsrBty*oQ{9<$P)eCPe4^I@p9<_3u!5KAVFamx+PiO1oGp@Fo=Vg?!IUIh&Wt*@Ij;xo@_PN>w(AwqRh|a_Cd`xTFVnbIzT# zNB<(}ew$`A#e9X2H6^2Jpv8g{YWiImPnepk9Dc8(FF2xJXv`tJZyu<+PhJ=CWWlZp zlk|+v_pTO;18En2xz!vL7rBpcfAlqv?U1ky0S^(_5hq}EQ=`xdp1=U^mWShc(BqTJg)nDBIv0I%d@iPxYf=zoNj z6bbm>ydGkd=taemqe&Z>-*Mhk&bkv!U;a^c2F)HK9NP*e3S*S7IExV-lOwbFq&yLv za}w<|acTS@r@*0HYSKljf|BOECd>{@j#i$ZRG8LSWkP4#p3c;Wef1uI%?5X)Pw0JP zr0AHUZV-NfD-q{7xxmt7&j5AGk^j>&mXqA|t5YDo=yy*@X~a|%AX9A0)Q9lr=MK)B z!HzIs;$PT6odO(%yp_;E%s`k-o&&iWVQtkAM*S8oTTv$S22@zxpvd9(nkM}i`(K2+ z?Qh51mnT&oHEE{_=v4H2~w85};`e@aWfnNO#_iEwKftB@R(-|g`fCN6Y z^wGZs+>HTBy%XKQ2CC&o1WG%!)D*i$;H2gHKV43siGA|y-?B6UC0;~NGt+oDm`>?h0%G#Z8IYc(U>&H0)bc4 z!S*h_XO1Ue^Oe7*_o%BZ)?o}ru0bUNU0whh4E~8XqA{WEIvmDp;b!ESA@J;O_6NiD zbOK=hK}qk}au~NY=e4KdRxGyR40*UccI3K#wxs|+KSI@+VHS!kcxy;&bgs>$k!B6X zSx<)x$5xBWte0Yr*3brf5U3E1t}j*spUYAJ>n^hJBVXrv7k4!6w!oiFZIxPLa#3}#FS&xhWlOv>WmR(TYut~ zO&AQUApfUs7OY0Z5R+IS-K4%f$Rmb7WNCo^oj?&1O-S*45w{a`Sl5l6!McP0k4cnA z^FAUM>iCdh>O`Y6Xty~H9>y4e6@i~h_u9Z2N2ZOC?**dxZa`=y!*0T=w+ceOqh2#c$gW4d27|mlJjGRKo82A}>(=X0n8%w5ra(1$)n6_*V zB5n7yajeu#l=$m{12Wt!#v2<@^5`W3gP-*tO$~wuYbecpUWb{jzRnAuU4zUs=~up( z{Wj4jyl53A*s8UjTSXhuTgujfM4@j=b%gG)7~N0gFVb{=^=$HB0Oz&K3B9Sgp1DM( zLhl6gtakBq72}|7xN>M>bj;S!&5yz!Xh@wqo(pfqB-QW3ofF`@?(kVNq1#5ljISLD7roIQ| z=J2l`9K+g2;I<34yG@Jl_xxg~oOn`tgisQ3&G*e%-;e+1k^=Ez3(*;WJ`8wS>HB|> zfM(85W^+0n4b8RS_Wu8fGY<216U3t7uk&Psde=ZsssVRgmu)S&4GPiNWjQEb}=%u~mUcHQ8x#-r25 zhP$k{lRO7sgW6OG7m!HQn^|cGnzE+_LZmCl?hjo>^7!rwG#jP)GoDR(s_f18y%k0(Xb63no^emcvEx4rDg)P+_LO!A8phUWF$ZXMC zYQ7Fgw-<1)`p!I>JWkLxayC%T+$ozH=UF*D-;&<(zb5{IQiz@T95Nlh52f?OV*UDY<~YVw~}wUWsEOZ{VPeX2uZy2kbcRG+k;X zVH=6T@L~Hg{E4R6bJ#M11MMbzhcr(J8 znY=afR{3x42(W>i=amWkIpd7w%u-escM%`(rE+ia&hq!M_LF1CZmeYP6ON2YqtobF zv?0ny$|{-@eU7q{JW8pjIuXxf8n6Pgg6fRlgd}1%kkd$q;idEM!7jvhdNS!4Y9m|^ zwF4kQ^`R|r8Q3yJIP4D66?+Q(1NvTP5vU1z6V-*TMqL0XV^@&-QH}64aJd$y{j9?T z`{*{!eV;oFMxxFmV4#3GDd;C0a8$$GwP~}f=dOYFfY<8UYWK`#>YRqIgRO-;0Kb53 z0N7j);Mbs@kmZmtr~@n;x)It7(tFffnuRBcs%SkJOxgN?Sj_B zE+f5AB*bR83vw$4huw#Q0M4BPJe}x)111*eF6<@zKO7ZXh~{F7G3~ew#Bsu13>2WF zu`ny}9oU^HI6{WJhB}EE#EP*HWEb=-+!*r%pH2uRE++;PLWnQOFxnbw9R)@`L+z$q zCHIidkYCbHG8Ifi+A~TQ?FlQHEnrJnp3J3;Q;c2A&&(qXeR>h4g>r|QPGOQZ6aNs$ zi4f8@k|X&t;3q92{3U!M#u5(`JP4mK5eN>v0+EEwN3_89L07@fAj{E1XlGPAG!gP0 z=8xQuh=%vVZy+#;Kv*fn79jkEL2Dsxy3L@ax~UKq%o2hD8R~2RTfq8Yeb5AeZ}$Vz z4PZ6dV0~~LKwVs@`yaqq6oZAj2A~Hz_5jhc2;e>b)x8Ej2Oa>3ivHl!(0{P4u*;CA zxj!oRx9Se-J_J0USHV6I8Z;4Bg=j!0V(ZcEsA9|k+<*8$93J}vDgPJSl3JAvngbudE*)eh6?Iiv)iqU;>Yy58Ewk=%t}=SAtP$VhCbQzXcf~lx6T<}KeA6OzirH$jKEOQ4Guv$W&RT1o zVNq5-{hv%5hD5K(w2?JB2N;2_#5tl>UjH8TQOp4=IJ zy@)KmDfiXW$hJsd%UYBalMYLeBi$p$FJR$;i0P=hRbgwS>lSY4+mNzu)0%-*D_4ux z99+9?ef7p0Tl%)u?l`$KeP_weo7=mhhLkRS+rJpzY&%hLtobDO`u(IgS)X%%eU`tj zf0TO$c0W!?Evowrwn3wKZC>V#yl+^~r0Hk--a+y|&o9neo)d))RJaHv3F!WoJ2Qv_I_C zit|=3o{tuQLI*tGD1L$^jmF=hDJP$|KUws&`|0o#-s5`@wD*rZdHu#D^T-eEpYD=f z)-;e_VH6|LQ8QpQp1A=J@}C_w*rFN_s7hxvchW5563>d2!C- z$?)>fO~DNwd`q0NL$rvO&*al<$tf6)&g9UMHkbOAx-0F=Cz6ou%u4ZR`6W>sg$>b; z1$02GDSwBHzyG|I2gw!YpD&s!c~uYXDVfO7{s7y;CouJ72xn40ZK3pd6KJ%6>926U zY6v{}^ZWxpct zEqfEO+*3mzE63c|KlLWQ>G16%J}2Ki8vb#=d7`bWex~f)uMLHVikan{j)gP#b^3-6 zG@Y)blvR{|s-d-dcb2qbE9>(9%c%UktUL-9>8#xpu+Qe;e+MV`o5!x)^lPbp@Q~kW zzsp|XwmAwGs{u`!@18K9ISZ~r5a78wpC+@1z(Yw>K?pP(X86Wx%sfM=uj5yn`>E_H z_s)XbFCTtMI{mRRi|Y<%5g~Rq}}kd{?|R@9j97v zHk_$U{^RsRo%ic!WK~H&8?u!4Su$!+q6`ys6ERTb?51(nn0TUhGIgd_b4EL=dl?>% zw_-#Kd}Y5CUIw;Ce(EVJC+9q$zTnp(&I{bUSK2(2chO!Wzk*(C7eX#$HS}Pik6xI; z0u{(uVS3Cg#lqC$f|-$et#OAzmvTtyZunUhqB2(&idxxvlwg1n!(&S2Agc@BXT$xM zJFZ&3CTF$%%FyV?QD>I_TgF~y5}CDRM?`W2czDxd2vB4zu-D1%>_>nrMF41;w}6CWd%8X~R8`Rbo+!LousGlI z$DZFit4lk#PJV@+CLRE&GA#@awTV1HK2N*PDUv)=_$Xs!JpLA%1vUYufE<8Xq9aI~ zSjWYGm1j+kTd5o#IiGY%b^gyj&U`?zTyT=Kk5m5sek z{l|Z(xNF*A`Nl?WlWJM0&M<1yU$3`7S|_?LST0Bsy_0$Bx0!yox$X4Iy~O*b?|Z+4 zfwm#{7ww3Ax8mj6bL$7z-Cr}i@^;jN$lN912=?_W=DR*G`kp;_qn-Fi2evN@&hZRqM_oqZ#tzLW zbaB89FiFdsb{Nwi9UDI|8x3BF*-oyZxDpN^jI_FAfjuXi?P?a6KPxdRMOEyp^KEw? zdOf!rZAP~ec*_FxDF*|)LwAjYI@s9u3`Ms>qPY;Iw#c4%-J_OS9>vQQbJ zABA2$xz2gRiuL!_o?4w6Z69g6L}$r@h}{vUOM{n5mZe2(Sn%5ErGVW3;Z^KO$0P6K zw#Mbe9XgV5qV?*}CvTpq?+4z>y4iNG;H_1q3VKl`^S-w5`@&BDn=aj!r%gr-mdh4% zeDO)zo)O{5PRI{gWx)Q8>f2U7VgASKWWC2$`II zS8@${< zLz<|O_@UxSYxq1XOJ(n@6F>;P7IrM;O+b{_ey9J;Yo$q)Z(zr`zn@|tO4lNtmHU4?Zb}j<+0=gQV zP0*)WGuE~q?)*`dOul!X~~{Fr*C z_();gvba@o<8hGqFDI~<&)pimDY_YdkNJvJpc=`P$-}p94cZ+YyE10q*5TC)mq-@S zJjhlcJs;`<-5rzmQ+Duof((c0u=(hUsN&GgE;fb%oa5BZj99@2nM_Jy&gj;)6LJHe zmS5>Qmw8rtVcFH!cY>e)_;4k!zS6a?4@9QtD(ozl+I+D5YdWl2WaMp@Y$JCXa-IVW zA9}(zOyta=L3sbN(ZBO@oEg_lSz)rzY`5ukm9FBn_yu=8)d!moc{fuqXxe$bd9q=o z{%OO_hR=0n)zuZxDuU~_cAc9%gS^SLH27qeYlX5{srbXqV=t!$qVy3L(QNDt`Wy7w zeEO`%G<+O87B{hNx^{jU>;`Hxx*2zjF(jB3uHpj|BS7h?K_<^RPTic$oBTNaLT3tb z6L+7iqS5Kb%u=paxJ-WEXp1GwLGEJjn(nm5F3Wt(;E33OT}`e;SL@!JiJUB&R7`_s z_iMkwq*xxYhq#H9Kxw7xvb_aM<<||-reO0FixG2@T4*9SNi^AL8e(2xGvoNe^^zyg z?@3Tj=tM+9y+Tn}CwMH6$7I3HB01Ak_50%r_{3Qp&@L z7BDvfyWjGEHfcJ~R^H3L+x;l<_1x#JMfBQ;z6Wzye5rt?9(GRgnfJZxz1{tw^GnA* zhfv4w4x!eqhS4lGSlIWoYJYL<&xF5a^@|2r+C*#;L&1&Y9$@D)4>Kxhk0@_Qd3Z+* z8Xl|TF;g=BbY$Pq)xMiu`t9h}^tNw3$>TlX5^9R29K{%KCv^&kK_5VE z1$?5X-~!!+Gm6Bbi$&|cGgsjieR@+!(D`ay1;9m>VvDO7_1?QoXF<0>cltnD2=!?=?&9HWGl(|XWH@it)`W!s%=(eG@xpu`4 z7S7f#>zyr}pE;j)wsQIET#6=_ay8^pSFbc_4^0tN8a~_>W3p_m@&6&^A6QA!%#f9OW(K<15<#5X3Xf4_DXCspUSkBz9b?Wj|`?9@L4w#x)+19%VFD4u0AC56o4Yo#U~p;Y@uq8av<7ioUH^^Q`)Do8SJtWY03s;# zxD_-$IhN=`8l=oIoB#%2Fd-FcI=g3hMR$5@Q0w*1?!km9Lmdy;IC?2DiTacAnzfD{ z&6;M^(Y{d5ktq}g?GAG>XP)z#WkX|@(y!>c(-&acHu2v|en%a-|b{3?BvyP?+I2&lzQ>{08Y!i&C192hrOvopaa(N zoYN7f&rbi`?)#YfzYDk=9JfFf_|E&Zvy;g@Ik;P%$~wo3AB#H{cROzPVeql77tg=I zWSad*{)C~|Y_mt7?Wr3*hT_OK@*sGorehueTM&>nrp=RcNxBS&z zv9NKVP24j*=sp>yQ;F)Q?G?fmDJl#w_h_LYnrpTC92Dh0u>f6xzqVaZ9cUxGm z(}>{|an^NihxWSe16U6Vir++$vZnY=k_!1%)cv3t`GJUke5@aX>B z-L%c`mu_)SHJGB#&7%QiUPS8M=g*(KN-RlTl-u(UQXk)TsTU0Bk0%-TjqZ7D39nif zwlp`;(Rv?`2np*ySiiMAyVR%>TkBe1Sofy(S+#xjqPoV`gu#XLN!Suri)7MZjoQm{ z!aC9Vw7Jx9Ua*xkq)VUp)1Ths)OUF}XA(1i7`zN-0HjcG5Ia!6aYi&AaF2OymK}z2#BV4SkQZ~Gq2O2`*4q>Z?L~`X!~f`#LpSEt^s;0#gDT|lqh=+bfqCG zlxhHApfDtUf^5zr)({;^TS(QVUZlcl7pZ$GT+#{r9ZU(52~USgVLxGu5Z1^;$T9d% zNSaouc|2_}^L!?F&H&T`pT_I4>?L4Ti^Zrt&-JoLtCyRPkB`XP+~cgvYX@s-%TZ*1h8g+JS0bcp!Q2iyhBbv3$r%3g&CyzF*tlop@++bN0IO zZpCw#)N|ji{aRSHyfu8}8LW-}#wK84+lpuF!Rzg#GlP^itHnogbj|JokG8D(J(cZ$ z`+r``Ez3^I&dK%rv%cZmV1o{maD{Cq3soV_8Z0%yw64#>*Z8{JhWD9Thu@2~LOh3F z0=H@Tnu*EHW1S;kMw=&7=9}S#glCMcTyMSyw}4J0gv0Tm___L-T{E;9*6h<+2ThV@ z-~2X^A9NEk4ttcenGwK)N(~H3P14M>%y*f38*CFlV*Es()pn0v?aS?$X}#UDs^wA3 zpO!5x@hyMbnmZr%M^4y+La{S|O6s@@V^L&t(ZSWp)M=f4j&+8auJNGqtV}I(;{KuA zlQifg=t}LOnQfD|#!rp?96L1;F}-(g5oi*;1eOEL=1(JkquMbC@slJcx(C~g-yw39 zO_jjYSE&8pOzXS2`B+I$e8zpU5m68UiH3=*Y-xEmnMo(2?yCWJ8J zH&P*`k#5C>Nj@qB#->(O$A@kky=nf@0k8aJ0sjRo@)P?AeBeIIJTu&nx(nS@&J3qM z`vl8NhFX3f+@TrrF7SfsG2W4c!_h}tk6|xhpI*uwDV+WNvOK=EaB`g5;Lx`6_pUSh z!Vbh9aM^!7_Qh6ml%eNZr5Ubwc%;nf^Tott_aEQszE4UFOx1jw|GlNkwY6n94f>Lo zV6!7+)oSGC^;>c_^hMJ7K&hGZd+w|CNOv^03|6_xp7H+C%y4knletIZnS)_H-@0~oFX)dP zCC+}*%|<@PwE(R5Ls%@qyzkw z`i16gc6rX<+`8OV9uoI{7k7t2t0$%qgBMS=%M*n(yAw7dW(f zykW)_BtW?0{*uCIB4#J2QV=L!EqyCLtw>eQD>myXWiApYQKS$nfC!ugSkbijw{)*O zO7Fd1fnKy8OCBeilQ>JdL|9R&V2EGGd(8XAJqX-XZ*hxw(SnmAiu98n&cM^y!K~Hl zvE7tYt?OwwWA}WI*X}1>m%7qjUpn=JXwURM$$sm-bvuRYH-(mrge~pDu z;D#(7ec0Mkaifr*y){knrY7;#i}}5!%HW>YH277N-1}dl&C)o@NEv58Cw3f(pn$1eqz~c z=4_1DkCJR>ClS}eJLl%cI|t+XntRB-m3=n`n@6@xj%fbsUO>cP&53i=A1q(~ytrL% zsV`Dl8o`Wa3{EL!a+)MT_!O8%ZD1R)@T_mZ?kt(Jm21uy2zCmmgnPx-k`alcY^5wu z<|U7p+X2qVo6=2^z2b+WWZ_29oG4c;0%#{BIYsY{qDX(Is>8TUt*|h)vat5DSz*^_ zALf8^N^qvR*1Cc`?s|eeGM$sHR>(47YwL!R-(Jj1Kpwq#^y`VF%RdsiIX8x>av14$?yjlB&$3+(Lq%Fa8s`HL@YRAt2N>*W$7g#n+OO;U1c< z;pJWHn^-l!%GG7e^6=`bjgg(!L(~~>h!0json{w`9xG~8R8vz^wvnUqv}7CqB3sGS z(soj@wM8!tOd>Y%uNB*i3+WbP9-P~ z%z;zUK$-(N4)6erc=mj?a8i6;zDs%3(BJ5sQMuu;(plCcFl2R--(V=P6deOi#kBvF za_aBo&Z*d`g)?EA-P$xT648&@Nfc3?8TIVF{KX=sR3cj-8<#-EG~s2Q1$Qf;0E%KQ zVRf-)*icSA$Ch`OH^DO({1YA(Z$BLJF8|5A{hSW>kFN_8F<7^I%^?}*X z>|=4c!B}5bV2qvYy>udpacHWJ1@ermG)b*nGK`yYKt$oK3m*zg=6?AsL305XX)0cgglV z*^{{Y;r3-~zlR1ol*=yR#Z#WGjepPQy!sfIf_t0vE;Y?HtNQ!uqP&WKotx)^7?;f# z2en5}ug}|fa-CU}%>t;?MuQgSBvN;FWB*K}W7(2|g3nGVR}f%O(SEo4vQL#DYJBw)heWZkDMiW%nxB+CO$+u=(-3aF7LsUOT zB@50CJf`N|}-uqP>Dg{9;}#uZkNA&@K+KH?V#(by-_k zrtCrX4(|V-H)C;+1S-F#XQW71tX4eJ`z(JeQ%EDk&x8ho>pVN|MJ|<_%1P%ad6)SC z!abs&l1K6Z#RL5*!?niECKNNdRff%|E!uH|^B$Lju4s>qp36P+J)+#E>|};}NaBI& zJl)437sgMHoP?dfcKbjw7Jx|I&ne0JoFn*c(fSJHsCUudV2x<|_L#w#LpzUcmakm4 z;HCWry&MV$bhU4`rlKey`%y+x`lnBCGf(7v%QG!HR(7*3V%m6cRbagl-*725<&Ks2y|-J)A*eRMH>P`|0&`21A#*i6!T@@OBGD z;#cBpqOXE%-XOb)ahcje8pU72QZZW8Q{)+7R|kexf>86$8ouW4d_2e=vK#J#M&n5& zE#*0Vmid>R%CY9{=BfGB{Ca`C@R)E!@JNux|H0qNZ{&UB74UL-J=`v?J3mk8C%P&! z5nmKPmqbf$iSLX0g(%^Ff*1Vvywf}>Z<2e4C+1z?hH#xZ_t?Sgf9x@iA8(~#Ml>V6 zrhphMQHhLAOwXt{n-5zqvhB3jcjmeiycYWW_TA_E%;TBEQB?%_`#{{!>gNVmo}Ybp z?)p`aN8ERxzgT9Cre~)bXE5?l*AMDk(L3#Td$r+qT#P*C&yIDQu`AO<_PUyxh`9@p z#uK+&6HAQqbTh-!c72FRWv87@f10WI$*Q?A#Kl}!U|kKuRMEUu4N-%O(*sw#w3=n= zL3yu8DtP;hZJ%Au13*|(mGt(>=wpY(hIh|%l1gnleok>PDgi^C;_4SLdE%wRyzOy{A_{7zJNXLoz|-k#gNHT`Rc zQzydb9z$igIx3$#A#4|akvNKn1cAImoC(%h)&-_5!<0TpMN;=u&QQw8-sEB8AA&I< zjj)?IO1eZjPi>@PX`2Abi5tlo5A^fMKQJbg0ZoFc;7<`Az)Ua&eHY`6^~1j)N-2+M zMU2C&N{%z{Hs4feA!3PWBC60>2o*f$KLXBnf)mbp$m!**;cntl`1L#+UN+}9`wi;_ zO9%v}@wk_`RooZcqrmC!_6b zqxpWTJR5fhnM<8poBIjRP2PXKg4{ul#cB;N83YjWzNS3BaP9OJpBsG-VqeFnZ}?o7 z_T_zIDk&@K-^4&CG2JY0!H(5OHv4Z4-BPvwd-U3{tKP{r0_8jAD#ZQqdu^BsSkdlp zE3#e#vl~Tbb2i~;OZml4nD#7VoiW}Gv~a=Vm5ZN-wg&ujJ8Qkt=!SGXn@Vhl`OH9i z+N(DHAb(1Gb319%>yY=unPJ5RwFSMi8gsn0Akw(g-o|Ul-!*tN*g5z~fSccYk2nXd z=_#p#<^!!5t8HIa_3@Y0kNSL*pIN^dl^dFUdZWey=N3aRVXJ9I!g3|stkL$p^N1VR zL*Fgj@q^_Fm6zC{NS+NV0Pc$9+xg`=Yx)nj_fW~-~7p8*7TXRHGTjTPY|NGR$R`UA#e z#wEHV^&DvfJ`}qN9fy312!lU@^WkgZ0k9TmIwT4b1UUt9hwVhbG57H(@-G^LmCub5 z*oikv#v~Bwb;(6ZjaW~dC|V(k2A+!?!4keVcbs*Ad6&MGCZ=KOWef%T3-=fQwV*_x z5ZVeA!YsiGK_0(~Kg*xs-{V*C-2^d$2Eh*Dq%cloDvpvIl413d6r%=mW1?DS@z;uE z<80e+x5{Co<9cVN+ef!kF3;_js(wL-D#Ftg3KRj#E;_{ zh`fC@XF?&K)%Ye^mJ%Uz0wc zN?(+g^2zSI@xSyoGffv&Zcyxa%kSQTKMVQ;clZ>zezQAnvEA52K^K6iqfp3Le3Q>_ zc-FOd;N+=fO6tR`#YM}j4s|4sqoFwJUU7l3qiwfqvG<;Uj-b=Qu|XI7*1Nmf{MN^D z+EGcb~ZS7^!F8yUY~ibYlH1(kfbM!&)FEbZtw(q-}f|i zW!l@Bom7Sk9@AJjUl>eh@l5TQ`Jk%jafh~(H`w$ewDWo;}E;bRbOS}Q(vkCDw z05iGd?~od|HXa9QL@8Wq0D)P4^zO5VVz^`V;8VpI794K_GO?t zeB`X-`tU~hg9454wn!g};OjVySeu45O!1f(^iiT%$6Rr+~^L#=6EX z&+)Cx8TZ4Up`KB0k8I(}7lirY)DnZVil^BRzCV8c$~BFUrN~VEIQjNq@~QVrzrU!* z&+p)^w_6tSGdg+gn{{W`NTS^q(}J$JV{H5lFYv?hyS2{;tD0g<6MpvPw0%iTf0Z8p zr8uvoY+binr;28wKWy{PZLxQrceq!an}KtmU8_}}T2B=$9b10V~8Mo?cZCoRzbxoJg(CExdxHt8zeC22M67!RbV|#KKT;!0C$Dpg{Vgo zD0fmC8-7y3jUE~j^)qD*(HYJ;S_p9|CKquSE`~pVD-ctN&xkb$e|Qcw7s7;sV43ih z$bOU@qlY69%z=%ZoVb&K#P7iU!#)HOGGp=0ge|0vWH4ohf}!QnMrga~rx^vzh3p;< zm)|6~BMK3(6mJnl2#@ofc@;o4;w@9busfr=}*Q$8qm8Kue#w?CmN85Qj z?RDMY0rgh+?)F*eg>?B(t;^NZ+1IizZ+o)nNz3D)#D^&#(n%Tl??+!fN?e!pHT6aD z-`*?O9K$;AHA_#d?pW8h4z_xFS!?*Nz$7;xYlNXb?;@sd2G{eWYG0v$&PYbh``{Gy zhrgfZ@&~HWg9T7J8=_(%2B=9{}D;J=VoThm`qkc6nmfAuXd_ zhr3V5_N{7Zuko)eEB{u0zkIghcGb_?iKdutpD|m|KfEiiL>X%yV^4K$cK7vo<2vnd z)T+Ydo^rpK$vH=Pg4qmCpMEfO0wC%6)V`=fRNb!@Hau!Y^<5hCm|F=gL7yfLQvWeG z@eD!Memj z^UDO6MO5)Wkw!=seC4iT+pu;3G{gzU0j3*Ek4@k-a4vDTad!c_fxqktpwIlq;<7&h z?94-)eVp~2E9^MdJ7y(gBg38Xh=F6R;?(oh!t>%A(ggWBJ-V`4U#;>nK4F?}cFr>1 z=9GP*<0h91w={Ph;H`P<{Ke{^UL!GnGQV!$_oMH0ULAhj`))uU=${Uqg)f?+&Z8QBPGp@*|bc$4NoMPqec-|$|#nL&& z{+jhpGrEzP;($n(9ZzyW&dx6xU(ttd_iOB|h1S;Bo^Qx%z1q_RM4D#mZa}WVMUbp% z1a6xCgozQH?yv!1~3X04*-kh<{}_;eft--r8(l>^x!gD`W*74Q|^ zkKk5_ExZL0jdlUJlm>W9JREle(}$iy*JI*wZwS4lCzRvVN?H%?1U;XAj~+?COJBv{ zGJz_<&f`AiZx);soaCc<6P!r)eO5Gclo7&IvHXE*@RZHwOtR^0UDhsU5#ttf39AG+ zcR4UoT*tk@#RHvXBj*SwngijuaYi_q+@HK{{8xfdfkfaUSPJwjS4DG@2zjNV(;(4k zk?9|`gL#?7faO`>b~$O+=djIbmvf0d!6c5e5b~}&=a1}5{5zBPJsG>deJVIxkeRa^ zs24pSsF}row)EUUq)VRKzYkm*5x?wsBsxMI`Yf=(E6@dDbHvC{^p4yJW{$0I*QIcfgqdbp9<_O8Yh@>~Uv6Jw-(k1bI??on>@W2k z*muaY;qKoJKQ`yC%iWUiU0Cq@WZB)?6|Haj;nOD}{sc>|Txo6*>D=M{E07T^3pDik z=yK62*04_KPThgLGk0t3ec#4Tv(^Jm@P>xk@#@tztLiga!~1Vf(O|zwS9qy)<4kK?*OtN9i6M;< z*cd^;Mw7NN-tlrI^NOn~3zJgQy{2|1CaO=0I0=_uz`R41h`g zPYVKa+ZHqGm}}V&IVnKjFv5-C_HjJfJ*+(}Fe{6RV+FG0Y-hGNCy8y%wr723hB2Qq zXP5-m3f5xQX_l1L!1x5H`L{AY0$EroOly{kb(gIRBoq1bF7Q(Y)k1eMQo0kkVLAa7 z18%rowaa*oX^5GJ#c`{>Haxp!_PUN7r*5ZNCr`&!mO0Wv+~Ub+4QT~7>FYk+OFx$t z@%{OC|E$v=>2I4~i{Hg%M^{%&L{sKeBW~P~`%56pq)SPQ+85pl6#6pU9@s80ZWD$O z-|O@ZzG_VUr&kb=buTR_by51j*RtY;^}7Z)f}+S@MGIBdme1`q&V#Po+}C?9@{06K zc01&tRv!@M;~q{QYZI3u3&OK~GPPgseQo;w{^z5=$ZEru%>EZMw-Bu~zU;3VP;mW) zA-luxh3#4Z_e*z4w6xV9;7$Qkj4x9y0|}j$&AD~ItG1M{EL~B0vf^Cb)%K&qS@RJX z1+!E_Q|X&~+q|_mbX@I_W;bIqV#zo2QrXJ)@ZOT^5HIIyN0GhvT0I+lYuDAp)UIt% zwuW?v4Mj~XnR5cWBR}K6)4;qk$&m7~QI)Ba8PV*%>8O#wz*PQ2q~aZ6Dd<}%TS#jN zKG?HJB5YK*TIZ;Ci`GHsCg>-)4|)QwK?I`sKu2;F$mcG^_TygQ{}3(^%}Jf4Ua~*s zI%PXWPQ6dfr>>y=q4m*Sn4PRwoEh$aybRv|>qQm2l0|2YFfTAcOfRO8$pyX-{)}@B zF=K>&g%QKt$f{*ixVgaeVT{+nE9Z%LwcG@566Y=ZEDOb4%o+>gvOm5?(+b{A8uEos^Si!^2TpBfBsiiApD+_gZ+LWf1NR$-1@84Tgw6S6Kc89jNT%_F!d-ZNINoiwy&~n zZ&P^v(K^F=O=ChEr`vPj>*(_7@AF5Y-!Sf!K#oM5t2m+ZGYM7~sBP3t6O?MT;-`cz z2;^8Y?g4yr9pV@kjgE&0L2$Z3I@Q{b+8sLgbbmvP;3tu*(AO}(u(3df`fJ=F`~?D( zw4B^e*-p&@o(UF>K$FrAQm<0;s7Glb^i7NnOiLD@O<|9*;#oIvp6K0v_T^4w&A670l1vWu8hSmox z(hSEqe-XRJ@*DmuOwF49vMhU7-v3y-3a}`*u1gFPZ`X7W-5rA6-EsBW-QDf=+TDTe zwe#BDfe9v}SfGH2AkzIW@Ap6Ryv#7gFlW7Muf6s@=VU*4@NmRE=Ekin{FVMUBA%W} z-%_zd{Kr4LF4@|t^Qo@Rou9M~Z26(_`g$X3xrdkdZp40)b!7VD(#%PznimxhVs3A` zS#`U|!>g~Jekm(x<}#9RYF_QxCqNAA6mdFIirE;KU&p^*dfoZ4_K>Ic5H6*P&Uy8I z-^&w;{h#c6GBWX>XWd?XOPTrM@s}w%j^gJ|6X|!x8@{(9+toka>`BY_Ey!lC8oZ9x zgst#Rv94ENBTu=wRV*uv&P~qhlb-gW@Lj;WHK{qDsBZ^;RabUb>P5l46^ku(53L>X zDKadIj%*PT7``@SNx(s`{a6R>82R40x^(H!if`Jlo6|}^_4%y$@-Ud$)1Nc6F*P$!w>&ZnmUd>s+}1SR7-?K;2r;B!{Ht}Vbb;7yMy;KyNmb9+9L0P) zqt07@NZ$`A>TcLz_}d_2&$`ZVQ#u(J8}}Jo7^fg2HP9>cmvqhaN%~`kFUFzf4VL}Z zX7*6`FwgGZll)EvObI?7ni*a@@~^1kXj`pawY*~o$Ck$KjHBbknBAdOj$~#{Stqxzh1w$o+ATav#rsIOX=qYYnbcT{YcbmeTLn3?kRwD~f1(r)}qsPuu6T=9>>` z^sAmD?pZ{ez*-(BwGo7@>R{f~w4CJriI)4S+g^98ANF`jrs?v3))Z1p_1hh1d~O7e z2|W}(I&wfvWbM9n&(sy-#)Y@`yev&{J)GYvP5Vasq9933n)>Y2bC*{$l83zW{}h-} zH}7uQ6}NYSo839+WXxantxfhd9nttfgUC9$QOUutyh|-x)t9MpGS4b=i86oN_vsl| zKOg=W@GyI7s3y+Tdv za?l(9e|>s+9&)(bwwb++8?@=78{3|cskUZ*~!cGn0RRKO7d{9JVBxQ%sw*6AO2DeR8tGR*}y zzNlVi;QKkr(JyT;PQDoQl6<}IP4&AMANdULybEO(`8DxxyHil@nBe+N8q1q3Zq&a1 z+_=_}wxA_mU(Ll*8r500wsLII(cIPFW`0@z>F$R)ADgD>u(2OeI@&p&SR|e|gxQCC zMdEz126+UZ58f0!A?TL>bnis_Bg0jGu4<(7jq<{ReYyGBxmmljFpc{A>mReRJMp*D znU%ks+RJZ{hxne_KIX-aubz#3m-#*PFYtTl+tNGHW1yptZ8@qR4Gmqj?$STp9qNOM zR>Zmqvd69iT^Gm%De(|grEu~8y z8nA=zp1zqe)YKTYu)obkaJ>a{V^g4Mws9=9$O-*L-6gG2(^)N->WjyPD`RF4F|)k}~rI^Eh*F^9GaN)WX;koYKs=$XH>toBlEVG<`6; zSxap195*~Bc$t0O{lfz11V0Hq8{RA8Xyl#oFm~U0BV@>E*J6b2S2yODX z{-xSg(f7hy1>E=GO-0-p*~!u;Io&_ie{FeMl+Zk(_LIbyb3dwnJS|)1R>{864YOQz zAM6tlPz$?0MZ|d2K3AtaE;8z@f1)w{G$ zPqMoHDycfG+NdGjcLvsvYFsCC!{azVm9s`!#1NgRBop2v%}MKueX9tI(4>rD2-Y*{f#qpxnz2i5NZeF@Q;!fD@3D?hD z*?(pBwJ~=Bp3VI_r1CnS?Aa~)Y~x;SI&}Ener(%$Esrsul}a0C;Azq9HMVR@aD*gaX;#}Zv3dRpBYJo1Z-p9a{X|JlEMI{*%+a_*#w(C{@cZM%}a?8v8m9^FF9EStHM<>^P z)~HF74oyxrx>hg0R!DfBpNFHa{$I9<;_vDw#Vhk}XT3>l{GoGdOsd<*(O-sscP%tl z`N+301F%{^SH}*o1iy`elR`F!#fA68K1DnII(w`zJr^60HLjnk^rh1Z)$H;5s^Yp#a9oaQGuqeMDTj;WfPIH8!m71AHl?BZc3sy+drb2cnKhxN z)f=RLrFh}hg)5wo=M zgjP#hFKcnAargSNxIIyUVUEBP-lF}yW(JX5m6vBvPkQbD^mKyHgPJETUSGfp!SWK5 z^8n%qAE3)OH^BV8zk^Rj2FLl-yIViF?vZFipt~)T_mL%)Ecj9I^~tBFsZ&xWCC_=? z<8^Yf`EC7=ri{Ye?`7{~Z@6xzLa#HybE2H$_`2ijs_G=yii$iR9O|29UujT@XUQ3| zCshxNL-PB4ADr3z%f0lHFU48?axFy%DksR^lO|!icCKlv?Y#RkuO_}n{ig+n1fKQp z=kwityqVU_uvK~=GB{B8+USfZB6Rksk#!z7lGY4BTEW@q0t@o@=t&J?- zOclnB@H&?3BDK3T-PFsZ{$gLjPblXP@zaEULVK~6*iQ;nch!v2dgw_5ZEOHHrN89_ zJo!)dWJhCn(Ou^_V|!&0%>xbnbrlTA2^&(^6M{WtN6F_)x zv(;$F(ecg$inQO>zyJ5;mc)BcZ$2wZKK98o`%b~gsu^w#s0qSZT^ozuW1eq^;3pC9 zV*KOI)><9$#y`hCPBVb$SW{FqFxMk1A@Pk&@A{?W2na_UUH zlpa}5c)JGAju;a&E4F)Viu}G-O@K zX7dIYrj$2zzM<$t|0zh?wZ?~*IgW9jEq#XjrTXph9pk;)y|rbaZobfzx+1^sJg(|U zSxoVdf^WYP^Yy=e{faJ}R6M=xRHdi$B)1~fF!q2b=t$FKYp%o3^SM`3Z?pGLFWT#@ z$9#8#qrNTJ@&@x-%hZ(kjdh~cgqJcye#ou9Y@=&AR)px}a?aV=rNFtp>l<0I+jYfc z)jTqT4(C|mPpFd$?Z2qJ)G_a}+_k>2&9+O9P{&dG2ip#7UCSNQG~+P+J@k4{lZu58 z{3dP#`-ai5+n8o-UG87Lt5{dynV(xuSr6L6?Q85S?fdOv_CvM_)-K?c z0>gIwLG5+TMafs3E|`RTK1Ya?%G9lpd#^BTFlAee_W2%1ynFiJ3i=w_Fd{FqXY`Ng z(J?Jzo=2aGN{=AJjs|w|YN0n1&&xOGWV~&L`#5ho zUlm-`Bv+PoJZ;Da|97`iuB5bmm-E5vi|u>WuYk&Ew@VDI>tkPzb({Pno5fgSN7O2d z(uZ#g5`71{`9UwT!LWRlF*HQ_iVxkFr9toBf!Of3NsM2cgyvFv z^;gY%%q)6qu5bHluW;x+Zo7xMw|2Zlb^n#+Px!V?jdH_g-F3}ywNY9tCJGW%(g|sS z+FRG!(84^#s&Ma#^C-cuUEs3d2O;glwuHBf2#zd?&_>w8SA|Xwy5qaf;i~Pfd{ln% z$KX#hULSnE;RW;Z>WgL=@AHY*pRRs-J!#dO^_d|h_2lVlgI8$Syjr=nr8+HY7sbZb zqN87i$AyLkW%-Eqf3=Niql-{{IlIZ{J#S-E0^ZgBU{Al9-7&vGv9V&ilLfQI2MXi$ zfwoGoTY){pd?E&fuMV;Jw{>4W|tWA7k%%YIq-`-ZTaW^Y2ja7vWEUx zjrF@fI*%iI2+Ist?SfBXfKN!rFen#Kzd)ag8=rf6WkTnr|KrH{Kte!^0eH z9j6@g9e>!z+D=()=B-AJeunmq<_|b~moX#7tnI5^q>aJqJZ580^FZ4a_gh~3{L%w0 zA$7v2h}1~GsFbLVQGZ3Y4xbQ|<#Ae@uc}*hF3;&pt<>cykCLljaWC2=?t8T7K}&tJ}Y;tp=pGxV*lkQ#obit=XW`=YRjPt$Y-o}!l zoy4~!ZSq|;Z_5@JR_1liDg4$d>sRKUtk2mybN~5OS<<-L->o^dMC@;1ZC5>3p>KAi z?=0U7KF_@qz3O?Ma@@0yH+pEy+zVBS>&)tF*pu;nadvTbN!_wK<#gpARTpY%oLRSM zRcm@XAFPQrRGFSwrdjV>H(1)3_COIl(M%A-xZ9M4m?4+D-l!QT%4Y+@qVvDrkc?wp{ZSV}kCSdZD^-q3on=uiGv3q1siKiI-$5UCyZZcww4!M6*xV z(jb~Xn<;Bu8*NuQ;vD{tadyeBvo*E4S^Am28;W$DwcFIY#EbkHu97)Uf23;2u~Zrr zNH<|#vKf4WI7_`lTcg`;*kdX+H@BMXdPjTrh3-$>eci2&65A;2UW?M)&(sH%;bHot zy6(Em+H2Yq+8V7r-NoP)A>5dE@@lYq3wFZ=#>YU*;d}$NC0(IUFkUX3a~s zg(}{4di9Wsb)}z6_Ltl&X;WIO%)NY9#kQ&@PA6S66#FP={+2}O!;Lr4lULUqY0??T z=nrYXs2$=8?iD?T_$eo3N1Z)u{;G1ROs?>+Tv;Wn8Sa$gveM10yiH`&zWfPkhW41j zVt#1pW?Nuy;27aZv8UT#+Wxg(H1{yw(Q~?q>QBN6u7qhxZz2_hR+X(NlNY)zcVpcg zZU<#)GB3CFZcg%(@(1WM+)o@LThR^K0?sIgs6T2i>S<$~*=k*Ho8lPbzR`pA{O-}q zW3l^9`vBWc3pxx9)w&a!p6V#^8ef;~PA8G~iPNg1s)59AvNN5>>l{wn$T?FzE=^RcopX zHa;|ev2Axx^_u4U*q;ij9Wpy?dc>y4x>53|^zgrfzI!~-dC+s6ql^E@d6aQIebXoR z_e0)vdtpx8^{DQH(GOCeetom{YkB^wnum04eF!G!PseVd9U^W-Z;j<@$JY5+yLar| z$fCfF9#8bAn9i<4%Wmg)`eFOt{99Vq$E;T0u&d|ydq2GL`xp1FT<%&%#0qQmN!DT5 zp|q`UJKw%Osa}B|Ep3@bU+oC~J!zGnaAGPSm2@x6_&Ggy?2lPL0(130fBou+m0**d z1!XnuC;rm5H}V#LTSJG|W3%TnuQ=~hUSXc;_H^?z{U_-xez28`3rPTXm==UVTv-A~qGw+{3y_Dpt3)*Fmqm3@^lZoTE#6(3b|$nnf3PAld}12li>*6LTFqHll;e;IqRHn3bV zH#Y~GatsMNt#*RCg%~DyaHY%+`UW|Oc&4NjYI!r+9#=QldoK5|Mp>b2sM}q)BDuS= zNVN=3?ix-Km#7bDHyLi4Cc$+#+aEYe-LpJ+&yJp_Jnp*JcNnlbD{s23KceN-?M03s zjULBSWF%2vbyvAo`AC_jawfk}Zv)V7(0PPUe3chM%b&K@ASV=#{8ifw45bvA59sSb+96>d~ zNg;oPt_Xb-(kQ5-kB4Q4n5*=wzFg2JCoiiqL-ob$Q`Ea2ub5|HPih`GJ=*^4aH=ND zspub<1I!!k7RyohI^Gq2Zowr+F9B_mYc6fIphZRig-)YT)*A;)ZE5)2oA_x zuO(j1JeBTatbL7Hn*Bm2b};lqZRK`(6WJse!Rbp?y~-mMF_o@WJ!@V%Uy%hU&Z<1f zdDH@WGULH!ury}4xrmgwOgPHhxuwiTYBbr72vR*&&QuD@%?f`-hCEsRr-D^Z!+gWR z)B@%O`<{;!r%9>mp@;!J3}cO((Fye0w86B_IKq&ui_q#dQEKcLA@0Mvbbqiv(ZBjg z#VOaz6Wl!9{&0(So9foat()5gxBG6C{7?CLXy968J$f>mz{{n4^%d=SeH~+GbAqL@ z?X!KEV}bit_f_so!DxqU_0YNK0ls;!+ostm#S1;S<4hW*qN2!nLPw%jNtTltR4Sdz zjOJyXkKb*ZY{Omu*KOI+1uLFY_n|7F%xdCd8p|RW0Jwwa7;g3 zzX%oU8~PRc)#zntY`SY6jJ*7r4hH0Ux3|~R*KjSBJ8L4! zo)>2Qy!PWz*1NO`?~{}JzxX@x+0)O@X1;O#d^CGt(Sn)_%30hQ&1_>A+j!4+e!d|| z5qU8gapkq8xW>`DLP@`c_C~s{Y>6^bw#G?bHMhKbNm)VnpRqqSeP5j2GiPAlu!3Ht zWmUYa9`T5ID>TqF)ip9KK!z~WG}x4EY-0GT^;1{zZJBt2QEYOZ?ewrJrD9R}%(7!; zSIZ|=eyP6W+`{dPq8GWG&SZD;E2Ng%A^JzA0!s}#P$%0uS;OEp4AE|uLWTQm2WBvJ zk$9_2#43^XT~44Ypj}ONjhFKq7qi=I`9$S9)iYu-nN5DCRE$46i8XO%t`Rqi9mVvg z2T?CcUt+0Brn;a^RgO|VP*SQGm4Yb4D|*n&nBH6fR(kYN57PL;uUG2_>rWWg8={P@ z&?zueFW1#*cBsolnOKLna*vqZ^q}3A-PGKC&pg7i&nmN3 z*`ghHQK4?_)y~_+=bl%F`$S8Eb~D#smFQ9r4pvpMYvGl=ZrKT6JwJ_pHz#@h>p^eQ zQ@y`5$Z1>ntg@GEJTZ%%BW7qNb3=#GyG1}{Nc#vXDm8L*cz?`N8|J>mR7Z1{???9{ zsuZVW8BY4DSEX-?hX2a>+2`l1{8a^6#nI*Os<*pf6MA$NhtoINq5M*@lX{wFs-~@G zgZibkQHV<{eI(9nqfcB@yQ+>$Ms@hm*GgaP1{#;&PQBOHhHG~*Jz94Us z&&h}6268DbcCwuKOvDpsRX>!y(CJDm?#VC99g0}RFU5XkD^+h|Hkm|K&|X;GG83QI zMcYz0O7CmfW_Sj3wWrZ)tVTaUbL2NGHIJlpp*}wW`S3(~2=$%}B=-` zb!<1T5&xGkS-c_jRX@_-RgNJ~fSGGJ$%y&Bzchi#M57nf{(hMGcvwZbym zGS@N>mroXxwU(_t)Z9Y%#UA%OYdmjwao&Bs#<^!%hU$llB;88Bz{$08Vrf?4fS;D{ z&%aLkeE5A#%Ijp8l=##+pGRdK%DY^A0&B)btIp8%#XkB;7K2BgPh8-hP({Rnh&|z@ zA!4A#C)lym)J*qHa_8sLa>7+EchOe2EKe<-Qh2FgRlzc>D`YHdT^Unz&e_%b(uaCO zU8j36TbN$V8hQ_Xjv}ZXwGl`rxq0x5&3BnkdVZEr{`? ziSEZ(xb4VumrMQC6+mq@DuvSw*9?n|`;7}x8(eCbp#MYHK%1-XBnjem{%>wJTSymE z%gEZqdevp+M=(#U!mcQncU9cN`}S5wsz$0ls#=k+Nj0rtHn8V8QTRj1hl6rSeOp7L zbM~jc#&FlT+>~va2~E|@oM#?_xz?olnkmz0LWhg5{s8(J?qgMliQ+V&C2!|faa*`h zT)enJ++OYi7r_7IbA|2VF=?2Z10r8&=jk5my69~NnX#QwVWLfhxtTcvO6{asZy9On zVxg_0tW9kPY}K}V_Ii#8bnM4?M0+ O${o^Qh+x&-EVD-Fw*^S!U?}l>AtUxGY=j zbglATX{VyN{3khoWTk!Skv8|E)5qY?fnTO)-ThJd%cFF4rMGjcTd`_4b3|0=^Ucu? ztC!^4)xTT7;DBy^qR$o2K8{}2)}}!QO1E6SK^V!#kba6gu4zuX>hYD+D?%!!Rs>eI zsp?XlU%k1e6Z~{9m$9yOWPROq@_0oztE{Ry2aWR znk(vJDMVTfz3j^$W*0Cm=wdRG3@3J}w5mL)sR-o~MX{oocitzEDEuhKZo>|&W}IfMSVjh2U&5tblCuSbY3f+&M0qHwv$X5Xo76K;2$59(~`W-huw@GUF># zFGR8$eibhLBt>@IpV^;qEH3?)=i3cm3dcTBei_P)t`= zs~B<%RX`uaYSpiWRZ=5OOD&@_=x*s=>HPE-y&t;D7VE?GgLN0Rp_=8=3}Gragqct6 zBEyK*s!Phr3RmpARw^4N8{zudb-rt;Ozw8tZMxzwtcWD zAFOeCQyMG9NG2&?G)jM9wXRyyT(OS0O<)8aMsp&&iYcV)(pM-CaNYxQ4ygw(Mi8My zM?xU-2o0j?N@^KBooUHtp~I>--(Da^>^6^BQ zypwUd@wVZR;fTIcw^b)<$7&9!Bh{;C=^ruNgE(rngV*Phq)(&y{18#)<-O);i0v!8jfMPrS#*4V~j-szw2T|KUO z{EvOwc=>q+dCm76^ozy2xBzpE%!jBAnJ& z*HmRy_O6^$d9SiZRdLmU>en?M&N|nFGKb=eGK)M-?`AvjKLv+$Rh_2M>Xzxd815UF znMRqGquTe}P^53Ji`DvRj;LQ_9JdGu!R0Qjz|6qx3n!wFYP<5YvVn4=GDgWLOB4+h zdDwYAN#0&wAKEBGeo3AuAEg+f_yo<gQt&wYbtCOX+QY#U2fA|aBY1Wy2MLW^e z{i;>!(zMI8%Iydk6rZG}C;J}9mjai3_GUP)ciHQGZnPV23EuB%2z z)>&g0Q*X1(qO`8FF0ysDAG5nV<~fErM0f0eUlLeypyXcZow9`T;tH;6VAb~OoSM1L?_J)=Z1VP)ov$XlP&cWQ zR4JUzV0so^huOpIVpnqY`7C}dZx){MnfwR-2+r4wBC8J2gkVK4wZ>U9N?jpEOOwz8 z5XE1^Oq`eW1GJN1N`)FLEG<&HswS&8 zs{TYbQ(MwV4TZ8fL}$_M86)G%1T%w~avyWB`%!zMOWq%%oPjA{su!)V_quO7ki7R#P{g0au zQScP5@;iAO7@;$Gp#eXEpUn5c9&o@&oYL;pSYYH_^TAQ|~c7xVi z+fQrK-qvhH7hsZliTb1Tr}RbqB>n>otrZW50od!Jp4e4fBc_UB(nG10Izqieousa< z>8jbMIij&?Yp}YdkCsCJ_$|$5&3R-xo|<;(y2w)RM~`xn`ifevd8?kJZlSiT|B^f< zXE9E=$g$i^CW*FFjfwfHuZk@BGq(cSd)Hg8T36onj!TGZSJ%<-yELfc?UOZjd+GMc zEnXgtbGNDTp7NyV`N+4o3ipr+(s^fJIQ`zXS3JXrECM%%ARDpGoNTLW)l5?4xr1Z z66!6LL(QP>Qpc%8st2{2I!`^L&QX`CLDVWLjPjzCR0mvpQZ{M;G<6+nGbN*)=~i?U zE(&HBok3^Q74%EwDbMKFbS~}B#4zCu&v-LS=>pn-xuu(#y$r+pvLS3ZyOSM`Xm*56 z!fM&~STl6$W^Ot+j+@5~fnKeJ&%1(ag0+(xLxD8r4zusrw(Lx{oT=`zd9mEx~4Y}UjaPBJikSpah{CTb+U(CJXTJmaq2Y0w5+&XR!*O{BoZ35O` zabHlYO2Irw2T&NzpWQrYAw z0CjWNiMSO771M?FM^?RuIl;s+v5W;gb(p?N@1pa89V3%PH$w$Fg82*C*&b-0F_@V+ zmAS_pW>T5ucuj5QD07*4%-q5K^MSCb%vL6aS%Le`j4G=DCe+$ev=?u@){B*!j-7a!%X{_9(lZ4PXxgS5w#ncr2gofHf4%IC_9% zia7^Ahff8IPZJF2Hs36y3&ny}94mYmR$|W(Poaw6&MSli=*cKTmxL9-%w^$&;30~@NGq|fI8R(H&J|CJ55%wH5wW&7QuGxYfQ<^#|D_QL zF5)*#*W;_$KJ02#`XAF)dJQrcff`GRR4}z24wxI* z-5S_!8;PN`P@QurxN z$Z7vp4p8+`)gd|%e-quvon#lXkW^4d$Q@)yDuEnAWg(Ln5m&}j*;FcZ6j^;PwV%F; z#okuZNi+d|3SsIpBbk;M^^?pkrj+^2lrhCjEA|HamVL-xWt(yp>=4eu*|{HV4%-}l zz<7-GVs;dmVg+u?fVMOykab}rSqDqv(6Tn%cbI+7?qIJ23rE2sBiT;imgaaxIQs{y zLPmFlIRIpBWmYnam_L}sj3<=%AaK`e+%p(QB918b4zr25g3q@W2z|qpFvI`Dc0at^ z5nyN}Th11-hrvlz+)wD}`iNbpfs*UM!$&vv!EBg@xgF4eq*eiFbG}7%@GwB3blleP|zC0MnB=9uo@ZJ59m4c8;ZGzfOEh; zFT^~t0PK<~Dy4X=F7^)d?{|@%&*?WMj*$-G7Kw06@%q3mP zlSByd330BQicys*>%hhPrRc5fp?nADx0WhFHH$cg9C{~thI~Lap(aqTs7lHgQD;59 zlxDzHL3BO(9U|F9Y5{c#v8yL?^>{=_Cweq3V>C=Z<}TyMwqv)lRz#Rv+%t~HOvN)? z9(S8-%eCN+vwyQ;K#l`>eJMWc1>oQx#)ki_FFT7J0Gy1(tk~iIMVh=kYh zb0WJ8M>Otfh$z_xoYjE6#azO(w}AKjSUnKdiT&+5G=$PBXN%cG+(FLFkK&)<;w^L+ z1`AUJZ*WXg;cu|iN+4yK&_d`V%obWgLHP-t1XkdMaY7qG0VeYXvIgKeyM&p-5g`ry zbXeFg_=tCe2r&x0GhCF!FTzdXAK^Tr+BEb&PlL`LD~uBA3XQ;M4TTAUS~x3=7nTU~ z;J@7xE($6!Ply*sfU}l}>&02X;w;2w9d*JEIdQa4xUVt&^=buREV zQ{5VlLVfi(bvmk#&4Jl3_-s*p5AGVy-!04;M2J!J7BJK=@?UB+H4G!)gT4!;QAsyt z#^O6)z}#k9vra67@mauhU{29(=rm}SA=GnnIhlsJL)of)@KhAy-CJcEj(f`bssXBr zst6)gwTO5_xR61loVr1VQ3h%v)s5;559uxT>a9z)!*u}Ej-Fma7eVQS!SU(OJOdlm zV_9|~c;poO3r?gF5u+F9&duaFsF?y*j*RI&xMmU%G6^Hxi){>avCv=h*z=5@EyDOm z<1=4op5Qa@1Eb8uXm17Tnqti35YO5no(;lpVZc@xZZ}~hF!ndZ$^u%>i1^Rn(`%sF z@8PwH;Gy4_-+b4N?G2^m#HJulzGh_jYrnsj#Q$RFH2l>k@EJzndArylIJUFZz*9Wb z7Yn_(6AZ)&W_Sh@gyF&*VX<&ZxF*a(+j;J_ST!h$Z6MKmUF-{B-{{-GDfVgH- zYpIU35#H2!iBSKL_DD~ls8%6c`~+>qN=rq5aWmYAEBqxc2oCdgCV>fLhB6hj33^7x ze5TvtJZp~#myWsZbMUR4MKrm=`r%wW$7CQ5e4;1Nm#MGhW73~oK-4C#15LrI+sYQo zCQ3hLdnKV%DVrkpJy9A|SE16IAyXDAsH32hDbqen&sT zd9(#+x&(w|Fh_tGCt!3NzJX`|#j_w_w=Mo!L%i=uu#=IkW+p(Nl)!M*c$LUjGPh^%AI;BpL(9^k%XLb4DEeAE}M zVyR$32crtN`$3r{hziM7vP!h%h08|il9V7Vk`7C^fv&SsN9l*?A&wAU^B<8>U%@%I z37JkRzFj}M5uB23h<^>BZLiR3rVVt(D6qy&jP46MlMbZkqB^*jI!Cr3GZ6Pas&=7Y z;RN>TQz;7+HsyOoC*@sbx-tfu{DEp4ag!L0T9*|Xen0h@YDBk0b#Wve0UaJr%iun{ z($kT@{f*e?L4TrZp=R_4T}2P0H(`8RFjJsb%xop|C&n%Uj`(DDEl?A|ZbY0J4##l^ z^xY@+4(ki``y8HcIL5y>)X1Z6jzrU z$z4WPpAJ{zGdBb4n4RQab6c^Fzzj}-9>Z|18<)Xt;NEd{`PRVHMt&y0hmQxoJcI(E zMlbjZ4TMjaKf!}bE<>gfk+`1B`|%t2y5OsS;rg$|<1(Rx5QM1q1PF+N zCTcBy6YdEwg&ByFNB& z)Qh1&gc&R~OZ1dZBl10f?=eDjlTINLwu7JF9furPDia4ILu`iY8{!*rfY?*i;<6mP zc^|F_W7KAg4N>2Sut6hLi7(gylEb&bj+Ka;b` zM&ur1JMi=nzFa*OucB1@m0MBc9;++|o_490s=lkb6Q>aGPLW&480r9Z0sAiIQ`J-~ z{R+QLN5;Puk#-DqpISz}r$!gXK;-BN7s;E; z01KP~w(P*m8?b2z^1B1{H=zA2j)!=4V<_gcOeWkS8l2SzoH7b}c{1A)EVq)W1D34~ zhRUY*)3NlQbbI6jyJ;=3K9BwYmh6D2_yi2MpS=k_>7eD2ac~FW?{Z zLy*JG1v<`P%%3BsmE%_Cf69Cb^!j0pekP*Td))I2JjUZ41Yl?tqT6}lF4$*3xM~&D z(ilWKFCkdS0_QcxxVj59|Ha70xW@pEKM?AwJs9b!Fd9*^J8n+{mi7yif#NA(y!roW zFD+tT3*>;~#O2~!aTjty9=TszDPHO;g-Z@_P>>WVjfTgdlun3y#J%E5WRh*5-hRKY zfPREXKAxMx-DKB5dpN=S*#s@ogHbVUp(I{FM-6~Sn-Gr1ep_@kr&4pDz<4z$ys zaFO;>C*X+QqVm94sg#Q5F`k>~1o{kiaa{$?(-W+bhwMEFV>A(5)Pj8lmr4W9=>VUo zIq+d)1KCGRENg~pC-9sYj4FeumIM@*GHRf37JMNI8tN95(iWhn9rFviTYyjT6Uh6m z!ViH56TnpWQ0GTw7>yca(J-sKVgB>c;hh-1Bhonib^(8}0}v5EgN>@eJk5o^&{dPc96c+HEk7 z-NA6v5EGkXR6{T)V+B}ig>V~n?_BWJT|~5Wyu)LlX%Ft5kM|lN{3%R@PCJkLii8Hp z{rW;p^?|Ai7axLeCW~coJ8J<&*&S_PHA-cf9r%@$GE&(20aR%a{~jXpJcJq!McnzpSaHseV`ISqHxbFyoQ&(py=Q;2*-#~O zF}fN!04YF!CbOP7#5`nXF&mltOcwKt>4*$(IQ}OZbvK&*#2DF^%r<5q{3#{SbO!ll zeZ=dD@VXY$zyHU4aPM-a597oB3$;Z9mp8yVPTXYfJNp;b*Yo76;ky4;)s^s1D&bbV z0$+V%Wn3pt&-rqHa7u0<`0_J+>~KB^yJM7d&A~Zcz)J)89(*b9$zR}`Vh`E~_~R4# zDE=V7?!TzD5s_;HI4KD{bdtZx>)<=aAP)-^B%w8;Rbwbz1N2ag&H z+DIH-;ay&XW4Rm1cmkZPM*fx|oPpE699%O13jG+6a~yudKX4p=EB3u`7bc6%;7oM{ zZX(4A$m!mR*TgGuqGI52dPo(Ba|038HUl+Hz(PadALOD2a{}snI#zaRE7g_^=u2n` z_2q_G+Kk_iv!@D<(lBU@=4>jn0WQk`aDOl&-CDXo-5lIso35so!i#E0`A|FI49p{^ z5xwCyy#R(@pdTbvMIgBtMa! zz)~aXJ2?;tx=5v9Et;c1?NDYkRBsN(a0&YWK4lM_-{XLsUT_FGZX-JZS$P248KXE1 z+*1b?l5n_}6mqz>>>_Ak8y=mDNY)6M-Be(x6FBx0T!w+r@jRk)0^J(XD+rN$IXwcd z=^ok*`P?{oq+=1s3YisnmqK*CDd2Tiu~QMjDxrs7LVMo?j&s;A@beEKN4tvm9*%e` zAkH>L&r1?#B)QWHJp~$fPu>K?5@}?If8G@ zkL8c@X*hy}2j~%q7S_WT=qJ>Nqs?Nxn_$GZ0uAxNz%;1sMi?;;%##ZIJw)_+$sa(a zrI5c2$03XVf?94rU}-FPt0SC*cto_{TKzR}v>M)23L@bbxDn^UP3OQE z<1+^cZTO>H2h<6ER{{LN-|5iS?{HqWV18$FLFgb#0y}kqvzP`&Q=8gI_93T|Pl>0* zRbn(z7pPI9f*FpkoKe7(yULe1gg%@>@GKV+Y3MSHB1eL|j*;(3HB?Y9aMD|7rG3c?+Lve3!F4UjJgS=(FsbORH)06VM1&*C)ENm?MjLdACj z9!n5M0Yy`Qk;ZVDc7tJ zYdD;MtMHYYKoebp!p()xZ3Ul<2g9^v^Ozy58?x>oFhCdl-Wq%qh-miPD-2}ovvr|> zoY+gqwuh2v+74y#`=}3f z?1AVtmLJ6b1tru6?9>|B)&^*yb->OX{LJDr_yVZrQ~3ED?zRtbQ^S7+f90cEk^n`0 z725b4u$9B-Kriiuu9CrxGJsBOQl|J^}8zC6vG!NE7NqNk@TUmWn#bSL%lv@Bk?mu`3klI3bOM>;1d7(hWHo zjV`gDB8yvXP-WSSe9eG7ZV{ZQUZN{9!~>}LokRYajRX*hpFn8T=v zwxo6FT#ZK-)swnLPC;*KKXL$hgQz0T5=)5`)nwwW>M;BdY#y-db#M%KOcKQu+KKbgy5q#fX--?>p6pr|i?`XT$C2vq%E0rUiu{GVHR4-EPh zXTWr1d3%8=EviH}nSY^`9PC}_Wdm@bhikz6=LxA1{{rD7{K0+(ei|Si_WRGV@&`&? z*kXnTVxNPf8X;;ONB(si_1$AoJvX_1xGv`Qb1zYwJ;yzPYjh5I{SodS_knZcA9CGz z0zFQCh+Dn*Zpga(^ZRhU4)~aajO-;ir<&*BCk3N7MGo{l1l#b?I(Bpn1mJozV%cc0 zO*?SQ7@%YZa4{ZAs3X+$Z!GvzN&fGmu|zH2j4Cu@do!q?^78xtgIDKH=684 z-XYV;Cu9)3a4V|!|H6mNLqse?$8rFwCXuL6RHNVHCA7*1c%jV@ciJNYtzu>%&g?^` z{)|x}OUh;jVB|-^8FB|l&=~WdjFQd7{S8q6cn#m{DB{#6XrI?$pG}B^n^2Yg4op$( z53t%J=0k%(-+^TCmbX!F^Q$ikFx zZ98)#z}km_kD~z06Sen z?tTdMHx;nZ5m-osLs*3B*=KOX9aJ$cW87CkuY3n8l7WRSK*MT8qJ40Iwt{1(pn6gZ zxmYOj{Q|z7kcvDmmB(f`;GW+#l6Dx|OYj#j!9(1NcewChZEg!3#vD}J2r&?dIRqc* zDk^gom?=9J5$ibWA)A4jG3Wy7h^Un!%>$YOr5dq|q>_?E9bE5t{N)#5$Hm~&-8hrF zBcIuUQOHHa=!bK^B^YNL#ZWZ0kL*Df5eD)J)bb##mlj4$CkW*58sdwpRF$OK3or2n zbn^tP;@ju{S~?3bDUPR&ug%)**!rFehr0w#@Ic@Q4j}}02@rx4B)CIx2^J){TX1)G zcY*}xkn`_1`~RMO=5BU&rl+O4y1M$Uw;g>Qt(e!(#PgWRHPzX|d5yW)Ds1PO=pA-} zMC;T+Qe31TL{fg2T1pM1iD;gE%!)3uy0sr0`iztyACz`U_gTO1f!#6-JN^K&aE3Wq z0c>Ln+QvoucA-7@<5PFwDP2t)SHS0!5B(9K90%~kPeAs5!5%+{<~a?5X$>o|Yp{$w z_yhFyjK9Hr%x50Hmsz<@y{jatm+*dH#>N>>sx#4TpA-|T!LO9H%)Xv;C%{lJAGy>K z%(iaenKpnfH=wok(Mq4G4`ysCfkbR(R&_ud!DzFAQR{as>X!K6dg1Z2vPQ8P`}!%h zU)KFzt4b@EWmY`^{UTw9eg(#{6RWA&Shz;d?6BXbFq$WWr;cgk@c`%};A=1`*TI`q z!rm%??OXuw(s*zJx3vk{8{YRXciY^X@O-B;E?&T9dWX+xH}d+F-}JS;BIu+C?gE~o zVXd>7G3*Gdycd~!MPl#V!0&U2HIm8v+5!7I9zWtJ=7ZVj%|4m|6wD3uZf!M2-9&9w z!rtu2N@Wq*CfC4M9VhAjnKTgd#avcb3hVk~#9>&zY0l5g&ZjsBB1I=1&mGy!+E;@( z`@sBbC6comS=#TIjz7rhyx=(ITm#O~C0fusGnj!L=g1JS;q+W2An`ew37piNgv&6G8#<)5ukg&4qzjXXWZ+EM(Lrr z)KRR_Z)6^N7h8EI5~EAhNIcDpSr7gQf@lnO%OzxC5z^sdq$o@O{vPWziLoOGEt0AI z%&0LFIhf_IAGs;=X6STqV_=9c*0W5lryP@Wu`&`wey1u+@m+TShn1vN#X1^*P4g$~ zA-Z?DFJ9x7_+dtZ-bnUk!KWR~9*zHDl~}zsJl*jD^&%GrZ7wq0ACJ^2wF`EW?!o*{ zlZd^~uRTzWd>f=CB2y=kmVePny4|DC-`bMPGWd%A#W%hQ+iN#g*aF7XFX~Ii+Yzcp zzE)A2$I-nFuroh~5jX9yWDe5<|75))FaCc0xPq-w9!vEb={)lv-9z&&e!_jM#3wU5 zKjhr)ECZ(KC+wKw&Ph%OGxcIfO&w-Z1DwsA%a~J5MzgrY2(iAH?lg+E#2b7oDPDlB zqL#Q%+zaB!<|^W{x$@xO8R&Wp`mBsp4>ZU!=IOU3FTQTCtjJC@o|To9F7gn$5;MKw z=!}DSf0kmg++gG>gf-j;-O?HRL-#2^Wo_XZGx>c=e^#e1(b{{kn-|avYAL(0T5_oS zk+AWg$QJVJ9cJQ5XqL9DG)!b}aDcUk>)3bm&>vOkJzcSStFX%JCb}XDeKHvv#-gRD z$;_Q9f#2B1jQB47wKQIterSOnNKJoq!e1P^C+;8?iSDs`gpIKZKg!6) zYl7ODNxM`74YE%vj0Y{ZtlJku7&BJkv1`nnyronU`}hVcqSsvCOFrpUc$7(Iu9XUI zqlasdtCTChD;Z070AtVq~r~zxQ9_-?ydNNOQ>g+uUPB&gBCx_af7v~GwOPL!IO}YD#$`nH0<~IjbB$XbqHbGqsUA8r$k1K7y-ZPxo5%#5~x% z$6kJ_xQ_Vu*Bc4uKF>vYKvWP zmUcWZhtLBNv}Y8OR}9-(*A7LQ>m*@?7RGkfQ4`&<9!4;xjO4lHpaXY<{uwJLbIjt} zdR85NWu-<20~X~vgS*5SWHPw4BRe&i#WIZXw;#X6c% zq#kN;9AmV4i=0^07wDUn=$mI;{g?6Pi(*jUfKs!eRov89l=?Mw-Gh475!hR)?Zu2Z zXP6faXWY>_RJtKKwUMU7{BlI?r~au{R0lKLp3C?#Lmi`*BAsZpjXH`|(vj*bJ|#e~ z`e{`cBf%H!;-l&b#u+!g`;+>Rh`Q@)oR+FqM-I+l`yA#z1Crs?^5a$ZqZwY~|9Jy0 z_6W1Fs*EM=c;XCgeumssrstR9{jJpbAnpF7O_#EYHh|oAK(-au_ajGx8K6swE!(~99@ylIIgg6ps%Z3##5C`eaaoFAb+P~qh)a4G_1m-jONMVd4Z9( z4+Kc{ zw|kp9nTEc3#>)FvzFk({kw3F~2211ttofI?Psc+iQs>*L(I3MjelGPd)uX;8t#``T zw1t-$atFqpiPX2=|8lFZl?Lh)r5@{5@5!59=h12o(io0b8lxKV+WbSk^(1$iP zH3E4XK}*h3b0bB6(0a+Mo;? za09tavb0K(8??Mn?~PRPV4TW+?)74Qk~A(Ue53GR7<4cBfZd~l*9h3Pdn!0 zh{X;phO7)Gh2u!uJ}k&ZwAcdPw25b*KL|6hSE|;Ddl-m-bLA>sh2#ouY=ld2OhpXu>h7JtN9i=K8DOU zB$dvT^cK?el$4&6?}_}X&!SEs(I=>L9e011yPsh@U0~H}9;Mp|TKXoa$(z*cP+D&l zzfb4sJ@jzBeWR&64J}uUcF$rZ-c647hi&R~O1FYK%t6gWGD=>gR?>K12KqpM)3-dO zudLef;}2!r{h8jgC9F4e%PpN2s86mMl15iXpZiKky{0S!rG1C?%;NqNl;|!cIKW!T zHd@Lo+lPX3?M7I&$ae8`VJN8LqA z|B_Bl-ZDSj)@Pel@=@ZAo8m%vKvz6aG zwB@%*z>l%YAQ8+8;O`fKDH@4$?q|8m5Y&8M6c_|s3G*cG!aUNMejLff~PW3VDQdrVAk&pJuBy7CJy#FbZoK6i2Jh_6pIZiq& z!lk{4juptq9qQyg{bMD4sSo;Z0VrZ0dq^pq! zz20<5DIAudcF1+2>O}4ZG~NZ;YcsO{oYuX^ohSHq8(GnHtB&TrOYYp%@hR3=uaHVv zwC%fa>zpKq`zW>EzIoKc$~8*5h*ZXr+8R*6hm;*4elL*6-<6-36>jA0xl)Fj&xwr2 zA|VHO-*nP=%3E!!HLS-okqf=dM@U1LzsdCSIT=mQ z9Te`3x{iCt(@%Np3Cg#H{_r!_hac;qC^ed_{)%keqs`uh$H6miqUf3 zFrRX6=K3Dqo=$0A(A&0?MmEprIor(t+_cC45CB%%Y!^>o;9U!-wZh~pLOnt0=Y^w% zXCpP;kg3zulCH<^gr#B#+I1DPaJ^?-LCfoMlUtq7h;fp-|D7uyY>q5S8AJW+GCPA_ zSprEKL=Ml>`vvY4n6s|n*$tF`H0}BpefEwwKP8vPsqajV6G+Gh%3)XcAh#>H<2W*K zigB-z3Kc8N#}G{An#qW0#~nmeh}onh^=inKRTvYuc& zzX^{~AIP(=D{NtD*%Fo*y*2bP>oUJxruGKWu6nG4lXhIiIJSkFSisqQ`s_a1=~B4e zyo}e+(I8LhuW96GFlFwK)*MEAU8auq^4ZMQD_q}CF7BY2i=l-YFvBfJue--}2P`HZ z`0PRgp3rl4Qsc+M3hDv3-_P{)YtEnO4ld)`s5{gfP?wg3`$ai^oAgbx&}!{lU`s17|ZnqeAj(| znMj3ho5jVE9|@I z2X<;nAGvf3B?T#TGq$dz{-%?6y^b!E=5gvNg|ToL-^cT|72&J;wOh!Z&b2TY`CO*t zWsI~_`){fHi#%s1%@@2?UjtsrlX`^8A3Sv&>E6cK1lnOU*DoSvnWU9M?YVhUw_gsB z7hNMIA&lsw4ZP+Aa9H49S6`D2f(Fdk#pVh z-a-xPtHl|lT^eoqBwS`4FLxigzrs^@dG}t@eM_7F?~1-oy$}hX$u-@EkK!#J^rDVT zSQGZA-Q`UNTH!SL+7f<;j*M7MI=Xf_&uFEO^XZf@jrMs;8akS)DrFUz4Lv2rm6UJ{ z7W6J!eG4+J_g&pOo`60-5Pt6^+VKVTQIsb~(m$$TvAx0eJ4X%9qxWs(efkLAiIm2L z+eX*B`bhka7AS{w>N@y6DZk^66})9H?|2?=)00?^i?H4gkcWl*5~4Qrwo{O#&GhfZ zj98~geI_IMy>JbI9GTgg7&`~)=u+z<7VnupZhEbpX;M(Z?07!Z~6>H zA30CZ7FpqZcMA80A^bj$JnMZY1xxE5((tD;TWQKsgK}-fhxs$@unJ44IsWjQXbt^n zhAwTvY$+N0c>yU@O%DLWV^>%*OjSUarg0A1IvS# zgKvEkJd(SHtGBs?BW$$ToM;ae$dtN%!@yg3I1HJ$&;Wp;dL&FTDFUgugPq*~_4 zY{3kZ<&?lZ&kyo{w$<6)Q+s7~Qp`E37ydPWh0q~`@q^`aO_SSo%G*4;RovF7fBb#b zCAJNwL}8%oqg(Sw`jfr2v>)WP;zlXU*FTh@rdUS`zlwsG+w#`*TK+0-N1lnl(V#<3?31=-I#a^&z6mVoHmZ(3X`zTL^I-<>Y)Bl@N+-k5+)ec6z zh{E~XcI5EA6*{ijSY7*Zhp=#`W-xy1$FV#P1X1=vI3w@PeDlw_RvxxP^ z=`YgmUwZMycrj*MiEqp0DO@VzQT7M+x{d#GP~D$!A#XH0YtOLMOdXrP$^5-iBsMb7 zm!wku8Kzw+b5nL3FSxtMnsQD_oZw$9|=T{DIlD@(2Y zHzNy1nLGuAs>Z#xdUA1XOXyaPD+%wF=2<_cAImCjz9gl@tjJp+XKQ!U>{;nm%-Oc- zw$p4mko#dy47fD4^0k-Td=mKxpi_;J9x5!?Z;_<9EfJj(HT4JjdD1_ZMqV z_HPd;Vqi;@FZOY0tYkK|OrM|L(%4!|_YI6J8*$#VkewM9u&P@VeUnQb4-3~5dkh}> z7h-emKyX6TY5$L|-j?o$zFB8XTa<{XPBG_#ecT=7wayndkF%!Y_iXoW3=|2LP_AYl zN-b#2At`!9yV}X~F`{+UMXiVZldXc7VC!v2$u234j~kO)N!Sn=FEuxm_*5z-J}tj( zSX6q!_Jw=J))cC|Ed2P)$G`kv^4-kui_MmI*mgUbIvSWuX8f4G)!ay_O?2vMn1@>j z&7Lhn~W%}dUSwe|lJ8pf{C3q6YY zSlXqm`>x%w8}lE}doKF2cq;o$_9J_;cEH;@*dj7HI78WH`^UOU%a^bv@2@$ocn+CL zrIpASBFuA-i}{kYG^t)>HD|u8W?9*`LB4x&HF9)}{#To4os*rNeNWsOxjAS49A&)I zOtD!XZI%6w*n#oQqldf8TZHu8SzVNjgsS-#<~$TROzC7ElioWUlv&Q^1ux}%5?U%3 z5_V^FPv37l9Wf+F$+*w{|I{(ANLC{~azF3<(1Bo2PagG)#}+j$?o`BGskwEjy)kiB z^XyM7UVDG_WAJ=zllWkCSzim+M{8&M0r{CPIqGuU))<5DXGbOTXiJtOr&>PXh#nPd ziR$E8>G){tt<;Zv1P}hcsJKvGpB_`Nl{r_ox{!FrwrX8G(&Mxp?g##%F{N_UPP&|9 zXo4K^yLiN~$#C5n8Bsmwt~@<+PLG@>?#TQry`K>B?@wr+yJ5~3ar^x<9ow?o7=Myo z3F(C^7rCDJ+TF!mH+^~9Lt})zIl6A%6ZtD7l<+8yp|&ler1cF>iLIM-A?K#}T!BH( zd6r`KG^MMrv%hcXmxPYF{0UKhtE-=5f;*IOJMWS_AL0@t;zB=16^Xx+vsJ!U`70+K z544pxE3<>H9BQFOB@#<^EIK7uwZLr0&-RY~GWq@Gq)J!HrBZ0ri(b1lLDW6ZV0 zP(ngXQcS6Md)(3B2zHn*=N}mPB)WZclc?1Z_k(5qJ$+65#=v>c8Zp%}OZdeQ zXC=%Vf_u61k#!KvHv`P)4By)(t5v+K6?ko|LE)I;Q~I4R)6%9HX4p2mhRa)txSH#d zYy+|_>8mm}7#a&3oxkFz`_X-?uBDOWyMH259s<;&tmQ@Ql}si~vxs|*~3$#Q~Mgt zj=!Dng!9=;Gm2ynGuAf@%$$|k)m+-~&X#RBoAFzE&$N|kZ8OsixhWr)f!V+<(^tVeCkJ{Imb7ZQxmloUqW zHP>0WELQ0U(QcWS-sww?tXblFSnCSP7p?USoiZM!S2H}dZzqo85O~C{Qh!E@bCwLl zP19oAI_F7o9ULD{v5u{s#c6tJF5!5tJaq5YBxQk^!#2UVBy(~0BHIb2yk~~iLdtR! zv+py<8V+W!GFu(zl`g)L!KMDZp1QJRV+_gs&D7J`R(<65dDgi_tr~1bWn534M{H>} z$+<^fqt?_6p2Ge_e`QT{JTi{V>TT#?AMTEaCuoYdg;>GVH?wJWe!(Eu2Nw26|H1D{hoE(so3guU>LHy^Z`I zd>53XcAw>orI2F|Y&ngT*{ryfkoG&e+f}i$E7CE7_om=JFNhp z#wf!>^HTdG*HU?ia!(4_wq(spy_@m9Io+0J@8UcGs-u$awDAYyE=wuLLUDj|klp7f z1Wvvh@j02|273?dLE)+Gq-bKMG1|4m{+(r;Sr!`DebQOh0G7IzTc21;+HN|JOR};Z ze4{4cm70M{eT&CB-Q^>`^*-&;&uj2?_8e1=fcO|EEmaS=qlf|6>=~qOl&?Aq+r|om z?C+!z-t&Q|pyb`J*j;-ZuWSy-aaWdl9z;b;(B1j971A0o0=-<-ly2HHchFbNcT_## z%xm{M^03l-PG0RU8>|<3KIHRBnqP6tvUE%A?26Uy6Ad*I*3o5}*^>^=CjyS}3!W3o zC9w~9l_;m(byxi2l*B<ChJ(wUVo*Jzj8_RvH?c-#d!QzpKUEIba#SqEr`;+IrYl z+Ev#Vd4PIWW)!z}wH0*^mG&x;?rxNFl6!^}@91Vrwv`gfn5S4uIuexg;GMg`&Q?He zA^+gqVN0@?bqurTvo~~H7Vk@o)uEopa8l*$bTvzjgcfG&3OR#=3Rx^6q`g=!=i#!ur7wi{&6sj2+8L0(td!A^` zyx#|^1|Il!`HO^JMKlWLhqdTm@^_6InC2M=Kh-{8F5efwCAcIwk@OGyYkEg$kCk2W z9#-1tx;9JgSyTN%d93a8*#hQ32j5HYbk9-kKV=O#(J|Tr-xdEW?^x|39`#bxY%Tw% zh~HyUqK*VAd8%ot?lhk_^d$0G%orG$-$hDMPonQeMMi80bPE=YSQL~(*CThuPKh58 z|0aHFj-$C8xeMitNV=5cT;jC2!ZF>WJ4I(ljby*YUJ*X_(z_cq9$xTvv3H^;M(z(8 zBW^}5ihUI~HO?AyE~NVVyKkr$w9USqp#xECqGm)C^?$9^qSyELCPhq-8(ZbQeP&GR>qjK7!&+(sIrq0URV=iO6Yzx>X3uBEx zXKeUVKec;SmZhUZbVl1dSS}hoS&!2Trq4*Lntn0kQ|9fgS=p0}$-)ot^|!LE6&}J= z*jgAbRN+mEP+DkZE@^0&RWPe))`_gghIbaD<6l=BIlp8U&)Kg~z7$6d=@~4EgS39i z@2&v&LW6TQT%2*@CwjqBM=e)Pd9uGi%Cx{M(z zp&lhx@woJeewrW+QQ|ytfjXhzLvsT;y=CRs@LOgo+ueJ#4^ljRxr1wtY}6Kb3Nj}< z${uLj{pAB=m^C!=ZS{WZz2<(Z3}mHu1s=FK?JLiH;seI8R{p}>+qW%PJ<=ClICe$! zk-&BJA9=bq$9oF&ZmMUQ_o%Ope+USyGXB`mc(^Seh3Z6{j-HS(J84XYkfTJxwzzrRc|U4@M0W5& z(8DecEuzcBHi*9(e=1>V;@}+Jax6}KkuW6TY+}2liaC2ET~3hW)PB1&r0Z@SU>T2!kc(4wpXM(R3t);J`uYsE|+P*mk|R)1p=+mDXZNJeWOB^;eE`EI3B7O z`ZLrbv>_A`Q7YnA=wUEESS+|FI5*;}sD4o$BfGNm!k19<$W}3zL0TKRJbsV?%NB<_60{g>0nc+!t+tm?Z ze)`KdY3{arBu|9Q72!ZPO^=Ue9|XKB$TU6)%b)nrln4&47Aa%T_?tE9s4v5ggf5dRjhNm0smVtg*T z);V+G&l)eJ2zl(EomtXtr9B=~vvNV2BW60C;sRH?JX#BA-PvR4EWU|kM_qVOg5vk` zMs+{YlGo%$(hTt=T+4Hvnyat$gFKCBf*+;F;uvR?{l2iqyvx+ayjZAapW{45L|tjI zmt&i4IV{_EZL1xZM6|DP53FB=3qnn}k(b&H&i|Zi!4@Vv2G|$dMp>&{4j4BW zdKo4d3z>hj%n&-VV_KYLwCSdyq2at?u*od6wfVp`S8!~!7qySG6}08I6@nl4DEp8^ zTh|J6Eq`0;TmH0Ew=}aX5+>MIItsvGWpWG?QceAgznXShuGnNpRr_Zl!~B!6s6ogc zVmM@KCw#ItWM6?L!XRO*MYG(o%(gahR1golDq(|Fb+p4Dv)$~rn5^sU%UpQbL3#~U zYDinf>&|ZQvURezbOgn7E*)L}t?Ps1l+egL#FS<3BNVdLwNH24cHVR5bH0Q@q!CPx zqn#g}KZ>V8PZn@YwyQ9icZCh9q+_7-C)YbP;t5c#KKYbunD~>kt@D#O2)6o*czHU= zsgg?`snl0{Y1`dPi9&GrQeYVShv;-Y)~36AjdzZJW1y`+%`=i%!HSG?@t)$ocY$-E z*%3!VlY+5(ab)v7Ee;T_W=LO>`dmn>` zO>r;t+F|s}2xR$7`WCxuYUPM$E$^;IbZ8x-A_AVO?jhPi?7+Fc)xH$sX|B45t06{# zIMo3bwZD6}CmyDDGU~H*qAuJJBG-2ZU;{ns33;yHOhmkLYu9bIBJXWxubBccSM8k%?7d|Cr)E z$^O8xzB|4*zJL7Z0!@QI1d9cR`qq2aXa!hNsn0m`D{Ot`ecilAiBmi8nai$uHveH? zM{hgN3s1IplrQ9K2v5xf_}boiB0&F-@onLS z+uz1l*Rv9vL`QG^;+A2Jo#UV3KkPUA@AwYEWj)UGz4tn!S0zs>T#uDlAGN}taa$|m zF0Y*+u4kXrR_?>hZIJIXt@)qVIQ~o8-l=U2t5NV>~uWzsl|5HL4{SbIoz?bZ%j% zl|97WcapY=ogH&*2dpD)W7v^vVhl+1;zpbAlW1;Ec#B0g;Z==G-Xu5DH-!u_$6md)+H zpygCY$>oVXZ%b-*!Lx0q40Y8KAPi@!H^CuA$^|7W@ptLsH?E1UC&b|$huO4*nCkpp zJmvDqd05@+sT`HJ$rFiZC`c^(2ze`OSc?^+5|}?!5bv>T!9|HxDy<>$8_}?c-Xwyp zuQp0+?#^@+AQJ=`gr5IQ|U2y#rBDUhFl-CfmP1zq`E8^r#w{4R4&5X;~jxF#1RhM_iC<#iyGRd-`; ztJ+360E6gj@Vc#t1^EZA&q}alEfV(->2?Wu%FXx}udJuFN4v&}EyeRNOfM$3q!ujv zs~J6Z!HzQ&=9t;?US)@x4`gg{@XVFeZmh;lV8v~jIt+AL6HsR*wX2*xMb90^2iF6e zd?X0?<Y zuFv7W=nn=C2gU{(1Sa@3e;yF~fB0sj8xO-)TrY5%^_eu^T7Q{f41Ctrv1FD9@&)?B z8`~-HCJ@KI&z~Z4M^23RJ9ILb$-d6MP@d46P)>H%+ZAdW{3>`kP(M%|Tf-DwAI#*K z5$qpK3rq|AK`I>sqgXW<0iW%+?36LyZ}T^XC;o%4l)qv?3LXj$3}u9BMeJu+`<sMI68PwDz}?B-^WHt) zsovb4;_ef0`J{pud8G~}vZW0&TS@y}odEXt8+y|bFtMlA*F-aH2qPKWu(CRhmC-HO zK{4Q&`XSXTxVI*&#{Vi$V0D$XcdWJkEMH|Og}JWcu12mcu1c;yk!W3>T*Rz&CeD8@ z{*1XW|4)RoxGC#yqg)xp7$o!SV6nKXG_eH>#k{aBtsz1x7haM7#EoKYv7hr#=NaTY ziujZVuAZ*JNd5t0p{fu=<$`(O0}(AU9CC@oaL#8>puEJm1kf3sMUQI>%$ARd%yT=x zc0O`$5-+-zN^$Zx(sK5$sY>oL#iqn;j)Boe=MPJVO|>}@6sKLai1)oLZ6f;SJ88aa zmTQezh^UxI?9q0h)n}qVZxJVRU(87y;AD7IaTTf zz(cVQUMW8)%JJ0M3i^(Y4rmM-@)jH~H_(+LnC6wBUnS)!ky{C%<+G&j^q{qH5o8iW zT0!~(vVJnh4cAha1mDF#;?XOChdUNtW0r~KbfOm>#Qr@5ovp`f4FfrJjp&=%N^Y6Go~7=MM2)Ay&{S7bwbo#?zNL3pfn(=C(CH_M!+WN+C2})M zs|=p~BGD{8h=_d3I{q`_MLVf0(P0(ArBvnGNTQ4X)~?e>D-cB&?OE=Q_Kc#xw<97) zXQCV74xm+Q!#J@YPSm^JFO1T!ydK{??;UTtSM?pmmZ(bw^~nkQ7i$)yWRWH`wcUgoLC0=;bQ4U z{MIZuHm|_gy36wfCWep1aSU{S<0<0(1P^dNemR64cg?#4o8~D|X1#ddM3@sT-d3K% z?&fH%x$ZZfRPQ|B1^VXCup@MaDX24Ew0GEF)nWBagdy#FBF7H7i=*j=@M}f->jTQW z#j}%`v2|#?dPKGQx$4J)+V2j+ptgX~=?Q##KVy?T$BR0FwBq0mT|<0|Mw_m}!mR=C zL?UC?aB6-j_S!nminyP^{=JMSnB~OIU54f66tQm!@Kod@_Ml`q`XC?Z^8{k)KA^Mf z5^4=X`MzIP>RA(?22i$pH1CQ>HabDkPH4L?Ci;+LMnD{!3H zmVsJfEuY$6$%Mzn0p>6oEc0V<%zuDAiUKj4AG!Yqb|1SE2fvX8Mz)#6oUMSxu@4c= ze-Tqq1o^kZLu3R;Q3^c1fRwfb+1~+{K%?jo_6d$Bt%iFx3{c@CT4cr;Q|bju{t zSWm1}MWQoT!1fj=-DFO<3C(oGdDUqX%fml#O?)fV6wT%+;anO zSR_s-(yzE!NWAZC;4H-Pz4HRR7eSaW2J@a|ag`VYN@Od1tFN3Z;CqU9{_BWk$A~P) zTw=S{IW2G^j2ElG?sUra7EYCgAWIrZs`LUY;vH$vCw^IVokTb1g7f!VSP&*rx=*ed z(pcg}dlC&e3_iPmh%(jV+j|g!sJP0zexPPX5II=Lby|FkclR6gWMNifcFTR_IC zl0eP2lv>c9#iZ}yRcVDjeL*bh-^6pQM~6nqd#TSpQW>F^&kS+=jo4Da5EalX-kR0d#ygz zy1Ab-n@LyQux-R5`vS3ESBdS}j6T%)Hr(#_M4tNLFL>bI${p*m*4luf)Vk2C0vuZg1`#?y7t)7{}=2)b9%x2M7{Qysf{Af}#xMbk0BW+IEm5(~2t z{`S^H8noyA>xpm}h(DxW*vf4NDseR<+Mgf>n-J6Th=`RVydyWhjp<=Ll?}}N2QY1G zcuNutDHdf3y>%%Tu?y7IV0@0H)NR=DI)>e#_5kVI4Cbab@@4GSa*U5JS;y7uY}Z9WIuxOO*6^-L#1zyG$LHug)?RX*4L3}AYH1OkCNDLdo4d<$ zkB;Tl(PmpoZ3|`E1~PXzXfhpDo}tVo#&IJI$i39}#QChj_Bz7+;TWwrkNhpB1r-pU zdd!8+KBQyiqsX;>yr;%ilCmC0p)bh4>LHLwf)4?mSrtT z$NT>PYV#J)ZlNxxgQ49NM!)LVJU92Z=boGNrzzCHWp-23G5CA&cy)!7IU65+F6{rw zc#qZ-ttwNmtMPxl155Xo*1O1ihhqI#pzU?mCY@)e1+gJtDQB2tmY@s{;`7o}552bq zBaz+*ehlDr)OWjO`DC%qPCfK^>cu6r>Xw!>Yu zh*;Eq@*ilAw7!%-{xIHR+Ye+P;& zM6Z~MUg^r%rQ>89h2^XTk~5F?ok#!CqZpQh3w+OfZ6tF)m*!@6nS`vAp{16=sWp)3 zf(W%AD8bgGY@}u@kk4T}^?^J*fe~#dD96D_?>6NT=+{d089lC~CU@2+@8585GwO3J z=*IaV5%v1WfdtK=#r~$B#(=7QN)1L(wx3z)lGKA>=zk8EY!i}^fviSTi{F4Z?}?|i zJ6d2EK2jY!xrchu`^_CBbS2SL&9Ub7Xqg_&VCzzb^F&hY0h1X+%iGZ%RcV*C{8ARo z{UYqy@%(z1_I*K)ic&+f(GA0p&aP;bMrtgw@{T#hFlNz9sFgbO8C@pMW1%Lqn?w@P zDNZ7xhN>0d{9Z(D=}{RgDCb4;lZ#lDf9P3N@J>XM-&&xyuM;!1kvASA$C*S;>Ct-` z$mebH-ii9E$**hBCdIKBE`vJ$mVDO5PIdFH4}8Bw{T=0w4M@2j|8fUCaEtof#S;~Y zAn6Q(wktJy40P&l`n(=BQw5Z&UQeBAH$6I4N8Rp1YkuLm-SmMj;a}qMe&~^_wMf4d z2vk+6hR$0hr{Uk$F{C>7dKxm?49op%(C)pc^`VsGI2xcB$k7*Q#|E^4E@66P!=P|< z<6oMH=#$S(yuEbNtN*Z3?=$ekKYWTYbukjg2V*LMI)}K%D1j05Mc^nURRcC$M59(Rhz{%9&-mr$$W2t=1Ru;p^7zcBx z&IjtkbFcu5zaVPxo3mNG=no2OR@_ z3;m>z5WUd=U(xd#GLOm6-T9OavaXH)gK^*yqkd%=kOXvuk(jc)VXe`dXBu+vOWuBv z_|Ug<6p^aA$fI9bNAzF;;sF~|gSw|7IgHC4LfdtvRQ=!{cq{v`4Ijftunb$`AY2$% zus0u|gXZABScWwMP7DpUg!BH4Kfe%pdI2l(CifmfyRGA+=U8Vs&|B{-YE@BE&Vk&>9J}^()zg*X}UL zVg*b}Br`w(O}2}fVJfXrQTd0moF_Mj!IylEhfrtn*iH#YP~+>Ek?umfzCw?mgPS-f z7JMOEJSEJ=xPpk^RNi-;C)ZNKhvfG)by)z-q_=$mWJ&++A;%KN_yF@-1Fhj?cKRRh z{EJB5;pFv;{5Mye$l+sZNah|1nf*xGpI8?xiDdUij;2wXPgsW{ynfA)|J}$~O;(4_ zVinw^9Sb0PdfcX;+B`^%=-2c*eK(BONby8cuZTS93^x^cswVP~Of9rQD$6n>cJnt~ zu1{_0oHvyjqxIO-Ai8!S`lT874`cS6gwHVnIck7*ZqFL&6#fgu(_COotw7#Nac5;l zx(R6L0({r&_=en&7AnbmAHdV_fLchP&kW^SBl2`UTyJ`ht4}YOMmdv-x$a6I8&7Z0 zV{Z4*Uu%%hy5wve^7{ZzaSvm`SVpNlXpX`JmSVuE59+q==x+dx}!6Bszq<@%p3L5xG(9Hrj8QmJ*~K+N9pw> z24p%dyD+R<8<5g`e#=K${NdKodB!imVK#=hCBg`FOa6`$Nz~_U`6osoJ)&zRpH0+f zJ!;pd?4*`Ia&L3wA}>-915=R)yDXY_=cQNat<`|sRVPZREnXF2UCJx+%Y6PTJ%9v z_vO33>&O_!y*;F!j7IK_b~;9_==%hG;NG|7ZHkhUsFdw!O`RLLG@3S%eCl?`F>JTl zj0A6Z%Y9Pm&A2`cDLTaWT=-(Aa&K*9I1N72Gf4P!xv;X0`1W7v=QHTTFVG4C`ui93 zODnYHM`p|l?V4M8CSOJ$oRbB9kD~{@<-0}>Dv*N_++(G`osqNXQ6{8i9kJ4_Y8DGneP%Zbmw!@BHHW_sW7L_=b;$Dki)$v$S!SES~!kGFugrYJLa zgDf)}+#;n&s{BZbl^;tLah&!?$(DmFdbO)y4Y|D+Q!SE)TQS zTKE=5keffa-k(&B{3=UZU9Vu=ehb&dc2_^wRJa0L@z7)VS zQPOn{R@Iw$2>un9;vdKsKjCY*$>)}M9mcxXcr32LNPbOx#kFhrFc!lJG!Mp@bK*LF zpCwKd4|44!K8RQ16Y&Oj42J7&ia1I9MV!i=1I4j;SDT6h;4}~6lPH3Zw-w(?!}9vf z*_Qn}x^ShVxE=3HUD1Y@Hd2h{S~9!SwP$6#BiDY%J6xMJp0CAf;?c#*yKOcIJ21be46-I&;9| z6>yqi!xn6`TCAe;PzGu&+*N(4X;3*ClPc&R{4;{}OXB~GPx8RJk zJKs4TzytOO7Trybza0G>8y%B5pX&J2F@mESXPq6x*l}(KdtEPZ^oAL=4NOn{*l})< zqrYRMqdmXnbJSsHy4sH49Nl3M>*@HKy>YAZYy%kQe|B`@Nt zh1nl6*^$@baCq6dR&#s=e`s}>9ocr9;{~hS|A9hyWxr$>9VzzQ{F-WiX5R(+@fG_q zr}8)GcxeA%e{5f7KV;tui~Sz^dHY)XW%~vD7W)kQDEm+LvG(?`+%K}9vKt-i?O*I` z!aJI+u@AQ|wQslYv%luK9rj7~U)WQqyS=5oEBCkOsUh~B_TTK)*kh=ky^+0@J(-=W zn%QUDJKJY*tqOa41p0pEbfRp@%SA7$;2Ux9xn}%e8szyg6Q&CM*!9a^GrxSt867Mhatv--H3e zK#rcmufiD4dI)`mc6>?+wS=ldHz8T*AXE^V3k`%eLOr32@Qv`3kXI-t#0mKYjc-Xp ztdL7k1wn`wtU^3zE+Im22wovkNDx9oKyY%+#D0-R;a|&3i$Sonk8q0RHRs1HXDo-n zp`5eaw%p+V4a&eGKKqouZ`vgK<_HA@9c4NCz_ zSxXU1aZ5Q%MN6Wkm?g;)vP5tsSt2c8S>pIzKX+PO7L&zj`DC_Q-m|x*k-viFmidYK zzWKQMg83H5Wp-FTXTE1X!{5W^4d%_}jpp^{9p;_pJ)CVfuQDGpFX8V}^KA13KEIjA zm?xRXnSVDAF!wk2W6#WA%@fT%`97Lspt+B^h509QEptb6J9BIP{$OrwuE6)I=1S)3 z=4R$eGZ!!yH^6JNKC|5%Wwx4aW}`XN^wyMS`eb@; zN-@1Oz2e&o(+ATV(|tZyO_xn)P3KG}OczX7OnXhoO`A-|Oj}K>_`l4w+O*E}7w0QY z(@jfE<4ki+qf8U|%rq@FO*73h4L6N2_2zGX(;$xDO~0DDnmU+%GPN|dGPO5#H2rL9 z%6SbUjVha}nrfNqo03g6IV*3fXew(eZ7O8SXDVPyFvXe@P0^;prX*8t&Js;gCdDM0 zGK~gPmNCniYW!$4n?4#p7@r%T8ebZ386O+(8gCnKaHb!3jW>7f%(%$7#Q3Liu5q4mhHU2a#yZBT#+t?o#%jh&#S|8-^N&7=AMhF!VO`F#KZZXy{^S%cr%Wg`ugTiJ_69E}xo)T81iy u>W1=s${9)-N*apsDaa?6A&(*6kZ6cDMDp<%0tS~sGXQioSPfLX;r{^4OA8wS literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/default/magic.wav b/ground/openpilotgcs/share/openpilotgcs/sounds/default/magic.wav new file mode 100644 index 0000000000000000000000000000000000000000..15bd23b5e977aa266a16650ddea41265a0aa0102 GIT binary patch literal 61834 zcmX6k1z1!~*V~;pw|7~V?pV4(N(2EFL@~ftP%MnsR_yLX><+LM6BS#rP!R+bqy$8| z{^R#Q^UU3eGc%{p%-p+i5uu?=n<$ioz#;v{rOnhyC=?16Qpgz!WmO`TLZe71Q4#Tj zhCq8nbZAUOVB8=A%7Z41)x}I3n?7*jl&Ldy1E)`&G&Xf6B_ephAY14So<4T;%!#wd z>Vl`HrAaL0&Yu8uhfs!@6?~vT51!ugW66N(YmQrS{D_iacLMNJ~+7v=rI|+7#L}+I&b$X-golqb;YcrDf4})3(zN(2mf~ z(2mhg(JsU9DcU(&9_v4GGjU;fiZ$HjFG|^#hB0dkFkWYoUw(mfU%O1%~;IX%UI7i#5l{?%_v|TXFO(X zV_aq&W!!+2&v?oB%6QKxWfU_S;rWyCk?{jk9fQJbWw4oj3_avN290UXR5Hz&uFO!T zJJXk`W7;uom~KoTrZY2!8Ow}jj%SWx&R`}n)0mT)8O-6#xy*UY4b08VIm}bcY~~r} zO6FnaDrOFIEAtZbAoC8hkok~#k6FyT$b7^sfah!GTjnR`7iKfFp4q{yW%5|xnSIO# z_-$eKFgYwe%akQ&kt{RTUna^@v#eOQEDM%1%Z(Myie&X?4Pg1OMzavsI941hgtdq@ zoi&TK1fFwPDXgii;jDG6)vQgd3#@IdYplzx9M&1u0aiBaAe3IRo`px>us$hL( zJ%Cy%lp3I|htOUr?5w`$FWn{BiRn@B=&grI(8;|BYQPFi@k%roSng*&R)r$1+CeTKSR$M_6zn| z_7(P1_G!px+20_2VgF_q!}9~AXY3;OBesB}hyySf1yy3j# zJb>pJ&U;P{=OpJmrkn2 zx11`D6_@1VTsLk%?f`Bi*Nhv_m2y3}YHkuYh&!K~3V9)S40j55I(InN8G1)@H*;rm zS94Euv$*@YC%MZ3q5vT7ap!TLatpb6++yx~Xt~XO$i2h826YY(=e_4@cnw@3kKn0z zC0vr%#^v#vxb0j^o)^!Q7sgBBx$pvc|7uP=36v)AjJ#>QA-o9QdfrUlHeM1hoHrO? zRsrk_-Wc9B-WuLs-WA>nUIA}EZyhg}cbAvRI}W7-yljAY#(T-T46P@57kRgNuX&%K zrGa;g$KsdrwER0f2LC6|hX06%@_+EG`7V47KalUrH}LKFZ1^3@C;1EbTK)tm_2bXx z8~Gsslgb~>cjJ%ePvMW`KjJUqm+)`$FYvGP_wv{APx4pri}{cFm-u)1r};(je9M0c zxt@Onepm3b_|5!>d_+JK2n6l?uY9_IBPiwf^34Qge3d{epbPv3){rL(5(KdVLJ%P! z1u=p)zPrF6m@J4CcnbCl774}*#skzyfm|?K;39|#~UPKXbM0G+NQ7qKlMYf``kS2p&@^hUHu^htDA^a`FgMHfVJ@i7ry{8aQsL=z+8 z22qoU5Wf~#irL~HBBA(`s9p3{)G0#5c4E5NRO~Ib632)qi$_5}Lu@1N6mi8`v6DDT zJVopwUIx#Z;vvxMBu)_b7aPTc#dE|*#J9w3$#HR`_=Px2d|y09dLd&I3UUMlGje-b|zw}~sovm~TsxI`zJ zCt*s&0C!4Ehu;1Yy(Cl;AUPt*l4MH8NTd>biMzyK5+t#c%#m124oEIZj!8B{-*U+< zNh-iiko=JBm8_C{k!+ACrPm~1C7&f9B`+kmB^Lo=7xdnfcuK1!gtP(biP92DgXELM zO!`)0Dn+DR=|br!X^=Ej`dN|&5Mn7QHAuT)#DCIg>0ap)>0{{@=}ze!sLhu8Nry=n zNzW>AU?$_@Y{~gMVru#=tJ~7x)-fM2`mV+#0abhwZTrJL$PL5iv2)MF*fFgZNCF8{3Rshn_K52xf&X#tvZHu~uv-#>XYN z7H@>n9at(h2UB4Su?g5yEF3?D^#F&E!cS6h=<}ncmS@1 z@eP<0uERZWH+(Ms89R*!;rH>y_(b^C;N$RUJO%m;06Q4>#-HJ7_+ET7j>FR(zlhJl zE%E;NIXoVh5w~zQu>+?OXYgZqEIt-b#AWze{4C5=ho8Y`5?}GR_zC z2wwsttcXE`p1_F)oJxGe%kWaX759O*{lrjWH{n9$5E5b_VT76;Q48zbA?6ZmiDF_q zaSvM05RpV7o=OB0$kL>94!SWMKyC;{0=JOHT6ge|d} zP!ScxM1XxrbP;O^59qs3h{*B855VLRQ3~zfh*d-b@s6-0uMsa{{s`hb(M=48b$1et zgplloxisWOn7@vg53_HFS#trV0s0z=UYLzfMv;Ta$1wT>;QbzYy~zqfPSVH_vXGcT zdXtlgZNxC5h`0o}lmmA62{G9XnDr5Z$ut-H5Dn%qguB1NQ->;YP`h)J+| z6yT8y7+b&^9?G1{X6hJ3PxWc z4ncnz(L{Ix212p{=F0_Y??O)=@bCzsChx&ovjN)z;x}-+3@}rZ_laYK5~wO8t`Zjs zJD~dnF%HJ$Le7HOwgcTo0OLts23h>$)F0qa0rZK;JopumbAi@lK`Kmcs+t~0@9C=k=KbWK=UEMj6%L5{z7RN;Q1Z+ zcolkSWEaRk55^rO#*?dH{^NjE5^!rJ(D)6g=!H@r=;i}L47`{PqjEsjcVV_S(B=!A zGbQ9i4B<)4BNBm2ImA!k`!3*I648vWfKm@gI}5Naf*J1vj#|*OWFi6Jv!F!@96bU& z%mSTj!XM$b1PyS_0~ut&x_!h}z@7`z{|dM-gSqb#6G3tl$OnWM=-?%wb2#8|g5ZPR zHG+oOkSbE}KP_4XG+rh&K*c=J0ugxxbonmGejDI@9B`aZcmZZ}fL;x7hDv(C3`H=X zEzDg67##bbzD9r~{s6x-ly`#7y#=ZZi1ENt0r^i? zyZ|DR`~%vy8t7Ajl#77FCqNg50VeO^mr5oAjurT7(9Avmv!F5}lDq_T9fc9ciC%m@ zX!S7|_ivqVu)J4sQQnZ4$`ppY_iH3%v|@{?q&I05KH!`%kKL zpgjs^z7Lk*4Zm{$eh$b`2rESZmEV9f|EMW|-icseDD)K3MVt;Ak??Hxb6D zK(d*j9S;Dy2i9l+`Tf(Ie{)`fwJ*WAfg#cL3)P>9ce*o$uh93M3Au(#t6t=fYDpK(Bhuo038WF|Qd zN=mW-wEhiHln8JX@-X--D}ee9oaqDp{Q(16rL3ww?*fI--vG0tz=403JM4ce`vN69q3vHBcnf1z z!Yco2a{!|T7+(RtNdvrn4|MDTEx!!y|FC!f+S>#c=1EQ@Ey2g+~V1NiC4}<-TBW<8v0G8q(c&kEqdKR!nQ zmm)!0JO9Uv{=juD@fLiD57^>kd@L~%eBWPOL`;Fm+>Bqrl@N^&;V7{ZpN#wAKkz90 zJH7@lg4n+kb_mV59sUub`b~)YL3kdn$1mgap=UQh?7?^7>+nd3_j7Px;smr@!yEAr zcoH51xU=RKP|A|AK#qEhpP%6St;^i>AFIdiMpl32@dJ;$?3FP(~ zEb$&l{|(Ui&&!BG|Ncd3duY`_bR7yj8A~1`&yl;yTVw^vm*tQT$u{yhxfHlsPu?eA z0l)5&VX~EEhOB@*C%Yq?Eju7PD!VCbklm75%LmE2W!bV+`74=G9wwhE-y%#Uu6lhbF$yC-Vm8W z<|(Tq3&`iBAISbbIRPw0OAY~V+6cR!HNc-@%m?;hQv5OYAEw7fU{xrJIbjRY(dYu$ za~7h{5jI+l+=Bh>Sfo(;4LJdO+zp5;Vu`Fr`XM~nMJFJSkvmY!Mp!6;rXWv|d?XNk z22VX|j+$UM(f`mv=q|Jq9gh7%^;jhu2zyEt_rt2NVb~|^JI2I^!M?E-v%{;fNg(-$ zu=lb9uhob%2tJVpe)S4){OJF@c{$j18EDmS(5fErKwiM}3*=6cBWncx?IGP|*0OHW zQnpnVCOaq-%JP8&Gi76-HAm(S+#Uoqo_w>c6nJkg?}E$&-et?JPST(78= zkA{3&v0t%Xk*`>%IH;g1I}{A%K;=5+f65I?KUJa9MDDx~hxdP$fxUTO^|qFOiynL~*y4VTtQUP;`g-I5%M5PI)R z&PzO`Zc6wWNmkV-hM5J)OW%?0GM2&qL(&{VV#$w69?(P$w0 z3B8WSqwi22)`Y%9#c)2jitWSRV(r)ttPMMkeZ(B_W^4rPzprE0Fkjpe?C_tA=Ha{W zRrqz>ieN%)+zII(c%?+Ja$B&M{@_6m!%liLu^09r{~xbsgQuBIt{@MQy`-D02kbx& za=IY94bStki?R?oUv7{um!FnjlshYo3WK6bk)o(n;7YoZt^A<;sMM=`RRdM4Rr6Ie z^;?yR`lx!Y`ilC#TB@0;DbQGI8#Sex1g)jcS{tr~YY*)N%>>Onb*{Qf<)cbd-B6xT zegT;VD>lgw%3Z;Jp2@b!Qo-(~$^6JKXl)J!@-`a~Lv%#a?G=1UdGBI$VPGdOp4Ne)RrOP3&V zNSAam*iSXmhP(jI4@T#qU(l0qrqg2!;FOk(&Onc&=g?&ID>4O@p^wq2Xb80MQ3q@w z*vSVh9nM?puoKu{3;{Xpg%S&Ugqec1wxGYz7Bn5K_6kVM1mJgLdm#V9qTsZKzzJ&| zXw@Rj9(x97!74NcZ1E&o4P$Pg0oZADJ)9OtfaX#0C)jXoD$F_neCQ}{87{@hAC?m&5CKt-5{@% zU@z;H^Odd2$I7*;-5|NCsz}vhl~U~wa%)oCs&$&#>bV-V=8)#N<_^fuQ+rT5N4rTI zt{bCcnaE8D6LXUbx~Dps$sJuSNVG>2sVPwJQJny5{I0N4jFjJ#pOKFNt3E4R4Uw-u zIfHZ{YY7HfLwv$j_+l&yU4fjImP_izw<WauHo*Cu$b15&FT6&mK{!NDucW_LB2r znj}LqU%VOaN5(+T5hqF>h`Yt!aPv_F<%?p9WV)mg?le3>11^B1zes1m34Rcq_7Sue zos4FqdXz+4;oQzfgOFKBtMn^)L^)zao`EHfK}I25GzQ&(I)Md^z-SPy?7;I52T2CN zwLmM{ik^a#J_3F>4eBOvKKI4eV-kpSQiy(Zh=05AaX&I>Z)pz`k^{cJxOD&d7$~N3D{}1P2i^Nnn){Z66(a>q939@k+--&Bo+@9uMi&- z9~N6n!X+LOYpFZjI&GHZO2)&zlnC0ki~Gc-Vzp$Jq*T%a(wQke08!`(+_%g}&w_pJ z!Z_Ff;IK1x3Y~_YLE=FkMq~)c@DJK)-l>?owL^EipwhJPREV*CbqvU3k(@14(bfKh6qM;BzEG5!gN6j{~YfukH_=i zZRCCBo#v(TpTiyb9iA(1J9iV@zt3X3upTmHj8s|Xf01QxH8_ie(TNROJZX2SGiZF;ZCX6NongnC$C<((CA5^}BOfqt*dgSS+u+n; z3p>03EE=l;D~v}{kkOzW(~uOn@p^=>Btm5eapsZ_c$eSjnu?AWygaVlmPDmDyY~A2Vz7H|8l8 zIhG5oP@AK+%k3iU+Z}E>j&Q!>oa`cWdE#=&h3?wq{N6du`IOTsr!`LJoW?t+yT%${ zxl_HOyv5%8J&IhKY@29z+kNThQa__h>l0XZ*yN%%pOvd8+(c-yi5gq#7wde&VEw}0oZ00@<%KdR&dK$7iiIa8@txD zvs&z%M%MqR*;=iuk=1=~$Y?Qkr_i@?eT4!k8{Ln1ODcpZ{H5F@oFsNRJA!kBlg)Dx zOcouK+(JD_LU~EO*kq5Xomqmp(89vvp7|WJE2c|LiqveyWqhcFAy~tH%XDMVnb%lc z-W1_-$$FFy5;{uI@iZ(1>4m#>Triy{;2wpyYz3?|)&-6=k0LrOIgM^3e=28bN0{C* zUu5lJzt_pfb*!<>IMLPLIl(^A`nB19)5j(o^(wPk%X+&s=d*5Y9$N1r?;l>Mr-l1= z*Pl)*hi^7tEpMAK4f9Pun9edEWVzp}(8^%_$J*Q)v-)IJWP8==qT3~JX28~v386*7 z_r2@wXK5dZn7wti^(78(D_@^}t$C;VGVbT{rud$ttXl#{R7_F`F2WMdVqc_9>U+^O zzJuTOp@%}b#pvX)h1rrl_%ww=`_Rze_K!<}S99Q~ej`GwL-2q?j~Ncf3`Rw^bTAKR zL{N(;RrL4l*`feES(&Sys?Ro=rQyq2hz+ll@~2(c^t!gUdRWcNns+r{YNs{)Z5i6Z z?#ZRJF)Vovq8ika+%Bt8^~E%u;TGcr~$8g_|z2yk;}O zw#xdmMT*`>ok)(6>V?a=bJ@q48yTPIYzD$w$-Ir{>_dk~y&6ywF+6Cw zk!HG2$m@Lb{m~oq!kq=f3)Ih@KcQ8e7BhM+pN*Wtl882BhnOi?%i>WjdP+Ki+9tFQ z>Doe_z!6H`5apVeW^p!5N40US=L(r}V+RrmQm*?Yv*_PmIjk*Ett8hYdxa@H3P;5L zz#7Mi<6jmRB75-*5IeTX*zz9ImpBUd?d4c9F@&52=f|Nk9+{11Nc)R@L_5SK5=*p> z=ujv$UAiih4wFEW$(kl*6NzBwq#D@k+?Ni+4$G3%LHc_0CsyBWsJ3ft23oze&>0w} z)AUl)?*}<`PW*Sd=F8BQz;2oS3vMSU&tkwU$^FdvV(5W@xTheon zJ5z3rxocXu>)qTcP3K_lJbaJplFCEjMh=sR*adw(9h{cjrn!H9v^?*g#4<;G)n(>) z>{6T(Tvcvg+y=WXb6f0|XGEN**i11vs8Fm}u#Fu?ze5dV8U-VfmvS?c2=lKNTg{)E zu#|C#lKZ1~QOkw8n5ySL8NZg+Sv8k*xzZ!K-lFl6Nby|JBK~UDSL&m_H9g_o(w@M+ zTuLdGV0>Vfvpadmg|*W6c!_MIVxV$?;*i{2=1&aArXvSpYXWwoA|4=1szJ> zls{Mer#!3JENj7LNC;sK*c6p57(I)a zA%~^ckkMElo=1L>rz`E$63uOGwn>ZL!7$fsCiu@g=0nXV8$Re$Og5W1o1E8&nu#ox zwp#l~j(c5V-MZXAc+|Sf-Sp1e?4DZ27@nBS)RyYzm`cqZtj9Uj8BwnpzV*JVy=EHC zoLanp|v;_=^;Yp#foOt36(){loa8kv2t7?pRdGJ8r5Ui!JtYX@|pCCXui-< z_)~a9+>U%Bij~iFjb_U%tSr3EPMcmgnW$B(kEg`Ny-&?&i+o1E)+|iye9b~n@(aUY5$1Qg&w^2@o z*3&FaZ7l82IO#o21LDG;#|RTQBw*1pf01pEB&_+&$LDu-7z`V;t>lx^$%yZ_0!}i8cGG-u+rq|LO0V-c5X_!rm;)_N4PEkB8pdyq&yc?zXN^ zotD_oupFc#6|Lw3!3W0E-UVGldgzQefjxdq6Kc-3>9$#6`BZm_$l=ZHt!Ua?^`M;n zP4K<&*WAWq?U|I7oRz{Il0#xtw4P_hxYlLelGwQE_ppXZf3n(RdKWTdd5)r45;No} zDki$fXNsNbS}oIbfMKoPN4r3=1`m@g5X|6h;_Vi8NG}m>iY!fs?up3*O|jx5MiHwx z)%2@Gr5zQGYS-$GN=gCQXes8bcQ+lNFQrqjKCMBmw7HaNix5~Q8v`rSp z(YBwdFRWTz`L&kSiZjx%CWEtcj!!{wMp#1_HS|(&T0psXiQ8gFuEh=2UgQ$za$iJ8 zVe9<1+nrvts{$XgO{Xz8wYqCD&}0{RSulV)@b7?{-xVFD`K2j8cGL#{b?NnH)4|)| zXfP5jO5tu~a%ht%)4S7Ja(+&`$Iv^=*e}_?3G^ ze2EyKayPkX)(xkWyB0Ie?aeS#QukerC{?l~dRhOBlYr@7mk`zGz<8iuO)sy%FcjKbb7E zSZ{U2+(P>qo54x#_Gv1v9QduhbXd8ul2>Q^yQDjiIahcdZ6mYf>GCxEqo9V?(DC%| zx&~Ig+iy;DR%abmz?Fy{us5=K%8ziq8m4woPfG23ZIG4nC(H7qx? zvRq?5#^Jb2y2o#y-GSSK?*zvN2Kf#1{^il`w%&P{Q;>6_tA|^T+Y+~*o^F24fxHl9 z$g>dtP)gX$u<>CF`Xz_Xjq-_c9iR!?;P^y2m{w4+@vg@)=UswrU$)QPD?hsZdSNlM zb-2i2a@nrd^^}XLkK`gXCjW1pc1hF z;WRTHSX;SsMR3EZ9%afiA86>%#wwk#$-*K|7ORET$&C_Hq_go{S*+4l6{;j;3$X;r z6aFgp0M-EZZSEv-9==iOs@re+&ERZWuNkErEc*-ZFV+x7nTMiLc~ZSX9jAJv*dYre z;^5xG5u+1?JV5nQyIwCg%Q91&_n0M_*P6S7EW~!FoVtuZyw(PEhP)4_Md54!7% zdQw~qoy(o0UFUkf@g3=}4-5~s4!Iim)i>GmtDDNW(}m*d?$+oN815RMmCPSIcwF`f z`-l+BL$vS3*YXtmE4OxTa@cZk=k+7*SC709*2FSrk#=Ujwok0;wQup;yry2e4zJF_ z?g|QpJx&s=IAP$~=elk1^$8ggAs_H5nvDJ#PWaopjxel8me8ZyihnoM+^$>kr>0BG zu9f~(=9;zGl-XEXjnF?J83G!mx_MGIrQg?9ziK?)zL=`xTosf__9GT>ZZ|`c z#B^ad*Mx;L#?dBF&USlt9_cXaKHVdtbkIedJxnDvliI=%bM^>qB-zqzgoDfz9bsRf zB~lkKsGMU$3>&3xuXK}r#Q4&Y0v^wX`+@&UxKC=pV-%M(gG?$-zL;d_ zuBn#FyNJcuWV8(;|3i3_*dN~VT*7bQ6X4yFHyI@VtURRIsDER)Z02paW0I(0DH3IJ z@|#SnD$zZ+@NlSgd*Qn!Wz|qj60pT{`&l}Xf|oP-DN@VO5yx*DO*lM%Q zpjSI$m4fjc2ljs6cF93mn&~CG4r74VQ15*n43`4yuewr_BDUmRjAwDXr-9EC0{?>U9)78e}63dKu$5v~`p&)i}C)giGSe=*vMbU4L61R{avb zplCX!ZA<^&Z*T02W?zKYiOKqYR$g`|terFq@wdIF@ks6ah6hc}zrFXM}1lYLrX zK+MpX`9X7?Z|eDyFWt0;!?i8HzqMau72&3)ckJhT-txEb8|s>4@l&x-aI7z;t)_W& zOG4)xN(1MhQXEx+I@ELwlB6Et)Heym5%4yvuNxS!j*)t;geI0zh`7XEM?HcL6hPq#%zo53ZCiL z&zI|;8+9M8JS@X8O&l~kMoZhL;ckp*fw;C(|$`N-Cs-606Y)RPHEk8Id zgSdkfO1r&*J7T9KT^g}+6gv9uDAy4i6S0^RfrU<1y89w|x3pnOb#L|KhA~~?-0kEr zL#7?>WNm-JVuZ3)u(9h=^_&Az|>1Cmvcck8C-(3#+Rs>B6q`pl^clC93b*ivAYSycckolux>2!F1_!p~| zH)!n5nymZVZ?cy;I=IAol=vBz*UqtZw z&Gb3vc*#(#EXPlXrgJB=yE$`3M~SammH7wQ(KtDaT}L<%a_qHmt zswghoQSqu)-BHV(t{^OvT`E1KUP8A;4)$ia@~reFZv}fE+rYmkeXn2{d~9kQFBm_& zXSmNc5{{>>ewy;MXOz$6W(rK1raGdQoAep>Sy?$ubb0FW*-sf#6Lu#GizDLS56p~l z8SpvmN{~9}Y(K{V8xwY>+@5?ZqjlE%Iac#1^O$p8G6fm@VI2<7X@NyS#|CVgx9aSQ zrWMoHv~B%!DEm6Qh*|lk@kR6dhE0`~J}Sy@xIR07bD`g-FZCPfEvmKdTL&&4 zeSGq|48zRAndfHsPs^HEFoG2`!_U*cOmhNzDSat9i<&ChP4-%K+YfYFX}8^ALJVhm zH}Cpp`D*{Ych}r6jlEoZqv*k%SDhua>Wj@5UG%oxA9LRveSGaM^ZMB9-wWJ6_|{D6 zSs>g>+G>)_BW;^)BsOpDe4Vejo;OAqKRCBLWZAv7>1VkRPRG@Hf!TNq#3tA=$+goM z?fS&wwMB$lBgv;ZwJrFqtj(#*Y+Bteq@LmrLd|6^sz`N=YM-KB_6FX3^$>FTeART_ zX#GRDmpWz$GELT(n6&9!_45p4Er#3V+S8mVMmM)C<15!QP6>8yR-th36KYjvQ)GY8 zb%2jaztWhGi8;wvM^uf98vS<^Z**`^Ed$?tJGXrD$ zed;$Qz}oGlxgM{h=xXPGc=s^%#`D~(7XmKzT_1Rl`n>ji&WGP`sqYl;;-4z6H=fNu zjh)TPb-#1wwM*rxUI`v$h_-#;Z0=d+P4iywvDn?obFJ4bZ>IMjk0ZwA#u~R{u2kpS z5I>`gwZ>&`p>A-G>Zq{HRd18(8I^4X4UB5EDzaw6AD8YY%wNl_D9CTTOi%&N`wo@+mE z|J-4-evI7_xCPnzMS7C8rG52_m6z6j-gW$Jej(@Q^cJ)=rG8WC@8_?sw;praQ?PZ@ z=7U>$_U^dY^}@3@o0n}dz#H%96crVJJmJaEdn0D2wx^nm@f_1JV#Od{q$uc^_hhdO zKVHA2=tqMalXfKcCb`9~3z%dpL-w?0mQ+2yaV_hD*ZG}!{qqkzv3{p1dG#gYecem) zal(zNQ%Tw8JGXBAu)Xhq<%Qu-A5|~o95i7%J@F{=p6wIksW#4cQrqX-4|G}YcF?06 zq&X$@K!3)-W3jZj>9I)6hDe*>D6cw)@n#-!hG0q`r=_iq^~^c>)I)7{QE%CX5d*(S;Mv*Q@I zi$1G^-iC_8x`IRfFi(3IN81gSIbctHF7f^R2PY;6j%*k)aKz z<<8W-Ga@pb=dPN2V)p$Bd;6`_3~Fw@e=)mmYx9=&J>$<^e{kvT>x#v{8yhv%!Jp zzd)YB8FZortmNx4yTqYp<%m=l$TE17#gtlztS_o;EU$JE!I zCYjx&k9$Akc*w>BD^ISd%<@{hdb4)d*(0}Zl)T^Fw2qgq9&Y{DX0LuP%3*eNlyxPF zvMmdOni40C<4vA7;mF9+Sj&*DKAFC;A#0-}5=)b5+tJ;OFZnP1ic==S5-xl4rUJgs_PgSC2(T79^iY zS{}c2@V(^HRL>^QaKZMNdl*XLh9mVBA@ zb4cydA4KugC(o~zoVs?{e}Cj|+TO53#pk+j=RKEvR@QB$oJV>MD~ullYN7@WnVqB< z${TEm7KM%W-|JECI>K{#a7j$v@b%-Lr*%xL&v=ur8EX>9@buN#v&x&gex#Lol=YP7 zRL-i7sjm4^QrhxS@N(nb{g-y0+LBG(X177KVZ>(Eu2V;Bu3mWxA41h%ZQa~eM48EH zkk}H_<#e^y^o@C?RgWFbwb#p{pD}jqP|nDR)a~PGV7awpsiOpmUi}NaGi~o{2Vhe~ zh>#}ol0@R;6urvja(lc_aWwLiY^kZrmJ+jMdFk4ycZlchHr z0$StiOTNx|KIPi()2j{_?}^#|X4|+O4ZD}*M4VyY*!ZTg`d4?Wz*;lH=AQ9t06*M6 z(m9Gb;7PcB;AoF`&c|I=_*jR@246{;HDyf(edhTY&!_f`e>;@hZ=2l&Vj6?m{_4-3 zhK0Wm)GKNi{u)v-z4*+_lE;cW!!Md24Lh)IPx$VGdtwiKJt8_^b+h!L{qsF`<~!BtRZ>x$ek=3i~Nnj{|;zftf)g0&n>b57-n?=vU#>=7)#+#>`DxHTLo3A!)+& zPwBSlVFxQ=dN29BT#g7k4tDNee;WkY$MU;AO$gHpm*LV8Q z7)@}Bl>%>b&h)tc;8h+~tVh(XS`k&stuRT-W5!ylZxM?=AFN#-&$z zC$Erq{GKl>dE0oJd0W$D(_w%QI zul=>5GNvly_p*)TY^O%=oUq{7k3-8x4;f!O zd2ITYbo(ivCgo09m8MF&HKjByZt9w8su}88!)865k)3`p+GS4L!&+E9FbNl0i2?aKHBCk)$lU+D> z?)X`|^Tn61Kk#`wxt!LR+$-nrMftM3@a1WzoT5Ih*Vvu%koDUV<1mDp*qpE=Vg2Cf z_>Tj#Vx8mG$7RNw#ea?sj&YB`gLZkmw!dsBP&JVhJRNtF%~uJvx3&9Kn~71Pw~U1D z%D>FUz4gz2E1JJ{45cyoi!h-&$aJXLE<=jGPBRd`2wb5d^ksG@1MbEgODZ4rD)mT8 zL2`ZqcgWO)RY~hcdW|2P_A;Yl*0ed~+~0G$=e)=~m@y!Q8~)BZM&#OsHfGmtY`H)! zV7qf$nep9Q{=`&&E?M<5`{952_s_pQy6xbUee8Wf*@q7wI6CHZR^GN7@9&vBzgmn} zo%_47o20*GJ2T5DzLcWA?|lPUr?3iBQ2PX0)w-v(ucMptf;U6vV0Oxp<+NJuU37%q4Br(Q8*LZ2BL2VFtf(&`ZhlWZj=3yy^sv9<;N$Yf$TwEO`SyjyeT@#M zi4r*H>0#7u)L@1?@1RsJ>#y0X&(LSUTL8Z72et<{%8FI}4HxZa8B2Wmk+uWR#9d7I zn>cH*Sz_aG-tf7@qDF5?bxSp$@NtSFee<-=>5r#vpRhjZSwB15X560rmD))=!Fs}f zEpe0ja43}GZoDFI$ zSX{ccYE7fKy`-z7Yh}AwL zz>8r+qaMUAOjwhQr{+%_o<42b{EVFR7b&?>3S+eT0PhrYG4HO#LasNRZBb@8r1MkR z5nd86PH#tIP0rVvmx1>m++J``T5zT?|J8>#VJ}NwUVDA+by3l=FS!*5D*ycY`D^LV zqvf~C0!ufQl~w$zI{91NQBU2+ua{BGgm!ut+`Z2j?+|L)r7e-A!T0jxWG7Txv{~?V z##Wt|Izj#sz6$Y>k0S`|f|x7davAKCjLo#b-lOfan-A3e{gqT*T_5qMyuCjKh5z&i zFw!V^*TEKx=Hrbw8n!j@{?6|B*&D!Y=eM9+WWN-slBu+oHR6G|HSt>ZNX5`6o3Si! zS$(vMwO(WGU~6Sx>GaL@oO_hlM4wKd{yti-F83oY2@Vr&?pgF29-GcFGq-$X^TMIe z+0XdYINUhf<-CKVjoe~@*<{mX!&A%qc7L6gyD5A|2Tlz+*Y9M%n9v*H?P0lLfstm> z3t}$~zM7Pk{B7jTQF$X($ze&(@z=w%{j%Nc>>Laiw0)X$+QYhbT`_!-xFjXb#FennczW|O649(hrQE7mFB zst=eT1}pP0OUx?8y1?4ZdZ3lUa;y0~!&H5{$vVB%aL}UCT4CSfl;t|!Smx^QvfJsm z{UqCKR@*J&EpAy&w(+$8ePC&?Oof4mccFS|7JD+ZXDfU z-IUe*vn8hOMdzZP*dK2Pxl++Td4aEd4SR=BMj%Ej^) zajO($^V;@X+sIMkGyZQ73eix+AC|U>V?_%z*W1K5@^1TfXNueC&T+;#Hd-&p`>pG2 za~wOJBV6&$9Q!@nbL&*=SzDg{FULSy3>uYe|f40Ou=q#NAFbIVtd3wzCOXyfOBMHphbXX*{z z^(8~JezblU{04TwCxFn8(GSp%Fmy0%GT4m04a*Jn^}DsN)eBTrl)*}e>V~>N+h4CY zMjA5>eL=>zHA==b!(~H?;i+z?_N(S^_$}mVU3$qd+E`-fXY6ALh34Rbp}oP!XfSRw zr0E0obF~VcQddQHRp-z@(vO8-z-%}ML>lTrTig;_@7u;cP)s{NQ9;;wWvYoW?_D|>&!|W^UlkKtgiS~)M zg|-dW_159m)=WBCy}A*H>y|ad+-5K!{1}A%C35?v_TL0 zLs?$E4rfUVG^F;P<}sWuj-h38^ji#R2EFMVNR~qL9AXvufEopIEflm_IP;Q`SO(nF zM5xuriG4-01ckb|UHl-d6c3C2r0LQ~`Jg<-+QK&9cH73;Ses=1CO5zs*dcU+s`onI zRLB-~i2sQzFg6;Bjlk_Z=6mq|d?M8Fdq63?5DemH!B?#OKlS^2F-2M~ZGvtmTz)0L zv39dD_TBc+_TTn6$3VwC`x?93-ooD1Hq3U*S_fM9%hDtK+#}*K(MRehU6Kx<-OtM= zc`-Pk<${|pX4ULeW+pht%XA$^4K+T+-D8Ka7eHX`pdNyKI!0C`pO(!Y;Gb5&+Gssd zpI8sw@jCMcI3}#eQ(12wXDI?la0fI=InyD-N4-hU>g+nTZkFyk#?uL%Q?~{#Axdqr zdZOB_+ON!2^i^C|Tv04h{#2GKL(~^kUbPYKD|&S~^-$GjRXNpp)l`)LKb1G?E>L}U z)T;Csbxz}6;~`U#NoAplSm@+$gBQ}^eH5CVP(O##OPN7Xv-#pl9z#p~D;($7b8Fcw zM$L?7&M+c7m<L3t{yNu0IL#js7$Hm8CD_Dhv7hJ<&fquSQTPm==QsaB zcq~eCv0N9m{$1+^tJZ3;zLF*DS^2$OQ@$(@1BI|eJ}l|w_mUv{$nB*E;=ke&@uQf9 zXPzrQ087$W{3!ebzJwJv3#Wy4;CuRu?LlSj6ml?Xb9e@GRwqFrSU{evkZQ?Gtgoy? zt(o#qX|&WHfA>0nioeM<;}uY=4+5*u41C0H&_N7e!0Ol%5NOM(C~_VY{+aN9NVde{ zX1Um0VD1jDik7A{V{KzYP$cR4qx$~vFIj~)X{zghHfe&@qA~nau4@b6-IA!iq0wl6 zY1e2yT23=m-CUEX*{2THWT?+-nrH`U^R?S`voJTwhDrvL!4JB!4)|%&`VaaFhBihY zV@p$AQ&+RjGS^(kTpc5kGxs!YFby?5G!8MnH7RjNzM6PQx~R$YSh@z7`WkDw;iCx5zqD49+l}ZM=yu4XX zvQC$i<%ZHsFjF6dRd}L1#6RLAsjak3iU4^vPE14VnuP?cP%3^9+H@eekNy~+M=+Y6 zfYgc+#tAEgDDkm)P|A_+OBJNYVuVPE%Y;Grb3(i5l4u8nO+& z;jQwYaTrLIMeuNWYfJ{8qBeK83;;8KQrIr+Pj)3& zhnox9!^`EfJXorE+-t59U&vPyW(#YCEy5nq6km9MVJ#>cnvVm+a}77Kqw$2dVeWY( zTEt2iRThk{GIioy! zc4xkG7QQ$4oasyrVXE^hg?#QSTb>=y?&tcW0_no5(Po4BWx^yrmJ4IoF$Y+hr@0x7 zfEB3^XwDS65mlee2ZHMlRnn0jy$EkQ(DHEM~qTXsOnCo{~Avyws#J z_XK-2&vFZt&mGGg(2{YeI(nGbV-?8+8`Q>BXgXwE3|gxVJY|aE>oU}u$F_fILFug+B!LgmF)we76!nZ2sr*IG*|5GsLw8)l7g zJ#uw)EVlYe9npfbgw=uxtNa^`yhzExk77nrHq_m(837ck60Z=9`6drN`D~eRt6BeP-})!PpO{h|5iE$t|taKCDfzK$k(HEFX}oqjUp&N$^_P21W8$g z>&5P2a_L0S^^=&k%r~YyT0mx|F!eBUvcQqm2ZJ>VjtZ6FE<#fM$PUyjIKY_5lVHyp z0((lKuAwF}!bPGjT1v-k1?^nsQSy;Y2Lb9pP0cVgS{j+(G8x_x7Mp`+%3tp)P_$fG(8M#@O^3q-r-U_jTzuq>VZoS z2a&!JO3(!M02{|8aTEw#C7-}e!iqJYu`yG?$@Kv_+#0l8nJdREDw*+eYdBx}7FaJQ zHG)!+yFuSxBhNA2c)PHRzs;$*uTTZg6&eXDUdeanR|%2gN^!FoApH>usUK#u0iszv zDa_$%td4^*X6Ip6oQV2mC}`GXaM~fL-Y>8>*{N(z)CKpUDe48Mge7?2_2Hx;g9j_~ zSg6CS2RB}g{f})575{B`DvZQekHMR!1Dq9FvESG)Ao^nPj@EFKxvJcBeBVRnD~SH@ za3&~*hrwI;)1-mj^rx0F_pe90aCy4>;gSmYra?tK;88;2E?F-a&Ry zzcb;y6GkbicjyHVz=roh-6+A!U@5hgeh1Hs2h=h!@nwDvQ{lYu|2_kU;r}s>8b?iq zeyt8xoY82fN+4FB5K8hWF^Mhm{^Ie<;oi)c{oX1&S zf}*@@sSLjEtNE1qjd?d_>06e6;AljGX6*+uzl1)ISA7F|{tlkPRFK~9uxDKepNM^M z!ziO4-_aZKC&Sosc(&b{3QSM9s!YRpI8L>p6x93w^`dKJeaZ@|=q*0QBCz5=K(rR2 z*Orm_6WLAdYIZT#1Qh{;8MvuXNpK0VLM~q&b^3hF#%`=lgm@i)KA3;bHRl$BfNcp@ zzlf!|Vs;{^`}=rzOW}s$!z@8>G|>G(`ZWM&KLfv}QytJIc8shtFM^{~TTs%Y;B1ln zKNpLK@Ea-f3K39EHDg<0{=JJ1scsB>?H05dj{O{XD$d8>={&B-MH7_ z+ut&o%y7_KwJ;vf|IfQ575)W}z-?Qpboeq|B0E!|@Iu&%J&r#dZLIJeSj0Xer<$5r z4l|!QEB(ciMI9AKSZzWYoEwJW)oO9SIDtFK4d%|VcQB)bGvDY`CWD;_Li;0Ei(kn% z5t{IKQO}03UXb@+naA*aIg0+W3@W)%m|;vY*>x#(Z@i-Z2aR=Nj`1E>72}d+=sig7FplKVK0Z zuhA0Z`71ovp{$mD19y!3jE-eN)HKH__C7X&djajnTI}W%K<*D^&ttAA&kTc`PA&L7 z-2;ES1in%t^$auI9PESB;h``Z?Th)1?1x#qj0T;HYI-in(q-5q&xB)E09xN4UOK*@ zsgJ-RsmyPv%m?W|@bUsP4HeFJ<{tYu`;OhkN+7K7Vh>a{f0w|8Bmll69pJCiw#+?= zc?YkNO7vSQ8asz0WFz<|Ji-hcLHB_ZR&V^uCTD`v-wKwyA{gN^kBl2s5*>xtJ__%e zu~>?u=uP+xZ{Rc10#|@txfYy-&@;|r4$Gv|;kz|}T8x={GP4=| zs3p|KdoYH+vK!eJc+IoS1B{*WsEU@d@z5j}F+C7)dA1BJ$af)!}}>uU8QPa4Xg#ywg+1LKBHkb zG6&F(ub6V!pM~OAId(E$`xRE=nrtt$|4)X+IOfo=gV|otqKmYJUV<5}7c~~2GY#W( zG3JgR=r0Di8R#&Fx4}DGg1NglX5TVDuNm+MDRYh5f|*8wV~8F;A$RGAsKf>I@_5vH zw{S{Slj{LLiuZJZ$xk)1R9#%l@2#|yRJ z&LUe5zt1vD2X&Dh$O*Rwb@t9 z5%i7~lRlR6DL6pZTa)h3TIyRQO#BfYgaPlSHP6v4&^*)+wnS2|nHbTF-Bt@*Cx_m8kY1qaAaN z;U}>i*PHGP_rdgMO}|ZF-7L$rm(c+6BA|^cUMDSaBxL?ie6+fxsD~1|D%_?)X_9woSk171~`eiLHpmpfoct#~<;`B%+mbidW|~`g6|I&9*Y6 zP1qO5J9sM`6Ngxruov~)N-zCx=QD}z7kj5#w@NAQRsMrBH5p^G&iSn6;-bA3Vk-Yg zIU1tY{+%o2+$}iotI$58g`Q7ur_)r~W+sy;gQ>zd`n%)tWaMSmTXH=XW;4 z{kcchcmJhgyYQpY&7wz#&Jv%&=W(3ArZ4&DsN#gBJAY3ycuq!rj@lQrl$uiXJKgx+ zn$=LZEw-rH_%`;Mho$A8{V#sJe*M=}kGrAVaeZTRNI&J3AEVNie|qct!g?o?ic$w( z!%alf;N#H^Lxat(+|3`D4`S{wONF?+dL_-y)~}qL$FI+6d+XXspIc9VO^&d15(aka z8C9jaHsnR))4JpBQyT^DNE+DgSQ9Y3Z<_sS)0Ld_4PM4-0;;C=;s=Ix*cf&;x8|L7 zSO0q+lh@Pq!2KZhe#-OeaW(cPCdp@tt3Q5z{@ue&pV;VzEn0P)T5qd!Zi)CIvUcO(=VeUqubv!G1hq1fzRY08ImjJhAxV3@nQs~~q z5wTj^I&*=aoP8zljCq~y8UG)3li*FC3BlURvomCMOP8b-UD!Os5_Q-RYwZeuM%16i- z6c@9brblJ1Gfj8ziJV;FM2*TZO^B&JZ?kWtAN?YiHsiGkeH#pG`mFjWck1sS5BuI) z^~N5!GiFfJ_08!@yKOD~t7Lxo+&jCux}GN?@mSK*_|)i;)(47Rzg~R{`MSMij+h<& zCAm(yglN5#tnCmm-S>ELQ1PdLHgw~dwsq_^_2G{U`?L1G`S-)_lIc{J;GiUP@{zDh zu3>U@B1fO5zvJKN*S7ri>b>kVPfXI=3JpUhX&iYcGs(YBcls-^mg zKE|?wDn<2^D*A<`#2#_qHM}mK_Iu7B$v9e?CMgVBp8=%>noPQ!?VG!?YZceexYECA z-ogA*;}+Mokkdgo?Nx-s(r0h8=<(i`=Ay!PKVRpJ_vfu=6EYI2I@M;Iak11f_I8DN zkesv#Dj`l%R;%oY*SC zNnB3A>s&JTS>P>er{wE3o+jDE+J22Q!`_pb9rYu_>Q>v-WP9Bk!E*wXnf*Q+vL~x- z?%d?X^&T+NCB(e3EcpVgjLep|!;S8&(blbiLfwjk&l z`M6~2OUn(~f;v=~SXPU%rpp|$aLdi|TB zw`YFYY`7aSrP}+t=Bl?N3b^aq^Qw8;KwZ-SYyOt}M9ms|-`H0bv=x#gX>ODmrL~8$Uws}ehe6}zq!Zyf$(G~ zHXW8o=YF|>$ki@WPVg)C>t^p-9O+9|1NfUl`oanMf709 zd`q%a-=lv%%lT6BfNB-rsR7yIMBU7=dn#pS#;aM+|NRzixD>)9E0W@ZS zwJX4{bh0{D7#wl5oF-Cbas3|i@$&mBxsT|z752CJ(z!u{qtdGHA~#Nx$D)PgV`G4jaS$B7U3ZE1)tsu zFVent^8apGfIWY@&>=Lwl7Hh}&30F;%f{slf1Up#I%B+_$X>IXr8-QmpbyVT9FyER zroMByxs~#9X;}X2!g(4nVnN@6mdIA>9&Tlx>3Gv?HpIHpG0$<5OEp~453=}}6x!MP zFuJzwySusLZzk088xCUWdIEO@g{A=UgEQE6ky>Pqg-29|WjvRIbM^(yVbjRKfYOfv zzw}l3-BFQMo>uM{(^ty=<9hq^;nsKWN<)Iy)U&s3-#{0UuAiPiH?wKx@n35K4#>|F znM$cKE1ZSw75!=djKXoh%ayjWOb$z}_Nms>*tPVTl9=z6zJwO^qb`OuN_HhDMdS)p z;HvL~J}oY2OP`M));z!KwU+AO$C(RHIM(&reHxO#S=v6`<8bS(o<+n#XLkJv~kbZxJy9r>l`@stH+T1 zYj%r7hSUvT%&aTyn)yEOvu9DZHhDE#Dx5v#8zk@XK-yZq~~4#SoKGQensr_ z`Wx!Mi_0U%|N8giw2Xd#5_vxUVl}?P80UXV*RM}`wbX~C$=(C5Ce(06Bjp!!j`-QT zKjK>O7yhm>O?ldHx+;&m@44-1FRe5CD|EiA0u`2CwmadW@%GqDp;N7KmJZ}8ACn$)Cg?cH`T6EgEQ&HT zb_76W6%w%}%lYS{C=h(} zbboVWokP4;gX0{7S&D2;M^jxaKbSmwN9Q@Vv-YlUJD<18(NsHk^~j7UYv?39&vY=9 zS7svN=0jkVVJ&NSnZkO7?+==9{UYq(N=^2_{-xi1`>2wbwcdph2i^0yu@s0$i`IP8 z;zMV$3D&ia`eG%6J+Nxv9?c2jz4+alXmv5p7(emU+Wb?kJU z)4Zm~lg~|Obj!43j9*xz=TVG0p?&yU@we_&(e+F@YlXtKoO{`o|5PRXLl;%3 zRclU_%rJ^P;N$sK`qP>B+0!j`uE6t8Lv&HGHk&?-#jNBujD%HUQ?bfSKr+h0QwRA)!C;K4z8j^Wnj!rw%9^{)V%YB|x&5f^nmsZM;T$4R~qtXbTx$XEH9 zZx)$do~>9l=|}h^>mF@L!Ngxvd_I%CL;I%GtX`$^{kUbWWmG5lNQ4@~*(vT%(a#g5 zxD-z_^P|$dqLqrN^iHQC>|8`Z$Vj=S`DmcYXR>b_mBCn-=`GK3gxK0r4U|mrio7eo zi9cbgYeYF~scWu7WDhFF=T-PwA?r~d=wsD!s=0NrgO~p%jLQC{n@bxg_nFXF_5XwWv3=+IVT^qa`&^pCDMCAv{`8Sa(%ybbUJ3@**3AQav3uASi*EEzn=o%P$H*9*)2I)A}k$B65 zOAgnE;KSi}!rOSZi8n3bh7j{;At9u3;>1c0I8aRw-{#cXDme#xkA>uWGrVI$-i0s3 z_x5Jo8XvzCehW2Obct(r?A1!oD%Xks&oz+T5%3_t(og%33BP*zKG$qEPBafQ)iZuK zWr3FVn3t;d`_3=gm3QTrP_zkIQ-Ob?|Mc{2q*$W~HO;|I& zouKpX3_CB|m~ECr<}@;aTVkyTCQKdN#5=$}+y0;Y7;1s%!X;r3znj~~-hUzp63caecZl6hk)hWZmL6y;oFyW-{ z8ZkgGD<$8$KAwPa+FxY0u-W=mc8aeV8}%>I#q!3K4fRo~A;TO+tz&O<|L`?=Kit7z z5pCirUc=^4D~Sn&k-EsF^OvPo*4x%GQVll2(plR;X;x@8lT8`iTKnmsV$WR1DSiN< z)_qq-D*_cglsT%)+ABtXasz7?AL8b=i1nc-Sd7MaZEw|7`HkI^&GktS7zcA`4Yj!$t%MXl|zU{wSBQOwxiM>u0A!%yb=DAg5@xoN*AyNxDOOq z}!KuSf+A1EA)V8ONFn6t> zn%*9sr_S-V!}3O)DDH+rX}qI@)9i|H^PUus-otyupw-^oki%iE!ykl=4V@KoJj5sL zbwtJ3l}Xc67NmSlvPXY%EHSPtT=dQK`PTQW(nZYqh|(%A>o2TVv%)3!FKtHd{`V`N zetYbC9sR}e%jo-2SBV_T?i6N<@EJ3#@{cT-l{wZKJi~7AA__K2zOPS*vyJmB#lj;m$)UiRzzq}Eo(FG89COHWT{B4;05~-Ps6aY5%G}? z!zKm&<@hMnr!E+8XnUxKs+($4jAu;4ppn^R>S??L_tp_m4V*U}G)C!zHT?t6_#N_T z#X|LyH@98PCImG{yK>*Fy7N;SAX5SJl5uV2LVC-;B7+G!asv zj_5CNd^enOpZMQgu}vSVYoa}BxMq3CLL1x~z9VN2sSm$z4bUb$O^ zg2aiDrLG0s594I@e~P}!JncGw`nOW*^=+*newa zAC&@rpr!gThGlw(zMlbVDt)0gNc~F@fEM24+s?P8Zx6pg0p(TOb!#pAnQ`!0+b+iP zsnh|}IPFw;jZRVht1X2KPYGL3JZR0ck8xIUZFYJcakjDIUalAIBBO~pWEyRO_1bFt z5$9vqIoD@rLq|{B8z=z%gjXDgTg2YDN%{f(#VF=BvxVsfKXwz{!n{fwt(fF@#`leX zW?*0S1^pZNNmtR=Ro?OQ@i|#suCPVn^I{*LyS{;ejRQwPi(C_Wu>-0lN~gl4V35n# zOVwY$*L;wkz?-CWVK;Y#o=UwSGpPp*A*4yw?5VEPK|_P~c>fA+9CF(G%@ghpcQpLZzDE;QU zL%Xm53YHaO7`(~O+CJNo>`wb_yVZH!*}{_;ygBq-gnx`RZd7cqaFwGzIa}GWn9u!_ zMdXe08DZRKoe|b2c0^pu$V;xn6zBgc`}(KYH+^2LedSHx_TyzyceRZ^FYUKYlP9q! z^f!HDe~AER`c#r07@%K8oMoHvRpF*Sp5Mm~L(ah;Iu$B|$5>Y?e1Ztm zn#&*~GsVzGwIbjp`pY|2d;J8n?KfBN2Ke>Nequ#Hf z#5QXL`rvISUTd8}dWwg&V$?&VaskQ637zqM5>Rf>M2j14br8z<|JBF?+aZVY_%p>IL27Y1=+q7yD4#cXX;^&Z(B_G zd@TGo=0JgWfX%a9hud8nW#_<80apUkl-xa%8% zSjGdT_x#=|=IS`}Z{i_kftu(foZ*Kd>8qD%H~c4e;%0gaRZ8DxzN;x~6$r zc_jB|#}`|9*;n$1Yj-`_WzThndTM&-d24uk!TYPDbG0MSegn$!s*W|N4sKaD%kA*J z0nnB`kaycYJNmkoxdu3I+BMc#aTfHp4&kVH5kKdNbFsU5@YJwZky$aV68@A^SH47yWIlIZ{?E-uZooU~P<~0d0||){BRt9061t(Gruu=3(i%)} zm`2WT5vLN@RQz3eU4{NJGhGd+Qe|vO>hCeX7Zerx{i|(2wS^DVSI^X-2d-f2J7$P! zxOx@tE^^A>lZ`4Vu1BZoo|nxIi@_Gl*?Yg@|rkVVLv z@L{{-X8t{S-&COf>Oba>s(4S)qd!`|%Zj7=CWK5^CSRI|8)Nm=G-DKh1tj?I2zV0M zK(S5nR++DzY=RyQdK;FD$KB#1>Ka_h^rk=1-8D0>A#}`R;jMLr{gmUAy{r9&ZLjT? z?UnVAd;!kwbA;9W3ocfuBR#N=cARh;+$HXTt{ILLa71$jhF{IqVW&W$ae!G5cll@} zEL@b=*rve!-6T!mlbBWHzZf4;WI1?aUKNutV>P$6vM!Y$NbjLBJz%|V?}Rn-zI%#i zuQw`WQ~22E$q6MXTDW6%t+76SndI?r`R(7=pWdjylL6;!Un~6AMMr5z^`(gZ- zciaDV%(XX^GT4t~O|u9`@;jy>mLudbXa$bImz`%xL2Db~ejoZds&`yg?5F7U;mw0b zJF}(l%uP#g;}2t3%Sd{KIKt%)Z4mt{_I0c_YLFKf*>r!sN%__9uJ3&Rp9+QkhNT;K zSsIUePi0>&>KUDRwS-VlTD<*~+{DRn-^sNBo4PVts2f>sNjgbMkmG1$4r!+aYkKvZ~g{INx%Yp3Z(| z+m)%NaDPWz&O^=F&HUBUm-4cw`6PLWW0?D%XSk=-baOVi=`y;l?gy?%&b646W=ZdbGyE|)#PmfiUC!Fow!nVEPCK62S=(m$z1UG` z&fEF@yaY|`V(Ez76}!o$?p5B-p?AX1MEb{Ej2oEry~4683o3dePLOQT%k->gm0pOS z_my1b{!UJATB~hf(~OFv+!Hi2e;#-_@ZRNHo$uy9eezNH>qOuw_Ib#}xb1O6!uQ+N zrVT|Q8RcKre&l*uJ}ot?o8K_=B3a|T7?vB-+OykUNvy+kBG*9KeHSSMcT6yZBAT;5 zv82)!~9rq;r1?dj=p4?=5Yp7=|GJj1 zmta|{Wp1e0Qd&^dsif4$S2D* zP+g0iB_AR$vQ4%=5jN8c%)fMrntQ5^s@t0Wx-G_?mVs0g?uO739<-6J87_-!C2E{^ za7hb+W9>LHja*KDW+#aG@)Y|r)ST_z!`#uX@%9n&M1BGDjI2b|LgwM$#3WR+YaW@9Fb)nzMg zA`5vO?n#EK8|tfB22elfR!DkEhR$ykHISHU8gBGAIP}|*WO~oA*nEg8;0$uSy@?~% z(ZW_i8p_TgX-jQ0Ni=|pr#hT<56P!&L+sb>LH32XwRj}P2+#R1+-+#iir7<}iXYEk z6>_06G0Qr6l-xtEBoCFEiDUSMQ185fN^dc=cL`A9H5D_Yt=2&7#7;N{*%NJTvFfjc zqB>Rjjy>8ZhvZ)1y%J&we;fWf{8hy5$jZ^a@rRT5RH|4dHhHq=kjYk3_2;~AZ?Z@D zj3?5A&s7YoGq}d`q*BikYLj0^R_%|y-wuCW?w#}VlC1dRO{#CqZpS_MamN$kwdt#0 z+%LZ`sqfO?u1&xCV^?u6)f!6`VF;+BZ*m9BN!O@)WD?Pa*iY6*BI72i9enX03pMRS zJ)c9WL{5rMi%yPe8U8Uu8QjYg?L2D>leAn3RFk8a0lWbxPnOWv@UX8Pkr&+5@rBE< z zDcTF~?|yV8;-cxHzED%3`Jy?Yt8eIOvg5QrhqqzuDUm8s)e&S%k!@lPz8bfY?Fw$8 zDtDF-6V0;6*3BN^{Li(_z1ZE+744{pbuEP&V)=^H8zu3c>c*uDm!uJLIXOydDBR%+ znXwdYF&UreUTF4cDBU*w1~|%NUjp4+Cvu%Bz@X6T)e*{UMO_uExu#!l%rO=loXDRT zfc|qschJxq>7_+xk0l;0e75#E_mhT@=Ne5OC>@)0gd-}_9c{V|E~axMY>HRkSca@1yrVg@zwcT zP;)ZeelSmEnNJ=lA`{s+NGHlbPmMzSdOzuhsF3~$N)Thmp!=^NZIRx9f1>Tb9kQ!| zyQSy6XK2t1@7R#bp<&@YBc4ZXjO(0qq}CB_wjYydgBkjS-<*cocb{3L+^}J zxhCHMT4+i^>HmM(X+*_M z2jBJBTyge3vPC3O%U>1xU_UX)G0lC`TQ$TIa>m=oC0SKmzGb<-hUT4evrJA>9#(lg4~| zGdpJ`q)I|ETMy|>SI9ZkLb@)yi&G%gX^t=u%GV;c6;i))$ngYYc>r#%BG^J-V}d!3 zFi}RR@^$P8Xyu<<-Wo0XP<6I~K+gFLMLBg7?Q|naY^F<)eYb*4w5&50>Rg&F%1g@q zssydSzBUpp4D>#B4%)n`u!^6=^p_yf#Tn97)K&{w;eQD^GP{BsA{-RA$zNo% zwVKsp?JCDghp`^kg#NZCRLwzLCsgb`QBAo}vG?};aSNVN?xpTU9<6t5up?}3#OxS# z;+5o~38CRrY#)dy)xAGg3gQdf`L-|x*@r}IgPVWLNRM}=!01*MTYk>^eEP$IblsPj zpKQ@$RSp>?<=Qvehe$6-mAa_tzbqDRluy4GcMu4T7ulcp-+n4E^^{<~dhi z`iz}$^Pv4fuiY=~k)na#WLl}ctc*Zb{BR|&8KC!=uahkq4VTYpS(#Q@D(geku>p1b zINuQe?7(7mUqdX>hJL`zXa6A4;W&|KX=Z+Hjz_xF7i4K6MTykY_ZgZ`7k)^+QDFqz z7J+1YB*Exe7=&E0?`#vUCbZ<&g=6AyX^gD2Znajoj+RGAH-ukYHgkqPLslSqA{%%D zS%O1fWB3c$m&}B&HWZrnyKD?!MVul}vu1#VEdm9Y$0xB{ zDJNc!wKO5NQVZZ0a2RLj8rwJPK{-NtA~fTbTqttIYJo_J;r8*H#gW!r`zoAEXL?@1 z1w6>x!W-``@Lml*7FsK!TU37J@8AvcJJY4W=+f;_ob^=ONR?x7ge`7c^cn94d5C4Y zVoFhQR@m3DFPAc=|Fjka`JL2lU<$2OopbFq_*W)B#rmSc?3&-#d~2U|wqSR_1;Zbv zSnlWQ<;irfarBh;aTh7Ar6<_1@1~W+AtpkcY)f;gyiG!KLVkse4XGZS5mev(*zwxB zSz0OV<<>y~@8x#zRmDm22%EoSjpK>K-(j`R5N6W~_;}yYNNSzRM;)tqp(`=ewB(X% zHVG?i1pTjNJ8}m8!dd5f-}Anm0!FG%XoJmT$V{+H1ge{_Yzkdqsb%VC$ktcZzcq|B zH6T9Hm-*w8#}?}t=cwkmVS6tR7x(cKz{(5(PY{e5vYIdhtftmB9^~;0Td*}tS|NCm zDl&%JN_Hm<;B`c#Q(k7~vWJkv)tXIa+S31!1o0j8-4bI3oV`UD`Wi+WS)`?PLeKgL z#ri3tF^KWA<}={!{Ph~mVP#Jw#wc|S^!JSuEtjY}IQyIm;%pa)kr{?KZ5wsIdc3Z- zaj?Zgb!Vf*Vb(kFeZS3R;+1Y$+~#e@wWj%&Yvg(+7*5#f!WA)9Y9s9suYfk(2^D`i zW-Ij%_^Ln<(f2VoJP}NiXgw!~TZ<(NK2O8!C2i_h$XVeJ`X1y zzwM`OS?GP=Ksy{@XY-9E%J#3bwR>?;VDOjV_Mr#EKSlkBQzXmfrz9*5eIf{&Y57CG ztG>O={pA0E84xliIll7IN}-9@gFcfn0af!tzD`g3_qFnE$B#RImMhIQ^pU;>)sE;L z{?MgoE-U)~zK~J!etMeivrqQa(iggG+--ZeAW!f!?;-bY`&A)}ZfZ$2Y}YZmxBBU3 zhM}YsCmY-={7aNG`gY`|u)pDa660uX^%FTxVE%!N^lBmvy6pNAV}Ic89yG+e&$Hc` zC514(OzYKo0k3=y_{RH3E5>W5nA+0g`2Nyjsf!rH?IK$nISq-lhUikC(rLaO0$XbC zm{Mq`uvwZRFO^pF$;`h*Yokm57f!i9X)79DnlDnXx!ZCLhmR}89p&2L(As7qXCVtW zZ5Eu`^`hT1etcK)h0NRY>}86XJX@+9F1FyZu@_)1-%Va~Gs`EU?f*^}=A$M$i}TY^ zuyJDvuVtTUGaLhU=-cZX=^q##7`vHo5We&xD0!yQQOJ@iGRdZ3V?W~^V;%D+3rSuj zFM(luNOwo7mV<8&+BcEA$F!zns0gH^FC)W2%SG|)g!@Q#C?{1F+Y4TPCs)GGLpJ9f zB-n1i-l99m#X(#R{waJGV)!Xs4Cd|H^ivQ{FDxf42}o7nOB^Mtft@=}+Hh+bg(Spr}vvp1G#VsbejamX)(Q-p}57|a(*c8tu*{@_Au6@`XKAdBLhjGBXAbZGk(wq!BQlGb=uGTLBiuma3MPI4O7qtXBh)% zl{Bor26ivg8@r=gAhky0>y7csv#GjZ4}HK$T)_KnjjYr|_)HZ+tc)XPkxz*{oTks9 zQowR;1`&6dssti&4p_rkxX+8Aw}L4;j`nN^y67RYS!I0JI}lV2=nK>;st&wjE`m5J z^D>zU!pT8rf<*ZbKdmkDCf_h;L0JZ~BJ+sahNp5JJIW(eS$cUAxSwG50M?p!AX>`K zYnEY`T9(>dkv;@cClo7ZIb@~|VZv}*Tpqkmne&Pt5*06#@2Sz~8yB%k1vCA@#-$?9 zuMHK0CsvjmT=w@Hg21yPP4*(VxqHaK)-!2%3P;dSjv`I-AoYpz!lyw5K^G2E;yFqXJqLabr^pc`O&tI$RST>d4^Ac-blWBnkg52YpQvK$AFxPA;Fr)74BH0q zahpJ<)CED<7rl1}-2zn1GQ8fuWIcSgdW;4ssS9!DcMq?%6=}KuP{W}tS&9VSZAiu) z3!dpOY7-R+j?aMSQI>{%fj)+>cLKv)k^DlIqxyrhGSSV=XEc=*k&4Z#M%sMc3sXb- zqWDg(B3vO$um?BcY|~E}7}!SX(X})tT8@(YSkcMd4CXmkA<6H zcMqU7`=ZSbq853@MhOF?o7Q-T31>*9?z-+U&t_M=ql1`5Eit9)7HC&!R~QBmgZciB zHbGUr4?HNwq+zttq*W*QrQMExI}>Fl$L)(X-9p(Xt4PmT^H$3RU27BG`P$a6;Evo1rPv%+z%>Of&@%zSL#90OK?X%N%kRQBAF?aX6+ye77lHpwI8R5)|&#IEQ&h_y5@ z!&}g&vT)}=71iiqjzI!s9CQNnk*@cUI!+9My95t@`?jScsL-*Xd{ znoBgbh&T-^HP$xGH^&q2sOiiC@Jds-f7z|zI(LvaFn=jQ);VyizXdsQt#Mx53asxr zt|5P(Ys~#&Z!rVtgP4oW==pzWE#8HjzX@k4H_}SaVvlncnaJP3@&(fbT|!+0K~@22 z+WRod?%`})%=U~7dMa%nMZ6TuT$OWYjij8dU~cVs_FkQJ1#*beh?M;FR-pb z#0uOmR08j~k^NuSN$=c$(TLcfJ|P`q|+Y!O2%j{qs|13YMDMl z4kCT19pJRIIQg!E%+45u9d&1aBIj5{<<5g%>w)y(dq~}GjoyC<>&QXSXy-AD-2;>M z6VH7aR@hwJiIs7YzWD!e%w=gv2-VXoumN0x$@d<$l} z4O5EGv>c=TFS0Jkx#4tuCZ090Uzx+qWXyhdF{Vxt?{$||YgB4|cjIPL43W%S6JKH1 zRf!BU+6-BS<;ae^qG+!E&*;P{{c-9Rb3*K9>t<65^{8f+C8i!m%FtIg+wg(dz@3-2 zSjXWuaV&P+x2;d%&N`jh%WOj*XiJB(S9xFbani8|yK%RDICkx)`RD9tMu`*d47Thn zWf<3izlqb`?P7hT$xf9{ip%-8tPa`mX>>2l`dzs^Ay{s0yJmmvG`i0OP4Er~-54Go zmSI0<98)^2Kv!75^dH4K;~K#y>}c}Ua@C@uo%`5H=J}e-rRTC=ejArL=-1`a=IV3i zD?&nWmFR9!K|vv0o@S=c`TU<*9e#vmmlRY`3?YV#)ty~~Y6f@qK6a_B*$iXuu1yP^ z>>m}7t6pkYz(m{1I7)$n~55xC=oUmN1ggT{&UQ4txuGY$`Es7b+yQmD=BK72fLQQrh*~PLE zej;DZmB~%?dhVgP$x7J=quSM5tx{z{U@uW5c@2r(DO4cMBDYz=U&pOXU#L=c3NC&l zyO>@@Ub9H3bk>`zB4OB%N~ITo zbVW|g!pGqqv>c!0D(K^xs0l{U@97>`-w$G5m_z-*=q^XM$4)v8Ggc2&7A=_+JOzo_ zkC7Y(e+Zdn*lDO2is7VC2X$E)ef;zPS~?53sPF&r-w}5l*Ps4e0CoUk%ocU2g0(OJ zb!7oM7Y68@+iYB^SaZ`^sQWGqz*yO?+-&DI3uEe3M68+r=lg#D2ai*@``qXAe!t$Y zPI46bptrR$2BW#HLsRgf1s#Til%QukK#RG8wl|tN-zkx*`wHzLQltX;+8wRsF#25q zT3Cg)gsNpR-@FZ+Y6To}Ds}f=^e*~Hs>yp(i@TInCD1J(pZZ-Nx?C}NBWv- zDp+tzJ);K67uX7KTMt)A1~&Ee?%Hh5XDa!7ZnTIUoL7i-O+}mBPhS8p-I?aI??Tq( zWsfV_)miNwy@0z;BfG4M)lR1OMKS9bOpWs#G~XR~Ssrq~AQi#0(FmJkJxpZ(o%B+D zCNsrn0{68%L+Jd~bnXbz`N2um{ttRCXEL9<;S%<-SFK4bW1f}+UgV<>PJ!>Qk4Uz) zT(=EqMT589kt36}1nQM1kzFF{{=1-6o>P}asIvr2-a(IxJkE3;-$(_1g=nK$bOf3L z6i)DOZ+!!j_6GP7!}E@Cw-oLXWF42Wcow6-FU5ylN{&T2n!luGq9YpmbSnHGa7He$ zIS2d4Po&O=o}8thpd!5w(7z0>XP}7=<*#C-dcO z?lwlM`GDw9PHQxJ_GxtoT0=SbFr7;G-P*g_cx@tA_0{OMv=qy1CH!bKddnWp z`UIz6$xBp%=RgO^+HmbMRq36uN$&su=cdqeq6$na19}#A?d7*|SU9O*(0#D75&Lb= zN*|&Rjn-1xO&L1(HSTqt9J{gfKsl|hKsVpZI`-1{p$%H>6>U`nZuw9f{0b}#fnS&5 zJWKUy^n==^HPjZuMGmR^pxL(EvlvTZ4H(*oot6TRuF%SGPP#j584cb|MAv9wj3IYv zGLQ(NK~~TWq!Aq#rqj8inEk$?XAz-UX6#`V9<1+OK+zAMJd1VKh?AWT?#`uhKN+kL zv{y+7fCJcW)0kww3L2<@Uarv3AjnCH-==dW$!H*xIK52WsXedV!@{}3sXXLVQo+wG zUfY3KC9-`zTxcgzzf`C+3SKK|OQ6y?bd@+`J3Oum_+3Xmx~E;&?r;*F zfyHX>KS29I>!uIVdT2v|a4NLd708@M!ldaFwfC`+-=jChI8N{&m}JoddZM-g?e%@+ z+$%^l!M7X21x^5=D-j44!UIyl&~{L17F4>2P71$6!}sA}`f#y}b636LBv7B%3 zU^jCjeETH#9|@ffCc`>a%LeNTz#u=ni9+5^)!V{3rb8tK(8(C6I0)a(0$b*CLX&~P zJx;V0R{SX7QjXr74Ml9{>ICThG^<+)f3)(+Y4Azl?E-D9Iu3fN!rJc(uWKLaaq+S) z@!laYARGSE8puD11x#$6l})CHMJPgxrQEl*o^14@Z`wBQKTNAfre1Gkh0yXJr~~Me zu^Whqt~XBlUpCNJA|G~gWjS~p1yxic8IqxZYM?Zg-;0rj_4)o3);J%Cm#Q7`M+}Dw z6R|lC>AL>8c0%2V)zC(Ds7utNYJH$8I%Uk|xheWoaBKs-HwD}e0ms6K_!n`}5o+%!76Xul(ESth#>6-$gOMlrZ4Gj0FfiEN= z;E0$0O+HRE4Qb?~qseJF(O&$D@%lCPO((kujh_PYJ9w4C6B@!VmO>v5(JZ#X9ZvFz z@JbZ`rE<+l+|h?^`x6ws32pbV>e8>m6Tu)Y18h0Sv)a>V=bF-#9X+aj59fJTp9)v3 z05ez76K8nj9!S{=P6Jgq%^ zx+`3y5$9SGfmBczcgbN-O|&hlO`D|3d~-X}rV>t7z_W6BZYEUeL05J2&2*r>8eTI1 zn5041E8)eb;gQ0E-pMNqxwSmPm)vlNY2aKx{RevSy(_>MzQM8;JB+iW;p zBi2#H8cu_ILB6#f3~z_dAh=`#o@uN8fIRcF>NdKuHNwN&9T^aXv~R>oci~Cv&>|XS8F;jQX6xNi7A4mvOgrsOu9oUi(0Ga<7cYd9(u`9M9#wYuM_H=ka4Q(0go=blr3p_ppUQmVP5A%C2-wFZI7TWvhd1*+H(de0@;OWJ1 z$4c&f0x8*>`J|HP+VAb#FO)%;3JK;2u|j+-TN#3T;ZzPddBvpfNe&NnPNwSAmb{ zMkeHMLPT~7c(jG9E@R*HO+zw@vlcpWTd;R!1OgeX-3jGQWJf7zvZv9TPa#Dng2$EU zRHr!m?!1wA^Vw-G>lCuIoYU*V-uD5!9b8ky)dhU&1!5LXrfWo(@55bl!P=eh zu6vqakJFRrHe3|x#CIP|6&6Ph-znz3E$nkCGQ_EmgX3>fAHb^)qKDShOzo&TlG7Br zK_ypAf**!hv+#pQgY5!SuB#1!z$mD5HduNRxg&JAHk|f-b~74&PyrQhgmQXlziIQ( zf`&j-S2_0*FtM8bFq=<}f?7ljd>Kz!p}F*jaHH+uLkjy@fkqV2Hml3{s{5A z^_+r_j^Ubp?BxHv?bD&e4QdFD8l12ZtM=&GK%{`DCW588VD(XivgZz{Mq4lh~H(cS3h(r^f#uBb*j}5&#Qo)qPv&zu;)6qf0@QxLH+XwUoH@l9O zv4Nc};9R4j!yQPi4EB8ne4C1Ftw4u9!)G1fvj=&v010&sTn%wn4Rq1%IhX4MUtZ7W zU0B;x);$&uQI5`?ge^M_TUvM`Ho%P!(dq1(;sZiL{vX5Qn~0tz;u-S=B`7zPLRM16 zs|%F8lzX^1?Q%Hd3^-T~IvLhrt>fT0*?fW{4xP%4-Z7mgr$gg~tfQemU3(50<3Ja# zg2uzhxoxboEmqS~B;-JS1K4yH+1C|(FIC&2(=Ue?73v?N9sCEro&X!@mZ~;T7pp(0 z!#RU7=rw)m=C}jeEYx;_nK2P-cOR0Vmwo`vZyDde1O^J4Yzqv8E^w9eUj_}F0(XSe z+5xW{8SyJ5=z^2xqD5D$bC9E1oK`C&PA^`wu(;QP6GEacXJ>byk3K|#Tu|g%ts3mh zV-+4VkZ5bL#XKq5otS@DTDV32TFi&YZ_~=(KV&=wX}D?BMx$XC%dJBzhWiFnd((_gd~a#>*STu!+wdoRbn z&yV<72XlfW>Gipe@8q%DH<8D};-AVnc7m7whEL)*V(PPzco}fXC{9#RLJ9aZ9SN6@ z92HiU@X_u=QtSmc*7Njkd@ii8)9~DU{VVPi;DqXfNA>kHz>=Qhx6cWZY+Z1S|MDmE4Xk3 zDHwysF^;P?LjSv1MFlt82-pbER~IOu4>()F z^%Y>f6{?Tsp1ai)uxBW`%U1k1Yk@l+2z(%d%XS4ac}S03Emb%4AEEOF?0rLIzgO60 z3HUIYr?duUR-Pp|*)H}ba8zjg!W$uS+^WHD(Xker0q7in0|{?iDLAz<0`nAbPgop< z++%)(?sIs5EO)Z#d*K>F>huLKQ=v&AVM|%lAy!k3Ow59}jn?l2z1CVsVuq_Y@$v{w z3O+d*><@x_Bf-HCSIy@>XOTi_JgJQP435Yv;Smwqs2eHzkhKd;sbn={Sk(!h-v@a# z3LY>NoEpY1gl_GFhQt{ig}8tCcVC#1z{qtzqWG*R45^b{SV zmuS7PModmY(A`1cvyBxC>$elQ&P;bC=t=ZRVV?-SsT>$jg}&D#>mDGZg(p||hQ~m& z0xEet^<$th016P2Lul>7))L;`tL&;Z-xBzJfTsyN^A&9myBGzACL$rmKy5DYXgQdZ z&3BgbtTNzQ#Y!6>SA|EvFEGvluKn@n2w9jXq%LrA>Ozwd*iyz?Is@+^e7l5|mOw8# z?7jmsE+0$~u}ljb%?h_V07jlsGl5|u=iZf1@#k_nWAFtDU2zU4EKa%+SL8%^*GaKQ z;3X_p4>-I$vd+TDDO5l)g~+b9KvP)e_gRZeFGm&}L9@Mq6*nycU*Q?4tKWc<1V26v ztcu`Bd8}91%%X#`73eJo*XMzkr-1q~_{4GWYI$Tm!h1TFtMb|13Qjl$FT-h`CUh|I zt!bP^5l=nH(ogw+px{^tu#aBYXyHv<~`hJf#0|GV77p)e+vX6-*LXD|oty z6zxOSw<7-08_a0~Mm*r@LY@juxi!4^9z5Hjzlq0GbWsiI$WtC@aqf8e@S&e}|xpw9@+l z`7F-!u2u@Pf72U*&w?xGvVK!QX3W#6j9tXJ7 zJf1%mZ|#rl;UG9s%(-2HvR&Y%z~P~2YYnh926Oj)VDx>y735jv5sRubn2`-EeP}|v z*zGiMXb$p1c&YDc1z^Hd=qZcSP1f_^PyN}?H12Q@UL*M7X{i4pYZ2DLs0g3L65^>l zIImNji?EWeac&mQQuta$yks9Mak7KX=*E{dyuj?M7(5Za7Xi_+tfMM|OTy0Y2Zrv3 z_K%=@=IZNtRw26-8kL~!UF@P=e zB3`zPGkM5q?Bcy~y#9|W+M@3z=)&r{!hJg-DVGDWZmg~z*^Alo7%se(IsF+hhQX^I9H)l3h#)BsP^Og zZ|cv2;ZDwNG`vXUq_yD`+v)Lmy9_jk72stwJ6^!Lv)G65#a3~bQm|NPI#ZyxGR{vx zK+teYQ6&yW)d&6}|7tsDcaPonhMuyps}gyI`TagmvgkwDc`>Wm$9|V0m0EGyqrk<{ zoZ3|OC2ZJv5g8~vpF*>#hMKOUa~*0ydE6O22%a!Z{}&DM zcd+*W_ecTuceG7#t210DbiYbgAf)p{*4Y+rc@K&dk+y;81mX-^>erD18-UkIsH&x2 z#mY@AtADv}68yLVJW0eac%5%t#gE`ZNU;@1ssGQ7r_V4@FYCD`s;ccbS?0IF7zZU z0C8;)UL<-=SFp=%Jnwh><_&>tG4v|9+Zo>R=@XG7OSxkv&np7LW7)TmxmWpCMnvOi z!#;!uOz;n(O$w?g1S;vg+lbX)Wo;**72%;2^0|~{m7G0@ZxTADry z4ziBbtdC&LaV-ftOW-7gzh@+#E8*u_#y%c$)h>9U4^Po9R(J?{@Ik4i5!rDH?4GH8 zj=b!E49@4;hkQpwC9{Bt(CqrLrs=#AA~O8}>)fS1p%2g>$KI|FZ(axXrl9wA0JAnh zw_ZH}q?|~aCD^_Lv2>QO?^8gt1c-}sSk65sf=6qBg23P^o;Vd~HNxiTrwK2_6y9qM zY`bv&74X(o@Ec)$ok8Ojzo+2^Zig%oQm!?77V&?vGI74!ftxtFQ$S`Kv@P__q0ov6 zCIs}c(4_Equ0%7ja-HBe2RYkNL}#w#Y7tZD3ct+dr-Z9R(5Jw~1IRmpyTbcbgk@9C zuBUQ#q9=PXFc`yX=0c}i;n0`C_)@eUKYowKa9uz2BO;SRVtCN#vh*pec@EDJw&gx> zVjFi_4{T0y22bf{kiieZ^9SrltXfDJ3(slC&kC-e#;Udh9ibzoa!wZg1lNt`CC+dN zs|kS}A`UFH(_N2BDj8E6MA$?DSzukeq@GqxwnvI~L zDG>>}fOoA(mE~ADsXR-_xA_tL*~Z=Sfaw8tz5xCztd?nLq?3{FgV@;N`=Cbrd@{fy9@?1EWu>X@;^$DIYyp@BrKh(8Q;M&N3#_{w5ES?9%%I3mzh5>t# zL9&bUCbybhFMv192OH1|{*#pgf7&e-SY6|T{U_=SnBYa}Q zn=zVC#c7H4Rp4!IkMH0a?OE+~n~h-4I)p3BumNT827g(&V*h7U7?Z=K*=gwzloGvN!WREL4@CD36BdrRY9H&rM1 z3b7Xv%ia%^vm!LG5*P}fuE-7h9jPaDvM`VvhR2``t5tB|_Uxe>?=IkP58sdC-qEZo z9I-HFP&?5ND9#1O!p|n;d0Vc@U_XVtD|CGw!{`dyl>ZaCim=qnX zsjm0jcZBU9(}8V-v%Pnxyx%AeFG*Td<4)2K)FFLpURRINQJ_Kmptw=-!<|*$v+`ae zGhBxbB-wRp)IOTjK0ywoX|MZdxI0pt*44ez`@U3D9bro0my^D!*`sFfr0np~z<&B* zjP#%KTzAiRukcQg{A!5&)0*MMiR%;Fkd67J>Cy8Qm-MQCw*P|vHTi&gUw_fO#muu0 zsZ~xf_GtIyosvtAk-sGCHHwV#SwvjBXz#f#4_n?ieEr{he?}EM{*X=>bHWp9uCCR! zc7C19b>6R49XRRFc6E11&NH4@Xkb4!;pe0pwZEuel`=FnJLSEGarGP5K9*REJWVl= zLB!X$FoDHSedox;p^1~j6O?JO<8D`1cE0%6xvuBeTwZxI6!nI$Rw%XhfRxInb(?l= zxIeL-vLWu+!~1s~cgEc5dB1biXO52~IcTr>YrW{?>f{9tGwa??%+?2cm&B*UwY8s$ zD{}Sr@6)#=RMolOAU|bU>X6j88#bu3Fno%(rOkaUZ#6TsrH>z<*x6%8&~XT z=4|A>DP7ZkHXDZ;c8pE}wQ(_=OTGszAv z2>)x2G!`4jnd;!z*D?_$MD#M7EX%QKUwVx!F)G3FGVNb|tbRqkMPB70|$Pa+W&RQM|L z2XaU5Hcstj)THkDXL3@1G{@=d)D(T0k)qC|iZPu`qZ!I^{b=BCb28cy*1K|7IwTKJ zZ^%c?A;@hU==f;M2tja zC~hU6-KwXN)x8Q%BRI|uyrv!So8Dv!SG+u2Ixd~zS`-n@ujn zWh|dk!F7mJQ-i0p#iD!M$T6Nbn+KZ&KQ;FmH>t1s&e-ZxW1fEyvUatvc3tt!(kl`= z)Vxr0WI}JIm3(A2R;`{naas0pwl#4txTBP(0%c?&FHcxh!(OvN;^VU=SKrZ3m|cTSsJ_3FaGyz%KLz?4$=IWhn-BCA>TP+o{GyzuhUoS8L|{hXchfN1 zp=VpjW*$zZ*<$}apVQyVUrWhWt@?-5%-YDtAEJ%(eCAl<=;&VLAE6A2rCN|RSv4(np*I2)56|j$$V=}ZOjbimfVf%uReNJB+A|f{idz{J$tDg*kjCv zKmDPMRfH^UNe07aqtIAn+@*@lVO+!Vi!yHMqrsm(R3J>JqAf$K)E&%&s>d{>E7;=| zS~j_J`&A2CoACIj6J6T~y>2l&Gs|u;QLXRE&&j}Rwu<<5BQz#4`$*`iB}{4MQN;isA_YyC=ho_ktf|1!`2+#fst za6jXZmxpnJ|6_LJ8`R*YGxPGBz(iv$RkEv`PL)L@ylOsAwbU$fnf^A4)Qf&iJ}*u6{^V@xe$IbQwFl;fy$KRsi)Z2W zbLlgbqjC=>*nTcOrkvF763uC)y)K*n52SqUES-$+q4}5Uoi$y#>3>Qdt5DOl_n$Hk(}$tAdDQ5p zPg5R|zm@N+>BbAjeC$hfMSZFHC_Mn;z}(ABWm|4Mr#IC)t96yb)C+A;TY}@yGTk!P ztOi^B=kU4Ri=x2pDE7{V@4x z>G0vo$|d|&33#KVBU2U-MvrlMgPmD&>BaX+C7_7`QFnyWua7lIe5wVKKtr-MvCE2Q4GK>bPS#+<=5 zT7U9X3YqZrpOLNaCr>b%cYD$yG6DRr0CSd7pEZVjss>=_9sEG`@uW>-dR{)<@-kNW zU@AI$(Whsm*}}*{i^fJ~)>y!d4NRtLyrb$yyKcw5I?;(`1i0`U^uCn*m=Y|>BCKB`~yiYLrb z=nFq7yXAkB4087!@Knt_1-uRtuWJmc8qgt6}A~vV~|zee-o= zG&|g=Hj!7W%d~aI4QBJcW-g`EN0M?*y-VkXvw@eGSUHHkzWL}DA~$EYUZ^Fri~IU# zWUz|d(+bX`1Zgc%UvpUgS!u1UH_p?!wn^}JW03xdTF6Yr3(VD4uua2y3fkjf!=UTZ z59C;ut38y*WSi0jKUf*LGU?#kPP*ob+KrL=IU*X@>9Dv10sGR~scw4yd3!T3unMB^Ba#JDMq@~5i58?OaQLUn@l|3!MV zFrT3lL_aK>CY<_@^l)rPonf+GpnXO*`7vq?UNsw-@%kQFkqUiJ`0mKP@oBau6MY@r z?j-cuMysXlq3cgaC4tFxBDb_$KgRjZrN%iGd$|IO>AWne2y|m9)siQTt(r}FK~7S) zX?v+k647uG?Ruc!0VW~+09lH2!IdDARb@)&8oiM=419D!b@hzr=ts9!dz7_4BCk@a zRgvkoi`P##L%`4q@#Ie^r*=lDgI< zcnFuWniTZ~tc=ad0p)XWHyvM0z<9!3LKo)d=3eUc9^%uzuFg?EP!g#jx=P2t-}t<@ zSt}4QUuN20C7$C|Wa5Xh3PqH^oIKeyw8DAXW&L&dof7C|#v7^hN_vz!%i+`*ZJ@^J zjB4uD`ir`(e}qphMXjYYV}|S3%sGBV5gAY`)f!+TeSqj`ovjT)M_h~CaMH=7T#08+ zb4z-8NoYPhv?a!$=6U9${$kG6=PNU%@0oFZ!5^y%A3gaQ>TtC3tJ*B6ah;x~-eDg4 z9{+9WCM)?^i9^QRP@ggO1U{kK_YR#)rl_wfe@HEv_Uls~S3GJyvCBb7kjwNB(an}r zR{c$9rG~}>dKxP7dGu{jALyiBYdijxj(`{!!2jStMe z)VS4BugQbtUD9WAr8*Qo(pGy9+3l3RqXWS_bt`h9QeTdCC8D?Mh~my=hU^XLTR95e zln#z|z&~su3#cJHuO$`CW$Js%EAk`A-9k?14fugh#oshef0z6sU0%wdF;UHZ0ABY% z|I^4Yh=HQDCMu6mQ(mYJpbJbRc<1wQ-6-hx4Y=Wiz|+B=!S^}4kLXPnZzR)iWdkx~ z6BAxb)YfpBnxTWtj?NGN5g2S_s=rCK{dr7EUhD5EKg1H-9Lfl<4EK!GVP1v9zfZU0 z&i;D7hrT1yi_pV%{ad(8Z16m~YI9=)-uk9=mZ&eiAblit#}4_8NyhKfvFKlHjuwWP zu^Yu*&NAozEY{F4Y>#AOIPW5tL*&q9lCv;PYeGNAR?O-C2AyFF7MaM46q%iZe;*)w z{4kwf*7_>FlYGsQg!sJmM|24xk^t|d2@chh5MuG$T5K&_ea z0h2hNM!r91l;B=-cm<>(J3@T5k{6U_AP z4o?%=#n-SaMP@`Y@~%Q#puA2$wWsBA%4%fNC+c?PQ{}W$2Bj|yt_p1oI?bu-+wvlM ztv6)8WGBCh_E(^q<|B0MKW1bS{}=Y{S!DKfCcHoHuc8CUBXW^aqM62b=B3D_yr&4 z4cN$CmFCJ&HA{cPtfr6L$3ZnPR}WG5P9J?_%t7oO{Ezy3=B!|R*cL7ct~cED!TCpC zt=vS5dQbjD>8iHY9RW``F=1Zl5_W47DCtvp`6u!XcGI4G_51WV+#Gl#@VVL6n1a^* zn>0ZB0S?`RE+)Iwty&j&bUid*V(V%h$aT%cLtH@3Yaery8DgrnM^7he zM<%23E1eVf(C29fTzok)`#80(Tc{d11wLINPS7w?A9qD>i;t!&6@@8ACw;mq=6jDr z2Dc&>NtOq;WCoQW0d%xXy$$hy5lI-R=NcD`F6iNf;Mi{bY_FgJoK+I>B8Sino}-7? zMe{f4u23sfzLI~I7D;c>;kY|>9fLFrQ?fIe?(8*Q*9TyeenQ6)39U32jx!rSx` zVG;Jm1mgjgbY~-l>%=vOsaGyW_xg&ChPBZ!#B68L-{pBM!j@DfSHb5B$hIg$E=|&h z7;l;H2K;oKuT4FCXQCWgKF zA9dmjmF3!H;}@{;Uo7>OaITNwn1hHM98hfZS-BuxkW}oL0;ui|ewDxQu3SN1+{rmN zMWWXMqc{!qvN@m{?Gv*#6l=A5sOMpyWe8`W&UEe2q<*()6M<*di7JKBU11-ePioMP31q7 zR{9U7HI$l=mC!EyD?XvQR5>(N=c6ggOjK^B%+~fBIl(_d?ZU6n%VCfqy!lP>W6hNQ zkecJ|Xb(TVXV_T5SLg;#Is%HEP9J%ssZ44qx{O6*^x0slyfb2G1)FXcc_IyRR zp;ln8=>Bp_?M^O@$V^QmrnFvPWCZD|_91qo&FpN>(z{|QRZs(xjJ-Y;+r1Jheh%s0 z7s-~Ozhq<^f0D;`1>0aJRpO`dWu%kmx*v#5#!@~Vk=y?$@pwso!ERZ@yyLE#k1ia~ zAgwn7@xP4A=CHuTz!9?zeI+gUrJ~ekcs`z#r^|~JCpou@d71g#m*LJLswyJP#2TsQ zbBn$%Xz`QqK>tg|@l({yoMZxe8ZgYK+IA<`&P9UGAO`R>n&f-RX89NCZGLL=)}M!N-HQ*YKmQr6P2K;W2A7 zxjL24Rka=3*f8qsqri~6;PoQ3m>-~hQ6sz^A7ces(1q#+ykIq$jC~DxA*!3g=)pm4 zJQLgBQ)bY?hz?13EoxJb*XZbbhCHjL<&4ebojDBg~)3>RC_N0<1 zx0b%4=h-9DEwsGp+E@A+-Dd10J13EN*-fQLc1v&hTS+qfx-D6n#lTi{OggCk53Q%A zuZ(#X1Em}ILxyNO^xOI>?AWt((ECLi?7!pN=ljZ6>U&H&D$iF(F*W=Hvllvhq1Ipd z-T$gT!>{`L(97Tz#e%M6GY7&gZeyXMchcivq4d3cMwao*UDIZfd$$!Xn~g`Z2UOOC zR}Id(7=3RI8nT!wpQ-+d)*Ya4%UoUG{eJ|BD^i7$3+| z;`qco@qG1z&YCIB=pXZjuaEzxbQ8$7(Nnd<%1fNpX3nxmehW-!Lg&s{r53#Byi^OT zVi;bqI?{3fZKnIYDE%eg0J%`ots@zfjSNcc#0-t_9b9mB#*kSnv zrA&DN3AGCODC%ujE6+&F>0vh9)6jd>`?~+8@;!brDR`6aWA7TGCd#U+id}l(>+S1I zH;upjZ_(FwmhnhnJU+2a!5;LEG>md>zVbLdHy(K1zKQ-=xw|?9Kli7Bp4{hV#7FfR zR=k%fMIT9xY#Wx6pHT3!HNl=PoK1mtaeUjF$RFtr#tO2HNBdY)(-( zp91}KLc&bK$`d`84xtrK06Wh!(eMR%7qWR0JsrM+`$z*~wTA53Ql^ z(N05M*gV)@PnjRkfoK7}HOJC7scGN}zNr4{Ehz0#^<909`33R9Rl&MJnNI@1HxrNb z82u!=l&HtpivIL9KHC^N0{;?tmI>-}`1S&2xH23au?(5Agt_s5;`6$Nj`1?~?Gh?o zO?0H$M7fiR}y!4JV0{UsEY|=g?wlX7d8w>nj zti8U(g$`4DlSv)zG{vDDlAGX_yvLLQW{P98EWy$i6;;*5hPn|WSVr{iJMAs44n2~- zrq838kRoa!MV3WNJRVEHhV8n@i)x6RUazG7;r=DW(V9WaM5aA{h19IW-Ad9i=<|=x_Z`NG;&97v%P8Kwock4Ez=N)-=sgdXYL# zc~PD~97UJv!>gD1drD2!iTX?Q(0wx`1v{GqsUc5MAEN`#vsk&iKWx?-#BOTPAE+_h_#1ef4G)ayEtretf12)bWq9mTks)75 zb)_!8OZ36sM61pcsXT>ex2b&3znDo=eSCMZ@JFz&G`{DCW~s}?M$@D|@W{5l zfxg!MW4@5$=G$BSi+n4Y$aBim&-=G`sDG2x41M`9QO6kd1L=WxtS80u ziMy{S-&@bu#y?*ANY28}?8X^CD=&nHO`$9DSWhe8Ori!e(CiwiCG=ZJS1wDpeTTeX zd24(B^X~U8_P^}k?`z>3$~p%7Wm&_gRU3WoGiiy>>n-#Q^)6>}$G84b$b|>KU;In4 zi7!e0WCtC$Ch#*{o+Z_#x6nlY+y1To_vzi!6I!n&*JaX)={KZb>Dj$e@!|LV2Oj^3 z{D<@gJor^SB00(vN;NQMYrT@%3*bqc9zV? z9rQj3>iNJ{RD{#9h;vYh8Z1<(cEq~7ZGIE@6CYeXuv6qNAJdN;xADr~fyZ^?C42&V zp@Tu_Woxk0zhpkyH-XQC*Mm*zhW(^j-zcQEIT6p?26UnA_%{DGW9S?l9ZI8TT{rM? zJ{_07fHOQG<8>TZlBz8wHvD6tBOS1k!%gT9u7-+&PX=z7F0|APEO)PQ5shRGR6Gmc zxFe7stb?aQXwPNgp$S#tt>M3ds{`wdzZ&YFZognkhH#0MwNNvI6p2>y)k zqLulfF~mG;?g_fWzJx0YgA&&!PD!kr=udn%VQlyu{*ue))8>EZ?MDN(f=2^Kg5#Jh z;7J&j*edDUq}EB35{`tP5AH^Xev{af5!euTJ-9uTlh7-%b&{>d?4*l{;l%afGoi+z z9zlEXC-~GKfjYstp@rce5*{SXNjMpv9_|{>31^4ThSE8K>zu^K;9H@q!B0ckq5k3W z&}k-vO${Fi=OsAlwr>sRhV0>&!;gpOgl2?p1`h-;23G_(hl)Z6LL)-kLYvv;>Co8l ziSUt70v+>{LN!9eL;0cDP=4?cp8qpZ;se1&A$Q0gIvlVEA4B$S2rk59S51fg#PCkO zc|ANNWDqf*1;=~}KVt1bZ19C(ztFgF?}UVHaawKh3sR(&XT#SJKIM_LozY=QnbI;_~S({q(Uk*sgZ}bih8F3>JH@=-ppZW4a zFqQ~_*hOU|m+Jw3#W`ef^h29UBkSS__wn)EsZ_Ym#s?a}2R(+U{57sQt3<=+O60rp zeEBD3rz&io@`u%e1`Y;<5v`Qq9W_R71Z1ssf;(19+96KD~Ky( z0-Y!=0S!>}C%TUpeZ77W`&C0Ld6^9TQuNbn?C=%z$wPQvOzpbn#2da2%jR424dN34 zvpHQ7L|>+4bjZm>x3ZC)JBhZgBg$468NU>baxmWOR&?>`gXT2_-CAVGO(WvjAO3Ox z3s3aIZ4FmNa|1V~;>R7!s(w;#;CWQ&tJeejPE@??B?`L5+>Fn~2G^`)S5(R)8}pSq z^u^6rMQ30WyZ;%pwMq9{G{AghBQaGV>B3SMxjfW-!L!TBELw?fIu!{>?1+dk?@x0nbZH7Iat)0@JFec+gY=sVa z2iP7pQi=3Xr$Dc?Ts#!ToKYWkMMjMADZbCQ1B;keum!t#2cD@$WDNGe8os5h$9ijp zz4|u*I(LX@L#8-=Y}d2wY@r%fkI(}{RI}a3+cyO7 zUR&r6I}V&&1s=s9D;KCfw4aSiccq9kNk!8=sF~C_EP-A{Wz0(TI+3OJP(*vqC70Zl zVfYziBD+lG3`HejGSPnzvRCA8i=GD?@pQ&w-ycz?qHz>L2RD=g?CaxL?tKiyn5GA` z^Xe4v{*c_9D|gHPk(qZvj$sWC(Xx=|>_k)}7UB!3p-n-L>dyp=SMYt+lAn}F20$+x zfZxFaFzSlfah{c-uiO zR2C_@%3nPDEqT0BiVtWnk-Q9g+>35qc~D;$w1NjfRaR{BVku6t;eQ=M%xIwApOt>D zwuVzp2Kz;Rr^x1Q4ShaP|6x~gbRzCZ9JmxZ6jfpe(H*Dbw-aa5g_C}niAue+PgM`x z<~rCes>rXQ9fqN!R(L%B!yh-({0m&1&FSsOJCzHk6P)KCWrs?ZH@Fg{>u@Eu$uX*3 z{v*4-H=Y79eQzH6&pve=R3YlRvsspG#|kK@A^4Z2ZxgmWJq}kYk7ECfr_=TaXman9A@sQ- z>hQ|IE0GQEB9l6U=-+PnC$d2DfOP>r!jAZMRpqQa0>9gvc#lQ)b2~V;=xFc6_7ej>LR2?jEhjG7gdE`?)kE}EdLA6g zM9UE|C{gJ_%mLDyxQBgh+8*MZgf1Ui~?%+=iq{v1ho1#}iK0jsD zkiMf|!?W`M4k;|*`grr`FalQ=9VdF=lbH@o-qqU}Zxfps5$Mb;@Mr1N`?TDHNY-Ii zYlRC%aj*Ws_>fB77jv}c>y^+^5$h2Z1FxthWHPR%&-kzO8UH~lR9;bq-`YytU-b5F zho`QM`ZM}@9=ylPUWVh9=&Gpd3D(yD8A`=6rfxc6do1`62Vj zy%D*Pg}hRr9#Q)`FQRRi;-|l&zDM29aBVUjS;j!^Q^0Xi`9yvh_DU_KS`mF3M6JX_ z#uCAMg9f+U_#1OFY$IpFsu6qBl+CqwCHWe)g}1)N3Skqqq+98+|lIt26@tJT1}F|@Lab!MxtKuc-x zg*oauDr8nsv9=4o^ALNvE%zt^A3GrRW1RFCJsWi!=&J0n_2BltinXK@Oc&A}pX#EScaneEk0?Cnu(-%ZLi&V3&| z-vvi)ty?4BjgIsht|0v^k?yOX6P-AR&2Wd7=4S4 z_y-Z+5kPpe(n?*dw&UqFwZGIYSSXwLD_;ARGkiulEkBfXynSnx&+xPLVHY*jR_YV* zo^qugIG@A4nO%$oe+|l92p*l0`^&|0OL>)?FOO2*g>JHxHAvEV%0y+P`XAk2M{s7D z@R16lX=|j7{)he;DF@&AKKT0sxWFhR(^RD)l=T%H@(FUZ{*xEW|493#@ltn5lA@*B znRdmfgX!8vo3 zr~pB! z;eXcujjxOUBmY$Y75^^3Bw3}QQl9iK{+ECKamS`@iu2?SJ4u;s49;m)-$pXXuhV18>T2-pRhfzKOncUkWpsOy7CmufE6qM}2NG zhNt@r{Qdl`@kiwP9`|kV?)Ap_u6x5w#(c~BiMP4;u(!7FzOSP{!QTfD{XqXC{%`$7 z{vm#=|1Y1*x8K{<8}GgBS?amw(Y?=l=X)K#ZFoga`fE!k{cHSV{OSI6z88I4y;kpE zo~fRHJS#n)d$xGadk*6#+34Nx&G6;>{`M97^O=IJ`M>l{@m=!H_PV@VJiRj&2)*H%}o`)T+0?t|{up65LCJTq8*iD#Tg@+5g~x~tqd?l# zQ{R%^R(C^Q%eXSx73Vtayy`sRY~i}-Z01s3!(7dnEI88D(jDu*#p*1~t)Jyebsch! zbbjJo=lqrlhRLor+`EBm1V3-NmUI2@uEnl_u2x(X>$>HaMYskstdiA?Jp@0{iw=$znu*V)b4!uhPTowF+br}*XZN8*2smz-Ul?VUrM zlbx?P$2x~Q^PKgZ=i-avN5?OSUmX8u{MPtC;&;Vwj-ScZ%i=G_Z;C$=e~@W=vNPU! zp6{=S?-AcBJ{14J5sXibuNR*Xf81eZPG`ILQSp=be1H6w_|M{}$G;z+8$U2U5dUm^ z3$AGq-zENKK3@~RFTON>a{Q<9+3`K&z3~?uyBy_?BFATr_Z@p2*Br|n-#QlX+gZmg zhbO*fyepo{o%k;u#g18y{tn%7H}3DazvAK@%^Y1EUpr!}~Sj%T`G2Oj4S7bVBaGyBG@wn=^b#W8o-iezQcPdVG zv~VFPJ7T+P+hIFv+hm(-TWTw`O|*SzE3*C1_L1!q+k3VW+hktv*aq7A+A?j; zY;9~ITUXn2w&AwdY!htbZ3}D#wn?^^YZ6KqwnX*Rbl z)s|puU~6J)WUImFR@<)FA7Vd^eJ6HF>_q;3C$=bdcI=|qDconkx3HjYh?O^$srwtei={FTG|J!8AZX7XO=*c!3c*h?{IVot}L;@@*I z$6_wT?1=d@=12biE#^qfmdNkl$NUoWWz5Ey@i9fbM#PMXnG!QPW>n0Z{9X{#E9Qlm zr(zzDX%f>e#vfBBrfE#=nDm&sF{v>vV}daaV`{}TifPXONil(#yV3rb|Dtb3S4ICF z{cm(d^wH>((Z5EYWqRmEUPq$0L~o7W7F`~_B>Kzf_o5d>PmCTPJvDk#^pxnr=z{3C zqKEL48$B?3MD)n$7o&5cdqj7OZXDe(n(=(mG0|6}EYT9bo6$+p-e@J-h;~KSh_><0 z-Keusm!tlP`a9}$)Q+g1qe`PTM|}~smH)qs+RbYlzpaS+g!hv9=8I9stuIE+i)s@k zM-@ixi<%!bHtK_@qNt~%x<%EBa`PI%PexRysHdWoC{L6lDn9D2H7TkYpSYr`tp8cB zS-?Wak4zuQ3 zhge^>4z>2P4zzZ+W?CP$cCfa!wy?IgHn%plHn1jJYgxnAfE7_`jkVgWb}OUkt+y;U zER~jvmcK10E&DCMTXtK1wtQ#VYT3Zgddn)y=awaw&n$~A^DOf%?^|YB-my%#jI$J2 zMp^RtdD$|+(wCo}mTr~|O9#u7mPagYER8LxmSjs!OD&6G30OQ9zr|*WwOB3x4^@nE ANdN!< literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/default/moved.wav b/ground/openpilotgcs/share/openpilotgcs/sounds/default/moved.wav new file mode 100644 index 0000000000000000000000000000000000000000..1038fc29542b2d5b9a54ab25d39b06bf07e99e0f GIT binary patch literal 81292 zcmW(+1$Yx%6HO{{*R^DmY<4%Bji=sHY7~mQySo;5cXxQWKHMMvaQ6qrokEe~P}D#Gy-EKYmuLP$>8=C=o=#$5#opLX*%cv1n5A>1cCD!e4TD||0}C;TG(DvXRkBMcF?2rMETkrB}-qG3d<~FA zvVY{5$dQqgBj-o1i`)?TZ{(%OJCP3~A4EQj)JMsq!coGRgW4L)i-KF)PSfN zQJbSSMD2|_9JN2{T-1M2&!P&V%A@FLHaamnAv!I(MRb$sNzr4YH%0G=J{Fx9eJ)xj zx*shTl|}O+QWPi35;YKY6}1(07Y!B75^WHj6kQNSh(Ev?5XXqCi_^r};%ed!;y&V; z;u+!t;&b8);ym#W@hx$oSSk4|)=G-SRVAdv11BL-Nc@rriAIty{wlsFE{4C|FaAqB zSX@usL>v@{#d@(ytP_6{MT+-|PQbfe6P*$5gm+#5?>$8{S=3IX7S$HvA_nfiMSI|u z7onm$qG(Z~sGg{ysIMqVv_jNgv{AH1bV+nsbVqbiWs<{^e90q8q2!K4Bo#_k(gMjhiAMSx zehNwxq~oPiqzj}oq&=h~r9Gvaq(`L1(&N&z(%aHI@aTiIkt{|wRn|_{K-NN5OEyBb zM|MJXQubI@A`{3}@^> zTUX0ze`|hdZfb68x@s~sV$B`(Wc6=VNZm-4p-NL3R8N&nmGhNOC88viA*DchT`@(` zLD5f++a%V)}k@<*~F*;`quY_#l@Y_P1Ztfy>_EK@dL_F8sCmL#7jA1d!A z-yr7|H|2iCAjNvczl!#XtMIJ}i{7QR<_r0@Y7dqWYoglj@zyq7JM3sGF-PHKtBg4^j7pBVT=5 zteCGZ!(c;q!!*Ma18x)>s~Wo)`x%EB zBTb);wCSgDkZHZ?ys4MD!jx;?Zti3L+kC_P!dx4vhg3rbAl;E;$W>$oB0={f9NHC~ zi7rM*qR-KJ=sPq4TZ83d&#(^IRqQqP91G){v1EKV)&?JkoyQtruhCWL733j8B3+Qi z=9=cwrgz5nMzwK~p_ZYsAuL9C&Zq;Lsp_%n zkQ!ItQw>vnQ7u&cR{7Pex;m_yU+P`zZkjEc0=P~iw6o#AwrCG%BXym05xNe#?z)w_ zE^xm_cT87be?@mhXVhovU+exHGxT-zhxK>#62oxATth2^+(;Wg8onDmM!oTaVXDDy zs0PozHuN+sG}JU?8SWeQ8uH;j8a{Wf(Q9tS!UKun_ru5 znSPpXnqHe6<_)GabB=i~JXhP?+wA!tkt<9{9tz)f^tPROm$PH zIVU;KIbS<}~9|Y%Oii$QjnP7S{3u zABxw&#rP`hFt!5w3$>$<5eqs8F`&21cTFcvQ%xt0`;6s=E{4_m0fwOAwZ1zX?e!h> z-}Eo_mGotXIfg5+@(PV48aMK4IE#jz-GNm5=~Z2Cr0tR7ck#H;{M8L8KS_ z{2f-`IYf%)p=q$<9-}^^bBL+OEMdp9Z`iW`pZ~GtY@BPhE5|k5 z)!((o^~u$kYr>^*K5m&i*1dph$OSn)7v|2mhPZ<4SEdnjhfbu=Q5~pkhtXb4Vi3>q zmOd8JGMiXOe8wl>dOQ{TiJn6%p=C&4WTQFNT*K7N*w`pBJ~nhT)HN*8>kS4&bNx>J zHvM~jqQPiLG`J0E#w_C-qruFW4wyHYtw??IM)L$@D>4~*gX}=+p#LHLk=w`}cuc@^ z3z0L38eNW*BJ0rxSOL}z+l>#vpA)HYeb3;Hh@r$Md@VuYJMl%>X}mo?5s$}@VGeu& z{9QkMCB6w;j+bF?@zpp(V8lftlSm<~mK;lo<&5PqafEn}&m}4oSBOX=g4hYMF2tAN zkMN}s&87Grd>FACm%;a4YPm}EvD~rLvF@{Gl8wkkWOs4_xscolk4BPP$qjJ-i#$sH ziRgV>S376Vb}V+(rlwOvs5g$U)IMr7M61}j$*F`W-J^@0)#;<~Oa>gNv$1nD95zHiz8Dn9avwzM4_AOh()ta5p-en)U(z$eQuPd5E zx$az?`w&;kt><_?#_e#=<3!v@4&(N?o-+rT4|EPa##x)%=6GR0WqVCVlS?cc2p7?a zm09L?L;w5p3xQLhGIKdFngpjBKk$;0J@PYU%>=^vl3j95uPJF;C z6F-T|#12bu3u8^TKD72C(@7CTv^n{MoIqYCmylgar>(zjimj79&ECtA2|t9ZZ*XA7FU_;P)OvLDbkB6ZbmR0! z!(+oSqsr9QRN3q?-!nZo#~@G5IYBIHFYN;V~XKz?o}8$1&7#cC zI@A{maUOGaca}J9^f|gJ{eXT6d72OXP6@F+>>Nmw@cb!w-oOZ%&dg=z1+$1f$;P|t zy8eUOx`o~An&I+rGh9*JBUe+-#AR`3T^*siHsVUSx!fy=XGi{%yDneo#ywR%Yxy7i zQ+^m>3SQ$1F)8a3%S?GCmI9%x> z$jn?*4bxCVnf|)Yt*fQo1=#L3;NQC1u9`cVBbsu}QZ1|11F{>YTdtpG5F2|M+nRWD zee+B6Q}ZNa70zE!LpM2JLOe^H*PJ!!7}~`A zMK7gSKwWJMKdperyC5THGgp{@AP2uOec4;=9jL0M>^t@~OR_!LC9Kv(yK1}IyGq#( zu1Bs55Zjq9At&QHb5q@OxzXHV?u^^OyZM#%oNAN)4-g3(ZamH5BdU5MEqob(%OiEANm6YyVH8vOlh=onw2UwE;9Pz^c} z)=oK`74UA^7=rzaHG*>kCW3lAAM$x4A+h9Hwpx;{9U!i&tQW1dA+B}ccE2@>>vot})zjZYb2+8LmxSH?A1+ z?-k_X3io(-Eq5Y6(0zc{^XJ?%_-xNJi10yv7XQJmaF6D^+(1`Lb_he$)u|lEGMk93 zZLMbM4A`R$ToEaJ*8mocbwo3oGp&Nkd)YkNJPVLf43Z61*8;CM+uRaz zl|-5$cEGnE5j%PnJq)OI7F^-M!~n}JOFior%UZ~j6zgrMiXqDi=&geQlSUEM0o&Yw zYMTrBS%$60?!f2$4f$AvRl|aKGTwo3;zr^Y)*3Q;6Li~XY$m!F?SiV%Nl@bp5Eu0D z3c%VD%mW!4jp49D9^!iF+96A}Wum32g|iN{R#-gbSC};ZM0SQXnv5d&d9EKWH@602o6gOL==h-Cj^dPnWQ(|)P)s4mhq0hn=VziMI+L1>UQc8>cy(lz*FedJ5-m|TJ?AJ z9yP0#YjKz)+vsV)Pf^Bk#)+odCYL$iyx*K*7C;S_Ay)x0&olpH?hbL5!&MF;hs_MU zPXJ=G2X8<~E&VJjtQPW|^=~qtoKNnz*0ug^IZAA{AcTpS{Qpe61vz>Q;`Its13pp! zZq37+W3BL8*dHWNnOF|>_ZPMbe~C2(M6e%SgVsh{A>Yh@LB)7w&V~-a0(!4NqOpbW z8n>|O@Ly-}^~6cb6*vnlg8?NCva(hh^0uROkJV)@u%r>qElnU}7m{7|M@hrft(Kz}g-3h`jEP!l(pj~Szl zDTZFg&xU`EoyqS>H>YXuDLl@4Y2h~Y$ar1 zW0(qmL0`L%UqTUV9pJK~<}nD5-azid+*1KLKGlR8L&kH4*#@)mtLdwG8fr8 zb9dnz@)!6y{6*-It=xrfvF9lt;~DLF4AE8i@A+p2h6nx%%?PE16*0x(<1u?;Ud3IF zZ5mfAeo3M&@oADWr9({iTG#;C?>Ji5)ADw-Rb zpys)9s$#x!rjnE&k+%otEhyK@B4ooPZ$eDgwT92P2W^1XKu=(6iHp{qwk3|e)JcftcE@-7LQ-q(3mw1; z?86PRzI`8+OXs@&<396Me7*hQ;KE?fVBcWdKp)>kZ=q*3VA3s~{oVoIS>9#d0iN6L zQtq7VF-#|8xVP>+&sE=P|MS4npgcG|u+Zo5esWvgmt3`6Ay_G_>z=DQ_mdmOi+peW zCxVT`$+3Imuefk6kpwYz#Hdvx(_*Tk>3dsHq!j;|M=)M(wP_!6N1J%&{koa zYMW?Fv%Bnb;XG`gX!~ZJ1^M#^`E0sikm={^Mr&>;9f}k3`SMkYC8~qE4yH^*M5qCU z?zd{J*9j$#V!Mz7W*e{;t)Msdz}7&o{0AKjy?+4~NgNkcOuld2x~yx zAdU79wiUJu*2#E(s6?is?eSB1ExbSOgZ^3_u=5DunPLE| z*(~db?UqtYFS4^ei5la4NNsk`1E!#%Gm25WcDdEwN&a!c3n6D{K&U9N)xXTc@Hpq; z+QZsbx_@!Y-JSSD{5y9~ZVuOs3j;G?cUQQ1p5c!JSFi;-rNjM-`{bIy5^MuzC%uDC zW6J5H%rkC3yza^{!GY7_$&TMf+1;i^6%t_DO*$fr>?8itx`C( zYo!M%$w`~SAKbqkmC)O&e?^TV&qZWL=8Miq2Pk4yEmaMbH59{T3q+ZbEu%CMN6Hly zzl8%TCRS7t_7>JEdsJ4v;!cH0&^F?9R5Q_aNe9_u#Zs*hJ#Wo)iaj>}PJg|C(l2-a zb~bT5wZ`BnaIN#P%0veF+^(T6Qthbsj#5XFeTY5Xe%#T|QP;lFj*t)WH-MKCOj^Ty zok7<^GetouuE-WkH^}nk8tok2G}C+2aP$Fs8NF&AWfTJI9j9NWMPU*iW{5MLg{dhQ z&IHq4(=w>_1Mnf%_qJA!5(f^m;!gSyBW6F*!<`XSE&FBb2Rs>gli}vd&lX#r2k>C0 zz-j*x-y+XCm@YSSYS&NZD^rtJ&=HIu*rM;8!_&(9*=SpD9FTogi;O<_?^d?noHyKY=TEF|_NVYoTYdUmRQ++7vz)+8P|`d&W26YQc;sVK2Js@%{bT z!3i4OpPucC? z9m;BybuE2a-23;mGK1i^u$O3_WQdGYH#T~RsZ>jkDXfd17{4*r;(y0-_RUzP@r5o@ z_m56v8iby*NF3GaAlu$0;u2g3nS7@gxa~vsdiHmg{`gX4pCL;3P#v#2sN5=dDz-}- zOIC`vOMA=fs%sm1Vo6qs!|$9-52DW5wpiAngAM;`4l6y%LrRI}s&0$%kohb63j0Zv zS-j*%d#S@@FS7`V6XS??mTABu93*ITtC7$bXtsl{_(mhwt4um{o5gKE z2wd%CsLN(z6!sqB%(YCzKzI4WJ*Q#m#3*u`qXF~K73bc__26o{l3m&CzwAQpgj?*Z z9mor+LfTL%#EbHtbx(82*b4d+J=xWmFZ4DD1cEC<&4Qf+y1;AS6mJ>KBE zr<(o+-{}go68h@~;PqtCZ|8EC0Aqb|?R2l>J9tZi3&K6(nk0l0+r^)X*%&??ZXc={ z+8*Oen3tSiDLPG_d9zC8suyy$R8OluC#Plh-jsdbBJ#IpNyX!DmA`cRwCD5w(nsR+ ziW?f#eA3iY=TtvZBuD=c3=!zdru}+Tl=3U@N6+v1-W%6|b+InpSQo8so5hH@nSA{~jDLuC zxNpC=KCf}Pnct4SmTkxpU6OjM{HyGlY=-Qr?3T2R^qlyXXuHTDvB-0^2hByqUE2_t z0_)k&1G2lK?jvmw-4!`Q>uFE zFY0lc$y&Rg0JFCNt04CD=AV!$?@?!Vx&R2pYd+w#=v=+85=k<{uGIhDHV|V2a80-|!sa?cS;Wv!T;5`lP(n>`ZZ$=T&=D zSJilwQ&jawMsY$P_hjUmWXJCbpR2qpE7bn72$N-dv^07XE5%aHJM@2P|CP^(9vk^e zSX4UXXTzVRMNPlA_)32}`hCvNbHCpI-Y@7B-B_|fE`aKI8@WjqacyFxiG7kkC)wh1 zyt^F7kQSO^d4K6bd9u2fQHlR$JHev9$AN0WWudj9X@SMQfLqDNQwOZsNRjTXDkz^U z_Dgz0|16Mpku{Oel-a=*@JTU3ci8-t*kkj8#<9eaV9i0K`WcFifZJ{giv+^RI^x!f z=~{>BFMI)6hg!=#cJ1e{@@x5b|B>XS(z4)Y@QlzMp4JtgtS<5SqdytZsdMQaAn#c~cdUPM8H^CiJS+ZW)+t``7 zKyCG04@V>nPkNN}Au%hC4{!5W*c_Vyou{$NGex5!+e9hE`=nMysj`;(rgFCOm-4at zlXi-UBj(r}IWJL9?K*2e#HT5gc8(;p8jh$DS zTvsWlgUPa~r;4YsuiU>nG&b%~Lc5gum8Pf6PcBXn#r+$6dPoWR~v7WlFCTu^p0~5(eSd4oK{nh5~@4mvX^d9qhgL7kV zCHAV6m;O(dzsl^YYjPgt49$66?O4?sSv68G2IdhLWaED?DO~WZ?AenKpGq2w`WPde zE8MGG!~OlhldeJ$EJh9@92etTap1SW;E>##qNXjJe>=ii=O_pPHSjNNtzCqLLTU^ zDBp;55g*H1{9g21S+P*ah^4Bv1_!>(<^}vO_l$&vy`41<;I01@uZFHNlss4e!t8oC5gI_0R5tEQA`ZKCIl9I@i6-~;!l@AlxqTWka zs}~s&EQ?&|I0Rj6p{JUsHvi3)<|Hk*jNLVZ6iwyl6vK5!w6*mxmB?%dHHu|6JNJPu z_Lx%Av9ysXb*iX`wyl;9XiZad{de_r^;310W{z&BewpbM5{qY&(N3r9vA1?$Vz96O zjQfalwN;F@0p?@4`7EA6-f;T3TOL8+-(c;KHD*j$5`)IRj(Hd}E@oQH{m_5GSH4ou zL4F6QoeFnXe!Dx~oeQ|Ry{np=^}h3eh!MrbCSFaL7XKjh$~VESU~{Q7Ky7aveVk=9 z>+0os=#BTQLN#J?;?E{FN-j@MsC=;U*3=u7YE>Rqd3~iFsmIdpr=Ly#m2o|dN^Ig; ziQkk@FI)Ge=KDGy2mWdpJxY^KY;|NicH7=qsv)?>EXfmQmt6l+{4V)b;F;#R?B$3z z6ASe}iSnDGy6Q`Y&Sum+*O;L@s#&3R88WbtV>o}+H^vwA;A|H8!86Wuh*?HWEyLj_8WK|smhZ7Em{zHKVo%6VT4tbEghr?XwDmkp#jT4o0{51)8GN< z%^I0LjslAfd8!+z+M#HwT%((XW|A^`5#Y3wpl|GSoo4fZai8a$0lf_+UjU25qW4Wc z<5R;7!#=}S<6V>4yaZ_sOmJo5U&~6{NM{FEeO~SL@B>`Q)CKEfw4r&q$%+VxTjVvT zpS$mE9*l|U6}KB$frx}J@uTBD#Ow*-!O_0j-X#9ByTIL$U*#==Y#$mp<8R<&y@ZG3 zukfF|-vTp30y+5!t1qOUW@*mmwI-n0IUAQhvCUyz_lx|*~t zac5#$!os-OvEsNzakj+1sdch;XRpp_P;+9n=;X_;kA^`}Rel_L`zn9*r!Qr!tg2o_ zPNKh1D%&2b2Iq9S(p?ee(u&W$^B+H5_Jn!5`+3WPTVHql9vq#gDln?hIwr62mIhVM zlMhh!FkU4F(nmdK{d>I)xy|<8_$AZd;FOzdv|yAq$8nKq$j=PW@&07K5}A5BbxGoh zU`^LpvV&oktZU@Gigy(qBZf($b&-&Fy`fHiux)?|B-fMzTEKYYMq_8gaNSZ>Tg549 zq{Jdx9X(hqlsKe*c~@mq%`*KWWFApylhavT24Kh`d;?~vy*GATpQX%|ZIm@r-P2FO z@7W@lZlFZ&aJO~4xhpP(s|RCpHn6X;4k0R|L(Mf!Ta0!^ApW?@>>@+r>1rzr*dwOtT$%h?ZLp+WXTzxPjhhfotJf@#chz#9fIM@uOm| z1!?~yUd&~)vp@l#;yTO=eGLPfg5ltWz!skp_=$y{3_#8~K{gx=zX<;J)#0zW5}A|E zd(>Jg3bfg_bP0Rbz0$h|Cf57$!lVVsS;@VUhXCrD5}FgRLQS{%&xL*^EJ^K@<*WXv z_Sw3LwPUNbN_o%L*FBDy^rP~dnXl@6oLu6I9Hq%1CfHWmipezcIXYhZPBK6+=hyMV z`7gFVIq-Dg^O5;e3fuhR1;<2rs%-sg?Hkp6B`WVOK_s;lcl1Aq0d#>!7&s94Q>ik@ zENr!5seX@XE26<4Syxg+T^4_fxEd)FQknEemGw!1pw<<({LpolEs4sEoCloNW@U_N zxh3G(4Bo2|_5us&C&ttIfPR7Qo9>aeuWFE@j?5r?A?YVwD_bnLDe5U+$e$>lDzh~w z^h=T3mL(1WgMm)9m3`-!ZoOu1qxC5DvQqgeRhIDvR^L8{xyEha+j+-%X7S72Iqv4{ z7plLFw4m5E;Qx*07T~&w!BOzMTn9bgM4Sbc#{df8ahu$k&T8G!o~iC#t~bsJHUzrF zcJSMrNAFq6Y$0bpEAtEu91cH?ZJ6*f;bDBQxQC(ZJ|lmbdF^~aJ)!bwF*nBZ(Z3+* z4L1rWhK2=3`Sy6%cpctutXFncKesc0j@+;lPgFh;2dZ0ng}d`<6ee}}+5|0kFjN?9G%$C8ZiW3$`#*e=?iQZJlt(78|1y_{?9U#$*cW1`CJXJ z6wrk_zHU<8q;3fZVw(jo^Htc#)OvfNZI&H#X0s{$Bk!1C)37eq7~2w9g{{CCw)A^_ zN#3vgO7{cTR<;HBl3IY$igA(LELQ~A5h7cUcX`_dG%+{gjwB3AN=lj@PsaQTi-VuN zw>{l_&4Wv0R>j{>8JQud%H@2@5!O6a?P;YO{2lzQoGootXep@w5r*0Fpj=_P3oOkI zIP}(3vr};Y0V?$P{n+h@s!$o zNOPN*>BRK{6@C@9kerNnKu;kw_?)sWO4~cfGX}CHZhw*@)sbGB)+Xgf_!%#8R6}&? zO_Jjxzi5-hqAD|%So%AbfWuBf*SGV;3DDeR`ktE0YOCtDe5yt|h{gC!F=Uq2A}9 zR4U+#4(0W(Hq;675EgB2Z&+vOZtQMO!_HVVB#@&c{WL3vmdIVS3J1=-H#*{EJVS0S6SVeF@e~4L0Z6+Us z%6`?plpe#4^i2!7V%x?&E|L?^th>J^%ORrk3q&ipgMx6z9 zR_0)p^4z(mi0JV@5(@r)`JrI+_cemG>M1zk`0ZT4j$*#qeV9Ze7WMgE{K@#D=e=Wj z=)J8EiI+D%sDDX?on&)$n2|HMbU)O6Re#H)m9^DkVLVcKeJ zWh%#1)*kjb&L&)HV0MBsbxwvRYjWn(O6y{C-6P0C{SCQB%tiY}vC_XaT6BZ`8}pa@ zDPP@Pg)Mjdwm`2lM(R$e4$01lyGO2wcp3RD+9MImBb9a326ct%g_2j=RXenE3}4OZ z1WNMu%l2br4ZPU6M|)7o%Sh=AS%z|~{sh*~wu`RMdwnT^@j*Pe%OCVicl~xuu!Lb& zuc_Uw?W;GN4Ma`b9*Sq4f|KEfGm&cPxNP4A{i(I>kX`BsIsUTUAO~3+f*$`GbYwZc znb>J2A_COxR!nyDg1Z+ zdqQN)zR=)+#y==P`7uwPCnI<)d@*)MVj#_1<$6`L`ny_bbq3a`o;@|i$Y&Z8BgTB6 z_V&n&18+wE+!Iad9}|t3?e3$TkV&-`UeJ*{I&T4XB%rO z>NT#^R#jD!9TPo{$Po4u8Y3G-2cQ++m3RwEs1H+` z+G~d^^Cd?`QqfDvM@4`AMoi||3UlLG|K{M8z$E`0&rPmB-IEky7Yw~Mmy|12Ewt5) z=gqy<$N9GTBLe-w3GvH!&;P4U1I zr>IC*Or8LK^}H*Rc}dPf^EI=g&z8*kGWSJxUd-)Icb?su@nFuI+#eGv&Pea*lfgma zHgD7&QVx^xlJnwQa-r_LsTp`6E}*xJjG>d^f?%1gS)oazgvjbsyUEoegVF=s+6{V}e_|Hq>SU9zH*?Qi1Hg z;=Hz=d6Gp%^=Esz&v+(z1HM}x1JAlXQ#$K*BwMdk{n2+{X>J)qmPSr9za13r&B3$& zOiulm6PFda=jilH$|jrb2Y1d^Ow{yOy%qI$Hm=lv_Sq zi|keDUfgI;sc%SNT<~XLoBv;5HE$(viDwb`MGd}KPaSX@zJ)p9&ooSj6fs$GI}?|u z#HM=Fu4S~%cIFgRKUo80a||u~&oFy8O4`@w@lt(gu=z-C^vqwJ-kMut-%|rj0HV^c0R0 zsX+xFsO5EkY1=`y%Qt3W?X8%zl{*7i)(74W-fI5z@SQk80-v-faZaqp`@%V&XlLNm z*Od91Z-x@Az|n=j9?p$#oRAc|Dm2jhk?u;)L30gFlwBlkqRJ~K{61Tj8ChEvr6Z6E z%MNf@8m%I69BKTwL?&*5J!o}L^dgMq%jBh9sbeb7BO98uY|V+ zH~6Z0Zg3LNH@|^j@f~{>oEfh{C7cRM02LpbC`-JQv@`Kt;*o^giQ1H^sikREGN)%h zshVE3ag~0lZ9;=>JJs<*w5Z+ZbzdI;dK)!br?L*Gd~Cd%=Z-nAlcUVh@(X46J`a5U z^1pvBD=rPV-tRu1KmO}NA*UXMc7)pV3makRpgbV%DV$cOE1OV}AIVFG$?7W~X}!kQ zh}criF^g&Mn(R*Dz3^=ep!Cf3wF?qZ$5n@=I{@nx1YvZJ*JdBOU{dXz-L(H%{Wv;4*g zBmi2lP}j+@4OwHg)05oudri4mwg`D{9s=%+j@JJisSL;4{GUVX!^Po`Awl4+ zC)cH+3E=iB*^_}Ie&XuumU$fBNuG4iJidpg0XRgL1IxdeGjnypBfOoZ!0YzFrH98P zJJR_M>@v%3S!9a61N9HHfZO6J@xAk}3mgW1>k?>53)pEi%RC2$WmskOQnGW&4;!4Av!hCE#boUR5=PT!>$Y-VIr!t>it6Yt^Im{AEhVg=e72N#p{-AokB(LKg|3l=3_HEPes|EWMh;bEo zHQyqv!Kp}(y#0GyQOh3>e*FDAIbyV^i_EKOq@zsx(K{9jkm+2eDVxUFX(#o{o=uPA zR)fbR4?G4Z;QD-{fu^ozDWC=)xNAG2UCkd&H;r+?RNci(Nj3D?>EP;(<`%Q{ znSIoA`zW%Lm9RX7Js>B+d0OVE&zyG0_-BMB#7vF(7Ooc(`)9bPGM^l!HW_)4R5)Vj zHLhfSwfDNOZonOw;4k#=fmyoCcaVw7 zn|>PiHM%&X{HCy@IH($CC_si25q1M~sRDKmBd6Qj`r_A!zK&|Ng1yT5eMP=|?l$x~ z`)HWEAA$q!0Wcx^`L2QEG2yr|aSuXs1E;+)>?WA0mm|9jFV(o}rn0>{QkRXqCWGuf zcbYH5m*Z~cxQq_d{g&?)FOC`;IU#Dbc)YZcvWI31D6ePn^VYVud@|eO#K$3Gb9x`bx0%BT`Lx&f|}67(AvODAK+WI4t3QYwk6pbJ19EQ)tPVT`w6~8eP|4L zFggXyzN>sBXN9@wl;bHVx3?Ve^a|jQ6p(L*P#EV<re+ZomfO*_M-*XxQ<3##T!9wVk)UAosxjx?`|=LT^0}yLsl= zS5iyZyY8btL!jJ$+?V6+!#No@m1Iw{RkgKryZ{B_8DH!Z1$%_Mgy)C<3(g9x^4m*)XI@y4q3zK$s@VRdT^Vupgt`wgs>HMX6 zew_!*-Ta3;UXJ*H79)}bQv{jq+{ZW^iKtxFFKT(o_^)||!#`~PH2dd2r6FNUsb4e2 zbQXVZ&v$-hDl^rg$9*Sy84ICXZZtnYQ9|r+GxzCFlz^&j55dmA9S+pFl)mIT=BeTD z5nK~$7wF{0Jw3Td=US_P=#SJktk<1_eYjIh4T;Lmx%_zl{?PqUb^mgAmP3jy(>76# zllmp~CA*{x(udph_$Pw1eTRy0?6~tg2kE)N9j?U(iAL0?VIW zhn=kd5Gwr7o`ON(pganG%n`swM}Rju&vM(6Nyge1g8Oj}(bw{wz{#C9A25)!`KjKA zP>bJ#XS^PB0{mJixrKahOQIr}dE7zZD@uc(LodRgLsLUPAkOdHr`c;xH+Xfw*q>7x zrVqE#;|bgd-U)sU)bN*jPJ_ZOW#7Z@t_`ryK+o9NZtO|!jeDBA+}#U!4h;5Yt>$aE zV}M0(<9_eH%s=BTo~=+1ES`V(AeIerlFrhnxrf)+*pehn9Xct82`hM)gq=`5h5I=e26CB&1-_?_!_G#-K$ zw_*i~6)jfW-MwgWiWDfW#odc*ad#`l-7SIt8UAmv($Fv&dF9AH`|PtLvv-cN;epuG z)=REvHA`RPDdyd!U#Gg}x8#hDiCPvn(AwI5S~#X9yKfk&dPB}|FJq?XoG&_|dgAh= zAw;AL6YYVr?pm2iXlRVW2Eh#^_AtTc{Cl~15kme2md)rdM4M>=4pBL+gdg)N&BjP(FekC zyGf;Jthaz?iQ8kW(qC&U`KjOA%fBaKE=bkQw7=2|=V_B(D{X3O?v$NLYQjAK4YI4! z|Gk?dV?I~jV`;4FSzRNHXQ?E#xgl&He<`sOzRZn5>BVT`5K_e4NCWWW$NiLo| zGx>bds)ROys{UXH!*Bj`zL)+-39VtyPD}bB`9<=zKFW0{D!aXz+|2ttp=#opz*T=IeV}kMeo&-4$B_@& zU-o=h{lCR`Pd$16#`UFT*i5roET!F6W=b<{FJn7~7RdVa#`ZGnY1;GBudE*~WlacC zVg_3KiO02t?%8xAdX4^KANy6)4^hX%(j#-neQ#DBP2{o0bWb92WFIQa7P}qkE%&T_^R-$Q3p&rt)ap)X@K^( zZZQVy71bG14k4TElsPqi1GWA|u^mm_&7EvToo~bu>O$h^AB^()MYWw$Rjv=OXSwu` zd_i5Ux6^wYm5p}pn(j03qaS;Q`~LIYq<^vj5w|^MVoJ_538dr60^wD&uLMKhnRZ)=!E`xaAGO$H~;?AL>io9eirSuSxk*=cT<%3rT;T zdLX%C!dc%ePjUBA<1am%k;DDm^S7@|;6lQ#q>A(f+0yD`=SQSgrh{lha>eB4ASZiZ zYyO!xSo=7caWQp-XOBZRKZ$9S`*_IR$mW)|LS>^gNV(Z>_$Rv~q__5SahG$aXV3rX z>x*m;S3WrUpMn>Iv~4_O62y zx|^H!796^uYSuOyed%ayPHbA=bJP&^8vHy0pZ>FNcS3V2w>jv$@q6p*x5Rilx|-WR z5@*kM=AddnSShRpyRn*jOg!s2ZM@jPvC&dHu2l4zs0J~IO+VXiIh%`zO?HsxSxc6}b;vbmZw)&2PuFCR3^_4b4H)#{(m*Q?AmoVMY%c;A(vQ9;* zv;G792%p^bdH-3SJE%_7_YLv=3oAa@Y56`-i7v`%NxSI$NlGjl@cVPq!`IO_(jQ0f z(D0=BDc4d5r>;+(kn&sd78DEO{q231JR{+o{OLLBokM3sZ+NgJsHcodeh6}R-9L`C z=#S#XNwu|26~T0GPRm?rkB;tMhQByrug!M{g#9u5>L=E`#9mJz)+usoN0|`pQoO0AT`7{ zi76==sh3kHrc@*w3ro6-RXy+9;w|bufS)Kw)-^UUGieDNfQJ10oa7>jH~jy2b9sxQ zsW6Pr&@wPUi_($1CutF=cS#V}huHeiKwg-;cLLi3za$q)6Vw087?aP)`$yht`J(dv zlw$Vo7BcA<=n<7YtX$-KYj;-*t*U=w;2l}sG4E8Ronx)}Zseq#Az#YAFaNaR<99EO z54pc2hn9=$ZQmx=QYMMj?Nj5j!Z+sVo|XB2$;;g@5?&8}zxvbaucLCSa74C>CzaDm z7qzsK*Hr}uqbu@3=#$)iqVC3wHK{~gmDHQsbiKPVh4?edw~7(KF;cNj-5b}W{&)woG5;vhuQ5^9c8g3Dt&4j#Sv1BY*KyN1o&1D z_3y~l-e_C3xBOq65kn95BVS{G3QUI3Ks|hm#oNle(VLf_)eh`U=!;z+o!mcVJDr_9 z;mh_*Y!&#$FZ+J<_Vz&b7Z{Ab1iLR+PTz! z{5|Ca`!Ms+m~jz{qWi`dan@2)-(BuhJ`cJb%2?-a^OYzm^i8&}pDw&A`0VnFiNs?@ zuKiIi>nPVTxD+4kdrfU3(sF(Jvieh(w;NwKd~5nJB(qSCd!f-W=ggvzF6~gdsy*e= zPLr*?Xl?p$~Ep48K|$2G?_MEXm4U}HJ?jZf~Co&nx?*r&m&p4V8Ubx}_%ci;s-moL(XJBcp&DasA) zncjjppeUVMf9O9cC&V7krS=B4=C*nE+(IoeRr1qMf0sWo>K%HqGoafppR&ni=deMh}NM0q46~7l=(8t=z@fJ0KbFl8;3x{33#j)~9WxrZO6ZJ`2 zytWR`?I{#)T4|MykM6DBx^$pirL*4TKTgDw-P_gkALz(&Z;XGlzeeB+Z0R|~`G=FA zC!Zzjwxe6p#up9JxYC!49_{d??!;mxQkJIVOz|f7PV5Tix*pAiDs)$vP|na$BpR3K zNj{WZD7hqf-xE628q&+wgHF^wiMxmk`=l+-xSFSPUXhB~>^v1xoBGR1e_0Efjzkp9 zeKX=te3qk#9PWAQYeNrfG4BjDOL$>98J!y1=Vapla$utGKbIB*V@cB-@e&7(^X%(N0h!uJEw2e()C7ayj)wb*}s~*n9}1eoBGBt zut<)EV7RTZR;870@(8KED_l5c?`nHstpy*gp-n;cW3_9g^gDaLNb5+&`U$5mNqHi5 zlLPWQ^8V%Ut#hDZbAmqou5eJcx-;Ehh*+zjd(xBlrqj2QmgE5^Z<4$ue(Wd4H)7}(P#J&n2>mi&J0W1>$JBphtH&sPpg@-G_XS7A>6cNkAHz$U){LA z_L^e2-Uh_|PqeVssu9vr`_lL&k>x`7eszBQ^k)6*@b_VvAvv?cJ*JM1h2jY@NjONS z*oFvOh>%^*9Q~pCyXEh@d@7U`m!oyqKe3l>#l^PNY44(aHQM>wQaHAHM8({_a(g10 zMwN+cYMJ0XEge*sQ_tA%5z!I((HjOgCrh%6B|$$<2=oYRZQV~inQ$+H=v)V1AMZBr zI5+~gy_>Lt^SzhwkkirG%HuibuHjB|S2n`+E!fw3_|?kBDeTBG?{2!Pi+FDuvTBo8 zx^6me+27fZI2+Lg+)+AAWKs>Kq8~N8)&}lqS66*Ub4v|0ME+*y|1@v2{_LoTRr@0S zDBqW6NM>=lkm)#ND`Bl~?O_>bDQPWW``0cA$Hhakp$5paeVT_3=c4jWo_)HMOR0n^ z#~!^kyWPRpZ^!)x@Y-f-8e@i|)3VR*sk2vkVOme_)P`Zk@WAJL*Ji5|lhf29P4 zPSZ`~*u@fGC7w@8P0C1`m#8E)LklM#cX~VBj1}o=JPr~+JZW3f7P^m@CjJH&$qq8} z**6SyW?5himY^NoR^~hlGM?oQQ{y=!WV1Wtt4D`~J$d=b9kp6`sF>+Pii(;vN-oIG{Hm|ihma*jg8`fpTH7C*4O9ELyKyJMUHjX22=&nexgvkB ztQY5^Y?s$D)7ISby}7(uHvdD1>m7S5;gpyIEH+*npmkE~DeXYnL#V|3VZQf^FWBq!5;cI*pfLv$76wcSE#PTIf>b<9 zIGk9Eoexh+OPY{)K4D!#xrE$-0)DSQ(^rLk`knnx0FP;!yc4a5_DL-h)r6}4!M^u& zARnZ@dfzuFa52F_OgI+K=+L}pGUjJ=%R4g9-IR+7Ke=_+2FnNf%<{*qHuZMus^2>$ zuo5Mgh=lz<-54P$w%f70!yD#mnpNdP+4ucE@BTU?bYD~v%NqKeWIa?V{tP$^6*D|EHpi;Ii0g&oLMIOKWmu@S># zj>R{0+z>a(Gt|YJ+h}eqaBF%wwIYfDMV#lTbqp46iC5H`?h@WzzPTurxc%?F4?Kc5 z$+zG4kyHH|Rkz#U?7#tH+s4?c9dPY;>Jj=mly7umy0>08{gQ|2{QS?|K_5l@P+Lq8 zw$d^DMc6=p`9ZmW8jezq+4x)kpj||b=76i5;|MqZnrWt~h-JQ|xxIxmsH62z>Vvvn ze)QBz3FRI6ZS|~kEPKs=m{*y9 zVH4hH<@H8}8Mi|~>WLX*{96|l(gWwcfDd+VVbl=ALpQ5NJVlg}Vg8jR} z9Irc=WjeK*FkemYub!${|FiC#?kxSW-px2_yocwx%hwhaxE=KVUi6&T^Q&pZj}4vA z93!30ooifSQa$BgWfJ;V`Sf{O8|{u#UaBpOw>P(3H7$vo8h6F?o#mx1))`B;)j2G{ zIW(R^g@+ESJrnJk=sG7tXicvS9@R(EFCe%YYudn!@m|wmn zuOib}uK#09a674yO!9ukW2tBfCcDcJ13dSHvfn>r%kKszp~4dqFrkKa)_3h&6jw2! zbzlj;VJ1HOJ?cC`rJmY>#wdvxe68~j2;@t6LbWA5sReAc3h;K%u}=NG+9;40^vi=`|-xP1xg0*ISE?oQ)mDtp8ei+w;|IayhmkH7W_sT$E6tUKCugLCkg(9#}do)~SXYvz}1 z?>}Gol#%)G7f%jXXqBjX=6#N%;&r*M(ocEmI&3c;A0DHI*9#pJvNWtfRPMNWmRHWh zaz7%&dB#dC);{)XmHM;vQP}HvYI|@0&e>N)FT{O;Zf!lGaAFfWFixUAcEp?F4a4F; zGX|q1IOv;h*&0t#7%b!Ip{nF5>E2`wkLQ%cY4p4he}J$WO`^B8fukGr1!9rr}yFREAw{6+26bN)L5D$X_X} z{wPlaPYoje)nqP9-G|U~Y6{Dti>EjWKSSyB&cp{VBhvrm`|5k*KZ<_ZI)B~3CI7U* z_`qiWYX33+DDL$`{QE5w5%2nfHzbwQJ~>b%(aJdp#`&ZDyM4<+2Z9*bP46(`!#ebF z>Ip3p2g8ZdQE!TA?M_EGNmk-|QDP=CIbDz+s`4d%>ndV()za`YV#@5_fkqS*Z{g@r4 zrzk1TcGj{7>>bdb+h^`+*=T8O`@=C=xQ$v$h%yib#oEM_vXn#o1WRKwT|q}hi@Z(g zkM2_{INW}0K?O41|J-(Wn0q9iu)RJ8%<8b`kawZq8kh<{?tUOg;IVHCDy9=q@fz+s z?d$D-;$I%95opKlS3tF<1pf3t_QjyCHjeDV3?u3n^w~ZKj-$61^efNF`p)|{dyBCq zE?*)yL;^J_z=?QFmA-G{y`&>}HJA z3=YR2_d#Q|URbNEgro7$#8v|puLWR&g;5IH7_u$wOk~-(4VJu)fvDSkb$qb)G^NK_ zBXWd^p-DNjvg&<#f~tA zS*JNBh;!vNYJ!$W_ZnU!Oh2H8D8CY+FNG`F9J~8kzOOg($iA1}qJGV<`u2LxxVK?d zbGqAc+nb=iJi_Q}SlxBq4N$%Fp&(k*J&!2iv0hr=hl*uWJWm_90BXDy>-`!{zgFTx zDsZ(>ju|FRmWsVw`j*{lL9mSe}N|ygvm3T*z1U2Lq+3-|0K#)Yy97NWVNBxT)g3&X?x^2 zF7}Y`DdBnt?o(&AyZTu=3$yH3YxDTaF_R*{%Uv}jBy1xr=E|m%);?%})fWD66tI zyn1yI!wK4L?p{2M?+@-#)RIQwi=FOr`bI59YoInET9d#5R_e{Q_gY@{FY?xS)Muti zd8Im13wbJh)8#0N^^|*}=r&(=Nugp6!RicmB-jtxR@+Y4t2%3Qrf-w`^^k|7klfSN z53Qr+j^FK%Y-4Qk_ICEM_Hn3#-u{LUou;mDs7>XS#Fz(RZOudhbTjo{Ct2fBaKg$) zVNU2|d|W7*ZM<H(^Zg|VX$9M}aYa=s$M`TnE|8O3? zT))4x&w}dh1s=PV?Bf8R`We~w!*BT07EnFLKM_@llyEBh0H&BU$ZA6uY1VG~b@b>W@!|?GqgmT|Z_@T*>&H*6Pmb zE(?5!Y#_sHP^dbmERpJn6S$M-(Zk+^_t-;Dc^(y-{hkD(uqk+kF#QC|;csBN)X~eK zDOU&RWcF661VVna)D5B-mELtP=s(N0H(NE}$42%1zep-L7mM3EPLt041_$WG4 zgQNts;@T5KbOqg=r7BQ zc5HdaP)8GIJ(QU{bG~NF%V7u%rvBea+KiU(DA#ySh!t)?2smc&{GSC)zGkd9#u^@@ zDpkkMShRR!7yjb~2;)=FI1q+*z7yvy9`YMJ9{y9HYcck2w>!2vs!r?m|nlv}WXe z^-z$nDG!ib;zD5yI)c@y0?i>K2vx$!9&5YTkwLgYks6~c|EKy~-L1Y-H)#Dq?9ZUn zXc%?fIovLHE_&u8^rC3~_rqc=)arvqRx>Uez473SwMcat93CGLL{Rm7gIrrF1@`-& z(nQUx4ptoSaUbAoN~0P+6ivl#_T7#*)C*3)K-h@#=V-Z?TvpmHo0TJ6}QyJ zYeltUSid1CH|IcMTVb~&Ve$?4pb&w_8HomLPs{O-Ti+DWKKp)qKuI+g^PM$8VOp2RKRuC@xk82c~(f1j>^5XVfqxkiCPk` z9}9L<)#fr6HVui{5S1EvB%(@`46EL3*=*16I0LRz+@8xCPtEQi8i!wiDTjymitt1& zjQ%Hfw&|gHmhG55s6Ve-DudK0}Qk9osd z?^pL>H%4pswfDNscw#)$qm6vn@5<^srH|YSo$4#{KXN|x6E-V2#~?wQrM^cE-#~{u zRccKn(ir{r--Sw8z1QMQ$-v{Rmre4|(i614|HhYo!Dhre$IxX_TKFi80@3^xUG}*= zrWy7nfF8U>oQ2YKS7tE07neylKt0N)3FhI?j$R##+~AA7c-F}sz@(@;Eu2kpXTWZ(<1C9|+Kwr^F81w5iURn&SY zm8OG0Tp`vjLrgXW&8FqxpCMkacOe-`QSTk^H8_J~PA%sxUt6!JcTnf5kyHPR0E}|fo|y*Q2EW`Y?p#Ud{B|riOT5#=O4m$7^Lf5RmD2u0O^X9BCRHpNyo~J z5o>e0CWsBB?&uz0lY?^^GSm&KSKH31XrQNIKZf85cT>OojjDA{_bYJqhMbD7;BGo- zRt0W#S5${5c?EQUZ*UfZRf}K_mJ<(QW4~8(maP0FSYdy|*KHmVAlm3k?vo4~sXPAm zpizgIV+j)hqCFb<`VK6~OXfaQL04{{-i1i`g3-xc4}GYWWY2xQ!|_oc+-t}aOEXm< z)%_a^hSA1kO;Uq1LY@$>wGq>#6`(hxVhYMy)vt}h-b_ZfeC^N+xnb_|BE?DkH9N4HP#pon@ogMQV?_c|4ZnqVyMMWto%#CvhXQ0Sxsd zG0qygs~2c1I2ZR}4;3)JqD%cNJcc297TH=ndzQlPwPUKy5O;>>Gkm75~XV_Z~dUW}=c;-shew-X26LGl@Wg@k(dUHmYUSi9(9NgnP|n`rxHT zdQPHHpUesQn`osG&#O?!-@|hU&*UU3!G}0c_sOtJ5<6ewXBEKPw{va}8*j9=YA(>e zx1xqFtjAdZOPY>G=-+(CvQka*^x*W4drV-NY3^*=6L&54pV%s<>hZ(Oq1GkVBepNL zs3bJD@Ru?i z?@&W~O_iaxUKGrFxE{o<)AVq1*P=wcMYX=<3(YwpH?&pkLOpcg6Ul0GX+u?y+EI-I z)0m+aQm4ZlK7;mKI{iRbK_}OuNS(>v?vnoHlzz{;?BVad=&ajK#(NwaS5#c*^7DNb zb7Hn(`xH?9!O~u0jbWUT8LV7_TuH7Wca^Pj6FgKhisieMJnD7zvAUU0(TnQZW|&uX zuzVeeu!8KjO~yJSjkB@Sy_jgTqNmaScCa|H>W}Ef9U(FukCiCmo$cA>8Ro9*sf_=b z!DODV<^~Orbs6Fv`5K!y{)V5xhXK3wV(7Q@C;O<>2&hkS4?$C!Digl zGB_VYxRooYg~l6k#vfoF9rQo+TiP9LO?H^3E7a-ARwbG&R8=dhd$CN}h-tg26;aY@ zr<|aU`3baQ3))E0(hc^%14zg;)}kjf2zv4LMXDz)CQ5ongwc}BH4p!f1}RGGhtbh5 zizj)&v;0L~Gzk17P1&aGWa>}%Z*zWXa4v#Th^B|?t9jRZ;lzwFdVu9!HLe?1I3WYr z(^^c53BgvBU`ot!PRs~qj5I|j&<|mXYtm9^_oloih;ip0e7=29$26|BR_LkUc%z8#ngxE&K0POw*m(e>9Fe? z|5N<$aZOEKO#R~*;%k}`fnLXMWG>&-xEry5!yW8kK5EH_k9ulb z0>9vjZHCQbdtrHK-DYhH!Z5;dg&c7an&@ws@iA4(P9~EemyuS2zV47}&`&oN|MEng zh*y!}$Ni|)fU^^DWfIN%!Xh^1Vn9m*NZiL;Q_KlI$M_Z)z(NvIyYTS>pG z+2j!QiE6K@dr)3B)P|gj1Dp{%k8G)3#_K$x-WuH7xgZ$rrF>F5vXOI49tl;RgZUrg z48)Vqc;yw`pKYAzoLIRQpyB7FsvsyEq#|5&nn?`l_IObgp<_yflR~b za$4#5_nV$}9@OO4qMAS0THE@?JjSvJuCXKD7C(zg7Tru&nMjk!PY#-j^OKzM`%KMD z8741tO&T%n;si5m_L&EppPCO^7NQVXmlz}sm9$Y2;?aV|WVYI6O^GJp< zsjZo~gb8==xw}55O0-sP$I_s;$d6wV85LKy$d}~>WI4&oe7QgMluz`$ zjHZvphD|cF+D}x4tot}tuO1Omd*1zu|3#-~(c-VnxvtGV4kG6WR)z**H);`6ZiH)j z*eK&J<{pnV7|q|ZyYskh*o@$;qWt8*f4lp0CKmA1R%G`<<+k-yWq#qr1gFUzHbOZA zld&3$-1Etw=fOod3t|+;>vtdq`c+?s>UAsv`-(ufoy=JM$RE3M?!j_@tckw~>Ta5C8WgvQ*`2pyKQOuIGXGw|Y_c3hIiR*R9WS!WI@31D`q}!? zdfIw`eCDF9qGPRdD03nYxfb9@zT*_kB}4p8-Xs^|j?QJhr%?}G2O^`Op%zfMQMybS4+T zsu>K%Hd()`<qcsQENYE49;8mZ)oen7P$b$c7##CdX*HLipKGCCmSVqAD9}?95 zz99X?`7k&?>(w8La<*wEZ8CoAkoq%L_@ol_Rr}O_*raltg|lSiO+m!Q5+gm)W67!> zuuoI@N@uTf>-qKVWMTJt+!jMM{x$Y<7HV;pQ#j36jG{!c)A^0F%qz>(592d_M=O4+ zdyCuTIR=BrL1ej^s)E({sIMX0C~kbvZyC?<7`a%BjjYaU{jUC0zoA9K0lv*j+++oU zk^U9cqIJbeOa`@i1;a28$WRXKVK5?Z&J>vJ;F@Qd`BO$1175lHn@ZJAqJwtUI#$7& zNquRmb)vPG?HRW|IP2(Eyk-u>k2W2^P8=dPIfZgowAqVNj@#0Qxuai*JA1-Ya9TTB z4_F>CJ!OEsrF{?9;SgTxkaHT-B$qL%=B{v%?DdXV7R%iMzr6~iqb?EL2zWI6=~YP7 zieQDWYcp6snR750TQQgz;})_1zuF*u1YHY{@!L%}F|)ZPg}5(`4GUG4NZmzb;?h&J z9_-g#R%9W_`&KfSO+@a-(bBo`tG=NjPrg}^7_5oT zV}Iw2lv4Jpu{^d5DhHF4Mx2-noCGtfq*mgYK19rgwV!yu1GM?X7PonqVdPWAut}}( zBNOq35$w!vX3}-Xx+fC_Y~+p~0XOwAG2%Zms+zp7%jzA@>Kgrby|1x=*l?5kA$H*i zQAr_Y+-%n#sxR@0&)L)J;DReaj%RTLabeFhi!^Yu+L{^&cA4({fqW`1b;I*i!eLK#hHkq3UQH1I4fZ=_hE|K z0?ui5@n2CQ@*g9YWJ=>|?6HMgeo*ZMQczC~CF>qTZZT4=PCmLo`%k;3#eTbKwYhcE zu!T3ZCb0XjvSP|bxbe`V!|@eaDM``eV8_=zLv8?@;i)Zhev0y|ku zR-(`)YvDD@VxeEcI;lmqaDjV*vBv0vZCFSim6y{Li7&54%#=wbpg6eZBD_P}Z@%s! zUNY#{46?G4-@N@(6!33RFIo;7pT(;MHD~O^1b^~~%l!8;Hfk7kr6+j8;5$FgYmDLZ zw#R=>ORI`mp;}@oh9;d4zyEC_gzB78pZ=rMdkjXoRoEGOXdnc^Qb6ddvf~i_T z{9=pUhTkbco@%qtLbE*?AJode)vh=?@cXqLqa2eQ*Bpv7(K*U#W_D9$YOZen){Dsz zF|Ln76W1!H&CUBZm1nwCUkV2^?MP(zm`N`+yW_bY0c-& zV5K{7L&CY6!P^*|_ZjTYX~jxfwV`@l?$a(Zl|R5hF0cz<_{lMDS`KdTeyl`5TS&C} z8pQH6RgWopKD{=W`(_Z=YGn6&sX_+${)BV%3_G%p{R*NLPt*u3&wHvp$B0w}eW_MO zI}E!2lI(a6cIdPc#8LY2h*13wC#WAi1}%6`*+6Ob<6$bP+o{LoWiKzN$(-Dv*WX3F zR9n||C%!F2A3#nON#C@cyxY!+U#ykU`)kXvmUVe#dFlr$pXMBY{=k|Z$66(RJH!2y zT-whdI8S*MgEP~D-yE%V)8}G0#&gfw;w`JN|8K~>CGsziya!7iiYLj(yNc$lETg6{ z6rREU-~?!A7*k$TL5I6=f5(aaK%@FF!R!%J=^|a_1e*|GMr?2AFU(-d=KRfhgTL)& z4$E?fneP>tj#h?@riXJpb3NvRXa%j#F2?{A{qs8}J90R6XFumNXGdlz$1_*48+nh; zq_3sIMrTv!ufkTLDU%BuyZ#07DnfO_Po1<7Ugi65QzqLpIX0bha#k7-@-Ph!X=&!Z zHfDz^sY^jRmyrW>AYVMiJlJ3)5VZgK=zD$yjy@Bs?^YjTZ#r@B8?nD5u&r6Dpm|}} zKT#9esp70-YgT^_6PZh3^R0N9YGf+i>A--3sm;bdJz>7=X7;uw_{sq73p=%+-+rbB zG57?0h{Wz>ahrRR{p=>52~IfZsx~INU!r(aMa{{n*oA#rOLX{(SgH9b7K8s}>>r+5JDHFt0gs1{6RYV{@TLM7(-)&wJX zMP}v0Z>RC930g&X6X&E{;$GK6=W#&-3I4}5zN%Y z_B-Y{Upkiwom|PBonq8C{}Eq+Fdt-+Y$c|N-h-vLfjHv1Go16b(ovK-VI6qhN?=>B z#EMdI>Q+m9MmLx48bj{$|Mksye&+~%HE-x|Zi|NY5LPNgxhMr^KC3))JHg8%-Z&=; z4zQ>~aw@U&MfI?{OP!|{V`fxS&Qb;_$oEo7rXfa3*O{!A3Od#m-*4eAwdB7gwCUW? zw(QjnYQf3;Ybfz#JHEeH3bMy7vFpq5#mhlPg56`2!6gQezuw@vf{%>mt}kNU0%Sj* zVd(tsE=-kpEmQ4Qa=*^P=?o~3l_pv=cIOu(1SDbUH{W13O6#++<0X~eoa{~V3*OmJ z;2xTq9j_Ohni{G{5f|nHqZ`3_Y{|6Tu5ur0#zlGj5T&y^fs=P0OW_0cElZpfJd<6q z2!qIv->_5Dln7XcMTu!5uq6BRpY&*bw6-3c<|Dk4;I!7sii^DasJw>B4vVM}ZYPs& zLX^B7&4AOKp(ex@o0u*8n*IDtE*PvqPs67N*YT!2i{A`Z00v3X>~^xak4b1x;iyz$ z;@0PH7XJs=7QBs*`@9ld{d*9@KFp^L;_9EVHBUh?OMt3=7B2Dk<6uFVpc2c`*^U5L z-At`QXLe^hCSe-PpDjdm(VE|{&&i!jCfFP0il4Dx1vrCr5>m6+;G8VXa#e>(QJ(YE zo2sY_FW44F#s=m_Zlbm|!HHUUm z=>-ooUhXIb=lD$nH7m#pU&dsexgxd zyW}Ya8h;dfu~Rzadg1gtmpOFDb$dT29)X(ibk#|p+YHv?Kl&FQ(A8Q~{2OLMu&b#P zbEw<0r+36S&b5P2v{hN5^id|tF=VyJKn6oa4^^cj)D0})9g)n(9M0YrC9C;S%nv@? zjGZgNdIquV9n`*;!MfA%7%7|tvv@{4DfN?!De213>V3W{5&e}?n##T9`C=5aXlzuq zZi7l+B`^6vcTErn25|^Wr2tKc+O#P%{6I*Xp^(U$1jT2w!+(Z37#H28NrPA zA(i;x_p1CU#SGjvc!TWN$H`2@-2fhS1a#svnW(PrgnLmB>r@9^;wMhkDeTEqIIL;d zZUF_Y9%RjCV)Yzy6kqK?!PgPPJCuLq5}@mg=?5$Uwh=2Ikh+Ugz+W106LNxRsKlRs zV!l+eqZYhBo3VB*E1pC9=XpgA-)xh#!k>AJ>}pY}Qov%7pQm(m1XkrQ}; z6T%WPRxZPOUg5l^Dsi#}8*m+cutB_=$FPyC;%L`xVGNaui`?TE)Tz6(BLz7D2jtBl z2OC*|9^~fX%t(!)zTAb5jcN4A%)^?Em(LQVoR`XR`>SzR#!+FA!Ah^dZR!hZnJTrC zw}V{9$Sru*_R2M?O0ThS3$a0aq(7t@Vg}ym4^ZaO*yRoU>rFYQ@(b^=8y0gC>%RlP zk-~(&i=d9Z!3ZMp;=$V4eENrnlN-jV3zV(AQ?opj%GC@ar`_D@By8eQP|>QO!7A(9 zTrS3>qgwQvL-XoO*&bLp{pMuKH$AS4y+7(+)ga3K7RZ zz9y6V1ZQ;DB!V8Ny-;f^6}XwjsbBQr_Vg1)iQ$3D7`3SuAWNTZ{H%Mq$TWSzKhDp9k>lkIC&oO>(ZR}!^~hSPE=M?*(5I~e)Eb2q*GFaa+}V|YTTaI z@aFDQsjjW$2MbP8x=1dm7V2Y_sVq9hK~ga8e?SCOUfn2{V{iY2kFZ%hDnEl)ITrR* zWo*E9@sqR@HHHr4Pj%_yxy#M2BEN%Y+lndXiF`#$aM;3+un`$ z93=-&@>5QAum*Ahf3=4UsGbsxZ);J>tAIs=Fs=maY-YHG-^2R~pmjQk&oYtt>yf&R zsI|NLA0B)ROrf4c`fg5kWzKshv(RqJoz-{R5zx0``gSG)7nR#eec=$V!SB2#uDAi8 zCPDQL51|k}T=DrJSb6xaUaY!<@G{sCSvkGL(1YT|Y!C+~MUdG-O~q!41RAPQU#OOZy- zcn(XF%#7Ec#Cv$@UeqS7uq#*L=Yy(cSBX~7^Bj4k3HXCWyj~Znk$jAr;~J(moAKIj zs4A4eP8+QEI=n+2K6REf1Z9mTtYh%K48*RtB# z_&N5iHQ!U%i7j+8mlmq?yfZ*W>yfAKRO(7ssMc1dkG!gDjQB*-@H54=XjUVI&m&0_ znfN}QcRWwL=4vO+Bwp-ABoVCMDsU%EU}HU4o#(uxdguWh;gzcrOP!N$69F_Ab1PHz z5AIo>P4t8n@y;`PX&b&_DvhZ}J|<%G(^Gg>$m@!dwkdvk*A+N?@4UUeH;f;(n@rYx zPekMZ<@a)Dd$O`yP^9axsAyjFq8oZAb-Yznaj&@kmP(QP{zhMPdrrt^`EO|nuO7@P z&(ja-B5J-zN5l*IR&y{>L#IX)#O5o@b6{s(ceWA_%FFPI#i$(&)mNc)a*HbV5^)r> z#vagpb;|utJE8ncrrMW^_8#6rL1NUG%t1c(ZSPJH!L&lhWsy5f&s1)Rzrnr#SImSj zKbaF%UMhx#cu1`zKP=j4wW-mSY2}Nkavp-pwk9k^6ogIWC-!hrW%1Ctv9_77~om$jCS`lM0HRZByK_99-7e6>h z+v{6L*lswTiq{BEcKG0~sNNN(IX1)S`>Ze(8x{DxzB2j@X{zI(EstZZ>%7#4Gf_|4 ziPiZ;r`r^zr?J`-4lk~v=Q2IF9UTEGgiGv;(USVkSb$b$f_9$Hs6}>WPfNjmvUx@~ zI5DDLNu4H@010Y|72P3iAhx(pk49~4TWgkZTrnHfyg$(;dCa@f*sJ!D>u_5)b5lPk zImlO&mFKPjWL&kxJIWYCqZ9EHIM-=iQqnjn0r5ZKJ^wNaYcc@-R&G5_If?4oNZT0t zr#>n{C4)=s{VLaH=VIZDl#T||Ig|k3YKKtP{{kDYoI?=Kp+whOd4$#P>HNS%_9;RS z`3SGo5JjVwC|4Dc+Y>)*1uGcGJ^hQ=yc8C$4!qiyy#5cay3$!?zLx5KObk0sFRs0m ztKlo2$!EB2btS9wu`Rpv5q#MSpf?TGmHK?*=N&wAN#z2OP)%_z_(d_XG5&TvwGFr0 zgqp&2@Tj-k_l4k4_w_?+s5HtUIBufK(qGYF)zrb~)d73rxxqz;T+?-CdR85jSBEG)#%JJM4zb24nw9wKN3zMDm zqN$@hK1oH4GT*vTr}^sZom7)LhMcPj)wMb5U(!)@R_a*4I*1}wm0pRR; z?Wl9UJ;VCUVuDL}N*E{aQExHFw21MZ_-+K}R8=qNC*a$LDA&N&whPJj{kC(CbuQ+# zDHWwLqO6SN9cO`dzSDXbik_1RydMNV`CkqD0Z?0$)8xv5MXy8tkfaoHRkgpe6}E41 zHPiZghk06SJ%~WNVWqn|B3u9x`Kv^M6N%U7^)i))CK7f z=+R=Ks`ILAq4GPOpr73{Jd3nA`MIl*bB8@AdWp~Fy`bI^ta%pIvI|mc`XZL%B`U&G zd94kTGT}wPcFu6MkVk8^;3bFqsu-2jg5UB2<_o~+x(VakAVYa6UnUOyof>C%raj&E zMtGcBG35nTFuQomIml7N*^4UJN1;B?H;&BpC?5Gc`8G;^ZQN@;5uQ0}UD&e+V9(x^ zOTwzmiB^3N=05%6oKAMs)OhPH!DOFc4RIaJllL0=i(?~e8wQU#RH{UT^{eokbEuS^ zi2oANKy`4Oo>U-odPdukPc9@@U+xHcvpLSoj$O8&1xelQ7U&J#71$6_}`Gc;H``dyeL9+2m% zzkr$V)c=O(ume?Y#j}nX8u{taC$^@Gt*axADMyB_utjzZQtpFW_n`l(DomU^R7~pY z`^XeU$>W;k>`R?tv-68%ynU+m2g_1>tQ=tSazA*#Q+<~`xp=>)h$6bFZ^Sd!Me)Vr zKckP+N%?Us?H-Xbp@s(%E#tDw4+bKrrwmB+5mj`r3~_9L!r%2(x% zp5eZ$@BGFwo~ks{Jf1&17kJ!9Zo>;_no!n}X-%*%R0Bp~t*_uU zKk=?^VrR0$DxOM3r6~LLJ8GRz>2sbdH!zs4$b=s>!y@N9iVjZ46t zSHeG@tmJcDwVj}9yu*MlN@GxTMKs9TUigE2`f!-G>^LYk|Ex8So+3 za_JUX-4JOr^@n!!&Bs&UIwF@-caSUGBJ=Qb14g-ag9|i)9r%pT+8(rPCy4z#)GGUm z1IfZlC=JOJ*ASC`B!;-h-S!#*Q0@`xY*~};5gYr&RrKSeVBJe7+d$A#loYc3F2A{o z3w6Xc(pu>$+{&qF-mHhs)`CoQ8aWw!2za-bT@M@$9HGLm(o)do?3&Lw?zZAd8<5Rf zsgNgYmEb}>QH#Ohj-~X^ z6O_g?y^@DhXZ?}&v{PNE4i?n`9l*uZ6uPntL5@Z#>Ki4*fy5#Yd5sF{zi=7Gg6NlU z-`4hGzXmHg#ES53g8jjdq-lCl?*;k@FMCe9d1Y;`(GdGd36S+4Ovd%2_&`V^68}Ih zumYw^meNA`qP$gxOONOm{UlYCY6^9^}n?VV8(c=(g!;<2vqNH#V-b&tx&@%Bh7Z1k#F|XEYCEFoywX0fwzaSTc7hgs$4Qx_l%jLsESTwiW)Sovf~^4_dD?C9{(`zk zV|e$G_>4_*ZfOp+#EoF_L3_9bwUjzaAy}LXwDZ)-8>xk{rjy}8>;vi8PVd(&5W*C( zyem^M$w5`H%5tpdvcHQygNX%C={O$Y=x-hG9E)|ziDtn@?WinDL-k4S;E9+ESMeT| z2cNM_TJH+#cTGl{LxWjRhw5TAa-e#WOUXoquWM*f;LS;7p}9zfyvIz&fPt=NKEf~ucn z)@Va8?I;j37kTeKtV1d+-NoRL=rxd;rh`Iu0QYYJM`ACXJ@>@%LWGc;8+Ap#MAv?A zV}sm5daUPg{{#!bK?QOv^|&ATSrALB3;Om#&aYN6E_-t8>zL3JuK!ET_aPQ>rfVMl zLY7`Te?jFi8V;jI-TRt4LAjw$Q~#7^xN4x-lVV*e6xWiekb22!XJIJ}qT05~5Z$i* z>}uxBqMuoj?xOoQm`cX)a8)|sae};$Ols|G)GaU$kH~M(;BNzqp)z*285PQX>LJ#} zgD(DmN*;0|Sr0yQ2DQ(d?8;m6n4X;baPs4x@@g=-lc@J$iRcUzF zS8Q0jHp)9XXO~M+SSyzj?9lE(HLf-_)CKNlX#Q4X&dh50E{MllEmkc+&7zQePk7*% zC{9D?p`SRLj)`Ez5Uk(~pjvJdSFjtw_+dVILnbry+LB2u7J~}!2jx5BO>*HB(7hlQ z+E;9=REOnrlDSp|K;805yIou+aNxv`Ovu}%%tKf96zb={dB$k3 zLG+(+66IJ{KGF%-M0gNnz z{Z^Fi(lqLcQEE20ZDTpltJR|NSaBIj77cj)jdUuX&`KzO(VIF8MAoZigJD~T>d4P1 zIz5qob|n&x|A6&h>Yl1cf_ybIwkp30es*CE-1&U!YnZfGsYrxM5kfQ2)`3E-D<8Hx znVY{3{)&q_-%DmZ{YW?ADq{5!*bzy%3lqgI)D%m@76~H1?_kN?V)r)&U!Pi<$0(-d z5>HEumh_V^SkHOJ9={FBJ&9X0-OXr0x-tD30Md5xFyep_8(ke)2w zcT9Gd^>soWqPRCf8*gvSn)J7iwxlXip0ThCHo`;vfhv0ocq}TDvWj?5yO(kBSRw-%qXw2olnzNF$A3YJ@aWqhTho0n(x{ zx)In2L6l}AR0IQIlyq-^O7nZ4XaE0?m){?3&vW0`b*^*Hb@Fre#8hm!qG}8GvNCV^ zKdM$W>f#$^N+$RsVt2TIDY3TH7I&5(3_EhZdg7=WKPRlPv!fQr-?xrAf6@BFYl5!b zk&X}5eCe7UsVN84W$uBx8T>c;jQ;@Eco#icn@vSQBWj{MTcNawvq)L;eBX)hqu+yciguJ-?EL*?{BZ4aF#?vWf70qVHd?}-{hI>Z2)FW zJ1;2xy+4K&1I^@ux*xc@RxzJIo# z(XH3R`=0egDQ~XuO*a}S59}=e11-l9XI2cl&B=~|=E>lXz7%YzdBHutJgo@$Z<=YV zF~o5=P zW_@TX+HU=v^@(*;`NqwK;c2TKR40-TI!7Ghl3j#+bRF*43^EKKQf)8`x(OnR8~S!3 zu0NDIscWwFifK)?ZmCza8d6E5RaVzw^M#{bt57BL8ySj{s?`7AAwvF2&-0G9i&N#Z z(9^{Gm^`)3w1_HJk|FaYwqg&bTg|njYGGHo(77K5?M8+pKNHovAK;TX~N1L{|<>c$PvbRxOW%y4@j z8J*tb^G6ZaE8{I-%RN@ew<17ZR83~ON@+cNx^K4Kira6P z)k*K5pbkm`%OV5^~`evHt6rY2@Q3>5r*xn4-SGCr>wGmcn)GTxi? zmo_KgGu&8XZ#F(r{xi36$LF{U*no2TJCma>?T@jikTtucO>ly0#z}iKx?MnMI`luUw7x)^H|2b~I z<*(rJqA?$%5uQX6hx9hkN8lZ1ddFd{O`~pmit!PXkB%8l-A~N~-)42P;|KFUUs1EL za?ncjl{3ny;UI-fIo4Ouz4p*6#JYCc`T!}t4xD2~I)A-JP zIHDIiZ?QT^{}rr-$>7l4FcUqxQq3KtuI!cTiqgieVr+JeS4LXf@k57NLx}!Lh1?o* zklxB&P`Ly0cs(sjE622-QCcf^Bya3VkH86K61UiGA_*ly@vepM5gxTB?k!j2a_f9= z#uQaz!&2S7?RDl^cX@MNaIv?i@t!r9+QL%SbG(_uaCKL8ntPsdoxYS*W4&iP*r?Tr zZ~mdTCbkhy#I+T8WxcTxBEZ{Kv7SGp8ZebkfLGu!KeWTV#qknX*%@9(;H>u_t%X+) zE^#*sj}c9yeM@xV3+t)xTmM0@jrRLrfwP}Z^jaovKjO~`ZHQIbvkOF}!oFpJ`grx( zSl^G$mShA*yM4xdrK!8O@eMskm9gFXVN3n4&kg0wB)0b}IhvhXx^dY)Xbe$G8~3fQ zYCYu^y3rGgQo6t&of{7 z-}Q{8Gh#231EkXIl_wm_;Ws?1qRLkHd7~qJAnz0Dk;w9z$bkEV*@v2nu~c*RhpXPV z&%%qV=+QrbejNf9QFYLV-cl2k&Ys!kZ?0^0AKu>({Wf>>n819`MptR8Wgy!9t)mjP zz%TS`AOLMv|Is#j9%`V;DyAm^f8rRG?xXBezW-V8JMUZXBu3hwlugt2#ntou7VdF1 z_GYo)y2@$SBz?R0F%?zgeOdlkb1|LFONQ{B zqNl^WZu6-7re|*OmA=7+weEXg+vxh&{?k9-BmVU*B0xW(WfoX#waUgUyMR{B-OSqH zr*6dcnsLv2o7~f8b&K{9M8tG}w+gM^eba&DfUpsRr zc;Hj5Fm0mNlN??NHI6DYY8LEl_f6LVZmV4NOXVYv)3;JH9RO69et0Cdip@^b)}uQhuZ!WGVpDE(xDY;{07>i z)86R6tj*PDF`MBUlc!s1FCsIHm_Q$Go4d0ALDVUH{yoYm@~V%tJR;%`0}bP1v@?!e z@6F&)wVPvzUXv+`SCnw0q35c3k_^C5y}oCj`JHpKx;uJTbc*s!zYz7a?=35q$Wc?Z zl>d8ki(`yC&i7UDu<;p_?gvnzRm0xy9;9!L8XLI8TRJG2cnSr~-;@kvD;S3-^>jx~ z=Plj#kFgt&x2YeU5*+QGsC4y@jEc6q(Y2jq_0U#DY>qg9efx^Oj{nSyfr9pW*IZxA zz)+V{X&1;1M2BL!3FcnUCoX@<6N)2tx4Ap=sc(42iow!qNwu(jz__IxB)W7T)a`km z&s|=3VY`$1N923n{XwQaE1P5X1dGu9D&2Q4@R%)KBBXPaPSgT_4qEnF-DU5yT47s! z<7Y;?XM$499FBcBmQ2wQPh-DFWvZgR)%z6{H}_Q^70ku)bUb*N>xpY*Q{{C@D}?4< zKxCwducduW`CZ@bYpS*@JJQjO4y-G91_37Dg$EAk8y$CDL2|9x?$T;&JAsUF`Ko6|mdU&-FXqm|qarS;bti zgI04QonNbplE_peFH<6Kf$+479MVVrs@A~p%KHCe@UtCsTLsoAiIKnS-w`po?EBVJ z*8Q(`!q?A?aE~x1`=4J@D2Fyk!NrO$t#9Dro5~j7;y3<|czHr%Ki5@#js2zXb-RpuLJ82NpG#Ce zBkEGXO)Pkb=VSf6dk!}K3GG`)qye&n)ycI%-{N2H`$jM09-{9AbEE;tC#&h)dy19v zD|h8P=+b_^QdXKfTDwH%$7Oy=b!8*ZufFS^9_mcxgk8XV*EQL?K=iPIxy#qap60%4 z#zmjCb}JP;-Th+qoub* zOp$A^xKE;m`ja=gMxMQbSA`qwFfM&l6pz2iN8CNdXbn7b3u)tw68%iss*yhWxI`;<#^rs1=Scc@jmj5 zAw(9RQsHu4cR7=cHoiOhB6m@4z3RqfdMbWYc4)+Mn7)x|oRe&hSr81n`pQS)o%C{E zCsyS}&`Xz+*H1T|DLR!GuM^EFfd6qBZSpxWkdovCzb13{j-JfC)IVJ(JzHWjynkcG zKGW~evGTb-!PhEad-CjG0{FO&zZ~bWy$`q=Th*eT_`GzhiQjxkz2{JspUvB@E{>h{ zljtL?5sN7d0$O3T*?=&q29lOe^8ar%u{a-Ft~hV zV&)UI=w>wZrP(L(I$XrVx^gcMC!a(#UE6Gp4m2`zYcy=L%Ol{=-b_|!*7e2MwrK3rq956 zUqH^|IBOeBgz@JS2Z1TRqD@rR*Rq-@6NqbuzV?OdWhN4gL5TBr@7Fxx8 z+w7ho?XUKIr~U34M!j!i>KulX+mU=>4{tf@>>641wC?Uy;}w0fli<8k)<{sFis|L) zjF8IuB4k+C>Jzj|7HF2HL@Tq6(e`ogEMgvyl|P6gSEKLlqP^YtO1;6}Cz&zG;$l$l z;O+4s%+G-qRjV^$XbC8zJI9?-EXaAMO|3WbUeZc`k`LH&0*NBEtsmYF8Dz( zj>#EPy?9yqAJOsmbPwHzr>J-BVD_bMCLK)56yHW`5V~iDb41NS{^ zB-&~>Ir?nx8+s+zpUm8-;95s^Bg!ZW{%dukxx11smGW`EH-ZPOo%m<(=qrg8JvCQo zN$x!85Tr8ib&!!6PlQ&jthRNo2UqWNCJYUx-uSS8PF#4@1>(53)LW5LBBr3%Keze> zro|VDyXCn=?OGw{$KkWXzE$50-b(zgeA)OX%r}d1=9Wtdzv}!{on?0jI$~doJsTAj zHQ#UR)gp4sHD@}&40nR3T1-OR-I#ZRcPx(@2V}{turC}fjoUFZ$~TC6!=qCR*4^OBeyxEcJzKgH?;X4y*TVRepYfo}(s4-$fZ=oyaP)HL5BHkv}UQEAY$dr-f%)tei& zf$5Pk_7=xWFzi=^RdQu`izNJ5VPWEexX%7Z?xZp+OI0YVg}bzJQO<-nm;gB-`fIB~ zWVwiO*y%LmiFM~t;+=aEWTv-IV#Q?9dC2AI@}?=!zM_CjDUb=y-p!?F>V zony4k)SPa@n}6xinAUSexfTASGDa)m+O2#@Eu-!C#EgsX>5ZUX;gGsLVs_bfVMD=! zer!(i#YH!ayA-(Y@%gV|afU}sj5J*LuwQ%7ef@o)Pjo}yNpK_AM1B^Y?EcO!;_FSX zrVCuCGt@;kRljz88-5~^YHRv$KJvGUS{rPS#UE?Ga9t@?s$|=+OU~!|M;<29mk+P} zBJK-oj`E$eYPqB`nP9b;uC4I>e$Q9_OPuUrkAs}u2d=XbZ$zGVURV5v0ZPDXdndZ- z7vjm|v`jKqKWm*_>muV72N~g0W=Z;|rjfmnD#!c8$cGSf>x4YL23pc`qY;&LkKDbH z63umnT8j0aH{-5Wa3xfvQL(Idw7YgG7bwXK!o%E7?F0Xa#EBJ##4U_z9cZH7r`vyN zgcTkY*2I-+50B{%?!OZKqvx2Bp#SB%80IT?B61sbk5$xS9wQhVT_t8nOl+Vsb){+U z-@=cVNs3UEjb!lOvRXua7IVix7}U_m<~VR!N)UUm>vSr!K?C@d=xuahA-LZa$iSbX zmhz6;fj)t%>MiWK5$H1MgDptK!Y(R#Mg>NDbBvzugN}vaZZB$FOqi%f1%&G_tCC-d-3Ck6jV_ee_wTvE4H+8mC-!!rl+N<@!R6GFJFB zrh+#EGqRi2g=sA(nbfmFiKB1tsVCci!#{{@xY#R==vDoN4zZcqG226Z=yNdSw*|WU zDHFf3{kd zDv2WIJ*y|(K{r5avOF(|x}E|B(ozQ~UFeJ3tfm?Vs2uA=o!4bL$8S)l>!hMu`ZiZ8 zdx^NdNiK3MxwKK<<#a=?v{#ugh-Mepj}kL249>%GvXfh^qVy~0+S{xc)7I}9Z|R-X z2SjDw&}VBd{eY=iw@ib$?=Gs1x>FPI0voTUv4(nxw%j@G>6D7c>X%tsYsg>zP7GGC zj`x!P&PD=c-d0np)f-?BC}wqj--0;cRwCH_$+p^7Q!1%D62}e)|1^rsQAcvcne@~) zx85h#kU<}pV3GOhj~xdNW+Q7a_)$&CI!pC=E2Atw-$S;01U-|RjZ0MO=h7GTC2zE` zFvrsakwg4co*{i<)C+`u)|Tk}1h9x6;wK%agQzgbykDAQs0&;|{ri{nogJndERo$z zFh?7;>9br!|Ku0Ozs6)LMO^fIRN?v3|67DRJPF*C>-r<^p|pY>)*inikLvcS(ECUFPV=Z{uW8&h zX3{5go^FRZP<#&WE>9O?E#s;l36@_j6yM2OKA<=9BWk99rl+SF-|`q^`Bq1=o87Sj zo||LM17x0_>z`BkP>jmzgWwoQZT8#z>?M5ySx{fMf^^RR$UA!QzJw5k57F^I#{AE? zZPW(G=R4zlItBZfkBpLZp%pVrBZQ+FatmhH+t$)Hv z&G4?9hq%cN&EN;Y7XcJBJQf>Azf0 zAL4bq+g^P0ZMsWF@wsEHbs1bCtKMuFbewHP4x|Tq4HaCe{5_9n7N)j70m)5(c13w^ zQS#Hx(S}*9BahQap~HARJRn_82>z2!;t0N($4>jQ z!aPpDCDPjwy)chHL+S02GcHEf?EFQJp*lSvd&^ha)p zescEdaDw#6xY_r3x)#6Zo0s9+I!IDq-rW~1)R&Wg%Ktv(w5GG_WaxVsey+n$FQZ># zsi#}avqh4U;oN@o*{w#71`x^E#(JC4`}B;cnc()W}kV-sK_^EWi5H) z7`nW-vFbdmj0t>SkhBzPFxS!9KZ1_UI!JnPba`cJ&USOw=jg#X45t_5l&+xHi10zj zg6yxhc?>Qn#A==Bqu0!Z=4f+>`7bAP4INRzoJnuy8K{>79g1+u6_Cw;LMJGArp@U1 z6ltHuxl}Z3A`Q8`YZN@3jb<&vo^ zhbYmW-{1q@G-wBO-B=p@S$UrruWH>b> zXUV89;hovk<%uMXWJODOVkW;A&Dxh0w1;+Aq1*(xL(c0g^iB<(wVSit1)VO3`a6%Y zzp+MBWIh`THbkclHhcg~FmkX0!gwtgk-*ddMmhpjvzQ^g48Y&bQ(@=k9RD4esPrbZI+i9S;}G zWd)*5AHb~x>3d0rvgz!r9(sBg->gV?@lUKRhbM|GCGxGg>{0r;1v^23euBP}%xTLF zm5%%rK%Oh1M?6+0H^20cUZkFKJN%;}K^>r5d!8e?YpE05&1pFKle3ehsWo3zQZzs@B z8}cu~QT~u`JwVIWiOO5DIHh{%3bC7nn?8mP=b^jcMAt+2 z9Yf~j)bsDFc&MmwvPIba0ODI07$ILi)j++I_9?&CuDqg2(7LNkjtsSBNUqNUn$ zHuc!S1o-r>p|i6AoN*o!Cg<}DPfXy{x3b?BAvs^ePwKED2Q$xhaf;`W^=MB0l`a|W zS=?LSp}|I*@9^H^^yu$^*Cls63Azplap!&Vdct@0_}~8UhE7G+D&v*$B`3C&U5U={ zQYWzk8(;>vYD+XsA~lq`r$@XKjU! zIh<_w(2XMRzs5Qe_`TeQa<|pT789A8iI%!+bb`|Iy9fM6Y{^5&`YL7x?M8ooVjhGO z$lzl)9^{h~pw4yBBc3C9A45llv(7^E6y=V)PLHZsle<|0e7H;ou zXm!zCtFbz-(92r_DXNRS3!U9m3h(A$*O8}&SOKl!zTRkIK?fskHT}qX z*YUF^Ae;#9>dp|hR1x+hvg$#T_G51aIi&=+6b;p$KML=O=e*{yC&8;IANsf8HuPuhZQv}?1gkmow(#YbJZBrbIf@)* za$Cefyjw;AK_#}_W_}1r{BUsN_q_{n2UO)6M7b{-O@QidX9N|VS!e{IA4yoZ8&wdhkLoOEbSv;E&(07ZmfoVt|vx5eqbM6gx<6Zt; z5b7o4eQd`rOoJOHpkY??lneZOI&yk}Z_AA&e&dgvm>?t-;WWF^Ie!rE!^Qc0$W5~n zZdnBhuZ;6lXn6NTS(fF>P6r=5;vx&+IqHMjN8 z#vjJJaK?5tydeAJ!F9oq4{-twF%QeJA*axbbqo65H^!Uh47jl%^cN{F!Wm9A-Zvu5 zl4c~58H=VI53R(XN`abEb0+o6dGzhgg=Yk-za6W~#1@t59YW*$HLnionismzcnP!- z8%r=x6@D&V`J?$xGN*D7%dRbFFE|(jd5dt-){sBB9hnm@>(9@}g}8POJD+%zB^Xf+#)gP-l1r!=E(IJPOc)~N`walBP9`k z;5eL9llAw&mpF_4B|bqKJYR^D+`{*ov138INPu_l7$wlo%R)BxHufMqE4RfDNNox` zQQ6-Oy%%TPfak12EBph03;i^DvG;*v(F=R3k=YyVS%)WzjWB~x*W`{`PNn)Ma9Xj@ ze%s?s<#0y#=s8`?3go7qgrumvMf{%D=;AxXD&FQccmS1hr4NIrI-uHO-tOYrV)w+M z*QDb;p6}0N=a2aONciIrpBI}&Ow|yyX%V`2Ca|{E@Wl!457GI{(Oc8ewcF8M70`A+aQ=0%1SW8T)sUDl zWJ7$A3an53S@FhhV8e^vxzG7Zm;OKCcRb|nhrmod$nBQ{*Gz=o?RbM|P0<+c&}l8^ zj*rHIafEobKU8lEXNu(}ag}b^>3?x|O#<{3UnWiyaxEmEj=FU zYyA5Ytn|*D+)_H8rtx#3OFSAgj(zk%UP4vytSO6~if!iR{3Ys>&5lI+n{zgck-1uC zBTl4VXitK$Q=M~Lf{ot;eqBuTz`@NXs7d1ArLoKW+hqx>+|GIE=mwSVnD*3(Ae+v-H1kMum})1lG}lpZYn=XY?L)=Q;VO*DhrJ`JsO%6 zop)OHYTmj2ro;})kV0esO?+g&DjhyEx?as+-gCCfX@0K3ptqg|i_#BrM-L11DgQ~e z^>q%`ZC0axh4bFV4!d;f8+}Xt7T(dU6tgL@ZNh0va0_VLm{?rbxs|$_Gt5RyrVgBb zYsZvwCrf-8n#J)z6O=bqzi;p_pnDD?`S&dg_T;=f?8Qwl};%MB~HG-5wB#^obB zg?}ABJ93CC&Amsr{I}zJC(MY-Fy5f!@`dYfazxF%Ddt+wDKZGB{qM$=sJOd)!^Cch z-Qp_-3;Q|-Ysa>XZ4q?^%!rrF0&*%rHBHHOP0-tdvuNolt|UhxCDnU9IM-J~-Rigz zZkD!-UoWwM`J-h8eVeM2{ZxBxkN7*R15-x}nO$Q}#XS$MF~4!FV7mKRH+cJY{pcp~ zPouAUmNC`3Zdg}GC%wDh6YnU$DEQmbiS@;G~sGGj$)*Sj+MvxD#?kyGb zb>do5LU*hcS_7q-dz$(obykx+5r!M=isRawAU*Xr-vHBTJaMxKCC=Sn|I(JZb%{QO z3Zk>+ekhw=u8ZTI+R$^zKc7kQE$B?z5W>fM!!wb(t`^h{AN2R3HZj*RN_)$5&^r)p zgiUG+)tH0zsnpmE4#p)kj#))rQ;vFG+pGK+S=RBo_Nk|uw>3H2Tw|f$k}C4u<{7$E z((NEE#v# zRpqv+;LgMn+ZfZ?g8%JF|tJwz-k(T@UH`s|haXa{HDi*L&4BotY8eGUKy* z)HnV+>a4IyW&aGn;rfcop1j$lOR@W_bS zipM`QA*tfGi4}t1x@MOcT%=0LACwt^X7TqbK7Dgw%mL+8$)&{yl+Gs_vrYx;B^)h(Ja(vmE*bH^o&SXW z8Gc0>;2RjXBz{@!{NOnIvhrKxf03E$H(polhQz~(lj0`%4yt7w-5i5m1+^|#??6Iy z)u@>P<`vNEaz@RhC#kM)Y~TZs;%s^!kGW4M+sN2@h=bp@=K88cZHuZAxXfJRm%2R4lv=ZybsR8CZ_K!5X+b6dpP$nnlhHwf;&X;Jl}uY+Au7_7ur^tto~=hbgX zRlM}a4q;l=X8O<nz#>NGPkmLT3uC^;?kRGk}AY|yi_0~4ExpSIh zpDW!M?tc~2Bfd}UykHCOX)@r8ta%>AH`4o-bx1AYYV9maKfyz)R+K9!{L|;tBjUfDgXkXT|_OZFZ+sV z$M3kjl==YMR_m!diYa3 zKWUep-#T`<@2K0b7p_RJlj37q-l1|O!)rNLXv66rlM0j7;E8mjEB}>igKG)63;WfP z>Oj{GQQOTwVoH;V*TctS}v|sy%KXu zY2m%y`>c7sAA)g#&VE6AyhbCzfIc)lItc z-zRsymD-%A!O}6MVs85zn8%#+$__7CxYYB~i^9)2FEDR(2lKWLfs^@#e$1@xjSn7* znI8LQOpd>}b;U8Bh`NCs>?AUFHMQ+- zk3(k2+@*SHq4js*LTp09;`p~>cKMoFRI4g=lpD&I%0KQj=h%pW;YZ3{3|kiAch@(6 z@jZ#29(z7^aZLYUQQtT8+KmFOcQ&)j@4BWrk2u;!u87$0xah|2_s$76jrkxZDQY*l z;4Nf<-Xb4X5Y)Hz=22~idv)a75f>tuaH@^6Px^|27@`Hg_GeSGQP|vzq*Tyf!Shws za_&YhzvFRa!11GNnp#wUW=4R~c;8w<24y|?lO4d^?F7dc2Ny|qRb`&Vf6n=?m#*td zIMql#eBq{6o;}W+9EgbO8uh$X<&ly5cB6IGXwTlU#|BZdfV!o^Qnh# z2j=Di*K%in=QURk&{>LldiYC54UV3~l+<5+Yd!t!&*|e3{M08@VPD2BsOWl6Wo|ir z-hXm4HWmx+%267mLKVng1b zOXmxwQ`boM7ex?pO&fLVLvsdJ);<0B((g7Z> zHBvgbraBDQL?z9r;PEhrtxn)W-(w~(Y$Zq4#_VTTMFLGvJM*48*fj-A@IKfUA9=-tyI;N;CyW`KsN}s;W;{Qk*LzlO3mA-RN&?Wp4)=eTMgUYp7n${R*U$ z0`x%6c5ok`Cfgm{y@ge$wY}U;>ZiD@`66k4C8xE1+kUs@*oo4vzCEr_!BwX0{ApPf!gwcm1ButRaAFt` z^aDJH>P8!+>J(EK3(_+$$jtA0sPc2>QOM2o|-+t?)=!()Vc;TPc+#2)0rAr8Qdu% z-oOOzjyxK1$FW}dhR*XRp7VS*jlJ(9mS}M&jRo~4hYEyxT88_3XK&|Y=SX)yZ3DWk zlE0m=AH6{F^mmn^>MDXd)Jt#;jBfRmkbkVg1 zXElnd)!HEc9>I1PN7vL>WP;YgrJe9&caYKC02*eJHb9%B?;r=Xo;b%TQxJ+?sSA{G z%1HGBHCh!xNPDW>q4T^uy)05;-_G|PRiKIbKBcs~05vdE)UjHC^;V@zs51zr?|H|0 zuX+}OLcN6Db@0{qEH{=iHDV(@^H0o^o{xQvu%}LXUdOVNoLf60LsBKtm#A@3JxQIR z>{I?^Vpn5!^Au#ep=9#!6A2iB$6bZaV2ktYW{m==qB|#gRe6^PO9ptKg3<4w(`^`t zA)`Q_)ZwQa;PF^g&~BnndY~><1pS!tFoK+aSL)}xfRG%^Hws`ANw(%Uszo-0{%c7@ zNf0sj@@EB;OV{fXPsm`(%S_PFU!!+v9(6~xshw$oXTKd#B zWgMVuXBa4-^N>!1D#LQ#vGzo|iBExozmRDN%iNVfnm$H1p5SXrbn7XoXGM8lIkZ(D zDD0!|y^Z!7c*T+>@uKZC&iE@bZFJQ!ktBwhF*Cda==@ZP7(D?ixgK)5g;@@ZKv!$0 z4bY=O)Y`;cflsZv)DL}5ZAM*WRHm|=qQ>EzVRJr`i@c01t|3m-%P0@>-#=P9QJbN3 zOZTP|sW)`XN6h!aw-dnK8-rysoX!LAVaO#k0EIQ4UWjxou!?j+^#=z{)f2P@YC!#6 zb+f}i!Qy-uy+BJb6Dr;Sk3x_-Z=x$cV;v8$E#pl=^!#bSz>I)8SY4~CYc(%)# z`{bd6`Unx7X+%)Mh(Ok5pOchh*oxz|w&r;Inde<5B*bwJ$yCk!j(w0ylt}UdQZdkr z%7{0R#EdSj^rqYR3^`(C16>}fn!^5bKmRUf> zlgf;l|3LNW0Ut~TUt$+_+iay7b@KJ8uR0C_-d%Y67JZX_!BP)$>q>rSAG*v5YGE1G zMgxKnNL;ZXwSNtf|0sOguEgb<+b6);7Ua#pwaK6bK6L*O(r1!;Jjkib)R_Ok9(I7M z8^Oes%Vd7O#Qtv%ipf>YV>~yH(BEDaomY}h_?g-!cxXBJz6Se~NK{Mg<+`8&Zz7#i(;utp%=6fa zUU-c;8ePcS2nKsCdP9HHvGeJeIm4-h(|3Cq59YFVQkUwD>)dma$;-jtl=_?V#N1N3 zDO1U;6emCX4{_|8#A|gj-7fCP15B+LkIj=rZ14yf#meBeeg*f_AA=-(LskD3;s^kf?ldQkEm)Gj^nFPF(u33}n?upbNS4Uq|vPuw7 z`59W4w2Hztuk_~F6J3}E(hI!C?bu#J;n#ZDaa*Y%f5Gm)1t01gtgfxh(0Hs2p{nf( zI_wE|_@`*70!Y(w;&^FP`v1Y1OiW7=X0vp@RS z6R>ewQ0@6M7Tp$l#2-H1bb61E@%?0N-+E?4V8~U_DcN_#6`wJ$`v_Ky_!2YkVozos`i{XLy zm@#2ni>ci6F(;!kwe)xK1Wz(ow;VeY4CJxeyI{%GKuS-*#dLj=iD*GQSGo*;&`W~q z)(zC$ry$)=pnmi;J-AdS6H~PC*$Uxhr{H(&QE{ae3F1;eFft51ksB z#CZ(je}nYtR0U?}ar#xTDmD_)o@Gw3uX%QW_g4;Is3f=lMQw}v9()^(j(J@>gJ$aw zLReiTU2UN`pi457EoL(NpapVx2@AU!7=9h}{@Oe0O~vHq0XI@#OaI3dZw00w^ztr) z>yO$Kunx+CMm>-_ZZGwo)PkeGXBZW&1d#EEGTBxp*f*hyb}>?%iPdv~b9+HOn#L59 zE}>};TZ!6q<$fp+HDo`7xS@W;)@;qB+RAEG^_i=+eNiB(o_Kd9fVB+Dk z&5>3`=B1tn@uRdAhkbRJvyNAz%!~QK|SC$_kw0u5UnR! zR>=*mAd_31%-mQwt+d`ANvMVV_hCw3e^3Da;m>A#j}-R4QUB1aZvBpiYzb;nU2sa? zpu2xL{kBcX*nE#(>&~q-PmeYF>Z^0i2 zA#?l}cy4Y`5N-c&_@fhv0@}-|3;P;QO6;-d{6F!Az&TJozq+M(jS-r+TmJe;;w|7MzYs`$kf*6Uc1GKOXb2t zknVnl5(VMW5Ai(ShWF1?ci4?vY7!PpkSFd#_n+tIQu7%G4&Vjmha3Rc_D|K)eW0gx z!Jn5q=QAtGO0jxby{YT@jrzO@aE8aRr*6nVA*}&iy3Z;JM%gxkN4KcNt^-njCf;QQ z^CbN^C78KBjh@rP;3B@peRmS?^#nSpWT<}l37J0|%We&)mjvI<$A>(IWUbRb26et9 zUQZovq{-mjWl`nQ3x8sWzFpg`y-?fZdECQ-5-u$PPS+wPTnQ@p9&+Y_75EF42;3I0~H;}&)?C%%Qd;xZp zoc27uJUO38ZibJL)9PTx-O=A7U;8dTXlcG(5~*2*cO8RmUXASAA#UL&RQ=X8-z0~( zooG!Z>lb1=gYo7wL6%qzV&ot^lQ#BM&viS6N|JT(Zv;8NAL!d1%KZ{Y?4Ug8ldZAd zOmMh%wyjpXnu;leYp3JO!Fg1`lumYxoBqoXILO@uGBW%_zI9 zwVAG`Q=rZiq1vepGY&q*V|{}Cq%omBSsSJwqJE$jmit-ws5kufFDGJKtkK&J^zQXp#Qtji+$+A)}9>kRujc5tp53mt=N}*p;h@r#1i|)TaBEnNQqfQoW%w zg=Yg6;(v5)w8BqlYkx;YX9D<^7q$8Dv{W#+<7S99l0lj}h{teRe;@9WTHZW3V*y%P zgImj^DVrDu`RIpevx->i$F$pU)$8=ePV^+&W6Xbz6Z&L*4cxOkRP%L)x6_XcO~l*# znD|T?ys{2Fc`k?vQa=?&ocu#hVjt(-0-ChbI;%sJir7@$LvlF>n>4?c=_ohkSNQ5Z zxd+#vz0!zS9tH*PN4(SV=C{P%KKHz4uf|L2Mr=st&C0C5#@Hj%K!0D(3GTr9%EBW% zfOc|IwcDPkMt`{Q9MOk<%p}ajzK~mN0SM@6Xzw5J%f>;QaYU)U<8Ha6^(4;L1l&8R zsTGgqHS#LcS=Ummp(K2sc37vwv0MD;GC`;bV*L)HGH?=JkyPQ7q!08PENbyJBsyB1 zy_8~>VH7jWe#W;PiN$=1n|T^J>mSU8Sg^0rV>1>Twie%e4{aiU#G-r;OyOTaDu~zK zp?`F~xdAIajOft2tZOyeIg=-aaY~K3k)zquQr0JRNirMZ38!5E&gz1GFNYRL!c!Q@ zCuGieBnVM{w7(0_NceR*?=EGXN7iamIq(~_=m;{`c6{A+*lAJ&C0cAhn)yAbQk58s z)SnUYhf?!G@i?b>noiQQ+!JqLfeBtlI#H39JaHXfnAAfRz)$nD-cCsVMdWNS_Tg#J z#|mqYv8O)9Bm16HJxkVqJ-SLNPFGV4_Z*)tQ9r=lT^>(QHJ=f4TFxCImP8(tEc((1 zyALmIthNxztqVfXTJou6-k7o4j?B{(>L6ypMH7hvTmLHeUVALlH2eZN zS(%YloLk(_nLI@+ZegCsZ&2zYzF!wChTB-63oQeyrI7hjFKE`)D!6t#4}g{(Lub;T z{+V`FG{|kN+b-%2-G^5v)m;DK8JAZ!sf|EmiKe@$i}f4Y4-5|FU7`(-xKC$daUGyb ztdMd_(b;uL^jSgBcMpSraRFO&A$U9S@IrAs)MFquX0Zzmi!%bA>%jb&qhPk~wQf@X z)`@DGl}5BVj_QTapveEA*&wE2#@p{wLwgRZ=mjzOwf1{Nvl^kDCezy=L<(fe;A*^u z{?LCZ@0x_%eMWBYGrm=dDD6dTnWy+Jzmh8kD~o=SQz37o1ZW{m&?9xge%p`V(Gq@+ zpq`}`mC`Bb>#y-8Rw8K<9gHDva)nrPOKxe=)zf&A)JJE+twpiIq=H9k?fP?P{*J{X zomUcHe2;F6mwEyml#L%!k5!aKdaDrmkj|GhY>blJ9Woaz$dl@a>gyg8t7wPpNmcnM zWc37h&lgBl6L7$#w?L|V6yA9X+Wg3GWp+n9>A5$D3kCs<=+{FW?h1G5f4fKsBFmm6J;57Di6^(|0xB;S!*)UC+GF}#)etXbx$ zOV#EKe6v^V{440b9jzqKKZ{+SiOm&pP<&E;vxn%xw|KwOb>TwJ+EGE< zoWDQgIZ_MP4%!buV;4c+o#sA#4Q-MdqF)Q>kUx1oacp-UZOK_UgSscfABXLZ6pEQ{4u8SKMcFysef)y!jsVIdpz zXU=yeXE+m?m%6|x{u{wtW!_i&kcB1{l~U;|HKgBjRvLO@4O&yW*sfE5Vy zv^>md%wpYw_MHLMq~3oqchnx<_Y_?;6$(nmqc1gF4)YEX!k185s-vVQN4TILyeGBp zf_W=-hgO_P zO+K}p-Uz9el_xD_hhOU+s=uVFQo6;YA1IqsS%((&@w5lrPx4-kQ!WqZ7ls;faJ=-s zjN;oh4T+$X<9kw2q8PxiIWqyr?C>5dLuA<@haI&L#>IG`p_k`%E zuv77LQ$zP&HW{F!P+h8s&+`_E0~X=ATlq{2RwUMXTWsil{9No1shB?pN7O^tUuIYF zP*tkTM?r0=@GFRvOMSZ3)JxTyhV7Hz;Uh822cgPAp?W>M<1~1985De>7iNc|XJ#0E zpmrwvONILuQ&%_wDOh2AZT!vNDsZbW=R0}qrZ#*d^?kpf`=o17)}GGE%WW%tRXeEC z8w-a>oo^?qtECFg%`Rm=oYca}tgLM8bLlG*$^ODP1IE_|y_mV#Sb#4$i1kaSnS$MN z3{7&0_e<5SR3WMZ0@}-@s(VmGZb|9xkSe*B*cCFf zLHaDjx07ngk$fhH&o9Bol`6W6XovG5s!R7!FFGAtavD-WEcSs^sqet6Sh24lN@!+jHT_J#gk)-YKi^&Qt2Z!!wb=@7ZMsRx^kqX4ZN&HIOzxOhyI+`9DIfT{9P&*#Sfdu6C?^HSrX|`91E9^F`nrE8a5jIHF!D( z-IE8^$MC*ha70hmqjJmYd_&?%y;yfGDu_F=zjgdf>Sk9H5pc1qFy0(N*76Z&F6S-X z8CyB&Omvb|(HEc#t+n|RmGGiXq$YHBsHRdfhs)u?6m}v!-4D8dgWes%*-JcL?z~@E z*DRhPJ!aAuB=@CsY7GwQ*DR=&Mifos?4@RT73-3I62bJ79#EatwudK2u*M5K`y=zV z@qzgl&q?4(^ZA>>J@-4kz`vm@C1=}?r^r)9N_WF0ZMpGe(r8ntF`XQBeKHI&rfF`1 z8ZxJ^DRr{Hz>y-p>vgFP1r{r8CVFG2T=<234VGpM{_Jf9zj zJkCN69-tqjuQHpzN#B#kcL(#^`e-$o*p;^%TZPJ>H-qpD{lG?bjL z^dd>OUJ84u4`n5~SOZ>4r{6+;S09Rq9e5TF2Ga=oNuP++kjBGb5{vR-n@nZDQpugo zZ`_FW%3BA*aFv7L2DhlXSkiiJAP4w82i?iXz={JWJL$0{UDXjao0Mjopy+@7xsoUFlx zZ*_!wBM;fnVK-6c&<8d~ozyt9S1OEs=U!e$^-Qd7K~dr7K$ zA3|F>NrkhO4$G>Xf^@kqVrNnry^ZIjql2Z>W+`{G^gvGH=Rcscq_$nOw^#>-kUy#Y z7rqvKUj%x;(nT6KL%}>w_YrzXG`7fe6*RhZ6HE2|5x&0^os-7@-e)IgSdaK;`L*1# z-V2<`Gjz;u{Y&GqF8e&fXQhMmEc};=&v1n7;c;kE9t|ru(qXdf09t*ep4 zwQx-WXCYPY(rMX})mKN~3ZKXG`$W!Ex)`QH%PizeIvS-vRyani2U+o1ekWGlU3BFb z-rWwJDxT*Oe5Q*~@gcjAUUk8)m0d4q^?wj|PYvmI!OW^c^s_WSZ_YVOU&y4;Tk2t1 zNhCZSI!S!*ENi+CA01@<=UCwk{Fv`JQR$&CPPh7C;vrI%UymJ0$4mPVza+6ju|Jpc z4e4E#9%7+fd*mXUpUUTCWz*TO@Pwar-_)h6S^9CrekjB$s-y8UxQB&KlBsf`Wn+<% zxA|!+_V*lbUAoq#PgDA!q-!Rf_l@9fg58_VQ>Ei9oA)R4_w$^Ba7t?ECXpIMsWX(7 zN{@dKFZ3vX7Y{~yi4yT@dmGodhkL>=qq!flIQ4JX{S>~F#50%hp2Hy;Y35WSCel|V zKQD|8B{)m-kZ93+VzY@vi0+?-rUONf-xNk0wB;vfctTrle9=dece#&mZsP@a;5)jx z2rhnzRQ-$0pM<`1&^j`=qE3i|r9b8Z@+@|u^gh&qdNLuoD;*|s3nYakOX`zyLpEc7 zI8|gp&>E(*57D8bLFA;iu(Phjw(gQI{EPo$sFC0r$(SOkCRDOTtj z)>#*ADsvuRhUzoAv7d9icMzO$6dDO0l614ZBo4fUb>?^GRwwo`k`tD$xkpGweO51h zU{djM9{P`l7Gm8cplihj-3o8lKre`ABKDV9oL4z<=_9U3>`*W-vf$C7*o+66h$DSr z`CVXJ;hwUr3CzaOSvBAcCZUaD%^3DM6KhQ>P^4!o9$Rl1Qayz?3&%8PWs)Nhy*U-z zdJ89-%{rFC?{Xtbr)k}gpDGgFfm4?rjC*Li+DN3_L(-2VT}^_a@HWrPfW~)`+Bn`X zcTzCKG1*9gR2mezTBgQ^@twW+=hD9|^Tji`g_rQ;G-RwCD=dIcy3cB4LZI~jbTxiL#`5Lz2$XbD z?==O@P>{11jDlpIaWCWp?m+8`AJ_nWBR7HAwxYZ8<=oBs;#sZ8br!!l%-yzy{p3J} zqdZ?`*Y(%G(8We6z-=94&V*7L5}Hm-PPFhKY>Nh*oeQ}*$o{Ib;#A&}hg@t9>6^~j ze|bD}GrtA94XRdSCr5av@NpU^8G)r+18#JhA7bInfO}@~uAQuV3hzD4XU?H-gtvsV zq+2x|K9!!^GUnDL$X%N_xWAqgb8LwkW4{ zfj9JqpSSVnFKFs8TOn!Ld}eFtrme;|1ZP5Yfs0d=S%Ga?;cz%G0Ee~a4sxKUdqF+1 zHBMpm?!i;9&fm+zHBI2wDs%>ngj%vD!B3DI--&g9O5cwS@+bK&$snabLAgsL)*_NA ztChQ3a6YaO8^|D={f+THRzU=B7K=wLH@WY-V-Mx9#$0r<_>bV-vx92vl8Kl+BbB`i zK89Fqbvdj1@OB_X2a!~X6$y$%22TMKMxPO;VS9N%8yP-AEWdpE#=P{sCL@eiQFHD?iZo0 zcr2M%B#U_7BJQka{98JUs_~@qaGGeU(Y#GO*Lm!rqv_`cctHkCY#ga}k>37xAw4J5 z$bxotIQ?v5{%J^Jebyu%h~P*FU32(`8w*zFei{SkMT97p7TVik-m9XoTESxx=(h;y zEr0KbURi+OqlbI~@%hTY0b4j@L8%%6h4a1fWL6f&{?GGWu`|l^?sP29@Adn7Kk^U( z)+@9TB#CMK*~YuYBbJUh=`0p6MlcoHkawtTd}(wc9yyGiC$pntd`mh#gFI2ZmV)qy z*uVwh{}G|+^bM+DeXRchHrFTE*B#)Vv+SW7ai_1KqTD|1(Oy&ew)EczcyABRq#D{q zd<-Xdww&-u{cF8yXz!x=q=POQs=Xp=c?(`n=JQ9Os|tTqgJ+-X(qFcXC%TD$#bf<6 zfU?K%?w4_{5~0Z8`GQuH3ztknpX%H;;>Y%eH;=%F;)kCJS!lg@&sKPNJG9+FT&5V7 zdk6L`oqMz4lxb*T1sy$rXLShOcex>c6Q5V4LLw)5*ujbXUTh7~anfTMPj!@Zo;GKl z-MOg+9j6c)T%rdO3z3fK*>Kk`)-H$_k^ykR8O=By*>O4?*o~;oX1*(TMnRsH!wR~G ztl~##$n!iopZC+DiB#)sXNSd*EJj^qbpx`6)&?PkHMb32z!TOWA9-kpcF_1N zI~A|K4m&CWm)^urU5{M<3QexSyE(i~_(>vaN1#|SJ|lk7Hndk3KN%VNd0%+-5KmgK zORP+MADNgL#)(UmLaNrz!;car0WlR`cpa+ednf(4^@JZ5hj>u>6-B#==8=BI3uu4o zY+cO#R|wxh@CLTC!+3TecKAh3Rc^t$JX!1o>FWHAniJ7hB1?irBQ{)fG{H;VjRZ=3 zN+ur^;R<&%#fwLYyUN%^Ae27g7~9obL)Yh~TnJg?{ZhZHecId}I+d=?d4$eW=27 z52?{R2@O-IC_Ro27ELsrx1VF3=lEujJ-p5NEaq-?Lyw27NHDSF?V`^{5LYS02`boP z!k1F(@?&Vub27SrB+qGy^d3jwhy*uBk4vYk8>)8Xt9cq~NIuV#`^qjCgLK(a^IMXMYYliTp_1OMJUz{HasW zsar@VxzRv^8I#T%Bo>kim2+8v*d#5`XA-OG&3!BTp2=<12<{XQTx_k$c%IkDa*4%x zgwKmjF7@k&dAA_1Nt{FOI?2U|+$CaZO58Au48mbfX$0R9S_pzpI#fH$=VcF~yE5S{ z@hkJsNKn3Zpcl`x8zp4j#gV5|LAxu$r`vLihz%*0Oa?R(OIO}4-ljwkq!y?--*1W@ z_fz??BV@Vc^0Q;yUCY?3*uPn2XhGuVTfCSKAkP6=Y1Y5)VTm`K?S% z7u_cwob)qK;4^X5dCFZPwuy_l|N9^uIf!5#LaPsFzp1Py--;dxEkzG88;**cE_yd3 zk~PZuvqSHcSkfr?S#k%LxRL6^BL&$_CeH}xz1gg48tcvE4iKcS8l33?eQ`)<$Q(=Y zarzQhaB?e(hy8&66-%iCTBHIR_9APV!CpjviI!=>Gna5$f|}BwwfE-Ty`j8lbMbwT zuqvq&k*;y!`DURfh)tNxx2o|Q*;#WWNKmSzOIxrP4zusmNcAvys2rbYi7!|fYc&pj zkWOKVeb)%BO!D4+L#HcyYlS|q#T}l?GsJe1J6~??WY&@iWh7cRfW5cJvXI!-L2QI? zc*j#L$>;c6f^ahdiCPAq{$y+-zFw6bDrh^2qHJdEe*XOjIcYf)>1LNagGh^b+Nsz` zBSSxx`=>d-0|yyB_BIi2!8jBrW)Hiu48?B# zfjd>IE6(#LKlgKlXVeMtlUSS*AxTC)s&gXMd7|jRtxzi!UG_pxha%VU^hGBp!8ww_U5I-|?i#@X5W6LZ|HOM4M{X|~e`P3||5u_S&v{2{?8xto(&*f$?6w(ul&*S- z%1HcFya%cCOoKxCHvM8GK&)o5E#$;L<|Y;lJwfLak5OU^XW)w})YQC%XIGZ@)?vSb zMN<`;_JHCoptwl6#0ye+k|0}5M&CWrXFv^;x#3~VSaY~JLe~L-)T@od`v+LnZcT-^EZ*mGidFs&@IppDbMA5 zTiKytT}{N|5#5su)gp;v^+6k#C;lq3uofxp$O?LLf&um~yO6BA__y78zMwSpV2`qA z@eq1I-JwQZ;{(G*mTC;^6b&<#6F&^a1nEt*aTxDk#wsN;TMG&bT16zfWi;#0NB$5j zkvV8|xjWv67PpWKL9&$7S;l(=>m-BsPeBW&@?6P=$`gee*YKp<>j%+xH9|MPWP7Xg zpH%i&htnlqHaZk@6)pZ6PrnWA1d&jp#S%qWjNWd7MjVC@c?Jqflv=FHRGt!m)3>nF z5&T@dtPFPPLHm4-{7XD{5$867=S*imr^&k~;g=3)rQzbMzck5)Je| z=OZ{Of`%g#sXs<1cSNHl^912%xd|ouk;~4uaRwrb!uukp^+Ot8qCr0L=VaH{5((2 z=LOXU5u9W+|MliAE+R8`jC=a)X!s0Pk&4EUn_2!OvG%f@gJ?|Ag>|{h#aqq4+ayYm z3Gd3yE_zpV-F581XZU%~d81T}h;O)v_dFx!DxYr2>7}xA!G09Zk^4^cZF%&r*f4_n zMRS<0`9;4)Q3UW_KoKCVm{n0nuphGe4um(^&4$DvM=^Xe??pZgnxD5DK?EY9Z z>maClgZEcM-@L$b&5v@_;CrJ(>y;hm!g*3JCU(|!UG$Qmo=W^uKA*&Q#m|)!%=bLR zzE+WFp-5ZqN3rLQ@-&H9yI6zdjUkl zvBxA2T^K4bVJ)QV^Q*#|p|Acz*WBaN!c8x@@g{TgeT^g(RkQWq*PzcAh71 zW1oWYDd)Wu&dugD2jG7ffj7ism7DD%-w>Ua1>Z=lRVLI)25URJ--(5^f_DnS@q|$B ze>qmC#5_lH=29Q&LYAd6L9DjF=p&gD^5pVy+ysGGJWn^cwwcJJ*k4k2aRKfch>s@~ z3epeoJG@+tHAsF^dUjvpf6Tx_ko!R1BX_>Uj^u`sh?^iMAK^|oPSt@pV zw1apby`hz1mcb*FJN_p1LsIc3R-$C5Cvs+z?^}YdodRD8>eUFMuQKUeDw4zt&4K$5 z7$wX>IJ4Jz`&f1^nlFbF5PHTjzvH%kQkTer zM64utdVyz;;0$x%s)j^$mcc=S^%#rwFLu0GLQKKMb8>RmFC|vB72fEJZu*|TiH>-U zb=2fM+aWERxiuxf+{|FM1UI_qnNgg`QF!icw1`-89?m+QbL(g_nFD^Fh_;c~hKA3Q z&N<2qd7+Kyc&YYLu-wERiZdm$J(JGeyHwkVG$%oQiGj&yMITJ$tlF{zv3f@GyZj0* z@yeL+%x=rF&ZhjXE^n>RIxD~t$9Z-twI(<4oJ9*u^j_jhi6I`!&(nzgB;LJX3d_lf zJt3W;a%W4E#-kF{(>k2fVQBC+cFR#{CiyL~wj|yncB$loBmyRJ zK=FCSFBlCM9>#(YiIhqpsX&(4P+I7xQrDIPUrLrP7aGS9gC2`NoXgtsBREr$$F4}k zA^1da!^9&KO(~TPxjZMDTdM(*HU$k=8ZMa1HzlJc-lZV><=g5aMfup*q8Ftq;2c~d z-dR3c?_o6Iz0mC>xmT$SkR6JbT?pB5AuX{X3Q0b?J}VY4R#5H4(-4^uFGTdd)MQGR zrA)jPjeL~n3$KVbE-_lETo(F>MhU+Jv5*^C)*%>cBiXN1dK@D% zU7jaN^j+jzCa=l=7jNVLO1cVoD~c|@U3a_p-n$R!N4K;f0us`Vgrsx{NJtAjm3l~t zgglX!kdB9RN(o9SNJw`G629-he82h4?97=nXJ&S1W@paKITL9rjyU~?HqwjP4JD7{k)!{1Bx4+Do~;6Zv}^PKouEki zG~y&Qz{nMyfQ)oYMt`Y6Xnna+E*&FYMEMWkN9W=qE@reRdJ4SOXm#=bzg5IVj&}1S zjd<6?6s(FyV}y^my~EKPqqC{&(eI{!7xV;Wjpo!{QID>eH7>#%d?y?6X0(bpp5@>4 zsQ=HDBW>>{dQNm=IgTE880miiFJ&Xz^?#UIS;#-)TP3inSdKiOqSr>Pqa5CXi9Gh9 z4@X?{FVTvwVGN#&x8EG~ErMBIHSh2)w(^un2$!>Dbf-!PidMt|x1sLv|2tMm9Ohwz_Ui2bUD z$fNz65xgb-5s?ncJZPyAXSWExR8^eOh&a6wXD-ru80{krM%f%tj`SBtT8*cpeI)P? zj&1^sPM=0PLkqq6uS7hP=mcCDj4%)J_M(#t(dZKGCLP2qqb}M;bXGJPExO?gHo*6b zN)TzSe2hBIK>vxjkUZ*=j+-pr0sZLPL|SAcS-(j0bp(kxAbHX5bKz@5JNI2dGeFIw z?=}H>MW=ES=--i6--wGOUuxMpI32lkPI30}_ z(M%*dWft}Bi1$_&C5^OIM!Fx{<7*7SyNPaUiTH1eK^d0FF>D6DI6^+wwNUG%orDLqp9 zpwIO{DQ(oRHuml>g-^l|?V<@vb{@3qS4EAxp#*8@n zk^{igxfV7D)@7_H2IDOaz)Vm{S)MW~<#E^r?a0G=hDiA#9ETj2q!di~6WotR*y|{p zawO~vp3pRmbQRI6Zh=cyBYYaBq+AH!#ovuYnX}RSz;IRaXGkpe2wNmsNS>Vu*Ft`2JmgYGLe^j%&f5ML zx;Sq;3w!^I!=vGpuu!-^92AZViBNeVM>!&;DsoC=*lXOf>Je}!b^^yH@G zg5)2`Q^}tow`@Vy??&Qqav0)oC%c6&l8wW7m>>0?oV*1sA9<5=lev;@k{>4Jf>wsz&O7dQ^Cp6(Sfi0Unnz)%TlZ_z3 zT_JHL;Q=xRnrNmVhbGCtpnc@+#I{6N+z2}qG=?M=LxQ|a;$Y&##E?YO#LmP!$uxYA zBZ*SUj6}6WGMP*qPq2w{iJHkN&@oK zXCxSu;x6vi?38E>iv93D9>mSW#`u}|Z}HjC)>1n$4br=xp$sqM^Wxd#exg5Q?+e6l z#?Rpn)NAo~5?kXP<89;R<2~awAwSh6?gC;Z{J0yR75ouoj}MNQMw)x^F!5iUOYDiK zCI&*v_*qak-Y5PH+8?e!4(llDkQE;hUl4B*_Yz-1tHwb{;tz{M7g7A}c(M4a;8gH? zPzL$TiMNa|hiMnjk=Ps07tale>l~1je>Yw)J~Ey^J|VsaZ{lJ6t;FGYn|Lb9WTDgs z@C!o|tQ+^^4T2wo^+A>R$e=gyj|K0?&3Hm95J?jyfV zLA#(qPzyPhL@r~4CBd~I9;f5K27d<45qrcx?{DyL`rU#dK{doK3>F2)g9<^}zz(_~ z_pw32;GdvOkQuZHh~R`@7y5OCV59%UZyG%I3kUB78~irGdcQhK(>S>27YRh9Uf^H% z@B5ehU;O5Nf4`Jp*Z;|X=x_J41qGn@Vvo;5L()TpmitSQdk3Ehj`<~nINbLBIfU%s zxPQU_)^8nL_ft{wYQca0QN(-@jP3$Gg@<$`D<^Du}p=*a% zda^&%PxH@$a(18c4|wyv0p1{Qtl!9Q;1j+Kow)h^g@9dhD|$N-)5@RWjq`SS>E3bg zLvNzD$otsO&^Wq8IajcFTB4FPB%+tKwaB=X&|Qnch@yho|^U zz2RO>uemqR&Efs)X7hSL3!d(u^s>BsepCNnP|>|*uH>U{ZW;H8d(%CH{3ilRc^p#p^-j5ukYlR%%H_QYpgR+x0nii}QCa5haaFIA z`^x>t&5gRBcJH_kKqHU)(h1#aZa;U3`-@Y??d2L?F_eV_WHL&y%gyd(qGX4l({hqq z$Gz?}cTYOsxqV#0{Q}{!?#FIbH{G4(o^sRNq`TR1+*8hD$9KPRes^{`51iueKxeKq z+@ai7&N?TotExr z&RXZ9(-~&D)85(R>;{D%?$^k-Bg!p83+!pXdY{JFT2iPC;jq^RBbZne2Sz zR6{O3oW9T>JImSX9B>XgZJd10FLo=ZKPdiZr#kgff^JSTr<~KyNk!~U+j0)rXY8to zY2(y(ET^NBaC$pGIdz@+&I)IabI*CtS>ybJvd?$&IwPD#b_vHu9cwsO?bc2MXN>cX zbIq>qJg`eSx9yzH6T6?2bSgV^CAGBrXA+Yw?dF&x}ExVh&%bsYL2aQ$sclKhtnBB_mYj?3T?Dh5)d%JxX z_-E|7_Q&=jdzO9J9)x(#o{cnFfZPR@<91Ep%>>5Zfc#~DZx6NigH~&odVb%z%zE$0tW6ia0T3=d^tskuw)$-KuDv3J2w9Z?hJq-BYS#_-Q* za1L6j(1Jb5>Sgt{23kF>b=EWM5K{bx)F-U9mS>f-$^c&6nqtkgYFeh%)+!0(TV)YS zSo^GZti@IntC01+RRVNJTGOr1tnSuiYninQG4-u4EXAs4$<|v|%-Utmw-#B~te4gS zE8Wsja^E^_?lXTis{-R&tAP~&`=xo>++dzEubB0bz7im(%?0LubD+7=%xgX{?*aQC zvxIfn{M+1O{%a00ADfHK-%ZP6tsCZ3b0Of*%o*mlW|oADSyIjX zW@EFGS;eeiD&{QQFWJN_1EZOJ5!=(OXTFVegG||cY}_+SgI;d)iE+i)X~a?Ua;X1R z4Wj2=cK<11r?(bxFYm~UJ+78;w3F-8?5%h+xdFgF^%8*7aL#$Kbe(aiY3m}#sr zmKqC;$;LtB8)KSL)_9?(8pZG|f)cz1ymp{k9gqk5Grco>O^vI1P2*!jF-&8#zF1$Y zU(jFc*YzFxB|R`6>h%oHxT9Av9_g)&pY_T{PGh)%t6YtA{gqz8@IbARQOo$+NHY$A zc30zl!$n!H>Ff37`mcJ-IIdsTujASU)+InDb(JpBhwfP#Wt0+m9R$M=()kQi&p94w?a_ys6*ZIwC}`mJhduhf#7ujSG%tATb_eW{*Qzg9`@pn6*s z5O+d-q2>a0S$m+~RnMrtc2Rw*W&)N&yRPQZmZ*o-Kh)*wJawFU6lt!jtJR0LGQ3I#->b)>PBf_G%;bGxY~`srrvP6=ld&DNx;`_Eop5^VN^k zUTO~YU3E983{fY8UVC+s+DUDq)>B)k2h_D{L2W#8U88nUQ`P!vQcb9%5nDrT3E%tb z2WmUDg4$Ru0_;G2s_as(DZeT?)YnRiDyvVFINS%yUFDeaP+`DvJ6D;l;`*B}3V+>{K2pmzAFpKB}x$HY>fA$w~+1OXY&HPI;m% zQACwMx+BV5Ws@>V>4BJ!m2Z^2%1~v!(pMRyv`|_rm6bGvCn%Z93FQaGexj5|Tr=e> zrK0i$Qv9HNugp{mAf>ESSN6&h{1cQ)C_!(fozg&2f&W~N;aMCxGF8_Te+d!Q|>Iclq<rr1@<;M}awzAOJvo=$0d6+=N{p0?%DLqd z@~^SGF-~sqrd-XCwi)1MWl25}>mOSb`!2RIb|IEsHsnHbN%?u~Tx@;pPV84eSH^yb zU5x2+T+S|U0d#Tf!`PYFh}eqQuGl@`i1M-6j@VjY?Tzh>osMmbor+C~Esv$gX2(V& z^;J+m99sa)Bf#4nn*9#frx&#hS!g#6AX2CMZmbO^&M$h&7D$L`<>RL8)y_0AA@B7fZyRNJMP6v`bnoJ(F%qk0c85 z&!o%JW9c+(Hegi-l`63d(knp!ljzuaDGUC#pk5^QSSk^_Dcz9{NV}y4(oyM!^pnKK zGNoHcO~n3?=1EheKGJv6kJ4|z$doQg$E4fRHQ-K=R!9@2@1<5!Z)v`C2pGquBhn2} zIxY2-`b$NmZc=+`lr&RnE{&A3OG&AWluc?aRg;Fo9VRV9PG3lUrO%}XQXwgq)I#bY z)t3rOoux`r7pW$2lTr?;xKu+bDfN>+ltxH{rG?TEshLzq$|ohH{8Db|Ke3QhT6!Cl zQ=|$~L0~tP@QMP`o2Pff1z(;%V_L%u4Z; zI8)3JzY`COlf|9l0CASsU7RmY5;p*vE{+q2i9Z4Il{iSOFOCu0ic7?e;!<&+coLZD z;tp}PI0N=uaShTe7kk4F5*H%f2(gFQQ7kT25-W%wiCx4`K_f$)Doz2l24WiA5@M=& zPbegYVox!zSX8VgHWS|!D~peXisE}>L$Rw^SWFSyh$TVE5hallE%9GL5#!>0!9%Et z*j%h9*21%(m`i*u{36^Ct_l_4&n5DpT~d5Y6vS1+X<@FgP&g<|6fOv_1Rkjsahq^l z*de?YRte{YLx4UKvV^n3KY$(+jtYB)6T*)|rZ7|Z9{wZ3YGJ>ySXd;i6t)NpfYD#* zE#wla3FU-V!Z2Zuum+gRgb#!^LUy5yP+n**bQ0PNgOOsjFjN>T^b$T6Y73)<)U zFWj0!ccF-oTSy3^U5zh5Eqpc$Fu3l0VNq;U02#Va{*{e}^Oa ztK13r*K_B%vmC=e<0RNy9K~PYR&iUnt=wiVgWJumk4Qmt_@d(dml0R5aV%iPUC8Esa#90B=Aab#kitejLXh3 zoW#9i^TQfkz~$vkj^(bhcUYc#!2ZKtU~TSimg07^57;B@8TL>1F?*LiiTFz_$z`#( z;NQ+3MBFBJ3%id!#vW$(0Ba9>h+WIBW*4y;>;iTro5}tN$V7G(o6gQ;7qVZlquE_> zm$TE^5r9l(C$Ur5E^L2x5ZjsU&JJYzu(J^}g&hoc5}@s2JF;EbZtM_t06Pu11K4^9 zeaJRsi?J=)@@#9iBHNCw!L~&>7n_asSc}bxXIWNa9kvLY!peBstPWRUU6zDTf_=$c zV18q+FqfH&%p>MDbCtQvyg>K@bB5W$9AyqLCzylGZssI&4E}>mCbOB@!)#>^GfS8) z2p?xoA@nP=g4w{VW0t{8U=}k!GP9XQ%u*(U*~YAdnaGS~Ml%ot`IGoDFfzFrmFWk6Z>BHPocWk(%+zG+F;$s&nHtOo zc$Q`wGIf|v@RwzBFnM7LGDVm?OktSPOg<)+ahMcFWwL0Fxj_F-KcQJhU|!NB^N1#x zXY>R5EPaGNMxVj+9OBQ@f6yoC-|0j2QF3Vd1x&>@`x*<#rx&mFAu0-dc3(-aB!gL9` zEPNrI3hUFk=$tTx=Z0aj&EH$3`g8H0FqsCApsnIZL)HrGw^%>QL>O=LX22-7>fmC1E{!}-r zBh`ayK{bc{fNDfFfoVxKpsG`~s47%NsvK36DvM`%syJ1EDuPfUDmRs#$^|zsmB2F_ z6{i9`Ej&3YMp2YRk<`EB1M&s=n0!h;BJY#WVIRQWL+B=acgVZs74i~!f&7C!L!Kb_ zlgG&eat*l}W+l0RTt?0$7n0M-`Q&VJE;$d+S>!bMXOT0= zaby}fh8#wYC5OX~BtL)i97ujfenNf<+l_2Tb|gEHoyiZ$mSi)s1=*NvL{=wjl6A>C zWW6_T4YC$lg{(wYB+HP6$zo&?vN+uQaPyL>WHvH|Ou)YN=9!Ij$vA0~3JguMBm+yp zW)WG$bK(i{kho6VCjKVw5f|aRMBE~-5a)?=#A)Iz+~0_k#4+LsahTXo93b`(JMhdT zb`k4{4a9n4EwPGNMl2^*5-Z@YATo#r#9ZQAm~>(WG4+j^0RMO*jTi$nf*1}v4DP4I zK%y_v3#JRvjp$5tfN2ZUnrK0^A{rCThz7(5L|vj5@jg+Lc$cV7R3<7B6^RN&X_%r! saiTC$kSIi?68VUnL@ojw@ Date: Sun, 15 May 2011 23:49:08 +1000 Subject: [PATCH 40/43] reduce defaults based on feedback and testing --- shared/uavobjectdefinition/stabilizationsettings.xml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index b11c0f1dc..80c2968f8 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -7,9 +7,9 @@ - - - + + + From 71d582495ee6e0d5455682120c7edb0562c4eb6c Mon Sep 17 00:00:00 2001 From: dankers Date: Mon, 16 May 2011 00:16:19 +1000 Subject: [PATCH 41/43] On arm bias calibration terms now matches boot calibration terms --- flight/Modules/Attitude/attitude.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 4aeea69a7..f4c892466 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -152,7 +152,7 @@ static void AttitudeTask(void *parameters) init = 0; } else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) { - accelKi = .01; + accelKi = 0.9; yawBiasRate = 0.23; init = 0; } else if (init == 0) { From 5e03cd5801bdf8dc97b2c87c9fee51879eff274e Mon Sep 17 00:00:00 2001 From: Oleg Semyonov Date: Sun, 15 May 2011 19:46:31 +0300 Subject: [PATCH 42/43] OP-483: clean up sequential build order, add CC-FlashEraser tool to the builds --- release/Makefile | 22 +++++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/release/Makefile b/release/Makefile index bf9817b25..882070fb6 100644 --- a/release/Makefile +++ b/release/Makefile @@ -24,6 +24,7 @@ BLUPD_DIR := $(FW_DIR)/bootloader_updaters # Setup targets FW_TARGETS_COMMON := ahrs pipxtreme FW_TARGETS_INPUT := coptercontrol openpilot +FW_TARGETS_TOOLS := coptercontrol FW_TARGETS := $(FW_TARGETS_COMMON) $(FW_TARGETS_INPUT) BL_TARGETS := $(addprefix bl_, $(FW_TARGETS)) BLUPD_TARGETS := $(addprefix blupd_, $(FW_TARGETS)) @@ -76,8 +77,8 @@ endef # Firmware for different input drivers $(eval $(call INSTALL_TEMPLATE,fw_common,uavobjects,$(FW_DIR),,-$(RELEASE_LBL),,,$(FW_TARGETS_COMMON),install)) $(eval $(call INSTALL_TEMPLATE,fw_pwm,uavobjects,$(FW_DIR),,-pwm-$(RELEASE_LBL),,clean,$(FW_TARGETS_INPUT),install)) -$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects fw_pwm,$(FW_DIR),,-spektrum-$(RELEASE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install)) -$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects fw_spektrum,$(FW_DIR),,-ppm-$(RELEASE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_spektrum,uavobjects,$(FW_DIR),,-spektrum-$(RELEASE_LBL),USE_SPEKTRUM=YES,clean,$(FW_TARGETS_INPUT),install)) +$(eval $(call INSTALL_TEMPLATE,fw_ppm,uavobjects,$(FW_DIR),,-ppm-$(RELEASE_LBL),USE_PPM=YES,clean,$(FW_TARGETS_INPUT),install)) # Bootloaders (change 'bin' to 'install' to install bootloaders too) $(eval $(call INSTALL_TEMPLATE,all_bl,uavobjects,$(BL_DIR),,-$(RELEASE_LBL),,,$(BL_TARGETS),bin)) @@ -88,20 +89,31 @@ $(eval $(call INSTALL_TEMPLATE,blupd_ahrs,all_bl,$(BLUPD_DIR),AHRS_,-$(RELEASE_L $(eval $(call INSTALL_TEMPLATE,blupd_openpilot,all_bl,$(BLUPD_DIR),OpenPilot_,-$(RELEASE_LBL),,,blupd_openpilot,install)) $(eval $(call INSTALL_TEMPLATE,blupd_pipxtreme,all_bl,$(BLUPD_DIR),PipXtreme_,-$(RELEASE_LBL),,,blupd_pipxtreme,install)) +# CopterControl flash eraser tool (change fw_spektrum to fw_ppm if fw_ppm is enabled in release_fw target below) +$(eval $(call INSTALL_TEMPLATE,fw_tools,uavobjects,$(BLUPD_DIR),,-FlashEraser-$(RELEASE_LBL),ERASE_FLASH=YES,clean,$(FW_TARGETS_TOOLS),install)) + # Order-only dependencies # They are bit complicated to support parallel (-j) builds and to -# create the pwm/ppm/spektrum targets in a sequence of build steps +# create the pwm/ppm/spektrum and CC flash eraser targets in a sequence of build steps -release: | release_flight release_ground +fw_pwm: | # default dependencies -release_flight: | release_fw release_blupd +fw_spektrum: | fw_pwm # sequential build + +fw_ppm: | fw_spektrum # sequential build + +fw_tools: | fw_spektrum # sequential build, replace fw_spektrum by fw_ppm if uncommented below release_fw: | fw_common fw_pwm fw_spektrum # fw_ppm release_blupd: | $(BLUPD_TARGETS) +release_flight: | release_fw release_blupd fw_tools + release_ground: | ground_package +release: | release_flight release_ground + .PHONY: help uavobjects all_clean release release_flight release_fw release_blupd release_ground # Decide on a verbosity level based on the V= parameter From 50f1e15f544c9a22b727252ec63de1bcf905c246 Mon Sep 17 00:00:00 2001 From: elafargue Date: Sun, 15 May 2011 22:48:18 +0200 Subject: [PATCH 43/43] Aditional artwork for GCS (artwork directory), plus show basic board info when connected on the uploader gadget. --- artwork/GCS Icons/README.txt | 1 + artwork/GCS Icons/application-certificate.svg | 443 ++++++++++++++++++ artwork/GCS Icons/icon-checkbox.svg | 91 ++++ artwork/GCS Icons/icon-gears.svg | 390 +++++++++++++++ artwork/GCS Icons/icon-info.svg | 131 ++++++ artwork/GCS Icons/icon-refresh.svg | 230 +++++++++ artwork/GCS Icons/icon-stop.svg | 130 +++++ .../uavobjectutil/uavobjectutilmanager.cpp | 30 ++ .../uavobjectutil/uavobjectutilmanager.h | 1 + .../src/plugins/uploader/Uploader.pluginspec | 1 + .../images/application-certificate.svg | 443 ++++++++++++++++++ .../plugins/uploader/runningdevicewidget.cpp | 131 ++++++ .../plugins/uploader/runningdevicewidget.h | 69 +++ .../plugins/uploader/runningdevicewidget.ui | 91 ++++ .../src/plugins/uploader/uploader.pro | 10 +- .../src/plugins/uploader/uploader.qrc | 1 + .../plugins/uploader/uploadergadgetwidget.cpp | 12 + .../plugins/uploader/uploadergadgetwidget.h | 1 + 18 files changed, 2203 insertions(+), 3 deletions(-) create mode 100644 artwork/GCS Icons/README.txt create mode 100644 artwork/GCS Icons/application-certificate.svg create mode 100644 artwork/GCS Icons/icon-checkbox.svg create mode 100644 artwork/GCS Icons/icon-gears.svg create mode 100644 artwork/GCS Icons/icon-info.svg create mode 100644 artwork/GCS Icons/icon-refresh.svg create mode 100644 artwork/GCS Icons/icon-stop.svg create mode 100644 ground/openpilotgcs/src/plugins/uploader/images/application-certificate.svg create mode 100644 ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp create mode 100644 ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h create mode 100644 ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui diff --git a/artwork/GCS Icons/README.txt b/artwork/GCS Icons/README.txt new file mode 100644 index 000000000..5c290233f --- /dev/null +++ b/artwork/GCS Icons/README.txt @@ -0,0 +1 @@ +Those icons come from the Tango set and are used in the GCS. diff --git a/artwork/GCS Icons/application-certificate.svg b/artwork/GCS Icons/application-certificate.svg new file mode 100644 index 000000000..077f741d8 --- /dev/null +++ b/artwork/GCS Icons/application-certificate.svg @@ -0,0 +1,443 @@ + + + + + + image/svg+xml + + + + + + CertificateJakub Steinercertificate + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/artwork/GCS Icons/icon-checkbox.svg b/artwork/GCS Icons/icon-checkbox.svg new file mode 100644 index 000000000..185dfc615 --- /dev/null +++ b/artwork/GCS Icons/icon-checkbox.svg @@ -0,0 +1,91 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/artwork/GCS Icons/icon-gears.svg b/artwork/GCS Icons/icon-gears.svg new file mode 100644 index 000000000..8e2572fce --- /dev/null +++ b/artwork/GCS Icons/icon-gears.svg @@ -0,0 +1,390 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/artwork/GCS Icons/icon-info.svg b/artwork/GCS Icons/icon-info.svg new file mode 100644 index 000000000..62c2cecd6 --- /dev/null +++ b/artwork/GCS Icons/icon-info.svg @@ -0,0 +1,131 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/artwork/GCS Icons/icon-refresh.svg b/artwork/GCS Icons/icon-refresh.svg new file mode 100644 index 000000000..3d0cc562d --- /dev/null +++ b/artwork/GCS Icons/icon-refresh.svg @@ -0,0 +1,230 @@ + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/artwork/GCS Icons/icon-stop.svg b/artwork/GCS Icons/icon-stop.svg new file mode 100644 index 000000000..8955e4375 --- /dev/null +++ b/artwork/GCS Icons/icon-stop.svg @@ -0,0 +1,130 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index 856fc6159..47ad9a8ae 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -143,6 +143,36 @@ int UAVObjectUtilManager::getBoardModel() return boardType; } +/** + * Get the UAV Board CPU Serial Number, for anyone interested. Return format is a byte array + */ +QByteArray UAVObjectUtilManager::getBoardCPUSerial() +{ + QByteArray cpuSerial; + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + if (!pm) + return 0; + UAVObjectManager *om = pm->getObject(); + if (!om) + return 0; + + UAVDataObject *obj = dynamic_cast(om->getObject(QString("FirmwareIAPObj"))); + // The code below will ask for the object update and wait for the updated to be received, + // or the timeout of the timer, set to 1 second. + QEventLoop loop; + connect(obj, SIGNAL(objectUpdated(UAVObject*)), &loop, SLOT(quit())); + QTimer::singleShot(1000, &loop, SLOT(quit())); // Create a timeout + obj->requestUpdate(); + loop.exec(); + + UAVObjectField* cpuField = obj->getField("CPUSerial"); + for (int i = 0; i < cpuField->getNumElements(); ++i) { + cpuSerial.append(cpuField->getValue(i).toUInt()); + } + return cpuSerial; +} + + // ****************************** // HomeLocation diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h index 8a97b60dd..f97f969d8 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.h @@ -61,6 +61,7 @@ public: int getTelemetrySerialPortSpeeds(QComboBox *comboBox); int getBoardModel(); + QByteArray getBoardCPUSerial(); private: QMutex *mutex; diff --git a/ground/openpilotgcs/src/plugins/uploader/Uploader.pluginspec b/ground/openpilotgcs/src/plugins/uploader/Uploader.pluginspec index b2c9a8777..6b24fe1e7 100755 --- a/ground/openpilotgcs/src/plugins/uploader/Uploader.pluginspec +++ b/ground/openpilotgcs/src/plugins/uploader/Uploader.pluginspec @@ -9,5 +9,6 @@ + diff --git a/ground/openpilotgcs/src/plugins/uploader/images/application-certificate.svg b/ground/openpilotgcs/src/plugins/uploader/images/application-certificate.svg new file mode 100644 index 000000000..077f741d8 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/images/application-certificate.svg @@ -0,0 +1,443 @@ + + + + + + image/svg+xml + + + + + + CertificateJakub Steinercertificate + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp new file mode 100644 index 000000000..7e9b1889b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp @@ -0,0 +1,131 @@ +/** + ****************************************************************************** + * + * @file runningdevicewidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Uploader Serial and USB Uploader Plugin + * @{ + * @brief The USB and Serial protocol uploader plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "runningdevicewidget.h" + +runningDeviceWidget::runningDeviceWidget(QWidget *parent) : + QWidget(parent) +{ + myDevice = new Ui_runningDeviceWidget(); + myDevice->setupUi(this); + devicePic = NULL; // Initialize pointer to null + + // Initialization of the Device icon display + myDevice->devicePicture->setScene(new QGraphicsScene(this)); + + QPixmap pix = QPixmap(QString(":uploader/images/view-refresh.svg")); + myDevice->statusIcon->setPixmap(pix); +} + + +void runningDeviceWidget::showEvent(QShowEvent *event) +{ + Q_UNUSED(event) + // Thit fitInView method should only be called now, once the + // widget is shown, otherwise it cannot compute its values and + // the result is usually a ahrsbargraph that is way too small. + if (devicePic) + myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio); +} + +void runningDeviceWidget::resizeEvent(QResizeEvent* event) +{ + Q_UNUSED(event); + if (devicePic) + myDevice->devicePicture->fitInView(devicePic, Qt::KeepAspectRatio); +} + +/** + Fills the various fields for the device + */ +void runningDeviceWidget::populate() +{ + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager* utilMngr = pm->getObject(); + int id = utilMngr->getBoardModel(); + + myDevice->deviceID->setText(QString("Device ID: ") + QString::number(id, 16)); + + // DeviceID tells us what sort of HW we have detected: + // display a nice icon: + myDevice->devicePicture->scene()->clear(); + if (devicePic) + delete devicePic; + devicePic = new QGraphicsSvgItem(); + devicePic->setSharedRenderer(new QSvgRenderer()); + + switch (id) { + case 0x0101: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0101.svg")); + break; + case 0x0301: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0301.svg")); + break; + case 0x0401: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0401.svg")); + break; + case 0x0201: + devicePic->renderer()->load(QString(":/uploader/images/deviceID-0201.svg")); + break; + default: + break; + } + devicePic->setElementId("device"); + myDevice->devicePicture->scene()->addItem(devicePic); + myDevice->devicePicture->setSceneRect(devicePic->boundingRect()); + myDevice->devicePicture->fitInView(devicePic,Qt::KeepAspectRatio); + + QString serial = utilMngr->getBoardCPUSerial().toHex(); + myDevice->cpuSerial->setText(serial); + + status("Ready...", STATUSICON_INFO); + +} + + +/** + Updates status message + */ +void runningDeviceWidget::status(QString str, StatusIcon ic) +{ + QPixmap px; + myDevice->statusLabel->setText(str); + switch (ic) { + case STATUSICON_RUNNING: + px.load(QString(":/uploader/images/system-run.svg")); + break; + case STATUSICON_OK: + px.load(QString(":/uploader/images/dialog-apply.svg")); + break; + case STATUSICON_FAIL: + px.load(QString(":/uploader/images/process-stop.svg")); + break; + default: + px.load(QString(":/uploader/images/gtk-info.svg")); + } + myDevice->statusIcon->setPixmap(px); +} diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h new file mode 100644 index 000000000..413a406fd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h @@ -0,0 +1,69 @@ +/** + ****************************************************************************** + * + * @file devicewidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup YModemUploader YModem Serial Uploader Plugin + * @{ + * @brief The YModem protocol serial uploader plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef RUNNINGDEVICEWIDGET_H +#define RUNNINGDEVICEWIDGET_H + +#include "ui_runningdevicewidget.h" +#include "uploadergadgetwidget.h" +#include +#include +#include +#include +#include "uavtalk/telemetrymanager.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include "uavobjectutilmanager.h" + +class runningDeviceWidget : public QWidget +{ + Q_OBJECT +public: + runningDeviceWidget( QWidget *parent = 0); + void populate(); + void freeze(); + QString setOpenFileName(); + QString setSaveFileName(); + typedef enum { STATUSICON_OK, STATUSICON_RUNNING, STATUSICON_FAIL, STATUSICON_INFO} StatusIcon; + +private: + Ui_runningDeviceWidget *myDevice; + int deviceID; + QGraphicsSvgItem *devicePic; + void status(QString str, StatusIcon ic); + + +signals: + +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + +}; + +#endif // RUNNINGDEVICEWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui new file mode 100644 index 000000000..105a385c7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.ui @@ -0,0 +1,91 @@ + + + runningDeviceWidget + + + + 0 + 0 + 516 + 253 + + + + Form + + + + + + + + + + ic + + + + + + + + 0 + 0 + + + + + 75 + true + + + + Status + + + + + + + + + DeviceID + + + + + + + CPU Serial: + + + + + + + + 160 + 160 + + + + background: transparent + + + QFrame::NoFrame + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.pro b/ground/openpilotgcs/src/plugins/uploader/uploader.pro index fac544066..05742868d 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.pro +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.pro @@ -6,6 +6,7 @@ include(../../plugins/coreplugin/coreplugin.pri) include(../../plugins/uavobjects/uavobjects.pri) include(../../plugins/uavtalk/uavtalk.pri) include(../../plugins/rawhid/rawhid.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) INCLUDEPATH += ../../libs/qextserialport/src HEADERS += uploadergadget.h \ @@ -20,7 +21,8 @@ HEADERS += uploadergadget.h \ SSP/port.h \ SSP/qssp.h \ SSP/qsspt.h \ - SSP/common.h + SSP/common.h \ + runningdevicewidget.h SOURCES += uploadergadget.cpp \ uploadergadgetconfiguration.cpp \ uploadergadgetfactory.cpp \ @@ -32,12 +34,14 @@ SOURCES += uploadergadget.cpp \ devicewidget.cpp \ SSP/port.cpp \ SSP/qssp.cpp \ - SSP/qsspt.cpp + SSP/qsspt.cpp \ + runningdevicewidget.cpp OTHER_FILES += Uploader.pluginspec FORMS += \ uploader.ui \ - devicewidget.ui + devicewidget.ui \ + runningdevicewidget.ui RESOURCES += \ uploader.qrc diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc index c4dd1b347..1008ef3ba 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.qrc +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.qrc @@ -9,5 +9,6 @@ images/deviceID-0301.svg images/deviceID-0201.svg images/deviceID-0101.svg + images/application-certificate.svg diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index dcbbb8fbd..8163d3968 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -115,6 +115,18 @@ void UploaderGadgetWidget::onAutopilotConnect(){ m_config->bootButton->setEnabled(false); m_config->rescueButton->setEnabled(false); m_config->telemetryLink->setEnabled(false); + + // Add a very simple widget with Board model & serial number + // Delete all previous tabs: + while (m_config->systemElements->count()) { + QWidget *qw = m_config->systemElements->widget(0); + m_config->systemElements->removeTab(0); + delete qw; + } + runningDeviceWidget* dw = new runningDeviceWidget(this); + dw->populate(); + m_config->systemElements->addTab(dw, QString("Connected Device")); + } /** diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index c0274668b..7c7bae19e 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -31,6 +31,7 @@ #include "ui_uploader.h" #include "delay.h" #include "devicewidget.h" +#include "runningdevicewidget.h" #include "op_dfu.h" #include #include