From 63e7902ee2f9a1a05e284ac1937ad77c0a07671a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 27 Jun 2023 11:55:20 +0100 Subject: [PATCH 001/168] motion control and planner hijacking - motion control and planner store/restore functions to allow mid flow hijacking --- uCNC/cnc_config.h | 8 ++++++++ uCNC/src/core/motion_control.c | 17 +++++++++++++++++ uCNC/src/core/motion_control.h | 7 +++++++ uCNC/src/core/planner.c | 26 ++++++++++++++++++++++++++ uCNC/src/core/planner.h | 7 +++++++ 5 files changed, 65 insertions(+) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index e200aa080..d1f16ee5b 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -288,6 +288,14 @@ extern "C" // #define ENABLE_RT_SYNC_MOTIONS + /** + * enable motion control and planner highjacking + * this unlocks funtions to perform a full planner copy and restore + * this requires some memory since the full planned contents must be stored and also the motion control reference position + * */ + + // #define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING + /** * Uncomment to enable module extensions * */ diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 424d96d46..910991d7c 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -1147,3 +1147,20 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data return STATUS_OK; } #endif + +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +static int32_t mc_last_step_pos_copy[STEPPER_COUNT]; +static float mc_last_target_copy[AXIS_COUNT]; +// stores the motion controller reference positions +void mc_store(void) +{ + memcpy(mc_last_step_pos_copy, mc_last_step_pos, sizeof(mc_last_step_pos)); + memcpy(mc_last_target_copy, mc_last_target, sizeof(mc_last_target)); +} +// restores the motion controller reference positions +void mc_restore(void) +{ + memcpy(mc_last_step_pos, mc_last_step_pos_copy, sizeof(mc_last_step_pos)); + memcpy(mc_last_target, mc_last_target_copy, sizeof(mc_last_target)); +} +#endif diff --git a/uCNC/src/core/motion_control.h b/uCNC/src/core/motion_control.h index 87fdf523d..103e5b7a1 100644 --- a/uCNC/src/core/motion_control.h +++ b/uCNC/src/core/motion_control.h @@ -119,6 +119,13 @@ extern "C" uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data_t *block_data); #endif +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING + // stores the motion controller reference positions + void mc_store(void); + // restores the motion controller reference positions + void mc_restore(void); +#endif + #ifdef ENABLE_MOTION_CONTROL_MODULES // event_mc_line_segment_handler DECL_EVENT_HANDLER(mc_line_segment); diff --git a/uCNC/src/core/planner.c b/uCNC/src/core/planner.c index 0f48a1bcc..e518c3c60 100644 --- a/uCNC/src/core/planner.c +++ b/uCNC/src/core/planner.c @@ -605,3 +605,29 @@ uint8_t planner_get_buffer_freeblocks() { return PLANNER_BUFFER_SIZE - planner_data_blocks; } + +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +static planner_block_t planner_data_copy[PLANNER_BUFFER_SIZE]; +static uint8_t planner_data_write_copy; +static uint8_t planner_data_read_copy; +static uint8_t planner_data_blocks_copy; +static planner_state_t g_planner_state_copy; +// creates a full copy of the planner state +void planner_store(void) +{ + memcpy(planner_data_copy, planner_data, sizeof(planner_data)); + planner_data_write_copy = planner_data_write; + planner_data_read_copy = planner_data_read; + planner_data_blocks_copy = planner_data_blocks; + memcpy(&g_planner_state_copy, &g_planner_state, sizeof(planner_state_t)); +} +// restores the planner to it's previous saved state +void planner_restore(void) +{ + memcpy(planner_data, planner_data_copy, sizeof(planner_data)); + planner_data_write = planner_data_write_copy; + planner_data_read = planner_data_read_copy; + planner_data_blocks = planner_data_blocks_copy; + memcpy(&g_planner_state, &g_planner_state_copy, sizeof(planner_state_t)); +} +#endif diff --git a/uCNC/src/core/planner.h b/uCNC/src/core/planner.h index bfc2caded..15a062fc2 100644 --- a/uCNC/src/core/planner.h +++ b/uCNC/src/core/planner.h @@ -112,6 +112,13 @@ extern "C" uint8_t planner_get_buffer_freeblocks(); +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING + // creates a full copy of the planner state + void planner_store(void); + // restores the planner to it's previous saved state + void planner_restore(void); +#endif + #ifdef __cplusplus } #endif From 34dc536bea97d8764f24a8d83063e6b19ba60c60 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 28 Jun 2023 10:36:45 +0100 Subject: [PATCH 002/168] stepbits and dirbits realtime modifier callback - added stepbits and dirbits realtime modifier callback --- PINOUTS.md | 6 +++--- uCNC/src/core/interpolator.c | 9 +++++++++ uCNC/src/core/interpolator.h | 1 + 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/PINOUTS.md b/PINOUTS.md index 268907f53..ea08eff7a 100644 --- a/PINOUTS.md +++ b/PINOUTS.md @@ -49,9 +49,9 @@ This wiring can be completely modified by the user. | DIN10 | ENC2_DIR | | DIN11 | ENC3_DIR | | DIN12 | ENC4_DIR | -| DIN13 | ENC5_DIR | -| DIN14 | ENC6_DIR | -| DIN15 | ENC7_DIR | +| DIN13 | ENC5_DIR or PLASMA_ARC_OK | +| DIN14 | ENC6_DIR or PLASMA_DOWN | +| DIN15 | ENC7_DIR or PLASMA_UP | | DIN16 | DISPLAY ENC BTN | | DIN17 | DISPLAY ENC1 | | DIN18 | DISPLAY ENC2 | diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index c46264dda..a8039fe23 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1216,6 +1216,11 @@ MCU_CALLBACK void laser_ppi_turnoff_cb(void) } #endif +#ifdef ENABLE_RT_SYNC_MOTIONS +void __attribute__((weak)) itp_rt_stepbits(uint8_t* stepbits, uint8_t dirbits){ +} +#endif + // always fires after pulse MCU_CALLBACK void mcu_step_reset_cb(void) { @@ -1683,6 +1688,10 @@ MCU_CALLBACK void mcu_step_cb(void) #if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) stepbits &= ~itp_step_lock; #endif + +#ifdef ENABLE_RT_SYNC_MOTIONS + itp_rt_stepbits_cb(&stepbits, itp_rt_sgm->block->dirbits); +#endif } } diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index 7d95b733d..7616f3d4a 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -53,6 +53,7 @@ extern "C" extern volatile int32_t itp_sync_step_counter; void itp_update_feed(float feed); bool itp_sync_ready(void); + void itp_rt_stepbits(uint8_t *stepbits, uint8_t dirbits); #endif #ifdef __cplusplus From 90d4e92ce9bc6e56c315d15861606320b44429fb Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 28 Jun 2023 11:47:02 +0100 Subject: [PATCH 003/168] reworked step ISR - reworked step ISR - stepbit RT override function with update of stepper position --- uCNC/src/core/interpolator.c | 677 ++++++++++++++++------------------- uCNC/src/core/interpolator.h | 53 ++- 2 files changed, 365 insertions(+), 365 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index a8039fe23..0c131b521 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -38,57 +38,6 @@ #define INTERPOLATOR_DELTA_CONST_T (MIN((1.0f / INTERPOLATOR_BUFFER_SIZE), ((float)(0xFFFF >> DSS_MAX_OVERSAMPLING) / (float)F_STEP_MAX))) #define INTERPOLATOR_FREQ_CONST (1.0f / INTERPOLATOR_DELTA_CONST_T) -// Itp update flags -#define ITP_NOUPDATE 0 -#define ITP_UPDATE_ISR 1 -#define ITP_UPDATE_TOOL 2 -#define ITP_UPDATE (ITP_UPDATE_ISR | ITP_UPDATE_TOOL) -#define ITP_ACCEL 4 -#define ITP_CONST 8 -#define ITP_DEACCEL 16 -#define ITP_SYNC 32 - -// contains data of the block being executed by the pulse routine -// this block has the necessary data to execute the Bresenham line algorithm -typedef struct itp_blk_ -{ -#ifdef STEP_ISR_SKIP_MAIN - uint8_t main_stepper; -#endif -#ifdef STEP_ISR_SKIP_IDLE - uint8_t idle_axis; -#endif - uint8_t dirbits; - step_t steps[STEPPER_COUNT]; - step_t total_steps; - step_t errors[STEPPER_COUNT]; -#ifdef GCODE_PROCESS_LINE_NUMBERS - uint32_t line; -#endif -#ifdef ENABLE_BACKLASH_COMPENSATION - bool backlash_comp; -#endif -} itp_block_t; - -// contains data of the block segment being executed by the pulse and integrator routines -// the segment is a fragment of the motion defined in the block -// this also contains the acceleration/deacceleration info -typedef struct pulse_sgm_ -{ - itp_block_t *block; - uint16_t remaining_steps; - uint16_t timer_counter; - uint16_t timer_prescaller; -#if (DSS_MAX_OVERSAMPLING != 0) - int8_t next_dss; -#endif -#if TOOL_COUNT > 0 - int16_t spindle; -#endif - float feed; - uint8_t flags; -} itp_segment_t; - // circular buffers // creates new type PULSE_BLOCK_BUFFER static itp_block_t itp_blk_data[INTERPOLATOR_BUFFER_SIZE]; @@ -1217,7 +1166,8 @@ MCU_CALLBACK void laser_ppi_turnoff_cb(void) #endif #ifdef ENABLE_RT_SYNC_MOTIONS -void __attribute__((weak)) itp_rt_stepbits(uint8_t* stepbits, uint8_t dirbits){ +void __attribute__((weak)) itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) +{ } #endif @@ -1236,463 +1186,462 @@ MCU_CALLBACK void mcu_step_cb(void) static uint16_t new_laser_ppi = 0; #endif - if (!itp_busy) // prevents reentrancy + if (itp_busy) // prevents reentrancy { - if (itp_rt_sgm != NULL) + return; + } + + if (itp_rt_sgm != NULL) + { + if (itp_rt_sgm->flags & ITP_UPDATE) { - if (itp_rt_sgm->flags & ITP_UPDATE) + if (itp_rt_sgm->flags & ITP_UPDATE_ISR) { - if (itp_rt_sgm->flags & ITP_UPDATE_ISR) - { - mcu_change_itp_isr(itp_rt_sgm->timer_counter, itp_rt_sgm->timer_prescaller); - } + mcu_change_itp_isr(itp_rt_sgm->timer_counter, itp_rt_sgm->timer_prescaller); + } #if TOOL_COUNT > 0 - if (itp_rt_sgm->flags & ITP_UPDATE_TOOL) - { + if (itp_rt_sgm->flags & ITP_UPDATE_TOOL) + { #ifdef ENABLE_LASER_PPI - if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) - { - new_laser_ppi = itp_rt_sgm->spindle; - } - else - { + if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + { + new_laser_ppi = itp_rt_sgm->spindle; + } + else + { #endif - tool_set_speed(itp_rt_sgm->spindle); + tool_set_speed(itp_rt_sgm->spindle); #ifdef ENABLE_LASER_PPI - } -#endif } #endif - itp_rt_sgm->flags &= ~(ITP_UPDATE); } +#endif + itp_rt_sgm->flags &= ~(ITP_UPDATE); + } - // no step remaining discards current segment - if (!itp_rt_sgm->remaining_steps) - { - itp_rt_sgm->block = NULL; - itp_rt_sgm = NULL; - itp_sgm_buffer_read(); - } + // no step remaining discards current segment + if (!itp_rt_sgm->remaining_steps) + { + itp_rt_sgm->block = NULL; + itp_rt_sgm = NULL; + itp_sgm_buffer_read(); } + } - // sets step bits + // sets step bits #ifdef ENABLE_LASER_PPI - if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + { + if (stepbits & LASER_PPI_MASK) { - if (stepbits & LASER_PPI_MASK) + if (new_laser_ppi) { - if (new_laser_ppi) - { - mcu_config_timeout(&laser_ppi_turnoff_cb, new_laser_ppi); - new_laser_ppi = 0; - } - mcu_start_timeout(); + mcu_config_timeout(&laser_ppi_turnoff_cb, new_laser_ppi); + new_laser_ppi = 0; + } + mcu_start_timeout(); #ifndef INVERT_LASER_PPI_LOGIC - mcu_set_output(LASER_PPI); + mcu_set_output(LASER_PPI); #else - mcu_clear_output(LASER_PPI); + mcu_clear_output(LASER_PPI); #endif - } } + } #endif - io_toggle_steps(stepbits); + io_toggle_steps(stepbits); - // if buffer empty loads one - if (itp_rt_sgm == NULL) + // if buffer empty loads one + if (itp_rt_sgm == NULL) + { + // if buffer is not empty + if (!itp_sgm_is_empty()) { - // if buffer is not empty - if (!itp_sgm_is_empty()) + // loads a new segment + itp_rt_sgm = &itp_sgm_data[itp_sgm_data_read]; + cnc_set_exec_state(EXEC_RUN); + if (itp_rt_sgm->block != NULL) { - // loads a new segment - itp_rt_sgm = &itp_sgm_data[itp_sgm_data_read]; - cnc_set_exec_state(EXEC_RUN); - if (itp_rt_sgm->block != NULL) - { #if (DSS_MAX_OVERSAMPLING != 0) - if (itp_rt_sgm->next_dss != 0) - { + if (itp_rt_sgm->next_dss != 0) + { #ifdef STEP_ISR_SKIP_MAIN - itp_rt_sgm->block->main_stepper = 255; // disables direct step increment to force step calculation + itp_rt_sgm->block->main_stepper = 255; // disables direct step increment to force step calculation #endif - uint8_t dss; - if (itp_rt_sgm->next_dss > 0) - { - dss = itp_rt_sgm->next_dss; - itp_rt_sgm->block->total_steps <<= dss; + uint8_t dss; + if (itp_rt_sgm->next_dss > 0) + { + dss = itp_rt_sgm->next_dss; + itp_rt_sgm->block->total_steps <<= dss; #if (STEPPER_COUNT > 0) - itp_rt_sgm->block->errors[0] <<= dss; + itp_rt_sgm->block->errors[0] <<= dss; #endif #if (STEPPER_COUNT > 1) - itp_rt_sgm->block->errors[1] <<= dss; + itp_rt_sgm->block->errors[1] <<= dss; #endif #if (STEPPER_COUNT > 2) - itp_rt_sgm->block->errors[2] <<= dss; + itp_rt_sgm->block->errors[2] <<= dss; #endif #if (STEPPER_COUNT > 3) - itp_rt_sgm->block->errors[3] <<= dss; + itp_rt_sgm->block->errors[3] <<= dss; #endif #if (STEPPER_COUNT > 4) - itp_rt_sgm->block->errors[4] <<= dss; + itp_rt_sgm->block->errors[4] <<= dss; #endif #if (STEPPER_COUNT > 5) - itp_rt_sgm->block->errors[5] <<= dss; + itp_rt_sgm->block->errors[5] <<= dss; #endif - } - else - { - dss = -itp_rt_sgm->next_dss; - itp_rt_sgm->block->total_steps >>= dss; + } + else + { + dss = -itp_rt_sgm->next_dss; + itp_rt_sgm->block->total_steps >>= dss; #if (STEPPER_COUNT > 0) - itp_rt_sgm->block->errors[0] >>= dss; + itp_rt_sgm->block->errors[0] >>= dss; #endif #if (STEPPER_COUNT > 1) - itp_rt_sgm->block->errors[1] >>= dss; + itp_rt_sgm->block->errors[1] >>= dss; #endif #if (STEPPER_COUNT > 2) - itp_rt_sgm->block->errors[2] >>= dss; + itp_rt_sgm->block->errors[2] >>= dss; #endif #if (STEPPER_COUNT > 3) - itp_rt_sgm->block->errors[3] >>= dss; + itp_rt_sgm->block->errors[3] >>= dss; #endif #if (STEPPER_COUNT > 4) - itp_rt_sgm->block->errors[4] >>= dss; + itp_rt_sgm->block->errors[4] >>= dss; #endif #if (STEPPER_COUNT > 5) - itp_rt_sgm->block->errors[5] >>= dss; + itp_rt_sgm->block->errors[5] >>= dss; #endif - } } -#endif - // set dir pins for current - io_set_dirs(itp_rt_sgm->block->dirbits); } - } - else - { - cnc_clear_exec_state(EXEC_RUN); // this naturally clears the RUN flag. Any other ISR stop does not clear the flag. - itp_stop(); // the buffer is empty. The ISR can stop - return; +#endif + // set dir pins for current + io_set_dirs(itp_rt_sgm->block->dirbits); } } - -#ifdef ENABLE_RT_SYNC_MOTIONS - if (stepbits && (itp_rt_sgm->flags & ITP_SYNC)) + else { - itp_sync_step_counter++; + cnc_clear_exec_state(EXEC_RUN); // this naturally clears the RUN flag. Any other ISR stop does not clear the flag. + itp_stop(); // the buffer is empty. The ISR can stop + return; } + } + +#ifdef ENABLE_RT_SYNC_MOTIONS + if (stepbits && (itp_rt_sgm->flags & ITP_SYNC)) + { + itp_sync_step_counter++; + } #endif - stepbits = 0; - itp_busy = true; - mcu_enable_global_isr(); + uint8_t new_stepbits = 0; + itp_busy = true; + mcu_enable_global_isr(); - // is steps remaining starts calc next step bits - if (itp_rt_sgm->remaining_steps) + // steps remaining starts calc next step bits + if (itp_rt_sgm->remaining_steps) + { + if (itp_rt_sgm->block != NULL) { - bool dostep = false; - if (itp_rt_sgm->block != NULL) - { // prepares the next step bits mask #if (STEPPER_COUNT > 0) - dostep = false; #ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 0) - { - dostep = true; - } - else - { + if (itp_rt_sgm->block->main_stepper == 0) + { + new_stepbits |= STEP0_ITP_MASK; + } + else + { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP0_MASK)) - { + if (!(itp_rt_sgm->block->idle_axis & STEP0_MASK)) + { #endif - itp_rt_sgm->block->errors[0] += itp_rt_sgm->block->steps[0]; - if (itp_rt_sgm->block->errors[0] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[0] -= itp_rt_sgm->block->total_steps; - dostep = true; - } -#ifdef STEP_ISR_SKIP_IDLE + itp_rt_sgm->block->errors[0] += itp_rt_sgm->block->steps[0]; + if (itp_rt_sgm->block->errors[0] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[0] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP0_ITP_MASK; } -#endif -#ifdef STEP_ISR_SKIP_MAIN +#ifdef STEP_ISR_SKIP_IDLE } #endif - - if (dostep) - { - stepbits |= STEP0_ITP_MASK; -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (itp_rt_sgm->block->dirbits & DIR0_MASK) - { - itp_rt_step_pos[0]--; - } - else - { - itp_rt_step_pos[0]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } +#ifdef STEP_ISR_SKIP_MAIN + } #endif - } #endif #if (STEPPER_COUNT > 1) - dostep = false; #ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 1) - { - dostep = true; - } - else - { + if (itp_rt_sgm->block->main_stepper == 1) + { + new_stepbits |= STEP1_ITP_MASK; + } + else + { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP1_MASK)) - { + if (!(itp_rt_sgm->block->idle_axis & STEP1_MASK)) + { #endif - itp_rt_sgm->block->errors[1] += itp_rt_sgm->block->steps[1]; - if (itp_rt_sgm->block->errors[1] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[1] -= itp_rt_sgm->block->total_steps; - dostep = true; - } -#ifdef STEP_ISR_SKIP_IDLE + itp_rt_sgm->block->errors[1] += itp_rt_sgm->block->steps[1]; + if (itp_rt_sgm->block->errors[1] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[1] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP1_ITP_MASK; } -#endif -#ifdef STEP_ISR_SKIP_MAIN +#ifdef STEP_ISR_SKIP_IDLE } #endif - - if (dostep) - { - stepbits |= STEP1_ITP_MASK; -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (itp_rt_sgm->block->dirbits & DIR1_MASK) - { - itp_rt_step_pos[1]--; - } - else - { - itp_rt_step_pos[1]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } +#ifdef STEP_ISR_SKIP_MAIN + } #endif - } #endif #if (STEPPER_COUNT > 2) - dostep = false; #ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 2) - { - dostep = true; - } - else - { + if (itp_rt_sgm->block->main_stepper == 2) + { + new_stepbits |= STEP2_ITP_MASK; + } + else + { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP2_MASK)) - { + if (!(itp_rt_sgm->block->idle_axis & STEP2_MASK)) + { #endif - itp_rt_sgm->block->errors[2] += itp_rt_sgm->block->steps[2]; - if (itp_rt_sgm->block->errors[2] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[2] -= itp_rt_sgm->block->total_steps; - dostep = true; - } -#ifdef STEP_ISR_SKIP_IDLE + itp_rt_sgm->block->errors[2] += itp_rt_sgm->block->steps[2]; + if (itp_rt_sgm->block->errors[2] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[2] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP2_ITP_MASK; } -#endif -#ifdef STEP_ISR_SKIP_MAIN +#ifdef STEP_ISR_SKIP_IDLE } #endif - - if (dostep) - { - stepbits |= STEP2_ITP_MASK; -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (itp_rt_sgm->block->dirbits & DIR2_MASK) - { - itp_rt_step_pos[2]--; - } - else - { - itp_rt_step_pos[2]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } +#ifdef STEP_ISR_SKIP_MAIN + } #endif - } #endif #if (STEPPER_COUNT > 3) - dostep = false; #ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 3) - { - dostep = true; - } - else - { + if (itp_rt_sgm->block->main_stepper == 3) + { + new_stepbits |= STEP3_ITP_MASK; + } + else + { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP3_MASK)) - { + if (!(itp_rt_sgm->block->idle_axis & STEP3_MASK)) + { #endif - itp_rt_sgm->block->errors[3] += itp_rt_sgm->block->steps[3]; - if (itp_rt_sgm->block->errors[3] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[3] -= itp_rt_sgm->block->total_steps; - dostep = true; - } -#ifdef STEP_ISR_SKIP_IDLE + itp_rt_sgm->block->errors[3] += itp_rt_sgm->block->steps[3]; + if (itp_rt_sgm->block->errors[3] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[3] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP3_ITP_MASK; } +#ifdef STEP_ISR_SKIP_IDLE + } #endif #ifdef STEP_ISR_SKIP_MAIN - } + } #endif - - if (dostep) +#endif +#if (STEPPER_COUNT > 4) +#ifdef STEP_ISR_SKIP_MAIN + if (itp_rt_sgm->block->main_stepper == 4) + { + new_stepbits |= STEP4_ITP_MASK; + } + else + { +#endif +#ifdef STEP_ISR_SKIP_IDLE + if (!(itp_rt_sgm->block->idle_axis & STEP4_MASK)) { - stepbits |= STEP3_ITP_MASK; -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { #endif - if (itp_rt_sgm->block->dirbits & DIR3_MASK) - { - itp_rt_step_pos[3]--; - } - else - { - itp_rt_step_pos[3]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION + itp_rt_sgm->block->errors[4] += itp_rt_sgm->block->steps[4]; + if (itp_rt_sgm->block->errors[4] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[4] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP4_ITP_MASK; } -#endif +#ifdef STEP_ISR_SKIP_IDLE } #endif -#if (STEPPER_COUNT > 4) - dostep = false; #ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 4) - { - dostep = true; - } - else - { + } #endif -#ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP4_MASK)) - { #endif - itp_rt_sgm->block->errors[4] += itp_rt_sgm->block->steps[4]; - if (itp_rt_sgm->block->errors[4] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[4] -= itp_rt_sgm->block->total_steps; - dostep = true; - } +#if (STEPPER_COUNT > 5) +#ifdef STEP_ISR_SKIP_MAIN + if (itp_rt_sgm->block->main_stepper == 5) + { + new_stepbits |= STEP5_ITP_MASK; + } + else + { +#endif #ifdef STEP_ISR_SKIP_IDLE + if (!(itp_rt_sgm->block->idle_axis & STEP5_MASK)) + { +#endif + itp_rt_sgm->block->errors[5] += itp_rt_sgm->block->steps[5]; + if (itp_rt_sgm->block->errors[5] > itp_rt_sgm->block->total_steps) + { + itp_rt_sgm->block->errors[5] -= itp_rt_sgm->block->total_steps; + new_stepbits |= STEP5_ITP_MASK; } +#ifdef STEP_ISR_SKIP_IDLE + } #endif #ifdef STEP_ISR_SKIP_MAIN - } + } +#endif #endif - if (dostep) - { - stepbits |= STEP4_ITP_MASK; +#ifdef ENABLE_RT_SYNC_MOTIONS + itp_rt_stepbits(&new_stepbits, itp_rt_sgm); +#endif + +// updates the stepper coordinates +#if (STEPPER_COUNT > 0) + if (new_stepbits & STEP0_ITP_MASK) + { #ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) + if (!itp_rt_sgm->block->backlash_comp) + { +#endif + if (itp_rt_sgm->block->dirbits & DIR0_MASK) { + itp_rt_step_pos[0]--; + } + else + { + itp_rt_step_pos[0]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION + } +#endif + } #endif - if (itp_rt_sgm->block->dirbits & DIR4_MASK) - { - itp_rt_step_pos[4]--; - } - else - { - itp_rt_step_pos[4]++; - } +#if (STEPPER_COUNT > 1) + if (new_stepbits & STEP1_ITP_MASK) + { #ifdef ENABLE_BACKLASH_COMPENSATION - } + if (!itp_rt_sgm->block->backlash_comp) + { #endif + if (itp_rt_sgm->block->dirbits & DIR1_MASK) + { + itp_rt_step_pos[1]--; + } + else + { + itp_rt_step_pos[1]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION } #endif -#if (STEPPER_COUNT > 5) - dostep = false; -#ifdef STEP_ISR_SKIP_MAIN - if (itp_rt_sgm->block->main_stepper == 5) + } +#endif +#if (STEPPER_COUNT > 2) + if (new_stepbits & STEP2_ITP_MASK) + { +#ifdef ENABLE_BACKLASH_COMPENSATION + if (!itp_rt_sgm->block->backlash_comp) { - dostep = true; +#endif + if (itp_rt_sgm->block->dirbits & DIR2_MASK) + { + itp_rt_step_pos[2]--; + } + else + { + itp_rt_step_pos[2]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION } - else +#endif + } +#endif +#if (STEPPER_COUNT > 3) + if (new_stepbits & STEP3_ITP_MASK) + { +#ifdef ENABLE_BACKLASH_COMPENSATION + if (!itp_rt_sgm->block->backlash_comp) { #endif -#ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP5_MASK)) + if (itp_rt_sgm->block->dirbits & DIR3_MASK) { -#endif - itp_rt_sgm->block->errors[5] += itp_rt_sgm->block->steps[5]; - if (itp_rt_sgm->block->errors[5] > itp_rt_sgm->block->total_steps) - { - itp_rt_sgm->block->errors[5] -= itp_rt_sgm->block->total_steps; - dostep = true; - } -#ifdef STEP_ISR_SKIP_IDLE + itp_rt_step_pos[3]--; } -#endif -#ifdef STEP_ISR_SKIP_MAIN + else + { + itp_rt_step_pos[3]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION } #endif + } +#endif - if (dostep) - { - stepbits |= STEP5_ITP_MASK; +#if (STEPPER_COUNT > 4) + if (new_stepbits & STEP4_ITP_MASK) + { #ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) + if (!itp_rt_sgm->block->backlash_comp) + { +#endif + if (itp_rt_sgm->block->dirbits & DIR4_MASK) { + itp_rt_step_pos[4]--; + } + else + { + itp_rt_step_pos[4]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION + } +#endif + } #endif - if (itp_rt_sgm->block->dirbits & DIR5_MASK) - { - itp_rt_step_pos[5]--; - } - else - { - itp_rt_step_pos[5]++; - } + +#if (STEPPER_COUNT > 5) + if (new_stepbits & STEP5_ITP_MASK) + { #ifdef ENABLE_BACKLASH_COMPENSATION - } + if (!itp_rt_sgm->block->backlash_comp) + { #endif + if (itp_rt_sgm->block->dirbits & DIR5_MASK) + { + itp_rt_step_pos[5]--; + } + else + { + itp_rt_step_pos[5]++; + } +#ifdef ENABLE_BACKLASH_COMPENSATION } #endif } - - // no step remaining discards current segment - --itp_rt_sgm->remaining_steps; +#endif } - mcu_disable_global_isr(); // lock isr before clearin busy flag - itp_busy = false; + // no step remaining discards current segment + --itp_rt_sgm->remaining_steps; + } -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) - stepbits &= ~itp_step_lock; -#endif + mcu_disable_global_isr(); // lock isr before clearin busy flag + itp_busy = false; -#ifdef ENABLE_RT_SYNC_MOTIONS - itp_rt_stepbits_cb(&stepbits, itp_rt_sgm->block->dirbits); +#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) + stepbits = (new_stepbits & ~itp_step_lock); #endif - } } // void itp_nomotion(uint8_t type, uint16_t delay) diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index 7616f3d4a..dad234436 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -29,6 +29,57 @@ extern "C" #include #include +// Itp update flags +#define ITP_NOUPDATE 0 +#define ITP_UPDATE_ISR 1 +#define ITP_UPDATE_TOOL 2 +#define ITP_UPDATE (ITP_UPDATE_ISR | ITP_UPDATE_TOOL) +#define ITP_ACCEL 4 +#define ITP_CONST 8 +#define ITP_DEACCEL 16 +#define ITP_SYNC 32 + + // contains data of the block being executed by the pulse routine + // this block has the necessary data to execute the Bresenham line algorithm + typedef struct itp_blk_ + { +#ifdef STEP_ISR_SKIP_MAIN + uint8_t main_stepper; +#endif +#ifdef STEP_ISR_SKIP_IDLE + uint8_t idle_axis; +#endif + uint8_t dirbits; + step_t steps[STEPPER_COUNT]; + step_t total_steps; + step_t errors[STEPPER_COUNT]; +#ifdef GCODE_PROCESS_LINE_NUMBERS + uint32_t line; +#endif +#ifdef ENABLE_BACKLASH_COMPENSATION + bool backlash_comp; +#endif + } itp_block_t; + + // contains data of the block segment being executed by the pulse and integrator routines + // the segment is a fragment of the motion defined in the block + // this also contains the acceleration/deacceleration info + typedef struct pulse_sgm_ + { + itp_block_t *block; + uint16_t remaining_steps; + uint16_t timer_counter; + uint16_t timer_prescaller; +#if (DSS_MAX_OVERSAMPLING != 0) + int8_t next_dss; +#endif +#if TOOL_COUNT > 0 + int16_t spindle; +#endif + float feed; + uint8_t flags; + } itp_segment_t; + void itp_init(void); void itp_run(void); void itp_update(void); @@ -53,7 +104,7 @@ extern "C" extern volatile int32_t itp_sync_step_counter; void itp_update_feed(float feed); bool itp_sync_ready(void); - void itp_rt_stepbits(uint8_t *stepbits, uint8_t dirbits); + void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t* rt_sgm); #endif #ifdef __cplusplus From 77a98775bedd63119f9f1490b5107b1e35d3b53a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 29 Jun 2023 18:16:52 +0100 Subject: [PATCH 004/168] Create plasma_thc.c --- uCNC/src/hal/tools/tools/plasma_thc.c | 305 ++++++++++++++++++++++++++ 1 file changed, 305 insertions(+) create mode 100644 uCNC/src/hal/tools/tools/plasma_thc.c diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c new file mode 100644 index 000000000..78cf71349 --- /dev/null +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -0,0 +1,305 @@ +/* + Name: plasma_thc.c + Description: Defines a plasma tool with THC for µCNC. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 29/06/2023 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#include +#include +#include +#include + +#include "../../../cnc.h" + +#ifndef PLASMA_UP_INPUT +#define PLASMA_UP_INPUT DIN15 +#endif + +#ifndef PLASMA_DOWN_INPUT +#define PLASMA_DOWN_INPUT DIN14 +#endif + +#ifndef PLASMA_ARC_OK_INPUT +#define PLASMA_ARC_OK_INPUT DIN13 +#endif + +#ifndef PLASMA_ON_INPUT +#define PLASMA_ON_INPUT DIN13 +#endif + +// overridable +// user can implement the plasma thc up condition based on analog voltage reading using analog the controller analog inputs and PID controllers +uint8_t __attribute__((weak)) plasma_thc_up(void) +{ +#if ASSERT_PIN(PLASMA_UP_INPUT) + return mcu_get_input(PLASMA_UP_INPUT); +#else + return 0; +#endif +} + +// overridable +// user can implement the plasma thc down condition based on analog voltage reading using analog the controller analog inputs and PID controllers +uint8_t __attribute__((weak)) plasma_thc_down(void) +{ +#if ASSERT_PIN(PLASMA_DOWN_INPUT) + return mcu_get_input(PLASMA_DOWN_INPUT); +#else + return 0; +#endif +} + +// overridable +// user can implement the plasma thc arc ok condition based on analog voltage reading using analog the controller analog inputs and PID controllers +uint8_t __attribute__((weak)) plasma_thc_arc_ok(void) +{ +#if ASSERT_PIN(PLASMA_ARC_OK_INPUT) + return mcu_get_input(PLASMA_ARC_OK_INPUT); +#else + return 0; +#endif +} + +// plasma thc controller variables +static bool plasma_thc_enabled; +static volatile int8_t plasma_step_error; +typedef struct plasma_start_params_ +{ + float probe_depth; // I + float probe_feed; // J + float retract_height; // R + float cut_depth; // K + float cut_feed; // F + uint16_t dwell; // P*1000 + uint8_t retries; // L + +} plasma_start_params_t; +static plasma_start_params_t plasma_start_params; + +bool plasma_thc_probe_and_start(plasma_start_params_t start_params) +{ + plasma_thc_enabled = false; + while (start_params.retries--) + { + // cutoff torch + motion_data_t block = {0}; + block.motion_flags.bit.spindle_running = 0; + mc_update_tools(&block); + + // get current position + float pos[AXIS_COUNT]; + mc_get_position(pos); + + // modify target to probe depth + pos[AXIS_Z] -= start_params.probe_depth; + // probe feed speed + block.feed = start_params.probe_feed; + // similar to G38.2 + if (mc_probe(pos, 0, &block) == STATUS_PROBE_SUCCESS) + { + // modify target to probe depth + mc_get_position(pos); + pos[AXIS_Z] += start_params.probe_depth; + block.feed = start_params.probe_feed * 0.5f; // half speed + // similar to G38.4 + if (mc_probe(pos, 2, &block) == STATUS_PROBE_SUCCESS) + { + // modify target to torch start height + mc_get_position(pos); + pos[AXIS_Z] += start_params.retract_height; + // rapid feed + block.feed = FLT_MAX; + mc_line(pos, &block); + // turn torch on and wait before confirm the arc on signal + block.motion_flags.bit.spindle_running = 1; + block.dwell = start_params.dwell; + // updated tools and wait + mc_dwell(&block); + + // confirm if arc is ok + if (PLASMA_ARC_OK()) + { + mc_get_position(pos); + pos[AXIS_Z] -= start_params.cut_depth; + // rapid feed + block.feed = start_params.cut_feed; + mc_line(pos, &block); + cnc_set_exec_state(EXEC_HOLD); + // restore the motion controller, planner and parser + mc_restore(); + planner_restore(); + parser_sync_position(); + plasma_thc_enabled = true; + cnc_clear_exec_state(EXEC_HOLD); + // continues program + return true; + } + } + } + } + + return false; +} + +#ifdef ENABLE_RT_SYNC_MOTIONS +void itp_rt_stepbits(uint8_t *stepbits, uint8_t dirbits) +{ + uint8_t step_error = plasma_step_error; + if (!step_error) + { + return; + } + + if (step_error > 0) + { + *stepbits |= PLASMA_STEPPERS_MASK; + io_set_dirs(dirbits & ~PLASMA_STEPPERS_MASK); + step_error--; + } + + if (step_error < 0) + { + *stepbits |= PLASMA_STEPPERS_MASK; + io_set_dirs(dirbits | PLASMA_STEPPERS_MASK); + step_error--; + } + + plasma_step_error = step_error; +} +#endif + +#ifdef ENABLE_PARSER_MODULES +#define M103 EXTENDED_MCODE(103) + +bool m103_parse(void *args); +bool m103_exec(void *args); + +CREATE_EVENT_LISTENER(gcode_parse, m103_parse); +CREATE_EVENT_LISTENER(gcode_exec, m103_exec); + +// this just parses and acceps the code +bool m103_parse(void *args) +{ + gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; + if (ptr->word == 'M' && ptr->code == 103) + { + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + return EVENT_HANDLED; + } + // tells the gcode validation and execution functions this is custom code M42 (ID must be unique) + ptr->cmd->group_extended = M103; + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + + // if this is not catched by this parser, just send back the error so other extenders can process it + return EVENT_CONTINUE; +} + +// this actually performs 2 steps in 1 (validation and execution) +bool m103_exec(void *args) +{ + gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; + if (ptr->cmd->group_extended == M103) + { + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) + { + *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; + return EVENT_HANDLED; + } + + plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); + plasma_start_params.probe_depth = ptr->words->ijk[0]; + plasma_start_params.probe_feed = ptr->words->ijk[1]; + plasma_start_params.retract_height = ptr->words->r; + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) + { + plasma_start_params.cut_feed = ptr->words->f; + } + plasma_start_params.cut_feed = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; + + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + + return EVENT_CONTINUE; +} + +#endif + +#ifdef ENABLE_MAIN_LOOP_MODULES +bool plasma_thc_update_loop(void *ptr) +{ + if (plasma_thc_enabled) + { + // arc lost + // on arc lost the plasma must enter hold + if (!(plasma_thc_arc_ok())) + { + // set hold and wait for motion to stop + cnc_set_exec_state(EXEC_HOLD); + itp_sync(); + // store planner and motion controll data away + planner_store(); + mc_store(); + // reset planner and sync systems + planner_clear(); + mc_sync_position(); + + // clear the current hold state + cnc_clear_exec_state(EXEC_HOLD); + } + + if (plasma_thc_up()) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits &= 0xFB; + + // option 2 - mask the step bits directly + plasma_step_error += 1; + } + else if (plasma_thc_down()) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits |= 4; + + // option 2 - mask the step bits directly + plasma_step_error -= 1; + } + else + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = 0; + + // option 2 - mask the step bits directly + plasma_step_error = 0; + } + } + return EVENT_CONTINUE; +} + +CREATE_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); +#endif \ No newline at end of file From fcf56957dbcdf8a20abc43f21593819dddd125c1 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 3 Jul 2023 16:13:56 +0100 Subject: [PATCH 005/168] created plasma thc tool - created plasma thc tool - fixed plasma thc custom Mcode - added plasma thc module loading --- uCNC/cnc_hal_config.h | 23 ++ uCNC/src/hal/tools/tools/plasma_thc.c | 303 +++++++++++++++++--------- uCNC/src/module.c | 4 + 3 files changed, 231 insertions(+), 99 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 16940517f..99933d5d1 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -115,14 +115,37 @@ extern "C" /* Tool definition For any given tool the respective macro TOOLx (x from 1 to 16) must be created + Tools must be assigned in sequential order + That is TOOL1, TOOL2 etc... + You can't skip tool numbers (for example define TOOL1 and TOOL3 without having a TOOL2) */ + +/** + * + * Enables Laser PPI capabilities + * + * **/ #ifdef ENABLE_LASER_PPI #define LASER_PPI PWM0 // Uncomment to invert the output login on the LASER_PPI pin // #define INVERT_LASER_PPI_LOGIC #endif +/** + * + * Enables Plasma THC capabilities + * + * **/ +// #define ENABLE_PLASMA_THC + + +/** + * + * + * + * + * **/ // assign the tools from 1 to 16 #define TOOL1 spindle_pwm // #define TOOL2 laser diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 78cf71349..c707870ed 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -35,8 +35,12 @@ #define PLASMA_ARC_OK_INPUT DIN13 #endif -#ifndef PLASMA_ON_INPUT -#define PLASMA_ON_INPUT DIN13 +#ifndef PLASMA_ON_OUTPUT +#define PLASMA_ON_OUTPUT DOUT0 +#endif + +#ifndef PLASMA_STEPPERS_MASK +#define PLASMA_STEPPERS_MASK (1 << 2) #endif // overridable @@ -90,7 +94,15 @@ static plasma_start_params_t plasma_start_params; bool plasma_thc_probe_and_start(plasma_start_params_t start_params) { + static bool plasma_starting = false; plasma_thc_enabled = false; + if (plasma_starting) + { + // prevent reentrancy + return; + } + + plasma_starting = true; while (start_params.retries--) { // cutoff torch @@ -129,7 +141,7 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) mc_dwell(&block); // confirm if arc is ok - if (PLASMA_ARC_OK()) + if (plasma_thc_arc_ok()) { mc_get_position(pos); pos[AXIS_Z] -= start_params.cut_depth; @@ -144,17 +156,19 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) plasma_thc_enabled = true; cnc_clear_exec_state(EXEC_HOLD); // continues program + plasma_starting = false; return true; } } } } + plasma_starting = false; return false; } #ifdef ENABLE_RT_SYNC_MOTIONS -void itp_rt_stepbits(uint8_t *stepbits, uint8_t dirbits) +void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) { uint8_t step_error = plasma_step_error; if (!step_error) @@ -165,14 +179,14 @@ void itp_rt_stepbits(uint8_t *stepbits, uint8_t dirbits) if (step_error > 0) { *stepbits |= PLASMA_STEPPERS_MASK; - io_set_dirs(dirbits & ~PLASMA_STEPPERS_MASK); + io_set_dirs(rt_sgm->block->dirbits & ~PLASMA_STEPPERS_MASK); step_error--; } if (step_error < 0) { *stepbits |= PLASMA_STEPPERS_MASK; - io_set_dirs(dirbits | PLASMA_STEPPERS_MASK); + io_set_dirs(rt_sgm->block->dirbits | PLASMA_STEPPERS_MASK); step_error--; } @@ -192,52 +206,53 @@ CREATE_EVENT_LISTENER(gcode_exec, m103_exec); // this just parses and acceps the code bool m103_parse(void *args) { - gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; - if (ptr->word == 'M' && ptr->code == 103) - { - if (ptr->cmd->group_extended != 0) - { - // there is a collision of custom gcode commands (only one per line can be processed) - *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; - return EVENT_HANDLED; - } - // tells the gcode validation and execution functions this is custom code M42 (ID must be unique) - ptr->cmd->group_extended = M103; - *(ptr->error) = STATUS_OK; - return EVENT_HANDLED; - } - - // if this is not catched by this parser, just send back the error so other extenders can process it - return EVENT_CONTINUE; + gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; + if (ptr->word == 'M' && ptr->code == 103) + { + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + return EVENT_HANDLED; + } + // tells the gcode validation and execution functions this is custom code M42 (ID must be unique) + ptr->cmd->group_extended = M103; + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + + // if this is not catched by this parser, just send back the error so other extenders can process it + return EVENT_CONTINUE; } // this actually performs 2 steps in 1 (validation and execution) bool m103_exec(void *args) { - gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; - if (ptr->cmd->group_extended == M103) - { - if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) - { - *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; - return EVENT_HANDLED; - } - - plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); - plasma_start_params.probe_depth = ptr->words->ijk[0]; - plasma_start_params.probe_feed = ptr->words->ijk[1]; - plasma_start_params.retract_height = ptr->words->r; - if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) - { - plasma_start_params.cut_feed = ptr->words->f; - } - plasma_start_params.cut_feed = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; + gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; + if (ptr->cmd->group_extended == M103) + { + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) + { + *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; + return EVENT_HANDLED; + } + + plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); + plasma_start_params.probe_depth = ptr->words->ijk[0]; + plasma_start_params.probe_feed = ptr->words->ijk[1]; + plasma_start_params.cut_depth = ptr->words->ijk[2]; + plasma_start_params.retract_height = ptr->words->r; + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) + { + plasma_start_params.cut_feed = ptr->words->f; + } + plasma_start_params.retries = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; *(ptr->error) = STATUS_OK; - return EVENT_HANDLED; - } + return EVENT_HANDLED; + } - return EVENT_CONTINUE; + return EVENT_CONTINUE; } #endif @@ -245,61 +260,151 @@ bool m103_exec(void *args) #ifdef ENABLE_MAIN_LOOP_MODULES bool plasma_thc_update_loop(void *ptr) { - if (plasma_thc_enabled) - { - // arc lost - // on arc lost the plasma must enter hold - if (!(plasma_thc_arc_ok())) - { - // set hold and wait for motion to stop - cnc_set_exec_state(EXEC_HOLD); - itp_sync(); - // store planner and motion controll data away - planner_store(); - mc_store(); - // reset planner and sync systems - planner_clear(); - mc_sync_position(); - - // clear the current hold state - cnc_clear_exec_state(EXEC_HOLD); - } - - if (plasma_thc_up()) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits &= 0xFB; - - // option 2 - mask the step bits directly - plasma_step_error += 1; - } - else if (plasma_thc_down()) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits |= 4; - - // option 2 - mask the step bits directly - plasma_step_error -= 1; - } - else - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = 0; - - // option 2 - mask the step bits directly - plasma_step_error = 0; - } - } - return EVENT_CONTINUE; + if (plasma_thc_enabled) + { + // arc lost + // on arc lost the plasma must enter hold + if (!(plasma_thc_arc_ok())) + { + // set hold and wait for motion to stop + cnc_set_exec_state(EXEC_HOLD); + itp_sync(); + // store planner and motion controll data away + planner_store(); + mc_store(); + // reset planner and sync systems + planner_clear(); + mc_sync_position(); + + // clear the current hold state + cnc_clear_exec_state(EXEC_HOLD); + } + + if (plasma_thc_up()) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits &= 0xFB; + + // option 2 - mask the step bits directly + plasma_step_error += 1; + } + else if (plasma_thc_down()) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits |= 4; + + // option 2 - mask the step bits directly + plasma_step_error -= 1; + } + else + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = 0; + + // option 2 - mask the step bits directly + plasma_step_error = 0; + } + } + return EVENT_CONTINUE; } CREATE_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); -#endif \ No newline at end of file +#endif + +DECL_MODULE(plasma_thc) +{ +#ifdef ENABLE_MAIN_LOOP_MODULES + ADD_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); +#else +#error "Main loop extensions are not enabled. TMC configurations will not work." +#endif +#ifdef ENABLE_PARSER_MODULES + ADD_EVENT_LISTENER(gcode_parse, m103_parse); + ADD_EVENT_LISTENER(gcode_exec, m103_exec); +#else +#error "Parser extensions are not enabled. M103 code extension will not work." +#endif +} + +static void startup_code(void) +{ +// force plasma off +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + mcu_clear_output(PLASMA_ON_OUTPUT); +#endif +} + +static void shutdown_code(void) +{ +// force plasma off +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + mcu_clear_output(PLASMA_ON_OUTPUT); +#endif +} + +static void set_speed(int16_t value) +{ + // turn plasma on + if (value) + { + if (!plasma_thc_arc_ok()) + { + if (plasma_thc_probe_and_start(plasma_start_params)) + { +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + mcu_set_output(PLASMA_ON_OUTPUT); +#endif + } + } + } + else + { +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + mcu_clear_output(PLASMA_ON_OUTPUT); +#endif + } +} + +static int16_t range_speed(int16_t value) +{ + // binary output + value = value ? 1 : 0; + return value; +} + +static void set_coolant(uint8_t value) +{ +// easy macro +#ifdef ENABLE_COOLANT + SET_COOLANT(LASER_PWM_AIR_ASSIST, UNDEF_PIN, value); +#endif +} + +static uint16_t get_speed(void) +{ +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + return mcu_get_output(PLASMA_ON_OUTPUT); +#else + return 0; +#endif +} + +const tool_t plasma_thc = { + .startup_code = &startup_code, + .shutdown_code = &shutdown_code, +#if PID_CONTROLLERS > 0 + .pid_update = NULL, + .pid_error = NULL, +#endif + .range_speed = &range_speed, + .get_speed = &get_speed, + .set_speed = &set_speed, + .set_coolant = &set_coolant}; diff --git a/uCNC/src/module.c b/uCNC/src/module.c index 33783e326..2ce344b72 100644 --- a/uCNC/src/module.c +++ b/uCNC/src/module.c @@ -60,5 +60,9 @@ void mod_init(void) LOAD_MODULE(tmcdriver); #endif +#ifdef ENABLE_PLASMA_THC + LOAD_MODULE(plasma_thc); +#endif + load_modules(); } From 16a7bcc905a1259b5d9f291f4337843557058926 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 4 Jul 2023 11:26:21 +0100 Subject: [PATCH 006/168] initial tests for plasma THC touch and go --- uCNC/src/hal/tools/tools/plasma_thc.c | 30 +++++++++++++++++---------- uCNC/src/interface/grbl_interface.h | 1 + 2 files changed, 20 insertions(+), 11 deletions(-) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index c707870ed..3e65c5884 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -99,7 +99,7 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) if (plasma_starting) { // prevent reentrancy - return; + return false; } plasma_starting = true; @@ -115,7 +115,7 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) mc_get_position(pos); // modify target to probe depth - pos[AXIS_Z] -= start_params.probe_depth; + pos[AXIS_Z] += start_params.probe_depth; // probe feed speed block.feed = start_params.probe_feed; // similar to G38.2 @@ -123,10 +123,10 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) { // modify target to probe depth mc_get_position(pos); - pos[AXIS_Z] += start_params.probe_depth; + pos[AXIS_Z] -= start_params.probe_depth * 0.5; block.feed = start_params.probe_feed * 0.5f; // half speed // similar to G38.4 - if (mc_probe(pos, 2, &block) == STATUS_PROBE_SUCCESS) + if (mc_probe(pos, 1, &block) == STATUS_PROBE_SUCCESS) { // modify target to torch start height mc_get_position(pos); @@ -149,12 +149,7 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) block.feed = start_params.cut_feed; mc_line(pos, &block); cnc_set_exec_state(EXEC_HOLD); - // restore the motion controller, planner and parser - mc_restore(); - planner_restore(); - parser_sync_position(); plasma_thc_enabled = true; - cnc_clear_exec_state(EXEC_HOLD); // continues program plasma_starting = false; return true; @@ -276,8 +271,20 @@ bool plasma_thc_update_loop(void *ptr) planner_clear(); mc_sync_position(); - // clear the current hold state - cnc_clear_exec_state(EXEC_HOLD); + if (plasma_thc_probe_and_start(plasma_start_params)) + { + // restore the motion controller, planner and parser + mc_restore(); + planner_restore(); + parser_sync_position(); + + // clear the current hold state + cnc_clear_exec_state(EXEC_HOLD); + } + else + { + cnc_alarm(EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE); + } } if (plasma_thc_up()) @@ -359,6 +366,7 @@ static void set_speed(int16_t value) { if (plasma_thc_probe_and_start(plasma_start_params)) { + cnc_clear_exec_state(EXEC_HOLD); #if ASSERT_PIN(PLASMA_ON_OUTPUT) mcu_set_output(PLASMA_ON_OUTPUT); #endif diff --git a/uCNC/src/interface/grbl_interface.h b/uCNC/src/interface/grbl_interface.h index ad64ba6cf..1ce26940b 100644 --- a/uCNC/src/interface/grbl_interface.h +++ b/uCNC/src/interface/grbl_interface.h @@ -149,6 +149,7 @@ extern "C" #define EXEC_ALARM_HOMING_FAIL_LIMIT_ACTIVE 11 // homing could not start since one of the limits was already triggered #define EXEC_ALARM_SPINDLE_SYNC_FAIL 12 // failed to achieve spindle sync speed #define EXEC_ALARM_HARD_LIMIT_NOMOTION 13 // hard limits were triggered without any motion (position was not lost) +#define EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE 14 // failed to start arc with plasma THC // formated messages #define STR_EOL "\r\n" From a879915ee54edb069fd62686aab8e4bd91d54e73 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 4 Jul 2023 17:59:49 +0100 Subject: [PATCH 007/168] testings on virtual environment - fixed motion storage and restoration --- makefiles/virtual/uCNC.dev | 6 +-- uCNC/cnc_config.h | 10 ++--- uCNC/cnc_hal_config.h | 4 +- uCNC/src/cnc.c | 53 ++++++++++++++++++++++++- uCNC/src/cnc.h | 2 + uCNC/src/core/interpolator.c | 6 +-- uCNC/src/core/interpolator.h | 1 + uCNC/src/core/motion_control.c | 4 +- uCNC/src/hal/tools/tools/plasma_thc.c | 57 ++++++++++++--------------- 9 files changed, 95 insertions(+), 48 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index bad9967eb..40f6a34c9 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -11,7 +11,7 @@ ResourceIncludes= MakeIncludes= Compiler=-DWIN_INTERFACE=2 -DENABLE_EXTRA_SYSTEM_CMDS -DWIN_COM_NAME=COM11 -DBOARD=BOARD_VIRTUAL -DMCU=MCU_VIRTUAL_WIN_@@_ CppCompiler=_@@_ -Linker=-lws2_32 -lSDL2main -lSDL2_@@_ +Linker=-lws2_32_@@_ IsCpp=0 Icon= ExeOutput= @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=78 +UnitCount=79 [VersionInfo] Major=1 @@ -821,7 +821,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit79] -FileName=..\..\uCNC\src\modules\system_menu.h +FileName=..\..\uCNC\src\hal\tools\tools\plasma_thc.c CompileCpp=0 Folder= Compile=1 diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index d1f16ee5b..c79978a7a 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -286,7 +286,7 @@ extern "C" * enable step counting on sync motion command (needed for some Gcode extensions like G33) * */ - // #define ENABLE_RT_SYNC_MOTIONS + #define ENABLE_RT_SYNC_MOTIONS /** * enable motion control and planner highjacking @@ -294,14 +294,14 @@ extern "C" * this requires some memory since the full planned contents must be stored and also the motion control reference position * */ - // #define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING + #define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING /** * Uncomment to enable module extensions * */ -// #define ENABLE_MAIN_LOOP_MODULES + #define ENABLE_MAIN_LOOP_MODULES // #define ENABLE_IO_MODULES -// #define ENABLE_PARSER_MODULES + #define ENABLE_PARSER_MODULES // #define ENABLE_MOTION_CONTROL_MODULES // #define ENABLE_SETTINGS_MODULES @@ -314,7 +314,7 @@ extern "C" // enables automatic status report sending // this value sets the millisecond interval of the reports // values bellow 100ms have no effect -#define STATUS_AUTOMATIC_REPORT_INTERVAL 0 +#define STATUS_AUTOMATIC_REPORT_INTERVAL 1000 /** * diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 99933d5d1..00f1e4f7e 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -137,7 +137,7 @@ extern "C" * Enables Plasma THC capabilities * * **/ -// #define ENABLE_PLASMA_THC + #define ENABLE_PLASMA_THC /** @@ -147,7 +147,7 @@ extern "C" * * **/ // assign the tools from 1 to 16 -#define TOOL1 spindle_pwm +#define TOOL1 plasma_thc // #define TOOL2 laser // #define TOOL3 laser_ppi // #define TOOL4 spindle_besc diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 97a953f85..346cc0aa1 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -46,6 +46,7 @@ typedef struct volatile int8_t alarm; } cnc_state_t; +static bool lock_itp = false; static cnc_state_t cnc_state; bool cnc_status_report_lock; @@ -207,8 +208,6 @@ bool cnc_exec_cmd(void) bool cnc_dotasks(void) { - static bool lock_itp = false; - // run io basic tasks cnc_io_dotasks(); @@ -251,6 +250,56 @@ bool cnc_dotasks(void) return !cnc_get_exec_state(EXEC_KILL); } +void cnc_store_motion(void) +{ + // set hold and wait for motion to stop + cnc_set_exec_state(EXEC_HOLD); + while (!itp_is_empty() && cnc_get_exec_state(EXEC_RUN)) + { + if (!cnc_dotasks()) + { + return false; + } + } + // store planner and motion controll data away + planner_store(); + mc_store(); + // reset planner and sync systems + itp_clear(); + planner_clear(); + mc_sync_position(); + // clear the current hold state + cnc_clear_exec_state(EXEC_HOLD); + lock_itp = false; +} + +void cnc_restore_motion(void) +{ + // set hold and wait for motion to stop + cnc_set_exec_state(EXEC_HOLD); + while (!itp_is_empty()) + { + if (!cnc_dotasks()) + { + return false; + } + } + + // reset planner and sync systems + itp_clear(); + planner_clear(); + mc_sync_position(); + + // restore the motion controller, planner and parser + mc_restore(); + planner_restore(); + parser_sync_position(); + + // clear the current hold state + cnc_clear_exec_state(EXEC_HOLD); + lock_itp = false; +} + // this function is executed every millisecond MCU_CALLBACK void mcu_rtc_cb(uint32_t millis) { diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index 814bd004e..6a88fd33a 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -179,6 +179,8 @@ extern "C" void cnc_stop(void); uint8_t cnc_unlock(bool force); void cnc_delay_ms(uint32_t miliseconds); + void cnc_store_motion(void); + void cnc_restore_motion(void); uint8_t cnc_get_exec_state(uint8_t statemask); void cnc_set_exec_state(uint8_t statemask); diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 0c131b521..dcc7df058 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1010,7 +1010,7 @@ void itp_stop(void) // end of JOG if (state & EXEC_JOG) { - if (itp_is_empty()) + if (itp_is_empty() && planner_buffer_is_empty()) { cnc_clear_exec_state(EXEC_JOG); } @@ -1109,14 +1109,14 @@ float itp_get_rt_feed(void) bool itp_is_empty(void) { - return (planner_buffer_is_empty() && itp_sgm_is_empty() && (itp_rt_sgm == NULL)); + return (itp_sgm_is_empty() && (itp_rt_sgm == NULL)); } // flushes all motions from all systems (planner or interpolator) // used to make a sync motion uint8_t itp_sync(void) { - while (!itp_is_empty()) + while (!itp_is_empty() || !planner_buffer_is_empty()) { if (!cnc_dotasks()) { diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index dad234436..4a8004a7c 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -92,6 +92,7 @@ extern "C" float itp_get_rt_feed(void); bool itp_is_empty(void); uint8_t itp_sync(void); + void itp_sync_spindle(void); void itp_start(bool is_synched); #if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(KINEMATICS_MOTION_BY_SEGMENTS)) diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 910991d7c..d898aac17 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -862,9 +862,11 @@ uint8_t mc_probe(float *target, uint8_t flags, motion_data_t *block_data) return STATUS_OK; } - mc_line(target, block_data); // enable the probe io_enable_probe(); + mcu_probe_changed_cb(); + mc_line(target, block_data); + do { if (io_get_probe() ^ (flags & 0x01)) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 3e65c5884..db0d385d8 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -92,7 +92,7 @@ typedef struct plasma_start_params_ } plasma_start_params_t; static plasma_start_params_t plasma_start_params; -bool plasma_thc_probe_and_start(plasma_start_params_t start_params) +bool plasma_thc_probe_and_start(void) { static bool plasma_starting = false; plasma_thc_enabled = false; @@ -103,7 +103,10 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) } plasma_starting = true; - while (start_params.retries--) + uint8_t ret = plasma_start_params.retries; + cnc_store_motion(); + + while (ret--) { // cutoff torch motion_data_t block = {0}; @@ -115,28 +118,28 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) mc_get_position(pos); // modify target to probe depth - pos[AXIS_Z] += start_params.probe_depth; + pos[AXIS_Z] += plasma_start_params.probe_depth; // probe feed speed - block.feed = start_params.probe_feed; + block.feed = plasma_start_params.probe_feed; // similar to G38.2 if (mc_probe(pos, 0, &block) == STATUS_PROBE_SUCCESS) { // modify target to probe depth mc_get_position(pos); - pos[AXIS_Z] -= start_params.probe_depth * 0.5; - block.feed = start_params.probe_feed * 0.5f; // half speed + pos[AXIS_Z] -= plasma_start_params.probe_depth * 0.5; + block.feed = plasma_start_params.probe_feed * 0.5f; // half speed // similar to G38.4 if (mc_probe(pos, 1, &block) == STATUS_PROBE_SUCCESS) { // modify target to torch start height mc_get_position(pos); - pos[AXIS_Z] += start_params.retract_height; + pos[AXIS_Z] += plasma_start_params.retract_height; // rapid feed block.feed = FLT_MAX; mc_line(pos, &block); // turn torch on and wait before confirm the arc on signal block.motion_flags.bit.spindle_running = 1; - block.dwell = start_params.dwell; + block.dwell = plasma_start_params.dwell; // updated tools and wait mc_dwell(&block); @@ -144,20 +147,22 @@ bool plasma_thc_probe_and_start(plasma_start_params_t start_params) if (plasma_thc_arc_ok()) { mc_get_position(pos); - pos[AXIS_Z] -= start_params.cut_depth; + pos[AXIS_Z] -= plasma_start_params.cut_depth; // rapid feed - block.feed = start_params.cut_feed; + block.feed = plasma_start_params.cut_feed; mc_line(pos, &block); cnc_set_exec_state(EXEC_HOLD); plasma_thc_enabled = true; // continues program plasma_starting = false; + cnc_restore_motion(); return true; } } } } + cnc_restore_motion(); plasma_starting = false; return false; } @@ -174,15 +179,17 @@ void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) if (step_error > 0) { *stepbits |= PLASMA_STEPPERS_MASK; - io_set_dirs(rt_sgm->block->dirbits & ~PLASMA_STEPPERS_MASK); + rt_sgm->block->dirbits &= ~PLASMA_STEPPERS_MASK; + io_set_dirs(rt_sgm->block->dirbits); step_error--; } if (step_error < 0) { *stepbits |= PLASMA_STEPPERS_MASK; - io_set_dirs(rt_sgm->block->dirbits | PLASMA_STEPPERS_MASK); - step_error--; + rt_sgm->block->dirbits |= PLASMA_STEPPERS_MASK; + io_set_dirs(rt_sgm->block->dirbits); + step_error++; } plasma_step_error = step_error; @@ -261,28 +268,14 @@ bool plasma_thc_update_loop(void *ptr) // on arc lost the plasma must enter hold if (!(plasma_thc_arc_ok())) { - // set hold and wait for motion to stop - cnc_set_exec_state(EXEC_HOLD); - itp_sync(); - // store planner and motion controll data away - planner_store(); - mc_store(); - // reset planner and sync systems - planner_clear(); - mc_sync_position(); - - if (plasma_thc_probe_and_start(plasma_start_params)) + if (plasma_thc_probe_and_start()) { - // restore the motion controller, planner and parser - mc_restore(); - planner_restore(); - parser_sync_position(); - - // clear the current hold state - cnc_clear_exec_state(EXEC_HOLD); } else { + // must restore the planner and motion to be purged + mc_restore(); + planner_restore(); cnc_alarm(EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE); } } @@ -364,7 +357,7 @@ static void set_speed(int16_t value) { if (!plasma_thc_arc_ok()) { - if (plasma_thc_probe_and_start(plasma_start_params)) + if (plasma_thc_probe_and_start()) { cnc_clear_exec_state(EXEC_HOLD); #if ASSERT_PIN(PLASMA_ON_OUTPUT) From 2100db85cf0fe2a71d3272b3300bd4c7136b6099 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 5 Jul 2023 00:14:56 +0100 Subject: [PATCH 008/168] thc up and down controls working --- uCNC/src/core/interpolator.c | 26 ++++++++++++++++++-------- uCNC/src/core/interpolator.h | 2 +- uCNC/src/hal/tools/tools/plasma_thc.c | 14 ++++++-------- 3 files changed, 25 insertions(+), 17 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index dcc7df058..5ce9aaa60 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1166,7 +1166,7 @@ MCU_CALLBACK void laser_ppi_turnoff_cb(void) #endif #ifdef ENABLE_RT_SYNC_MOTIONS -void __attribute__((weak)) itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) +void __attribute__((weak)) itp_rt_stepbits(uint8_t *stepbits, uint8_t *dirs) { } #endif @@ -1503,8 +1503,18 @@ MCU_CALLBACK void mcu_step_cb(void) #endif #endif + uint8_t dirs = itp_rt_sgm->block->dirbits; #ifdef ENABLE_RT_SYNC_MOTIONS - itp_rt_stepbits(&new_stepbits, itp_rt_sgm); + static uint8_t last_dirs = 0; + if (new_stepbits) + { + itp_rt_stepbits(&new_stepbits, &dirs); + if (dirs != last_dirs) + { + last_dirs = dirs; + io_set_dirs(dirs); + } + } #endif // updates the stepper coordinates @@ -1515,7 +1525,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR0_MASK) + if (dirs & DIR0_MASK) { itp_rt_step_pos[0]--; } @@ -1535,7 +1545,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR1_MASK) + if (dirs & DIR1_MASK) { itp_rt_step_pos[1]--; } @@ -1555,7 +1565,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR2_MASK) + if (dirs & DIR2_MASK) { itp_rt_step_pos[2]--; } @@ -1575,7 +1585,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR3_MASK) + if (dirs & DIR3_MASK) { itp_rt_step_pos[3]--; } @@ -1596,7 +1606,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR4_MASK) + if (dirs & DIR4_MASK) { itp_rt_step_pos[4]--; } @@ -1617,7 +1627,7 @@ MCU_CALLBACK void mcu_step_cb(void) if (!itp_rt_sgm->block->backlash_comp) { #endif - if (itp_rt_sgm->block->dirbits & DIR5_MASK) + if (dirs & DIR5_MASK) { itp_rt_step_pos[5]--; } diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index 4a8004a7c..3d63af062 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -105,7 +105,7 @@ extern "C" extern volatile int32_t itp_sync_step_counter; void itp_update_feed(float feed); bool itp_sync_ready(void); - void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t* rt_sgm); + void itp_rt_stepbits(uint8_t *stepbits, uint8_t* dirs); #endif #ifdef __cplusplus diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index db0d385d8..ed73ad9ab 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -168,9 +168,9 @@ bool plasma_thc_probe_and_start(void) } #ifdef ENABLE_RT_SYNC_MOTIONS -void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) +void itp_rt_stepbits(uint8_t *stepbits, uint8_t *dirs) { - uint8_t step_error = plasma_step_error; + int8_t step_error = plasma_step_error; if (!step_error) { return; @@ -179,16 +179,14 @@ void itp_rt_stepbits(uint8_t *stepbits, itp_segment_t *rt_sgm) if (step_error > 0) { *stepbits |= PLASMA_STEPPERS_MASK; - rt_sgm->block->dirbits &= ~PLASMA_STEPPERS_MASK; - io_set_dirs(rt_sgm->block->dirbits); + *dirs &= ~PLASMA_STEPPERS_MASK; step_error--; } if (step_error < 0) { *stepbits |= PLASMA_STEPPERS_MASK; - rt_sgm->block->dirbits |= PLASMA_STEPPERS_MASK; - io_set_dirs(rt_sgm->block->dirbits); + *dirs |= PLASMA_STEPPERS_MASK; step_error++; } @@ -289,7 +287,7 @@ bool plasma_thc_update_loop(void *ptr) // p->dirbits &= 0xFB; // option 2 - mask the step bits directly - plasma_step_error += 1; + plasma_step_error = 1; } else if (plasma_thc_down()) { @@ -300,7 +298,7 @@ bool plasma_thc_update_loop(void *ptr) // p->dirbits |= 4; // option 2 - mask the step bits directly - plasma_step_error -= 1; + plasma_step_error = -1; } else { From 60bbe46495736e5e0f19e5504c990d2a3d8c4dd5 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 5 Jul 2023 14:31:42 +0100 Subject: [PATCH 009/168] modified THC to require user action on arc fail - modified THC to require user action on arc fail (safety reasons) - added systems position sync on THC mode off --- uCNC/src/cnc.c | 15 +++++++++--- uCNC/src/hal/tools/tools/plasma_thc.c | 35 ++++++++++++++++++++++----- 2 files changed, 41 insertions(+), 9 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 346cc0aa1..ea1356277 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -253,6 +253,7 @@ bool cnc_dotasks(void) void cnc_store_motion(void) { // set hold and wait for motion to stop + uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); while (!itp_is_empty() && cnc_get_exec_state(EXEC_RUN)) { @@ -268,14 +269,19 @@ void cnc_store_motion(void) itp_clear(); planner_clear(); mc_sync_position(); - // clear the current hold state - cnc_clear_exec_state(EXEC_HOLD); + // clear the current hold state (if not set previosly) + if (!prevholdstate) + { + cnc_clear_exec_state(EXEC_HOLD); + } + lock_itp = false; } void cnc_restore_motion(void) { // set hold and wait for motion to stop + uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); while (!itp_is_empty()) { @@ -296,7 +302,10 @@ void cnc_restore_motion(void) parser_sync_position(); // clear the current hold state - cnc_clear_exec_state(EXEC_HOLD); + if (!prevholdstate) + { + cnc_clear_exec_state(EXEC_HOLD); + } lock_itp = false; } diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index ed73ad9ab..7500cefcd 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -76,9 +76,14 @@ uint8_t __attribute__((weak)) plasma_thc_arc_ok(void) #endif } +#define PLASMA_ARC_OFF 0 +#define PLASMA_ARC_OK 1 +#define PLASMA_ARC_LOST 2 + // plasma thc controller variables -static bool plasma_thc_enabled; +static uint8_t plasma_thc_state; static volatile int8_t plasma_step_error; + typedef struct plasma_start_params_ { float probe_depth; // I @@ -88,14 +93,12 @@ typedef struct plasma_start_params_ float cut_feed; // F uint16_t dwell; // P*1000 uint8_t retries; // L - } plasma_start_params_t; static plasma_start_params_t plasma_start_params; bool plasma_thc_probe_and_start(void) { static bool plasma_starting = false; - plasma_thc_enabled = false; if (plasma_starting) { // prevent reentrancy @@ -106,9 +109,17 @@ bool plasma_thc_probe_and_start(void) uint8_t ret = plasma_start_params.retries; cnc_store_motion(); + // wait for cycle start + while (cnc_get_exec_state(EXEC_HOLD)) + { + cnc_dotasks(); + } + while (ret--) { // cutoff torch + // temporary disable + plasma_thc_state = PLASMA_ARC_OFF; motion_data_t block = {0}; block.motion_flags.bit.spindle_running = 0; mc_update_tools(&block); @@ -151,8 +162,8 @@ bool plasma_thc_probe_and_start(void) // rapid feed block.feed = plasma_start_params.cut_feed; mc_line(pos, &block); - cnc_set_exec_state(EXEC_HOLD); - plasma_thc_enabled = true; + // enable plasma mode + plasma_thc_state = PLASMA_ARC_OK; // continues program plasma_starting = false; cnc_restore_motion(); @@ -260,12 +271,19 @@ bool m103_exec(void *args) #ifdef ENABLE_MAIN_LOOP_MODULES bool plasma_thc_update_loop(void *ptr) { - if (plasma_thc_enabled) + if (plasma_thc_state == PLASMA_ARC_OK) { // arc lost // on arc lost the plasma must enter hold if (!(plasma_thc_arc_ok())) { + // places the machine under a HOLD and signals the arc lost + // this requires the operator to inspect the work to see if was + // a simple arc lost or the torch is hover a hole + plasma_thc_state = PLASMA_ARC_LOST; + cnc_set_exec_state(EXEC_HOLD); + + // prepares the reprobing action to be executed on cycle resume action if (plasma_thc_probe_and_start()) { } @@ -353,6 +371,8 @@ static void set_speed(int16_t value) // turn plasma on if (value) { + // enable plasma mode + plasma_thc_state = true; if (!plasma_thc_arc_ok()) { if (plasma_thc_probe_and_start()) @@ -366,9 +386,12 @@ static void set_speed(int16_t value) } else { + // disable plasma THC mode + plasma_thc_state = false; #if ASSERT_PIN(PLASMA_ON_OUTPUT) mcu_clear_output(PLASMA_ON_OUTPUT); #endif + mc_sync_position(); } } From 7d327c1549a92981e238680e5e8fe9d7f8c69c32 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 8 Jul 2023 11:11:49 +0100 Subject: [PATCH 010/168] new IO HAL --- uCNC/cnc_hal_config.h | 12 +- uCNC/src/cnc.c | 2 +- uCNC/src/cnc_hal_config_helper.h | 13 +- uCNC/src/core/interpolator.c | 8 +- uCNC/src/core/io_control.c | 1220 +++-- uCNC/src/core/io_control.h | 69 +- uCNC/src/hal/io_hal.h | 4406 +++++++++++++++++ uCNC/src/hal/mcus/avr/mcu_avr.c | 28 +- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 88 +- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 64 +- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 2 +- uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 28 +- uCNC/src/hal/mcus/rp2040/mcu_rp2040.c | 24 +- uCNC/src/hal/mcus/samd21/mcu_samd21.c | 28 +- uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 28 +- uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 28 +- uCNC/src/hal/tools/tools/laser_ppi.c | 10 +- uCNC/src/hal/tools/tools/laser_pwm.c | 8 +- uCNC/src/hal/tools/tools/spindle_besc.c | 4 +- uCNC/src/hal/tools/tools/spindle_pwm.c | 14 +- uCNC/src/hal/tools/tools/spindle_relay.c | 12 +- uCNC/src/hal/tools/tools/vfd_pwm.c | 16 +- uCNC/src/interface/serial.c | 2 +- uCNC/src/modules/digimstep.c | 32 +- uCNC/src/modules/digipot.c | 10 +- uCNC/src/modules/encoder.c | 18 +- uCNC/src/modules/ic74hc595.c | 172 +- uCNC/src/modules/ic74hc595.h | 799 ++- uCNC/src/modules/softi2c.h | 28 +- uCNC/src/modules/softspi.h | 10 +- uCNC/src/modules/softuart.h | 6 +- uCNC/src/modules/tmcdriver.c | 28 +- 32 files changed, 6404 insertions(+), 813 deletions(-) create mode 100644 uCNC/src/hal/io_hal.h diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 16940517f..1b4bb796c 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -232,9 +232,9 @@ extern "C" * * For example * - * #define PID1_DELTA() (my_setpoint - mcu_get_analog(ANA0)) - * #define PID1_OUTPUT(X) (mcu_set_pwm(PWM0, X)) - * #define PID1_STOP() (mcu_set_pwm(PWM0, 0)) + * #define PID1_DELTA() (my_setpoint - io_get_analog(ANA0)) + * #define PID1_OUTPUT(X) (io_set_pwm(PWM0, X)) + * #define PID1_STOP() (io_set_pwm(PWM0, 0)) * * An optional configuration is the sampling rate of the PID update. By default the sampling rate is 125Hz. * To reduce the sampling rate a 125/PIDx_FREQ_DIV can be defined between 1 (125Hz) and 250 (0.5Hz) @@ -247,9 +247,9 @@ extern "C" // reference to io_get_spindle defined in io_control // extern uint8_t io_get_spindle(void); // #define SPINDLE_SPEED ANALOG0 - // #define PID1_DELTA() (io_get_spindle() - mcu_get_analog(SPINDLE_SPEED)) - // #define PID1_OUTPUT(X) (mcu_set_pwm(SPINDLE_PWM, X)) - // #define PID1_STOP() (mcu_set_pwm(PWM0, 0)) + // #define PID1_DELTA() (io_get_spindle() - io_get_analog(SPINDLE_SPEED)) + // #define PID1_OUTPUT(X) (io_set_pwm(SPINDLE_PWM, X)) + // #define PID1_STOP() (io_set_pwm(PWM0, 0)) // //optional // #define PID1_FREQ_DIV 50 #endif diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 97a953f85..caff08c04 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -281,7 +281,7 @@ MCU_CALLBACK void mcu_rtc_cb(uint32_t millis) // this blinks aprox. once every 1024ms if (!(millis & (0x200 - 1))) { - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); } #endif mcu_disable_global_isr(); diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 0a19d1373..4c12a723f 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -24,9 +24,18 @@ extern "C" { #endif +//undefined pin #define UNDEF_PIN 0 -#define ASSERT_PIN(X) (X > 0) -#define ASSERT_PIN_EXTENDER(X) (X >= 0) +// assert pin (io or extended) +#define ASSERT_PIN(X) (X != 0) +#define _EVAL_DIO_(X) DIO##X +#define EVAL_DIO(X) DIO##X +// assert pin io +#define ASSERT_PIN_IO(X) (EVAL_DIO(X) > 0) +// assert pin extended +#define ASSERT_PIN_EXTENDED(X) (EVAL_DIO(X) < 0) +// assert pin extended offset +#define ASSERT_IO_OFFSET(X) (X >= 0) /** * diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 20310e6c0..a716816c0 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1209,9 +1209,9 @@ uint32_t itp_get_rt_line_number(void) MCU_CALLBACK void laser_ppi_turnoff_cb(void) { #ifndef INVERT_LASER_PPI_LOGIC - mcu_clear_output(LASER_PPI); + io_clear_output(LASER_PPI); #else - mcu_set_output(LASER_PPI); + io_set_output(LASER_PPI); #endif } #endif @@ -1284,9 +1284,9 @@ MCU_CALLBACK void mcu_step_cb(void) } mcu_start_timeout(); #ifndef INVERT_LASER_PPI_LOGIC - mcu_set_output(LASER_PPI); + io_set_output(LASER_PPI); #else - mcu_clear_output(LASER_PPI); + io_clear_output(LASER_PPI); #endif } } diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index c9a7aa7ff..04bf7a10c 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -263,49 +263,49 @@ MCU_IO_CALLBACK void mcu_inputs_changed_cb(void) uint8_t diff; #if (ASSERT_PIN(DIN0) && defined(DIN0_ISR)) - if (mcu_get_input(DIN0)) + if (io_get_input(DIN0)) { inputs |= DIN0_MASK; } #endif #if (ASSERT_PIN(DIN1) && defined(DIN1_ISR)) - if (mcu_get_input(DIN1)) + if (io_get_input(DIN1)) { inputs |= DIN1_MASK; } #endif #if (ASSERT_PIN(DIN2) && defined(DIN2_ISR)) - if (mcu_get_input(DIN2)) + if (io_get_input(DIN2)) { inputs |= DIN2_MASK; } #endif #if (ASSERT_PIN(DIN3) && defined(DIN3_ISR)) - if (mcu_get_input(DIN3)) + if (io_get_input(DIN3)) { inputs |= DIN3_MASK; } #endif #if (ASSERT_PIN(DIN4) && defined(DIN4_ISR)) - if (mcu_get_input(DIN4)) + if (io_get_input(DIN4)) { inputs |= DIN4_MASK; } #endif #if (ASSERT_PIN(DIN5) && defined(DIN5_ISR)) - if (mcu_get_input(DIN5)) + if (io_get_input(DIN5)) { inputs |= DIN5_MASK; } #endif #if (ASSERT_PIN(DIN6) && defined(DIN6_ISR)) - if (mcu_get_input(DIN6)) + if (io_get_input(DIN6)) { inputs |= DIN6_MASK; } #endif #if (ASSERT_PIN(DIN7) && defined(DIN7_ISR)) - if (mcu_get_input(DIN7)) + if (io_get_input(DIN7)) { inputs |= DIN7_MASK; } @@ -349,22 +349,22 @@ uint8_t io_get_limits(void) uint8_t value = 0; #if ASSERT_PIN(LIMIT_X) - value |= ((mcu_get_input(LIMIT_X)) ? LIMIT_X_MASK : 0); + value |= ((io_get_input(LIMIT_X)) ? LIMIT_X_MASK : 0); #endif #if ASSERT_PIN(LIMIT_Y) - value |= ((mcu_get_input(LIMIT_Y)) ? LIMIT_Y_MASK : 0); + value |= ((io_get_input(LIMIT_Y)) ? LIMIT_Y_MASK : 0); #endif #if ASSERT_PIN(LIMIT_Z) - value |= ((mcu_get_input(LIMIT_Z)) ? LIMIT_Z_MASK : 0); + value |= ((io_get_input(LIMIT_Z)) ? LIMIT_Z_MASK : 0); #endif #if ASSERT_PIN(LIMIT_A) - value |= ((mcu_get_input(LIMIT_A)) ? LIMIT_A_MASK : 0); + value |= ((io_get_input(LIMIT_A)) ? LIMIT_A_MASK : 0); #endif #if ASSERT_PIN(LIMIT_B) - value |= ((mcu_get_input(LIMIT_B)) ? LIMIT_B_MASK : 0); + value |= ((io_get_input(LIMIT_B)) ? LIMIT_B_MASK : 0); #endif #if ASSERT_PIN(LIMIT_C) - value |= ((mcu_get_input(LIMIT_C)) ? LIMIT_C_MASK : 0); + value |= ((io_get_input(LIMIT_C)) ? LIMIT_C_MASK : 0); #endif uint8_t inv = g_settings.limits_invert_mask; @@ -375,17 +375,17 @@ uint8_t io_get_limits(void) #if ASSERT_PIN(LIMIT_X2) #if !(LIMITS_DUAL_MASK & LIMIT_X_MASK) - value2 |= ((mcu_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); + value2 |= ((io_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); #endif #endif #if ASSERT_PIN(LIMIT_Y2) #if !(LIMITS_DUAL_MASK & LIMIT_Y_MASK) - value2 |= ((mcu_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); + value2 |= ((io_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); #endif #endif #if ASSERT_PIN(LIMIT_Z2) #if !(LIMITS_DUAL_MASK & LIMIT_Z_MASK) - value2 |= ((mcu_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); + value2 |= ((io_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); #endif #endif @@ -415,17 +415,17 @@ uint8_t io_get_limits_dual(void) uint8_t value = 0; #if ASSERT_PIN(LIMIT_X2) #if (LIMITS_DUAL_MASK & LIMIT_X_MASK) - value |= ((mcu_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); + value |= ((io_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); #endif #endif #if ASSERT_PIN(LIMIT_Y2) #if (LIMITS_DUAL_MASK & LIMIT_Y_MASK) - value |= ((mcu_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); + value |= ((io_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); #endif #endif #if ASSERT_PIN(LIMIT_Z2) #if (LIMITS_DUAL_MASK & LIMIT_Z_MASK) - value |= ((mcu_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); + value |= ((io_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); #endif #endif uint8_t inv = io_invert_limits_mask & LIMITS_DUAL_MASK; @@ -441,19 +441,19 @@ uint8_t io_get_controls(void) uint8_t value = 0; #if ASSERT_PIN(ESTOP) #ifndef INVERT_EMERGENCY_STOP - value |= ((mcu_get_input(ESTOP)) ? ESTOP_MASK : 0); + value |= ((io_get_input(ESTOP)) ? ESTOP_MASK : 0); #else - value |= ((!mcu_get_input(ESTOP)) ? ESTOP_MASK : 0); + value |= ((!io_get_input(ESTOP)) ? ESTOP_MASK : 0); #endif #endif #if ASSERT_PIN(SAFETY_DOOR) - value |= ((mcu_get_input(SAFETY_DOOR)) ? SAFETY_DOOR_MASK : 0); + value |= ((io_get_input(SAFETY_DOOR)) ? SAFETY_DOOR_MASK : 0); #endif #if ASSERT_PIN(FHOLD) - value |= ((mcu_get_input(FHOLD)) ? FHOLD_MASK : 0); + value |= ((io_get_input(FHOLD)) ? FHOLD_MASK : 0); #endif #if ASSERT_PIN(CS_RES) - value |= ((mcu_get_input(CS_RES)) ? CS_RES_MASK : 0); + value |= ((io_get_input(CS_RES)) ? CS_RES_MASK : 0); #endif return (value ^ (g_settings.control_invert_mask & CONTROLS_INV_MASK)); @@ -492,7 +492,7 @@ bool io_get_probe(void) return false; #else #if ASSERT_PIN(PROBE) - bool probe = (mcu_get_input(PROBE) != 0); + bool probe = (io_get_input(PROBE) != 0); return (!g_settings.probe_invert_mask) ? probe : !probe; #else return false; @@ -511,7 +511,7 @@ void io_set_steps(uint8_t mask) ic74hc595_set_steps(mask); #endif -#if ASSERT_PIN(STEP0) +#if ASSERT_PIN_IO(STEP0) if (mask & STEP0_MASK) { mcu_set_output(STEP0); @@ -522,7 +522,7 @@ void io_set_steps(uint8_t mask) } #endif -#if ASSERT_PIN(STEP1) +#if ASSERT_PIN_IO(STEP1) if (mask & STEP1_MASK) { mcu_set_output(STEP1); @@ -532,7 +532,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP1); } #endif -#if ASSERT_PIN(STEP2) +#if ASSERT_PIN_IO(STEP2) if (mask & STEP2_MASK) { mcu_set_output(STEP2); @@ -542,7 +542,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP2); } #endif -#if ASSERT_PIN(STEP3) +#if ASSERT_PIN_IO(STEP3) if (mask & STEP3_MASK) { mcu_set_output(STEP3); @@ -552,7 +552,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP3); } #endif -#if ASSERT_PIN(STEP4) +#if ASSERT_PIN_IO(STEP4) if (mask & STEP4_MASK) { mcu_set_output(STEP4); @@ -562,7 +562,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP4); } #endif -#if ASSERT_PIN(STEP5) +#if ASSERT_PIN_IO(STEP5) if (mask & STEP5_MASK) { mcu_set_output(STEP5); @@ -572,7 +572,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP5); } #endif -#if ASSERT_PIN(STEP6) +#if ASSERT_PIN_IO(STEP6) if (mask & STEP6_MASK) { mcu_set_output(STEP6); @@ -582,7 +582,7 @@ void io_set_steps(uint8_t mask) mcu_clear_output(STEP6); } #endif -#if ASSERT_PIN(STEP7) +#if ASSERT_PIN_IO(STEP7) if (mask & STEP7_MASK) { mcu_set_output(STEP7); @@ -604,49 +604,49 @@ void io_toggle_steps(uint8_t mask) ic74hc595_toggle_steps(mask); #endif -#if ASSERT_PIN(STEP0) +#if ASSERT_PIN_IO(STEP0) if (mask & STEP0_MASK) { mcu_toggle_output(STEP0); } #endif -#if ASSERT_PIN(STEP1) +#if ASSERT_PIN_IO(STEP1) if (mask & STEP1_MASK) { mcu_toggle_output(STEP1); } #endif -#if ASSERT_PIN(STEP2) +#if ASSERT_PIN_IO(STEP2) if (mask & STEP2_MASK) { mcu_toggle_output(STEP2); } #endif -#if ASSERT_PIN(STEP3) +#if ASSERT_PIN_IO(STEP3) if (mask & STEP3_MASK) { mcu_toggle_output(STEP3); } #endif -#if ASSERT_PIN(STEP4) +#if ASSERT_PIN_IO(STEP4) if (mask & STEP4_MASK) { mcu_toggle_output(STEP4); } #endif -#if ASSERT_PIN(STEP5) +#if ASSERT_PIN_IO(STEP5) if (mask & STEP5_MASK) { mcu_toggle_output(STEP5); } #endif -#if ASSERT_PIN(STEP6) +#if ASSERT_PIN_IO(STEP6) if (mask & STEP6_MASK) { mcu_toggle_output(STEP6); } #endif -#if ASSERT_PIN(STEP7) +#if ASSERT_PIN_IO(STEP7) if (mask & STEP7_MASK) { mcu_toggle_output(STEP7); @@ -666,7 +666,7 @@ void io_set_dirs(uint8_t mask) ic74hc595_set_dirs(mask); #endif -#if ASSERT_PIN(DIR0) +#if ASSERT_PIN_IO(DIR0) if (mask & DIR0_MASK) { mcu_set_output(DIR0); @@ -676,7 +676,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR0); } #endif -#if ASSERT_PIN(DIR1) +#if ASSERT_PIN_IO(DIR1) if (mask & DIR1_MASK) { mcu_set_output(DIR1); @@ -686,7 +686,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR1); } #endif -#if ASSERT_PIN(DIR2) +#if ASSERT_PIN_IO(DIR2) if (mask & DIR2_MASK) { mcu_set_output(DIR2); @@ -696,7 +696,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR2); } #endif -#if ASSERT_PIN(DIR3) +#if ASSERT_PIN_IO(DIR3) if (mask & DIR3_MASK) { mcu_set_output(DIR3); @@ -706,7 +706,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR3); } #endif -#if ASSERT_PIN(DIR4) +#if ASSERT_PIN_IO(DIR4) if (mask & DIR4_MASK) { mcu_set_output(DIR4); @@ -716,7 +716,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR4); } #endif -#if ASSERT_PIN(DIR5) +#if ASSERT_PIN_IO(DIR5) if (mask & DIR5_MASK) { mcu_set_output(DIR5); @@ -726,7 +726,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR5); } #endif -#if ASSERT_PIN(DIR6) +#if ASSERT_PIN_IO(DIR6) if (mask & DIR6_MASK) { mcu_set_output(DIR6); @@ -736,7 +736,7 @@ void io_set_dirs(uint8_t mask) mcu_clear_output(DIR6); } #endif -#if ASSERT_PIN(DIR7) +#if ASSERT_PIN_IO(DIR7) if (mask & DIR7_MASK) { mcu_set_output(DIR7); @@ -748,13 +748,400 @@ void io_set_dirs(uint8_t mask) #endif } -void io_set_pwm(uint8_t pin, uint8_t value) +void io_enable_steppers(uint8_t mask) +{ + // #ifdef ENABLE_IO_MODULES + // EVENT_INVOKE(enable_steppers, &mask); + // #endif + +#ifdef IC74HC595_HAS_STEPS_EN + ic74hc595_enable_steppers(mask); +#endif + +#if ASSERT_PIN_IO(STEP0_EN) + if (mask & 0x01) + { + mcu_set_output(STEP0_EN); + } + else + { + mcu_clear_output(STEP0_EN); + } +#endif +#if ASSERT_PIN_IO(STEP1_EN) + if (mask & 0x02) + { + mcu_set_output(STEP1_EN); + } + else + { + mcu_clear_output(STEP1_EN); + } +#endif +#if ASSERT_PIN_IO(STEP2_EN) + if (mask & 0x04) + { + mcu_set_output(STEP2_EN); + } + else + { + mcu_clear_output(STEP2_EN); + } +#endif +#if ASSERT_PIN_IO(STEP3_EN) + if (mask & 0x08) + { + mcu_set_output(STEP3_EN); + } + else + { + mcu_clear_output(STEP3_EN); + } +#endif +#if ASSERT_PIN_IO(STEP4_EN) + if (mask & 0x10) + { + mcu_set_output(STEP4_EN); + } + else + { + mcu_clear_output(STEP4_EN); + } +#endif +#if ASSERT_PIN_IO(STEP5_EN) + if (mask & 0x20) + { + mcu_set_output(STEP5_EN); + } + else + { + mcu_clear_output(STEP5_EN); + } +#endif +#if ASSERT_PIN_IO(STEP6_EN) + if (mask & 0x40) + { + mcu_set_output(STEP6_EN); + } + else + { + mcu_clear_output(STEP6_EN); + } +#endif +#if ASSERT_PIN_IO(STEP7_EN) + if (mask & 0x80) + { + mcu_set_output(STEP7_EN); + } + else + { + mcu_clear_output(STEP7_EN); + } +#endif +} + +#if defined(MCU_HAS_SOFT_PWM_TIMER) || defined(IC74HC595_HAS_PWMS) +// software pwm counters +uint8_t g_io_soft_pwm[16]; +#ifdef IC74HC595_HAS_PWMS +static uint16_t soft_pwm_mask; +#endif +// software pwm resolution reduction factor +// PWM resolution in bits will be equal to (8 - g_soft_pwm_res) +// this is determined by the mcu_softpwm_freq_config +uint8_t g_soft_pwm_res; + +void io_soft_pwm_update(void) +{ + static uint8_t pwm_counter = 0; + uint8_t resolution = g_soft_pwm_res; +#ifdef IC74HC595_HAS_PWMS + static uint16_t pwm_mask_last = 0; + uint16_t pwm_mask = soft_pwm_mask; +#endif + // software PWM + if ((++pwm_counter) >> resolution) + { + uint8_t pwm_ref = pwm_counter << resolution; +#if ASSERT_PIN(PWM0) + if (pwm_ref > g_io_soft_pwm[0]) + { +#if ASSERT_PIN_IO(PWM0) + mcu_clear_output(PWM0); +#elif ASSERT_PIN_EXTENDED(PWM0) + pwm_mask &= ~(1 << 0); +#endif + } +#endif +#if ASSERT_PIN(PWM1) + if (pwm_ref > g_io_soft_pwm[1]) + { +#if ASSERT_PIN_IO(PWM1) + mcu_clear_output(PWM1); +#elif ASSERT_PIN_EXTENDED(PWM1) + pwm_mask &= ~(1 << 1); +#endif + } +#endif +#if ASSERT_PIN(PWM2) + if (pwm_ref > g_io_soft_pwm[2]) + { +#if ASSERT_PIN_IO(PWM2) + mcu_clear_output(PWM2); +#elif ASSERT_PIN_EXTENDED(PWM2) + pwm_mask &= ~(1 << 2); +#endif + } +#endif +#if ASSERT_PIN(PWM3) + if (pwm_ref > g_io_soft_pwm[3]) + { +#if ASSERT_PIN_IO(PWM3) + mcu_clear_output(PWM3); +#elif ASSERT_PIN_EXTENDED(PWM3) + pwm_mask &= ~(1 << 3); +#endif + } +#endif +#if ASSERT_PIN(PWM4) + if (pwm_ref > g_io_soft_pwm[4]) + { +#if ASSERT_PIN_IO(PWM4) + mcu_clear_output(PWM4); +#elif ASSERT_PIN_EXTENDED(PWM4) + pwm_mask &= ~(1 << 4); +#endif + } +#endif +#if ASSERT_PIN(PWM5) + if (pwm_ref > g_io_soft_pwm[5]) + { +#if ASSERT_PIN_IO(PWM5) + mcu_clear_output(PWM5); +#elif ASSERT_PIN_EXTENDED(PWM5) + pwm_mask &= ~(1 << 5); +#endif + } +#endif +#if ASSERT_PIN(PWM6) + if (pwm_ref > g_io_soft_pwm[6]) + { +#if ASSERT_PIN_IO(PWM6) + mcu_clear_output(PWM6); +#elif ASSERT_PIN_EXTENDED(PWM6) + pwm_mask &= ~(1 << 6); +#endif + } +#endif +#if ASSERT_PIN(PWM7) + if (pwm_ref > g_io_soft_pwm[7]) + { +#if ASSERT_PIN_IO(PWM7) + mcu_clear_output(PWM7); +#elif ASSERT_PIN_EXTENDED(PWM7) + pwm_mask &= ~(1 << 7); +#endif + } +#endif +#if ASSERT_PIN(PWM8) + if (pwm_ref > g_io_soft_pwm[8]) + { +#if ASSERT_PIN_IO(PWM8) + mcu_clear_output(PWM8); +#elif ASSERT_PIN_EXTENDED(PWM8) + pwm_mask &= ~(1 << 8); +#endif + } +#endif +#if ASSERT_PIN(PWM9) + if (pwm_ref > g_io_soft_pwm[9]) + { +#if ASSERT_PIN_IO(PWM9) + mcu_clear_output(PWM9); +#elif ASSERT_PIN_EXTENDED(PWM9) + pwm_mask &= ~(1 << 9); +#endif + } +#endif +#if ASSERT_PIN(PWM10) + if (pwm_ref > g_io_soft_pwm[10]) + { +#if ASSERT_PIN_IO(PWM10) + mcu_clear_output(PWM10); +#elif ASSERT_PIN_EXTENDED(PWM10) + pwm_mask &= ~(1 << 10); +#endif + } +#endif +#if ASSERT_PIN(PWM11) + if (pwm_ref > g_io_soft_pwm[11]) + { +#if ASSERT_PIN_IO(PWM11) + mcu_clear_output(PWM11); +#elif ASSERT_PIN_EXTENDED(PWM11) + pwm_mask &= ~(1 << 11); +#endif + } +#endif +#if ASSERT_PIN(PWM12) + if (pwm_ref > g_io_soft_pwm[12]) + { +#if ASSERT_PIN_IO(PWM12) + mcu_clear_output(PWM12); +#elif ASSERT_PIN_EXTENDED(PWM12) + pwm_mask &= ~(1 << 12); +#endif + } +#endif +#if ASSERT_PIN(PWM13) + if (pwm_ref > g_io_soft_pwm[13]) + { +#if ASSERT_PIN_IO(PWM13) + mcu_clear_output(PWM13); +#elif ASSERT_PIN_EXTENDED(PWM13) + pwm_mask &= ~(1 << 13); +#endif + } +#endif +#if ASSERT_PIN(PWM14) + if (pwm_ref > g_io_soft_pwm[14]) + { +#if ASSERT_PIN_IO(PWM14) + mcu_clear_output(PWM14); +#elif ASSERT_PIN_EXTENDED(PWM14) + pwm_mask &= ~(1 << 14); +#endif + } +#endif +#if ASSERT_PIN(PWM15) + if (pwm_ref > g_io_soft_pwm[15]) + { +#if ASSERT_PIN_IO(PWM15) + mcu_clear_output(PWM15); +#elif ASSERT_PIN_EXTENDED(PWM15) + pwm_mask &= ~(1 << 15); +#endif + } +#endif + } + else + { + pwm_counter = 0; +#if ASSERT_PIN_IO(PWM0) + if (g_io_soft_pwm[0]) + { + mcu_set_output(PWM0); + } +#endif +#if ASSERT_PIN_IO(PWM1) + if (g_io_soft_pwm[1]) + { + mcu_set_output(PWM1); + } +#endif +#if ASSERT_PIN_IO(PWM2) + if (g_io_soft_pwm[2]) + { + mcu_set_output(PWM2); + } +#endif +#if ASSERT_PIN_IO(PWM3) + if (g_io_soft_pwm[3]) + { + mcu_set_output(PWM3); + } +#endif +#if ASSERT_PIN_IO(PWM4) + if (g_io_soft_pwm[4]) + { + mcu_set_output(PWM4); + } +#endif +#if ASSERT_PIN_IO(PWM5) + if (g_io_soft_pwm[5]) + { + mcu_set_output(PWM5); + } +#endif +#if ASSERT_PIN_IO(PWM6) + if (g_io_soft_pwm[6]) + { + mcu_set_output(PWM6); + } +#endif +#if ASSERT_PIN_IO(PWM7) + if (g_io_soft_pwm[7]) + { + mcu_set_output(PWM7); + } +#endif +#if ASSERT_PIN_IO(PWM8) + if (g_io_soft_pwm[8]) + { + mcu_set_output(PWM8); + } +#endif +#if ASSERT_PIN_IO(PWM9) + if (g_io_soft_pwm[9]) + { + mcu_set_output(PWM9); + } +#endif +#if ASSERT_PIN_IO(PWM10) + if (g_io_soft_pwm[10]) + { + mcu_set_output(PWM10); + } +#endif +#if ASSERT_PIN_IO(PWM11) + if (g_io_soft_pwm[11]) + { + mcu_set_output(PWM11); + } +#endif +#if ASSERT_PIN_IO(PWM12) + if (g_io_soft_pwm[12]) + { + mcu_set_output(PWM12); + } +#endif +#if ASSERT_PIN_IO(PWM13) + if (g_io_soft_pwm[13]) + { + mcu_set_output(PWM13); + } +#endif +#if ASSERT_PIN_IO(PWM14) + if (g_io_soft_pwm[14]) + { + mcu_set_output(PWM14); + } +#endif +#if ASSERT_PIN_IO(PWM15) + if (g_io_soft_pwm[15]) + { + mcu_set_output(PWM15); + } +#endif + } + +#ifdef IC74HC595_HAS_PWMS + if (pwm_mask_last != pwm_mask) + { + ic74hc595_set_pwms(pwm_mask); + pwm_mask_last = pwm_mask; + } +#endif +} +#endif + +void io_set_analogvalue(uint8_t pin, uint8_t value) { #if (defined(IC74HC595_HAS_PWMS) || defined(IC74HC595_HAS_SERVOS)) if (pin > 127) { pin = ~pin; - mcu_set_pwm(pin, value); + io_set_pwm(pin, value); return; } #endif @@ -762,82 +1149,82 @@ void io_set_pwm(uint8_t pin, uint8_t value) { #if ASSERT_PIN(PWM0) case PWM0: - mcu_set_pwm(PWM0, value); + io_set_pwm(PWM0, value); break; #endif #if ASSERT_PIN(PWM1) case PWM1: - mcu_set_pwm(PWM1, value); + io_set_pwm(PWM1, value); break; #endif #if ASSERT_PIN(PWM2) case PWM2: - mcu_set_pwm(PWM2, value); + io_set_pwm(PWM2, value); break; #endif #if ASSERT_PIN(PWM3) case PWM3: - mcu_set_pwm(PWM3, value); + io_set_pwm(PWM3, value); break; #endif #if ASSERT_PIN(PWM4) case PWM4: - mcu_set_pwm(PWM4, value); + io_set_pwm(PWM4, value); break; #endif #if ASSERT_PIN(PWM5) case PWM5: - mcu_set_pwm(PWM5, value); + io_set_pwm(PWM5, value); break; #endif #if ASSERT_PIN(PWM6) case PWM6: - mcu_set_pwm(PWM6, value); + io_set_pwm(PWM6, value); break; #endif #if ASSERT_PIN(PWM7) case PWM7: - mcu_set_pwm(PWM7, value); + io_set_pwm(PWM7, value); break; #endif #if ASSERT_PIN(PWM8) case PWM8: - mcu_set_pwm(PWM8, value); + io_set_pwm(PWM8, value); break; #endif #if ASSERT_PIN(PWM9) case PWM9: - mcu_set_pwm(PWM9, value); + io_set_pwm(PWM9, value); break; #endif #if ASSERT_PIN(PWM10) case PWM10: - mcu_set_pwm(PWM10, value); + io_set_pwm(PWM10, value); break; #endif #if ASSERT_PIN(PWM11) case PWM11: - mcu_set_pwm(PWM11, value); + io_set_pwm(PWM11, value); break; #endif #if ASSERT_PIN(PWM12) case PWM12: - mcu_set_pwm(PWM12, value); + io_set_pwm(PWM12, value); break; #endif #if ASSERT_PIN(PWM13) case PWM13: - mcu_set_pwm(PWM13, value); + io_set_pwm(PWM13, value); break; #endif #if ASSERT_PIN(PWM14) case PWM14: - mcu_set_pwm(PWM14, value); + io_set_pwm(PWM14, value); break; #endif #if ASSERT_PIN(PWM15) case PWM15: - mcu_set_pwm(PWM15, value); + io_set_pwm(PWM15, value); break; #endif #if ASSERT_PIN(SERVO0) @@ -873,182 +1260,284 @@ void io_set_pwm(uint8_t pin, uint8_t value) } } -void io_set_output(uint8_t pin, bool state) +void io_set_pinvalue(uint8_t pin, uint8_t value) { // #ifdef ENABLE_IO_MODULES // set_output_args_t output_arg = {.pin = pin, .state = state}; // EVENT_INVOKE(set_output, &output_arg); // #endif -#ifdef IC74HC595_HAS_DOUTS - if (((int8_t)pin) < 0) - { - pin = -(((int8_t)pin) + 1); - ic74hc595_set_output(pin, state); - return; - } -#endif - if (state) + if (value) { switch (pin) { +#if ASSERT_PIN(PWM0) + case PWM0: + io_set_pwm(PWM0, value); + break; +#endif +#if ASSERT_PIN(PWM1) + case PWM1: + io_set_pwm(PWM1, value); + break; +#endif +#if ASSERT_PIN(PWM2) + case PWM2: + io_set_pwm(PWM2, value); + break; +#endif +#if ASSERT_PIN(PWM3) + case PWM3: + io_set_pwm(PWM3, value); + break; +#endif +#if ASSERT_PIN(PWM4) + case PWM4: + io_set_pwm(PWM4, value); + break; +#endif +#if ASSERT_PIN(PWM5) + case PWM5: + io_set_pwm(PWM5, value); + break; +#endif +#if ASSERT_PIN(PWM6) + case PWM6: + io_set_pwm(PWM6, value); + break; +#endif +#if ASSERT_PIN(PWM7) + case PWM7: + io_set_pwm(PWM7, value); + break; +#endif +#if ASSERT_PIN(PWM8) + case PWM8: + io_set_pwm(PWM8, value); + break; +#endif +#if ASSERT_PIN(PWM9) + case PWM9: + io_set_pwm(PWM9, value); + break; +#endif +#if ASSERT_PIN(PWM10) + case PWM10: + io_set_pwm(PWM10, value); + break; +#endif +#if ASSERT_PIN(PWM11) + case PWM11: + io_set_pwm(PWM11, value); + break; +#endif +#if ASSERT_PIN(PWM12) + case PWM12: + io_set_pwm(PWM12, value); + break; +#endif +#if ASSERT_PIN(PWM13) + case PWM13: + io_set_pwm(PWM13, value); + break; +#endif +#if ASSERT_PIN(PWM14) + case PWM14: + io_set_pwm(PWM14, value); + break; +#endif +#if ASSERT_PIN(PWM15) + case PWM15: + io_set_pwm(PWM15, value); + break; +#endif +#if ASSERT_PIN(SERVO0) + case SERVO0: + io_set_pwm(SERVO0, value); + break; +#endif +#if ASSERT_PIN(SERVO1) + case SERVO1: + io_set_pwm(SERVO1, value); + break; +#endif +#if ASSERT_PIN(SERVO2) + case SERVO2: + io_set_pwm(SERVO2, value); + break; +#endif +#if ASSERT_PIN(SERVO3) + case SERVO3: + io_set_pwm(SERVO3, value); + break; +#endif +#if ASSERT_PIN(SERVO4) + case SERVO4: + io_set_pwm(SERVO4, value); + break; +#endif +#if ASSERT_PIN(SERVO5) + case SERVO5: + io_set_pwm(SERVO5, value); + break; +#endif #if ASSERT_PIN(DOUT0) case DOUT0: - mcu_set_output(DOUT0); + io_set_output(DOUT0); break; #endif #if ASSERT_PIN(DOUT1) case DOUT1: - mcu_set_output(DOUT1); + io_set_output(DOUT1); break; #endif #if ASSERT_PIN(DOUT2) case DOUT2: - mcu_set_output(DOUT2); + io_set_output(DOUT2); break; #endif #if ASSERT_PIN(DOUT3) case DOUT3: - mcu_set_output(DOUT3); + io_set_output(DOUT3); break; #endif #if ASSERT_PIN(DOUT4) case DOUT4: - mcu_set_output(DOUT4); + io_set_output(DOUT4); break; #endif #if ASSERT_PIN(DOUT5) case DOUT5: - mcu_set_output(DOUT5); + io_set_output(DOUT5); break; #endif #if ASSERT_PIN(DOUT6) case DOUT6: - mcu_set_output(DOUT6); + io_set_output(DOUT6); break; #endif #if ASSERT_PIN(DOUT7) case DOUT7: - mcu_set_output(DOUT7); + io_set_output(DOUT7); break; #endif #if ASSERT_PIN(DOUT8) case DOUT8: - mcu_set_output(DOUT8); + io_set_output(DOUT8); break; #endif #if ASSERT_PIN(DOUT9) case DOUT9: - mcu_set_output(DOUT9); + io_set_output(DOUT9); break; #endif #if ASSERT_PIN(DOUT10) case DOUT10: - mcu_set_output(DOUT10); + io_set_output(DOUT10); break; #endif #if ASSERT_PIN(DOUT11) case DOUT11: - mcu_set_output(DOUT11); + io_set_output(DOUT11); break; #endif #if ASSERT_PIN(DOUT12) case DOUT12: - mcu_set_output(DOUT12); + io_set_output(DOUT12); break; #endif #if ASSERT_PIN(DOUT13) case DOUT13: - mcu_set_output(DOUT13); + io_set_output(DOUT13); break; #endif #if ASSERT_PIN(DOUT14) case DOUT14: - mcu_set_output(DOUT14); + io_set_output(DOUT14); break; #endif #if ASSERT_PIN(DOUT15) case DOUT15: - mcu_set_output(DOUT15); + io_set_output(DOUT15); break; #endif #if ASSERT_PIN(DOUT16) case DOUT16: - mcu_set_output(DOUT16); + io_set_output(DOUT16); break; #endif #if ASSERT_PIN(DOUT17) case DOUT17: - mcu_set_output(DOUT17); + io_set_output(DOUT17); break; #endif #if ASSERT_PIN(DOUT18) case DOUT18: - mcu_set_output(DOUT18); + io_set_output(DOUT18); break; #endif #if ASSERT_PIN(DOUT19) case DOUT19: - mcu_set_output(DOUT19); + io_set_output(DOUT19); break; #endif #if ASSERT_PIN(DOUT20) case DOUT20: - mcu_set_output(DOUT20); + io_set_output(DOUT20); break; #endif #if ASSERT_PIN(DOUT21) case DOUT21: - mcu_set_output(DOUT21); + io_set_output(DOUT21); break; #endif #if ASSERT_PIN(DOUT22) case DOUT22: - mcu_set_output(DOUT22); + io_set_output(DOUT22); break; #endif #if ASSERT_PIN(DOUT23) case DOUT23: - mcu_set_output(DOUT23); + io_set_output(DOUT23); break; #endif #if ASSERT_PIN(DOUT24) case DOUT24: - mcu_set_output(DOUT24); + io_set_output(DOUT24); break; #endif #if ASSERT_PIN(DOUT25) case DOUT25: - mcu_set_output(DOUT25); + io_set_output(DOUT25); break; #endif #if ASSERT_PIN(DOUT26) case DOUT26: - mcu_set_output(DOUT26); + io_set_output(DOUT26); break; #endif #if ASSERT_PIN(DOUT27) case DOUT27: - mcu_set_output(DOUT27); + io_set_output(DOUT27); break; #endif #if ASSERT_PIN(DOUT28) case DOUT28: - mcu_set_output(DOUT28); + io_set_output(DOUT28); break; #endif #if ASSERT_PIN(DOUT29) case DOUT29: - mcu_set_output(DOUT29); + io_set_output(DOUT29); break; #endif #if ASSERT_PIN(DOUT30) case DOUT30: - mcu_set_output(DOUT30); + io_set_output(DOUT30); break; #endif #if ASSERT_PIN(DOUT31) case DOUT31: - mcu_set_output(DOUT31); + io_set_output(DOUT31); break; #endif } @@ -1057,262 +1546,281 @@ void io_set_output(uint8_t pin, bool state) { switch (pin) { +#if ASSERT_PIN(PWM0) + case PWM0: + io_set_pwm(PWM0, 0); + break; +#endif +#if ASSERT_PIN(PWM1) + case PWM1: + io_set_pwm(PWM1, 0); + break; +#endif +#if ASSERT_PIN(PWM2) + case PWM2: + io_set_pwm(PWM2, 0); + break; +#endif +#if ASSERT_PIN(PWM3) + case PWM3: + io_set_pwm(PWM3, 0); + break; +#endif +#if ASSERT_PIN(PWM4) + case PWM4: + io_set_pwm(PWM4, 0); + break; +#endif +#if ASSERT_PIN(PWM5) + case PWM5: + io_set_pwm(PWM5, 0); + break; +#endif +#if ASSERT_PIN(PWM6) + case PWM6: + io_set_pwm(PWM6, 0); + break; +#endif +#if ASSERT_PIN(PWM7) + case PWM7: + io_set_pwm(PWM7, 0); + break; +#endif +#if ASSERT_PIN(PWM8) + case PWM8: + io_set_pwm(PWM8, 0); + break; +#endif +#if ASSERT_PIN(PWM9) + case PWM9: + io_set_pwm(PWM9, 0); + break; +#endif +#if ASSERT_PIN(PWM10) + case PWM10: + io_set_pwm(PWM10, 0); + break; +#endif +#if ASSERT_PIN(PWM11) + case PWM11: + io_set_pwm(PWM11, 0); + break; +#endif +#if ASSERT_PIN(PWM12) + case PWM12: + io_set_pwm(PWM12, 0); + break; +#endif +#if ASSERT_PIN(PWM13) + case PWM13: + io_set_pwm(PWM13, 0); + break; +#endif +#if ASSERT_PIN(PWM14) + case PWM14: + io_set_pwm(PWM14, 0); + break; +#endif +#if ASSERT_PIN(PWM15) + case PWM15: + io_set_pwm(PWM15, 0); + break; +#endif +#if ASSERT_PIN(SERVO0) + case SERVO0: + io_set_pwm(SERVO0, 0); + break; +#endif +#if ASSERT_PIN(SERVO1) + case SERVO1: + io_set_pwm(SERVO1, 0); + break; +#endif +#if ASSERT_PIN(SERVO2) + case SERVO2: + io_set_pwm(SERVO2, 0); + break; +#endif +#if ASSERT_PIN(SERVO3) + case SERVO3: + io_set_pwm(SERVO3, 0); + break; +#endif +#if ASSERT_PIN(SERVO4) + case SERVO4: + io_set_pwm(SERVO4, 0); + break; +#endif +#if ASSERT_PIN(SERVO5) + case SERVO5: + io_set_pwm(SERVO5, 0); + break; +#endif + #if ASSERT_PIN(DOUT0) case DOUT0: - mcu_clear_output(DOUT0); + io_clear_output(DOUT0); break; #endif #if ASSERT_PIN(DOUT1) case DOUT1: - mcu_clear_output(DOUT1); + io_clear_output(DOUT1); break; #endif #if ASSERT_PIN(DOUT2) case DOUT2: - mcu_clear_output(DOUT2); + io_clear_output(DOUT2); break; #endif #if ASSERT_PIN(DOUT3) case DOUT3: - mcu_clear_output(DOUT3); + io_clear_output(DOUT3); break; #endif #if ASSERT_PIN(DOUT4) case DOUT4: - mcu_clear_output(DOUT4); + io_clear_output(DOUT4); break; #endif #if ASSERT_PIN(DOUT5) case DOUT5: - mcu_clear_output(DOUT5); + io_clear_output(DOUT5); break; #endif #if ASSERT_PIN(DOUT6) case DOUT6: - mcu_clear_output(DOUT6); + io_clear_output(DOUT6); break; #endif #if ASSERT_PIN(DOUT7) case DOUT7: - mcu_clear_output(DOUT7); + io_clear_output(DOUT7); break; #endif #if ASSERT_PIN(DOUT8) case DOUT8: - mcu_clear_output(DOUT8); + io_clear_output(DOUT8); break; #endif #if ASSERT_PIN(DOUT9) case DOUT9: - mcu_clear_output(DOUT9); + io_clear_output(DOUT9); break; #endif #if ASSERT_PIN(DOUT10) case DOUT10: - mcu_clear_output(DOUT10); + io_clear_output(DOUT10); break; #endif #if ASSERT_PIN(DOUT11) case DOUT11: - mcu_clear_output(DOUT11); + io_clear_output(DOUT11); break; #endif #if ASSERT_PIN(DOUT12) case DOUT12: - mcu_clear_output(DOUT12); + io_clear_output(DOUT12); break; #endif #if ASSERT_PIN(DOUT13) case DOUT13: - mcu_clear_output(DOUT13); + io_clear_output(DOUT13); break; #endif #if ASSERT_PIN(DOUT14) case DOUT14: - mcu_clear_output(DOUT14); + io_clear_output(DOUT14); break; #endif #if ASSERT_PIN(DOUT15) case DOUT15: - mcu_clear_output(DOUT15); + io_clear_output(DOUT15); break; #endif #if ASSERT_PIN(DOUT16) case DOUT16: - mcu_clear_output(DOUT16); + io_clear_output(DOUT16); break; #endif #if ASSERT_PIN(DOUT17) case DOUT17: - mcu_clear_output(DOUT17); + io_clear_output(DOUT17); break; #endif #if ASSERT_PIN(DOUT18) case DOUT18: - mcu_clear_output(DOUT18); + io_clear_output(DOUT18); break; #endif #if ASSERT_PIN(DOUT19) case DOUT19: - mcu_clear_output(DOUT19); + io_clear_output(DOUT19); break; #endif #if ASSERT_PIN(DOUT20) case DOUT20: - mcu_clear_output(DOUT20); + io_clear_output(DOUT20); break; #endif #if ASSERT_PIN(DOUT21) case DOUT21: - mcu_clear_output(DOUT21); + io_clear_output(DOUT21); break; #endif #if ASSERT_PIN(DOUT22) case DOUT22: - mcu_clear_output(DOUT22); + io_clear_output(DOUT22); break; #endif #if ASSERT_PIN(DOUT23) case DOUT23: - mcu_clear_output(DOUT23); + io_clear_output(DOUT23); break; #endif #if ASSERT_PIN(DOUT24) case DOUT24: - mcu_clear_output(DOUT24); + io_clear_output(DOUT24); break; #endif #if ASSERT_PIN(DOUT25) case DOUT25: - mcu_clear_output(DOUT25); + io_clear_output(DOUT25); break; #endif #if ASSERT_PIN(DOUT26) case DOUT26: - mcu_clear_output(DOUT26); + io_clear_output(DOUT26); break; #endif #if ASSERT_PIN(DOUT27) case DOUT27: - mcu_clear_output(DOUT27); + io_clear_output(DOUT27); break; #endif #if ASSERT_PIN(DOUT28) case DOUT28: - mcu_clear_output(DOUT28); + io_clear_output(DOUT28); break; #endif #if ASSERT_PIN(DOUT29) case DOUT29: - mcu_clear_output(DOUT29); + io_clear_output(DOUT29); break; #endif #if ASSERT_PIN(DOUT30) case DOUT30: - mcu_clear_output(DOUT30); + io_clear_output(DOUT30); break; #endif #if ASSERT_PIN(DOUT31) case DOUT31: - mcu_clear_output(DOUT31); + io_clear_output(DOUT31); break; #endif } } } - -void io_enable_steppers(uint8_t mask) -{ - // #ifdef ENABLE_IO_MODULES - // EVENT_INVOKE(enable_steppers, &mask); - // #endif - -#ifdef IC74HC595_HAS_STEPS_EN - ic74hc595_enable_steppers(mask); -#endif - -#if ASSERT_PIN(STEP0_EN) - if (mask & 0x01) - { - mcu_set_output(STEP0_EN); - } - else - { - mcu_clear_output(STEP0_EN); - } -#endif -#if ASSERT_PIN(STEP1_EN) - if (mask & 0x02) - { - mcu_set_output(STEP1_EN); - } - else - { - mcu_clear_output(STEP1_EN); - } -#endif -#if ASSERT_PIN(STEP2_EN) - if (mask & 0x04) - { - mcu_set_output(STEP2_EN); - } - else - { - mcu_clear_output(STEP2_EN); - } -#endif -#if ASSERT_PIN(STEP3_EN) - if (mask & 0x08) - { - mcu_set_output(STEP3_EN); - } - else - { - mcu_clear_output(STEP3_EN); - } -#endif -#if ASSERT_PIN(STEP4_EN) - if (mask & 0x10) - { - mcu_set_output(STEP4_EN); - } - else - { - mcu_clear_output(STEP4_EN); - } -#endif -#if ASSERT_PIN(STEP5_EN) - if (mask & 0x20) - { - mcu_set_output(STEP5_EN); - } - else - { - mcu_clear_output(STEP5_EN); - } -#endif -#if ASSERT_PIN(STEP6_EN) - if (mask & 0x40) - { - mcu_set_output(STEP6_EN); - } - else - { - mcu_clear_output(STEP6_EN); - } -#endif -#if ASSERT_PIN(STEP7_EN) - if (mask & 0x80) - { - mcu_set_output(STEP7_EN); - } - else - { - mcu_clear_output(STEP7_EN); - } -#endif -} - +/* uint8_t io_get_analog(uint8_t pin) { switch (pin) @@ -1384,359 +1892,359 @@ uint8_t io_get_analog(uint8_t pin) } return 0; -} +}*/ int16_t io_get_pinvalue(uint8_t pin) { switch (pin) { #if ASSERT_PIN(STEP0) - case STEP0: - return (mcu_get_output(STEP0) != 0); + case ABS(STEP0): + return (io_get_output(STEP0) != 0); #endif #if ASSERT_PIN(STEP1) case STEP1: - return (mcu_get_output(STEP1) != 0); + return (io_get_output(STEP1) != 0); #endif #if ASSERT_PIN(STEP2) case STEP2: - return (mcu_get_output(STEP2) != 0); + return (io_get_output(STEP2) != 0); #endif #if ASSERT_PIN(STEP3) case STEP3: - return (mcu_get_output(STEP3) != 0); + return (io_get_output(STEP3) != 0); #endif #if ASSERT_PIN(STEP4) case STEP4: - return (mcu_get_output(STEP4) != 0); + return (io_get_output(STEP4) != 0); #endif #if ASSERT_PIN(STEP5) case STEP5: - return (mcu_get_output(STEP5) != 0); + return (io_get_output(STEP5) != 0); #endif #if ASSERT_PIN(STEP6) case STEP6: - return (mcu_get_output(STEP6) != 0); + return (io_get_output(STEP6) != 0); #endif #if ASSERT_PIN(STEP7) case STEP7: - return (mcu_get_output(STEP7) != 0); + return (io_get_output(STEP7) != 0); #endif #if ASSERT_PIN(DIR0) case DIR0: - return (mcu_get_output(DIR0) != 0); + return (io_get_output(DIR0) != 0); #endif #if ASSERT_PIN(DIR1) case DIR1: - return (mcu_get_output(DIR1) != 0); + return (io_get_output(DIR1) != 0); #endif #if ASSERT_PIN(DIR2) case DIR2: - return (mcu_get_output(DIR2) != 0); + return (io_get_output(DIR2) != 0); #endif #if ASSERT_PIN(DIR3) case DIR3: - return (mcu_get_output(DIR3) != 0); + return (io_get_output(DIR3) != 0); #endif #if ASSERT_PIN(DIR4) case DIR4: - return (mcu_get_output(DIR4) != 0); + return (io_get_output(DIR4) != 0); #endif #if ASSERT_PIN(DIR5) case DIR5: - return (mcu_get_output(DIR5) != 0); + return (io_get_output(DIR5) != 0); #endif #if ASSERT_PIN(DIR6) case DIR6: - return (mcu_get_output(DIR6) != 0); + return (io_get_output(DIR6) != 0); #endif #if ASSERT_PIN(DIR7) case DIR7: - return (mcu_get_output(DIR7) != 0); + return (io_get_output(DIR7) != 0); #endif #if ASSERT_PIN(STEP0_EN) case STEP0_EN: - return (mcu_get_output(STEP0_EN) != 0); + return (io_get_output(STEP0_EN) != 0); #endif #if ASSERT_PIN(STEP1_EN) case STEP1_EN: - return (mcu_get_output(STEP1_EN) != 0); + return (io_get_output(STEP1_EN) != 0); #endif #if ASSERT_PIN(STEP2_EN) case STEP2_EN: - return (mcu_get_output(STEP2_EN) != 0); + return (io_get_output(STEP2_EN) != 0); #endif #if ASSERT_PIN(STEP3_EN) case STEP3_EN: - return (mcu_get_output(STEP3_EN) != 0); + return (io_get_output(STEP3_EN) != 0); #endif #if ASSERT_PIN(STEP4_EN) case STEP4_EN: - return (mcu_get_output(STEP4_EN) != 0); + return (io_get_output(STEP4_EN) != 0); #endif #if ASSERT_PIN(STEP5_EN) case STEP5_EN: - return (mcu_get_output(STEP5_EN) != 0); + return (io_get_output(STEP5_EN) != 0); #endif #if ASSERT_PIN(STEP6_EN) case STEP6_EN: - return (mcu_get_output(STEP6_EN) != 0); + return (io_get_output(STEP6_EN) != 0); #endif #if ASSERT_PIN(STEP7_EN) case STEP7_EN: - return (mcu_get_output(STEP7_EN) != 0); + return (io_get_output(STEP7_EN) != 0); #endif #if ASSERT_PIN(PWM0) case PWM0: - return mcu_get_pwm(PWM0); + return io_get_pwm(PWM0); #endif #if ASSERT_PIN(PWM1) case PWM1: - return mcu_get_pwm(PWM1); + return io_get_pwm(PWM1); #endif #if ASSERT_PIN(PWM2) case PWM2: - return mcu_get_pwm(PWM2); + return io_get_pwm(PWM2); #endif #if ASSERT_PIN(PWM3) case PWM3: - return mcu_get_pwm(PWM3); + return io_get_pwm(PWM3); #endif #if ASSERT_PIN(PWM4) case PWM4: - return mcu_get_pwm(PWM4); + return io_get_pwm(PWM4); #endif #if ASSERT_PIN(PWM5) case PWM5: - return mcu_get_pwm(PWM5); + return io_get_pwm(PWM5); #endif #if ASSERT_PIN(PWM6) case PWM6: - return mcu_get_pwm(PWM6); + return io_get_pwm(PWM6); #endif #if ASSERT_PIN(PWM7) case PWM7: - return mcu_get_pwm(PWM7); + return io_get_pwm(PWM7); #endif #if ASSERT_PIN(PWM8) case PWM8: - return mcu_get_pwm(PWM8); + return io_get_pwm(PWM8); #endif #if ASSERT_PIN(PWM9) case PWM9: - return mcu_get_pwm(PWM9); + return io_get_pwm(PWM9); #endif #if ASSERT_PIN(PWM10) case PWM10: - return mcu_get_pwm(PWM10); + return io_get_pwm(PWM10); #endif #if ASSERT_PIN(PWM11) case PWM11: - return mcu_get_pwm(PWM11); + return io_get_pwm(PWM11); #endif #if ASSERT_PIN(PWM12) case PWM12: - return mcu_get_pwm(PWM12); + return io_get_pwm(PWM12); #endif #if ASSERT_PIN(PWM13) case PWM13: - return mcu_get_pwm(PWM13); + return io_get_pwm(PWM13); #endif #if ASSERT_PIN(PWM14) case PWM14: - return mcu_get_pwm(PWM14); + return io_get_pwm(PWM14); #endif #if ASSERT_PIN(PWM15) case PWM15: - return mcu_get_pwm(PWM15); + return io_get_pwm(PWM15); #endif #if ASSERT_PIN(DOUT0) case DOUT0: - return (mcu_get_output(DOUT0) != 0); + return (io_get_output(DOUT0) != 0); #endif #if ASSERT_PIN(DOUT1) case DOUT1: - return (mcu_get_output(DOUT1) != 0); + return (io_get_output(DOUT1) != 0); #endif #if ASSERT_PIN(DOUT2) case DOUT2: - return (mcu_get_output(DOUT2) != 0); + return (io_get_output(DOUT2) != 0); #endif #if ASSERT_PIN(DOUT3) case DOUT3: - return (mcu_get_output(DOUT3) != 0); + return (io_get_output(DOUT3) != 0); #endif #if ASSERT_PIN(DOUT4) case DOUT4: - return (mcu_get_output(DOUT4) != 0); + return (io_get_output(DOUT4) != 0); #endif #if ASSERT_PIN(DOUT5) case DOUT5: - return (mcu_get_output(DOUT5) != 0); + return (io_get_output(DOUT5) != 0); #endif #if ASSERT_PIN(DOUT6) case DOUT6: - return (mcu_get_output(DOUT6) != 0); + return (io_get_output(DOUT6) != 0); #endif #if ASSERT_PIN(DOUT7) case DOUT7: - return (mcu_get_output(DOUT7) != 0); + return (io_get_output(DOUT7) != 0); #endif #if ASSERT_PIN(DOUT8) case DOUT8: - return (mcu_get_output(DOUT8) != 0); + return (io_get_output(DOUT8) != 0); #endif #if ASSERT_PIN(DOUT9) case DOUT9: - return (mcu_get_output(DOUT9) != 0); + return (io_get_output(DOUT9) != 0); #endif #if ASSERT_PIN(DOUT10) case DOUT10: - return (mcu_get_output(DOUT10) != 0); + return (io_get_output(DOUT10) != 0); #endif #if ASSERT_PIN(DOUT11) case DOUT11: - return (mcu_get_output(DOUT11) != 0); + return (io_get_output(DOUT11) != 0); #endif #if ASSERT_PIN(DOUT12) case DOUT12: - return (mcu_get_output(DOUT12) != 0); + return (io_get_output(DOUT12) != 0); #endif #if ASSERT_PIN(DOUT13) case DOUT13: - return (mcu_get_output(DOUT13) != 0); + return (io_get_output(DOUT13) != 0); #endif #if ASSERT_PIN(DOUT14) case DOUT14: - return (mcu_get_output(DOUT14) != 0); + return (io_get_output(DOUT14) != 0); #endif #if ASSERT_PIN(DOUT15) case DOUT15: - return (mcu_get_output(DOUT15) != 0); + return (io_get_output(DOUT15) != 0); #endif #if ASSERT_PIN(DOUT16) case DOUT16: - return (mcu_get_output(DOUT16) != 0); + return (io_get_output(DOUT16) != 0); #endif #if ASSERT_PIN(DOUT17) case DOUT17: - return (mcu_get_output(DOUT17) != 0); + return (io_get_output(DOUT17) != 0); #endif #if ASSERT_PIN(DOUT18) case DOUT18: - return (mcu_get_output(DOUT18) != 0); + return (io_get_output(DOUT18) != 0); #endif #if ASSERT_PIN(DOUT19) case DOUT19: - return (mcu_get_output(DOUT19) != 0); + return (io_get_output(DOUT19) != 0); #endif #if ASSERT_PIN(DOUT20) case DOUT20: - return (mcu_get_output(DOUT20) != 0); + return (io_get_output(DOUT20) != 0); #endif #if ASSERT_PIN(DOUT21) case DOUT21: - return (mcu_get_output(DOUT21) != 0); + return (io_get_output(DOUT21) != 0); #endif #if ASSERT_PIN(DOUT22) case DOUT22: - return (mcu_get_output(DOUT22) != 0); + return (io_get_output(DOUT22) != 0); #endif #if ASSERT_PIN(DOUT23) case DOUT23: - return (mcu_get_output(DOUT23) != 0); + return (io_get_output(DOUT23) != 0); #endif #if ASSERT_PIN(DOUT24) case DOUT24: - return (mcu_get_output(DOUT24) != 0); + return (io_get_output(DOUT24) != 0); #endif #if ASSERT_PIN(DOUT25) case DOUT25: - return (mcu_get_output(DOUT25) != 0); + return (io_get_output(DOUT25) != 0); #endif #if ASSERT_PIN(DOUT26) case DOUT26: - return (mcu_get_output(DOUT26) != 0); + return (io_get_output(DOUT26) != 0); #endif #if ASSERT_PIN(DOUT27) case DOUT27: - return (mcu_get_output(DOUT27) != 0); + return (io_get_output(DOUT27) != 0); #endif #if ASSERT_PIN(DOUT28) case DOUT28: - return (mcu_get_output(DOUT28) != 0); + return (io_get_output(DOUT28) != 0); #endif #if ASSERT_PIN(DOUT29) case DOUT29: - return (mcu_get_output(DOUT29) != 0); + return (io_get_output(DOUT29) != 0); #endif #if ASSERT_PIN(DOUT30) case DOUT30: - return (mcu_get_output(DOUT30) != 0); + return (io_get_output(DOUT30) != 0); #endif #if ASSERT_PIN(DOUT31) case DOUT31: - return (mcu_get_output(DOUT31) != 0); + return (io_get_output(DOUT31) != 0); #endif #if ASSERT_PIN(LIMIT_X) case LIMIT_X: - return (mcu_get_input(LIMIT_X) != 0); + return (io_get_input(LIMIT_X) != 0); #endif #if ASSERT_PIN(LIMIT_Y) case LIMIT_Y: - return (mcu_get_input(LIMIT_Y) != 0); + return (io_get_input(LIMIT_Y) != 0); #endif #if ASSERT_PIN(LIMIT_Z) case LIMIT_Z: - return (mcu_get_input(LIMIT_Z) != 0); + return (io_get_input(LIMIT_Z) != 0); #endif #if ASSERT_PIN(LIMIT_X2) case LIMIT_X2: - return (mcu_get_input(LIMIT_X2) != 0); + return (io_get_input(LIMIT_X2) != 0); #endif #if ASSERT_PIN(LIMIT_Y2) case LIMIT_Y2: - return (mcu_get_input(LIMIT_Y2) != 0); + return (io_get_input(LIMIT_Y2) != 0); #endif #if ASSERT_PIN(LIMIT_Z2) case LIMIT_Z2: - return (mcu_get_input(LIMIT_Z2) != 0); + return (io_get_input(LIMIT_Z2) != 0); #endif #if ASSERT_PIN(LIMIT_A) case LIMIT_A: - return (mcu_get_input(LIMIT_A) != 0); + return (io_get_input(LIMIT_A) != 0); #endif #if ASSERT_PIN(LIMIT_B) case LIMIT_B: - return (mcu_get_input(LIMIT_B) != 0); + return (io_get_input(LIMIT_B) != 0); #endif #if ASSERT_PIN(LIMIT_C) case LIMIT_C: - return (mcu_get_input(LIMIT_C) != 0); + return (io_get_input(LIMIT_C) != 0); #endif #if ASSERT_PIN(PROBE) case PROBE: - return (mcu_get_input(PROBE) != 0); + return (io_get_input(PROBE) != 0); #endif #if ASSERT_PIN(ESTOP) case ESTOP: #ifndef INVERT_EMERGENCY_STOP - return (mcu_get_input(ESTOP) != 0); + return (io_get_input(ESTOP) != 0); #else - return (mcu_get_input(ESTOP) == 0); + return (io_get_input(ESTOP) == 0); #endif #endif #if ASSERT_PIN(SAFETY_DOOR) case SAFETY_DOOR: - return (mcu_get_input(SAFETY_DOOR) != 0); + return (io_get_input(SAFETY_DOOR) != 0); #endif #if ASSERT_PIN(FHOLD) case FHOLD: - return (mcu_get_input(FHOLD) != 0); + return (io_get_input(FHOLD) != 0); #endif #if ASSERT_PIN(CS_RES) case CS_RES: - return (mcu_get_input(CS_RES) != 0); + return (io_get_input(CS_RES) != 0); #endif #if ASSERT_PIN(ANALOG0) case ANALOG0: @@ -1804,131 +2312,131 @@ int16_t io_get_pinvalue(uint8_t pin) #endif #if ASSERT_PIN(DIN0) case DIN0: - return (mcu_get_input(DIN0) != 0); + return (io_get_input(DIN0) != 0); #endif #if ASSERT_PIN(DIN1) case DIN1: - return (mcu_get_input(DIN1) != 0); + return (io_get_input(DIN1) != 0); #endif #if ASSERT_PIN(DIN2) case DIN2: - return (mcu_get_input(DIN2) != 0); + return (io_get_input(DIN2) != 0); #endif #if ASSERT_PIN(DIN3) case DIN3: - return (mcu_get_input(DIN3) != 0); + return (io_get_input(DIN3) != 0); #endif #if ASSERT_PIN(DIN4) case DIN4: - return (mcu_get_input(DIN4) != 0); + return (io_get_input(DIN4) != 0); #endif #if ASSERT_PIN(DIN5) case DIN5: - return (mcu_get_input(DIN5) != 0); + return (io_get_input(DIN5) != 0); #endif #if ASSERT_PIN(DIN6) case DIN6: - return (mcu_get_input(DIN6) != 0); + return (io_get_input(DIN6) != 0); #endif #if ASSERT_PIN(DIN7) case DIN7: - return (mcu_get_input(DIN7) != 0); + return (io_get_input(DIN7) != 0); #endif #if ASSERT_PIN(DIN8) case DIN8: - return (mcu_get_input(DIN8) != 0); + return (io_get_input(DIN8) != 0); #endif #if ASSERT_PIN(DIN9) case DIN9: - return (mcu_get_input(DIN9) != 0); + return (io_get_input(DIN9) != 0); #endif #if ASSERT_PIN(DIN10) case DIN10: - return (mcu_get_input(DIN10) != 0); + return (io_get_input(DIN10) != 0); #endif #if ASSERT_PIN(DIN11) case DIN11: - return (mcu_get_input(DIN11) != 0); + return (io_get_input(DIN11) != 0); #endif #if ASSERT_PIN(DIN12) case DIN12: - return (mcu_get_input(DIN12) != 0); + return (io_get_input(DIN12) != 0); #endif #if ASSERT_PIN(DIN13) case DIN13: - return (mcu_get_input(DIN13) != 0); + return (io_get_input(DIN13) != 0); #endif #if ASSERT_PIN(DIN14) case DIN14: - return (mcu_get_input(DIN14) != 0); + return (io_get_input(DIN14) != 0); #endif #if ASSERT_PIN(DIN15) case DIN15: - return (mcu_get_input(DIN15) != 0); + return (io_get_input(DIN15) != 0); #endif #if ASSERT_PIN(DIN16) case DIN16: - return (mcu_get_input(DIN16) != 0); + return (io_get_input(DIN16) != 0); #endif #if ASSERT_PIN(DIN17) case DIN17: - return (mcu_get_input(DIN17) != 0); + return (io_get_input(DIN17) != 0); #endif #if ASSERT_PIN(DIN18) case DIN18: - return (mcu_get_input(DIN18) != 0); + return (io_get_input(DIN18) != 0); #endif #if ASSERT_PIN(DIN19) case DIN19: - return (mcu_get_input(DIN19) != 0); + return (io_get_input(DIN19) != 0); #endif #if ASSERT_PIN(DIN20) case DIN20: - return (mcu_get_input(DIN20) != 0); + return (io_get_input(DIN20) != 0); #endif #if ASSERT_PIN(DIN21) case DIN21: - return (mcu_get_input(DIN21) != 0); + return (io_get_input(DIN21) != 0); #endif #if ASSERT_PIN(DIN22) case DIN22: - return (mcu_get_input(DIN22) != 0); + return (io_get_input(DIN22) != 0); #endif #if ASSERT_PIN(DIN23) case DIN23: - return (mcu_get_input(DIN23) != 0); + return (io_get_input(DIN23) != 0); #endif #if ASSERT_PIN(DIN24) case DIN24: - return (mcu_get_input(DIN24) != 0); + return (io_get_input(DIN24) != 0); #endif #if ASSERT_PIN(DIN25) case DIN25: - return (mcu_get_input(DIN25) != 0); + return (io_get_input(DIN25) != 0); #endif #if ASSERT_PIN(DIN26) case DIN26: - return (mcu_get_input(DIN26) != 0); + return (io_get_input(DIN26) != 0); #endif #if ASSERT_PIN(DIN27) case DIN27: - return (mcu_get_input(DIN27) != 0); + return (io_get_input(DIN27) != 0); #endif #if ASSERT_PIN(DIN28) case DIN28: - return (mcu_get_input(DIN28) != 0); + return (io_get_input(DIN28) != 0); #endif #if ASSERT_PIN(DIN29) case DIN29: - return (mcu_get_input(DIN29) != 0); + return (io_get_input(DIN29) != 0); #endif #if ASSERT_PIN(DIN30) case DIN30: - return (mcu_get_input(DIN30) != 0); + return (io_get_input(DIN30) != 0); #endif #if ASSERT_PIN(DIN31) case DIN31: - return (mcu_get_input(DIN31) != 0); + return (io_get_input(DIN31) != 0); #endif #if ASSERT_PIN(SERVO0) case SERVO0: diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index 6574a1c46..55b7242c5 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -31,9 +31,37 @@ extern "C" #endif #include "../module.h" +#include "../modules/ic74hc595.h" +#include "../hal/io_hal.h" #include #include +/** + * IO CONTROL<-> MCU HAL + * + **/ +#define io_config_input(pin) io_hal_config_input(pin) +#define io_config_pullup(pin) io_hal_config_pullup(pin) +#define io_get_input(pin) io_hal_get_input(pin) +#define io_config_analog(pin) io_hal_config_analog(pin) +#define io_get_analog(pin) io_hal_get_analog(pin) + +#define io_config_output(pin) io_hal_config_output(pin) +#define io_set_output(pin) io_hal_set_output(pin) +#define io_clear_output(pin) io_hal_clear_output(pin) +#define io_toggle_output(pin) io_hal_toggle_output(pin) +#define io_get_output(pin) io_hal_get_output(pin) +#define io_config_pwm(pin, freq) io_hal_config_pwm(pin, freq) +#define io_set_pwm(pin, value) io_hal_set_pwm(pin, value) +#define io_get_pwm(pin) io_hal_get_pwm(pin) + +#if defined(MCU_HAS_SOFT_PWM_TIMER) || defined(IC74HC595_HAS_PWMS) + extern uint8_t g_io_soft_pwm[16]; + extern uint8_t g_soft_pwm_res; +#define io_set_soft_pwm(pin, value) ({ g_io_soft_pwm[pin - PWM_PINS_OFFSET] = (0xFF & value); }) + void io_soft_pwm_update(void); +#endif + // inputs void io_lock_limits(uint8_t limitmask); void io_invert_limits(uint8_t limitmask); @@ -44,18 +72,15 @@ extern "C" void io_disable_probe(void); bool io_get_probe(void); - uint8_t io_get_analog(uint8_t pin); - // outputs void io_set_steps(uint8_t mask); void io_toggle_steps(uint8_t mask); void io_set_dirs(uint8_t mask); - void io_set_pwm(uint8_t pin, uint8_t value); - void io_set_output(uint8_t pin, bool state); - void io_enable_steppers(uint8_t mask); + // all purpose functions + void io_set_pinvalue(uint8_t pin, uint8_t value); int16_t io_get_pinvalue(uint8_t pin); #ifdef ENABLE_IO_MODULES @@ -65,26 +90,26 @@ extern "C" DECL_EVENT_HANDLER(probe_enable); // event_probe_disable_handler DECL_EVENT_HANDLER(probe_disable); - // // event_set_steps_handler - // DECL_EVENT_HANDLER(set_steps); - // // event_toggle_steps_handler - // DECL_EVENT_HANDLER(toggle_steps); - // // event_set_dirs_handler - // DECL_EVENT_HANDLER(set_dirs); - // // event_enable_steppers_handler - // DECL_EVENT_HANDLER(enable_steppers); - // typedef struct set_output_args_ - // { - // uint8_t pin; - // bool state; - // } set_output_args_t; - // // event_set_output_handler - // DECL_EVENT_HANDLER(set_output); +// // event_set_steps_handler +// DECL_EVENT_HANDLER(set_steps); +// // event_toggle_steps_handler +// DECL_EVENT_HANDLER(toggle_steps); +// // event_set_dirs_handler +// DECL_EVENT_HANDLER(set_dirs); +// // event_enable_steppers_handler +// DECL_EVENT_HANDLER(enable_steppers); +// typedef struct set_output_args_ +// { +// uint8_t pin; +// bool state; +// } set_output_args_t; +// // event_set_output_handler +// DECL_EVENT_HANDLER(set_output); #endif #ifdef ENABLE_IO_ALARM_DEBUG -extern uint8_t io_alarm_limits; -extern uint8_t io_alarm_controls; + extern uint8_t io_alarm_limits; + extern uint8_t io_alarm_controls; #endif #ifdef __cplusplus diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h new file mode 100644 index 000000000..fb337e761 --- /dev/null +++ b/uCNC/src/hal/io_hal.h @@ -0,0 +1,4406 @@ + +#ifndef IO_HAL_H +#define IO_HAL_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +/*IO HAL*/ +#if ASSERT_PIN_IO(1) +#define io1_config_output mcu_config_output(1) +#define io1_set_output mcu_set_output(1) +#define io1_clear_output mcu_clear_output(1) +#define io1_toggle_output mcu_toggle_output(1) +#define io1_get_output mcu_get_output(1) +#define io1_config_input mcu_config_input(1) +#define io1_config_pullup mcu_config_pullup(1) +#define io1_get_input mcu_get_input(1) +#elif ASSERT_PIN_EXTENDED(1) +#define io1_config_output +#define io1_set_output ic74hc595_set_pin(1);ic74hc595_shift_io_pins() +#define io1_clear_output ic74hc595_clear_pin(1);ic74hc595_shift_io_pins() +#define io1_toggle_output ic74hc595_toggle_pin(1);ic74hc595_shift_io_pins() +#define io1_get_output ic74hc595_get_pin(1) +#define io1_config_input +#define io1_config_pullup +#define io1_get_input 0 +#else +#define io1_config_output +#define io1_set_output +#define io1_clear_output +#define io1_toggle_output +#define io1_get_output 0 +#define io1_config_input +#define io1_config_pullup +#define io1_get_input 0 +#endif +#if ASSERT_PIN_IO(2) +#define io2_config_output mcu_config_output(2) +#define io2_set_output mcu_set_output(2) +#define io2_clear_output mcu_clear_output(2) +#define io2_toggle_output mcu_toggle_output(2) +#define io2_get_output mcu_get_output(2) +#define io2_config_input mcu_config_input(2) +#define io2_config_pullup mcu_config_pullup(2) +#define io2_get_input mcu_get_input(2) +#elif ASSERT_PIN_EXTENDED(2) +#define io2_config_output +#define io2_set_output ic74hc595_set_pin(2);ic74hc595_shift_io_pins() +#define io2_clear_output ic74hc595_clear_pin(2);ic74hc595_shift_io_pins() +#define io2_toggle_output ic74hc595_toggle_pin(2);ic74hc595_shift_io_pins() +#define io2_get_output ic74hc595_get_pin(2) +#define io2_config_input +#define io2_config_pullup +#define io2_get_input 0 +#else +#define io2_config_output +#define io2_set_output +#define io2_clear_output +#define io2_toggle_output +#define io2_get_output 0 +#define io2_config_input +#define io2_config_pullup +#define io2_get_input 0 +#endif +#if ASSERT_PIN_IO(3) +#define io3_config_output mcu_config_output(3) +#define io3_set_output mcu_set_output(3) +#define io3_clear_output mcu_clear_output(3) +#define io3_toggle_output mcu_toggle_output(3) +#define io3_get_output mcu_get_output(3) +#define io3_config_input mcu_config_input(3) +#define io3_config_pullup mcu_config_pullup(3) +#define io3_get_input mcu_get_input(3) +#elif ASSERT_PIN_EXTENDED(3) +#define io3_config_output +#define io3_set_output ic74hc595_set_pin(3);ic74hc595_shift_io_pins() +#define io3_clear_output ic74hc595_clear_pin(3);ic74hc595_shift_io_pins() +#define io3_toggle_output ic74hc595_toggle_pin(3);ic74hc595_shift_io_pins() +#define io3_get_output ic74hc595_get_pin(3) +#define io3_config_input +#define io3_config_pullup +#define io3_get_input 0 +#else +#define io3_config_output +#define io3_set_output +#define io3_clear_output +#define io3_toggle_output +#define io3_get_output 0 +#define io3_config_input +#define io3_config_pullup +#define io3_get_input 0 +#endif +#if ASSERT_PIN_IO(4) +#define io4_config_output mcu_config_output(4) +#define io4_set_output mcu_set_output(4) +#define io4_clear_output mcu_clear_output(4) +#define io4_toggle_output mcu_toggle_output(4) +#define io4_get_output mcu_get_output(4) +#define io4_config_input mcu_config_input(4) +#define io4_config_pullup mcu_config_pullup(4) +#define io4_get_input mcu_get_input(4) +#elif ASSERT_PIN_EXTENDED(4) +#define io4_config_output +#define io4_set_output ic74hc595_set_pin(4);ic74hc595_shift_io_pins() +#define io4_clear_output ic74hc595_clear_pin(4);ic74hc595_shift_io_pins() +#define io4_toggle_output ic74hc595_toggle_pin(4);ic74hc595_shift_io_pins() +#define io4_get_output ic74hc595_get_pin(4) +#define io4_config_input +#define io4_config_pullup +#define io4_get_input 0 +#else +#define io4_config_output +#define io4_set_output +#define io4_clear_output +#define io4_toggle_output +#define io4_get_output 0 +#define io4_config_input +#define io4_config_pullup +#define io4_get_input 0 +#endif +#if ASSERT_PIN_IO(5) +#define io5_config_output mcu_config_output(5) +#define io5_set_output mcu_set_output(5) +#define io5_clear_output mcu_clear_output(5) +#define io5_toggle_output mcu_toggle_output(5) +#define io5_get_output mcu_get_output(5) +#define io5_config_input mcu_config_input(5) +#define io5_config_pullup mcu_config_pullup(5) +#define io5_get_input mcu_get_input(5) +#elif ASSERT_PIN_EXTENDED(5) +#define io5_config_output +#define io5_set_output ic74hc595_set_pin(5);ic74hc595_shift_io_pins() +#define io5_clear_output ic74hc595_clear_pin(5);ic74hc595_shift_io_pins() +#define io5_toggle_output ic74hc595_toggle_pin(5);ic74hc595_shift_io_pins() +#define io5_get_output ic74hc595_get_pin(5) +#define io5_config_input +#define io5_config_pullup +#define io5_get_input 0 +#else +#define io5_config_output +#define io5_set_output +#define io5_clear_output +#define io5_toggle_output +#define io5_get_output 0 +#define io5_config_input +#define io5_config_pullup +#define io5_get_input 0 +#endif +#if ASSERT_PIN_IO(6) +#define io6_config_output mcu_config_output(6) +#define io6_set_output mcu_set_output(6) +#define io6_clear_output mcu_clear_output(6) +#define io6_toggle_output mcu_toggle_output(6) +#define io6_get_output mcu_get_output(6) +#define io6_config_input mcu_config_input(6) +#define io6_config_pullup mcu_config_pullup(6) +#define io6_get_input mcu_get_input(6) +#elif ASSERT_PIN_EXTENDED(6) +#define io6_config_output +#define io6_set_output ic74hc595_set_pin(6);ic74hc595_shift_io_pins() +#define io6_clear_output ic74hc595_clear_pin(6);ic74hc595_shift_io_pins() +#define io6_toggle_output ic74hc595_toggle_pin(6);ic74hc595_shift_io_pins() +#define io6_get_output ic74hc595_get_pin(6) +#define io6_config_input +#define io6_config_pullup +#define io6_get_input 0 +#else +#define io6_config_output +#define io6_set_output +#define io6_clear_output +#define io6_toggle_output +#define io6_get_output 0 +#define io6_config_input +#define io6_config_pullup +#define io6_get_input 0 +#endif +#if ASSERT_PIN_IO(7) +#define io7_config_output mcu_config_output(7) +#define io7_set_output mcu_set_output(7) +#define io7_clear_output mcu_clear_output(7) +#define io7_toggle_output mcu_toggle_output(7) +#define io7_get_output mcu_get_output(7) +#define io7_config_input mcu_config_input(7) +#define io7_config_pullup mcu_config_pullup(7) +#define io7_get_input mcu_get_input(7) +#elif ASSERT_PIN_EXTENDED(7) +#define io7_config_output +#define io7_set_output ic74hc595_set_pin(7);ic74hc595_shift_io_pins() +#define io7_clear_output ic74hc595_clear_pin(7);ic74hc595_shift_io_pins() +#define io7_toggle_output ic74hc595_toggle_pin(7);ic74hc595_shift_io_pins() +#define io7_get_output ic74hc595_get_pin(7) +#define io7_config_input +#define io7_config_pullup +#define io7_get_input 0 +#else +#define io7_config_output +#define io7_set_output +#define io7_clear_output +#define io7_toggle_output +#define io7_get_output 0 +#define io7_config_input +#define io7_config_pullup +#define io7_get_input 0 +#endif +#if ASSERT_PIN_IO(8) +#define io8_config_output mcu_config_output(8) +#define io8_set_output mcu_set_output(8) +#define io8_clear_output mcu_clear_output(8) +#define io8_toggle_output mcu_toggle_output(8) +#define io8_get_output mcu_get_output(8) +#define io8_config_input mcu_config_input(8) +#define io8_config_pullup mcu_config_pullup(8) +#define io8_get_input mcu_get_input(8) +#elif ASSERT_PIN_EXTENDED(8) +#define io8_config_output +#define io8_set_output ic74hc595_set_pin(8);ic74hc595_shift_io_pins() +#define io8_clear_output ic74hc595_clear_pin(8);ic74hc595_shift_io_pins() +#define io8_toggle_output ic74hc595_toggle_pin(8);ic74hc595_shift_io_pins() +#define io8_get_output ic74hc595_get_pin(8) +#define io8_config_input +#define io8_config_pullup +#define io8_get_input 0 +#else +#define io8_config_output +#define io8_set_output +#define io8_clear_output +#define io8_toggle_output +#define io8_get_output 0 +#define io8_config_input +#define io8_config_pullup +#define io8_get_input 0 +#endif +#if ASSERT_PIN_IO(9) +#define io9_config_output mcu_config_output(9) +#define io9_set_output mcu_set_output(9) +#define io9_clear_output mcu_clear_output(9) +#define io9_toggle_output mcu_toggle_output(9) +#define io9_get_output mcu_get_output(9) +#define io9_config_input mcu_config_input(9) +#define io9_config_pullup mcu_config_pullup(9) +#define io9_get_input mcu_get_input(9) +#elif ASSERT_PIN_EXTENDED(9) +#define io9_config_output +#define io9_set_output ic74hc595_set_pin(9);ic74hc595_shift_io_pins() +#define io9_clear_output ic74hc595_clear_pin(9);ic74hc595_shift_io_pins() +#define io9_toggle_output ic74hc595_toggle_pin(9);ic74hc595_shift_io_pins() +#define io9_get_output ic74hc595_get_pin(9) +#define io9_config_input +#define io9_config_pullup +#define io9_get_input 0 +#else +#define io9_config_output +#define io9_set_output +#define io9_clear_output +#define io9_toggle_output +#define io9_get_output 0 +#define io9_config_input +#define io9_config_pullup +#define io9_get_input 0 +#endif +#if ASSERT_PIN_IO(10) +#define io10_config_output mcu_config_output(10) +#define io10_set_output mcu_set_output(10) +#define io10_clear_output mcu_clear_output(10) +#define io10_toggle_output mcu_toggle_output(10) +#define io10_get_output mcu_get_output(10) +#define io10_config_input mcu_config_input(10) +#define io10_config_pullup mcu_config_pullup(10) +#define io10_get_input mcu_get_input(10) +#elif ASSERT_PIN_EXTENDED(10) +#define io10_config_output +#define io10_set_output ic74hc595_set_pin(10);ic74hc595_shift_io_pins() +#define io10_clear_output ic74hc595_clear_pin(10);ic74hc595_shift_io_pins() +#define io10_toggle_output ic74hc595_toggle_pin(10);ic74hc595_shift_io_pins() +#define io10_get_output ic74hc595_get_pin(10) +#define io10_config_input +#define io10_config_pullup +#define io10_get_input 0 +#else +#define io10_config_output +#define io10_set_output +#define io10_clear_output +#define io10_toggle_output +#define io10_get_output 0 +#define io10_config_input +#define io10_config_pullup +#define io10_get_input 0 +#endif +#if ASSERT_PIN_IO(11) +#define io11_config_output mcu_config_output(11) +#define io11_set_output mcu_set_output(11) +#define io11_clear_output mcu_clear_output(11) +#define io11_toggle_output mcu_toggle_output(11) +#define io11_get_output mcu_get_output(11) +#define io11_config_input mcu_config_input(11) +#define io11_config_pullup mcu_config_pullup(11) +#define io11_get_input mcu_get_input(11) +#elif ASSERT_PIN_EXTENDED(11) +#define io11_config_output +#define io11_set_output ic74hc595_set_pin(11);ic74hc595_shift_io_pins() +#define io11_clear_output ic74hc595_clear_pin(11);ic74hc595_shift_io_pins() +#define io11_toggle_output ic74hc595_toggle_pin(11);ic74hc595_shift_io_pins() +#define io11_get_output ic74hc595_get_pin(11) +#define io11_config_input +#define io11_config_pullup +#define io11_get_input 0 +#else +#define io11_config_output +#define io11_set_output +#define io11_clear_output +#define io11_toggle_output +#define io11_get_output 0 +#define io11_config_input +#define io11_config_pullup +#define io11_get_input 0 +#endif +#if ASSERT_PIN_IO(12) +#define io12_config_output mcu_config_output(12) +#define io12_set_output mcu_set_output(12) +#define io12_clear_output mcu_clear_output(12) +#define io12_toggle_output mcu_toggle_output(12) +#define io12_get_output mcu_get_output(12) +#define io12_config_input mcu_config_input(12) +#define io12_config_pullup mcu_config_pullup(12) +#define io12_get_input mcu_get_input(12) +#elif ASSERT_PIN_EXTENDED(12) +#define io12_config_output +#define io12_set_output ic74hc595_set_pin(12);ic74hc595_shift_io_pins() +#define io12_clear_output ic74hc595_clear_pin(12);ic74hc595_shift_io_pins() +#define io12_toggle_output ic74hc595_toggle_pin(12);ic74hc595_shift_io_pins() +#define io12_get_output ic74hc595_get_pin(12) +#define io12_config_input +#define io12_config_pullup +#define io12_get_input 0 +#else +#define io12_config_output +#define io12_set_output +#define io12_clear_output +#define io12_toggle_output +#define io12_get_output 0 +#define io12_config_input +#define io12_config_pullup +#define io12_get_input 0 +#endif +#if ASSERT_PIN_IO(13) +#define io13_config_output mcu_config_output(13) +#define io13_set_output mcu_set_output(13) +#define io13_clear_output mcu_clear_output(13) +#define io13_toggle_output mcu_toggle_output(13) +#define io13_get_output mcu_get_output(13) +#define io13_config_input mcu_config_input(13) +#define io13_config_pullup mcu_config_pullup(13) +#define io13_get_input mcu_get_input(13) +#elif ASSERT_PIN_EXTENDED(13) +#define io13_config_output +#define io13_set_output ic74hc595_set_pin(13);ic74hc595_shift_io_pins() +#define io13_clear_output ic74hc595_clear_pin(13);ic74hc595_shift_io_pins() +#define io13_toggle_output ic74hc595_toggle_pin(13);ic74hc595_shift_io_pins() +#define io13_get_output ic74hc595_get_pin(13) +#define io13_config_input +#define io13_config_pullup +#define io13_get_input 0 +#else +#define io13_config_output +#define io13_set_output +#define io13_clear_output +#define io13_toggle_output +#define io13_get_output 0 +#define io13_config_input +#define io13_config_pullup +#define io13_get_input 0 +#endif +#if ASSERT_PIN_IO(14) +#define io14_config_output mcu_config_output(14) +#define io14_set_output mcu_set_output(14) +#define io14_clear_output mcu_clear_output(14) +#define io14_toggle_output mcu_toggle_output(14) +#define io14_get_output mcu_get_output(14) +#define io14_config_input mcu_config_input(14) +#define io14_config_pullup mcu_config_pullup(14) +#define io14_get_input mcu_get_input(14) +#elif ASSERT_PIN_EXTENDED(14) +#define io14_config_output +#define io14_set_output ic74hc595_set_pin(14);ic74hc595_shift_io_pins() +#define io14_clear_output ic74hc595_clear_pin(14);ic74hc595_shift_io_pins() +#define io14_toggle_output ic74hc595_toggle_pin(14);ic74hc595_shift_io_pins() +#define io14_get_output ic74hc595_get_pin(14) +#define io14_config_input +#define io14_config_pullup +#define io14_get_input 0 +#else +#define io14_config_output +#define io14_set_output +#define io14_clear_output +#define io14_toggle_output +#define io14_get_output 0 +#define io14_config_input +#define io14_config_pullup +#define io14_get_input 0 +#endif +#if ASSERT_PIN_IO(15) +#define io15_config_output mcu_config_output(15) +#define io15_set_output mcu_set_output(15) +#define io15_clear_output mcu_clear_output(15) +#define io15_toggle_output mcu_toggle_output(15) +#define io15_get_output mcu_get_output(15) +#define io15_config_input mcu_config_input(15) +#define io15_config_pullup mcu_config_pullup(15) +#define io15_get_input mcu_get_input(15) +#elif ASSERT_PIN_EXTENDED(15) +#define io15_config_output +#define io15_set_output ic74hc595_set_pin(15);ic74hc595_shift_io_pins() +#define io15_clear_output ic74hc595_clear_pin(15);ic74hc595_shift_io_pins() +#define io15_toggle_output ic74hc595_toggle_pin(15);ic74hc595_shift_io_pins() +#define io15_get_output ic74hc595_get_pin(15) +#define io15_config_input +#define io15_config_pullup +#define io15_get_input 0 +#else +#define io15_config_output +#define io15_set_output +#define io15_clear_output +#define io15_toggle_output +#define io15_get_output 0 +#define io15_config_input +#define io15_config_pullup +#define io15_get_input 0 +#endif +#if ASSERT_PIN_IO(16) +#define io16_config_output mcu_config_output(16) +#define io16_set_output mcu_set_output(16) +#define io16_clear_output mcu_clear_output(16) +#define io16_toggle_output mcu_toggle_output(16) +#define io16_get_output mcu_get_output(16) +#define io16_config_input mcu_config_input(16) +#define io16_config_pullup mcu_config_pullup(16) +#define io16_get_input mcu_get_input(16) +#elif ASSERT_PIN_EXTENDED(16) +#define io16_config_output +#define io16_set_output ic74hc595_set_pin(16);ic74hc595_shift_io_pins() +#define io16_clear_output ic74hc595_clear_pin(16);ic74hc595_shift_io_pins() +#define io16_toggle_output ic74hc595_toggle_pin(16);ic74hc595_shift_io_pins() +#define io16_get_output ic74hc595_get_pin(16) +#define io16_config_input +#define io16_config_pullup +#define io16_get_input 0 +#else +#define io16_config_output +#define io16_set_output +#define io16_clear_output +#define io16_toggle_output +#define io16_get_output 0 +#define io16_config_input +#define io16_config_pullup +#define io16_get_input 0 +#endif +#if ASSERT_PIN_IO(17) +#define io17_config_output mcu_config_output(17) +#define io17_set_output mcu_set_output(17) +#define io17_clear_output mcu_clear_output(17) +#define io17_toggle_output mcu_toggle_output(17) +#define io17_get_output mcu_get_output(17) +#define io17_config_input mcu_config_input(17) +#define io17_config_pullup mcu_config_pullup(17) +#define io17_get_input mcu_get_input(17) +#elif ASSERT_PIN_EXTENDED(17) +#define io17_config_output +#define io17_set_output ic74hc595_set_pin(17);ic74hc595_shift_io_pins() +#define io17_clear_output ic74hc595_clear_pin(17);ic74hc595_shift_io_pins() +#define io17_toggle_output ic74hc595_toggle_pin(17);ic74hc595_shift_io_pins() +#define io17_get_output ic74hc595_get_pin(17) +#define io17_config_input +#define io17_config_pullup +#define io17_get_input 0 +#else +#define io17_config_output +#define io17_set_output +#define io17_clear_output +#define io17_toggle_output +#define io17_get_output 0 +#define io17_config_input +#define io17_config_pullup +#define io17_get_input 0 +#endif +#if ASSERT_PIN_IO(18) +#define io18_config_output mcu_config_output(18) +#define io18_set_output mcu_set_output(18) +#define io18_clear_output mcu_clear_output(18) +#define io18_toggle_output mcu_toggle_output(18) +#define io18_get_output mcu_get_output(18) +#define io18_config_input mcu_config_input(18) +#define io18_config_pullup mcu_config_pullup(18) +#define io18_get_input mcu_get_input(18) +#elif ASSERT_PIN_EXTENDED(18) +#define io18_config_output +#define io18_set_output ic74hc595_set_pin(18);ic74hc595_shift_io_pins() +#define io18_clear_output ic74hc595_clear_pin(18);ic74hc595_shift_io_pins() +#define io18_toggle_output ic74hc595_toggle_pin(18);ic74hc595_shift_io_pins() +#define io18_get_output ic74hc595_get_pin(18) +#define io18_config_input +#define io18_config_pullup +#define io18_get_input 0 +#else +#define io18_config_output +#define io18_set_output +#define io18_clear_output +#define io18_toggle_output +#define io18_get_output 0 +#define io18_config_input +#define io18_config_pullup +#define io18_get_input 0 +#endif +#if ASSERT_PIN_IO(19) +#define io19_config_output mcu_config_output(19) +#define io19_set_output mcu_set_output(19) +#define io19_clear_output mcu_clear_output(19) +#define io19_toggle_output mcu_toggle_output(19) +#define io19_get_output mcu_get_output(19) +#define io19_config_input mcu_config_input(19) +#define io19_config_pullup mcu_config_pullup(19) +#define io19_get_input mcu_get_input(19) +#elif ASSERT_PIN_EXTENDED(19) +#define io19_config_output +#define io19_set_output ic74hc595_set_pin(19);ic74hc595_shift_io_pins() +#define io19_clear_output ic74hc595_clear_pin(19);ic74hc595_shift_io_pins() +#define io19_toggle_output ic74hc595_toggle_pin(19);ic74hc595_shift_io_pins() +#define io19_get_output ic74hc595_get_pin(19) +#define io19_config_input +#define io19_config_pullup +#define io19_get_input 0 +#else +#define io19_config_output +#define io19_set_output +#define io19_clear_output +#define io19_toggle_output +#define io19_get_output 0 +#define io19_config_input +#define io19_config_pullup +#define io19_get_input 0 +#endif +#if ASSERT_PIN_IO(20) +#define io20_config_output mcu_config_output(20) +#define io20_set_output mcu_set_output(20) +#define io20_clear_output mcu_clear_output(20) +#define io20_toggle_output mcu_toggle_output(20) +#define io20_get_output mcu_get_output(20) +#define io20_config_input mcu_config_input(20) +#define io20_config_pullup mcu_config_pullup(20) +#define io20_get_input mcu_get_input(20) +#elif ASSERT_PIN_EXTENDED(20) +#define io20_config_output +#define io20_set_output ic74hc595_set_pin(20);ic74hc595_shift_io_pins() +#define io20_clear_output ic74hc595_clear_pin(20);ic74hc595_shift_io_pins() +#define io20_toggle_output ic74hc595_toggle_pin(20);ic74hc595_shift_io_pins() +#define io20_get_output ic74hc595_get_pin(20) +#define io20_config_input +#define io20_config_pullup +#define io20_get_input 0 +#else +#define io20_config_output +#define io20_set_output +#define io20_clear_output +#define io20_toggle_output +#define io20_get_output 0 +#define io20_config_input +#define io20_config_pullup +#define io20_get_input 0 +#endif +#if ASSERT_PIN_IO(21) +#define io21_config_output mcu_config_output(21) +#define io21_set_output mcu_set_output(21) +#define io21_clear_output mcu_clear_output(21) +#define io21_toggle_output mcu_toggle_output(21) +#define io21_get_output mcu_get_output(21) +#define io21_config_input mcu_config_input(21) +#define io21_config_pullup mcu_config_pullup(21) +#define io21_get_input mcu_get_input(21) +#elif ASSERT_PIN_EXTENDED(21) +#define io21_config_output +#define io21_set_output ic74hc595_set_pin(21);ic74hc595_shift_io_pins() +#define io21_clear_output ic74hc595_clear_pin(21);ic74hc595_shift_io_pins() +#define io21_toggle_output ic74hc595_toggle_pin(21);ic74hc595_shift_io_pins() +#define io21_get_output ic74hc595_get_pin(21) +#define io21_config_input +#define io21_config_pullup +#define io21_get_input 0 +#else +#define io21_config_output +#define io21_set_output +#define io21_clear_output +#define io21_toggle_output +#define io21_get_output 0 +#define io21_config_input +#define io21_config_pullup +#define io21_get_input 0 +#endif +#if ASSERT_PIN_IO(22) +#define io22_config_output mcu_config_output(22) +#define io22_set_output mcu_set_output(22) +#define io22_clear_output mcu_clear_output(22) +#define io22_toggle_output mcu_toggle_output(22) +#define io22_get_output mcu_get_output(22) +#define io22_config_input mcu_config_input(22) +#define io22_config_pullup mcu_config_pullup(22) +#define io22_get_input mcu_get_input(22) +#elif ASSERT_PIN_EXTENDED(22) +#define io22_config_output +#define io22_set_output ic74hc595_set_pin(22);ic74hc595_shift_io_pins() +#define io22_clear_output ic74hc595_clear_pin(22);ic74hc595_shift_io_pins() +#define io22_toggle_output ic74hc595_toggle_pin(22);ic74hc595_shift_io_pins() +#define io22_get_output ic74hc595_get_pin(22) +#define io22_config_input +#define io22_config_pullup +#define io22_get_input 0 +#else +#define io22_config_output +#define io22_set_output +#define io22_clear_output +#define io22_toggle_output +#define io22_get_output 0 +#define io22_config_input +#define io22_config_pullup +#define io22_get_input 0 +#endif +#if ASSERT_PIN_IO(23) +#define io23_config_output mcu_config_output(23) +#define io23_set_output mcu_set_output(23) +#define io23_clear_output mcu_clear_output(23) +#define io23_toggle_output mcu_toggle_output(23) +#define io23_get_output mcu_get_output(23) +#define io23_config_input mcu_config_input(23) +#define io23_config_pullup mcu_config_pullup(23) +#define io23_get_input mcu_get_input(23) +#elif ASSERT_PIN_EXTENDED(23) +#define io23_config_output +#define io23_set_output ic74hc595_set_pin(23);ic74hc595_shift_io_pins() +#define io23_clear_output ic74hc595_clear_pin(23);ic74hc595_shift_io_pins() +#define io23_toggle_output ic74hc595_toggle_pin(23);ic74hc595_shift_io_pins() +#define io23_get_output ic74hc595_get_pin(23) +#define io23_config_input +#define io23_config_pullup +#define io23_get_input 0 +#else +#define io23_config_output +#define io23_set_output +#define io23_clear_output +#define io23_toggle_output +#define io23_get_output 0 +#define io23_config_input +#define io23_config_pullup +#define io23_get_input 0 +#endif +#if ASSERT_PIN_IO(24) +#define io24_config_output mcu_config_output(24) +#define io24_set_output mcu_set_output(24) +#define io24_clear_output mcu_clear_output(24) +#define io24_toggle_output mcu_toggle_output(24) +#define io24_get_output mcu_get_output(24) +#define io24_config_input mcu_config_input(24) +#define io24_config_pullup mcu_config_pullup(24) +#define io24_get_input mcu_get_input(24) +#elif ASSERT_PIN_EXTENDED(24) +#define io24_config_output +#define io24_set_output ic74hc595_set_pin(24);ic74hc595_shift_io_pins() +#define io24_clear_output ic74hc595_clear_pin(24);ic74hc595_shift_io_pins() +#define io24_toggle_output ic74hc595_toggle_pin(24);ic74hc595_shift_io_pins() +#define io24_get_output ic74hc595_get_pin(24) +#define io24_config_input +#define io24_config_pullup +#define io24_get_input 0 +#else +#define io24_config_output +#define io24_set_output +#define io24_clear_output +#define io24_toggle_output +#define io24_get_output 0 +#define io24_config_input +#define io24_config_pullup +#define io24_get_input 0 +#endif +#if ASSERT_PIN_IO(25) +#define io25_config_output mcu_config_output(25) +#define io25_set_output mcu_set_output(25) +#define io25_clear_output mcu_clear_output(25) +#define io25_toggle_output mcu_toggle_output(25) +#define io25_get_output mcu_get_output(25) +#define io25_config_input mcu_config_input(25) +#define io25_config_pullup mcu_config_pullup(25) +#define io25_get_input mcu_get_input(25) +#elif ASSERT_PIN_EXTENDED(25) +#define io25_config_output +#define io25_set_output ic74hc595_set_pin(25);ic74hc595_shift_io_pins() +#define io25_clear_output ic74hc595_clear_pin(25);ic74hc595_shift_io_pins() +#define io25_toggle_output ic74hc595_toggle_pin(25);ic74hc595_shift_io_pins() +#define io25_get_output ic74hc595_get_pin(25) +#define io25_config_input +#define io25_config_pullup +#define io25_get_input 0 +#else +#define io25_config_output +#define io25_set_output +#define io25_clear_output +#define io25_toggle_output +#define io25_get_output 0 +#define io25_config_input +#define io25_config_pullup +#define io25_get_input 0 +#endif +#if ASSERT_PIN_IO(26) +#define io26_config_output mcu_config_output(26) +#define io26_set_output mcu_set_output(26) +#define io26_clear_output mcu_clear_output(26) +#define io26_toggle_output mcu_toggle_output(26) +#define io26_get_output mcu_get_output(26) +#define io26_config_input mcu_config_input(26) +#define io26_config_pullup mcu_config_pullup(26) +#define io26_get_input mcu_get_input(26) +#elif ASSERT_PIN_EXTENDED(26) +#define io26_config_output +#define io26_set_output ic74hc595_set_pin(26);ic74hc595_shift_io_pins() +#define io26_clear_output ic74hc595_clear_pin(26);ic74hc595_shift_io_pins() +#define io26_toggle_output ic74hc595_toggle_pin(26);ic74hc595_shift_io_pins() +#define io26_get_output ic74hc595_get_pin(26) +#define io26_config_input +#define io26_config_pullup +#define io26_get_input 0 +#else +#define io26_config_output +#define io26_set_output +#define io26_clear_output +#define io26_toggle_output +#define io26_get_output 0 +#define io26_config_input +#define io26_config_pullup +#define io26_get_input 0 +#endif +#if ASSERT_PIN_IO(27) +#define io27_config_output mcu_config_output(27) +#define io27_set_output mcu_set_output(27) +#define io27_clear_output mcu_clear_output(27) +#define io27_toggle_output mcu_toggle_output(27) +#define io27_get_output mcu_get_output(27) +#define io27_config_input mcu_config_input(27) +#define io27_config_pullup mcu_config_pullup(27) +#define io27_get_input mcu_get_input(27) +#elif ASSERT_PIN_EXTENDED(27) +#define io27_config_output +#define io27_set_output ic74hc595_set_pin(27);ic74hc595_shift_io_pins() +#define io27_clear_output ic74hc595_clear_pin(27);ic74hc595_shift_io_pins() +#define io27_toggle_output ic74hc595_toggle_pin(27);ic74hc595_shift_io_pins() +#define io27_get_output ic74hc595_get_pin(27) +#define io27_config_input +#define io27_config_pullup +#define io27_get_input 0 +#else +#define io27_config_output +#define io27_set_output +#define io27_clear_output +#define io27_toggle_output +#define io27_get_output 0 +#define io27_config_input +#define io27_config_pullup +#define io27_get_input 0 +#endif +#if ASSERT_PIN_IO(28) +#define io28_config_output mcu_config_output(28) +#define io28_set_output mcu_set_output(28) +#define io28_clear_output mcu_clear_output(28) +#define io28_toggle_output mcu_toggle_output(28) +#define io28_get_output mcu_get_output(28) +#define io28_config_input mcu_config_input(28) +#define io28_config_pullup mcu_config_pullup(28) +#define io28_get_input mcu_get_input(28) +#elif ASSERT_PIN_EXTENDED(28) +#define io28_config_output +#define io28_set_output ic74hc595_set_pin(28);ic74hc595_shift_io_pins() +#define io28_clear_output ic74hc595_clear_pin(28);ic74hc595_shift_io_pins() +#define io28_toggle_output ic74hc595_toggle_pin(28);ic74hc595_shift_io_pins() +#define io28_get_output ic74hc595_get_pin(28) +#define io28_config_input +#define io28_config_pullup +#define io28_get_input 0 +#else +#define io28_config_output +#define io28_set_output +#define io28_clear_output +#define io28_toggle_output +#define io28_get_output 0 +#define io28_config_input +#define io28_config_pullup +#define io28_get_input 0 +#endif +#if ASSERT_PIN_IO(29) +#define io29_config_output mcu_config_output(29) +#define io29_set_output mcu_set_output(29) +#define io29_clear_output mcu_clear_output(29) +#define io29_toggle_output mcu_toggle_output(29) +#define io29_get_output mcu_get_output(29) +#define io29_config_input mcu_config_input(29) +#define io29_config_pullup mcu_config_pullup(29) +#define io29_get_input mcu_get_input(29) +#elif ASSERT_PIN_EXTENDED(29) +#define io29_config_output +#define io29_set_output ic74hc595_set_pin(29);ic74hc595_shift_io_pins() +#define io29_clear_output ic74hc595_clear_pin(29);ic74hc595_shift_io_pins() +#define io29_toggle_output ic74hc595_toggle_pin(29);ic74hc595_shift_io_pins() +#define io29_get_output ic74hc595_get_pin(29) +#define io29_config_input +#define io29_config_pullup +#define io29_get_input 0 +#else +#define io29_config_output +#define io29_set_output +#define io29_clear_output +#define io29_toggle_output +#define io29_get_output 0 +#define io29_config_input +#define io29_config_pullup +#define io29_get_input 0 +#endif +#if ASSERT_PIN_IO(30) +#define io30_config_output mcu_config_output(30) +#define io30_set_output mcu_set_output(30) +#define io30_clear_output mcu_clear_output(30) +#define io30_toggle_output mcu_toggle_output(30) +#define io30_get_output mcu_get_output(30) +#define io30_config_input mcu_config_input(30) +#define io30_config_pullup mcu_config_pullup(30) +#define io30_get_input mcu_get_input(30) +#elif ASSERT_PIN_EXTENDED(30) +#define io30_config_output +#define io30_set_output ic74hc595_set_pin(30);ic74hc595_shift_io_pins() +#define io30_clear_output ic74hc595_clear_pin(30);ic74hc595_shift_io_pins() +#define io30_toggle_output ic74hc595_toggle_pin(30);ic74hc595_shift_io_pins() +#define io30_get_output ic74hc595_get_pin(30) +#define io30_config_input +#define io30_config_pullup +#define io30_get_input 0 +#else +#define io30_config_output +#define io30_set_output +#define io30_clear_output +#define io30_toggle_output +#define io30_get_output 0 +#define io30_config_input +#define io30_config_pullup +#define io30_get_input 0 +#endif +#if ASSERT_PIN_IO(31) +#define io31_config_output mcu_config_output(31) +#define io31_set_output mcu_set_output(31) +#define io31_clear_output mcu_clear_output(31) +#define io31_toggle_output mcu_toggle_output(31) +#define io31_get_output mcu_get_output(31) +#define io31_config_input mcu_config_input(31) +#define io31_config_pullup mcu_config_pullup(31) +#define io31_get_input mcu_get_input(31) +#elif ASSERT_PIN_EXTENDED(31) +#define io31_config_output +#define io31_set_output ic74hc595_set_pin(31);ic74hc595_shift_io_pins() +#define io31_clear_output ic74hc595_clear_pin(31);ic74hc595_shift_io_pins() +#define io31_toggle_output ic74hc595_toggle_pin(31);ic74hc595_shift_io_pins() +#define io31_get_output ic74hc595_get_pin(31) +#define io31_config_input +#define io31_config_pullup +#define io31_get_input 0 +#else +#define io31_config_output +#define io31_set_output +#define io31_clear_output +#define io31_toggle_output +#define io31_get_output 0 +#define io31_config_input +#define io31_config_pullup +#define io31_get_input 0 +#endif +#if ASSERT_PIN_IO(32) +#define io32_config_output mcu_config_output(32) +#define io32_set_output mcu_set_output(32) +#define io32_clear_output mcu_clear_output(32) +#define io32_toggle_output mcu_toggle_output(32) +#define io32_get_output mcu_get_output(32) +#define io32_config_input mcu_config_input(32) +#define io32_config_pullup mcu_config_pullup(32) +#define io32_get_input mcu_get_input(32) +#elif ASSERT_PIN_EXTENDED(32) +#define io32_config_output +#define io32_set_output ic74hc595_set_pin(32);ic74hc595_shift_io_pins() +#define io32_clear_output ic74hc595_clear_pin(32);ic74hc595_shift_io_pins() +#define io32_toggle_output ic74hc595_toggle_pin(32);ic74hc595_shift_io_pins() +#define io32_get_output ic74hc595_get_pin(32) +#define io32_config_input +#define io32_config_pullup +#define io32_get_input 0 +#else +#define io32_config_output +#define io32_set_output +#define io32_clear_output +#define io32_toggle_output +#define io32_get_output 0 +#define io32_config_input +#define io32_config_pullup +#define io32_get_input 0 +#endif +#if ASSERT_PIN_IO(33) +#define io33_config_output mcu_config_output(33) +#define io33_set_output mcu_set_output(33) +#define io33_clear_output mcu_clear_output(33) +#define io33_toggle_output mcu_toggle_output(33) +#define io33_get_output mcu_get_output(33) +#define io33_config_input mcu_config_input(33) +#define io33_config_pullup mcu_config_pullup(33) +#define io33_get_input mcu_get_input(33) +#elif ASSERT_PIN_EXTENDED(33) +#define io33_config_output +#define io33_set_output ic74hc595_set_pin(33);ic74hc595_shift_io_pins() +#define io33_clear_output ic74hc595_clear_pin(33);ic74hc595_shift_io_pins() +#define io33_toggle_output ic74hc595_toggle_pin(33);ic74hc595_shift_io_pins() +#define io33_get_output ic74hc595_get_pin(33) +#define io33_config_input +#define io33_config_pullup +#define io33_get_input 0 +#else +#define io33_config_output +#define io33_set_output +#define io33_clear_output +#define io33_toggle_output +#define io33_get_output 0 +#define io33_config_input +#define io33_config_pullup +#define io33_get_input 0 +#endif +#if ASSERT_PIN_IO(34) +#define io34_config_output mcu_config_output(34) +#define io34_set_output mcu_set_output(34) +#define io34_clear_output mcu_clear_output(34) +#define io34_toggle_output mcu_toggle_output(34) +#define io34_get_output mcu_get_output(34) +#define io34_config_input mcu_config_input(34) +#define io34_config_pullup mcu_config_pullup(34) +#define io34_get_input mcu_get_input(34) +#elif ASSERT_PIN_EXTENDED(34) +#define io34_config_output +#define io34_set_output ic74hc595_set_pin(34);ic74hc595_shift_io_pins() +#define io34_clear_output ic74hc595_clear_pin(34);ic74hc595_shift_io_pins() +#define io34_toggle_output ic74hc595_toggle_pin(34);ic74hc595_shift_io_pins() +#define io34_get_output ic74hc595_get_pin(34) +#define io34_config_input +#define io34_config_pullup +#define io34_get_input 0 +#else +#define io34_config_output +#define io34_set_output +#define io34_clear_output +#define io34_toggle_output +#define io34_get_output 0 +#define io34_config_input +#define io34_config_pullup +#define io34_get_input 0 +#endif +#if ASSERT_PIN_IO(35) +#define io35_config_output mcu_config_output(35) +#define io35_set_output mcu_set_output(35) +#define io35_clear_output mcu_clear_output(35) +#define io35_toggle_output mcu_toggle_output(35) +#define io35_get_output mcu_get_output(35) +#define io35_config_input mcu_config_input(35) +#define io35_config_pullup mcu_config_pullup(35) +#define io35_get_input mcu_get_input(35) +#elif ASSERT_PIN_EXTENDED(35) +#define io35_config_output +#define io35_set_output ic74hc595_set_pin(35);ic74hc595_shift_io_pins() +#define io35_clear_output ic74hc595_clear_pin(35);ic74hc595_shift_io_pins() +#define io35_toggle_output ic74hc595_toggle_pin(35);ic74hc595_shift_io_pins() +#define io35_get_output ic74hc595_get_pin(35) +#define io35_config_input +#define io35_config_pullup +#define io35_get_input 0 +#else +#define io35_config_output +#define io35_set_output +#define io35_clear_output +#define io35_toggle_output +#define io35_get_output 0 +#define io35_config_input +#define io35_config_pullup +#define io35_get_input 0 +#endif +#if ASSERT_PIN_IO(36) +#define io36_config_output mcu_config_output(36) +#define io36_set_output mcu_set_output(36) +#define io36_clear_output mcu_clear_output(36) +#define io36_toggle_output mcu_toggle_output(36) +#define io36_get_output mcu_get_output(36) +#define io36_config_input mcu_config_input(36) +#define io36_config_pullup mcu_config_pullup(36) +#define io36_get_input mcu_get_input(36) +#elif ASSERT_PIN_EXTENDED(36) +#define io36_config_output +#define io36_set_output ic74hc595_set_pin(36);ic74hc595_shift_io_pins() +#define io36_clear_output ic74hc595_clear_pin(36);ic74hc595_shift_io_pins() +#define io36_toggle_output ic74hc595_toggle_pin(36);ic74hc595_shift_io_pins() +#define io36_get_output ic74hc595_get_pin(36) +#define io36_config_input +#define io36_config_pullup +#define io36_get_input 0 +#else +#define io36_config_output +#define io36_set_output +#define io36_clear_output +#define io36_toggle_output +#define io36_get_output 0 +#define io36_config_input +#define io36_config_pullup +#define io36_get_input 0 +#endif +#if ASSERT_PIN_IO(37) +#define io37_config_output mcu_config_output(37) +#define io37_set_output mcu_set_output(37) +#define io37_clear_output mcu_clear_output(37) +#define io37_toggle_output mcu_toggle_output(37) +#define io37_get_output mcu_get_output(37) +#define io37_config_input mcu_config_input(37) +#define io37_config_pullup mcu_config_pullup(37) +#define io37_get_input mcu_get_input(37) +#elif ASSERT_PIN_EXTENDED(37) +#define io37_config_output +#define io37_set_output ic74hc595_set_pin(37);ic74hc595_shift_io_pins() +#define io37_clear_output ic74hc595_clear_pin(37);ic74hc595_shift_io_pins() +#define io37_toggle_output ic74hc595_toggle_pin(37);ic74hc595_shift_io_pins() +#define io37_get_output ic74hc595_get_pin(37) +#define io37_config_input +#define io37_config_pullup +#define io37_get_input 0 +#else +#define io37_config_output +#define io37_set_output +#define io37_clear_output +#define io37_toggle_output +#define io37_get_output 0 +#define io37_config_input +#define io37_config_pullup +#define io37_get_input 0 +#endif +#if ASSERT_PIN_IO(38) +#define io38_config_output mcu_config_output(38) +#define io38_set_output mcu_set_output(38) +#define io38_clear_output mcu_clear_output(38) +#define io38_toggle_output mcu_toggle_output(38) +#define io38_get_output mcu_get_output(38) +#define io38_config_input mcu_config_input(38) +#define io38_config_pullup mcu_config_pullup(38) +#define io38_get_input mcu_get_input(38) +#elif ASSERT_PIN_EXTENDED(38) +#define io38_config_output +#define io38_set_output ic74hc595_set_pin(38);ic74hc595_shift_io_pins() +#define io38_clear_output ic74hc595_clear_pin(38);ic74hc595_shift_io_pins() +#define io38_toggle_output ic74hc595_toggle_pin(38);ic74hc595_shift_io_pins() +#define io38_get_output ic74hc595_get_pin(38) +#define io38_config_input +#define io38_config_pullup +#define io38_get_input 0 +#else +#define io38_config_output +#define io38_set_output +#define io38_clear_output +#define io38_toggle_output +#define io38_get_output 0 +#define io38_config_input +#define io38_config_pullup +#define io38_get_input 0 +#endif +#if ASSERT_PIN_IO(39) +#define io39_config_output mcu_config_output(39) +#define io39_set_output mcu_set_output(39) +#define io39_clear_output mcu_clear_output(39) +#define io39_toggle_output mcu_toggle_output(39) +#define io39_get_output mcu_get_output(39) +#define io39_config_input mcu_config_input(39) +#define io39_config_pullup mcu_config_pullup(39) +#define io39_get_input mcu_get_input(39) +#elif ASSERT_PIN_EXTENDED(39) +#define io39_config_output +#define io39_set_output ic74hc595_set_pin(39);ic74hc595_shift_io_pins() +#define io39_clear_output ic74hc595_clear_pin(39);ic74hc595_shift_io_pins() +#define io39_toggle_output ic74hc595_toggle_pin(39);ic74hc595_shift_io_pins() +#define io39_get_output ic74hc595_get_pin(39) +#define io39_config_input +#define io39_config_pullup +#define io39_get_input 0 +#else +#define io39_config_output +#define io39_set_output +#define io39_clear_output +#define io39_toggle_output +#define io39_get_output 0 +#define io39_config_input +#define io39_config_pullup +#define io39_get_input 0 +#endif +#if ASSERT_PIN_IO(40) +#define io40_config_output mcu_config_output(40) +#define io40_set_output mcu_set_output(40) +#define io40_clear_output mcu_clear_output(40) +#define io40_toggle_output mcu_toggle_output(40) +#define io40_get_output mcu_get_output(40) +#define io40_config_input mcu_config_input(40) +#define io40_config_pullup mcu_config_pullup(40) +#define io40_get_input mcu_get_input(40) +#elif ASSERT_PIN_EXTENDED(40) +#define io40_config_output +#define io40_set_output ic74hc595_set_pin(40);ic74hc595_shift_io_pins() +#define io40_clear_output ic74hc595_clear_pin(40);ic74hc595_shift_io_pins() +#define io40_toggle_output ic74hc595_toggle_pin(40);ic74hc595_shift_io_pins() +#define io40_get_output ic74hc595_get_pin(40) +#define io40_config_input +#define io40_config_pullup +#define io40_get_input 0 +#else +#define io40_config_output +#define io40_set_output +#define io40_clear_output +#define io40_toggle_output +#define io40_get_output 0 +#define io40_config_input +#define io40_config_pullup +#define io40_get_input 0 +#endif +#if ASSERT_PIN_IO(41) +#define io41_config_output mcu_config_output(41) +#define io41_set_output mcu_set_output(41) +#define io41_clear_output mcu_clear_output(41) +#define io41_toggle_output mcu_toggle_output(41) +#define io41_get_output mcu_get_output(41) +#define io41_config_input mcu_config_input(41) +#define io41_config_pullup mcu_config_pullup(41) +#define io41_get_input mcu_get_input(41) +#elif ASSERT_PIN_EXTENDED(41) +#define io41_config_output +#define io41_set_output ic74hc595_set_pin(41);ic74hc595_shift_io_pins() +#define io41_clear_output ic74hc595_clear_pin(41);ic74hc595_shift_io_pins() +#define io41_toggle_output ic74hc595_toggle_pin(41);ic74hc595_shift_io_pins() +#define io41_get_output ic74hc595_get_pin(41) +#define io41_config_input +#define io41_config_pullup +#define io41_get_input 0 +#else +#define io41_config_output +#define io41_set_output +#define io41_clear_output +#define io41_toggle_output +#define io41_get_output 0 +#define io41_config_input +#define io41_config_pullup +#define io41_get_input 0 +#endif +#if ASSERT_PIN_IO(42) +#define io42_config_output mcu_config_output(42) +#define io42_set_output mcu_set_output(42) +#define io42_clear_output mcu_clear_output(42) +#define io42_toggle_output mcu_toggle_output(42) +#define io42_get_output mcu_get_output(42) +#define io42_config_input mcu_config_input(42) +#define io42_config_pullup mcu_config_pullup(42) +#define io42_get_input mcu_get_input(42) +#elif ASSERT_PIN_EXTENDED(42) +#define io42_config_output +#define io42_set_output ic74hc595_set_pin(42);ic74hc595_shift_io_pins() +#define io42_clear_output ic74hc595_clear_pin(42);ic74hc595_shift_io_pins() +#define io42_toggle_output ic74hc595_toggle_pin(42);ic74hc595_shift_io_pins() +#define io42_get_output ic74hc595_get_pin(42) +#define io42_config_input +#define io42_config_pullup +#define io42_get_input 0 +#else +#define io42_config_output +#define io42_set_output +#define io42_clear_output +#define io42_toggle_output +#define io42_get_output 0 +#define io42_config_input +#define io42_config_pullup +#define io42_get_input 0 +#endif +#if ASSERT_PIN_IO(43) +#define io43_config_output mcu_config_output(43) +#define io43_set_output mcu_set_output(43) +#define io43_clear_output mcu_clear_output(43) +#define io43_toggle_output mcu_toggle_output(43) +#define io43_get_output mcu_get_output(43) +#define io43_config_input mcu_config_input(43) +#define io43_config_pullup mcu_config_pullup(43) +#define io43_get_input mcu_get_input(43) +#elif ASSERT_PIN_EXTENDED(43) +#define io43_config_output +#define io43_set_output ic74hc595_set_pin(43);ic74hc595_shift_io_pins() +#define io43_clear_output ic74hc595_clear_pin(43);ic74hc595_shift_io_pins() +#define io43_toggle_output ic74hc595_toggle_pin(43);ic74hc595_shift_io_pins() +#define io43_get_output ic74hc595_get_pin(43) +#define io43_config_input +#define io43_config_pullup +#define io43_get_input 0 +#else +#define io43_config_output +#define io43_set_output +#define io43_clear_output +#define io43_toggle_output +#define io43_get_output 0 +#define io43_config_input +#define io43_config_pullup +#define io43_get_input 0 +#endif +#if ASSERT_PIN_IO(44) +#define io44_config_output mcu_config_output(44) +#define io44_set_output mcu_set_output(44) +#define io44_clear_output mcu_clear_output(44) +#define io44_toggle_output mcu_toggle_output(44) +#define io44_get_output mcu_get_output(44) +#define io44_config_input mcu_config_input(44) +#define io44_config_pullup mcu_config_pullup(44) +#define io44_get_input mcu_get_input(44) +#elif ASSERT_PIN_EXTENDED(44) +#define io44_config_output +#define io44_set_output ic74hc595_set_pin(44);ic74hc595_shift_io_pins() +#define io44_clear_output ic74hc595_clear_pin(44);ic74hc595_shift_io_pins() +#define io44_toggle_output ic74hc595_toggle_pin(44);ic74hc595_shift_io_pins() +#define io44_get_output ic74hc595_get_pin(44) +#define io44_config_input +#define io44_config_pullup +#define io44_get_input 0 +#else +#define io44_config_output +#define io44_set_output +#define io44_clear_output +#define io44_toggle_output +#define io44_get_output 0 +#define io44_config_input +#define io44_config_pullup +#define io44_get_input 0 +#endif +#if ASSERT_PIN_IO(45) +#define io45_config_output mcu_config_output(45) +#define io45_set_output mcu_set_output(45) +#define io45_clear_output mcu_clear_output(45) +#define io45_toggle_output mcu_toggle_output(45) +#define io45_get_output mcu_get_output(45) +#define io45_config_input mcu_config_input(45) +#define io45_config_pullup mcu_config_pullup(45) +#define io45_get_input mcu_get_input(45) +#elif ASSERT_PIN_EXTENDED(45) +#define io45_config_output +#define io45_set_output ic74hc595_set_pin(45);ic74hc595_shift_io_pins() +#define io45_clear_output ic74hc595_clear_pin(45);ic74hc595_shift_io_pins() +#define io45_toggle_output ic74hc595_toggle_pin(45);ic74hc595_shift_io_pins() +#define io45_get_output ic74hc595_get_pin(45) +#define io45_config_input +#define io45_config_pullup +#define io45_get_input 0 +#else +#define io45_config_output +#define io45_set_output +#define io45_clear_output +#define io45_toggle_output +#define io45_get_output 0 +#define io45_config_input +#define io45_config_pullup +#define io45_get_input 0 +#endif +#if ASSERT_PIN_IO(46) +#define io46_config_output mcu_config_output(46) +#define io46_set_output mcu_set_output(46) +#define io46_clear_output mcu_clear_output(46) +#define io46_toggle_output mcu_toggle_output(46) +#define io46_get_output mcu_get_output(46) +#define io46_config_input mcu_config_input(46) +#define io46_config_pullup mcu_config_pullup(46) +#define io46_get_input mcu_get_input(46) +#elif ASSERT_PIN_EXTENDED(46) +#define io46_config_output +#define io46_set_output ic74hc595_set_pin(46);ic74hc595_shift_io_pins() +#define io46_clear_output ic74hc595_clear_pin(46);ic74hc595_shift_io_pins() +#define io46_toggle_output ic74hc595_toggle_pin(46);ic74hc595_shift_io_pins() +#define io46_get_output ic74hc595_get_pin(46) +#define io46_config_input +#define io46_config_pullup +#define io46_get_input 0 +#else +#define io46_config_output +#define io46_set_output +#define io46_clear_output +#define io46_toggle_output +#define io46_get_output 0 +#define io46_config_input +#define io46_config_pullup +#define io46_get_input 0 +#endif +#if ASSERT_PIN_IO(47) +#define io47_config_output mcu_config_output(47) +#define io47_set_output mcu_set_output(47) +#define io47_clear_output mcu_clear_output(47) +#define io47_toggle_output mcu_toggle_output(47) +#define io47_get_output mcu_get_output(47) +#define io47_config_input mcu_config_input(47) +#define io47_config_pullup mcu_config_pullup(47) +#define io47_get_input mcu_get_input(47) +#elif ASSERT_PIN_EXTENDED(47) +#define io47_config_output +#define io47_set_output ic74hc595_set_pin(47);ic74hc595_shift_io_pins() +#define io47_clear_output ic74hc595_clear_pin(47);ic74hc595_shift_io_pins() +#define io47_toggle_output ic74hc595_toggle_pin(47);ic74hc595_shift_io_pins() +#define io47_get_output ic74hc595_get_pin(47) +#define io47_config_input +#define io47_config_pullup +#define io47_get_input 0 +#else +#define io47_config_output +#define io47_set_output +#define io47_clear_output +#define io47_toggle_output +#define io47_get_output 0 +#define io47_config_input +#define io47_config_pullup +#define io47_get_input 0 +#endif +#if ASSERT_PIN_IO(48) +#define io48_config_output mcu_config_output(48) +#define io48_set_output mcu_set_output(48) +#define io48_clear_output mcu_clear_output(48) +#define io48_toggle_output mcu_toggle_output(48) +#define io48_get_output mcu_get_output(48) +#define io48_config_input mcu_config_input(48) +#define io48_config_pullup mcu_config_pullup(48) +#define io48_get_input mcu_get_input(48) +#elif ASSERT_PIN_EXTENDED(48) +#define io48_config_output +#define io48_set_output ic74hc595_set_pin(48);ic74hc595_shift_io_pins() +#define io48_clear_output ic74hc595_clear_pin(48);ic74hc595_shift_io_pins() +#define io48_toggle_output ic74hc595_toggle_pin(48);ic74hc595_shift_io_pins() +#define io48_get_output ic74hc595_get_pin(48) +#define io48_config_input +#define io48_config_pullup +#define io48_get_input 0 +#else +#define io48_config_output +#define io48_set_output +#define io48_clear_output +#define io48_toggle_output +#define io48_get_output 0 +#define io48_config_input +#define io48_config_pullup +#define io48_get_input 0 +#endif +#if ASSERT_PIN_IO(49) +#define io49_config_output mcu_config_output(49) +#define io49_set_output mcu_set_output(49) +#define io49_clear_output mcu_clear_output(49) +#define io49_toggle_output mcu_toggle_output(49) +#define io49_get_output mcu_get_output(49) +#define io49_config_input mcu_config_input(49) +#define io49_config_pullup mcu_config_pullup(49) +#define io49_get_input mcu_get_input(49) +#elif ASSERT_PIN_EXTENDED(49) +#define io49_config_output +#define io49_set_output ic74hc595_set_pin(49);ic74hc595_shift_io_pins() +#define io49_clear_output ic74hc595_clear_pin(49);ic74hc595_shift_io_pins() +#define io49_toggle_output ic74hc595_toggle_pin(49);ic74hc595_shift_io_pins() +#define io49_get_output ic74hc595_get_pin(49) +#define io49_config_input +#define io49_config_pullup +#define io49_get_input 0 +#else +#define io49_config_output +#define io49_set_output +#define io49_clear_output +#define io49_toggle_output +#define io49_get_output 0 +#define io49_config_input +#define io49_config_pullup +#define io49_get_input 0 +#endif +#if ASSERT_PIN_IO(50) +#define io50_config_output mcu_config_output(50) +#define io50_set_output mcu_set_output(50) +#define io50_clear_output mcu_clear_output(50) +#define io50_toggle_output mcu_toggle_output(50) +#define io50_get_output mcu_get_output(50) +#define io50_config_input mcu_config_input(50) +#define io50_config_pullup mcu_config_pullup(50) +#define io50_get_input mcu_get_input(50) +#elif ASSERT_PIN_EXTENDED(50) +#define io50_config_output +#define io50_set_output ic74hc595_set_pin(50);ic74hc595_shift_io_pins() +#define io50_clear_output ic74hc595_clear_pin(50);ic74hc595_shift_io_pins() +#define io50_toggle_output ic74hc595_toggle_pin(50);ic74hc595_shift_io_pins() +#define io50_get_output ic74hc595_get_pin(50) +#define io50_config_input +#define io50_config_pullup +#define io50_get_input 0 +#else +#define io50_config_output +#define io50_set_output +#define io50_clear_output +#define io50_toggle_output +#define io50_get_output 0 +#define io50_config_input +#define io50_config_pullup +#define io50_get_input 0 +#endif +#if ASSERT_PIN_IO(51) +#define io51_config_output mcu_config_output(51) +#define io51_set_output mcu_set_output(51) +#define io51_clear_output mcu_clear_output(51) +#define io51_toggle_output mcu_toggle_output(51) +#define io51_get_output mcu_get_output(51) +#define io51_config_input mcu_config_input(51) +#define io51_config_pullup mcu_config_pullup(51) +#define io51_get_input mcu_get_input(51) +#elif ASSERT_PIN_EXTENDED(51) +#define io51_config_output +#define io51_set_output ic74hc595_set_pin(51);ic74hc595_shift_io_pins() +#define io51_clear_output ic74hc595_clear_pin(51);ic74hc595_shift_io_pins() +#define io51_toggle_output ic74hc595_toggle_pin(51);ic74hc595_shift_io_pins() +#define io51_get_output ic74hc595_get_pin(51) +#define io51_config_input +#define io51_config_pullup +#define io51_get_input 0 +#else +#define io51_config_output +#define io51_set_output +#define io51_clear_output +#define io51_toggle_output +#define io51_get_output 0 +#define io51_config_input +#define io51_config_pullup +#define io51_get_input 0 +#endif +#if ASSERT_PIN_IO(52) +#define io52_config_output mcu_config_output(52) +#define io52_set_output mcu_set_output(52) +#define io52_clear_output mcu_clear_output(52) +#define io52_toggle_output mcu_toggle_output(52) +#define io52_get_output mcu_get_output(52) +#define io52_config_input mcu_config_input(52) +#define io52_config_pullup mcu_config_pullup(52) +#define io52_get_input mcu_get_input(52) +#elif ASSERT_PIN_EXTENDED(52) +#define io52_config_output +#define io52_set_output ic74hc595_set_pin(52);ic74hc595_shift_io_pins() +#define io52_clear_output ic74hc595_clear_pin(52);ic74hc595_shift_io_pins() +#define io52_toggle_output ic74hc595_toggle_pin(52);ic74hc595_shift_io_pins() +#define io52_get_output ic74hc595_get_pin(52) +#define io52_config_input +#define io52_config_pullup +#define io52_get_input 0 +#else +#define io52_config_output +#define io52_set_output +#define io52_clear_output +#define io52_toggle_output +#define io52_get_output 0 +#define io52_config_input +#define io52_config_pullup +#define io52_get_input 0 +#endif +#if ASSERT_PIN_IO(53) +#define io53_config_output mcu_config_output(53) +#define io53_set_output mcu_set_output(53) +#define io53_clear_output mcu_clear_output(53) +#define io53_toggle_output mcu_toggle_output(53) +#define io53_get_output mcu_get_output(53) +#define io53_config_input mcu_config_input(53) +#define io53_config_pullup mcu_config_pullup(53) +#define io53_get_input mcu_get_input(53) +#elif ASSERT_PIN_EXTENDED(53) +#define io53_config_output +#define io53_set_output ic74hc595_set_pin(53);ic74hc595_shift_io_pins() +#define io53_clear_output ic74hc595_clear_pin(53);ic74hc595_shift_io_pins() +#define io53_toggle_output ic74hc595_toggle_pin(53);ic74hc595_shift_io_pins() +#define io53_get_output ic74hc595_get_pin(53) +#define io53_config_input +#define io53_config_pullup +#define io53_get_input 0 +#else +#define io53_config_output +#define io53_set_output +#define io53_clear_output +#define io53_toggle_output +#define io53_get_output 0 +#define io53_config_input +#define io53_config_pullup +#define io53_get_input 0 +#endif +#if ASSERT_PIN_IO(54) +#define io54_config_output mcu_config_output(54) +#define io54_set_output mcu_set_output(54) +#define io54_clear_output mcu_clear_output(54) +#define io54_toggle_output mcu_toggle_output(54) +#define io54_get_output mcu_get_output(54) +#define io54_config_input mcu_config_input(54) +#define io54_config_pullup mcu_config_pullup(54) +#define io54_get_input mcu_get_input(54) +#elif ASSERT_PIN_EXTENDED(54) +#define io54_config_output +#define io54_set_output ic74hc595_set_pin(54);ic74hc595_shift_io_pins() +#define io54_clear_output ic74hc595_clear_pin(54);ic74hc595_shift_io_pins() +#define io54_toggle_output ic74hc595_toggle_pin(54);ic74hc595_shift_io_pins() +#define io54_get_output ic74hc595_get_pin(54) +#define io54_config_input +#define io54_config_pullup +#define io54_get_input 0 +#else +#define io54_config_output +#define io54_set_output +#define io54_clear_output +#define io54_toggle_output +#define io54_get_output 0 +#define io54_config_input +#define io54_config_pullup +#define io54_get_input 0 +#endif +#if ASSERT_PIN_IO(55) +#define io55_config_output mcu_config_output(55) +#define io55_set_output mcu_set_output(55) +#define io55_clear_output mcu_clear_output(55) +#define io55_toggle_output mcu_toggle_output(55) +#define io55_get_output mcu_get_output(55) +#define io55_config_input mcu_config_input(55) +#define io55_config_pullup mcu_config_pullup(55) +#define io55_get_input mcu_get_input(55) +#elif ASSERT_PIN_EXTENDED(55) +#define io55_config_output +#define io55_set_output ic74hc595_set_pin(55);ic74hc595_shift_io_pins() +#define io55_clear_output ic74hc595_clear_pin(55);ic74hc595_shift_io_pins() +#define io55_toggle_output ic74hc595_toggle_pin(55);ic74hc595_shift_io_pins() +#define io55_get_output ic74hc595_get_pin(55) +#define io55_config_input +#define io55_config_pullup +#define io55_get_input 0 +#else +#define io55_config_output +#define io55_set_output +#define io55_clear_output +#define io55_toggle_output +#define io55_get_output 0 +#define io55_config_input +#define io55_config_pullup +#define io55_get_input 0 +#endif +#if ASSERT_PIN_IO(56) +#define io56_config_output mcu_config_output(56) +#define io56_set_output mcu_set_output(56) +#define io56_clear_output mcu_clear_output(56) +#define io56_toggle_output mcu_toggle_output(56) +#define io56_get_output mcu_get_output(56) +#define io56_config_input mcu_config_input(56) +#define io56_config_pullup mcu_config_pullup(56) +#define io56_get_input mcu_get_input(56) +#elif ASSERT_PIN_EXTENDED(56) +#define io56_config_output +#define io56_set_output ic74hc595_set_pin(56);ic74hc595_shift_io_pins() +#define io56_clear_output ic74hc595_clear_pin(56);ic74hc595_shift_io_pins() +#define io56_toggle_output ic74hc595_toggle_pin(56);ic74hc595_shift_io_pins() +#define io56_get_output ic74hc595_get_pin(56) +#define io56_config_input +#define io56_config_pullup +#define io56_get_input 0 +#else +#define io56_config_output +#define io56_set_output +#define io56_clear_output +#define io56_toggle_output +#define io56_get_output 0 +#define io56_config_input +#define io56_config_pullup +#define io56_get_input 0 +#endif +#if ASSERT_PIN_IO(57) +#define io57_config_output mcu_config_output(57) +#define io57_set_output mcu_set_output(57) +#define io57_clear_output mcu_clear_output(57) +#define io57_toggle_output mcu_toggle_output(57) +#define io57_get_output mcu_get_output(57) +#define io57_config_input mcu_config_input(57) +#define io57_config_pullup mcu_config_pullup(57) +#define io57_get_input mcu_get_input(57) +#elif ASSERT_PIN_EXTENDED(57) +#define io57_config_output +#define io57_set_output ic74hc595_set_pin(57);ic74hc595_shift_io_pins() +#define io57_clear_output ic74hc595_clear_pin(57);ic74hc595_shift_io_pins() +#define io57_toggle_output ic74hc595_toggle_pin(57);ic74hc595_shift_io_pins() +#define io57_get_output ic74hc595_get_pin(57) +#define io57_config_input +#define io57_config_pullup +#define io57_get_input 0 +#else +#define io57_config_output +#define io57_set_output +#define io57_clear_output +#define io57_toggle_output +#define io57_get_output 0 +#define io57_config_input +#define io57_config_pullup +#define io57_get_input 0 +#endif +#if ASSERT_PIN_IO(58) +#define io58_config_output mcu_config_output(58) +#define io58_set_output mcu_set_output(58) +#define io58_clear_output mcu_clear_output(58) +#define io58_toggle_output mcu_toggle_output(58) +#define io58_get_output mcu_get_output(58) +#define io58_config_input mcu_config_input(58) +#define io58_config_pullup mcu_config_pullup(58) +#define io58_get_input mcu_get_input(58) +#elif ASSERT_PIN_EXTENDED(58) +#define io58_config_output +#define io58_set_output ic74hc595_set_pin(58);ic74hc595_shift_io_pins() +#define io58_clear_output ic74hc595_clear_pin(58);ic74hc595_shift_io_pins() +#define io58_toggle_output ic74hc595_toggle_pin(58);ic74hc595_shift_io_pins() +#define io58_get_output ic74hc595_get_pin(58) +#define io58_config_input +#define io58_config_pullup +#define io58_get_input 0 +#else +#define io58_config_output +#define io58_set_output +#define io58_clear_output +#define io58_toggle_output +#define io58_get_output 0 +#define io58_config_input +#define io58_config_pullup +#define io58_get_input 0 +#endif +#if ASSERT_PIN_IO(59) +#define io59_config_output mcu_config_output(59) +#define io59_set_output mcu_set_output(59) +#define io59_clear_output mcu_clear_output(59) +#define io59_toggle_output mcu_toggle_output(59) +#define io59_get_output mcu_get_output(59) +#define io59_config_input mcu_config_input(59) +#define io59_config_pullup mcu_config_pullup(59) +#define io59_get_input mcu_get_input(59) +#elif ASSERT_PIN_EXTENDED(59) +#define io59_config_output +#define io59_set_output ic74hc595_set_pin(59);ic74hc595_shift_io_pins() +#define io59_clear_output ic74hc595_clear_pin(59);ic74hc595_shift_io_pins() +#define io59_toggle_output ic74hc595_toggle_pin(59);ic74hc595_shift_io_pins() +#define io59_get_output ic74hc595_get_pin(59) +#define io59_config_input +#define io59_config_pullup +#define io59_get_input 0 +#else +#define io59_config_output +#define io59_set_output +#define io59_clear_output +#define io59_toggle_output +#define io59_get_output 0 +#define io59_config_input +#define io59_config_pullup +#define io59_get_input 0 +#endif +#if ASSERT_PIN_IO(60) +#define io60_config_output mcu_config_output(60) +#define io60_set_output mcu_set_output(60) +#define io60_clear_output mcu_clear_output(60) +#define io60_toggle_output mcu_toggle_output(60) +#define io60_get_output mcu_get_output(60) +#define io60_config_input mcu_config_input(60) +#define io60_config_pullup mcu_config_pullup(60) +#define io60_get_input mcu_get_input(60) +#elif ASSERT_PIN_EXTENDED(60) +#define io60_config_output +#define io60_set_output ic74hc595_set_pin(60);ic74hc595_shift_io_pins() +#define io60_clear_output ic74hc595_clear_pin(60);ic74hc595_shift_io_pins() +#define io60_toggle_output ic74hc595_toggle_pin(60);ic74hc595_shift_io_pins() +#define io60_get_output ic74hc595_get_pin(60) +#define io60_config_input +#define io60_config_pullup +#define io60_get_input 0 +#else +#define io60_config_output +#define io60_set_output +#define io60_clear_output +#define io60_toggle_output +#define io60_get_output 0 +#define io60_config_input +#define io60_config_pullup +#define io60_get_input 0 +#endif +#if ASSERT_PIN_IO(61) +#define io61_config_output mcu_config_output(61) +#define io61_set_output mcu_set_output(61) +#define io61_clear_output mcu_clear_output(61) +#define io61_toggle_output mcu_toggle_output(61) +#define io61_get_output mcu_get_output(61) +#define io61_config_input mcu_config_input(61) +#define io61_config_pullup mcu_config_pullup(61) +#define io61_get_input mcu_get_input(61) +#elif ASSERT_PIN_EXTENDED(61) +#define io61_config_output +#define io61_set_output ic74hc595_set_pin(61);ic74hc595_shift_io_pins() +#define io61_clear_output ic74hc595_clear_pin(61);ic74hc595_shift_io_pins() +#define io61_toggle_output ic74hc595_toggle_pin(61);ic74hc595_shift_io_pins() +#define io61_get_output ic74hc595_get_pin(61) +#define io61_config_input +#define io61_config_pullup +#define io61_get_input 0 +#else +#define io61_config_output +#define io61_set_output +#define io61_clear_output +#define io61_toggle_output +#define io61_get_output 0 +#define io61_config_input +#define io61_config_pullup +#define io61_get_input 0 +#endif +#if ASSERT_PIN_IO(62) +#define io62_config_output mcu_config_output(62) +#define io62_set_output mcu_set_output(62) +#define io62_clear_output mcu_clear_output(62) +#define io62_toggle_output mcu_toggle_output(62) +#define io62_get_output mcu_get_output(62) +#define io62_config_input mcu_config_input(62) +#define io62_config_pullup mcu_config_pullup(62) +#define io62_get_input mcu_get_input(62) +#elif ASSERT_PIN_EXTENDED(62) +#define io62_config_output +#define io62_set_output ic74hc595_set_pin(62);ic74hc595_shift_io_pins() +#define io62_clear_output ic74hc595_clear_pin(62);ic74hc595_shift_io_pins() +#define io62_toggle_output ic74hc595_toggle_pin(62);ic74hc595_shift_io_pins() +#define io62_get_output ic74hc595_get_pin(62) +#define io62_config_input +#define io62_config_pullup +#define io62_get_input 0 +#else +#define io62_config_output +#define io62_set_output +#define io62_clear_output +#define io62_toggle_output +#define io62_get_output 0 +#define io62_config_input +#define io62_config_pullup +#define io62_get_input 0 +#endif +#if ASSERT_PIN_IO(63) +#define io63_config_output mcu_config_output(63) +#define io63_set_output mcu_set_output(63) +#define io63_clear_output mcu_clear_output(63) +#define io63_toggle_output mcu_toggle_output(63) +#define io63_get_output mcu_get_output(63) +#define io63_config_input mcu_config_input(63) +#define io63_config_pullup mcu_config_pullup(63) +#define io63_get_input mcu_get_input(63) +#elif ASSERT_PIN_EXTENDED(63) +#define io63_config_output +#define io63_set_output ic74hc595_set_pin(63);ic74hc595_shift_io_pins() +#define io63_clear_output ic74hc595_clear_pin(63);ic74hc595_shift_io_pins() +#define io63_toggle_output ic74hc595_toggle_pin(63);ic74hc595_shift_io_pins() +#define io63_get_output ic74hc595_get_pin(63) +#define io63_config_input +#define io63_config_pullup +#define io63_get_input 0 +#else +#define io63_config_output +#define io63_set_output +#define io63_clear_output +#define io63_toggle_output +#define io63_get_output 0 +#define io63_config_input +#define io63_config_pullup +#define io63_get_input 0 +#endif +#if ASSERT_PIN_IO(64) +#define io64_config_output mcu_config_output(64) +#define io64_set_output mcu_set_output(64) +#define io64_clear_output mcu_clear_output(64) +#define io64_toggle_output mcu_toggle_output(64) +#define io64_get_output mcu_get_output(64) +#define io64_config_input mcu_config_input(64) +#define io64_config_pullup mcu_config_pullup(64) +#define io64_get_input mcu_get_input(64) +#elif ASSERT_PIN_EXTENDED(64) +#define io64_config_output +#define io64_set_output ic74hc595_set_pin(64);ic74hc595_shift_io_pins() +#define io64_clear_output ic74hc595_clear_pin(64);ic74hc595_shift_io_pins() +#define io64_toggle_output ic74hc595_toggle_pin(64);ic74hc595_shift_io_pins() +#define io64_get_output ic74hc595_get_pin(64) +#define io64_config_input +#define io64_config_pullup +#define io64_get_input 0 +#else +#define io64_config_output +#define io64_set_output +#define io64_clear_output +#define io64_toggle_output +#define io64_get_output 0 +#define io64_config_input +#define io64_config_pullup +#define io64_get_input 0 +#endif +#if ASSERT_PIN_IO(65) +#define io65_config_output mcu_config_output(65) +#define io65_set_output mcu_set_output(65) +#define io65_clear_output mcu_clear_output(65) +#define io65_toggle_output mcu_toggle_output(65) +#define io65_get_output mcu_get_output(65) +#define io65_config_input mcu_config_input(65) +#define io65_config_pullup mcu_config_pullup(65) +#define io65_get_input mcu_get_input(65) +#elif ASSERT_PIN_EXTENDED(65) +#define io65_config_output +#define io65_set_output ic74hc595_set_pin(65);ic74hc595_shift_io_pins() +#define io65_clear_output ic74hc595_clear_pin(65);ic74hc595_shift_io_pins() +#define io65_toggle_output ic74hc595_toggle_pin(65);ic74hc595_shift_io_pins() +#define io65_get_output ic74hc595_get_pin(65) +#define io65_config_input +#define io65_config_pullup +#define io65_get_input 0 +#else +#define io65_config_output +#define io65_set_output +#define io65_clear_output +#define io65_toggle_output +#define io65_get_output 0 +#define io65_config_input +#define io65_config_pullup +#define io65_get_input 0 +#endif +#if ASSERT_PIN_IO(66) +#define io66_config_output mcu_config_output(66) +#define io66_set_output mcu_set_output(66) +#define io66_clear_output mcu_clear_output(66) +#define io66_toggle_output mcu_toggle_output(66) +#define io66_get_output mcu_get_output(66) +#define io66_config_input mcu_config_input(66) +#define io66_config_pullup mcu_config_pullup(66) +#define io66_get_input mcu_get_input(66) +#elif ASSERT_PIN_EXTENDED(66) +#define io66_config_output +#define io66_set_output ic74hc595_set_pin(66);ic74hc595_shift_io_pins() +#define io66_clear_output ic74hc595_clear_pin(66);ic74hc595_shift_io_pins() +#define io66_toggle_output ic74hc595_toggle_pin(66);ic74hc595_shift_io_pins() +#define io66_get_output ic74hc595_get_pin(66) +#define io66_config_input +#define io66_config_pullup +#define io66_get_input 0 +#else +#define io66_config_output +#define io66_set_output +#define io66_clear_output +#define io66_toggle_output +#define io66_get_output 0 +#define io66_config_input +#define io66_config_pullup +#define io66_get_input 0 +#endif +#if ASSERT_PIN_IO(67) +#define io67_config_output mcu_config_output(67) +#define io67_set_output mcu_set_output(67) +#define io67_clear_output mcu_clear_output(67) +#define io67_toggle_output mcu_toggle_output(67) +#define io67_get_output mcu_get_output(67) +#define io67_config_input mcu_config_input(67) +#define io67_config_pullup mcu_config_pullup(67) +#define io67_get_input mcu_get_input(67) +#elif ASSERT_PIN_EXTENDED(67) +#define io67_config_output +#define io67_set_output ic74hc595_set_pin(67);ic74hc595_shift_io_pins() +#define io67_clear_output ic74hc595_clear_pin(67);ic74hc595_shift_io_pins() +#define io67_toggle_output ic74hc595_toggle_pin(67);ic74hc595_shift_io_pins() +#define io67_get_output ic74hc595_get_pin(67) +#define io67_config_input +#define io67_config_pullup +#define io67_get_input 0 +#else +#define io67_config_output +#define io67_set_output +#define io67_clear_output +#define io67_toggle_output +#define io67_get_output 0 +#define io67_config_input +#define io67_config_pullup +#define io67_get_input 0 +#endif +#if ASSERT_PIN_IO(68) +#define io68_config_output mcu_config_output(68) +#define io68_set_output mcu_set_output(68) +#define io68_clear_output mcu_clear_output(68) +#define io68_toggle_output mcu_toggle_output(68) +#define io68_get_output mcu_get_output(68) +#define io68_config_input mcu_config_input(68) +#define io68_config_pullup mcu_config_pullup(68) +#define io68_get_input mcu_get_input(68) +#elif ASSERT_PIN_EXTENDED(68) +#define io68_config_output +#define io68_set_output ic74hc595_set_pin(68);ic74hc595_shift_io_pins() +#define io68_clear_output ic74hc595_clear_pin(68);ic74hc595_shift_io_pins() +#define io68_toggle_output ic74hc595_toggle_pin(68);ic74hc595_shift_io_pins() +#define io68_get_output ic74hc595_get_pin(68) +#define io68_config_input +#define io68_config_pullup +#define io68_get_input 0 +#else +#define io68_config_output +#define io68_set_output +#define io68_clear_output +#define io68_toggle_output +#define io68_get_output 0 +#define io68_config_input +#define io68_config_pullup +#define io68_get_input 0 +#endif +#if ASSERT_PIN_IO(69) +#define io69_config_output mcu_config_output(69) +#define io69_set_output mcu_set_output(69) +#define io69_clear_output mcu_clear_output(69) +#define io69_toggle_output mcu_toggle_output(69) +#define io69_get_output mcu_get_output(69) +#define io69_config_input mcu_config_input(69) +#define io69_config_pullup mcu_config_pullup(69) +#define io69_get_input mcu_get_input(69) +#elif ASSERT_PIN_EXTENDED(69) +#define io69_config_output +#define io69_set_output ic74hc595_set_pin(69);ic74hc595_shift_io_pins() +#define io69_clear_output ic74hc595_clear_pin(69);ic74hc595_shift_io_pins() +#define io69_toggle_output ic74hc595_toggle_pin(69);ic74hc595_shift_io_pins() +#define io69_get_output ic74hc595_get_pin(69) +#define io69_config_input +#define io69_config_pullup +#define io69_get_input 0 +#else +#define io69_config_output +#define io69_set_output +#define io69_clear_output +#define io69_toggle_output +#define io69_get_output 0 +#define io69_config_input +#define io69_config_pullup +#define io69_get_input 0 +#endif +#if ASSERT_PIN_IO(70) +#define io70_config_output mcu_config_output(70) +#define io70_set_output mcu_set_output(70) +#define io70_clear_output mcu_clear_output(70) +#define io70_toggle_output mcu_toggle_output(70) +#define io70_get_output mcu_get_output(70) +#define io70_config_input mcu_config_input(70) +#define io70_config_pullup mcu_config_pullup(70) +#define io70_get_input mcu_get_input(70) +#elif ASSERT_PIN_EXTENDED(70) +#define io70_config_output +#define io70_set_output ic74hc595_set_pin(70);ic74hc595_shift_io_pins() +#define io70_clear_output ic74hc595_clear_pin(70);ic74hc595_shift_io_pins() +#define io70_toggle_output ic74hc595_toggle_pin(70);ic74hc595_shift_io_pins() +#define io70_get_output ic74hc595_get_pin(70) +#define io70_config_input +#define io70_config_pullup +#define io70_get_input 0 +#else +#define io70_config_output +#define io70_set_output +#define io70_clear_output +#define io70_toggle_output +#define io70_get_output 0 +#define io70_config_input +#define io70_config_pullup +#define io70_get_input 0 +#endif +#if ASSERT_PIN_IO(71) +#define io71_config_output mcu_config_output(71) +#define io71_set_output mcu_set_output(71) +#define io71_clear_output mcu_clear_output(71) +#define io71_toggle_output mcu_toggle_output(71) +#define io71_get_output mcu_get_output(71) +#define io71_config_input mcu_config_input(71) +#define io71_config_pullup mcu_config_pullup(71) +#define io71_get_input mcu_get_input(71) +#elif ASSERT_PIN_EXTENDED(71) +#define io71_config_output +#define io71_set_output ic74hc595_set_pin(71);ic74hc595_shift_io_pins() +#define io71_clear_output ic74hc595_clear_pin(71);ic74hc595_shift_io_pins() +#define io71_toggle_output ic74hc595_toggle_pin(71);ic74hc595_shift_io_pins() +#define io71_get_output ic74hc595_get_pin(71) +#define io71_config_input +#define io71_config_pullup +#define io71_get_input 0 +#else +#define io71_config_output +#define io71_set_output +#define io71_clear_output +#define io71_toggle_output +#define io71_get_output 0 +#define io71_config_input +#define io71_config_pullup +#define io71_get_input 0 +#endif +#if ASSERT_PIN_IO(72) +#define io72_config_output mcu_config_output(72) +#define io72_set_output mcu_set_output(72) +#define io72_clear_output mcu_clear_output(72) +#define io72_toggle_output mcu_toggle_output(72) +#define io72_get_output mcu_get_output(72) +#define io72_config_input mcu_config_input(72) +#define io72_config_pullup mcu_config_pullup(72) +#define io72_get_input mcu_get_input(72) +#elif ASSERT_PIN_EXTENDED(72) +#define io72_config_output +#define io72_set_output ic74hc595_set_pin(72);ic74hc595_shift_io_pins() +#define io72_clear_output ic74hc595_clear_pin(72);ic74hc595_shift_io_pins() +#define io72_toggle_output ic74hc595_toggle_pin(72);ic74hc595_shift_io_pins() +#define io72_get_output ic74hc595_get_pin(72) +#define io72_config_input +#define io72_config_pullup +#define io72_get_input 0 +#else +#define io72_config_output +#define io72_set_output +#define io72_clear_output +#define io72_toggle_output +#define io72_get_output 0 +#define io72_config_input +#define io72_config_pullup +#define io72_get_input 0 +#endif +#if ASSERT_PIN_IO(73) +#define io73_config_output mcu_config_output(73) +#define io73_set_output mcu_set_output(73) +#define io73_clear_output mcu_clear_output(73) +#define io73_toggle_output mcu_toggle_output(73) +#define io73_get_output mcu_get_output(73) +#define io73_config_input mcu_config_input(73) +#define io73_config_pullup mcu_config_pullup(73) +#define io73_get_input mcu_get_input(73) +#elif ASSERT_PIN_EXTENDED(73) +#define io73_config_output +#define io73_set_output ic74hc595_set_pin(73);ic74hc595_shift_io_pins() +#define io73_clear_output ic74hc595_clear_pin(73);ic74hc595_shift_io_pins() +#define io73_toggle_output ic74hc595_toggle_pin(73);ic74hc595_shift_io_pins() +#define io73_get_output ic74hc595_get_pin(73) +#define io73_config_input +#define io73_config_pullup +#define io73_get_input 0 +#else +#define io73_config_output +#define io73_set_output +#define io73_clear_output +#define io73_toggle_output +#define io73_get_output 0 +#define io73_config_input +#define io73_config_pullup +#define io73_get_input 0 +#endif +#if ASSERT_PIN_IO(74) +#define io74_config_output mcu_config_output(74) +#define io74_set_output mcu_set_output(74) +#define io74_clear_output mcu_clear_output(74) +#define io74_toggle_output mcu_toggle_output(74) +#define io74_get_output mcu_get_output(74) +#define io74_config_input mcu_config_input(74) +#define io74_config_pullup mcu_config_pullup(74) +#define io74_get_input mcu_get_input(74) +#elif ASSERT_PIN_EXTENDED(74) +#define io74_config_output +#define io74_set_output ic74hc595_set_pin(74);ic74hc595_shift_io_pins() +#define io74_clear_output ic74hc595_clear_pin(74);ic74hc595_shift_io_pins() +#define io74_toggle_output ic74hc595_toggle_pin(74);ic74hc595_shift_io_pins() +#define io74_get_output ic74hc595_get_pin(74) +#define io74_config_input +#define io74_config_pullup +#define io74_get_input 0 +#else +#define io74_config_output +#define io74_set_output +#define io74_clear_output +#define io74_toggle_output +#define io74_get_output 0 +#define io74_config_input +#define io74_config_pullup +#define io74_get_input 0 +#endif +#if ASSERT_PIN_IO(75) +#define io75_config_output mcu_config_output(75) +#define io75_set_output mcu_set_output(75) +#define io75_clear_output mcu_clear_output(75) +#define io75_toggle_output mcu_toggle_output(75) +#define io75_get_output mcu_get_output(75) +#define io75_config_input mcu_config_input(75) +#define io75_config_pullup mcu_config_pullup(75) +#define io75_get_input mcu_get_input(75) +#elif ASSERT_PIN_EXTENDED(75) +#define io75_config_output +#define io75_set_output ic74hc595_set_pin(75);ic74hc595_shift_io_pins() +#define io75_clear_output ic74hc595_clear_pin(75);ic74hc595_shift_io_pins() +#define io75_toggle_output ic74hc595_toggle_pin(75);ic74hc595_shift_io_pins() +#define io75_get_output ic74hc595_get_pin(75) +#define io75_config_input +#define io75_config_pullup +#define io75_get_input 0 +#else +#define io75_config_output +#define io75_set_output +#define io75_clear_output +#define io75_toggle_output +#define io75_get_output 0 +#define io75_config_input +#define io75_config_pullup +#define io75_get_input 0 +#endif +#if ASSERT_PIN_IO(76) +#define io76_config_output mcu_config_output(76) +#define io76_set_output mcu_set_output(76) +#define io76_clear_output mcu_clear_output(76) +#define io76_toggle_output mcu_toggle_output(76) +#define io76_get_output mcu_get_output(76) +#define io76_config_input mcu_config_input(76) +#define io76_config_pullup mcu_config_pullup(76) +#define io76_get_input mcu_get_input(76) +#elif ASSERT_PIN_EXTENDED(76) +#define io76_config_output +#define io76_set_output ic74hc595_set_pin(76);ic74hc595_shift_io_pins() +#define io76_clear_output ic74hc595_clear_pin(76);ic74hc595_shift_io_pins() +#define io76_toggle_output ic74hc595_toggle_pin(76);ic74hc595_shift_io_pins() +#define io76_get_output ic74hc595_get_pin(76) +#define io76_config_input +#define io76_config_pullup +#define io76_get_input 0 +#else +#define io76_config_output +#define io76_set_output +#define io76_clear_output +#define io76_toggle_output +#define io76_get_output 0 +#define io76_config_input +#define io76_config_pullup +#define io76_get_input 0 +#endif +#if ASSERT_PIN_IO(77) +#define io77_config_output mcu_config_output(77) +#define io77_set_output mcu_set_output(77) +#define io77_clear_output mcu_clear_output(77) +#define io77_toggle_output mcu_toggle_output(77) +#define io77_get_output mcu_get_output(77) +#define io77_config_input mcu_config_input(77) +#define io77_config_pullup mcu_config_pullup(77) +#define io77_get_input mcu_get_input(77) +#elif ASSERT_PIN_EXTENDED(77) +#define io77_config_output +#define io77_set_output ic74hc595_set_pin(77);ic74hc595_shift_io_pins() +#define io77_clear_output ic74hc595_clear_pin(77);ic74hc595_shift_io_pins() +#define io77_toggle_output ic74hc595_toggle_pin(77);ic74hc595_shift_io_pins() +#define io77_get_output ic74hc595_get_pin(77) +#define io77_config_input +#define io77_config_pullup +#define io77_get_input 0 +#else +#define io77_config_output +#define io77_set_output +#define io77_clear_output +#define io77_toggle_output +#define io77_get_output 0 +#define io77_config_input +#define io77_config_pullup +#define io77_get_input 0 +#endif +#if ASSERT_PIN_IO(78) +#define io78_config_output mcu_config_output(78) +#define io78_set_output mcu_set_output(78) +#define io78_clear_output mcu_clear_output(78) +#define io78_toggle_output mcu_toggle_output(78) +#define io78_get_output mcu_get_output(78) +#define io78_config_input mcu_config_input(78) +#define io78_config_pullup mcu_config_pullup(78) +#define io78_get_input mcu_get_input(78) +#elif ASSERT_PIN_EXTENDED(78) +#define io78_config_output +#define io78_set_output ic74hc595_set_pin(78);ic74hc595_shift_io_pins() +#define io78_clear_output ic74hc595_clear_pin(78);ic74hc595_shift_io_pins() +#define io78_toggle_output ic74hc595_toggle_pin(78);ic74hc595_shift_io_pins() +#define io78_get_output ic74hc595_get_pin(78) +#define io78_config_input +#define io78_config_pullup +#define io78_get_input 0 +#else +#define io78_config_output +#define io78_set_output +#define io78_clear_output +#define io78_toggle_output +#define io78_get_output 0 +#define io78_config_input +#define io78_config_pullup +#define io78_get_input 0 +#endif +#if ASSERT_PIN_IO(100) +#define io100_config_output mcu_config_output(100) +#define io100_set_output mcu_set_output(100) +#define io100_clear_output mcu_clear_output(100) +#define io100_toggle_output mcu_toggle_output(100) +#define io100_get_output mcu_get_output(100) +#define io100_config_input mcu_config_input(100) +#define io100_config_pullup mcu_config_pullup(100) +#define io100_get_input mcu_get_input(100) +#elif ASSERT_PIN_EXTENDED(100) +#define io100_config_output +#define io100_set_output ic74hc595_set_pin(100);ic74hc595_shift_io_pins() +#define io100_clear_output ic74hc595_clear_pin(100);ic74hc595_shift_io_pins() +#define io100_toggle_output ic74hc595_toggle_pin(100);ic74hc595_shift_io_pins() +#define io100_get_output ic74hc595_get_pin(100) +#define io100_config_input +#define io100_config_pullup +#define io100_get_input 0 +#else +#define io100_config_output +#define io100_set_output +#define io100_clear_output +#define io100_toggle_output +#define io100_get_output 0 +#define io100_config_input +#define io100_config_pullup +#define io100_get_input 0 +#endif +#if ASSERT_PIN_IO(101) +#define io101_config_output mcu_config_output(101) +#define io101_set_output mcu_set_output(101) +#define io101_clear_output mcu_clear_output(101) +#define io101_toggle_output mcu_toggle_output(101) +#define io101_get_output mcu_get_output(101) +#define io101_config_input mcu_config_input(101) +#define io101_config_pullup mcu_config_pullup(101) +#define io101_get_input mcu_get_input(101) +#elif ASSERT_PIN_EXTENDED(101) +#define io101_config_output +#define io101_set_output ic74hc595_set_pin(101);ic74hc595_shift_io_pins() +#define io101_clear_output ic74hc595_clear_pin(101);ic74hc595_shift_io_pins() +#define io101_toggle_output ic74hc595_toggle_pin(101);ic74hc595_shift_io_pins() +#define io101_get_output ic74hc595_get_pin(101) +#define io101_config_input +#define io101_config_pullup +#define io101_get_input 0 +#else +#define io101_config_output +#define io101_set_output +#define io101_clear_output +#define io101_toggle_output +#define io101_get_output 0 +#define io101_config_input +#define io101_config_pullup +#define io101_get_input 0 +#endif +#if ASSERT_PIN_IO(102) +#define io102_config_output mcu_config_output(102) +#define io102_set_output mcu_set_output(102) +#define io102_clear_output mcu_clear_output(102) +#define io102_toggle_output mcu_toggle_output(102) +#define io102_get_output mcu_get_output(102) +#define io102_config_input mcu_config_input(102) +#define io102_config_pullup mcu_config_pullup(102) +#define io102_get_input mcu_get_input(102) +#elif ASSERT_PIN_EXTENDED(102) +#define io102_config_output +#define io102_set_output ic74hc595_set_pin(102);ic74hc595_shift_io_pins() +#define io102_clear_output ic74hc595_clear_pin(102);ic74hc595_shift_io_pins() +#define io102_toggle_output ic74hc595_toggle_pin(102);ic74hc595_shift_io_pins() +#define io102_get_output ic74hc595_get_pin(102) +#define io102_config_input +#define io102_config_pullup +#define io102_get_input 0 +#else +#define io102_config_output +#define io102_set_output +#define io102_clear_output +#define io102_toggle_output +#define io102_get_output 0 +#define io102_config_input +#define io102_config_pullup +#define io102_get_input 0 +#endif +#if ASSERT_PIN_IO(103) +#define io103_config_output mcu_config_output(103) +#define io103_set_output mcu_set_output(103) +#define io103_clear_output mcu_clear_output(103) +#define io103_toggle_output mcu_toggle_output(103) +#define io103_get_output mcu_get_output(103) +#define io103_config_input mcu_config_input(103) +#define io103_config_pullup mcu_config_pullup(103) +#define io103_get_input mcu_get_input(103) +#elif ASSERT_PIN_EXTENDED(103) +#define io103_config_output +#define io103_set_output ic74hc595_set_pin(103);ic74hc595_shift_io_pins() +#define io103_clear_output ic74hc595_clear_pin(103);ic74hc595_shift_io_pins() +#define io103_toggle_output ic74hc595_toggle_pin(103);ic74hc595_shift_io_pins() +#define io103_get_output ic74hc595_get_pin(103) +#define io103_config_input +#define io103_config_pullup +#define io103_get_input 0 +#else +#define io103_config_output +#define io103_set_output +#define io103_clear_output +#define io103_toggle_output +#define io103_get_output 0 +#define io103_config_input +#define io103_config_pullup +#define io103_get_input 0 +#endif +#if ASSERT_PIN_IO(104) +#define io104_config_output mcu_config_output(104) +#define io104_set_output mcu_set_output(104) +#define io104_clear_output mcu_clear_output(104) +#define io104_toggle_output mcu_toggle_output(104) +#define io104_get_output mcu_get_output(104) +#define io104_config_input mcu_config_input(104) +#define io104_config_pullup mcu_config_pullup(104) +#define io104_get_input mcu_get_input(104) +#elif ASSERT_PIN_EXTENDED(104) +#define io104_config_output +#define io104_set_output ic74hc595_set_pin(104);ic74hc595_shift_io_pins() +#define io104_clear_output ic74hc595_clear_pin(104);ic74hc595_shift_io_pins() +#define io104_toggle_output ic74hc595_toggle_pin(104);ic74hc595_shift_io_pins() +#define io104_get_output ic74hc595_get_pin(104) +#define io104_config_input +#define io104_config_pullup +#define io104_get_input 0 +#else +#define io104_config_output +#define io104_set_output +#define io104_clear_output +#define io104_toggle_output +#define io104_get_output 0 +#define io104_config_input +#define io104_config_pullup +#define io104_get_input 0 +#endif +#if ASSERT_PIN_IO(105) +#define io105_config_output mcu_config_output(105) +#define io105_set_output mcu_set_output(105) +#define io105_clear_output mcu_clear_output(105) +#define io105_toggle_output mcu_toggle_output(105) +#define io105_get_output mcu_get_output(105) +#define io105_config_input mcu_config_input(105) +#define io105_config_pullup mcu_config_pullup(105) +#define io105_get_input mcu_get_input(105) +#elif ASSERT_PIN_EXTENDED(105) +#define io105_config_output +#define io105_set_output ic74hc595_set_pin(105);ic74hc595_shift_io_pins() +#define io105_clear_output ic74hc595_clear_pin(105);ic74hc595_shift_io_pins() +#define io105_toggle_output ic74hc595_toggle_pin(105);ic74hc595_shift_io_pins() +#define io105_get_output ic74hc595_get_pin(105) +#define io105_config_input +#define io105_config_pullup +#define io105_get_input 0 +#else +#define io105_config_output +#define io105_set_output +#define io105_clear_output +#define io105_toggle_output +#define io105_get_output 0 +#define io105_config_input +#define io105_config_pullup +#define io105_get_input 0 +#endif +#if ASSERT_PIN_IO(106) +#define io106_config_output mcu_config_output(106) +#define io106_set_output mcu_set_output(106) +#define io106_clear_output mcu_clear_output(106) +#define io106_toggle_output mcu_toggle_output(106) +#define io106_get_output mcu_get_output(106) +#define io106_config_input mcu_config_input(106) +#define io106_config_pullup mcu_config_pullup(106) +#define io106_get_input mcu_get_input(106) +#elif ASSERT_PIN_EXTENDED(106) +#define io106_config_output +#define io106_set_output ic74hc595_set_pin(106);ic74hc595_shift_io_pins() +#define io106_clear_output ic74hc595_clear_pin(106);ic74hc595_shift_io_pins() +#define io106_toggle_output ic74hc595_toggle_pin(106);ic74hc595_shift_io_pins() +#define io106_get_output ic74hc595_get_pin(106) +#define io106_config_input +#define io106_config_pullup +#define io106_get_input 0 +#else +#define io106_config_output +#define io106_set_output +#define io106_clear_output +#define io106_toggle_output +#define io106_get_output 0 +#define io106_config_input +#define io106_config_pullup +#define io106_get_input 0 +#endif +#if ASSERT_PIN_IO(107) +#define io107_config_output mcu_config_output(107) +#define io107_set_output mcu_set_output(107) +#define io107_clear_output mcu_clear_output(107) +#define io107_toggle_output mcu_toggle_output(107) +#define io107_get_output mcu_get_output(107) +#define io107_config_input mcu_config_input(107) +#define io107_config_pullup mcu_config_pullup(107) +#define io107_get_input mcu_get_input(107) +#elif ASSERT_PIN_EXTENDED(107) +#define io107_config_output +#define io107_set_output ic74hc595_set_pin(107);ic74hc595_shift_io_pins() +#define io107_clear_output ic74hc595_clear_pin(107);ic74hc595_shift_io_pins() +#define io107_toggle_output ic74hc595_toggle_pin(107);ic74hc595_shift_io_pins() +#define io107_get_output ic74hc595_get_pin(107) +#define io107_config_input +#define io107_config_pullup +#define io107_get_input 0 +#else +#define io107_config_output +#define io107_set_output +#define io107_clear_output +#define io107_toggle_output +#define io107_get_output 0 +#define io107_config_input +#define io107_config_pullup +#define io107_get_input 0 +#endif +#if ASSERT_PIN_IO(108) +#define io108_config_output mcu_config_output(108) +#define io108_set_output mcu_set_output(108) +#define io108_clear_output mcu_clear_output(108) +#define io108_toggle_output mcu_toggle_output(108) +#define io108_get_output mcu_get_output(108) +#define io108_config_input mcu_config_input(108) +#define io108_config_pullup mcu_config_pullup(108) +#define io108_get_input mcu_get_input(108) +#elif ASSERT_PIN_EXTENDED(108) +#define io108_config_output +#define io108_set_output ic74hc595_set_pin(108);ic74hc595_shift_io_pins() +#define io108_clear_output ic74hc595_clear_pin(108);ic74hc595_shift_io_pins() +#define io108_toggle_output ic74hc595_toggle_pin(108);ic74hc595_shift_io_pins() +#define io108_get_output ic74hc595_get_pin(108) +#define io108_config_input +#define io108_config_pullup +#define io108_get_input 0 +#else +#define io108_config_output +#define io108_set_output +#define io108_clear_output +#define io108_toggle_output +#define io108_get_output 0 +#define io108_config_input +#define io108_config_pullup +#define io108_get_input 0 +#endif +#if ASSERT_PIN_IO(109) +#define io109_config_output mcu_config_output(109) +#define io109_set_output mcu_set_output(109) +#define io109_clear_output mcu_clear_output(109) +#define io109_toggle_output mcu_toggle_output(109) +#define io109_get_output mcu_get_output(109) +#define io109_config_input mcu_config_input(109) +#define io109_config_pullup mcu_config_pullup(109) +#define io109_get_input mcu_get_input(109) +#elif ASSERT_PIN_EXTENDED(109) +#define io109_config_output +#define io109_set_output ic74hc595_set_pin(109);ic74hc595_shift_io_pins() +#define io109_clear_output ic74hc595_clear_pin(109);ic74hc595_shift_io_pins() +#define io109_toggle_output ic74hc595_toggle_pin(109);ic74hc595_shift_io_pins() +#define io109_get_output ic74hc595_get_pin(109) +#define io109_config_input +#define io109_config_pullup +#define io109_get_input 0 +#else +#define io109_config_output +#define io109_set_output +#define io109_clear_output +#define io109_toggle_output +#define io109_get_output 0 +#define io109_config_input +#define io109_config_pullup +#define io109_get_input 0 +#endif +#if ASSERT_PIN_IO(110) +#define io110_config_output mcu_config_output(110) +#define io110_set_output mcu_set_output(110) +#define io110_clear_output mcu_clear_output(110) +#define io110_toggle_output mcu_toggle_output(110) +#define io110_get_output mcu_get_output(110) +#define io110_config_input mcu_config_input(110) +#define io110_config_pullup mcu_config_pullup(110) +#define io110_get_input mcu_get_input(110) +#elif ASSERT_PIN_EXTENDED(110) +#define io110_config_output +#define io110_set_output ic74hc595_set_pin(110);ic74hc595_shift_io_pins() +#define io110_clear_output ic74hc595_clear_pin(110);ic74hc595_shift_io_pins() +#define io110_toggle_output ic74hc595_toggle_pin(110);ic74hc595_shift_io_pins() +#define io110_get_output ic74hc595_get_pin(110) +#define io110_config_input +#define io110_config_pullup +#define io110_get_input 0 +#else +#define io110_config_output +#define io110_set_output +#define io110_clear_output +#define io110_toggle_output +#define io110_get_output 0 +#define io110_config_input +#define io110_config_pullup +#define io110_get_input 0 +#endif +#if ASSERT_PIN_IO(111) +#define io111_config_output mcu_config_output(111) +#define io111_set_output mcu_set_output(111) +#define io111_clear_output mcu_clear_output(111) +#define io111_toggle_output mcu_toggle_output(111) +#define io111_get_output mcu_get_output(111) +#define io111_config_input mcu_config_input(111) +#define io111_config_pullup mcu_config_pullup(111) +#define io111_get_input mcu_get_input(111) +#elif ASSERT_PIN_EXTENDED(111) +#define io111_config_output +#define io111_set_output ic74hc595_set_pin(111);ic74hc595_shift_io_pins() +#define io111_clear_output ic74hc595_clear_pin(111);ic74hc595_shift_io_pins() +#define io111_toggle_output ic74hc595_toggle_pin(111);ic74hc595_shift_io_pins() +#define io111_get_output ic74hc595_get_pin(111) +#define io111_config_input +#define io111_config_pullup +#define io111_get_input 0 +#else +#define io111_config_output +#define io111_set_output +#define io111_clear_output +#define io111_toggle_output +#define io111_get_output 0 +#define io111_config_input +#define io111_config_pullup +#define io111_get_input 0 +#endif +#if ASSERT_PIN_IO(112) +#define io112_config_output mcu_config_output(112) +#define io112_set_output mcu_set_output(112) +#define io112_clear_output mcu_clear_output(112) +#define io112_toggle_output mcu_toggle_output(112) +#define io112_get_output mcu_get_output(112) +#define io112_config_input mcu_config_input(112) +#define io112_config_pullup mcu_config_pullup(112) +#define io112_get_input mcu_get_input(112) +#elif ASSERT_PIN_EXTENDED(112) +#define io112_config_output +#define io112_set_output ic74hc595_set_pin(112);ic74hc595_shift_io_pins() +#define io112_clear_output ic74hc595_clear_pin(112);ic74hc595_shift_io_pins() +#define io112_toggle_output ic74hc595_toggle_pin(112);ic74hc595_shift_io_pins() +#define io112_get_output ic74hc595_get_pin(112) +#define io112_config_input +#define io112_config_pullup +#define io112_get_input 0 +#else +#define io112_config_output +#define io112_set_output +#define io112_clear_output +#define io112_toggle_output +#define io112_get_output 0 +#define io112_config_input +#define io112_config_pullup +#define io112_get_input 0 +#endif +#if ASSERT_PIN_IO(113) +#define io113_config_output mcu_config_output(113) +#define io113_set_output mcu_set_output(113) +#define io113_clear_output mcu_clear_output(113) +#define io113_toggle_output mcu_toggle_output(113) +#define io113_get_output mcu_get_output(113) +#define io113_config_input mcu_config_input(113) +#define io113_config_pullup mcu_config_pullup(113) +#define io113_get_input mcu_get_input(113) +#elif ASSERT_PIN_EXTENDED(113) +#define io113_config_output +#define io113_set_output ic74hc595_set_pin(113);ic74hc595_shift_io_pins() +#define io113_clear_output ic74hc595_clear_pin(113);ic74hc595_shift_io_pins() +#define io113_toggle_output ic74hc595_toggle_pin(113);ic74hc595_shift_io_pins() +#define io113_get_output ic74hc595_get_pin(113) +#define io113_config_input +#define io113_config_pullup +#define io113_get_input 0 +#else +#define io113_config_output +#define io113_set_output +#define io113_clear_output +#define io113_toggle_output +#define io113_get_output 0 +#define io113_config_input +#define io113_config_pullup +#define io113_get_input 0 +#endif +#if ASSERT_PIN_IO(114) +#define io114_config_output mcu_config_output(114) +#define io114_set_output mcu_set_output(114) +#define io114_clear_output mcu_clear_output(114) +#define io114_toggle_output mcu_toggle_output(114) +#define io114_get_output mcu_get_output(114) +#define io114_config_input mcu_config_input(114) +#define io114_config_pullup mcu_config_pullup(114) +#define io114_get_input mcu_get_input(114) +#elif ASSERT_PIN_EXTENDED(114) +#define io114_config_output +#define io114_set_output ic74hc595_set_pin(114);ic74hc595_shift_io_pins() +#define io114_clear_output ic74hc595_clear_pin(114);ic74hc595_shift_io_pins() +#define io114_toggle_output ic74hc595_toggle_pin(114);ic74hc595_shift_io_pins() +#define io114_get_output ic74hc595_get_pin(114) +#define io114_config_input +#define io114_config_pullup +#define io114_get_input 0 +#else +#define io114_config_output +#define io114_set_output +#define io114_clear_output +#define io114_toggle_output +#define io114_get_output 0 +#define io114_config_input +#define io114_config_pullup +#define io114_get_input 0 +#endif +#if ASSERT_PIN_IO(115) +#define io115_config_output mcu_config_output(115) +#define io115_set_output mcu_set_output(115) +#define io115_clear_output mcu_clear_output(115) +#define io115_toggle_output mcu_toggle_output(115) +#define io115_get_output mcu_get_output(115) +#define io115_config_input mcu_config_input(115) +#define io115_config_pullup mcu_config_pullup(115) +#define io115_get_input mcu_get_input(115) +#elif ASSERT_PIN_EXTENDED(115) +#define io115_config_output +#define io115_set_output ic74hc595_set_pin(115);ic74hc595_shift_io_pins() +#define io115_clear_output ic74hc595_clear_pin(115);ic74hc595_shift_io_pins() +#define io115_toggle_output ic74hc595_toggle_pin(115);ic74hc595_shift_io_pins() +#define io115_get_output ic74hc595_get_pin(115) +#define io115_config_input +#define io115_config_pullup +#define io115_get_input 0 +#else +#define io115_config_output +#define io115_set_output +#define io115_clear_output +#define io115_toggle_output +#define io115_get_output 0 +#define io115_config_input +#define io115_config_pullup +#define io115_get_input 0 +#endif +#if ASSERT_PIN_IO(116) +#define io116_config_output mcu_config_output(116) +#define io116_set_output mcu_set_output(116) +#define io116_clear_output mcu_clear_output(116) +#define io116_toggle_output mcu_toggle_output(116) +#define io116_get_output mcu_get_output(116) +#define io116_config_input mcu_config_input(116) +#define io116_config_pullup mcu_config_pullup(116) +#define io116_get_input mcu_get_input(116) +#elif ASSERT_PIN_EXTENDED(116) +#define io116_config_output +#define io116_set_output ic74hc595_set_pin(116);ic74hc595_shift_io_pins() +#define io116_clear_output ic74hc595_clear_pin(116);ic74hc595_shift_io_pins() +#define io116_toggle_output ic74hc595_toggle_pin(116);ic74hc595_shift_io_pins() +#define io116_get_output ic74hc595_get_pin(116) +#define io116_config_input +#define io116_config_pullup +#define io116_get_input 0 +#else +#define io116_config_output +#define io116_set_output +#define io116_clear_output +#define io116_toggle_output +#define io116_get_output 0 +#define io116_config_input +#define io116_config_pullup +#define io116_get_input 0 +#endif +#if ASSERT_PIN_IO(117) +#define io117_config_output mcu_config_output(117) +#define io117_set_output mcu_set_output(117) +#define io117_clear_output mcu_clear_output(117) +#define io117_toggle_output mcu_toggle_output(117) +#define io117_get_output mcu_get_output(117) +#define io117_config_input mcu_config_input(117) +#define io117_config_pullup mcu_config_pullup(117) +#define io117_get_input mcu_get_input(117) +#elif ASSERT_PIN_EXTENDED(117) +#define io117_config_output +#define io117_set_output ic74hc595_set_pin(117);ic74hc595_shift_io_pins() +#define io117_clear_output ic74hc595_clear_pin(117);ic74hc595_shift_io_pins() +#define io117_toggle_output ic74hc595_toggle_pin(117);ic74hc595_shift_io_pins() +#define io117_get_output ic74hc595_get_pin(117) +#define io117_config_input +#define io117_config_pullup +#define io117_get_input 0 +#else +#define io117_config_output +#define io117_set_output +#define io117_clear_output +#define io117_toggle_output +#define io117_get_output 0 +#define io117_config_input +#define io117_config_pullup +#define io117_get_input 0 +#endif +#if ASSERT_PIN_IO(118) +#define io118_config_output mcu_config_output(118) +#define io118_set_output mcu_set_output(118) +#define io118_clear_output mcu_clear_output(118) +#define io118_toggle_output mcu_toggle_output(118) +#define io118_get_output mcu_get_output(118) +#define io118_config_input mcu_config_input(118) +#define io118_config_pullup mcu_config_pullup(118) +#define io118_get_input mcu_get_input(118) +#elif ASSERT_PIN_EXTENDED(118) +#define io118_config_output +#define io118_set_output ic74hc595_set_pin(118);ic74hc595_shift_io_pins() +#define io118_clear_output ic74hc595_clear_pin(118);ic74hc595_shift_io_pins() +#define io118_toggle_output ic74hc595_toggle_pin(118);ic74hc595_shift_io_pins() +#define io118_get_output ic74hc595_get_pin(118) +#define io118_config_input +#define io118_config_pullup +#define io118_get_input 0 +#else +#define io118_config_output +#define io118_set_output +#define io118_clear_output +#define io118_toggle_output +#define io118_get_output 0 +#define io118_config_input +#define io118_config_pullup +#define io118_get_input 0 +#endif +#if ASSERT_PIN_IO(119) +#define io119_config_output mcu_config_output(119) +#define io119_set_output mcu_set_output(119) +#define io119_clear_output mcu_clear_output(119) +#define io119_toggle_output mcu_toggle_output(119) +#define io119_get_output mcu_get_output(119) +#define io119_config_input mcu_config_input(119) +#define io119_config_pullup mcu_config_pullup(119) +#define io119_get_input mcu_get_input(119) +#elif ASSERT_PIN_EXTENDED(119) +#define io119_config_output +#define io119_set_output ic74hc595_set_pin(119);ic74hc595_shift_io_pins() +#define io119_clear_output ic74hc595_clear_pin(119);ic74hc595_shift_io_pins() +#define io119_toggle_output ic74hc595_toggle_pin(119);ic74hc595_shift_io_pins() +#define io119_get_output ic74hc595_get_pin(119) +#define io119_config_input +#define io119_config_pullup +#define io119_get_input 0 +#else +#define io119_config_output +#define io119_set_output +#define io119_clear_output +#define io119_toggle_output +#define io119_get_output 0 +#define io119_config_input +#define io119_config_pullup +#define io119_get_input 0 +#endif +#if ASSERT_PIN_IO(120) +#define io120_config_output mcu_config_output(120) +#define io120_set_output mcu_set_output(120) +#define io120_clear_output mcu_clear_output(120) +#define io120_toggle_output mcu_toggle_output(120) +#define io120_get_output mcu_get_output(120) +#define io120_config_input mcu_config_input(120) +#define io120_config_pullup mcu_config_pullup(120) +#define io120_get_input mcu_get_input(120) +#elif ASSERT_PIN_EXTENDED(120) +#define io120_config_output +#define io120_set_output ic74hc595_set_pin(120);ic74hc595_shift_io_pins() +#define io120_clear_output ic74hc595_clear_pin(120);ic74hc595_shift_io_pins() +#define io120_toggle_output ic74hc595_toggle_pin(120);ic74hc595_shift_io_pins() +#define io120_get_output ic74hc595_get_pin(120) +#define io120_config_input +#define io120_config_pullup +#define io120_get_input 0 +#else +#define io120_config_output +#define io120_set_output +#define io120_clear_output +#define io120_toggle_output +#define io120_get_output 0 +#define io120_config_input +#define io120_config_pullup +#define io120_get_input 0 +#endif +#if ASSERT_PIN_IO(121) +#define io121_config_output mcu_config_output(121) +#define io121_set_output mcu_set_output(121) +#define io121_clear_output mcu_clear_output(121) +#define io121_toggle_output mcu_toggle_output(121) +#define io121_get_output mcu_get_output(121) +#define io121_config_input mcu_config_input(121) +#define io121_config_pullup mcu_config_pullup(121) +#define io121_get_input mcu_get_input(121) +#elif ASSERT_PIN_EXTENDED(121) +#define io121_config_output +#define io121_set_output ic74hc595_set_pin(121);ic74hc595_shift_io_pins() +#define io121_clear_output ic74hc595_clear_pin(121);ic74hc595_shift_io_pins() +#define io121_toggle_output ic74hc595_toggle_pin(121);ic74hc595_shift_io_pins() +#define io121_get_output ic74hc595_get_pin(121) +#define io121_config_input +#define io121_config_pullup +#define io121_get_input 0 +#else +#define io121_config_output +#define io121_set_output +#define io121_clear_output +#define io121_toggle_output +#define io121_get_output 0 +#define io121_config_input +#define io121_config_pullup +#define io121_get_input 0 +#endif +#if ASSERT_PIN_IO(122) +#define io122_config_output mcu_config_output(122) +#define io122_set_output mcu_set_output(122) +#define io122_clear_output mcu_clear_output(122) +#define io122_toggle_output mcu_toggle_output(122) +#define io122_get_output mcu_get_output(122) +#define io122_config_input mcu_config_input(122) +#define io122_config_pullup mcu_config_pullup(122) +#define io122_get_input mcu_get_input(122) +#elif ASSERT_PIN_EXTENDED(122) +#define io122_config_output +#define io122_set_output ic74hc595_set_pin(122);ic74hc595_shift_io_pins() +#define io122_clear_output ic74hc595_clear_pin(122);ic74hc595_shift_io_pins() +#define io122_toggle_output ic74hc595_toggle_pin(122);ic74hc595_shift_io_pins() +#define io122_get_output ic74hc595_get_pin(122) +#define io122_config_input +#define io122_config_pullup +#define io122_get_input 0 +#else +#define io122_config_output +#define io122_set_output +#define io122_clear_output +#define io122_toggle_output +#define io122_get_output 0 +#define io122_config_input +#define io122_config_pullup +#define io122_get_input 0 +#endif +#if ASSERT_PIN_IO(123) +#define io123_config_output mcu_config_output(123) +#define io123_set_output mcu_set_output(123) +#define io123_clear_output mcu_clear_output(123) +#define io123_toggle_output mcu_toggle_output(123) +#define io123_get_output mcu_get_output(123) +#define io123_config_input mcu_config_input(123) +#define io123_config_pullup mcu_config_pullup(123) +#define io123_get_input mcu_get_input(123) +#elif ASSERT_PIN_EXTENDED(123) +#define io123_config_output +#define io123_set_output ic74hc595_set_pin(123);ic74hc595_shift_io_pins() +#define io123_clear_output ic74hc595_clear_pin(123);ic74hc595_shift_io_pins() +#define io123_toggle_output ic74hc595_toggle_pin(123);ic74hc595_shift_io_pins() +#define io123_get_output ic74hc595_get_pin(123) +#define io123_config_input +#define io123_config_pullup +#define io123_get_input 0 +#else +#define io123_config_output +#define io123_set_output +#define io123_clear_output +#define io123_toggle_output +#define io123_get_output 0 +#define io123_config_input +#define io123_config_pullup +#define io123_get_input 0 +#endif +#if ASSERT_PIN_IO(124) +#define io124_config_output mcu_config_output(124) +#define io124_set_output mcu_set_output(124) +#define io124_clear_output mcu_clear_output(124) +#define io124_toggle_output mcu_toggle_output(124) +#define io124_get_output mcu_get_output(124) +#define io124_config_input mcu_config_input(124) +#define io124_config_pullup mcu_config_pullup(124) +#define io124_get_input mcu_get_input(124) +#elif ASSERT_PIN_EXTENDED(124) +#define io124_config_output +#define io124_set_output ic74hc595_set_pin(124);ic74hc595_shift_io_pins() +#define io124_clear_output ic74hc595_clear_pin(124);ic74hc595_shift_io_pins() +#define io124_toggle_output ic74hc595_toggle_pin(124);ic74hc595_shift_io_pins() +#define io124_get_output ic74hc595_get_pin(124) +#define io124_config_input +#define io124_config_pullup +#define io124_get_input 0 +#else +#define io124_config_output +#define io124_set_output +#define io124_clear_output +#define io124_toggle_output +#define io124_get_output 0 +#define io124_config_input +#define io124_config_pullup +#define io124_get_input 0 +#endif +#if ASSERT_PIN_IO(125) +#define io125_config_output mcu_config_output(125) +#define io125_set_output mcu_set_output(125) +#define io125_clear_output mcu_clear_output(125) +#define io125_toggle_output mcu_toggle_output(125) +#define io125_get_output mcu_get_output(125) +#define io125_config_input mcu_config_input(125) +#define io125_config_pullup mcu_config_pullup(125) +#define io125_get_input mcu_get_input(125) +#elif ASSERT_PIN_EXTENDED(125) +#define io125_config_output +#define io125_set_output ic74hc595_set_pin(125);ic74hc595_shift_io_pins() +#define io125_clear_output ic74hc595_clear_pin(125);ic74hc595_shift_io_pins() +#define io125_toggle_output ic74hc595_toggle_pin(125);ic74hc595_shift_io_pins() +#define io125_get_output ic74hc595_get_pin(125) +#define io125_config_input +#define io125_config_pullup +#define io125_get_input 0 +#else +#define io125_config_output +#define io125_set_output +#define io125_clear_output +#define io125_toggle_output +#define io125_get_output 0 +#define io125_config_input +#define io125_config_pullup +#define io125_get_input 0 +#endif +#if ASSERT_PIN_IO(126) +#define io126_config_output mcu_config_output(126) +#define io126_set_output mcu_set_output(126) +#define io126_clear_output mcu_clear_output(126) +#define io126_toggle_output mcu_toggle_output(126) +#define io126_get_output mcu_get_output(126) +#define io126_config_input mcu_config_input(126) +#define io126_config_pullup mcu_config_pullup(126) +#define io126_get_input mcu_get_input(126) +#elif ASSERT_PIN_EXTENDED(126) +#define io126_config_output +#define io126_set_output ic74hc595_set_pin(126);ic74hc595_shift_io_pins() +#define io126_clear_output ic74hc595_clear_pin(126);ic74hc595_shift_io_pins() +#define io126_toggle_output ic74hc595_toggle_pin(126);ic74hc595_shift_io_pins() +#define io126_get_output ic74hc595_get_pin(126) +#define io126_config_input +#define io126_config_pullup +#define io126_get_input 0 +#else +#define io126_config_output +#define io126_set_output +#define io126_clear_output +#define io126_toggle_output +#define io126_get_output 0 +#define io126_config_input +#define io126_config_pullup +#define io126_get_input 0 +#endif +#if ASSERT_PIN_IO(127) +#define io127_config_output mcu_config_output(127) +#define io127_set_output mcu_set_output(127) +#define io127_clear_output mcu_clear_output(127) +#define io127_toggle_output mcu_toggle_output(127) +#define io127_get_output mcu_get_output(127) +#define io127_config_input mcu_config_input(127) +#define io127_config_pullup mcu_config_pullup(127) +#define io127_get_input mcu_get_input(127) +#elif ASSERT_PIN_EXTENDED(127) +#define io127_config_output +#define io127_set_output ic74hc595_set_pin(127);ic74hc595_shift_io_pins() +#define io127_clear_output ic74hc595_clear_pin(127);ic74hc595_shift_io_pins() +#define io127_toggle_output ic74hc595_toggle_pin(127);ic74hc595_shift_io_pins() +#define io127_get_output ic74hc595_get_pin(127) +#define io127_config_input +#define io127_config_pullup +#define io127_get_input 0 +#else +#define io127_config_output +#define io127_set_output +#define io127_clear_output +#define io127_toggle_output +#define io127_get_output 0 +#define io127_config_input +#define io127_config_pullup +#define io127_get_input 0 +#endif +#if ASSERT_PIN_IO(128) +#define io128_config_output mcu_config_output(128) +#define io128_set_output mcu_set_output(128) +#define io128_clear_output mcu_clear_output(128) +#define io128_toggle_output mcu_toggle_output(128) +#define io128_get_output mcu_get_output(128) +#define io128_config_input mcu_config_input(128) +#define io128_config_pullup mcu_config_pullup(128) +#define io128_get_input mcu_get_input(128) +#elif ASSERT_PIN_EXTENDED(128) +#define io128_config_output +#define io128_set_output ic74hc595_set_pin(128);ic74hc595_shift_io_pins() +#define io128_clear_output ic74hc595_clear_pin(128);ic74hc595_shift_io_pins() +#define io128_toggle_output ic74hc595_toggle_pin(128);ic74hc595_shift_io_pins() +#define io128_get_output ic74hc595_get_pin(128) +#define io128_config_input +#define io128_config_pullup +#define io128_get_input 0 +#else +#define io128_config_output +#define io128_set_output +#define io128_clear_output +#define io128_toggle_output +#define io128_get_output 0 +#define io128_config_input +#define io128_config_pullup +#define io128_get_input 0 +#endif +#if ASSERT_PIN_IO(129) +#define io129_config_output mcu_config_output(129) +#define io129_set_output mcu_set_output(129) +#define io129_clear_output mcu_clear_output(129) +#define io129_toggle_output mcu_toggle_output(129) +#define io129_get_output mcu_get_output(129) +#define io129_config_input mcu_config_input(129) +#define io129_config_pullup mcu_config_pullup(129) +#define io129_get_input mcu_get_input(129) +#elif ASSERT_PIN_EXTENDED(129) +#define io129_config_output +#define io129_set_output ic74hc595_set_pin(129);ic74hc595_shift_io_pins() +#define io129_clear_output ic74hc595_clear_pin(129);ic74hc595_shift_io_pins() +#define io129_toggle_output ic74hc595_toggle_pin(129);ic74hc595_shift_io_pins() +#define io129_get_output ic74hc595_get_pin(129) +#define io129_config_input +#define io129_config_pullup +#define io129_get_input 0 +#else +#define io129_config_output +#define io129_set_output +#define io129_clear_output +#define io129_toggle_output +#define io129_get_output 0 +#define io129_config_input +#define io129_config_pullup +#define io129_get_input 0 +#endif +#if ASSERT_PIN_IO(130) +#define io130_config_output mcu_config_output(130) +#define io130_set_output mcu_set_output(130) +#define io130_clear_output mcu_clear_output(130) +#define io130_toggle_output mcu_toggle_output(130) +#define io130_get_output mcu_get_output(130) +#define io130_config_input mcu_config_input(130) +#define io130_config_pullup mcu_config_pullup(130) +#define io130_get_input mcu_get_input(130) +#elif ASSERT_PIN_EXTENDED(130) +#define io130_config_output +#define io130_set_output ic74hc595_set_pin(130);ic74hc595_shift_io_pins() +#define io130_clear_output ic74hc595_clear_pin(130);ic74hc595_shift_io_pins() +#define io130_toggle_output ic74hc595_toggle_pin(130);ic74hc595_shift_io_pins() +#define io130_get_output ic74hc595_get_pin(130) +#define io130_config_input +#define io130_config_pullup +#define io130_get_input 0 +#else +#define io130_config_output +#define io130_set_output +#define io130_clear_output +#define io130_toggle_output +#define io130_get_output 0 +#define io130_config_input +#define io130_config_pullup +#define io130_get_input 0 +#endif +#if ASSERT_PIN_IO(131) +#define io131_config_output mcu_config_output(131) +#define io131_set_output mcu_set_output(131) +#define io131_clear_output mcu_clear_output(131) +#define io131_toggle_output mcu_toggle_output(131) +#define io131_get_output mcu_get_output(131) +#define io131_config_input mcu_config_input(131) +#define io131_config_pullup mcu_config_pullup(131) +#define io131_get_input mcu_get_input(131) +#elif ASSERT_PIN_EXTENDED(131) +#define io131_config_output +#define io131_set_output ic74hc595_set_pin(131);ic74hc595_shift_io_pins() +#define io131_clear_output ic74hc595_clear_pin(131);ic74hc595_shift_io_pins() +#define io131_toggle_output ic74hc595_toggle_pin(131);ic74hc595_shift_io_pins() +#define io131_get_output ic74hc595_get_pin(131) +#define io131_config_input +#define io131_config_pullup +#define io131_get_input 0 +#else +#define io131_config_output +#define io131_set_output +#define io131_clear_output +#define io131_toggle_output +#define io131_get_output 0 +#define io131_config_input +#define io131_config_pullup +#define io131_get_input 0 +#endif +#if ASSERT_PIN_IO(132) +#define io132_config_output mcu_config_output(132) +#define io132_set_output mcu_set_output(132) +#define io132_clear_output mcu_clear_output(132) +#define io132_toggle_output mcu_toggle_output(132) +#define io132_get_output mcu_get_output(132) +#define io132_config_input mcu_config_input(132) +#define io132_config_pullup mcu_config_pullup(132) +#define io132_get_input mcu_get_input(132) +#elif ASSERT_PIN_EXTENDED(132) +#define io132_config_output +#define io132_set_output ic74hc595_set_pin(132);ic74hc595_shift_io_pins() +#define io132_clear_output ic74hc595_clear_pin(132);ic74hc595_shift_io_pins() +#define io132_toggle_output ic74hc595_toggle_pin(132);ic74hc595_shift_io_pins() +#define io132_get_output ic74hc595_get_pin(132) +#define io132_config_input +#define io132_config_pullup +#define io132_get_input 0 +#else +#define io132_config_output +#define io132_set_output +#define io132_clear_output +#define io132_toggle_output +#define io132_get_output 0 +#define io132_config_input +#define io132_config_pullup +#define io132_get_input 0 +#endif +#if ASSERT_PIN_IO(133) +#define io133_config_output mcu_config_output(133) +#define io133_set_output mcu_set_output(133) +#define io133_clear_output mcu_clear_output(133) +#define io133_toggle_output mcu_toggle_output(133) +#define io133_get_output mcu_get_output(133) +#define io133_config_input mcu_config_input(133) +#define io133_config_pullup mcu_config_pullup(133) +#define io133_get_input mcu_get_input(133) +#elif ASSERT_PIN_EXTENDED(133) +#define io133_config_output +#define io133_set_output ic74hc595_set_pin(133);ic74hc595_shift_io_pins() +#define io133_clear_output ic74hc595_clear_pin(133);ic74hc595_shift_io_pins() +#define io133_toggle_output ic74hc595_toggle_pin(133);ic74hc595_shift_io_pins() +#define io133_get_output ic74hc595_get_pin(133) +#define io133_config_input +#define io133_config_pullup +#define io133_get_input 0 +#else +#define io133_config_output +#define io133_set_output +#define io133_clear_output +#define io133_toggle_output +#define io133_get_output 0 +#define io133_config_input +#define io133_config_pullup +#define io133_get_input 0 +#endif +#if ASSERT_PIN_IO(134) +#define io134_config_output mcu_config_output(134) +#define io134_set_output mcu_set_output(134) +#define io134_clear_output mcu_clear_output(134) +#define io134_toggle_output mcu_toggle_output(134) +#define io134_get_output mcu_get_output(134) +#define io134_config_input mcu_config_input(134) +#define io134_config_pullup mcu_config_pullup(134) +#define io134_get_input mcu_get_input(134) +#elif ASSERT_PIN_EXTENDED(134) +#define io134_config_output +#define io134_set_output ic74hc595_set_pin(134);ic74hc595_shift_io_pins() +#define io134_clear_output ic74hc595_clear_pin(134);ic74hc595_shift_io_pins() +#define io134_toggle_output ic74hc595_toggle_pin(134);ic74hc595_shift_io_pins() +#define io134_get_output ic74hc595_get_pin(134) +#define io134_config_input +#define io134_config_pullup +#define io134_get_input 0 +#else +#define io134_config_output +#define io134_set_output +#define io134_clear_output +#define io134_toggle_output +#define io134_get_output 0 +#define io134_config_input +#define io134_config_pullup +#define io134_get_input 0 +#endif +#if ASSERT_PIN_IO(135) +#define io135_config_output mcu_config_output(135) +#define io135_set_output mcu_set_output(135) +#define io135_clear_output mcu_clear_output(135) +#define io135_toggle_output mcu_toggle_output(135) +#define io135_get_output mcu_get_output(135) +#define io135_config_input mcu_config_input(135) +#define io135_config_pullup mcu_config_pullup(135) +#define io135_get_input mcu_get_input(135) +#elif ASSERT_PIN_EXTENDED(135) +#define io135_config_output +#define io135_set_output ic74hc595_set_pin(135);ic74hc595_shift_io_pins() +#define io135_clear_output ic74hc595_clear_pin(135);ic74hc595_shift_io_pins() +#define io135_toggle_output ic74hc595_toggle_pin(135);ic74hc595_shift_io_pins() +#define io135_get_output ic74hc595_get_pin(135) +#define io135_config_input +#define io135_config_pullup +#define io135_get_input 0 +#else +#define io135_config_output +#define io135_set_output +#define io135_clear_output +#define io135_toggle_output +#define io135_get_output 0 +#define io135_config_input +#define io135_config_pullup +#define io135_get_input 0 +#endif +#if ASSERT_PIN_IO(136) +#define io136_config_output mcu_config_output(136) +#define io136_set_output mcu_set_output(136) +#define io136_clear_output mcu_clear_output(136) +#define io136_toggle_output mcu_toggle_output(136) +#define io136_get_output mcu_get_output(136) +#define io136_config_input mcu_config_input(136) +#define io136_config_pullup mcu_config_pullup(136) +#define io136_get_input mcu_get_input(136) +#elif ASSERT_PIN_EXTENDED(136) +#define io136_config_output +#define io136_set_output ic74hc595_set_pin(136);ic74hc595_shift_io_pins() +#define io136_clear_output ic74hc595_clear_pin(136);ic74hc595_shift_io_pins() +#define io136_toggle_output ic74hc595_toggle_pin(136);ic74hc595_shift_io_pins() +#define io136_get_output ic74hc595_get_pin(136) +#define io136_config_input +#define io136_config_pullup +#define io136_get_input 0 +#else +#define io136_config_output +#define io136_set_output +#define io136_clear_output +#define io136_toggle_output +#define io136_get_output 0 +#define io136_config_input +#define io136_config_pullup +#define io136_get_input 0 +#endif +#if ASSERT_PIN_IO(137) +#define io137_config_output mcu_config_output(137) +#define io137_set_output mcu_set_output(137) +#define io137_clear_output mcu_clear_output(137) +#define io137_toggle_output mcu_toggle_output(137) +#define io137_get_output mcu_get_output(137) +#define io137_config_input mcu_config_input(137) +#define io137_config_pullup mcu_config_pullup(137) +#define io137_get_input mcu_get_input(137) +#elif ASSERT_PIN_EXTENDED(137) +#define io137_config_output +#define io137_set_output ic74hc595_set_pin(137);ic74hc595_shift_io_pins() +#define io137_clear_output ic74hc595_clear_pin(137);ic74hc595_shift_io_pins() +#define io137_toggle_output ic74hc595_toggle_pin(137);ic74hc595_shift_io_pins() +#define io137_get_output ic74hc595_get_pin(137) +#define io137_config_input +#define io137_config_pullup +#define io137_get_input 0 +#else +#define io137_config_output +#define io137_set_output +#define io137_clear_output +#define io137_toggle_output +#define io137_get_output 0 +#define io137_config_input +#define io137_config_pullup +#define io137_get_input 0 +#endif +#if ASSERT_PIN_IO(138) +#define io138_config_output mcu_config_output(138) +#define io138_set_output mcu_set_output(138) +#define io138_clear_output mcu_clear_output(138) +#define io138_toggle_output mcu_toggle_output(138) +#define io138_get_output mcu_get_output(138) +#define io138_config_input mcu_config_input(138) +#define io138_config_pullup mcu_config_pullup(138) +#define io138_get_input mcu_get_input(138) +#elif ASSERT_PIN_EXTENDED(138) +#define io138_config_output +#define io138_set_output ic74hc595_set_pin(138);ic74hc595_shift_io_pins() +#define io138_clear_output ic74hc595_clear_pin(138);ic74hc595_shift_io_pins() +#define io138_toggle_output ic74hc595_toggle_pin(138);ic74hc595_shift_io_pins() +#define io138_get_output ic74hc595_get_pin(138) +#define io138_config_input +#define io138_config_pullup +#define io138_get_input 0 +#else +#define io138_config_output +#define io138_set_output +#define io138_clear_output +#define io138_toggle_output +#define io138_get_output 0 +#define io138_config_input +#define io138_config_pullup +#define io138_get_input 0 +#endif +#if ASSERT_PIN_IO(139) +#define io139_config_output mcu_config_output(139) +#define io139_set_output mcu_set_output(139) +#define io139_clear_output mcu_clear_output(139) +#define io139_toggle_output mcu_toggle_output(139) +#define io139_get_output mcu_get_output(139) +#define io139_config_input mcu_config_input(139) +#define io139_config_pullup mcu_config_pullup(139) +#define io139_get_input mcu_get_input(139) +#elif ASSERT_PIN_EXTENDED(139) +#define io139_config_output +#define io139_set_output ic74hc595_set_pin(139);ic74hc595_shift_io_pins() +#define io139_clear_output ic74hc595_clear_pin(139);ic74hc595_shift_io_pins() +#define io139_toggle_output ic74hc595_toggle_pin(139);ic74hc595_shift_io_pins() +#define io139_get_output ic74hc595_get_pin(139) +#define io139_config_input +#define io139_config_pullup +#define io139_get_input 0 +#else +#define io139_config_output +#define io139_set_output +#define io139_clear_output +#define io139_toggle_output +#define io139_get_output 0 +#define io139_config_input +#define io139_config_pullup +#define io139_get_input 0 +#endif +#if ASSERT_PIN_IO(140) +#define io140_config_output mcu_config_output(140) +#define io140_set_output mcu_set_output(140) +#define io140_clear_output mcu_clear_output(140) +#define io140_toggle_output mcu_toggle_output(140) +#define io140_get_output mcu_get_output(140) +#define io140_config_input mcu_config_input(140) +#define io140_config_pullup mcu_config_pullup(140) +#define io140_get_input mcu_get_input(140) +#elif ASSERT_PIN_EXTENDED(140) +#define io140_config_output +#define io140_set_output ic74hc595_set_pin(140);ic74hc595_shift_io_pins() +#define io140_clear_output ic74hc595_clear_pin(140);ic74hc595_shift_io_pins() +#define io140_toggle_output ic74hc595_toggle_pin(140);ic74hc595_shift_io_pins() +#define io140_get_output ic74hc595_get_pin(140) +#define io140_config_input +#define io140_config_pullup +#define io140_get_input 0 +#else +#define io140_config_output +#define io140_set_output +#define io140_clear_output +#define io140_toggle_output +#define io140_get_output 0 +#define io140_config_input +#define io140_config_pullup +#define io140_get_input 0 +#endif +#if ASSERT_PIN_IO(141) +#define io141_config_output mcu_config_output(141) +#define io141_set_output mcu_set_output(141) +#define io141_clear_output mcu_clear_output(141) +#define io141_toggle_output mcu_toggle_output(141) +#define io141_get_output mcu_get_output(141) +#define io141_config_input mcu_config_input(141) +#define io141_config_pullup mcu_config_pullup(141) +#define io141_get_input mcu_get_input(141) +#elif ASSERT_PIN_EXTENDED(141) +#define io141_config_output +#define io141_set_output ic74hc595_set_pin(141);ic74hc595_shift_io_pins() +#define io141_clear_output ic74hc595_clear_pin(141);ic74hc595_shift_io_pins() +#define io141_toggle_output ic74hc595_toggle_pin(141);ic74hc595_shift_io_pins() +#define io141_get_output ic74hc595_get_pin(141) +#define io141_config_input +#define io141_config_pullup +#define io141_get_input 0 +#else +#define io141_config_output +#define io141_set_output +#define io141_clear_output +#define io141_toggle_output +#define io141_get_output 0 +#define io141_config_input +#define io141_config_pullup +#define io141_get_input 0 +#endif +#if ASSERT_PIN_IO(142) +#define io142_config_output mcu_config_output(142) +#define io142_set_output mcu_set_output(142) +#define io142_clear_output mcu_clear_output(142) +#define io142_toggle_output mcu_toggle_output(142) +#define io142_get_output mcu_get_output(142) +#define io142_config_input mcu_config_input(142) +#define io142_config_pullup mcu_config_pullup(142) +#define io142_get_input mcu_get_input(142) +#elif ASSERT_PIN_EXTENDED(142) +#define io142_config_output +#define io142_set_output ic74hc595_set_pin(142);ic74hc595_shift_io_pins() +#define io142_clear_output ic74hc595_clear_pin(142);ic74hc595_shift_io_pins() +#define io142_toggle_output ic74hc595_toggle_pin(142);ic74hc595_shift_io_pins() +#define io142_get_output ic74hc595_get_pin(142) +#define io142_config_input +#define io142_config_pullup +#define io142_get_input 0 +#else +#define io142_config_output +#define io142_set_output +#define io142_clear_output +#define io142_toggle_output +#define io142_get_output 0 +#define io142_config_input +#define io142_config_pullup +#define io142_get_input 0 +#endif +#if ASSERT_PIN_IO(143) +#define io143_config_output mcu_config_output(143) +#define io143_set_output mcu_set_output(143) +#define io143_clear_output mcu_clear_output(143) +#define io143_toggle_output mcu_toggle_output(143) +#define io143_get_output mcu_get_output(143) +#define io143_config_input mcu_config_input(143) +#define io143_config_pullup mcu_config_pullup(143) +#define io143_get_input mcu_get_input(143) +#elif ASSERT_PIN_EXTENDED(143) +#define io143_config_output +#define io143_set_output ic74hc595_set_pin(143);ic74hc595_shift_io_pins() +#define io143_clear_output ic74hc595_clear_pin(143);ic74hc595_shift_io_pins() +#define io143_toggle_output ic74hc595_toggle_pin(143);ic74hc595_shift_io_pins() +#define io143_get_output ic74hc595_get_pin(143) +#define io143_config_input +#define io143_config_pullup +#define io143_get_input 0 +#else +#define io143_config_output +#define io143_set_output +#define io143_clear_output +#define io143_toggle_output +#define io143_get_output 0 +#define io143_config_input +#define io143_config_pullup +#define io143_get_input 0 +#endif +#if ASSERT_PIN_IO(144) +#define io144_config_output mcu_config_output(144) +#define io144_set_output mcu_set_output(144) +#define io144_clear_output mcu_clear_output(144) +#define io144_toggle_output mcu_toggle_output(144) +#define io144_get_output mcu_get_output(144) +#define io144_config_input mcu_config_input(144) +#define io144_config_pullup mcu_config_pullup(144) +#define io144_get_input mcu_get_input(144) +#elif ASSERT_PIN_EXTENDED(144) +#define io144_config_output +#define io144_set_output ic74hc595_set_pin(144);ic74hc595_shift_io_pins() +#define io144_clear_output ic74hc595_clear_pin(144);ic74hc595_shift_io_pins() +#define io144_toggle_output ic74hc595_toggle_pin(144);ic74hc595_shift_io_pins() +#define io144_get_output ic74hc595_get_pin(144) +#define io144_config_input +#define io144_config_pullup +#define io144_get_input 0 +#else +#define io144_config_output +#define io144_set_output +#define io144_clear_output +#define io144_toggle_output +#define io144_get_output 0 +#define io144_config_input +#define io144_config_pullup +#define io144_get_input 0 +#endif +#if ASSERT_PIN_IO(145) +#define io145_config_output mcu_config_output(145) +#define io145_set_output mcu_set_output(145) +#define io145_clear_output mcu_clear_output(145) +#define io145_toggle_output mcu_toggle_output(145) +#define io145_get_output mcu_get_output(145) +#define io145_config_input mcu_config_input(145) +#define io145_config_pullup mcu_config_pullup(145) +#define io145_get_input mcu_get_input(145) +#elif ASSERT_PIN_EXTENDED(145) +#define io145_config_output +#define io145_set_output ic74hc595_set_pin(145);ic74hc595_shift_io_pins() +#define io145_clear_output ic74hc595_clear_pin(145);ic74hc595_shift_io_pins() +#define io145_toggle_output ic74hc595_toggle_pin(145);ic74hc595_shift_io_pins() +#define io145_get_output ic74hc595_get_pin(145) +#define io145_config_input +#define io145_config_pullup +#define io145_get_input 0 +#else +#define io145_config_output +#define io145_set_output +#define io145_clear_output +#define io145_toggle_output +#define io145_get_output 0 +#define io145_config_input +#define io145_config_pullup +#define io145_get_input 0 +#endif +#if ASSERT_PIN_IO(146) +#define io146_config_output mcu_config_output(146) +#define io146_set_output mcu_set_output(146) +#define io146_clear_output mcu_clear_output(146) +#define io146_toggle_output mcu_toggle_output(146) +#define io146_get_output mcu_get_output(146) +#define io146_config_input mcu_config_input(146) +#define io146_config_pullup mcu_config_pullup(146) +#define io146_get_input mcu_get_input(146) +#elif ASSERT_PIN_EXTENDED(146) +#define io146_config_output +#define io146_set_output ic74hc595_set_pin(146);ic74hc595_shift_io_pins() +#define io146_clear_output ic74hc595_clear_pin(146);ic74hc595_shift_io_pins() +#define io146_toggle_output ic74hc595_toggle_pin(146);ic74hc595_shift_io_pins() +#define io146_get_output ic74hc595_get_pin(146) +#define io146_config_input +#define io146_config_pullup +#define io146_get_input 0 +#else +#define io146_config_output +#define io146_set_output +#define io146_clear_output +#define io146_toggle_output +#define io146_get_output 0 +#define io146_config_input +#define io146_config_pullup +#define io146_get_input 0 +#endif +#if ASSERT_PIN_IO(147) +#define io147_config_output mcu_config_output(147) +#define io147_set_output mcu_set_output(147) +#define io147_clear_output mcu_clear_output(147) +#define io147_toggle_output mcu_toggle_output(147) +#define io147_get_output mcu_get_output(147) +#define io147_config_input mcu_config_input(147) +#define io147_config_pullup mcu_config_pullup(147) +#define io147_get_input mcu_get_input(147) +#elif ASSERT_PIN_EXTENDED(147) +#define io147_config_output +#define io147_set_output ic74hc595_set_pin(147);ic74hc595_shift_io_pins() +#define io147_clear_output ic74hc595_clear_pin(147);ic74hc595_shift_io_pins() +#define io147_toggle_output ic74hc595_toggle_pin(147);ic74hc595_shift_io_pins() +#define io147_get_output ic74hc595_get_pin(147) +#define io147_config_input +#define io147_config_pullup +#define io147_get_input 0 +#else +#define io147_config_output +#define io147_set_output +#define io147_clear_output +#define io147_toggle_output +#define io147_get_output 0 +#define io147_config_input +#define io147_config_pullup +#define io147_get_input 0 +#endif +#if ASSERT_PIN_IO(148) +#define io148_config_output mcu_config_output(148) +#define io148_set_output mcu_set_output(148) +#define io148_clear_output mcu_clear_output(148) +#define io148_toggle_output mcu_toggle_output(148) +#define io148_get_output mcu_get_output(148) +#define io148_config_input mcu_config_input(148) +#define io148_config_pullup mcu_config_pullup(148) +#define io148_get_input mcu_get_input(148) +#elif ASSERT_PIN_EXTENDED(148) +#define io148_config_output +#define io148_set_output ic74hc595_set_pin(148);ic74hc595_shift_io_pins() +#define io148_clear_output ic74hc595_clear_pin(148);ic74hc595_shift_io_pins() +#define io148_toggle_output ic74hc595_toggle_pin(148);ic74hc595_shift_io_pins() +#define io148_get_output ic74hc595_get_pin(148) +#define io148_config_input +#define io148_config_pullup +#define io148_get_input 0 +#else +#define io148_config_output +#define io148_set_output +#define io148_clear_output +#define io148_toggle_output +#define io148_get_output 0 +#define io148_config_input +#define io148_config_pullup +#define io148_get_input 0 +#endif +#if ASSERT_PIN_IO(149) +#define io149_config_output mcu_config_output(149) +#define io149_set_output mcu_set_output(149) +#define io149_clear_output mcu_clear_output(149) +#define io149_toggle_output mcu_toggle_output(149) +#define io149_get_output mcu_get_output(149) +#define io149_config_input mcu_config_input(149) +#define io149_config_pullup mcu_config_pullup(149) +#define io149_get_input mcu_get_input(149) +#elif ASSERT_PIN_EXTENDED(149) +#define io149_config_output +#define io149_set_output ic74hc595_set_pin(149);ic74hc595_shift_io_pins() +#define io149_clear_output ic74hc595_clear_pin(149);ic74hc595_shift_io_pins() +#define io149_toggle_output ic74hc595_toggle_pin(149);ic74hc595_shift_io_pins() +#define io149_get_output ic74hc595_get_pin(149) +#define io149_config_input +#define io149_config_pullup +#define io149_get_input 0 +#else +#define io149_config_output +#define io149_set_output +#define io149_clear_output +#define io149_toggle_output +#define io149_get_output 0 +#define io149_config_input +#define io149_config_pullup +#define io149_get_input 0 +#endif +#if ASSERT_PIN_IO(150) +#define io150_config_output mcu_config_output(150) +#define io150_set_output mcu_set_output(150) +#define io150_clear_output mcu_clear_output(150) +#define io150_toggle_output mcu_toggle_output(150) +#define io150_get_output mcu_get_output(150) +#define io150_config_input mcu_config_input(150) +#define io150_config_pullup mcu_config_pullup(150) +#define io150_get_input mcu_get_input(150) +#elif ASSERT_PIN_EXTENDED(150) +#define io150_config_output +#define io150_set_output ic74hc595_set_pin(150);ic74hc595_shift_io_pins() +#define io150_clear_output ic74hc595_clear_pin(150);ic74hc595_shift_io_pins() +#define io150_toggle_output ic74hc595_toggle_pin(150);ic74hc595_shift_io_pins() +#define io150_get_output ic74hc595_get_pin(150) +#define io150_config_input +#define io150_config_pullup +#define io150_get_input 0 +#else +#define io150_config_output +#define io150_set_output +#define io150_clear_output +#define io150_toggle_output +#define io150_get_output 0 +#define io150_config_input +#define io150_config_pullup +#define io150_get_input 0 +#endif +#if ASSERT_PIN_IO(151) +#define io151_config_output mcu_config_output(151) +#define io151_set_output mcu_set_output(151) +#define io151_clear_output mcu_clear_output(151) +#define io151_toggle_output mcu_toggle_output(151) +#define io151_get_output mcu_get_output(151) +#define io151_config_input mcu_config_input(151) +#define io151_config_pullup mcu_config_pullup(151) +#define io151_get_input mcu_get_input(151) +#elif ASSERT_PIN_EXTENDED(151) +#define io151_config_output +#define io151_set_output ic74hc595_set_pin(151);ic74hc595_shift_io_pins() +#define io151_clear_output ic74hc595_clear_pin(151);ic74hc595_shift_io_pins() +#define io151_toggle_output ic74hc595_toggle_pin(151);ic74hc595_shift_io_pins() +#define io151_get_output ic74hc595_get_pin(151) +#define io151_config_input +#define io151_config_pullup +#define io151_get_input 0 +#else +#define io151_config_output +#define io151_set_output +#define io151_clear_output +#define io151_toggle_output +#define io151_get_output 0 +#define io151_config_input +#define io151_config_pullup +#define io151_get_input 0 +#endif +#if ASSERT_PIN_IO(152) +#define io152_config_output mcu_config_output(152) +#define io152_set_output mcu_set_output(152) +#define io152_clear_output mcu_clear_output(152) +#define io152_toggle_output mcu_toggle_output(152) +#define io152_get_output mcu_get_output(152) +#define io152_config_input mcu_config_input(152) +#define io152_config_pullup mcu_config_pullup(152) +#define io152_get_input mcu_get_input(152) +#elif ASSERT_PIN_EXTENDED(152) +#define io152_config_output +#define io152_set_output ic74hc595_set_pin(152);ic74hc595_shift_io_pins() +#define io152_clear_output ic74hc595_clear_pin(152);ic74hc595_shift_io_pins() +#define io152_toggle_output ic74hc595_toggle_pin(152);ic74hc595_shift_io_pins() +#define io152_get_output ic74hc595_get_pin(152) +#define io152_config_input +#define io152_config_pullup +#define io152_get_input 0 +#else +#define io152_config_output +#define io152_set_output +#define io152_clear_output +#define io152_toggle_output +#define io152_get_output 0 +#define io152_config_input +#define io152_config_pullup +#define io152_get_input 0 +#endif +#if ASSERT_PIN_IO(153) +#define io153_config_output mcu_config_output(153) +#define io153_set_output mcu_set_output(153) +#define io153_clear_output mcu_clear_output(153) +#define io153_toggle_output mcu_toggle_output(153) +#define io153_get_output mcu_get_output(153) +#define io153_config_input mcu_config_input(153) +#define io153_config_pullup mcu_config_pullup(153) +#define io153_get_input mcu_get_input(153) +#elif ASSERT_PIN_EXTENDED(153) +#define io153_config_output +#define io153_set_output ic74hc595_set_pin(153);ic74hc595_shift_io_pins() +#define io153_clear_output ic74hc595_clear_pin(153);ic74hc595_shift_io_pins() +#define io153_toggle_output ic74hc595_toggle_pin(153);ic74hc595_shift_io_pins() +#define io153_get_output ic74hc595_get_pin(153) +#define io153_config_input +#define io153_config_pullup +#define io153_get_input 0 +#else +#define io153_config_output +#define io153_set_output +#define io153_clear_output +#define io153_toggle_output +#define io153_get_output 0 +#define io153_config_input +#define io153_config_pullup +#define io153_get_input 0 +#endif +#if ASSERT_PIN_IO(154) +#define io154_config_output mcu_config_output(154) +#define io154_set_output mcu_set_output(154) +#define io154_clear_output mcu_clear_output(154) +#define io154_toggle_output mcu_toggle_output(154) +#define io154_get_output mcu_get_output(154) +#define io154_config_input mcu_config_input(154) +#define io154_config_pullup mcu_config_pullup(154) +#define io154_get_input mcu_get_input(154) +#elif ASSERT_PIN_EXTENDED(154) +#define io154_config_output +#define io154_set_output ic74hc595_set_pin(154);ic74hc595_shift_io_pins() +#define io154_clear_output ic74hc595_clear_pin(154);ic74hc595_shift_io_pins() +#define io154_toggle_output ic74hc595_toggle_pin(154);ic74hc595_shift_io_pins() +#define io154_get_output ic74hc595_get_pin(154) +#define io154_config_input +#define io154_config_pullup +#define io154_get_input 0 +#else +#define io154_config_output +#define io154_set_output +#define io154_clear_output +#define io154_toggle_output +#define io154_get_output 0 +#define io154_config_input +#define io154_config_pullup +#define io154_get_input 0 +#endif +#if ASSERT_PIN_IO(155) +#define io155_config_output mcu_config_output(155) +#define io155_set_output mcu_set_output(155) +#define io155_clear_output mcu_clear_output(155) +#define io155_toggle_output mcu_toggle_output(155) +#define io155_get_output mcu_get_output(155) +#define io155_config_input mcu_config_input(155) +#define io155_config_pullup mcu_config_pullup(155) +#define io155_get_input mcu_get_input(155) +#elif ASSERT_PIN_EXTENDED(155) +#define io155_config_output +#define io155_set_output ic74hc595_set_pin(155);ic74hc595_shift_io_pins() +#define io155_clear_output ic74hc595_clear_pin(155);ic74hc595_shift_io_pins() +#define io155_toggle_output ic74hc595_toggle_pin(155);ic74hc595_shift_io_pins() +#define io155_get_output ic74hc595_get_pin(155) +#define io155_config_input +#define io155_config_pullup +#define io155_get_input 0 +#else +#define io155_config_output +#define io155_set_output +#define io155_clear_output +#define io155_toggle_output +#define io155_get_output 0 +#define io155_config_input +#define io155_config_pullup +#define io155_get_input 0 +#endif +#if ASSERT_PIN_IO(156) +#define io156_config_output mcu_config_output(156) +#define io156_set_output mcu_set_output(156) +#define io156_clear_output mcu_clear_output(156) +#define io156_toggle_output mcu_toggle_output(156) +#define io156_get_output mcu_get_output(156) +#define io156_config_input mcu_config_input(156) +#define io156_config_pullup mcu_config_pullup(156) +#define io156_get_input mcu_get_input(156) +#elif ASSERT_PIN_EXTENDED(156) +#define io156_config_output +#define io156_set_output ic74hc595_set_pin(156);ic74hc595_shift_io_pins() +#define io156_clear_output ic74hc595_clear_pin(156);ic74hc595_shift_io_pins() +#define io156_toggle_output ic74hc595_toggle_pin(156);ic74hc595_shift_io_pins() +#define io156_get_output ic74hc595_get_pin(156) +#define io156_config_input +#define io156_config_pullup +#define io156_get_input 0 +#else +#define io156_config_output +#define io156_set_output +#define io156_clear_output +#define io156_toggle_output +#define io156_get_output 0 +#define io156_config_input +#define io156_config_pullup +#define io156_get_input 0 +#endif +#if ASSERT_PIN_IO(157) +#define io157_config_output mcu_config_output(157) +#define io157_set_output mcu_set_output(157) +#define io157_clear_output mcu_clear_output(157) +#define io157_toggle_output mcu_toggle_output(157) +#define io157_get_output mcu_get_output(157) +#define io157_config_input mcu_config_input(157) +#define io157_config_pullup mcu_config_pullup(157) +#define io157_get_input mcu_get_input(157) +#elif ASSERT_PIN_EXTENDED(157) +#define io157_config_output +#define io157_set_output ic74hc595_set_pin(157);ic74hc595_shift_io_pins() +#define io157_clear_output ic74hc595_clear_pin(157);ic74hc595_shift_io_pins() +#define io157_toggle_output ic74hc595_toggle_pin(157);ic74hc595_shift_io_pins() +#define io157_get_output ic74hc595_get_pin(157) +#define io157_config_input +#define io157_config_pullup +#define io157_get_input 0 +#else +#define io157_config_output +#define io157_set_output +#define io157_clear_output +#define io157_toggle_output +#define io157_get_output 0 +#define io157_config_input +#define io157_config_pullup +#define io157_get_input 0 +#endif +#if ASSERT_PIN_IO(158) +#define io158_config_output mcu_config_output(158) +#define io158_set_output mcu_set_output(158) +#define io158_clear_output mcu_clear_output(158) +#define io158_toggle_output mcu_toggle_output(158) +#define io158_get_output mcu_get_output(158) +#define io158_config_input mcu_config_input(158) +#define io158_config_pullup mcu_config_pullup(158) +#define io158_get_input mcu_get_input(158) +#elif ASSERT_PIN_EXTENDED(158) +#define io158_config_output +#define io158_set_output ic74hc595_set_pin(158);ic74hc595_shift_io_pins() +#define io158_clear_output ic74hc595_clear_pin(158);ic74hc595_shift_io_pins() +#define io158_toggle_output ic74hc595_toggle_pin(158);ic74hc595_shift_io_pins() +#define io158_get_output ic74hc595_get_pin(158) +#define io158_config_input +#define io158_config_pullup +#define io158_get_input 0 +#else +#define io158_config_output +#define io158_set_output +#define io158_clear_output +#define io158_toggle_output +#define io158_get_output 0 +#define io158_config_input +#define io158_config_pullup +#define io158_get_input 0 +#endif +#if ASSERT_PIN_IO(159) +#define io159_config_output mcu_config_output(159) +#define io159_set_output mcu_set_output(159) +#define io159_clear_output mcu_clear_output(159) +#define io159_toggle_output mcu_toggle_output(159) +#define io159_get_output mcu_get_output(159) +#define io159_config_input mcu_config_input(159) +#define io159_config_pullup mcu_config_pullup(159) +#define io159_get_input mcu_get_input(159) +#elif ASSERT_PIN_EXTENDED(159) +#define io159_config_output +#define io159_set_output ic74hc595_set_pin(159);ic74hc595_shift_io_pins() +#define io159_clear_output ic74hc595_clear_pin(159);ic74hc595_shift_io_pins() +#define io159_toggle_output ic74hc595_toggle_pin(159);ic74hc595_shift_io_pins() +#define io159_get_output ic74hc595_get_pin(159) +#define io159_config_input +#define io159_config_pullup +#define io159_get_input 0 +#else +#define io159_config_output +#define io159_set_output +#define io159_clear_output +#define io159_toggle_output +#define io159_get_output 0 +#define io159_config_input +#define io159_config_pullup +#define io159_get_input 0 +#endif +#if ASSERT_PIN_IO(160) +#define io160_config_output mcu_config_output(160) +#define io160_set_output mcu_set_output(160) +#define io160_clear_output mcu_clear_output(160) +#define io160_toggle_output mcu_toggle_output(160) +#define io160_get_output mcu_get_output(160) +#define io160_config_input mcu_config_input(160) +#define io160_config_pullup mcu_config_pullup(160) +#define io160_get_input mcu_get_input(160) +#elif ASSERT_PIN_EXTENDED(160) +#define io160_config_output +#define io160_set_output ic74hc595_set_pin(160);ic74hc595_shift_io_pins() +#define io160_clear_output ic74hc595_clear_pin(160);ic74hc595_shift_io_pins() +#define io160_toggle_output ic74hc595_toggle_pin(160);ic74hc595_shift_io_pins() +#define io160_get_output ic74hc595_get_pin(160) +#define io160_config_input +#define io160_config_pullup +#define io160_get_input 0 +#else +#define io160_config_output +#define io160_set_output +#define io160_clear_output +#define io160_toggle_output +#define io160_get_output 0 +#define io160_config_input +#define io160_config_pullup +#define io160_get_input 0 +#endif +#if ASSERT_PIN_IO(161) +#define io161_config_output mcu_config_output(161) +#define io161_set_output mcu_set_output(161) +#define io161_clear_output mcu_clear_output(161) +#define io161_toggle_output mcu_toggle_output(161) +#define io161_get_output mcu_get_output(161) +#define io161_config_input mcu_config_input(161) +#define io161_config_pullup mcu_config_pullup(161) +#define io161_get_input mcu_get_input(161) +#elif ASSERT_PIN_EXTENDED(161) +#define io161_config_output +#define io161_set_output ic74hc595_set_pin(161);ic74hc595_shift_io_pins() +#define io161_clear_output ic74hc595_clear_pin(161);ic74hc595_shift_io_pins() +#define io161_toggle_output ic74hc595_toggle_pin(161);ic74hc595_shift_io_pins() +#define io161_get_output ic74hc595_get_pin(161) +#define io161_config_input +#define io161_config_pullup +#define io161_get_input 0 +#else +#define io161_config_output +#define io161_set_output +#define io161_clear_output +#define io161_toggle_output +#define io161_get_output 0 +#define io161_config_input +#define io161_config_pullup +#define io161_get_input 0 +#endif + +/*PWM*/ +#if ASSERT_PIN_IO(PWM0) +#define io25_config_pwm(freq) mcu_config_pwm(PWM0, freq) +#define io25_set_pwm(value) mcu_set_pwm(PWM0, value) +#define io25_get_pwm mcu_get_pwm(PWM0) +#elif ASSERT_PIN_EXTENDED(PWM0) +#define io25_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io25_set_pwm(value) io_set_soft_pwm(PWM0 - PWM_PINS_OFFSET, value) +#define io25_get_pwm mcu_get_pwm(PWM0) +#else +#define io25_config_pwm(freq) +#define io25_set_pwm(value) +#define io25_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM1) +#define io26_config_pwm(freq) mcu_config_pwm(PWM1, freq) +#define io26_set_pwm(value) mcu_set_pwm(PWM1, value) +#define io26_get_pwm mcu_get_pwm(PWM1) +#elif ASSERT_PIN_EXTENDED(PWM1) +#define io26_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io26_set_pwm(value) io_set_soft_pwm(PWM1 - PWM_PINS_OFFSET, value) +#define io26_get_pwm mcu_get_pwm(PWM1) +#else +#define io26_config_pwm(freq) +#define io26_set_pwm(value) +#define io26_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM2) +#define io27_config_pwm(freq) mcu_config_pwm(PWM2, freq) +#define io27_set_pwm(value) mcu_set_pwm(PWM2, value) +#define io27_get_pwm mcu_get_pwm(PWM2) +#elif ASSERT_PIN_EXTENDED(PWM2) +#define io27_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io27_set_pwm(value) io_set_soft_pwm(PWM2 - PWM_PINS_OFFSET, value) +#define io27_get_pwm mcu_get_pwm(PWM2) +#else +#define io27_config_pwm(freq) +#define io27_set_pwm(value) +#define io27_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM3) +#define io28_config_pwm(freq) mcu_config_pwm(PWM3, freq) +#define io28_set_pwm(value) mcu_set_pwm(PWM3, value) +#define io28_get_pwm mcu_get_pwm(PWM3) +#elif ASSERT_PIN_EXTENDED(PWM3) +#define io28_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io28_set_pwm(value) io_set_soft_pwm(PWM3 - PWM_PINS_OFFSET, value) +#define io28_get_pwm mcu_get_pwm(PWM3) +#else +#define io28_config_pwm(freq) +#define io28_set_pwm(value) +#define io28_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM4) +#define io29_config_pwm(freq) mcu_config_pwm(PWM4, freq) +#define io29_set_pwm(value) mcu_set_pwm(PWM4, value) +#define io29_get_pwm mcu_get_pwm(PWM4) +#elif ASSERT_PIN_EXTENDED(PWM4) +#define io29_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io29_set_pwm(value) io_set_soft_pwm(PWM4 - PWM_PINS_OFFSET, value) +#define io29_get_pwm mcu_get_pwm(PWM4) +#else +#define io29_config_pwm(freq) +#define io29_set_pwm(value) +#define io29_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM5) +#define io30_config_pwm(freq) mcu_config_pwm(PWM5, freq) +#define io30_set_pwm(value) mcu_set_pwm(PWM5, value) +#define io30_get_pwm mcu_get_pwm(PWM5) +#elif ASSERT_PIN_EXTENDED(PWM5) +#define io30_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io30_set_pwm(value) io_set_soft_pwm(PWM5 - PWM_PINS_OFFSET, value) +#define io30_get_pwm mcu_get_pwm(PWM5) +#else +#define io30_config_pwm(freq) +#define io30_set_pwm(value) +#define io30_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM6) +#define io31_config_pwm(freq) mcu_config_pwm(PWM6, freq) +#define io31_set_pwm(value) mcu_set_pwm(PWM6, value) +#define io31_get_pwm mcu_get_pwm(PWM6) +#elif ASSERT_PIN_EXTENDED(PWM6) +#define io31_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io31_set_pwm(value) io_set_soft_pwm(PWM6 - PWM_PINS_OFFSET, value) +#define io31_get_pwm mcu_get_pwm(PWM6) +#else +#define io31_config_pwm(freq) +#define io31_set_pwm(value) +#define io31_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM7) +#define io32_config_pwm(freq) mcu_config_pwm(PWM7, freq) +#define io32_set_pwm(value) mcu_set_pwm(PWM7, value) +#define io32_get_pwm mcu_get_pwm(PWM7) +#elif ASSERT_PIN_EXTENDED(PWM7) +#define io32_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io32_set_pwm(value) io_set_soft_pwm(PWM7 - PWM_PINS_OFFSET, value) +#define io32_get_pwm mcu_get_pwm(PWM7) +#else +#define io32_config_pwm(freq) +#define io32_set_pwm(value) +#define io32_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM8) +#define io33_config_pwm(freq) mcu_config_pwm(PWM8, freq) +#define io33_set_pwm(value) mcu_set_pwm(PWM8, value) +#define io33_get_pwm mcu_get_pwm(PWM8) +#elif ASSERT_PIN_EXTENDED(PWM8) +#define io33_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io33_set_pwm(value) io_set_soft_pwm(PWM8 - PWM_PINS_OFFSET, value) +#define io33_get_pwm mcu_get_pwm(PWM8) +#else +#define io33_config_pwm(freq) +#define io33_set_pwm(value) +#define io33_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM9) +#define io34_config_pwm(freq) mcu_config_pwm(PWM9, freq) +#define io34_set_pwm(value) mcu_set_pwm(PWM9, value) +#define io34_get_pwm mcu_get_pwm(PWM9) +#elif ASSERT_PIN_EXTENDED(PWM9) +#define io34_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io34_set_pwm(value) io_set_soft_pwm(PWM9 - PWM_PINS_OFFSET, value) +#define io34_get_pwm mcu_get_pwm(PWM9) +#else +#define io34_config_pwm(freq) +#define io34_set_pwm(value) +#define io34_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM10) +#define io35_config_pwm(freq) mcu_config_pwm(PWM10, freq) +#define io35_set_pwm(value) mcu_set_pwm(PWM10, value) +#define io35_get_pwm mcu_get_pwm(PWM10) +#elif ASSERT_PIN_EXTENDED(PWM10) +#define io35_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io35_set_pwm(value) io_set_soft_pwm(PWM10 - PWM_PINS_OFFSET, value) +#define io35_get_pwm mcu_get_pwm(PWM10) +#else +#define io35_config_pwm(freq) +#define io35_set_pwm(value) +#define io35_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM11) +#define io36_config_pwm(freq) mcu_config_pwm(PWM11, freq) +#define io36_set_pwm(value) mcu_set_pwm(PWM11, value) +#define io36_get_pwm mcu_get_pwm(PWM11) +#elif ASSERT_PIN_EXTENDED(PWM11) +#define io36_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io36_set_pwm(value) io_set_soft_pwm(PWM11 - PWM_PINS_OFFSET, value) +#define io36_get_pwm mcu_get_pwm(PWM11) +#else +#define io36_config_pwm(freq) +#define io36_set_pwm(value) +#define io36_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM12) +#define io37_config_pwm(freq) mcu_config_pwm(PWM12, freq) +#define io37_set_pwm(value) mcu_set_pwm(PWM12, value) +#define io37_get_pwm mcu_get_pwm(PWM12) +#elif ASSERT_PIN_EXTENDED(PWM12) +#define io37_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io37_set_pwm(value) io_set_soft_pwm(PWM12 - PWM_PINS_OFFSET, value) +#define io37_get_pwm mcu_get_pwm(PWM12) +#else +#define io37_config_pwm(freq) +#define io37_set_pwm(value) +#define io37_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM13) +#define io38_config_pwm(freq) mcu_config_pwm(PWM13, freq) +#define io38_set_pwm(value) mcu_set_pwm(PWM13, value) +#define io38_get_pwm mcu_get_pwm(PWM13) +#elif ASSERT_PIN_EXTENDED(PWM13) +#define io38_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io38_set_pwm(value) io_set_soft_pwm(PWM13 - PWM_PINS_OFFSET, value) +#define io38_get_pwm mcu_get_pwm(PWM13) +#else +#define io38_config_pwm(freq) +#define io38_set_pwm(value) +#define io38_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM14) +#define io39_config_pwm(freq) mcu_config_pwm(PWM14, freq) +#define io39_set_pwm(value) mcu_set_pwm(PWM14, value) +#define io39_get_pwm mcu_get_pwm(PWM14) +#elif ASSERT_PIN_EXTENDED(PWM14) +#define io39_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io39_set_pwm(value) io_set_soft_pwm(PWM14 - PWM_PINS_OFFSET, value) +#define io39_get_pwm mcu_get_pwm(PWM14) +#else +#define io39_config_pwm(freq) +#define io39_set_pwm(value) +#define io39_get_pwm 0 +#endif +#if ASSERT_PIN_IO(PWM15) +#define io40_config_pwm(freq) mcu_config_pwm(PWM15, freq) +#define io40_set_pwm(value) mcu_set_pwm(PWM15, value) +#define io40_get_pwm mcu_get_pwm(PWM15) +#elif ASSERT_PIN_EXTENDED(PWM15) +#define io40_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} +#define io40_set_pwm(value) io_set_soft_pwm(PWM15 - PWM_PINS_OFFSET, value) +#define io40_get_pwm mcu_get_pwm(PWM15) +#else +#define io40_config_pwm(freq) +#define io40_set_pwm(value) +#define io40_get_pwm 0 +#endif + +/*SERVO*/ +#if ASSERT_PIN_IO(SERVO0) +#define io41_set_pwm(value) mcu_set_servo(SERVO0, value) +#define io41_get_pwm mcu_get_servo(SERVO0) +#elif ASSERT_PIN_EXTENDED(SERVO0) +#define io41_set_pwm(value) +#define io41_get_pwm 0 +#else +#define io41_set_pwm(value) +#define io41_get_pwm 0 +#endif +#if ASSERT_PIN_IO(SERVO1) +#define io42_set_pwm(value) mcu_set_servo(SERVO1, value) +#define io42_get_pwm mcu_get_servo(SERVO1) +#elif ASSERT_PIN_EXTENDED(SERVO1) +#define io42_set_pwm(value) +#define io42_get_pwm 0 +#else +#define io42_set_pwm(value) +#define io42_get_pwm 0 +#endif +#if ASSERT_PIN_IO(SERVO2) +#define io43_set_pwm(value) mcu_set_servo(SERVO2, value) +#define io43_get_pwm mcu_get_servo(SERVO2) +#elif ASSERT_PIN_EXTENDED(SERVO2) +#define io43_set_pwm(value) +#define io43_get_pwm 0 +#else +#define io43_set_pwm(value) +#define io43_get_pwm 0 +#endif +#if ASSERT_PIN_IO(SERVO3) +#define io44_set_pwm(value) mcu_set_servo(SERVO3, value) +#define io44_get_pwm mcu_get_servo(SERVO3) +#elif ASSERT_PIN_EXTENDED(SERVO3) +#define io44_set_pwm(value) +#define io44_get_pwm 0 +#else +#define io44_set_pwm(value) +#define io44_get_pwm 0 +#endif +#if ASSERT_PIN_IO(SERVO4) +#define io45_set_pwm(value) mcu_set_servo(SERVO4, value) +#define io45_get_pwm mcu_get_servo(SERVO4) +#elif ASSERT_PIN_EXTENDED(SERVO4) +#define io45_set_pwm(value) +#define io45_get_pwm 0 +#else +#define io45_set_pwm(value) +#define io45_get_pwm 0 +#endif +#if ASSERT_PIN_IO(SERVO5) +#define io46_set_pwm(value) mcu_set_servo(SERVO5, value) +#define io46_get_pwm mcu_get_servo(SERVO5) +#elif ASSERT_PIN_EXTENDED(SERVO5) +#define io46_set_pwm(value) +#define io46_get_pwm 0 +#else +#define io46_set_pwm(value) +#define io46_get_pwm 0 +#endif + +/*ANALOG*/ +#if ASSERT_PIN_IO(ANALOG0) +#define io114_config_analog mcu_config_analog(ANALOG0) +#define io114_get_analog mcu_get_analog(ANALOG0) +#elif ASSERT_PIN_EXTENDED(ANALOG0) +#define io114_config_analog +#define io114_get_analog 0 +#else +#define io114_config_analog +#define io114_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG1) +#define io115_config_analog mcu_config_analog(ANALOG1) +#define io115_get_analog mcu_get_analog(ANALOG1) +#elif ASSERT_PIN_EXTENDED(ANALOG1) +#define io115_config_analog +#define io115_get_analog 0 +#else +#define io115_config_analog +#define io115_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG2) +#define io116_config_analog mcu_config_analog(ANALOG2) +#define io116_get_analog mcu_get_analog(ANALOG2) +#elif ASSERT_PIN_EXTENDED(ANALOG2) +#define io116_config_analog +#define io116_get_analog 0 +#else +#define io116_config_analog +#define io116_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG3) +#define io117_config_analog mcu_config_analog(ANALOG3) +#define io117_get_analog mcu_get_analog(ANALOG3) +#elif ASSERT_PIN_EXTENDED(ANALOG3) +#define io117_config_analog +#define io117_get_analog 0 +#else +#define io117_config_analog +#define io117_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG4) +#define io118_config_analog mcu_config_analog(ANALOG4) +#define io118_get_analog mcu_get_analog(ANALOG4) +#elif ASSERT_PIN_EXTENDED(ANALOG4) +#define io118_config_analog +#define io118_get_analog 0 +#else +#define io118_config_analog +#define io118_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG5) +#define io119_config_analog mcu_config_analog(ANALOG5) +#define io119_get_analog mcu_get_analog(ANALOG5) +#elif ASSERT_PIN_EXTENDED(ANALOG5) +#define io119_config_analog +#define io119_get_analog 0 +#else +#define io119_config_analog +#define io119_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG6) +#define io120_config_analog mcu_config_analog(ANALOG6) +#define io120_get_analog mcu_get_analog(ANALOG6) +#elif ASSERT_PIN_EXTENDED(ANALOG6) +#define io120_config_analog +#define io120_get_analog 0 +#else +#define io120_config_analog +#define io120_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG7) +#define io121_config_analog mcu_config_analog(ANALOG7) +#define io121_get_analog mcu_get_analog(ANALOG7) +#elif ASSERT_PIN_EXTENDED(ANALOG7) +#define io121_config_analog +#define io121_get_analog 0 +#else +#define io121_config_analog +#define io121_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG8) +#define io122_config_analog mcu_config_analog(ANALOG8) +#define io122_get_analog mcu_get_analog(ANALOG8) +#elif ASSERT_PIN_EXTENDED(ANALOG8) +#define io122_config_analog +#define io122_get_analog 0 +#else +#define io122_config_analog +#define io122_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG9) +#define io123_config_analog mcu_config_analog(ANALOG9) +#define io123_get_analog mcu_get_analog(ANALOG9) +#elif ASSERT_PIN_EXTENDED(ANALOG9) +#define io123_config_analog +#define io123_get_analog 0 +#else +#define io123_config_analog +#define io123_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG10) +#define io124_config_analog mcu_config_analog(ANALOG10) +#define io124_get_analog mcu_get_analog(ANALOG10) +#elif ASSERT_PIN_EXTENDED(ANALOG10) +#define io124_config_analog +#define io124_get_analog 0 +#else +#define io124_config_analog +#define io124_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG11) +#define io125_config_analog mcu_config_analog(ANALOG11) +#define io125_get_analog mcu_get_analog(ANALOG11) +#elif ASSERT_PIN_EXTENDED(ANALOG11) +#define io125_config_analog +#define io125_get_analog 0 +#else +#define io125_config_analog +#define io125_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG12) +#define io126_config_analog mcu_config_analog(ANALOG12) +#define io126_get_analog mcu_get_analog(ANALOG12) +#elif ASSERT_PIN_EXTENDED(ANALOG12) +#define io126_config_analog +#define io126_get_analog 0 +#else +#define io126_config_analog +#define io126_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG13) +#define io127_config_analog mcu_config_analog(ANALOG13) +#define io127_get_analog mcu_get_analog(ANALOG13) +#elif ASSERT_PIN_EXTENDED(ANALOG13) +#define io127_config_analog +#define io127_get_analog 0 +#else +#define io127_config_analog +#define io127_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG14) +#define io128_config_analog mcu_config_analog(ANALOG14) +#define io128_get_analog mcu_get_analog(ANALOG14) +#elif ASSERT_PIN_EXTENDED(ANALOG14) +#define io128_config_analog +#define io128_get_analog 0 +#else +#define io128_config_analog +#define io128_get_analog 0 +#endif +#if ASSERT_PIN_IO(ANALOG15) +#define io129_config_analog mcu_config_analog(ANALOG15) +#define io129_get_analog mcu_get_analog(ANALOG15) +#elif ASSERT_PIN_EXTENDED(ANALOG15) +#define io129_config_analog +#define io129_get_analog 0 +#else +#define io129_config_analog +#define io129_get_analog 0 +#endif + + + +/*output HAL*/ +#define _io_hal_config_output_(pin) io##pin##_config_output +#define io_hal_config_output(pin) _io_hal_config_output_(pin) +#define _io_hal_set_output_(pin) io##pin##_set_output +#define io_hal_set_output(pin) _io_hal_set_output_(pin) +#define _io_hal_clear_output_(pin) io##pin##_clear_output +#define io_hal_clear_output(pin) _io_hal_clear_output_(pin) +#define _io_hal_toggle_output_(pin) io##pin##_toggle_output +#define io_hal_toggle_output(pin) _io_hal_toggle_output_(pin) +#define _io_hal_get_output_(pin) io##pin##_get_output +#define io_hal_get_output(pin) _io_hal_get_output_(pin) + +/*input HAL*/ +#define _io_hal_config_input_(pin) io##pin##_config_input +#define io_hal_config_input(pin) _io_hal_config_input_(pin) +#define _io_hal_config_pullup_(pin) io##pin##_config_pullup +#define io_hal_config_pullup(pin) _io_hal_config_pullup_(pin) +#define _io_hal_get_input_(pin) io##pin##_get_input +#define io_hal_get_input(pin) _io_hal_get_input_(pin) + +/*pwm and servo HAL*/ +#define _io_hal_config_pwm_(pin,freq) io##pin##_config_pwm(freq) +#define io_hal_config_pwm(pin,freq) _io_hal_config_pwm_(pin,freq) +#define _io_hal_set_pwm_(pin,value) io##pin##_set_pwm(value) +#define io_hal_set_pwm(pin,value) _io_hal_set_pwm_(pin,value) +#define _io_hal_get_pwm_(pin) io##pin##_get_pwm +#define io_hal_get_pwm(pin) _io_hal_get_pwm_(pin) + +/*analog HAL*/ +#define _io_hal_config_analog_(pin) io##pin##_config_analog +#define io_hal_config_analog(pin) _io_hal_config_analog_(pin) +#define _io_hal_get_analog_(pin) io##pin##_get_analog +#define io_hal_get_analog(pin) _io_hal_get_analog_(pin) + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/uCNC/src/hal/mcus/avr/mcu_avr.c b/uCNC/src/hal/mcus/avr/mcu_avr.c index 09219101b..0c819bdbc 100644 --- a/uCNC/src/hal/mcus/avr/mcu_avr.c +++ b/uCNC/src/hal/mcus/avr/mcu_avr.c @@ -51,22 +51,22 @@ static FORCEINLINE void mcu_clear_servos() RTC_TIMSK = (1U << RTC_OCIEA); RTC_TIFR = (1U << 2); #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } @@ -92,42 +92,42 @@ ISR(RTC_COMPA_vect, ISR_BLOCK) case SERVO0_FRAME: RTC_OCRB = mcu_servos[0]; servo_loops = mcu_servos_loops[0]; - mcu_set_output(SERVO0); + io_set_output(SERVO0); break; #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: RTC_OCRB = mcu_servos[1]; servo_loops = mcu_servos_loops[1]; - mcu_set_output(SERVO1); + io_set_output(SERVO1); break; #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: RTC_OCRB = mcu_servos[2]; servo_loops = mcu_servos_loops[2]; - mcu_set_output(SERVO2); + io_set_output(SERVO2); break; #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: RTC_OCRB = mcu_servos[3]; servo_loops = mcu_servos_loops[3]; - mcu_set_output(SERVO3); + io_set_output(SERVO3); break; #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: RTC_OCRB = mcu_servos[4]; servo_loops = mcu_servos_loops[4]; - mcu_set_output(SERVO4); + io_set_output(SERVO4); break; #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: RTC_OCRB = mcu_servos[5]; servo_loops = mcu_servos_loops[5]; - mcu_set_output(SERVO5); + io_set_output(SERVO5); break; #endif } @@ -586,7 +586,7 @@ void mcu_uart_flush(void) { SETBIT(UCSRB_REG, UDRIE_BIT); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } @@ -608,7 +608,7 @@ void mcu_uart2_flush(void) { SETBIT(UCSRB_REG_2, UDRIE_BIT_2); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 7c68c8c90..e97f4755c 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -109,97 +109,97 @@ IRAM_ATTR void mcu_pwm_isr(void *arg) #if ASSERT_PIN(PWM0) if (pwm_ref > esp32_pwm[0]) { - mcu_clear_output(PWM0); + io_clear_output(PWM0); } #endif #if ASSERT_PIN(PWM1) if (pwm_ref > esp32_pwm[1]) { - mcu_clear_output(PWM1); + io_clear_output(PWM1); } #endif #if ASSERT_PIN(PWM2) if (pwm_ref > esp32_pwm[2]) { - mcu_clear_output(PWM2); + io_clear_output(PWM2); } #endif #if ASSERT_PIN(PWM3) if (pwm_ref > esp32_pwm[3]) { - mcu_clear_output(PWM3); + io_clear_output(PWM3); } #endif #if ASSERT_PIN(PWM4) if (pwm_ref > esp32_pwm[4]) { - mcu_clear_output(PWM4); + io_clear_output(PWM4); } #endif #if ASSERT_PIN(PWM5) if (pwm_ref > esp32_pwm[5]) { - mcu_clear_output(PWM5); + io_clear_output(PWM5); } #endif #if ASSERT_PIN(PWM6) if (pwm_ref > esp32_pwm[6]) { - mcu_clear_output(PWM6); + io_clear_output(PWM6); } #endif #if ASSERT_PIN(PWM7) if (pwm_ref > esp32_pwm[7]) { - mcu_clear_output(PWM7); + io_clear_output(PWM7); } #endif #if ASSERT_PIN(PWM8) if (pwm_ref > esp32_pwm[8]) { - mcu_clear_output(PWM8); + io_clear_output(PWM8); } #endif #if ASSERT_PIN(PWM9) if (pwm_ref > esp32_pwm[9]) { - mcu_clear_output(PWM9); + io_clear_output(PWM9); } #endif #if ASSERT_PIN(PWM10) if (pwm_ref > esp32_pwm[10]) { - mcu_clear_output(PWM10); + io_clear_output(PWM10); } #endif #if ASSERT_PIN(PWM11) if (pwm_ref > esp32_pwm[11]) { - mcu_clear_output(PWM11); + io_clear_output(PWM11); } #endif #if ASSERT_PIN(PWM12) if (pwm_ref > esp32_pwm[12]) { - mcu_clear_output(PWM12); + io_clear_output(PWM12); } #endif #if ASSERT_PIN(PWM13) if (pwm_ref > esp32_pwm[13]) { - mcu_clear_output(PWM13); + io_clear_output(PWM13); } #endif #if ASSERT_PIN(PWM14) if (pwm_ref > esp32_pwm[14]) { - mcu_clear_output(PWM14); + io_clear_output(PWM14); } #endif #if ASSERT_PIN(PWM15) if (pwm_ref > esp32_pwm[15]) { - mcu_clear_output(PWM15); + io_clear_output(PWM15); } #endif @@ -308,97 +308,97 @@ IRAM_ATTR void mcu_pwm_isr(void *arg) #if ASSERT_PIN(PWM0) if (esp32_pwm[0]) { - mcu_set_output(PWM0); + io_set_output(PWM0); } #endif #if ASSERT_PIN(PWM1) if (esp32_pwm[1]) { - mcu_set_output(PWM1); + io_set_output(PWM1); } #endif #if ASSERT_PIN(PWM2) if (esp32_pwm[2]) { - mcu_set_output(PWM2); + io_set_output(PWM2); } #endif #if ASSERT_PIN(PWM3) if (esp32_pwm[3]) { - mcu_set_output(PWM3); + io_set_output(PWM3); } #endif #if ASSERT_PIN(PWM4) if (esp32_pwm[4]) { - mcu_set_output(PWM4); + io_set_output(PWM4); } #endif #if ASSERT_PIN(PWM5) if (esp32_pwm[5]) { - mcu_set_output(PWM5); + io_set_output(PWM5); } #endif #if ASSERT_PIN(PWM6) if (esp32_pwm[6]) { - mcu_set_output(PWM6); + io_set_output(PWM6); } #endif #if ASSERT_PIN(PWM7) if (esp32_pwm[7]) { - mcu_set_output(PWM7); + io_set_output(PWM7); } #endif #if ASSERT_PIN(PWM8) if (esp32_pwm[8]) { - mcu_set_output(PWM8); + io_set_output(PWM8); } #endif #if ASSERT_PIN(PWM9) if (esp32_pwm[9]) { - mcu_set_output(PWM9); + io_set_output(PWM9); } #endif #if ASSERT_PIN(PWM10) if (esp32_pwm[10]) { - mcu_set_output(PWM10); + io_set_output(PWM10); } #endif #if ASSERT_PIN(PWM11) if (esp32_pwm[11]) { - mcu_set_output(PWM11); + io_set_output(PWM11); } #endif #if ASSERT_PIN(PWM12) if (esp32_pwm[12]) { - mcu_set_output(PWM12); + io_set_output(PWM12); } #endif #if ASSERT_PIN(PWM13) if (esp32_pwm[13]) { - mcu_set_output(PWM13); + io_set_output(PWM13); } #endif #if ASSERT_PIN(PWM14) if (esp32_pwm[14]) { - mcu_set_output(PWM14); + io_set_output(PWM14); } #endif #if ASSERT_PIN(PWM15) if (esp32_pwm[15]) { - mcu_set_output(PWM15); + io_set_output(PWM15); } #endif } @@ -426,22 +426,22 @@ IRAM_ATTR void servo_reset(void *p) timer_pause(SERVO_TIMER_TG, SERVO_TIMER_IDX); timer_group_clr_intr_status_in_isr(SERVO_TIMER_TG, SERVO_TIMER_IDX); #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif #ifdef IC74HC595_HAS_SERVOS ic74hc595_set_servos(0); @@ -545,7 +545,7 @@ void mcu_rtc_task(void *arg) { #if ASSERT_PIN(SERVO0) case SERVO0_FRAME: - mcu_set_output(SERVO0); + io_set_output(SERVO0); start_servo_timeout(mcu_servos[0]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO0_MASK; @@ -554,7 +554,7 @@ void mcu_rtc_task(void *arg) #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: - mcu_set_output(SERVO1); + io_set_output(SERVO1); start_servo_timeout(mcu_servos[1]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO1_MASK; @@ -563,7 +563,7 @@ void mcu_rtc_task(void *arg) #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: - mcu_set_output(SERVO2); + io_set_output(SERVO2); start_servo_timeout(mcu_servos[2]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO2_MASK; @@ -572,7 +572,7 @@ void mcu_rtc_task(void *arg) #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: - mcu_set_output(SERVO3); + io_set_output(SERVO3); start_servo_timeout(mcu_servos[3]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO3_MASK; @@ -581,7 +581,7 @@ void mcu_rtc_task(void *arg) #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: - mcu_set_output(SERVO4); + io_set_output(SERVO4); start_servo_timeout(mcu_servos[4]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO4_MASK; @@ -590,7 +590,7 @@ void mcu_rtc_task(void *arg) #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: - mcu_set_output(SERVO5); + io_set_output(SERVO5); start_servo_timeout(mcu_servos[5]); #ifdef IC74HC595_HAS_SERVOS servomask = SERVO5_MASK; diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 3f67203ef..d8abf2c58 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -83,97 +83,97 @@ static IRAM_ATTR void mcu_gen_pwm(void) #if ASSERT_PIN(PWM0) if (pwm_counter > esp8266_pwm[0]) { - mcu_clear_output(PWM0); + io_clear_output(PWM0); } #endif #if ASSERT_PIN(PWM1) if (pwm_counter > esp8266_pwm[1]) { - mcu_clear_output(PWM1); + io_clear_output(PWM1); } #endif #if ASSERT_PIN(PWM2) if (pwm_counter > esp8266_pwm[2]) { - mcu_clear_output(PWM2); + io_clear_output(PWM2); } #endif #if ASSERT_PIN(PWM3) if (pwm_counter > esp8266_pwm[3]) { - mcu_clear_output(PWM3); + io_clear_output(PWM3); } #endif #if ASSERT_PIN(PWM4) if (pwm_counter > esp8266_pwm[4]) { - mcu_clear_output(PWM4); + io_clear_output(PWM4); } #endif #if ASSERT_PIN(PWM5) if (pwm_counter > esp8266_pwm[5]) { - mcu_clear_output(PWM5); + io_clear_output(PWM5); } #endif #if ASSERT_PIN(PWM6) if (pwm_counter > esp8266_pwm[6]) { - mcu_clear_output(PWM6); + io_clear_output(PWM6); } #endif #if ASSERT_PIN(PWM7) if (pwm_counter > esp8266_pwm[7]) { - mcu_clear_output(PWM7); + io_clear_output(PWM7); } #endif #if ASSERT_PIN(PWM8) if (pwm_counter > esp8266_pwm[8]) { - mcu_clear_output(PWM8); + io_clear_output(PWM8); } #endif #if ASSERT_PIN(PWM9) if (pwm_counter > esp8266_pwm[9]) { - mcu_clear_output(PWM9); + io_clear_output(PWM9); } #endif #if ASSERT_PIN(PWM10) if (pwm_counter > esp8266_pwm[10]) { - mcu_clear_output(PWM10); + io_clear_output(PWM10); } #endif #if ASSERT_PIN(PWM11) if (pwm_counter > esp8266_pwm[11]) { - mcu_clear_output(PWM11); + io_clear_output(PWM11); } #endif #if ASSERT_PIN(PWM12) if (pwm_counter > esp8266_pwm[12]) { - mcu_clear_output(PWM12); + io_clear_output(PWM12); } #endif #if ASSERT_PIN(PWM13) if (pwm_counter > esp8266_pwm[13]) { - mcu_clear_output(PWM13); + io_clear_output(PWM13); } #endif #if ASSERT_PIN(PWM14) if (pwm_counter > esp8266_pwm[14]) { - mcu_clear_output(PWM14); + io_clear_output(PWM14); } #endif #if ASSERT_PIN(PWM15) if (pwm_counter > esp8266_pwm[15]) { - mcu_clear_output(PWM15); + io_clear_output(PWM15); } #endif } @@ -183,97 +183,97 @@ static IRAM_ATTR void mcu_gen_pwm(void) #if ASSERT_PIN(PWM0) if (esp8266_pwm[0]) { - mcu_set_output(PWM0); + io_set_output(PWM0); } #endif #if ASSERT_PIN(PWM1) if (esp8266_pwm[1]) { - mcu_set_output(PWM1); + io_set_output(PWM1); } #endif #if ASSERT_PIN(PWM2) if (esp8266_pwm[2]) { - mcu_set_output(PWM2); + io_set_output(PWM2); } #endif #if ASSERT_PIN(PWM3) if (esp8266_pwm[3]) { - mcu_set_output(PWM3); + io_set_output(PWM3); } #endif #if ASSERT_PIN(PWM4) if (esp8266_pwm[4]) { - mcu_set_output(PWM4); + io_set_output(PWM4); } #endif #if ASSERT_PIN(PWM5) if (esp8266_pwm[5]) { - mcu_set_output(PWM5); + io_set_output(PWM5); } #endif #if ASSERT_PIN(PWM6) if (esp8266_pwm[6]) { - mcu_set_output(PWM6); + io_set_output(PWM6); } #endif #if ASSERT_PIN(PWM7) if (esp8266_pwm[7]) { - mcu_set_output(PWM7); + io_set_output(PWM7); } #endif #if ASSERT_PIN(PWM8) if (esp8266_pwm[8]) { - mcu_set_output(PWM8); + io_set_output(PWM8); } #endif #if ASSERT_PIN(PWM9) if (esp8266_pwm[9]) { - mcu_set_output(PWM9); + io_set_output(PWM9); } #endif #if ASSERT_PIN(PWM10) if (esp8266_pwm[10]) { - mcu_set_output(PWM10); + io_set_output(PWM10); } #endif #if ASSERT_PIN(PWM11) if (esp8266_pwm[11]) { - mcu_set_output(PWM11); + io_set_output(PWM11); } #endif #if ASSERT_PIN(PWM12) if (esp8266_pwm[12]) { - mcu_set_output(PWM12); + io_set_output(PWM12); } #endif #if ASSERT_PIN(PWM13) if (esp8266_pwm[13]) { - mcu_set_output(PWM13); + io_set_output(PWM13); } #endif #if ASSERT_PIN(PWM14) if (esp8266_pwm[14]) { - mcu_set_output(PWM14); + io_set_output(PWM14); } #endif #if ASSERT_PIN(PWM15) if (esp8266_pwm[15]) { - mcu_set_output(PWM15); + io_set_output(PWM15); } #endif } diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index b80fc7225..aebede043 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -48,7 +48,7 @@ extern "C" mcu_delay_us(50); mcu_usb_dotasks(); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); // Flash quickly during USB initialization + io_toggle_output(ACTIVITY_LED); // Flash quickly during USB initialization #endif } UsbSerial.begin(BAUDRATE); diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index c0ee367be..fd9d4243e 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -50,22 +50,22 @@ static uint8_t mcu_servos[6]; static FORCEINLINE void mcu_clear_servos() { #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } @@ -79,38 +79,38 @@ static FORCEINLINE void mcu_set_servos() { #if ASSERT_PIN(SERVO0) case 0: - mcu_set_output(SERVO0); + io_set_output(SERVO0); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[0]); break; #endif #if ASSERT_PIN(SERVO1) case 1: - mcu_set_output(SERVO1); + io_set_output(SERVO1); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[1]); break; #endif #if ASSERT_PIN(SERVO2) case 2: - mcu_set_output(SERVO2); + io_set_output(SERVO2); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[2]); break; #endif #if ASSERT_PIN(SERVO3) case 3: - mcu_set_output(SERVO3); + io_set_output(SERVO3); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[3]); break; #endif #if ASSERT_PIN(SERVO4) case 4: - mcu_set_output(SERVO4); + io_set_output(SERVO4); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[4]); break; #endif #if ASSERT_PIN(SERVO5) case 5: - mcu_set_output(SERVO5); + io_set_output(SERVO5); SERVO_TIMER_REG->MR1 = (SERVO_MIN + mcu_servos[5]); break; #endif @@ -597,7 +597,7 @@ void mcu_uart_flush(void) COM_OUTREG = c; COM_UART->IER |= UART_IER_THREINT_EN; #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } @@ -628,7 +628,7 @@ void mcu_uart2_flush(void) COM2_OUTREG = c; COM2_UART->IER |= UART_IER_THREINT_EN; #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } diff --git a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c index 578acf24a..6b032574f 100644 --- a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c +++ b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c @@ -175,22 +175,22 @@ static rp2040_alarm_t servo_alarm; static void mcu_clear_servos(void) { #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } #endif @@ -212,36 +212,36 @@ void mcu_rtc_isr(void) #if ASSERT_PIN(SERVO0) case SERVO0_FRAME: servo_start_timeout(mcu_servos[0]); - mcu_set_output(SERVO0); + io_set_output(SERVO0); break; #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: - mcu_set_output(SERVO1); + io_set_output(SERVO1); servo_start_timeout(mcu_servos[1]); break; #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: - mcu_set_output(SERVO2); + io_set_output(SERVO2); servo_start_timeout(mcu_servos[2]); break; #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: - mcu_set_output(SERVO3); + io_set_output(SERVO3); servo_start_timeout(mcu_servos[3]); break; #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: - mcu_set_output(SERVO4); + io_set_output(SERVO4); servo_start_timeout(mcu_servos[4]); break; #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: - mcu_set_output(SERVO5); + io_set_output(SERVO5); servo_start_timeout(mcu_servos[5]); break; #endif diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index a1763cb6d..6a931774a 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -415,22 +415,22 @@ static uint16_t mcu_servos[6]; static FORCEINLINE void mcu_clear_servos() { #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } @@ -536,36 +536,36 @@ void sysTickHook(void) #if ASSERT_PIN(SERVO0) case SERVO0_FRAME: servo_start_timeout(mcu_servos[0]); - mcu_set_output(SERVO0); + io_set_output(SERVO0); break; #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: - mcu_set_output(SERVO1); + io_set_output(SERVO1); servo_start_timeout(mcu_servos[1]); break; #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: - mcu_set_output(SERVO2); + io_set_output(SERVO2); servo_start_timeout(mcu_servos[2]); break; #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: - mcu_set_output(SERVO3); + io_set_output(SERVO3); servo_start_timeout(mcu_servos[3]); break; #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: - mcu_set_output(SERVO4); + io_set_output(SERVO4); servo_start_timeout(mcu_servos[4]); break; #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: - mcu_set_output(SERVO5); + io_set_output(SERVO5); servo_start_timeout(mcu_servos[5]); break; #endif @@ -786,7 +786,7 @@ void mcu_uart_flush(void) { COM_UART->USART.INTENSET.bit.DRE = 1; // enable recieved interrupt #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } @@ -808,7 +808,7 @@ void mcu_uart_flush(void) { COM2_UART->USART.INTENSET.bit.DRE = 1; // enable tx interrupt #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 1d1400dc8..14cf75bd7 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -173,22 +173,22 @@ static uint8_t mcu_servos[6]; static FORCEINLINE void mcu_clear_servos() { #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } @@ -351,36 +351,36 @@ void osSystickHandler(void) #if ASSERT_PIN(SERVO0) case SERVO0_FRAME: servo_start_timeout(mcu_servos[0]); - mcu_set_output(SERVO0); + io_set_output(SERVO0); break; #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: - mcu_set_output(SERVO1); + io_set_output(SERVO1); servo_start_timeout(mcu_servos[1]); break; #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: - mcu_set_output(SERVO2); + io_set_output(SERVO2); servo_start_timeout(mcu_servos[2]); break; #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: - mcu_set_output(SERVO3); + io_set_output(SERVO3); servo_start_timeout(mcu_servos[3]); break; #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: - mcu_set_output(SERVO4); + io_set_output(SERVO4); servo_start_timeout(mcu_servos[4]); break; #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: - mcu_set_output(SERVO5); + io_set_output(SERVO5); servo_start_timeout(mcu_servos[5]); break; #endif @@ -507,7 +507,7 @@ void mcu_uart_flush(void) { COM_UART->CR1 |= (USART_CR1_TXEIE); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } @@ -531,7 +531,7 @@ void mcu_uart2_flush(void) { COM2_UART->CR1 |= (USART_CR1_TXEIE); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index f36aec1bd..37882ef1a 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -164,22 +164,22 @@ static uint8_t mcu_servos[6]; static FORCEINLINE void mcu_clear_servos() { #if ASSERT_PIN(SERVO0) - mcu_clear_output(SERVO0); + io_clear_output(SERVO0); #endif #if ASSERT_PIN(SERVO1) - mcu_clear_output(SERVO1); + io_clear_output(SERVO1); #endif #if ASSERT_PIN(SERVO2) - mcu_clear_output(SERVO2); + io_clear_output(SERVO2); #endif #if ASSERT_PIN(SERVO3) - mcu_clear_output(SERVO3); + io_clear_output(SERVO3); #endif #if ASSERT_PIN(SERVO4) - mcu_clear_output(SERVO4); + io_clear_output(SERVO4); #endif #if ASSERT_PIN(SERVO5) - mcu_clear_output(SERVO5); + io_clear_output(SERVO5); #endif } @@ -335,36 +335,36 @@ void osSystickHandler(void) #if ASSERT_PIN(SERVO0) case SERVO0_FRAME: servo_start_timeout(mcu_servos[0]); - mcu_set_output(SERVO0); + io_set_output(SERVO0); break; #endif #if ASSERT_PIN(SERVO1) case SERVO1_FRAME: - mcu_set_output(SERVO1); + io_set_output(SERVO1); servo_start_timeout(mcu_servos[1]); break; #endif #if ASSERT_PIN(SERVO2) case SERVO2_FRAME: - mcu_set_output(SERVO2); + io_set_output(SERVO2); servo_start_timeout(mcu_servos[2]); break; #endif #if ASSERT_PIN(SERVO3) case SERVO3_FRAME: - mcu_set_output(SERVO3); + io_set_output(SERVO3); servo_start_timeout(mcu_servos[3]); break; #endif #if ASSERT_PIN(SERVO4) case SERVO4_FRAME: - mcu_set_output(SERVO4); + io_set_output(SERVO4); servo_start_timeout(mcu_servos[4]); break; #endif #if ASSERT_PIN(SERVO5) case SERVO5_FRAME: - mcu_set_output(SERVO5); + io_set_output(SERVO5); servo_start_timeout(mcu_servos[5]); break; #endif @@ -519,7 +519,7 @@ void mcu_uart_flush(void) { COM_UART->CR1 |= (USART_CR1_TXEIE); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } @@ -543,7 +543,7 @@ void mcu_uart2_flush(void) { COM2_UART->CR1 |= (USART_CR1_TXEIE); #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } } diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index ed83f0fe5..85d2cee9e 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -36,11 +36,11 @@ static void startup_code(void) { // force laser mode #if ASSERT_PIN(LASER_PPI) - mcu_config_output(LASER_PPI); + io_config_output(LASER_PPI); #ifndef INVERT_LASER_PPI_LOGIC - mcu_clear_output(LASER_PPI); + io_clear_output(LASER_PPI); #else - mcu_set_output(LASER_PPI); + io_set_output(LASER_PPI); #endif #endif g_settings.laser_mode |= LASER_PPI_MODE; @@ -51,9 +51,9 @@ static void shutdown_code(void) { #if ASSERT_PIN(LASER_PPI) #ifndef INVERT_LASER_PPI_LOGIC - mcu_clear_output(LASER_PPI); + io_clear_output(LASER_PPI); #else - mcu_set_output(LASER_PPI); + io_set_output(LASER_PPI); #endif #endif // restore laser mode diff --git a/uCNC/src/hal/tools/tools/laser_pwm.c b/uCNC/src/hal/tools/tools/laser_pwm.c index 409da4812..6499a50e8 100644 --- a/uCNC/src/hal/tools/tools/laser_pwm.c +++ b/uCNC/src/hal/tools/tools/laser_pwm.c @@ -53,8 +53,8 @@ static void startup_code(void) { // force laser mode #if ASSERT_PIN(LASER_PWM) - mcu_config_pwm(LASER_PWM, LASER_FREQ); - mcu_set_pwm(LASER_PWM, 0); + io_config_pwm(LASER_PWM, LASER_FREQ); + io_set_pwm(LASER_PWM, 0); #else io_set_pwm(LASER_PWM, 0); #endif @@ -75,7 +75,7 @@ static void set_speed(int16_t value) // speed optimized version (in AVR it's 24 instruction cycles) #if ASSERT_PIN(LASER_PWM) - mcu_set_pwm(LASER_PWM, (uint8_t)ABS(value)); + io_set_pwm(LASER_PWM, (uint8_t)ABS(value)); #else io_set_pwm(LASER_PWM, (uint8_t)ABS(value)); #endif @@ -99,7 +99,7 @@ static void set_coolant(uint8_t value) static uint16_t get_speed(void) { #if ASSERT_PIN(LASER_PWM) - float laser = (float)mcu_get_pwm(LASER_PWM) * g_settings.spindle_max_rpm * UINT8_MAX_INV; + float laser = (float)io_get_pwm(LASER_PWM) * g_settings.spindle_max_rpm * UINT8_MAX_INV; return (uint16_t)lroundf(laser); #else return 0; diff --git a/uCNC/src/hal/tools/tools/spindle_besc.c b/uCNC/src/hal/tools/tools/spindle_besc.c index 6597e976f..d39109c58 100644 --- a/uCNC/src/hal/tools/tools/spindle_besc.c +++ b/uCNC/src/hal/tools/tools/spindle_besc.c @@ -67,7 +67,7 @@ static void startup_code(void) #if ASSERT_PIN(SPINDLE_BESC_SERVO) mcu_set_servo(SPINDLE_BESC_SERVO, SPINDLE_BESC_MID); #endif - mcu_set_output(SPINDLE_BESC_POWER_RELAY); + io_set_output(SPINDLE_BESC_POWER_RELAY); cnc_delay_ms(1000); #if ASSERT_PIN(SPINDLE_BESC_SERVO) mcu_set_servo(SPINDLE_BESC_SERVO, SPINDLE_BESC_LOW); @@ -79,7 +79,7 @@ static void startup_code(void) static void shutdown_code(void) { #if ASSERT_PIN(SPINDLE_BESC_POWER_RELAY) - mcu_clear_output(SPINDLE_BESC_POWER_RELAY); + io_clear_output(SPINDLE_BESC_POWER_RELAY); #endif } diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 5edf2ee95..5258a17d8 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -56,7 +56,7 @@ static void startup_code(void) { // force pwm mode #if ASSERT_PIN(SPINDLE_PWM) - mcu_config_pwm(SPINDLE_PWM, 1000); + io_config_pwm(SPINDLE_PWM, 1000); #endif } @@ -69,16 +69,16 @@ static void set_speed(int16_t value) #if ASSERT_PIN(SPINDLE_PWM_DIR) if ((value <= 0)) { - mcu_clear_output(SPINDLE_PWM_DIR); + io_clear_output(SPINDLE_PWM_DIR); } else { - mcu_set_output(SPINDLE_PWM_DIR); + io_set_output(SPINDLE_PWM_DIR); } #endif #if ASSERT_PIN(SPINDLE_PWM) - mcu_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); + io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); #else io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); #endif @@ -117,9 +117,9 @@ static void pid_update(int16_t value) { if (speed != 0) { - uint8_t newval = CLAMP(0, mcu_get_pwm(SPINDLE_PWM) + value, 255); + uint8_t newval = CLAMP(0, io_get_pwm(SPINDLE_PWM) + value, 255); #if ASSERT_PIN(SPINDLE_PWM) - mcu_set_pwm(SPINDLE_PWM, newval); + io_set_pwm(SPINDLE_PWM, newval); #else io_set_pwm(SPINDLE_PWM, newval); #endif @@ -129,7 +129,7 @@ static void pid_update(int16_t value) static int16_t pid_error(void) { #if (ASSERT_PIN(SPINDLE_FEEDBACK) && ASSERT_PIN(SPINDLE_PWM)) - uint8_t reader = mcu_get_analog(ANALOG0); + uint8_t reader = io_get_analog(ANALOG0); return (speed - reader); #else return 0; diff --git a/uCNC/src/hal/tools/tools/spindle_relay.c b/uCNC/src/hal/tools/tools/spindle_relay.c index 0e10993b0..f88f623a3 100644 --- a/uCNC/src/hal/tools/tools/spindle_relay.c +++ b/uCNC/src/hal/tools/tools/spindle_relay.c @@ -50,28 +50,28 @@ void set_speed(int16_t value) if (value == 0) { #if ASSERT_PIN(SPINDLE_RELAY_FWD) - mcu_clear_output(SPINDLE_RELAY_FWD); + io_clear_output(SPINDLE_RELAY_FWD); #endif #if ASSERT_PIN(SPINDLE_RELAY_REV) - mcu_clear_output(SPINDLE_RELAY_REV); + io_clear_output(SPINDLE_RELAY_REV); #endif } else if (value < 0) { #if ASSERT_PIN(SPINDLE_RELAY_FWD) - mcu_clear_output(SPINDLE_RELAY_FWD); + io_clear_output(SPINDLE_RELAY_FWD); #endif #if ASSERT_PIN(SPINDLE_RELAY_REV) - mcu_set_output(SPINDLE_RELAY_REV); + io_set_output(SPINDLE_RELAY_REV); #endif } else { #if ASSERT_PIN(SPINDLE_RELAY_REV) - mcu_clear_output(SPINDLE_RELAY_REV); + io_clear_output(SPINDLE_RELAY_REV); #endif #if ASSERT_PIN(SPINDLE_RELAY_FWD) - mcu_set_output(SPINDLE_RELAY_FWD); + io_set_output(SPINDLE_RELAY_FWD); #endif } } diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index 73f4a98d4..9ab92f569 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -54,7 +54,7 @@ static void startup_code(void) { // force pwm mode #if ASSERT_PIN(VFD_PWM) - mcu_config_pwm(VFD_PWM, 1000); + io_config_pwm(VFD_PWM, 1000); #endif } @@ -67,16 +67,16 @@ static void set_speed(int16_t value) #if ASSERT_PIN(VFD_PWM_DIR) if ((value <= 0)) { - mcu_clear_output(VFD_PWM_DIR); + io_clear_output(VFD_PWM_DIR); } else { - mcu_set_output(VFD_PWM_DIR); + io_set_output(VFD_PWM_DIR); } #endif #if ASSERT_PIN(VFD_PWM) - mcu_set_pwm(VFD_PWM, (uint8_t)ABS(value)); + io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); #else io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); #endif @@ -99,7 +99,7 @@ static int16_t range_speed(int16_t value) static uint16_t get_speed(void) { #if ASSERT_PIN(VFD_PWM_ANALOG_FEEDBACK) - float spindle = (float)mcu_get_analog(VFD_PWM_ANALOG_FEEDBACK) * g_settings.spindle_max_rpm * UINT8_MAX_INV; + float spindle = (float)io_get_analog(VFD_PWM_ANALOG_FEEDBACK) * g_settings.spindle_max_rpm * UINT8_MAX_INV; return (uint16_t)lroundf(spindle); #else return 0; @@ -111,9 +111,9 @@ static void pid_update(int16_t value) { if (speed != 0) { - uint8_t newval = CLAMP(0, mcu_get_pwm(VFD_PWM) + value, 255); + uint8_t newval = CLAMP(0, io_get_pwm(VFD_PWM) + value, 255); #if ASSERT_PIN(VFD_PWM) - mcu_set_pwm(VFD_PWM, newval); + io_set_pwm(VFD_PWM, newval); #else io_set_pwm(VFD_PWM, newval); #endif @@ -123,7 +123,7 @@ static void pid_update(int16_t value) static int16_t pid_error(void) { #if (ASSERT_PIN(VFD_PWM_ANALOG_FEEDBACK) && ASSERT_PIN(VFD_PWM)) - uint8_t reader = mcu_get_analog(VFD_PWM_ANALOG_FEEDBACK); + uint8_t reader = io_get_analog(VFD_PWM_ANALOG_FEEDBACK); return (speed - reader); #else return 0; diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 32e500734..b1b0a948c 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -173,7 +173,7 @@ void serial_putc(unsigned char c) serial_flush(); } #if ASSERT_PIN(ACTIVITY_LED) - mcu_toggle_output(ACTIVITY_LED); + io_toggle_output(ACTIVITY_LED); #endif } diff --git a/uCNC/src/modules/digimstep.c b/uCNC/src/modules/digimstep.c index 720be5353..1843e56d4 100644 --- a/uCNC/src/modules/digimstep.c +++ b/uCNC/src/modules/digimstep.c @@ -70,88 +70,88 @@ bool m351_exec(void *args) val = -1; serial_putc('X'); #if ASSERT_PIN(STEPPER0_MSTEP0) - val = mcu_get_output(STEPPER0_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER0_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER0_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER0_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER0_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('Y'); #if ASSERT_PIN(STEPPER1_MSTEP0) - val = mcu_get_output(STEPPER1_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER1_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER1_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER1_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER1_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('Z'); #if ASSERT_PIN(STEPPER2_MSTEP0) - val = mcu_get_output(STEPPER2_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER2_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER2_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER2_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER2_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('A'); #if ASSERT_PIN(STEPPER3_MSTEP0) - val = mcu_get_output(STEPPER3_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER3_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER3_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER3_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER3_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('B'); #if ASSERT_PIN(STEPPER4_MSTEP0) - val = mcu_get_output(STEPPER4_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER4_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER4_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER4_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER4_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('C'); #if ASSERT_PIN(STEPPER5_MSTEP0) - val = mcu_get_output(STEPPER5_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER5_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER5_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER5_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER5_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('I'); #if ASSERT_PIN(STEPPER6_MSTEP0) - val = mcu_get_output(STEPPER6_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER6_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER6_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER6_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER6_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(','); val = -1; serial_putc('J'); #if ASSERT_PIN(STEPPER7_MSTEP0) - val = mcu_get_output(STEPPER7_MSTEP0) ? 1 : 0; + val = io_get_output(STEPPER7_MSTEP0) ? 1 : 0; #endif #if ASSERT_PIN(STEPPER7_MSTEP1) val = MAX(0, val); - val |= mcu_get_output(STEPPER7_MSTEP1) ? 2 : 0; + val |= io_get_output(STEPPER7_MSTEP1) ? 2 : 0; #endif serial_print_int(val); serial_putc(']'); diff --git a/uCNC/src/modules/digipot.c b/uCNC/src/modules/digipot.c index 3fb87c29b..6cedfe3a7 100644 --- a/uCNC/src/modules/digipot.c +++ b/uCNC/src/modules/digipot.c @@ -71,7 +71,7 @@ bool m907_exec(void *args) return STATUS_GCODE_NO_AXIS_WORDS; } - mcu_clear_output(STEPPER_DIGIPOT_CS); + io_clear_output(STEPPER_DIGIPOT_CS); if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_X)) { @@ -130,7 +130,7 @@ bool m907_exec(void *args) #endif } - mcu_set_output(STEPPER_DIGIPOT_CS); + io_set_output(STEPPER_DIGIPOT_CS); *(ptr->error) = STATUS_OK; return EVENT_HANDLED; @@ -145,7 +145,7 @@ bool digipot_config(void *args) { // Digipot for stepper motors #ifdef STEPPER_CURR_DIGIPOT - mcu_clear_output(STEPPER_DIGIPOT_CS); + io_clear_output(STEPPER_DIGIPOT_CS); #if STEPPER0_DIGIPOT_CHANNEL > 0 softspi_xmit(&digipotspi, STEPPER0_DIGIPOT_CHANNEL); softspi_xmit(&digipotspi, STEPPER0_DIGIPOT_VALUE); @@ -178,7 +178,7 @@ bool digipot_config(void *args) softspi_xmit(&digipotspi, STEPPER7_DIGIPOT_CHANNEL); softspi_xmit(&digipotspi, STEPPER7_DIGIPOT_VALUE); #endif - mcu_set_output(STEPPER_DIGIPOT_CS); + io_set_output(STEPPER_DIGIPOT_CS); #endif return EVENT_CONTINUE; @@ -192,7 +192,7 @@ DECL_MODULE(digipot) { // initialize slave select pins #ifdef STEPPER_CURR_DIGIPOT - mcu_set_output(STEPPER_DIGIPOT_CS); + io_set_output(STEPPER_DIGIPOT_CS); #endif #ifdef ENABLE_MAIN_LOOP_MODULES diff --git a/uCNC/src/modules/encoder.c b/uCNC/src/modules/encoder.c index cbefbfe51..927294d17 100644 --- a/uCNC/src/modules/encoder.c +++ b/uCNC/src/modules/encoder.c @@ -76,28 +76,28 @@ static FORCEINLINE uint8_t encoder_read_dirs(void) { uint8_t value = 0; #if ENCODERS > 0 - value |= ((mcu_get_input(ENC0_DIR)) ? ENC0_MASK : 0); + value |= ((io_get_input(ENC0_DIR)) ? ENC0_MASK : 0); #endif #if ENCODERS > 1 - value |= ((mcu_get_input(ENC1_DIR)) ? ENC1_MASK : 0); + value |= ((io_get_input(ENC1_DIR)) ? ENC1_MASK : 0); #endif #if ENCODERS > 2 - value |= ((mcu_get_input(ENC2_DIR)) ? ENC2_MASK : 0); + value |= ((io_get_input(ENC2_DIR)) ? ENC2_MASK : 0); #endif #if ENCODERS > 3 - value |= ((mcu_get_input(ENC3_DIR)) ? ENC3_MASK : 0); + value |= ((io_get_input(ENC3_DIR)) ? ENC3_MASK : 0); #endif #if ENCODERS > 4 - value |= ((mcu_get_input(ENC4_DIR)) ? ENC4_MASK : 0); + value |= ((io_get_input(ENC4_DIR)) ? ENC4_MASK : 0); #endif #if ENCODERS > 5 - value |= ((mcu_get_input(ENC5_DIR)) ? ENC5_MASK : 0); + value |= ((io_get_input(ENC5_DIR)) ? ENC5_MASK : 0); #endif #if ENCODERS > 6 - value |= ((mcu_get_input(ENC6_DIR)) ? ENC6_MASK : 0); + value |= ((io_get_input(ENC6_DIR)) ? ENC6_MASK : 0); #endif #if ENCODERS > 7 - value |= ((mcu_get_input(ENC7_DIR)) ? ENC7_MASK : 0); + value |= ((io_get_input(ENC7_DIR)) ? ENC7_MASK : 0); #endif return value ^ g_settings.encoders_dir_invert_mask; } @@ -167,7 +167,7 @@ void encoders_update(uint8_t pulse, uint8_t diff) prev_time = current_time; current_time = time; #ifdef RPM_INDEX_OUTPUT - if (mcu_get_input(RPM_INDEX_INPUT)) + if (io_get_input(RPM_INDEX_INPUT)) #else if (encoders_pos[RPM_ENCODER] >= RPM_PPR) #endif diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index c703d71c7..0c069b83c 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -91,7 +91,7 @@ void __attribute__((weak)) ic74hc595_shift_io_pins(void) FORCEINLINE void ic74hc595_set_steps(uint8_t mask) { -#if ASSERT_PIN_EXTENDER(STEP0_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP0_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] |= STEP0_IO_BITMASK; @@ -101,7 +101,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] &= ~STEP0_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP1_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP1_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] |= STEP1_IO_BITMASK; @@ -111,7 +111,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] &= ~STEP1_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP2_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP2_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] |= STEP2_IO_BITMASK; @@ -121,7 +121,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] &= ~STEP2_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP3_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP3_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] |= STEP3_IO_BITMASK; @@ -131,7 +131,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] &= ~STEP3_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP4_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP4_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] |= STEP4_IO_BITMASK; @@ -141,7 +141,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] &= ~STEP4_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP5_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP5_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] |= STEP5_IO_BITMASK; @@ -151,7 +151,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] &= ~STEP5_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP6_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP6_IO_OFFSET) if (mask & (1 << 6)) { ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] |= STEP6_IO_BITMASK; @@ -161,7 +161,7 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] &= ~STEP6_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP7_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP7_IO_OFFSET) if (mask & (1 << 7)) { ic74hc595_io_pins[STEP7_IO_BYTEOFFSET] |= STEP7_IO_BITMASK; @@ -177,49 +177,49 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) FORCEINLINE void ic74hc595_toggle_steps(uint8_t mask) { -#if ASSERT_PIN_EXTENDER(STEP0_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP0_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] ^= STEP0_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP1_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP1_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] ^= STEP1_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP2_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP2_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] ^= STEP2_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP3_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP3_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] ^= STEP3_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP4_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP4_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] ^= STEP4_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP5_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP5_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] ^= STEP5_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP6_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP6_IO_OFFSET) if (mask & (1 << 6)) { ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] ^= STEP6_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP7_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP7_IO_OFFSET) if (mask & (1 << 7)) { ic74hc595_io_pins[STEP7_IO_BYTEOFFSET] ^= STEP7_IO_BITMASK; @@ -231,7 +231,7 @@ FORCEINLINE void ic74hc595_toggle_steps(uint8_t mask) FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) { -#if ASSERT_PIN_EXTENDER(DIR0_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR0_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[DIR0_IO_BYTEOFFSET] |= DIR0_IO_BITMASK; @@ -241,7 +241,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR0_IO_BYTEOFFSET] &= ~DIR0_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR1_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR1_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[DIR1_IO_BYTEOFFSET] |= DIR1_IO_BITMASK; @@ -251,7 +251,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR1_IO_BYTEOFFSET] &= ~DIR1_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR2_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR2_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[DIR2_IO_BYTEOFFSET] |= DIR2_IO_BITMASK; @@ -261,7 +261,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR2_IO_BYTEOFFSET] &= ~DIR2_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR3_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR3_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[DIR3_IO_BYTEOFFSET] |= DIR3_IO_BITMASK; @@ -271,7 +271,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR3_IO_BYTEOFFSET] &= ~DIR3_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR4_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR4_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[DIR4_IO_BYTEOFFSET] |= DIR4_IO_BITMASK; @@ -281,7 +281,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR4_IO_BYTEOFFSET] &= ~DIR4_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR5_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR5_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[DIR5_IO_BYTEOFFSET] |= DIR5_IO_BITMASK; @@ -291,7 +291,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR5_IO_BYTEOFFSET] &= ~DIR5_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR6_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR6_IO_OFFSET) if (mask & (1 << 6)) { ic74hc595_io_pins[DIR6_IO_BYTEOFFSET] |= DIR6_IO_BITMASK; @@ -301,7 +301,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) ic74hc595_io_pins[DIR6_IO_BYTEOFFSET] &= ~DIR6_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(DIR7_IO_OFFSET) +#if ASSERT_IO_OFFSET(DIR7_IO_OFFSET) if (mask & (1 << 7)) { ic74hc595_io_pins[DIR7_IO_BYTEOFFSET] |= DIR7_IO_BITMASK; @@ -317,7 +317,7 @@ FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) { -#if ASSERT_PIN_EXTENDER(STEP0_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP0_EN_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[STEP0_EN_IO_BYTEOFFSET] |= STEP0_EN_IO_BITMASK; @@ -327,7 +327,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP0_EN_IO_BYTEOFFSET] &= ~STEP0_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP1_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP1_EN_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[STEP1_EN_IO_BYTEOFFSET] |= STEP1_EN_IO_BITMASK; @@ -337,7 +337,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP1_EN_IO_BYTEOFFSET] &= ~STEP1_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP2_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP2_EN_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[STEP2_EN_IO_BYTEOFFSET] |= STEP2_EN_IO_BITMASK; @@ -347,7 +347,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP2_EN_IO_BYTEOFFSET] &= ~STEP2_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP3_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP3_EN_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[STEP3_EN_IO_BYTEOFFSET] |= STEP3_EN_IO_BITMASK; @@ -357,7 +357,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP3_EN_IO_BYTEOFFSET] &= ~STEP3_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP4_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP4_EN_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[STEP4_EN_IO_BYTEOFFSET] |= STEP4_EN_IO_BITMASK; @@ -367,7 +367,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP4_EN_IO_BYTEOFFSET] &= ~STEP4_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP5_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP5_EN_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[STEP5_EN_IO_BYTEOFFSET] |= STEP5_EN_IO_BITMASK; @@ -377,7 +377,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP5_EN_IO_BYTEOFFSET] &= ~STEP5_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP6_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP6_EN_IO_OFFSET) if (mask & (1 << 6)) { ic74hc595_io_pins[STEP6_EN_IO_BYTEOFFSET] |= STEP6_EN_IO_BITMASK; @@ -387,7 +387,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) ic74hc595_io_pins[STEP6_EN_IO_BYTEOFFSET] &= ~STEP6_EN_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(STEP7_EN_IO_OFFSET) +#if ASSERT_IO_OFFSET(STEP7_EN_IO_OFFSET) if (mask & (1 << 7)) { ic74hc595_io_pins[STEP7_EN_IO_BYTEOFFSET] |= STEP7_EN_IO_BITMASK; @@ -403,7 +403,7 @@ FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) { -#if ASSERT_PIN_EXTENDER(PWM0_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM0_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[PWM0_IO_BYTEOFFSET] |= PWM0_IO_BITMASK; @@ -413,7 +413,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM0_IO_BYTEOFFSET] &= ~PWM0_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM1_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM1_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[PWM1_IO_BYTEOFFSET] |= PWM1_IO_BITMASK; @@ -423,7 +423,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM1_IO_BYTEOFFSET] &= ~PWM1_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM2_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM2_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[PWM2_IO_BYTEOFFSET] |= PWM2_IO_BITMASK; @@ -433,7 +433,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM2_IO_BYTEOFFSET] &= ~PWM2_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM3_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM3_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[PWM3_IO_BYTEOFFSET] |= PWM3_IO_BITMASK; @@ -443,7 +443,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM3_IO_BYTEOFFSET] &= ~PWM3_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM4_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM4_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[PWM4_IO_BYTEOFFSET] |= PWM4_IO_BITMASK; @@ -453,7 +453,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM4_IO_BYTEOFFSET] &= ~PWM4_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM5_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM5_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[PWM5_IO_BYTEOFFSET] |= PWM5_IO_BITMASK; @@ -463,7 +463,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM5_IO_BYTEOFFSET] &= ~PWM5_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM6_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM6_IO_OFFSET) if (mask & (1 << 6)) { ic74hc595_io_pins[PWM6_IO_BYTEOFFSET] |= PWM6_IO_BITMASK; @@ -473,7 +473,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM6_IO_BYTEOFFSET] &= ~PWM6_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM7_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM7_IO_OFFSET) if (mask & (1 << 7)) { ic74hc595_io_pins[PWM7_IO_BYTEOFFSET] |= PWM7_IO_BITMASK; @@ -483,7 +483,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM7_IO_BYTEOFFSET] &= ~PWM7_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM8_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM8_IO_OFFSET) if (mask & (1 << 8)) { ic74hc595_io_pins[PWM8_IO_BYTEOFFSET] |= PWM8_IO_BITMASK; @@ -493,7 +493,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM8_IO_BYTEOFFSET] &= ~PWM8_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM9_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM9_IO_OFFSET) if (mask & (1 << 9)) { ic74hc595_io_pins[PWM9_IO_BYTEOFFSET] |= PWM9_IO_BITMASK; @@ -503,7 +503,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM9_IO_BYTEOFFSET] &= ~PWM9_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM10_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM10_IO_OFFSET) if (mask & (1 << 10)) { ic74hc595_io_pins[PWM10_IO_BYTEOFFSET] |= PWM10_IO_BITMASK; @@ -513,7 +513,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM10_IO_BYTEOFFSET] &= ~PWM10_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM11_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM11_IO_OFFSET) if (mask & (1 << 11)) { ic74hc595_io_pins[PWM11_IO_BYTEOFFSET] |= PWM11_IO_BITMASK; @@ -523,7 +523,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM11_IO_BYTEOFFSET] &= ~PWM11_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM12_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM12_IO_OFFSET) if (mask & (1 << 12)) { ic74hc595_io_pins[PWM12_IO_BYTEOFFSET] |= PWM12_IO_BITMASK; @@ -533,7 +533,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM12_IO_BYTEOFFSET] &= ~PWM12_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM13_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM13_IO_OFFSET) if (mask & (1 << 13)) { ic74hc595_io_pins[PWM13_IO_BYTEOFFSET] |= PWM13_IO_BITMASK; @@ -543,7 +543,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM13_IO_BYTEOFFSET] &= ~PWM13_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM14_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM14_IO_OFFSET) if (mask & (1 << 14)) { ic74hc595_io_pins[PWM14_IO_BYTEOFFSET] |= PWM14_IO_BITMASK; @@ -553,7 +553,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) ic74hc595_io_pins[PWM14_IO_BYTEOFFSET] &= ~PWM14_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(PWM15_IO_OFFSET) +#if ASSERT_IO_OFFSET(PWM15_IO_OFFSET) if (mask & (1 << 15)) { ic74hc595_io_pins[PWM15_IO_BYTEOFFSET] |= PWM15_IO_BITMASK; @@ -569,7 +569,7 @@ FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) FORCEINLINE void ic74hc595_set_servos(uint8_t mask) { -#if ASSERT_PIN_EXTENDER(SERVO0_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO0_IO_OFFSET) if (mask & (1 << 0)) { ic74hc595_io_pins[SERVO0_IO_BYTEOFFSET] |= SERVO0_IO_BITMASK; @@ -579,7 +579,7 @@ FORCEINLINE void ic74hc595_set_servos(uint8_t mask) ic74hc595_io_pins[SERVO0_IO_BYTEOFFSET] &= ~SERVO0_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(SERVO1_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO1_IO_OFFSET) if (mask & (1 << 1)) { ic74hc595_io_pins[SERVO1_IO_BYTEOFFSET] |= SERVO1_IO_BITMASK; @@ -589,7 +589,7 @@ FORCEINLINE void ic74hc595_set_servos(uint8_t mask) ic74hc595_io_pins[SERVO1_IO_BYTEOFFSET] &= ~SERVO1_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(SERVO2_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO2_IO_OFFSET) if (mask & (1 << 2)) { ic74hc595_io_pins[SERVO2_IO_BYTEOFFSET] |= SERVO2_IO_BITMASK; @@ -599,7 +599,7 @@ FORCEINLINE void ic74hc595_set_servos(uint8_t mask) ic74hc595_io_pins[SERVO2_IO_BYTEOFFSET] &= ~SERVO2_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(SERVO3_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO3_IO_OFFSET) if (mask & (1 << 3)) { ic74hc595_io_pins[SERVO3_IO_BYTEOFFSET] |= SERVO3_IO_BITMASK; @@ -609,7 +609,7 @@ FORCEINLINE void ic74hc595_set_servos(uint8_t mask) ic74hc595_io_pins[SERVO3_IO_BYTEOFFSET] &= ~SERVO3_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(SERVO4_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO4_IO_OFFSET) if (mask & (1 << 4)) { ic74hc595_io_pins[SERVO4_IO_BYTEOFFSET] |= SERVO4_IO_BITMASK; @@ -619,7 +619,7 @@ FORCEINLINE void ic74hc595_set_servos(uint8_t mask) ic74hc595_io_pins[SERVO4_IO_BYTEOFFSET] &= ~SERVO4_IO_BITMASK; } #endif -#if ASSERT_PIN_EXTENDER(SERVO5_IO_OFFSET) +#if ASSERT_IO_OFFSET(SERVO5_IO_OFFSET) if (mask & (1 << 5)) { ic74hc595_io_pins[SERVO5_IO_BYTEOFFSET] |= SERVO5_IO_BITMASK; @@ -637,7 +637,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) { switch (pin - DOUT_PINS_OFFSET) { -#if ASSERT_PIN_EXTENDER(DOUT0_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT0_IO_OFFSET) case 0: if (state) { @@ -649,7 +649,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT1_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT1_IO_OFFSET) case 1: if (state) { @@ -661,7 +661,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT2_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT2_IO_OFFSET) case 2: if (state) { @@ -673,7 +673,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT3_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT3_IO_OFFSET) case 3: if (state) { @@ -685,7 +685,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT4_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT4_IO_OFFSET) case 4: if (state) { @@ -697,7 +697,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT5_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT5_IO_OFFSET) case 5: if (state) { @@ -709,7 +709,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT6_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT6_IO_OFFSET) case 6: if (state) { @@ -721,7 +721,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT7_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT7_IO_OFFSET) case 7: if (state) { @@ -733,7 +733,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT8_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT8_IO_OFFSET) case 8: if (state) { @@ -745,7 +745,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT9_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT9_IO_OFFSET) case 9: if (state) { @@ -757,7 +757,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT10_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT10_IO_OFFSET) case 10: if (state) { @@ -769,7 +769,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT11_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT11_IO_OFFSET) case 11: if (state) { @@ -781,7 +781,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT12_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT12_IO_OFFSET) case 12: if (state) { @@ -793,7 +793,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT13_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT13_IO_OFFSET) case 13: if (state) { @@ -805,7 +805,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT14_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT14_IO_OFFSET) case 14: if (state) { @@ -817,7 +817,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT15_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT15_IO_OFFSET) case 15: if (state) { @@ -829,7 +829,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT16_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT16_IO_OFFSET) case 16: if (state) { @@ -841,7 +841,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT17_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT17_IO_OFFSET) case 17: if (state) { @@ -853,7 +853,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT18_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT18_IO_OFFSET) case 18: if (state) { @@ -865,7 +865,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT19_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT19_IO_OFFSET) case 19: if (state) { @@ -877,7 +877,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT20_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT20_IO_OFFSET) case 20: if (state) { @@ -889,7 +889,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT21_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT21_IO_OFFSET) case 21: if (state) { @@ -901,7 +901,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT22_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT22_IO_OFFSET) case 22: if (state) { @@ -913,7 +913,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT23_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT23_IO_OFFSET) case 23: if (state) { @@ -925,7 +925,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT24_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT24_IO_OFFSET) case 24: if (state) { @@ -937,7 +937,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT25_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT25_IO_OFFSET) case 25: if (state) { @@ -949,7 +949,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT26_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT26_IO_OFFSET) case 26: if (state) { @@ -961,7 +961,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT27_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT27_IO_OFFSET) case 27: if (state) { @@ -973,7 +973,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT28_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT28_IO_OFFSET) case 28: if (state) { @@ -985,7 +985,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT29_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT29_IO_OFFSET) case 29: if (state) { @@ -997,7 +997,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT30_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT30_IO_OFFSET) case 30: if (state) { @@ -1009,7 +1009,7 @@ FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) } break; #endif -#if ASSERT_PIN_EXTENDER(DOUT31_IO_OFFSET) +#if ASSERT_IO_OFFSET(DOUT31_IO_OFFSET) case 31: if (state) { diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index 18f6212fe..7f7be6cbb 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -31,7 +31,15 @@ extern "C" #ifndef STEP0_IO_OFFSET #define STEP0_IO_OFFSET -1 #else -#define STEP0_IO_BYTEOFFSET (STEP0_IO_OFFSET >> 3) +#ifdef STEP0 +#undef STEP0 +#endif +#ifdef DIO1 +#undef DIO1 +#endif +#define STEP0 1 +#define DIO1 -1 +#define STEP0_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_IO_OFFSET >> 3)-1) #define STEP0_IO_BITMASK (1 << (STEP0_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -40,7 +48,15 @@ extern "C" #ifndef STEP1_IO_OFFSET #define STEP1_IO_OFFSET -1 #else -#define STEP1_IO_BYTEOFFSET (STEP1_IO_OFFSET >> 3) +#ifdef STEP1 +#undef STEP1 +#endif +#ifdef DIO2 +#undef DIO2 +#endif +#define STEP1 2 +#define DIO2 -2 +#define STEP1_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_IO_OFFSET >> 3)-1) #define STEP1_IO_BITMASK (1 << (STEP1_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -49,7 +65,15 @@ extern "C" #ifndef STEP2_IO_OFFSET #define STEP2_IO_OFFSET -1 #else -#define STEP2_IO_BYTEOFFSET (STEP2_IO_OFFSET >> 3) +#ifdef STEP2 +#undef STEP2 +#endif +#ifdef DIO3 +#undef DIO3 +#endif +#define STEP2 3 +#define DIO3 -3 +#define STEP2_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_IO_OFFSET >> 3)-1) #define STEP2_IO_BITMASK (1 << (STEP2_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -58,7 +82,15 @@ extern "C" #ifndef STEP3_IO_OFFSET #define STEP3_IO_OFFSET -1 #else -#define STEP3_IO_BYTEOFFSET (STEP3_IO_OFFSET >> 3) +#ifdef STEP3 +#undef STEP3 +#endif +#ifdef DIO4 +#undef DIO4 +#endif +#define STEP3 4 +#define DIO4 -4 +#define STEP3_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_IO_OFFSET >> 3)-1) #define STEP3_IO_BITMASK (1 << (STEP3_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -67,7 +99,15 @@ extern "C" #ifndef STEP4_IO_OFFSET #define STEP4_IO_OFFSET -1 #else -#define STEP4_IO_BYTEOFFSET (STEP4_IO_OFFSET >> 3) +#ifdef STEP4 +#undef STEP4 +#endif +#ifdef DIO5 +#undef DIO5 +#endif +#define STEP4 5 +#define DIO5 -5 +#define STEP4_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_IO_OFFSET >> 3)-1) #define STEP4_IO_BITMASK (1 << (STEP4_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -76,7 +116,15 @@ extern "C" #ifndef STEP5_IO_OFFSET #define STEP5_IO_OFFSET -1 #else -#define STEP5_IO_BYTEOFFSET (STEP5_IO_OFFSET >> 3) +#ifdef STEP5 +#undef STEP5 +#endif +#ifdef DIO6 +#undef DIO6 +#endif +#define STEP5 6 +#define DIO6 -6 +#define STEP5_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_IO_OFFSET >> 3)-1) #define STEP5_IO_BITMASK (1 << (STEP5_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -85,7 +133,15 @@ extern "C" #ifndef STEP6_IO_OFFSET #define STEP6_IO_OFFSET -1 #else -#define STEP6_IO_BYTEOFFSET (STEP6_IO_OFFSET >> 3) +#ifdef STEP6 +#undef STEP6 +#endif +#ifdef DIO7 +#undef DIO7 +#endif +#define STEP6 7 +#define DIO7 -7 +#define STEP6_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_IO_OFFSET >> 3)-1) #define STEP6_IO_BITMASK (1 << (STEP6_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -94,7 +150,15 @@ extern "C" #ifndef STEP7_IO_OFFSET #define STEP7_IO_OFFSET -1 #else -#define STEP7_IO_BYTEOFFSET (STEP7_IO_OFFSET >> 3) +#ifdef STEP7 +#undef STEP7 +#endif +#ifdef DIO8 +#undef DIO8 +#endif +#define STEP7 8 +#define DIO8 -8 +#define STEP7_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_IO_OFFSET >> 3)-1) #define STEP7_IO_BITMASK (1 << (STEP7_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS @@ -103,7 +167,15 @@ extern "C" #ifndef DIR0_IO_OFFSET #define DIR0_IO_OFFSET -1 #else -#define DIR0_IO_BYTEOFFSET (DIR0_IO_OFFSET >> 3) +#ifdef DIR0 +#undef DIR0 +#endif +#ifdef DIO9 +#undef DIO9 +#endif +#define DIR0 9 +#define DIO9 -9 +#define DIR0_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR0_IO_OFFSET >> 3)-1) #define DIR0_IO_BITMASK (1 << (DIR0_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -112,7 +184,15 @@ extern "C" #ifndef DIR1_IO_OFFSET #define DIR1_IO_OFFSET -1 #else -#define DIR1_IO_BYTEOFFSET (DIR1_IO_OFFSET >> 3) +#ifdef DIR1 +#undef DIR1 +#endif +#ifdef DIO10 +#undef DIO10 +#endif +#define DIR1 10 +#define DIO10 -10 +#define DIR1_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR1_IO_OFFSET >> 3)-1) #define DIR1_IO_BITMASK (1 << (DIR1_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -121,7 +201,15 @@ extern "C" #ifndef DIR2_IO_OFFSET #define DIR2_IO_OFFSET -1 #else -#define DIR2_IO_BYTEOFFSET (DIR2_IO_OFFSET >> 3) +#ifdef DIR2 +#undef DIR2 +#endif +#ifdef DIO11 +#undef DIO11 +#endif +#define DIR2 11 +#define DIO11 -11 +#define DIR2_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR2_IO_OFFSET >> 3)-1) #define DIR2_IO_BITMASK (1 << (DIR2_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -130,7 +218,15 @@ extern "C" #ifndef DIR3_IO_OFFSET #define DIR3_IO_OFFSET -1 #else -#define DIR3_IO_BYTEOFFSET (DIR3_IO_OFFSET >> 3) +#ifdef DIR3 +#undef DIR3 +#endif +#ifdef DIO12 +#undef DIO12 +#endif +#define DIR3 12 +#define DIO12 -12 +#define DIR3_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR3_IO_OFFSET >> 3)-1) #define DIR3_IO_BITMASK (1 << (DIR3_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -139,7 +235,15 @@ extern "C" #ifndef DIR4_IO_OFFSET #define DIR4_IO_OFFSET -1 #else -#define DIR4_IO_BYTEOFFSET (DIR4_IO_OFFSET >> 3) +#ifdef DIR4 +#undef DIR4 +#endif +#ifdef DIO13 +#undef DIO13 +#endif +#define DIR4 13 +#define DIO13 -13 +#define DIR4_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR4_IO_OFFSET >> 3)-1) #define DIR4_IO_BITMASK (1 << (DIR4_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -148,7 +252,15 @@ extern "C" #ifndef DIR5_IO_OFFSET #define DIR5_IO_OFFSET -1 #else -#define DIR5_IO_BYTEOFFSET (DIR5_IO_OFFSET >> 3) +#ifdef DIR5 +#undef DIR5 +#endif +#ifdef DIO14 +#undef DIO14 +#endif +#define DIR5 14 +#define DIO14 -14 +#define DIR5_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR5_IO_OFFSET >> 3)-1) #define DIR5_IO_BITMASK (1 << (DIR5_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -157,7 +269,15 @@ extern "C" #ifndef DIR6_IO_OFFSET #define DIR6_IO_OFFSET -1 #else -#define DIR6_IO_BYTEOFFSET (DIR6_IO_OFFSET >> 3) +#ifdef DIR6 +#undef DIR6 +#endif +#ifdef DIO15 +#undef DIO15 +#endif +#define DIR6 15 +#define DIO15 -15 +#define DIR6_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR6_IO_OFFSET >> 3)-1) #define DIR6_IO_BITMASK (1 << (DIR6_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -166,7 +286,15 @@ extern "C" #ifndef DIR7_IO_OFFSET #define DIR7_IO_OFFSET -1 #else -#define DIR7_IO_BYTEOFFSET (DIR7_IO_OFFSET >> 3) +#ifdef DIR7 +#undef DIR7 +#endif +#ifdef DIO16 +#undef DIO16 +#endif +#define DIR7 16 +#define DIO16 -16 +#define DIR7_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR7_IO_OFFSET >> 3)-1) #define DIR7_IO_BITMASK (1 << (DIR7_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS @@ -175,7 +303,15 @@ extern "C" #ifndef STEP0_EN_IO_OFFSET #define STEP0_EN_IO_OFFSET -1 #else -#define STEP0_EN_IO_BYTEOFFSET (STEP0_EN_IO_OFFSET >> 3) +#ifdef STEP0_EN +#undef STEP0_EN +#endif +#ifdef DIO17 +#undef DIO17 +#endif +#define STEP0_EN 17 +#define DIO17 -17 +#define STEP0_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_EN_IO_OFFSET >> 3)-1) #define STEP0_EN_IO_BITMASK (1 << (STEP0_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -184,7 +320,15 @@ extern "C" #ifndef STEP1_EN_IO_OFFSET #define STEP1_EN_IO_OFFSET -1 #else -#define STEP1_EN_IO_BYTEOFFSET (STEP1_EN_IO_OFFSET >> 3) +#ifdef STEP1_EN +#undef STEP1_EN +#endif +#ifdef DIO18 +#undef DIO18 +#endif +#define STEP1_EN 18 +#define DIO18 -18 +#define STEP1_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_EN_IO_OFFSET >> 3)-1) #define STEP1_EN_IO_BITMASK (1 << (STEP1_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -193,7 +337,15 @@ extern "C" #ifndef STEP2_EN_IO_OFFSET #define STEP2_EN_IO_OFFSET -1 #else -#define STEP2_EN_IO_BYTEOFFSET (STEP2_EN_IO_OFFSET >> 3) +#ifdef STEP2_EN +#undef STEP2_EN +#endif +#ifdef DIO19 +#undef DIO19 +#endif +#define STEP2_EN 19 +#define DIO19 -19 +#define STEP2_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_EN_IO_OFFSET >> 3)-1) #define STEP2_EN_IO_BITMASK (1 << (STEP2_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -202,7 +354,15 @@ extern "C" #ifndef STEP3_EN_IO_OFFSET #define STEP3_EN_IO_OFFSET -1 #else -#define STEP3_EN_IO_BYTEOFFSET (STEP3_EN_IO_OFFSET >> 3) +#ifdef STEP3_EN +#undef STEP3_EN +#endif +#ifdef DIO20 +#undef DIO20 +#endif +#define STEP3_EN 20 +#define DIO20 -20 +#define STEP3_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_EN_IO_OFFSET >> 3)-1) #define STEP3_EN_IO_BITMASK (1 << (STEP3_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -211,7 +371,15 @@ extern "C" #ifndef STEP4_EN_IO_OFFSET #define STEP4_EN_IO_OFFSET -1 #else -#define STEP4_EN_IO_BYTEOFFSET (STEP4_EN_IO_OFFSET >> 3) +#ifdef STEP4_EN +#undef STEP4_EN +#endif +#ifdef DIO21 +#undef DIO21 +#endif +#define STEP4_EN 21 +#define DIO21 -21 +#define STEP4_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_EN_IO_OFFSET >> 3)-1) #define STEP4_EN_IO_BITMASK (1 << (STEP4_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -220,7 +388,15 @@ extern "C" #ifndef STEP5_EN_IO_OFFSET #define STEP5_EN_IO_OFFSET -1 #else -#define STEP5_EN_IO_BYTEOFFSET (STEP5_EN_IO_OFFSET >> 3) +#ifdef STEP5_EN +#undef STEP5_EN +#endif +#ifdef DIO22 +#undef DIO22 +#endif +#define STEP5_EN 22 +#define DIO22 -22 +#define STEP5_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_EN_IO_OFFSET >> 3)-1) #define STEP5_EN_IO_BITMASK (1 << (STEP5_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -229,7 +405,15 @@ extern "C" #ifndef STEP6_EN_IO_OFFSET #define STEP6_EN_IO_OFFSET -1 #else -#define STEP6_EN_IO_BYTEOFFSET (STEP6_EN_IO_OFFSET >> 3) +#ifdef STEP6_EN +#undef STEP6_EN +#endif +#ifdef DIO23 +#undef DIO23 +#endif +#define STEP6_EN 23 +#define DIO23 -23 +#define STEP6_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_EN_IO_OFFSET >> 3)-1) #define STEP6_EN_IO_BITMASK (1 << (STEP6_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -238,7 +422,15 @@ extern "C" #ifndef STEP7_EN_IO_OFFSET #define STEP7_EN_IO_OFFSET -1 #else -#define STEP7_EN_IO_BYTEOFFSET (STEP7_EN_IO_OFFSET >> 3) +#ifdef STEP7_EN +#undef STEP7_EN +#endif +#ifdef DIO24 +#undef DIO24 +#endif +#define STEP7_EN 24 +#define DIO24 -24 +#define STEP7_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_EN_IO_OFFSET >> 3)-1) #define STEP7_EN_IO_BITMASK (1 << (STEP7_EN_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN @@ -247,7 +439,15 @@ extern "C" #ifndef PWM0_IO_OFFSET #define PWM0_IO_OFFSET -1 #else -#define PWM0_IO_BYTEOFFSET (PWM0_IO_OFFSET >> 3) +#ifdef PWM0 +#undef PWM0 +#endif +#ifdef DIO25 +#undef DIO25 +#endif +#define PWM0 25 +#define DIO25 -25 +#define PWM0_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM0_IO_OFFSET >> 3)-1) #define PWM0_IO_BITMASK (1 << (PWM0_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -256,7 +456,15 @@ extern "C" #ifndef PWM1_IO_OFFSET #define PWM1_IO_OFFSET -1 #else -#define PWM1_IO_BYTEOFFSET (PWM1_IO_OFFSET >> 3) +#ifdef PWM1 +#undef PWM1 +#endif +#ifdef DIO26 +#undef DIO26 +#endif +#define PWM1 26 +#define DIO26 -26 +#define PWM1_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM1_IO_OFFSET >> 3)-1) #define PWM1_IO_BITMASK (1 << (PWM1_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -265,7 +473,15 @@ extern "C" #ifndef PWM2_IO_OFFSET #define PWM2_IO_OFFSET -1 #else -#define PWM2_IO_BYTEOFFSET (PWM2_IO_OFFSET >> 3) +#ifdef PWM2 +#undef PWM2 +#endif +#ifdef DIO27 +#undef DIO27 +#endif +#define PWM2 27 +#define DIO27 -27 +#define PWM2_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM2_IO_OFFSET >> 3)-1) #define PWM2_IO_BITMASK (1 << (PWM2_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -274,7 +490,15 @@ extern "C" #ifndef PWM3_IO_OFFSET #define PWM3_IO_OFFSET -1 #else -#define PWM3_IO_BYTEOFFSET (PWM3_IO_OFFSET >> 3) +#ifdef PWM3 +#undef PWM3 +#endif +#ifdef DIO28 +#undef DIO28 +#endif +#define PWM3 28 +#define DIO28 -28 +#define PWM3_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM3_IO_OFFSET >> 3)-1) #define PWM3_IO_BITMASK (1 << (PWM3_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -283,7 +507,15 @@ extern "C" #ifndef PWM4_IO_OFFSET #define PWM4_IO_OFFSET -1 #else -#define PWM4_IO_BYTEOFFSET (PWM4_IO_OFFSET >> 3) +#ifdef PWM4 +#undef PWM4 +#endif +#ifdef DIO29 +#undef DIO29 +#endif +#define PWM4 29 +#define DIO29 -29 +#define PWM4_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM4_IO_OFFSET >> 3)-1) #define PWM4_IO_BITMASK (1 << (PWM4_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -292,7 +524,15 @@ extern "C" #ifndef PWM5_IO_OFFSET #define PWM5_IO_OFFSET -1 #else -#define PWM5_IO_BYTEOFFSET (PWM5_IO_OFFSET >> 3) +#ifdef PWM5 +#undef PWM5 +#endif +#ifdef DIO30 +#undef DIO30 +#endif +#define PWM5 30 +#define DIO30 -30 +#define PWM5_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM5_IO_OFFSET >> 3)-1) #define PWM5_IO_BITMASK (1 << (PWM5_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -301,7 +541,15 @@ extern "C" #ifndef PWM6_IO_OFFSET #define PWM6_IO_OFFSET -1 #else -#define PWM6_IO_BYTEOFFSET (PWM6_IO_OFFSET >> 3) +#ifdef PWM6 +#undef PWM6 +#endif +#ifdef DIO31 +#undef DIO31 +#endif +#define PWM6 31 +#define DIO31 -31 +#define PWM6_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM6_IO_OFFSET >> 3)-1) #define PWM6_IO_BITMASK (1 << (PWM6_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -310,7 +558,15 @@ extern "C" #ifndef PWM7_IO_OFFSET #define PWM7_IO_OFFSET -1 #else -#define PWM7_IO_BYTEOFFSET (PWM7_IO_OFFSET >> 3) +#ifdef PWM7 +#undef PWM7 +#endif +#ifdef DIO32 +#undef DIO32 +#endif +#define PWM7 32 +#define DIO32 -32 +#define PWM7_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM7_IO_OFFSET >> 3)-1) #define PWM7_IO_BITMASK (1 << (PWM7_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -319,7 +575,15 @@ extern "C" #ifndef PWM8_IO_OFFSET #define PWM8_IO_OFFSET -1 #else -#define PWM8_IO_BYTEOFFSET (PWM8_IO_OFFSET >> 3) +#ifdef PWM8 +#undef PWM8 +#endif +#ifdef DIO33 +#undef DIO33 +#endif +#define PWM8 33 +#define DIO33 -33 +#define PWM8_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM8_IO_OFFSET >> 3)-1) #define PWM8_IO_BITMASK (1 << (PWM8_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -328,7 +592,15 @@ extern "C" #ifndef PWM9_IO_OFFSET #define PWM9_IO_OFFSET -1 #else -#define PWM9_IO_BYTEOFFSET (PWM9_IO_OFFSET >> 3) +#ifdef PWM9 +#undef PWM9 +#endif +#ifdef DIO34 +#undef DIO34 +#endif +#define PWM9 34 +#define DIO34 -34 +#define PWM9_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM9_IO_OFFSET >> 3)-1) #define PWM9_IO_BITMASK (1 << (PWM9_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -337,7 +609,15 @@ extern "C" #ifndef PWM10_IO_OFFSET #define PWM10_IO_OFFSET -1 #else -#define PWM10_IO_BYTEOFFSET (PWM10_IO_OFFSET >> 3) +#ifdef PWM10 +#undef PWM10 +#endif +#ifdef DIO35 +#undef DIO35 +#endif +#define PWM10 35 +#define DIO35 -35 +#define PWM10_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM10_IO_OFFSET >> 3)-1) #define PWM10_IO_BITMASK (1 << (PWM10_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -346,7 +626,15 @@ extern "C" #ifndef PWM11_IO_OFFSET #define PWM11_IO_OFFSET -1 #else -#define PWM11_IO_BYTEOFFSET (PWM11_IO_OFFSET >> 3) +#ifdef PWM11 +#undef PWM11 +#endif +#ifdef DIO36 +#undef DIO36 +#endif +#define PWM11 36 +#define DIO36 -36 +#define PWM11_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM11_IO_OFFSET >> 3)-1) #define PWM11_IO_BITMASK (1 << (PWM11_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -355,7 +643,15 @@ extern "C" #ifndef PWM12_IO_OFFSET #define PWM12_IO_OFFSET -1 #else -#define PWM12_IO_BYTEOFFSET (PWM12_IO_OFFSET >> 3) +#ifdef PWM12 +#undef PWM12 +#endif +#ifdef DIO37 +#undef DIO37 +#endif +#define PWM12 37 +#define DIO37 -37 +#define PWM12_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM12_IO_OFFSET >> 3)-1) #define PWM12_IO_BITMASK (1 << (PWM12_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -364,7 +660,15 @@ extern "C" #ifndef PWM13_IO_OFFSET #define PWM13_IO_OFFSET -1 #else -#define PWM13_IO_BYTEOFFSET (PWM13_IO_OFFSET >> 3) +#ifdef PWM13 +#undef PWM13 +#endif +#ifdef DIO38 +#undef DIO38 +#endif +#define PWM13 38 +#define DIO38 -38 +#define PWM13_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM13_IO_OFFSET >> 3)-1) #define PWM13_IO_BITMASK (1 << (PWM13_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -373,7 +677,15 @@ extern "C" #ifndef PWM14_IO_OFFSET #define PWM14_IO_OFFSET -1 #else -#define PWM14_IO_BYTEOFFSET (PWM14_IO_OFFSET >> 3) +#ifdef PWM14 +#undef PWM14 +#endif +#ifdef DIO39 +#undef DIO39 +#endif +#define PWM14 39 +#define DIO39 -39 +#define PWM14_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM14_IO_OFFSET >> 3)-1) #define PWM14_IO_BITMASK (1 << (PWM14_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -382,7 +694,15 @@ extern "C" #ifndef PWM15_IO_OFFSET #define PWM15_IO_OFFSET -1 #else -#define PWM15_IO_BYTEOFFSET (PWM15_IO_OFFSET >> 3) +#ifdef PWM15 +#undef PWM15 +#endif +#ifdef DIO40 +#undef DIO40 +#endif +#define PWM15 40 +#define DIO40 -40 +#define PWM15_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM15_IO_OFFSET >> 3)-1) #define PWM15_IO_BITMASK (1 << (PWM15_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS @@ -391,7 +711,15 @@ extern "C" #ifndef SERVO0_IO_OFFSET #define SERVO0_IO_OFFSET -1 #else -#define SERVO0_IO_BYTEOFFSET (SERVO0_IO_OFFSET >> 3) +#ifdef SERVO0 +#undef SERVO0 +#endif +#ifdef DIO41 +#undef DIO41 +#endif +#define SERVO0 41 +#define DIO41 -41 +#define SERVO0_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO0_IO_OFFSET >> 3)-1) #define SERVO0_IO_BITMASK (1 << (SERVO0_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -400,7 +728,15 @@ extern "C" #ifndef SERVO1_IO_OFFSET #define SERVO1_IO_OFFSET -1 #else -#define SERVO1_IO_BYTEOFFSET (SERVO1_IO_OFFSET >> 3) +#ifdef SERVO1 +#undef SERVO1 +#endif +#ifdef DIO42 +#undef DIO42 +#endif +#define SERVO1 42 +#define DIO42 -42 +#define SERVO1_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO1_IO_OFFSET >> 3)-1) #define SERVO1_IO_BITMASK (1 << (SERVO1_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -409,7 +745,15 @@ extern "C" #ifndef SERVO2_IO_OFFSET #define SERVO2_IO_OFFSET -1 #else -#define SERVO2_IO_BYTEOFFSET (SERVO2_IO_OFFSET >> 3) +#ifdef SERVO2 +#undef SERVO2 +#endif +#ifdef DIO43 +#undef DIO43 +#endif +#define SERVO2 43 +#define DIO43 -43 +#define SERVO2_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO2_IO_OFFSET >> 3)-1) #define SERVO2_IO_BITMASK (1 << (SERVO2_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -418,7 +762,15 @@ extern "C" #ifndef SERVO3_IO_OFFSET #define SERVO3_IO_OFFSET -1 #else -#define SERVO3_IO_BYTEOFFSET (SERVO3_IO_OFFSET >> 3) +#ifdef SERVO3 +#undef SERVO3 +#endif +#ifdef DIO44 +#undef DIO44 +#endif +#define SERVO3 44 +#define DIO44 -44 +#define SERVO3_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO3_IO_OFFSET >> 3)-1) #define SERVO3_IO_BITMASK (1 << (SERVO3_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -427,7 +779,15 @@ extern "C" #ifndef SERVO4_IO_OFFSET #define SERVO4_IO_OFFSET -1 #else -#define SERVO4_IO_BYTEOFFSET (SERVO4_IO_OFFSET >> 3) +#ifdef SERVO4 +#undef SERVO4 +#endif +#ifdef DIO45 +#undef DIO45 +#endif +#define SERVO4 45 +#define DIO45 -45 +#define SERVO4_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO4_IO_OFFSET >> 3)-1) #define SERVO4_IO_BITMASK (1 << (SERVO4_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -436,7 +796,15 @@ extern "C" #ifndef SERVO5_IO_OFFSET #define SERVO5_IO_OFFSET -1 #else -#define SERVO5_IO_BYTEOFFSET (SERVO5_IO_OFFSET >> 3) +#ifdef SERVO5 +#undef SERVO5 +#endif +#ifdef DIO46 +#undef DIO46 +#endif +#define SERVO5 46 +#define DIO46 -46 +#define SERVO5_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO5_IO_OFFSET >> 3)-1) #define SERVO5_IO_BITMASK (1 << (SERVO5_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS @@ -445,7 +813,15 @@ extern "C" #ifndef DOUT0_IO_OFFSET #define DOUT0_IO_OFFSET -1 #else -#define DOUT0_IO_BYTEOFFSET (DOUT0_IO_OFFSET >> 3) +#ifdef DOUT0 +#undef DOUT0 +#endif +#ifdef DIO47 +#undef DIO47 +#endif +#define DOUT0 47 +#define DIO47 -47 +#define DOUT0_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT0_IO_OFFSET >> 3)-1) #define DOUT0_IO_BITMASK (1 << (DOUT0_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -454,7 +830,15 @@ extern "C" #ifndef DOUT1_IO_OFFSET #define DOUT1_IO_OFFSET -1 #else -#define DOUT1_IO_BYTEOFFSET (DOUT1_IO_OFFSET >> 3) +#ifdef DOUT1 +#undef DOUT1 +#endif +#ifdef DIO48 +#undef DIO48 +#endif +#define DOUT1 48 +#define DIO48 -48 +#define DOUT1_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT1_IO_OFFSET >> 3)-1) #define DOUT1_IO_BITMASK (1 << (DOUT1_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -463,7 +847,15 @@ extern "C" #ifndef DOUT2_IO_OFFSET #define DOUT2_IO_OFFSET -1 #else -#define DOUT2_IO_BYTEOFFSET (DOUT2_IO_OFFSET >> 3) +#ifdef DOUT2 +#undef DOUT2 +#endif +#ifdef DIO49 +#undef DIO49 +#endif +#define DOUT2 49 +#define DIO49 -49 +#define DOUT2_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT2_IO_OFFSET >> 3)-1) #define DOUT2_IO_BITMASK (1 << (DOUT2_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -472,7 +864,15 @@ extern "C" #ifndef DOUT3_IO_OFFSET #define DOUT3_IO_OFFSET -1 #else -#define DOUT3_IO_BYTEOFFSET (DOUT3_IO_OFFSET >> 3) +#ifdef DOUT3 +#undef DOUT3 +#endif +#ifdef DIO50 +#undef DIO50 +#endif +#define DOUT3 50 +#define DIO50 -50 +#define DOUT3_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT3_IO_OFFSET >> 3)-1) #define DOUT3_IO_BITMASK (1 << (DOUT3_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -481,7 +881,15 @@ extern "C" #ifndef DOUT4_IO_OFFSET #define DOUT4_IO_OFFSET -1 #else -#define DOUT4_IO_BYTEOFFSET (DOUT4_IO_OFFSET >> 3) +#ifdef DOUT4 +#undef DOUT4 +#endif +#ifdef DIO51 +#undef DIO51 +#endif +#define DOUT4 51 +#define DIO51 -51 +#define DOUT4_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT4_IO_OFFSET >> 3)-1) #define DOUT4_IO_BITMASK (1 << (DOUT4_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -490,7 +898,15 @@ extern "C" #ifndef DOUT5_IO_OFFSET #define DOUT5_IO_OFFSET -1 #else -#define DOUT5_IO_BYTEOFFSET (DOUT5_IO_OFFSET >> 3) +#ifdef DOUT5 +#undef DOUT5 +#endif +#ifdef DIO52 +#undef DIO52 +#endif +#define DOUT5 52 +#define DIO52 -52 +#define DOUT5_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT5_IO_OFFSET >> 3)-1) #define DOUT5_IO_BITMASK (1 << (DOUT5_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -499,7 +915,15 @@ extern "C" #ifndef DOUT6_IO_OFFSET #define DOUT6_IO_OFFSET -1 #else -#define DOUT6_IO_BYTEOFFSET (DOUT6_IO_OFFSET >> 3) +#ifdef DOUT6 +#undef DOUT6 +#endif +#ifdef DIO53 +#undef DIO53 +#endif +#define DOUT6 53 +#define DIO53 -53 +#define DOUT6_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT6_IO_OFFSET >> 3)-1) #define DOUT6_IO_BITMASK (1 << (DOUT6_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -508,7 +932,15 @@ extern "C" #ifndef DOUT7_IO_OFFSET #define DOUT7_IO_OFFSET -1 #else -#define DOUT7_IO_BYTEOFFSET (DOUT7_IO_OFFSET >> 3) +#ifdef DOUT7 +#undef DOUT7 +#endif +#ifdef DIO54 +#undef DIO54 +#endif +#define DOUT7 54 +#define DIO54 -54 +#define DOUT7_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT7_IO_OFFSET >> 3)-1) #define DOUT7_IO_BITMASK (1 << (DOUT7_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -517,7 +949,15 @@ extern "C" #ifndef DOUT8_IO_OFFSET #define DOUT8_IO_OFFSET -1 #else -#define DOUT8_IO_BYTEOFFSET (DOUT8_IO_OFFSET >> 3) +#ifdef DOUT8 +#undef DOUT8 +#endif +#ifdef DIO55 +#undef DIO55 +#endif +#define DOUT8 55 +#define DIO55 -55 +#define DOUT8_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT8_IO_OFFSET >> 3)-1) #define DOUT8_IO_BITMASK (1 << (DOUT8_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -526,7 +966,15 @@ extern "C" #ifndef DOUT9_IO_OFFSET #define DOUT9_IO_OFFSET -1 #else -#define DOUT9_IO_BYTEOFFSET (DOUT9_IO_OFFSET >> 3) +#ifdef DOUT9 +#undef DOUT9 +#endif +#ifdef DIO56 +#undef DIO56 +#endif +#define DOUT9 56 +#define DIO56 -56 +#define DOUT9_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT9_IO_OFFSET >> 3)-1) #define DOUT9_IO_BITMASK (1 << (DOUT9_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -535,7 +983,15 @@ extern "C" #ifndef DOUT10_IO_OFFSET #define DOUT10_IO_OFFSET -1 #else -#define DOUT10_IO_BYTEOFFSET (DOUT10_IO_OFFSET >> 3) +#ifdef DOUT10 +#undef DOUT10 +#endif +#ifdef DIO57 +#undef DIO57 +#endif +#define DOUT10 57 +#define DIO57 -57 +#define DOUT10_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT10_IO_OFFSET >> 3)-1) #define DOUT10_IO_BITMASK (1 << (DOUT10_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -544,7 +1000,15 @@ extern "C" #ifndef DOUT11_IO_OFFSET #define DOUT11_IO_OFFSET -1 #else -#define DOUT11_IO_BYTEOFFSET (DOUT11_IO_OFFSET >> 3) +#ifdef DOUT11 +#undef DOUT11 +#endif +#ifdef DIO58 +#undef DIO58 +#endif +#define DOUT11 58 +#define DIO58 -58 +#define DOUT11_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT11_IO_OFFSET >> 3)-1) #define DOUT11_IO_BITMASK (1 << (DOUT11_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -553,7 +1017,15 @@ extern "C" #ifndef DOUT12_IO_OFFSET #define DOUT12_IO_OFFSET -1 #else -#define DOUT12_IO_BYTEOFFSET (DOUT12_IO_OFFSET >> 3) +#ifdef DOUT12 +#undef DOUT12 +#endif +#ifdef DIO59 +#undef DIO59 +#endif +#define DOUT12 59 +#define DIO59 -59 +#define DOUT12_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT12_IO_OFFSET >> 3)-1) #define DOUT12_IO_BITMASK (1 << (DOUT12_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -562,7 +1034,15 @@ extern "C" #ifndef DOUT13_IO_OFFSET #define DOUT13_IO_OFFSET -1 #else -#define DOUT13_IO_BYTEOFFSET (DOUT13_IO_OFFSET >> 3) +#ifdef DOUT13 +#undef DOUT13 +#endif +#ifdef DIO60 +#undef DIO60 +#endif +#define DOUT13 60 +#define DIO60 -60 +#define DOUT13_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT13_IO_OFFSET >> 3)-1) #define DOUT13_IO_BITMASK (1 << (DOUT13_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -571,7 +1051,15 @@ extern "C" #ifndef DOUT14_IO_OFFSET #define DOUT14_IO_OFFSET -1 #else -#define DOUT14_IO_BYTEOFFSET (DOUT14_IO_OFFSET >> 3) +#ifdef DOUT14 +#undef DOUT14 +#endif +#ifdef DIO61 +#undef DIO61 +#endif +#define DOUT14 61 +#define DIO61 -61 +#define DOUT14_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT14_IO_OFFSET >> 3)-1) #define DOUT14_IO_BITMASK (1 << (DOUT14_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -580,7 +1068,15 @@ extern "C" #ifndef DOUT15_IO_OFFSET #define DOUT15_IO_OFFSET -1 #else -#define DOUT15_IO_BYTEOFFSET (DOUT15_IO_OFFSET >> 3) +#ifdef DOUT15 +#undef DOUT15 +#endif +#ifdef DIO62 +#undef DIO62 +#endif +#define DOUT15 62 +#define DIO62 -62 +#define DOUT15_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT15_IO_OFFSET >> 3)-1) #define DOUT15_IO_BITMASK (1 << (DOUT15_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -589,7 +1085,15 @@ extern "C" #ifndef DOUT16_IO_OFFSET #define DOUT16_IO_OFFSET -1 #else -#define DOUT16_IO_BYTEOFFSET (DOUT16_IO_OFFSET >> 3) +#ifdef DOUT16 +#undef DOUT16 +#endif +#ifdef DIO63 +#undef DIO63 +#endif +#define DOUT16 63 +#define DIO63 -63 +#define DOUT16_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT16_IO_OFFSET >> 3)-1) #define DOUT16_IO_BITMASK (1 << (DOUT16_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -598,7 +1102,15 @@ extern "C" #ifndef DOUT17_IO_OFFSET #define DOUT17_IO_OFFSET -1 #else -#define DOUT17_IO_BYTEOFFSET (DOUT17_IO_OFFSET >> 3) +#ifdef DOUT17 +#undef DOUT17 +#endif +#ifdef DIO64 +#undef DIO64 +#endif +#define DOUT17 64 +#define DIO64 -64 +#define DOUT17_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT17_IO_OFFSET >> 3)-1) #define DOUT17_IO_BITMASK (1 << (DOUT17_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -607,7 +1119,15 @@ extern "C" #ifndef DOUT18_IO_OFFSET #define DOUT18_IO_OFFSET -1 #else -#define DOUT18_IO_BYTEOFFSET (DOUT18_IO_OFFSET >> 3) +#ifdef DOUT18 +#undef DOUT18 +#endif +#ifdef DIO65 +#undef DIO65 +#endif +#define DOUT18 65 +#define DIO65 -65 +#define DOUT18_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT18_IO_OFFSET >> 3)-1) #define DOUT18_IO_BITMASK (1 << (DOUT18_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -616,7 +1136,15 @@ extern "C" #ifndef DOUT19_IO_OFFSET #define DOUT19_IO_OFFSET -1 #else -#define DOUT19_IO_BYTEOFFSET (DOUT19_IO_OFFSET >> 3) +#ifdef DOUT19 +#undef DOUT19 +#endif +#ifdef DIO66 +#undef DIO66 +#endif +#define DOUT19 66 +#define DIO66 -66 +#define DOUT19_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT19_IO_OFFSET >> 3)-1) #define DOUT19_IO_BITMASK (1 << (DOUT19_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -625,7 +1153,15 @@ extern "C" #ifndef DOUT20_IO_OFFSET #define DOUT20_IO_OFFSET -1 #else -#define DOUT20_IO_BYTEOFFSET (DOUT20_IO_OFFSET >> 3) +#ifdef DOUT20 +#undef DOUT20 +#endif +#ifdef DIO67 +#undef DIO67 +#endif +#define DOUT20 67 +#define DIO67 -67 +#define DOUT20_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT20_IO_OFFSET >> 3)-1) #define DOUT20_IO_BITMASK (1 << (DOUT20_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -634,7 +1170,15 @@ extern "C" #ifndef DOUT21_IO_OFFSET #define DOUT21_IO_OFFSET -1 #else -#define DOUT21_IO_BYTEOFFSET (DOUT21_IO_OFFSET >> 3) +#ifdef DOUT21 +#undef DOUT21 +#endif +#ifdef DIO68 +#undef DIO68 +#endif +#define DOUT21 68 +#define DIO68 -68 +#define DOUT21_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT21_IO_OFFSET >> 3)-1) #define DOUT21_IO_BITMASK (1 << (DOUT21_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -643,7 +1187,15 @@ extern "C" #ifndef DOUT22_IO_OFFSET #define DOUT22_IO_OFFSET -1 #else -#define DOUT22_IO_BYTEOFFSET (DOUT22_IO_OFFSET >> 3) +#ifdef DOUT22 +#undef DOUT22 +#endif +#ifdef DIO69 +#undef DIO69 +#endif +#define DOUT22 69 +#define DIO69 -69 +#define DOUT22_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT22_IO_OFFSET >> 3)-1) #define DOUT22_IO_BITMASK (1 << (DOUT22_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -652,7 +1204,15 @@ extern "C" #ifndef DOUT23_IO_OFFSET #define DOUT23_IO_OFFSET -1 #else -#define DOUT23_IO_BYTEOFFSET (DOUT23_IO_OFFSET >> 3) +#ifdef DOUT23 +#undef DOUT23 +#endif +#ifdef DIO70 +#undef DIO70 +#endif +#define DOUT23 70 +#define DIO70 -70 +#define DOUT23_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT23_IO_OFFSET >> 3)-1) #define DOUT23_IO_BITMASK (1 << (DOUT23_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -661,7 +1221,15 @@ extern "C" #ifndef DOUT24_IO_OFFSET #define DOUT24_IO_OFFSET -1 #else -#define DOUT24_IO_BYTEOFFSET (DOUT24_IO_OFFSET >> 3) +#ifdef DOUT24 +#undef DOUT24 +#endif +#ifdef DIO71 +#undef DIO71 +#endif +#define DOUT24 71 +#define DIO71 -71 +#define DOUT24_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT24_IO_OFFSET >> 3)-1) #define DOUT24_IO_BITMASK (1 << (DOUT24_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -670,7 +1238,15 @@ extern "C" #ifndef DOUT25_IO_OFFSET #define DOUT25_IO_OFFSET -1 #else -#define DOUT25_IO_BYTEOFFSET (DOUT25_IO_OFFSET >> 3) +#ifdef DOUT25 +#undef DOUT25 +#endif +#ifdef DIO72 +#undef DIO72 +#endif +#define DOUT25 72 +#define DIO72 -72 +#define DOUT25_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT25_IO_OFFSET >> 3)-1) #define DOUT25_IO_BITMASK (1 << (DOUT25_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -679,7 +1255,15 @@ extern "C" #ifndef DOUT26_IO_OFFSET #define DOUT26_IO_OFFSET -1 #else -#define DOUT26_IO_BYTEOFFSET (DOUT26_IO_OFFSET >> 3) +#ifdef DOUT26 +#undef DOUT26 +#endif +#ifdef DIO73 +#undef DIO73 +#endif +#define DOUT26 73 +#define DIO73 -73 +#define DOUT26_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT26_IO_OFFSET >> 3)-1) #define DOUT26_IO_BITMASK (1 << (DOUT26_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -688,7 +1272,15 @@ extern "C" #ifndef DOUT27_IO_OFFSET #define DOUT27_IO_OFFSET -1 #else -#define DOUT27_IO_BYTEOFFSET (DOUT27_IO_OFFSET >> 3) +#ifdef DOUT27 +#undef DOUT27 +#endif +#ifdef DIO74 +#undef DIO74 +#endif +#define DOUT27 74 +#define DIO74 -74 +#define DOUT27_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT27_IO_OFFSET >> 3)-1) #define DOUT27_IO_BITMASK (1 << (DOUT27_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -697,7 +1289,15 @@ extern "C" #ifndef DOUT28_IO_OFFSET #define DOUT28_IO_OFFSET -1 #else -#define DOUT28_IO_BYTEOFFSET (DOUT28_IO_OFFSET >> 3) +#ifdef DOUT28 +#undef DOUT28 +#endif +#ifdef DIO75 +#undef DIO75 +#endif +#define DOUT28 75 +#define DIO75 -75 +#define DOUT28_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT28_IO_OFFSET >> 3)-1) #define DOUT28_IO_BITMASK (1 << (DOUT28_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -706,7 +1306,15 @@ extern "C" #ifndef DOUT29_IO_OFFSET #define DOUT29_IO_OFFSET -1 #else -#define DOUT29_IO_BYTEOFFSET (DOUT29_IO_OFFSET >> 3) +#ifdef DOUT29 +#undef DOUT29 +#endif +#ifdef DIO76 +#undef DIO76 +#endif +#define DOUT29 76 +#define DIO76 -76 +#define DOUT29_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT29_IO_OFFSET >> 3)-1) #define DOUT29_IO_BITMASK (1 << (DOUT29_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -715,7 +1323,15 @@ extern "C" #ifndef DOUT30_IO_OFFSET #define DOUT30_IO_OFFSET -1 #else -#define DOUT30_IO_BYTEOFFSET (DOUT30_IO_OFFSET >> 3) +#ifdef DOUT30 +#undef DOUT30 +#endif +#ifdef DIO77 +#undef DIO77 +#endif +#define DOUT30 77 +#define DIO77 -77 +#define DOUT30_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT30_IO_OFFSET >> 3)-1) #define DOUT30_IO_BITMASK (1 << (DOUT30_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS @@ -724,18 +1340,44 @@ extern "C" #ifndef DOUT31_IO_OFFSET #define DOUT31_IO_OFFSET -1 #else -#define DOUT31_IO_BYTEOFFSET (DOUT31_IO_OFFSET >> 3) +#ifdef DOUT31 +#undef DOUT31 +#endif +#ifdef DIO78 +#undef DIO78 +#endif +#define DOUT31 78 +#define DIO78 -78 +#define DOUT31_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT31_IO_OFFSET >> 3)-1) #define DOUT31_IO_BITMASK (1 << (DOUT31_IO_OFFSET & 0x7)) #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif #endif + #if (IC74HC595_COUNT < 0) #undef IC74HC595_COUNT #define IC74HC595_COUNT 0 #elif (IC74HC595_COUNT > 7) #error "The maximum number of chained IC74HC595 is 7" +#endif + +#if (IC74HC595_COUNT>0) +#ifndef __helper__ +#define __helper_ex__(left, mid, right) (left##mid##right) +#define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) +#endif + extern uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; +#define ic74hc595_set_pin(pin) ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] |= (__helper__(pin, _IO_BITMASK)) +#define ic74hc595_clear_pin(pin) ic74hc595_io_pins[__helper__(pin, _IO_BYTEOFFSET)] &= ~(__helper__(pin, _IO_BITMASK)) +#define ic74hc595_toggle_pin(pin) ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] ^= (__helper__(pin, _IO_BITMASK)) +#define ic74hc595_get_pin(pin) (ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] & (__helper__(pin, _IO_BITMASK))) +#else +#define ic74hc595_set_pin(pin) +#define ic74hc595_clear_pin(pin) +#define ic74hc595_toggle_pin(pin) +#define ic74hc595_get_pin(pin) 0 #endif void ic74hc595_set_steps(uint8_t mask); @@ -745,6 +1387,7 @@ extern "C" void ic74hc595_set_pwms(uint16_t mask); void ic74hc595_set_servos(uint8_t mask); void ic74hc595_set_output(uint8_t pin, bool state); + void ic74hc595_shift_io_pins(void); #ifdef __cplusplus } diff --git a/uCNC/src/modules/softi2c.h b/uCNC/src/modules/softi2c.h index 7cee0da27..8ada05421 100644 --- a/uCNC/src/modules/softi2c.h +++ b/uCNC/src/modules/softi2c.h @@ -51,39 +51,39 @@ extern "C" { \ if (state) \ { \ - mcu_config_input(SCLPIN); \ - mcu_config_pullup(SCLPIN); \ + io_config_input(SCLPIN); \ + io_config_pullup(SCLPIN); \ } \ else \ { \ - mcu_clear_output(SCLPIN); \ - mcu_config_output(SCLPIN); \ + io_clear_output(SCLPIN); \ + io_config_output(SCLPIN); \ } \ } \ void NAME##_sda(bool state) \ { \ if (state) \ { \ - mcu_config_input(SDAPIN); \ - mcu_config_pullup(SDAPIN); \ + io_config_input(SDAPIN); \ + io_config_pullup(SDAPIN); \ } \ else \ { \ - mcu_clear_output(SDAPIN); \ - mcu_config_output(SDAPIN); \ + io_clear_output(SDAPIN); \ + io_config_output(SDAPIN); \ } \ } \ bool NAME##_get_sda(void) \ { \ - mcu_config_input(SDAPIN); \ - mcu_config_pullup(SDAPIN); \ - return mcu_get_input(SDAPIN); \ + io_config_input(SDAPIN); \ + io_config_pullup(SDAPIN); \ + return io_get_input(SDAPIN); \ } \ bool NAME##_get_scl(void) \ { \ - mcu_config_input(SCLPIN); \ - mcu_config_pullup(SCLPIN); \ - return mcu_get_input(SCLPIN); \ + io_config_input(SCLPIN); \ + io_config_pullup(SCLPIN); \ + return io_get_input(SCLPIN); \ } \ softi2c_port_t NAME = {.i2cdelay = I2C_DELAY(FREQ), .scl = &NAME##_scl, .sda = &NAME##_sda, .get_sda = &NAME##_get_sda, .get_scl = &NAME##_get_scl}; diff --git a/uCNC/src/modules/softspi.h b/uCNC/src/modules/softspi.h index 6ab19344c..9f5c47ead 100644 --- a/uCNC/src/modules/softspi.h +++ b/uCNC/src/modules/softspi.h @@ -44,25 +44,25 @@ extern "C" { \ if (state) \ { \ - mcu_set_output(CLKPIN); \ + io_set_output(CLKPIN); \ } \ else \ { \ - mcu_clear_output(CLKPIN); \ + io_clear_output(CLKPIN); \ } \ } \ void NAME##_mosi(bool state) \ { \ if (state) \ { \ - mcu_set_output(MOSIPIN); \ + io_set_output(MOSIPIN); \ } \ else \ { \ - mcu_clear_output(MOSIPIN); \ + io_clear_output(MOSIPIN); \ } \ } \ - bool NAME##_miso(void) { return mcu_get_input(MISOPIN); } \ + bool NAME##_miso(void) { return io_get_input(MISOPIN); } \ __attribute__((used)) softspi_port_t NAME = {.spimode = MODE, .spidelay = SPI_DELAY(FREQ), .clk = &NAME##_clk, .mosi = &NAME##_mosi, .miso = &NAME##_miso}; void softspi_config(softspi_port_t *port, uint8_t mode, uint32_t frequency); diff --git a/uCNC/src/modules/softuart.h b/uCNC/src/modules/softuart.h index 103d6cbbf..e1b8103fd 100644 --- a/uCNC/src/modules/softuart.h +++ b/uCNC/src/modules/softuart.h @@ -41,16 +41,16 @@ extern "C" { \ if (state) \ { \ - mcu_set_output(TXPIN); \ + io_set_output(TXPIN); \ } \ else \ { \ - mcu_clear_output(TXPIN); \ + io_clear_output(TXPIN); \ } \ } \ bool NAME##_rx(void) \ { \ - return mcu_get_input(RXPIN); \ + return io_get_input(RXPIN); \ } \ void NAME##_wait(void) { mcu_delay_cycles(F_CPU / BAUD); } \ void NAME##_waithalf(void) { mcu_delay_cycles(F_CPU / 2 / BAUD); } \ diff --git a/uCNC/src/modules/tmcdriver.c b/uCNC/src/modules/tmcdriver.c index d25df945a..da9e08cff 100644 --- a/uCNC/src/modules/tmcdriver.c +++ b/uCNC/src/modules/tmcdriver.c @@ -41,18 +41,18 @@ static void tmc##CHANNEL##_rw(uint8_t *data, uint8_t wlen, uint8_t rlen) \ { \ mcu_disable_global_isr(); \ - mcu_config_output(STEPPER##CHANNEL##_UART_TX); \ - mcu_set_output(STEPPER##CHANNEL##_UART_TX); \ + io_config_output(STEPPER##CHANNEL##_UART_TX); \ + io_set_output(STEPPER##CHANNEL##_UART_TX); \ for (uint8_t i = 0; i < wlen; i++) \ { \ softuart_putc(&tmc##CHANNEL##_uart, data[i]); \ } \ - mcu_config_input(STEPPER##CHANNEL##_UART_TX); \ + io_config_input(STEPPER##CHANNEL##_UART_TX); \ for (uint8_t i = 0; i < rlen; i++) \ { \ data[i] = softuart_getc(&tmc##CHANNEL##_uart, TMC_UART_TIMEOUT); \ } \ - mcu_config_output(STEPPER##CHANNEL##_UART_TX); \ + io_config_output(STEPPER##CHANNEL##_UART_TX); \ mcu_enable_global_isr(); \ cnc_delay_ms(10); \ } @@ -60,12 +60,12 @@ #define TMC2_STEPPER_RW(CHANNEL) \ static void tmc##CHANNEL##_rw(uint8_t *data, uint8_t wlen, uint8_t rlen) \ { \ - mcu_clear_output(STEPPER##CHANNEL##_SPI_CS); \ + io_clear_output(STEPPER##CHANNEL##_SPI_CS); \ for (uint8_t i = 0; i < wlen; i++) \ { \ data[i] = softspi_xmit(&tmc##CHANNEL##_spi, data[i]); \ } \ - mcu_set_output(STEPPER##CHANNEL##_SPI_CS); \ + io_set_output(STEPPER##CHANNEL##_SPI_CS); \ } #define _TMC_STEPPER_RW(TYPE, CHANNEL) TMC##TYPE##_STEPPER_RW(CHANNEL) #define TMC_STEPPER_RW(TYPE, CHANNEL) _TMC_STEPPER_RW(TYPE, CHANNEL) @@ -1229,28 +1229,28 @@ bool m920_exec(void *args) DECL_MODULE(tmcdriver) { #if ASSERT_PIN(STEPPER0_SPI_CS) - mcu_set_output(STEPPER0_SPI_CS); + io_set_output(STEPPER0_SPI_CS); #endif #if ASSERT_PIN(STEPPER1_SPI_CS) - mcu_set_output(STEPPER1_SPI_CS); + io_set_output(STEPPER1_SPI_CS); #endif #if ASSERT_PIN(STEPPER2_SPI_CS) - mcu_set_output(STEPPER2_SPI_CS); + io_set_output(STEPPER2_SPI_CS); #endif #if ASSERT_PIN(STEPPER3_SPI_CS) - mcu_set_output(STEPPER3_SPI_CS); + io_set_output(STEPPER3_SPI_CS); #endif #if ASSERT_PIN(STEPPER4_SPI_CS) - mcu_set_output(STEPPER4_SPI_CS); + io_set_output(STEPPER4_SPI_CS); #endif #if ASSERT_PIN(STEPPER5_SPI_CS) - mcu_set_output(STEPPER5_SPI_CS); + io_set_output(STEPPER5_SPI_CS); #endif #if ASSERT_PIN(STEPPER6_SPI_CS) - mcu_set_output(STEPPER6_SPI_CS); + io_set_output(STEPPER6_SPI_CS); #endif #if ASSERT_PIN(STEPPER7_SPI_CS) - mcu_set_output(STEPPER7_SPI_CS); + io_set_output(STEPPER7_SPI_CS); #endif #ifdef ENABLE_MAIN_LOOP_MODULES From 2d23051fe2be276f1235e5e1e62a6979d1dc48fa Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 8 Jul 2023 11:56:37 +0100 Subject: [PATCH 011/168] migrated esp8266 --- docs/mcumap_gen.xlsx | Bin 417859 -> 463701 bytes uCNC/src/core/io_control.h | 1 + uCNC/src/hal/io_hal.h | 64 +++---- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 203 +-------------------- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 7 +- 5 files changed, 38 insertions(+), 237 deletions(-) diff --git a/docs/mcumap_gen.xlsx b/docs/mcumap_gen.xlsx index 556507546e84d2d48301653cde29e90fa0d81124..10826b0859a6ddecdfab34c30f667cd11ab8baf4 100644 GIT binary patch literal 463701 zcmeEt^;cZowru0>?iSpgKyU&C3GVI=jU*7Dad#)UySoJso&CTp5^&k(S2VF#j6ZM4j-Lv2`MsP)=Y0U zmNQ}Eh-y8l;Y=We7*^aFO0#*sv*P>#XZ>nichvq2_rg4U-)Co#g3w}|n4Da$*1T&uT6-r7gF)ngxOvY8_DLz6J&MmvkYmN6Yv};tkg{ug- z%YFa+qDof#{Jk0x@4|g@hJP4-+!RToyUL>R?n_b>jGy zbL|cZb8vLTsC$0>{NpQ!{7#KXXU)m(iIU`AY5g~$_2q5RCtZA>B9Dyqo_=%>iL1zF zn0ybE40~)m%Oz(F1^Tjw>>ALJmxThe2?kt^kw@OrkZ+=G+YXlmq_`Cdl#o|^e-hS+ zbVnb3cz7ta%%Dgoof(IrytAJy?8+8N?OVfREWYiBd0g1&FG!u$p%_Vk;~dcU%n~0N z?!u>a<58{`@AE+?uarv+rA`d}fW3xaz7R+5AimCx-mx68yv6SRKJO8_o}ZrJ0IL6O zrMGBt(Op2tR|&e1(V#2c#Lddlos;AF_y1qv|BILPf0SOGq^vT?g&uY){}4WUJ-?oS zEv4uwDc?n-=@;;B4XY)#=oQ&|FC#g&CTTF7oPW39!}#j@o7kgKnyVeY>S$bi5xQ2- zny~ac*AGZ63~p(%uGQOLaX!vp&R=E7DSTr3*d5PO)m~npIJQYAJNrkb0eg}|hZF^` zgglH;G$T-dSXpnw{H7LWUP|M4O;~-KVE$3^WS0M8TInH%c*JX^lbH;HQFn8jdLuxj*dEGU|)eB*yyBz4KToKmMYu#6VDafuU-`Oqcxq@!C`J?cCU~phNT270}!J z^f2|F^DVBTONdQMi73gsU8BrQKq%k(#ZMP^lfzMU1|aFq=aOQ^-ejf6nWw+;_Y}Kz zti#6i)bdTa~ZVCH~N@GTgfDw4J&Q6KY=UBn33pDU9qe3^$JUh}% z9s$M2jjYpA?gye*55-TuFuipi{#R9yl^=MR6rF4v-0>fm@LF3T_{C-rG9;#P6IQvCU)mc+YWynzkzHnKIoEwGAcM) ziFrg9LfT?H6R>))7w%$PdfLv8V3%1$EZtj!?%P(RYlQX*u54F`;)&5Q%-~}mkfTsK zN%1JxQ9`z^bhusU2le+Kc3w$;q(yvF&b_C}_x;kyI3|{Zl8in!N-w8I*<^+}E+$KI zr3_yG1=nW!mKH?xsj#nySTs@jPYQrk?&-Gc_9S2$$2w( zG3Je3Ub%s8n5^6xbes-qDp?L{Yt{90;Nz=ZDbbiB=WSEr^maaWp!%b;t_uE%Hz`4~ znUiTF1$M`%;`QVk{v>|C8cA`bHrvMW=ZE=9pVV!2!7#nYuNYB^QG4sAK!Liczpjec zS!bor#}@6=rs4Pciubr;*~-G52!~ZeeISfeUw}*hhCSD-PDD@6{-Vg}747K&&n%P~ zjz6=JwIsmm_c$(LI7U`;!4FLDC9?E$nn@{CO9n-9!K@U9bss(!( z1V^7#a+?iqmhGJrLy4rPJ;Z~8VYW{B*Y&LM0T7=%vAMtb`H!N>t-hw~N0c);w~#4aFQ0s{9kv86+NUcMo=-G`(F| zhO3c6R(_T@wvKTLG@B<8oA6hMC9B)LV|$nvaU}gNKaKbAjNmxS4=k8N$3~+# z>JO334w2pWW|jkqUf+>j%z1;X%};D5JOWto9c4` z*H}Wf_=nf3^b*+GDsI=Z1Jp?x4)Hll<^dQxAkBR&CkIIX)g!O?yB!ZPvScrQOyRlV zz~8%4Os46VRWPnpfREUjw`TR9g$vkuKMtEnaPD|wNVPb=CPKZ z=1AzsD+Ni{MF*@hK#-mX>Sd~`bByB21sh9Gv4D@#PFO%wla%#at@)Y;gz_r-_t@qqr z96btB`Q0yq2iu4Shrqk1bsPR6I@fVTT_$4v(YIBu9ZTJh4}WG|dLMs-*C%g&4S_cY zAC4}&1)n;)?{DtFqP}P6Rfju|f^|mxScamT#!9n8n5bd{tNv@f55JDZ!Tx_QkIxdb z&Ju5Tj?aEDe`#v>>+n7!*HDE+t9<+_FYa0?&ONQNcBj(!bjZXD`8s%q zhX(mtbccs@7kL^|L|!{8{*>B)18lM;=I8xKyv`2-sl&?0*z9~2=&AdiQJt6aew5Tu=n4|u z`^D$}@%#E}j(DHlz^>uLwLb)5!}t0zuDkbsKY2Ag-dN1%0bcA6*lFVr!|6>&d7ali z7?S1b@~OKadoDWf3$hLAuFvD(piTNG&o%r)R}8qkbM6p~kCxZYpf_pWX@1^9>pnt1 zda@7?7?4v17oQ#;4(m3-)L@DSAIK4%%cM`w*Hpju`-|Jb`*ot;p2vst{Vo+w|NDo- z>&d*He8~A8*kAI4$s@u0#I~6qg6}{wzP$B&2(i z@`*;ibRYbD>8v-wlS}vhV8k1ttEIec_$SMN@YDB`Nv9#4zTh6S*z5B@v*{{SqTY{Z z;hdhIf8A`phs<#_@1>hm3Z2lUqh$TfFBj&`f&Caw_?k5Z_DZk8Q}t#_Kg5*yJiTb* zFMF+5ZSKw9Xf26ggVL?rg-JMYdhk@-ub)O__j;4y{_$8dezUvnZ}+P7%~9wC-;;NC zYTd|L&*SB1&sQe#w@$amYLz+=Zx0Z8Pm59AEN92ut;Ox-fxuDSNW=Z5?LkF9%)PI7PiA8a+QkoD5&TiV+BJ8?XtYa)n`gv_Id8Jf0#B1BO11akAk)80SQ2L^b1ELs!xkM(UFvEzxR2>fPIdw7XsB zQ}3cpmDoAY-rUyqrA}}2qo%B?EM02_Q0w2wlM@$@CD3tAfgjDa(JVoS3a?Phq2aHd z)pB=#@UI>kiM0FVr2Ay{>$3M?GFXKU@%uGTe?u@F+=&ghW~=s_m2B`%gg&>U07ZGbDTeW96D*Q?GVcZL{mCW1&-FlJ={03sV5+B#~?## z_lk_y7%(Mk;y3>)gYCMY@v@`0*{zpp&dq=Mw~@=meMRE^BH3O~72_{4A6Rd^38jw7 zk79{AAn;$gm9V?eHBV)opJLy)=1NC+uGeLA?nnNq!C%$w$#eoD{V#^Q|Hj~NyXU7? zzV~R>=Gi@cS|$s|N++Wi*T!$k6MgD@7g~B@Wv)7jvOV05%k>g z;!PcPWC1*_ZiyoVp)2`c))Ao$$V(fHoo(R(>r`v{aedV7pa)QaQwO`=N+$;nlmvDW z1dqvaZ6irk& z`CX)a~3Y_Awtf=&*if_e{i2y`p%uhb!q4e1)Pe5;D%uD}*3KrO)0x4(j z!-6uAWJH*pGRTsN&q-{EL{XVOw&PweaRf}T2$y;V2CQ>aewPn&`}BZY1ZmJtgE(L1 z`J8_~7_p6BV(MB@SE?9W9_!I4n*rH79>TtDiCoCo_Y_)MNlje}I5{w_pU!>g;^oGT zYbNyp3d{>Q>_6Z^^Q846$-}AnMewHnzZ(R3;JsB^sFxJrWjT${i`+{)NywWg*xR$o# z#gKVM9X%jzLICE66MjX7IpTwbRHoNo^C0CkIXHb!7ka<9Wf7OhMV7aV$-d9q8gmmd zp0D1X;}c&lY!v?c9C>9=%`sj2(C2+kQq1JMNZG@CGZ3bf;6--VVfaQ}pK*;xmp!Se z=LIIZc|1y5|3Y#d!j-nVV5?VWr)z^q>Pp`)H^Ft$03*n-L7kVh2w`UUs(K$o&^0yd zhP26fD<2#tE>Q7MGHzfKe*z27@@5jXSCp2X(wR-)(AGrmX4v;CA-auzf zDR4uB9kms=J6!#evi&4S!3iI@odpInZ^bcA(7^AVp6^KuCY579t%;zb%fL`sqWB&- zY^AAYz(zYKZ?{1OaSYpNSy9s4iBGIAl5L+RP=oPkCRnnu(xG58S4Y*p;Ai?h@ zBFm34K>4Yw)@cX~eUrK(v5otBUDS}{rd-aGfg@m;23|D`75_R87FBH=NsooKsEI`}=mvU<4KsJ<^a?hp~`nL+gk_${s1xQo7Gc1$xv* zG`ngm?(~Sd3{`tnu7XoOkR%5TmaGUvBJ(h_JCi{eFAtV#UXdi63-2j(w!;vMkwO|8 zav)bS16aj&VwN4%F@ZTTE3hT?Y8pl=SLj&T@=Z;^4P`t`-khxx%Z~NF%pHGiOaymX z#&S;m3cGw%+YiUxknM`!B8(RY@!%d(v>lB&T9|mZg^Z6F9^|)s#nN%2=MxLF#8ad5 zyvcSW_NNJI)Q=h|AkSfq5;<p@u5t365|mf*r`bF`G2VxMdc+StVX84wFU2nlzabsboa$aLHp{blmiEFr_QX-(*{zb(TOYkoN^M34^m}YUi=g+R&#PX4L`iHBd@~u zS8e>o>SPaV3lg4KXYN^Ld&D!g>8OuInBr>R@aDQ+OL)Joe82Uog^HE>g|TB|W9oH3#>esWcVLiwiGX_h zbs!l0u0lf31>|+*|D+ZZ;c75GpIAOw7CTI1E*f-AapqZyPhHltAzm}LInK|OS{s8 zq7esk0-ns_v?_X6@U|-Liv4UpV<0w+h>cd%U8}HOww=Q$m0$(<({C25YaIPuSMl)7 zyYt;)pP)IK;|yDdZb*ZU424g-+BtU`CQof4@){Z8dAMHvWt`?GP_>9ctwH3?0}g zjf?SFaJLRSjkR^)O$WIu%7X@jV8gWYD>%P@*?XptRDtlXK=7M=9-=WcOCIglH(vZd z!~3`Y&qthjl|8QeNQcXcxvQGV7Vpk36%hEbk-YG6fm1dQT0oHsLm_x4E#VFnyYbT9 zVRj-L!OM8>qdK+Svi#wH$!GoZB7ZphMSk|3_fxaFKkFrk7O%?vQZ#i%J+JEY*_^dW ztJg9)cVI;37{Nf<63@yGyTg;C@rxtS^g0wC!rCu(`Yb**_pXXTE550+t9MC4>!@y_ zz=%I~j&nR^|4xUiOgKl==rr$HzNpIH*CV{eT#e`EUMYEAS4@H!)1>DrPMs6nj%G#X zv+rc8vn|Iy9Vz~J?ykv1h5x!T#6k3O@mmEZPdnyrEG;EsM9GI>vCAs0Z$EI8T@@O$?;SJSvmazQ zvn^kLI+_?u`)FFYP?8OiHkqdIc(;fvXRJae-wE_HUaZ{L@wlw<`}(?BX1!5W5+Ljl zZ)A2@N(g5#)~UgK{NDH5CzclOJ}aZnE}MXf&NOM{MvmDJ1ZJMJ12oPk;`jFhwe<4C z0esW6zQLG?b~=k6*rgXg6C3z6>BRvlsz65ie z>+g)B!zX&W`BV5^!bjKkT%tEyZWPr0l_K}~2OR_PS51gt z=`X3e7yQG}u~|#Rh!ml*!O^mwIR}&^?tI&BX_FHQj~1va*3{+QK)>8TZ@;%Xo8E}} z-ltPUz6DKJO9UA(-C6qRjwLrgN_IqChXhksh_|9R*VlRb2uz>{6U6eLXzpcW=-A4x zNpcY?pzn*guPh{RK;b<{A_t9i^l{%L5ubYEZM}y^bYKnNR>xd`O)X5BdP&Jc z=QS^zuXuO{f*D1!+x9&Pd{FzjXdOhxK~5%2(XV$3O;R^w>vr(;X>!(W`qNrk9X{_g zjjLjQaUGtbSyIW~etS%3XRGf+$m80@?s~YmU$ivF&Pb}(9^^F|Twr~^C;Dc{(O*5q zGE2f>YSCR&H!323sbdzy*U?zo#h4FfB|GS1Vkx2@y??2xL=eUspv<~6D^1QT93%4M zBgZ(@{Dr7gd~|eFAvfXtndUbtuo>hq?ndFhrX4|dzR!k5lZWAu;khz^1<9}>zQgOy zLKMETiHmkWmJd_WO+=@1p=K6kkzOL59Dj55s3Dx>5aMQQ?EmSj*>O)3%d15!{gJ3l z`Ktx$>w*(*R-Pp9;pT)j1+F~B{xzei$M&c1i*={|!4orU#WTa#I+3q*z8yZoj2&4Y z#{4;|WuBlPb2X4m8f|Q1%bEl&ugwweHDih~?9tA9xoKk;h`(u)N#<0S6c29-!KoCh zjf%LW>u4xs!09d-12OrWq$q`Kn6cBg&P?yC%jI>%9I+9! zCzb+HN@rUXseb!a`~1#u{Fpa=QKKRexwdW=0*AAv(7j^eWPo@`;qj=k0<*9`fnfuEtzWVl|SZ1b>?y5V_(VzdCq_sBJ?J7 z7nlw>4XI0U;+?aD{2Z-i>U21UPG$E8B87R^lyX@(7>gw zTQU(2Sr+vSw50LN3+NTO!6$M4+=-$4j#VE#P1OF9P8+PPd9G55(Bl<&>PAP@6km6w zY}jygm#MGrT61*Iu0wWz9if^L^L+Da2i;9ljng}?m%4$dGr?>sf5om#u8l=PR_~5| zu*{AgQi9ppsE*1NTFN`+$3 z$qQpcA%gQm2ZQ*_%T=P^qmg{E5HNxVFwiEU2G*- z-p8S^HbYfSNHC?=32xvCixRbqs1G=51-z{Lbcc{!Xunfqu7Rhty7 zzewkKk^WAI&-)qPFR15gbvydZLCusC|=A+{oa7dbu+88B)_0^*sf1C>`ifl z4D8)$+7AZC)0K7kkl!TWLgSZwT+6#)FO|^{4afM|8P0iwpr1k!XqTO;PC^%HM=c>K zuE=h;LH-ThEaci%dzeU|24ns5ZGbb+Noq{+h6Ou$YtneSI*UoWCiFH<2w0N+?7B1e z3-;bK_UpHVg`GQT0n#Q6ZBW+}tO;C6EcKWdLDhdP$DZ42yNC8KOZ62P{v^!Q%CNDdNn&+I5xU@ad$z`|6em2` zs=(m7ffCap!Lmp>1t2_|LY|-l|9aL?ar5KHNa6O`L^xbxqdlbx43T z_hrN}p%pkW^q{7lert+olwHz|ym(oTOLH~8qzVeHc}`#c^Iy=3FVHqTxSK9M|Mo?F zG~G?;Zh+wY*>tp@9-i@V*Q(GPv@KO7xgDtPcuN}d7v1x&FS=!M(dWYkKVXIP7M&Lvfv9qvt>=wo_9shCg-F+nfNY#Pb= zMPi;UY!fLS-I_S=j|i?X(y`*Wh;snCE-B;=M-{&527VGwU1{Gs=UZQQ@87eVpn1j7 zE>?p)hn6Vfs<>6iscJA#-L6VtUnR3XTh6YwM|PaA#`&(Owv5}AAh-XmK}qZA99J^R z$M?UaPTL8I3=ZeQ)ys_A-$S2J7y@%L!QhT9;g&sYTq33NgM3euM;KmcIw)#Jq6sN#)<8_I zMJjW_U$wjtiImqn1-DV$V0d#)_g`_4QY`M6v+mugvMeIi8bTi`5gB$sA1ZOQyE(lM z`HGNS+wxikQwC*-JutfGqZ3Ngjuc*9iJgiJhxd64edV{e33XU%Jz)a7g6l8ZQJ1>k zsV1N$)Hk^E5P6TZv@aA8kbJ2k^l8{o8NqYqvYHBr8m#lKBS12MInz%4dvRK%jy zTFtH}MsH_M5Tsein{x5{sQx^G!;y1U1Qc=FK(YI#E>8NHY_UY&uHtGT(lM=sm)lBb zX%WRVz4~2HVV7Q#IRYoO48`Vx8Xnk?S_xv(`VFVk0$n}mwf3{?aKwh~_2km9!G|ls zw2o8}N>K)|#2~X(Tx*1|Qb#OVJD&r))wFURV#!spEfddhn0V*qlOw1nwZuo2q+a}7 zqpR5Clp>751)hdzF*O&zr7K*h+Iyh0VhRLhfhqg8aKrY9afy|-De)ukCEzvIaQhAv z*V4FHx%gszuosrF{S_`XofS1nV)EUn&g$Uca+lq>ek64uefW+6KS=E%4LwL?qlay{ zvU9bncVd;yfVLDoSy}@7Q=L0~07Wxg!b$9LEZw4p>s=JU967;ikMltV*Re1(a&>QE z!`p(APm-A0)G@J_dF{*}A%>cIJ(IfTB1x5hiipgdMH4C?I&nELGK9sM&L09Jy4&gV z*V6adb94%-5B~<&TSr8=sT8!yq^e<}LSUZE$rhNZa7C?ucqY8w-20X>81R$xVVuBa zhim6ET&CM(QU$yA`M1@3L1?YNZcXw6-gJFDlsRK9KYT-sz5pjbE?R2%7&J56aEZ{8 zdcCFUjfJ`91KmGNRM&i<&qz#EQ$JfyO>UDhW7a8uiT?)TVj294CG&NdJ@C5czHf#w z+cV-FC80R!$WVMb#dRQbPJMt>h zLQ<6G>Qh{#*u%Ln{kU4PbkGZ?0|0+q`3ytve&@!?&IWQpzc7S7LFvO-RB&yG7F$D( zJTemq+`j zg~uA8!T4O4t^-YMWOs$`8un%CWm2b+--lRu&`M-!+4AKe3zI6d4lL=#53P?%v-zCl#Ds0Q zv-7n!(vmB(4kQ}jK;I@{IKR#Bq9fgVZK2}un)aNFclv z#3s6!D2i=)O{X>7se@GE0mrjaZ~IOr%Nw(lPh z&$Y-%*Ak)QZwr(Q+9ReV{g%YVk`_Xz*6OM#QRMQDYiMkGiVdY`I*IFw4FwuSr2R?2 zm^66XCe+wcdP%vW!*|3Ox$yrfI~OYZosgT#i)>Mp7ul~~WWRb;OT3Af(HMH3^{+0^ z4Sn}eq_#ulgWLP;NWx9L+D`bh>bQZ$Y1_)}B1w$!|4>~LMy1IAFgkzsJmpo}&&WE1 z>>~+NpFfj|G27oH+Ezj%WLjrX*_DTnnnCY8E5`n2PGgW=&5AFG)Gx+f=&MeFYc8o6 z|NL2_rp6%6f34AW&A#VvEx;QrinhZ)!m@nl^5-8AojabS5{FzJZ-O@+?RaWNz!lpG1;3xn0%APx` zQpcdWNuJNrbTltod6K!76S~QNGML~NBJ=luh#wLE^1v-3JVgZcrsF@+J5${nHEBQQO9LLsj{4{y2}b} zy(}N@x09-pp**PRjE9f81RVX)iE26zYC4y)2pu&9W}>o!B4_X&hsM!TQ;B4?jW2W~ zA+{Fu?R@mufp?};? zLd&RFLdMYHIeerftzFQKD|jHT%D;UV8fI$_EF7mVt+UA-sPT_`H@tJ!G>H0LMbxE% zzIlg8PnExb`<%0J#pHy==(e6FS7%=^1BLWJEg+1o>$hO^{dOa-!IUHYqe<${6L5_F zho)mlm_xRQKNiNKE8B>wU#iyB7u5n9dy?#OSY?w#zEFcFj@g1wW}&~{5@qtwf~Cp6 zvc~%0_^F^wReQpH?GzUOp)@5C56f5E6~(Gt^bBr=*3RMtGe}P)uF-%)TI)9h5#=-7 zZXlNq`vudR`YC^X9Gd{+y@q6IT|j0~O~R-Ajqx{J(4PYcj{z^IIG@DNq3*NSkNG{R zdZ*aPS}k^;Ogn!2Z|S;1H0x&$h6q^=ZsBVc^7?>d^U$N4W#~kKhySDk{VnmYtaQDO z?dmn#YHU3yfmsP>q&{hJPhy9fUI%xh+pLAv_hQHtAd%pDfbmB8`?&XnM0w@+@z~H* zvJupb@--Ji@!@e}$A-pK*R4uEO!V~BH}=H4eupluE;+60heekDlc-cU8B(?oRqNdY zP+qnWD`PA{VUy%%R93{;Ii7>w&f08E?f0_U??ts2lzw4hVC%VZN?9yaS6^d?RIXHK zvsGu4v)1NC9V-+OkyRVI@YhnZM!gT(PKu{|KQw%dN+m{qg(Vo1OCTl#-QxU=K3zd( zv%)j**XD$1q*b@^3EtlghARgWX5W+_FW}2 zf2nfCCM>r~rG_Px;oF&!lN{+uR<7zisd~D-Y*Cx32j#Sq15Z82`cy7QBf4#pbhhvz zv*y0rMOCA^oGTV@NlB_zX$O%Ssp@TbNNW5X5*tzt{gr>-1x{R6EXgCLA0Ix-BU1VJ zJ3O=92Fqdj-yH7!o-Nz75sMP!S18{SVQPd-rTXP%Gn{aP6Isl|w-u>y*Pd~zBahYQwW2W7%aHWgM-S0-{28fu2OSB# z^b7Wptv8}~tFyhE)=5AOiwM;IVA}mAep~1aOA2tF9)mRbMWHT|J!r;%){^Qm;IZC! zX8jWyUu$mF9TQJrmr^ekiA9B+Ac^3+#x}}yU-NcY8&*sob9Q~K58*-6@l`O|&9jF@ zXHX`~?A+dm$L+r{VVes}`QE4b5!a3sq=~VqJ0Rq$ut6e^!!xSm?FNNbPu3ByH*3+@ zrb8p%(;JJ$FawJ8Qc`RI$f?J!O%lZ?J%qFdW0#9EwN&kfc~P+uz>Zw-DbBWA_Z~5M zB9aQ_1LV+iNGRhh3=xIk80l@bP4rAe!q+Qx(y#Y9b?H7>+cutDZ>Y+*Z@mvma(5Z+ zL;OIH+r3H8JmVhkr=usxm3wv~zu)6T?{GNYP;qD15+8qgL9x&0vkpU1{y_1@3sb+i zt+a+e37tgTol!HF9D%B-VRl+xC0vBv91fNmuX5w_&NUo3J{lxZD%zArhz~~h( zg|%p6qqk$;2GF&r{LY4Uf*4a(N))E%(ZT3P>p8q3o=RVzC=7IhP_E&pAfohZc+k_6 z(!1>Bt(BWAPa$$ z{f4%cthd>;F8gh?Fom^{=Bg3l?()6Z#QQ*PA_2SQaTWlb6bkzqYr;fqGq4Fz1+eSb znPtw3qn%Y(iaj*Y%OGI6@-ewxOF5FIwP1qmqGMT8LiJ{cw`L9 zW5BdCPtQWWC zai%f#H2@KWtKTjHZH3+T6|@y)q4#jmR@gB!Og*k9Z9o<-JLC_f)s|Ji*p5$n zR93&1thw3^x&5utL(5Qi#Bc4{#tk~`Bm3Ez40+yRxMtO?f10p|7to&sBuZ$KpsqY1E9p z`+~slEHInw@VgDn@DJWc%5N6`)~nfU#_T%|AX;yc*VjdH_Q|RU)Cm}j-EbkM7&^7b zn-dJdUT1ya){zm2`M(BSshM7(K2u=!aPD=AW!mn>;ndHD7-zI4yZ zK~PTxL3EX}=Eb@__w=>;WO!gpZg_0xd#k?T;v?xI7y-?Nk?%Y98dsKhSv4LYVhV-& z?EyayLG!^>kaplmnBskD5z~_9j@Vyzq9xT2{+h#gO+&Vpj%>Vmb2?;3n^YkPY*vmQ zp__A22m)$5o~&asjzo^qu={d&&p)>Hv|DqFjcDAlVbrX3E4#Z6DgU|8CA#-JCtSYAC|wKRo|d2 zL+t;sv_V-s{GVA+pP($zQjYC|TQ8JD{HvK2Gg8m;#$$D|6mH50yc}7!H{I|NvJ`HS zW`B$4t%>%Oyj5`5*CjjFEpxL`I^1C%=K%fwybQ~sO+-d0y^*xsufj>f8leM81 zCSXEMNT4k~FGX>-FD(eI)-<^{3#ic-%I-*KY~}5G2O|jl!L?)kk*CPOd`n(#O~TG) zRQXQcb7=)ZdryCPaarH0kN-2!eQyIyIRYx@72>$^_`KA zylRXv&I+c)+3=-8%)~Qrf<)B_F%|b3_NlR^Q363{u=>@A7Tw`}Im&P`Kj;KbgaE<% zNcx}!cnjWRfKs`7keVKndIwI-xG**gwW;O;%!C>|SCpK?RL=@iW~4qMPy@E8mlP0F z{@Y)A5aYeRG+Ytx!cK@OyXiM0F6|72Qd>e~&io;Jt_7^$o{YkptpCDR8m4OFS2l0rye>`9B4mp|9xp00q>TNd)P+&`SXt+4$&(1sP}yu){M5 z7O51bQ6B^T(GRip^Ay0~5{@6M-vyuxNA%9yD02xUKW*RFz!xPwX+ZTWJYqdNe+wOV zm>BaA^yWH&H`axX;!tlcM$QJ?m*;iR?HpsC!3)r287X}&uaO6Ou5ER9UcJ^i8wF41 z__tpH#s}cKZWfdwgl~cr^P>K)KXj0l+EPOcM6#b+P(j|(FN4unW2pUbj0+=C6c(tB z$tSt`jf)F=uuqc&5o%-eI2Y8$e66r&8>gcB`KLryMl&Nx5ui5Kh+_cIyNxh1`KpHz z9AJJgA$-T3Ons_27>%F|JcG@wX0U*~0)Rb8Ej_|!O($VU=J2MDni)v4KEWdHpnPUg zfm)cP_6b%BAtYuTdeDiIkmXK5gwDWQUNugDvx4PC_~Rhg>b#}Av@LYRcxpQ>b$6IY zBLo7*dIK1$#&pHcHgnzw$NZQgIeASTJpNeo-XW3OSzv?8L80+UbL_EVOW`ig`MvidEk?R)zy4@DIMFPsjGB%GlI#zotev=BX;?=> zC~elWwp}Os;Bp-*GGA-$_1jNb&8m0aPMJqQ<4UgZWHPleZyb7e0S$|tX7#H&Rx4<~ z-tiXC^au-Em(D)!mi7%Rb;C5nJv2Z4@mQIBmtkLia5&TcnX?dWm=hoE6Tb(+2aR2; zH(PAo#gxWnNq=0YGuimH48-NyNEP3@nuNvP!gUkI7n7%^&?T)>&{_yAWwHWQ{eZPFsX=aQgLu=#n&rU7^`CSRrc^i;sUoW;ZdtnZxLsO z7~+eM8pSaN3h$@X*C(X*mN_sT`Zt(~?JkUx z6Tf?0Cmw*^OS;P3=;%_xlq~r%ngd;XT)1?apLFD!ziE1pC`aN1UpPmlaMNPgxc1^J z@7zymZ7S0c#K_!&t~jYN0~4Drt_$e<(nCqo}tiCIaKuJ!RrR9rV5PYy@HVsiYYQMdOWOcO(A;!FPY6gnqL2CK7j3KNC7Q&#wlfuo#<+qTUJJB*xpQnnNKNdY?Fy-vs3g#wN%C@nINJbqPbK_ZxC{$>Q=L+M?q;B%;b)l+ME8 z%v-N~Enec4Pd#_?p_D#o(bAGP2Sh7;uYPz^u{J7S(iDz*@S%7{&O2O^RVbftql-hu+JTF^9j7_lMx+=cp8)1!*x$BTx%BJQzBXSX(e_G}rVKOQRIG4hu^?Q#K1e0HK9WJQHGkTr zsf-v2>Mw*hs@|`-Eg*gSvXeABI`M09!FnM)QkN=i{4QZU*2Ez7l15Xax0PjV+>Q7q zGs=Ps@5#{{#>p=*bbP;^`HxGz*k@X+^p8$KFstZrM#sU>h5uv=(%m743%cx|uP|8& zyyhbppgASB`@v)S*}6~pJo4XTu1CdS4$@^gmSz#;QP-oALP$weXlx{xH4o9JG8OZ? zlH2awZ8rB3;f!RIn(vf__Vv7gOR@ zA99Xc{=BEMtU!~P($~9s&4uvih1w_n;?MHhVm z={X37?zl3mu`CwvOrLW=pK8nF4|kM7TfTX*9Z0o~j{SIWDbE)`3nP1Q0@t2FRh00O z2A5{E3*jY=V#UuP_Usl(1){$`CLOm_4HnmGj~hk7`R$HC$#F#gohdZP3U#SuXYt|x zizUqz1dPVljNz-nV)=(7{DngXzFm(?{pvXDCm#$Uu?$>SWyg^&I(isVbPe;WmtUE3Rn{D0Vc^LVJg{%^b;6;csGDUvnGE`ySt zu`gpS2_uQfHb{i*>mbY62V;mVSt7}v-B`0^-}h~-_nGN)U02uj`(B^>{{8iP{2q_{ zpPBc(=e*B(zP9Iio%1?I4~fn+-S+Ph9vmY?=PT0DXVrcV9iEo==1=xSUaQynQ&mx$ z)qjmJfBJHu>U<4APUE#%eVN@Yjj{5GQ7Cq|~Z19P?fTqVL}QN<(s+Ho3?55s>f<@E<^yPuysgdwlb) z+;|Dpf~9;}mPl2-J34pYD+~$5(!Z8;(i2GjwdE}pX7lmzkKH!{W}w4=x{)_krTgxp ziAdmgfZ^-+ou&iu&gH-P_zy=afCT>b)-VgVH(i^7ztt012<$(ydyJ732z-*jU0BNX zXFVi2?04-l3GnMk^F~j3J+_*!(IqD@VvsR8W$w_ndpqt>!dRA~d-qM;H}Sn{6F1&R z3Urw{d~tt?yUm3FEt+@lPaOa|Md*w+d8Ezt1lGYx-)1M2qeoL%p$0Fy=Cw#AcBAM~MW+r<5`i^Ru`d-Ti3a6^A&34+yYOzkYuHPN6 z5C~Dio_uvW<<`M;E92>^>VtEBr7A6(Yg?2Oa3*Adw1NVu$+A9++0##7KG2oMW{XE> zZ#n6CSY4emr@T15IF8mj9U7MQHZ&}XUP@wf_9SA7n{S2qXRF~-LBbN1clg#^1#Xh9 zUqEF({JQ587-+8kG%eYoDe(MA^wLX@rR!6oH+usbM=*4HNI5#P7c002zTDWvL8mRI7>h7iC|@-tJ0gW>i20u3@Hu9H$NV_S>@@um)7cJ zWsfco87gmF+Bp7mcIB#oOYM+kU&(eAejIZ60&Bp(ae+CNQ|Q^9P~MMk_g^?H9`0}5 zZLx5A*laPD=2@r8H!zwe-$6t71uBs%R5?`{y_e*~La{51rSyAE;#?8aOSfM}5A(|12z9JG#Cg zR@7HuQWI;y1iH_TYVqnBtroyo*&<~^L?iF{`OHVM(VSHl*M~R_i1YH>=KoBb=!pGinpQXMDOQ0+<79V zS%ozG$r&Nhoo?o##g*<6NV0|!76vGev`Oj<`jbp^*rz=vN987a_Vc(H3VlM4a9*U% zwmUikg7b?fkw+zzh5KxR!K>=Uwjh-DLmn0d?3ZvEC-mgKmL(&bH}bwmRf+9AXOf)z z?AtKJ;;7hfRr1?Kv3Ep8qICr$sy}8#enik;{%rOs2WhZRJ0v^HmtbyFylFPX@cI50$H`KVvBQN2w!K2SmZ!<^Vohv)k7MDG% zQSbbXd7yFjN#CAK6I>V50&8PjQ7>!>F-q}SEtUQD=~VRRIvaJPlPu4;eOr8Y{#x>)FFKI8h`Nsnc6k=Y>L-E(BWWanV+9&NJfnQp6QKJC@jmhaJRq%Ze1Ot zt2pHdTG-RQLqI+w@2>Olx7ym4&#Du|h4eK4#yfC)}K@73qzh?gjQG)#S8j4^7W zy^ZQ@l&0mvN7~x$d=Y+*Qt^6D>q7K9(_Y0G!^nXjuhDx20*l@=&;zFPR?oH?<@ zAV$F%r4`P<)qh{puB*@XY!Pk;S+ zWw)o2sD2Ll<+F*1swMf@x?sxE!^IF)d6!`8z3i1djf{L_f^~m1YMEC3WvWEe!QU#X zDyYk7p8?<0_X_$aM)m-gm=!5r#5{n4mVHcJ-!mLfTN_hzuoGbMXoV9VoXdG?u&%a| z_vy9hk%RgSdNElQj9R?U09-K~Qy2V7RZG0FE#GQ=z3PqYZGzY7_w*5L2dOV6LKl%= z{>S(uHjOrH3^0Npp-g)nixm$gM)zu$Qo}bOf1%hq;8|0X@9A^XBE-Q+UK`UtePZjN zZkqTNPOouQKxrd)^dNl9NdD|WAqXgdc-z%MmK84o+>-cd9rov^hZ28&dc`422vDu$ zaK0cn37D;BIEwhGV7hO+>)0RP-7%5iAVyzQq~(HZ%jO@@n!Q6nI4@yZ6@slC!|Ez^ zikG6&+M$Dh1VE>E>hAyX;KAr04-QTT6CZrQYDT{|9Qaz37)nIU$gI@xocz6Pf`%(g zNE!bn`%oslPSfn>o=` zfn3hc2;YYY>Q%|G>P$K8RD{<3)r-B#!kS^!2FqRrY|ELE=sUMGdaM5VVTmHQey>M; zW}5UJi2K)$FAws73Up99`jwauB8}5$3)9UdO5^Rc1rfp6vbqr!_uwzP6$1bopup!_&f<9Y{s=yzGz_~U52lS*{}T!TsYu|A ze(Yp<_N@FfqyA}JE+kKTYTf0vXsk|wJMh#tYOWD2WoQ9GqVnAeSZv#TKj7FZ&d>ib z78WpToSPB%ySjMb-aua&fN(#xVGP}jus^0Z7wlW*feJ7xW}NHJMGNaq$*4bc%uxy_ zDC!4j0=^S{0BE``AD|%+S9U&-w<{ut@cAF;&U%RHndU+Aih*9h1Odhcnt(r#ZNr$M zbSQ#Eh~53AhayZHCJJAXn9wTH2+1?W;dKnA*5UorQ6MUA6C4Wk3)D=oz%cdGKUBgI z+Xoz=f7-ztFvM{Ee`w2{pnrlj%piH@=oOv#*k0T;j^GMxc(>o`&)NdtA>E8b_@^ee zAY0``HSEt5s8;mwbtTZznDKN!yJmPyZ$5{ndV2myx!1h&cFe<6wvy?-Wj<8zCqU#+ zjOqdRXM-D)wCAGIw!vShtI9{!x!uJ<%oCQ`>oaBr8d-NBnY zg81fq?OIdY)bhRM%A0sLFR3c<{IdN+0>Zcsq8v1Q!~t0d12#U8b8nD+6C4}@mqw=)TPDyAZ~>OV>B zt3wjBk~&Uem3UiFu*Xiqc@SP-R_RK{S;F?t@m`_<&m>_sr z9ziQ$gbcITZc2Q;xr-;^Mwep%!8*k{gpM{M!uLUo>qk3E^{m<8hP@EMv>6c>2>lzn z0%0Y9pj`(tbH4lI_r#wPq@V322&!yznJ~(3sN^99Ue+ZxCwY z+wf&D&b5haZtmMY0EH}SB!;Mf%nWk=K2wD zgT(nY%Kv-$TMxebHOxmZ8zdOkDF5#zQ4b+`9+JoS1Wk;Sn6B>ELX(aTLXP$i_fSWN zi)|x^cw^%4ClX(zRR+(#mAr5eWd^yv&V0i5-Ab14^_g>mj1KbV$o~A9P&I=h5qwNPUJ2MK1s2FJ8-%TKioB((oFb{BJ)b%18Vm(Qs%; z9PfqN<)~f8(Bg_p4C2w*BVSIc6>v^o#GdM;yL6Oq9!ci&&`7?wBcxzK56H@$bJ7lqpf{W-fHNU4lAj4!OCXRG_LR>u%; zynCqARx6v?9a4_B3^mxdkD&&1Tf})5eac!-(m#OVySyO3HaI%Q*V!DzY9}z6qBM*mv%tZ|*%i4XIH72eySB(wP1PIeD?m?X!-jTUGiI(gHwgiHOt3Ft#UjzgB{-dWXZbfvzK+^ zoP*Sq?V&)c`UCSWW~nMxhM(o4D~N-0mq{rzFGhTgTN3N8JeB@2?s4#5LvBz%_~nt$ z><_4g3O6_moJxJyw^;Yy<{#Z7HBGpq(Q~c~v$nT8_C!GXz?YmO6R(0tO|6hmWUN}S zF{V46a`Rc6D?G-=TVY`md3{UbUk+Lbe&usWCOl*LO5c&HFggFvuOYHtkYS-4dS7(Z8D&^*-fLtFpPsn7Kee8> zyfa2 z^I^gG(h|le2`WFcF6jqg3qR9w7wZJfICf6F=I@URMXxVFvjgrJ-lT5j?3H_DKTY3q z_k9P4S7IW1c&q=Jgi7VOSyNkZtlp$3Whb#5V*N%1$ z#!5;&8ld#BUBuB|K`g!vX)!!hg=cxIhiGqaUB2dypBy?UU|yAfs94ot)Z$SbvO4Z6 z@V$m)aS^dUK2$CN;hBc-r{(Ls5_UtYa&0e9)NZbgxVzvF7Mll)qG?MnU%ApgKG=2G zTjD!kGk;hU60*EGTWO@bzq_M4cGMo{cKFt4z8PcnVsvq3RbrlHtuwAoUE;_*;hC*r z>-3C-y~>4=!(TmnO~%x@<{cG-IYT)+>kwyaScYa#50z_?_${s(=F!_9eF`_mR$_$vq|SHh=^BX) zy(w@})~j^zXlBO#cqN^W&>+*EyqYTgM1x&6i${(NUe+7WGe;q5n%8>fW5*YtG}`f% zQQk);PP~lr_L!>q$%5s{&kKXrXy3OwQxWBpY)^ib+vx6W6;Hp*gFUYjzIO85h;5dB zqMA<;*8MeYLhZno0@hmgQfaXO=ltM-PDy>)$EBuk^gM3cPP6)yX3>@Jk>Ap7ZhiRC zDb%52HydZcZm>I5A9KfTeNkF*;dNBO${S-G|DWhAPrq_w=vH*4S>jFq$vB0N93!->7vmH}6fOu1n#^LBj`45J zJwJ9;zhZ;&pSsE?aX=_58ywzIVyR!6uoDch5^v9zX9X;GKNM zm!zhe;#+9zx3#)KTiT^?Uaob9YTgme6F&I5+voc=o7CR&{yfdA>3EFZ)j{xB4WrL5 zTJQ|}iIX+6e(#cJktb`yE-BJ}fG#0Xq_j*|P5K5CAAi=7xSSZ0Zju>qBV&HNM&$tF zBsP$f_RFaK<+V=LK~wq|}c%=F@TdrMu+y;29MvT6z^(E^_4(2KwN5 z-OhG|UCF+5`^O`SyXDrYCE{HxNfu5JWJ}UjCli$Cqt$BOkjRQWF(XE>tps%?Ss#k z#aJKNM>XsDm&v2nTV}W{Gu>s&7_GHCS8iK4owo#bAy;mW^cfIMNiMGEKP7&O|5Q(? zj}ZeCIf2#6*{yYBe ztr(vSGlhrNj2#4Xy=6K1)*|z_8^7^kQ>wWOp3ykvR#qMS2d z?^MK4WW33&u*oiAN!fK@EvCmxk3~t2Y57T8hlE+cGUU2@s4f41rkCG8=a{@L#bR_??k~rE^PMyB`&|mk_Zp|p zyzin4knZ9pc~5;=@zy}d(s$W#e`T;AP$O{GzdNMrPT6|(W$LJHphpA)t$ff}6_u~$YonrGS7yzOu?bWU zQ%+}Km8+e94+| z^~{hmq^^(;-%<{#@EL+UrJ0qs6<8V0(mq3l)2(J))pwbsy-oGe_JtkNh(e~A(2sd< z!rGbCJ45QmCoJAmiy&ag5;I3SKRcdJ+3|eaRNRVv^6%TypMHDCdE>cd@WluymYyf4 zwKQ--WNz!tdQuzdSG_3}gV84I4m0La&KE_LJ_+m0=i2OYY-}qSNUT$3+p=YiJG&6} zI?4A=Xmx&ilsZfnR;HZ=m3_6*t-dkGGn-XAgR|fkk7D6sHsNRTPAqm%ftp_H>~gx` zl2UoY<%X*gRER!0(K9g&8t}RKhP)|EEQU%zkRPdQ{hGYR)}=E`tLEJ-o&VL?GFuVK z-9W!YrBS)d!O~+5{J|NnOybz4{EIR<;>oS~R#c)CbsFy}xgFwzr)IKhgK>tP8qJKD z4w#FAmedt16VY+08B6`?4gM`=@gS09wmHrewu1T%`&8T6M%KHpLm#Q!W|!8@^{aEcx%37LeXJeN=dJG?u_EBtwqiRPHRJu3 z?_t$tbQ_Dz1GF>r{mn$N$XEi3O+Eq&&S%*K6m$=+1U&mY6axIOL+^^8q*Jy8dJVtP0s0r6lXsVsT9|&Sr1BT^P7>E77(Bj$bTPUL|?^5h%RhC|s(Y5wr)*?6&W}-24TD%1ISR<&XQ=^HdO!sLQ9pwY)peP!h zPdRIOpHy7Um`XfMJOh0-ND-P_n(q}jOV{v1K||iU&?zHMT3*95LUsys4l|ssUX^ezs@EXB!QhZ8K6u zT;NhF4$&JwKge#gS=xzay_$KV6})+Urx5!JLBDqaRp&K&X_NZbrG8UHS;yy{i5m$f zuo<)B_L#20I<%>I*Z2CtJNBH(`j2I2DmA2>bf71YnWXShXe1 z8NXUIZi$q$bmzI+@`hDqX>oqfvXbnpo$j-VbGa*)i9;xsvDq}r z0?)h4hFp8Ifh5Uj>x8bZKHm*OjAZ8dB{nd1bp?T64AnW_FICsJD9* z4(-K{82M?TZA&mFe#Vv#jd`!^au{OnO60~bM%ORGd`Y zdOkj}4w8mmy}lvs_Gm+TD<<&;KaY5+$?X^#Taq&$k~=lS6UlI@il%ffg5T?A<EI>+=|D`*b$hnx02iFDLzX03LMmJ(%`t~Kfi7iIbtD^jbW&7^@| z#EXJ6%M@Kc^oj*h<)ov#pV{Y!XWskogkhljl!Pu%{G_!SF;>bl|1DO!g(v4IdlIFe z0lf@p1Y^#g$rI1-wy0EG9Qc&w+ByLKA4Gc>Y3PzS&}rAz6(s!TLBLLcb;N*N`G}^Y zJQS;(C&M{g8dZR_&JiqNib+(Nk4)@=q@XvyZg{($-tgWEO?2mH5|>ppIF$fxUZddB zD2_R{cQ(l`gF$?+)VMWxo8uF*?&1bu)lMR-e%|7``E@qShEf=in8~8vfY(M&^=Gq= z`~i#L_FQr6?fWjUA~n_@YmJ5omf8Lk!2uqejQ;vk`)GR1+>j*9TJvi3MmPNyybzfP z$~Zyb%fF#BoXqRcUjv_%=+Nfc9bIj1a&10!d>hX#g1aJAuqJe28A-pjGPvu6@*uIik9+j_JxV27` z_y-Jno{FvWBXu=K^`GKN++?JoTQW>*3QTJ%Ok3)SfdiRi((PT@K?Dm03|N$FUbQY7 zun_%_iq^iW<+zCntDcS+ZvPY|8f48SRKRo!RqPN9CYCWUu^_<2g1F%t2qu;*D1#T5 zl>$DCoh$`@f}cqYy;}4i5o~w!pAl@AYR9wjse{1>KlTbT!3DWzmwJ}b6Ur%cQTrl_ z+b(rc{Y4?p4rqb`1$&`6L=ACB4}}-K-eiAAKd5U{DDXEZY=E~)l#{rmc4}Tkk$q7E zF@pdxvkGG7Yappz6Ykpm@=IUTY_~jw=9byLp=+He`oO(~VB@`eBVQ>X_wF2K2~+J9 z<{eTIptz(it}ROFV}(8hPpxEa%HRygy4u&}?NYJbmd{N~!#4lBMeI^dV5cZf5Yz#t zn4f=y4aVo(9mvhnuuAdK`!n}$xLhn%6S-o5cv9NIko>SM@Mk8UEKgmc%|d`#{gwEU z=g{BlX`z%pGdDaQ-&dM3T<>wT7~l)tKAN_Ya{d>Y!o|bkr2ndVzS7U{WDtlUOtIu&!??mvh3|@0vWZ6y2 z3oA87Eg$!8t6562udKpVuP>hEu&&HLe@Vi=COXbqeFx@P8Cl=?2L+O-AM87|p6r!hX= z|H#mAQ&FRF(&zzGf2Z!V(%uVKjh8yIs0**#oaNNHkolC#$&P`U1sBP>#|1|V*a+F$+qQ`W0(xiy3x%ySW`^nL6 zTBEgiebeUZM@Qc#N3-*H&|D{qv=orS3xb=26jJGkhyF&hD}?>3R(9lSu=2 z?~SND73p(suBIXx4NJ@M@{jn$z+mHIF47<*v$^=5B$tkA{a#NO(knxv)sA-#e4BHi z-Yg}ya5ir3P@AM?G70C}s}-qX_QlvO-FR7;7TPR@-A)XiLVCfL4TmP}RCSs&WvrsT z)NhvuZ4LtpLwXfER5I{y{jzI!3I&eB38T2-TEPI4vS=@ZWor_;J0vH+I9hU)GAPY_ z(Wh_bA^{0evy^DjTN>#LhPj6(B61tUwRBu0`NQQqqm$QrT-zM83@HR1+Vm-&4bzEL zd>w0>-r}qdM|Lx1i!g;lON=0l^_Ql*#wI4ZY`fzTO(jj~Cp=&ffdkt$%WgI{RF8WW z0`6-#bczMl`jE8BC_j$`YuV6qJ7s#9PrX_+LOKsgEsOA4kw@9=ol~x^9_rLQ>H* z7BO()Y8%=fep;cyRj?U%Z9-%1M90|qwJd`1ThX6Sd__bLAO^a{*-#lTzpZ5rXbROo zT$^oeMvpsopDD+&o!_J~K&Z#Fifi;Ou?1CMoj85_~-7g7+g zJK>XU)MGdE#msuuFFoN+T+7NOyUW-zsbP32rK}l|Js+l(T7=j1pDnRf_QS4T$9EUE zu4m;_u4jSk%bV1b8c##kv#tikL7kOJ#TtZBX9SoPG#U{fGRZnRb#I{novpJcz&tOi z^Cue|NI_TynEmfHpg-S|UaiJo?)8pYR*!?ml}%4}DZQsdLUBCJ1aoZvr#XbWkO+E` z!$JgncYLBN6RHBi9;oBHDay;p+iG{uF&ZSu@&hWbp=&ixS}O6=+4*HcoX7$g-i<7ICboI!_69 z)WD%Io_{VP0%}$D6yo4BRH}WjXdl4rjqk1m`8x9*RB?AuKlgmyg8fho(b3B8667-c z^pPIhf?m_vF*Fc*W`17|QiNScz!z!|aB%&|?GgTR|2Se!W_(JcQv4eQ9|FRyQMYbc zET|~4{TO0x!4(0$`e7U&se+Xx%etx|bG-qb_98F_%)F6M`Jov4z&NPwPz?Ue>ov=a z7fNT@xWJz!2L(9ELBw6~_7%Cd5N;I}2;<(&ghr)D(L|T<3VKqb>lzzM#?5ZcaxuCI zy{@%n4bAK2XaMf^4FTsQ!_C(%k(9?ulPN7@`)@Vekacjy0UBD2vc4aR`7+rVi8f^hs3lU>LsrsZb&`3XFN zf$64C(E8Qy_(EY3y!}Ed zAht7K|0iN=)hUgGI&jTVkgaE7Av$?iLD*=b2Dve9i}stP#ITurMGPCaTte8)>Fj*o z{n_diih%1+%PmcJ;q73-xZ!c8y=xq^Fl;#^QSa!QaaR22;i<_?JzlYn8w{5y?u%Wf;y&7;~B$(ynYQQu9+- zw6=aW>tbCQl>l}QF5lH*0K?(Jv&)q*WiWLCSe!P_X3e%JEn)S#C9b%&D?6XED;r!> zZ&IggJq_u~2D6Vg{u!BA1MRd_QCg=aANE!@DI z8jKYe4(DAesnVbo!~!uCF;FbBJ1gi(mYsZp&Yi44Ng%-31BcOyLV9f_g;Pg`g&)|# z`5&M43y>>!*E+NH`7JAr4hpkV)uOF;SU+-q05U{qZ*xD2I5Yk#%r}AO16WO`YZ>xq zl?4=*^*)No?ieV{cK;9(a0`TuJOa-OoS~Ra?K`yEnWj#>{x2art%El z#`aj5>50iBSm11n`fxV#It>`EC?X@Zv@qL>P0KM>+hH*cUMPsoHl7(DkQW=5>ddxI zKx>&^%g_SX9CMrsm{qpV4agH6s$1nxhe|rl&QllwXZy>c3KigN zfR)iW_VaPtfXLEu=pL21?&5sS)wEVjqNdDsAVgNO=u05PJR9p<;7To*Rp&@*axAiFFwG(-KzUUs#Ur2|Dx8V(;i zRPeN%AQVz{Zel6_k>mm+zY$fsi`lsH*93jr%-3Ctn8$SK(koB}OtIoHGCfn@2sQEVXphvzKmQUq|oO@5w{6+ezpP$&24S)e!ekwUi8Bb3Nf0LMgfP*;Z-Fpbxtpa#*M{l0dvx&A*SRP; zU&+YYB6ynMW2|YB>U5sh^TO2?2)h7kMy%9#uAxmHr;eM zLs3WV)lC;Qo?b4+E25RLlHG1M6QgmXxIJ>Nv)}Ag9mgI-bG|_iK=;fR(O+^8K;2E9HKVCd5`NF5Kz81Ar=aqBp`8?vZ$wCeFo7L-_$GUY2Pe^V#ogS4L z&po!ILMhhZbo#<&4=@d*axT@PVD!y7$LODoa~=cA;Y{1nDBbmbEe-nlk+W`{ftd+$-F=%q!@`$L}tj zN?CeZ_Q2$HE{*NmJo2UQLDzLixp6sL&2Vj3!xp&c2hayx8)t~U@B=y!yL)fw3@O!? zoz-^;kGYw6!`bTMRvpqhhygP#Wx)eUw?~|(o`&duCcc%Xswjwv-44>~X&f zy={&I>(6)XVExJ5PS|I!at&$HoBeB3m3g7TartvRj=|?(DIxL`#|!xJ3AgPR9MoU3 z8OGYKi%G{E--jP3;nd>h3oSoa`uh0O>y>k@r&6YZo?X|z2&ZEEA=&JSq{~b{>~hyT zvdo*80Ip0Y*XxnJ#Bnm#*rWbJ4m=M{pB~nR`*m>juBF(^W9+GBnj3{I&#M|37epqX~#5e&$MNJKBl=^ zU3EBiLKUo<@2P?f>GMzFdllIXE(&MV&z;g8v<&n7NnY;YBY9>FQ^tJqv}Y#gJAhc) z@?VIbfZ)3eg6|d)v5pb}@vKg(CZ>o^Zjr`M@zx?pQzZendj`72c!Km*5^(!TX4iPn zpB6vQe=m6exSj6y?O2eqK1-5rOamzqT_#A0JZHMk=7xsLyJ~329SJ^ExJ7Lq>iM!U zZOrT51)f;VpL3HYe<5xftx%xykvN%k`b5sV!UoBu;U3Y4*H5l$4TXBXmF$jsa4&S} z)OyiLHyv5r;ITn<1B)Famw{uLfOAC1SFR8tM;8(yBhC8jaqmDxJiQLqrjlT7DoMBo zYg5lq@m5K&Ha#r2ez(DwLuqh9`;#by^`rF4$o_z1_t+YuNylI5w)_f9TVmaR5<9vc|>+uObaGhM4a>{$b z_Jm!k?WGHOHKrtVY)MHJP)m;3Hy0h8Km@ZS`SdxRNYUVImpqG$#7M|Vrcpp`&yW!j zvnAc7bxbAAtpQtVtujz8H(?_)!Z(y6^(`&A9=7@P35$a~*d)w_1?0gq z@=e&w=8{m6Tn<_#sKE;}upzznCCimUoKpokxUeAWICfLM4Vg{vtEPLu=grUgYg)=sOP#hLD~TWhGwey?3`+yOtvor?-{!`$_S}+7stq}HTbww-UKMU8 zed+R#MfTUlW#pnfmRBd875I^F+noE9y@#aWdmuF@(V15Mq;{=OM5iN$KdXJ#< ze3K}B6imD?*Zo-O}M?7EJz0#A>XHd(Si@pJNR5l_9cPaBLc1%Et?Y~u2+N&w}GR&{v;ZbJoO(b)+{iCAtF|Z*3 ztO(m98Ug}79Zd|6X!s>c8yR@n&c2_lT_;~?zjyOat}xXG105Ry3D~fAb=HO7p@g}L z5XwAOcQC+IJZ+i;&sjPp@x8Oz>u>h!<2Dwro4TCoY$ld=X3hQp(jH-Pi2y`nh$;Iq z!G)VhBuc@KBUqWTZD%YwLzlE&^vG_`kU4ny(hQB7+!rsk8XC3dmxW@l<}AHU+->d{ zBor^~uBOjdFe_@nCS1K7keEc>T!E2vWFn~g%~(#tqIlmXs#@7wbkLL6bq#1( z1rZTo)d&b+sl*~unyp`v49VXRS`jEBfoe4Ncd4M~k5U2WjC`RCkV~{gAy<(WntA=1C!Xg=^6D4WxQ6Up;!U1T{4qZ1WFa101Z(EVRg(s^na&< zUV5Sm3T22YfTjMM3aG{bzXMIs6I75RKvaPh|8Et%n$fc@*l!tfw`YS~gf7+7U^`6i zgJAgoKnp+Y7TF=;8_zrF8KYsTsXg?{vKkxRgssZodQfm-O7EGWwF=51$v}6BrlX5O zW-P^d#UC3V7f%*XLthJ$ZR@xQ4|;2;(Md$j0erzn)Bk0|JOl;XUZmf%rRu(+bc=C+Y$>`AQ*v50>hG zNeYS)xTqbT2(&S-ZeB9I_AKj^sB z%KKgamG=vGAww1h2)q0+#;1X8lFvcHH+GL%5Uhi}2va`Dwk~}cemm)|X$cBIy0jKbV zVg<98&Z1nJ&5K|G(5x=uI=j@=)&G8A!|o>7m_d2|1P=P${J{%wRN)K?992MoqY67L zF7Y6P++ndx9Xr4Bep05EWc*Td&{TQ%7%0dyL9jo8UyfdC0)A=yEpxqMlzY&~b6sbA*~Q;c&%p z5OtR7=Hl^bkdYkRkkQPXGzj3?&I5n2aQJKW;GlNgSLA$o<}HryfiWkMx7*HDIf`nl z0Wnk=!(^QJ0NsGIo1YQmLuwdRbZY6NBJE^t$D&L@^*28_m$%~X9EYU4FVi-whJbT8 z|Lr(Tv+CmY@nx11bZ|?K_if(ii@>Q12-rc~0VkB&AKHHab3$drb-wPg^OX@_!JAhV z;SC%|*#Xtd?F8?rWNnJ~%PdLfH@j~6cCVWW1xE-2|IE* z5Gc23H^JR{l2r&1C)!PjxY}blI5#By?K15-wZGHGIW>?iA|AYo#Q=(E?_mgkO zAXzD!B0G%VC}@Zvwq9L3Xzl9MJ%QqGQA4bOW&P=@J#hA9^{=xhqvdU#OyAAP>-O+Z zDQZSvL7sZBNd&Efb{GzlIdl-bER>70anX71`(H6@SBEhdW%^`Dv8Rx@1kDBla<|T3C0) z-_Q~4w~NpK7cp?VRhan)As)Y%@`#&Ah>y5i4{KaKpv;Ji+;H-`TDG2)R-unxZGkjJ zW74BtaDe2yc>v93VRuSmAq~-2ds2wL`Up$V$0MMRfWOs80MN(yz4jE4&F&~!sDW&D z6lAl(glrZiouij~2(%FZi$4y@rzzSQ^>xg71iWN#Ww={>`PUF!jq~yM8Zj_9tT5AS zbz>#BC=;wOAVoAqWt<2&H~jy#DgZMF{Cl)K`5i4VVzd+yqs2U?Qi!1fBZf**CNWg}mM>eWLH~w0tbT_I?02Ye|9hzT{SFliVyN^GLxre>zd{Ap ztw8Gu&3q(YWT8efPKJVkUmb7xrD3IpDF=a@LYy7#f;4hOMd|)#b`LB02!MPo9aBfF>ixveA&Ou7&K+;rao+JvkSXN_I8UHwmbQL*CD23ZFzg!KtlQ?|jcr{fjw$!M-=h5q7+@Q!z9+kjwtkzyyPg9s$Rx5n?kt z6<$PxQqQ&Z*OFxexd}Msx&uzRLV`%D!70~o;FRkQI8d?Ls3i+BddNu}$mjuk&k-{E zf3Ww8{8JIY-YfE&vbA)hmoUNplyz*{j3A@01sOd9LOY(z!@1`LsBxy&gMN##~G^Bpy_e$OBdslY9`z&7oNQXlLRQ># zUET}xyB(K!>6NyeUcvDrhA^mJ#c2=Q5ZB0-=il<$sjT#FT9sYW4lm%Q&%oHa9=Uhv z$O1$>`$R-n-8Z8naf5Q04tP`3L38>gvL@Iy8NKQA$IY;^N_z7(x6iqfv!4?uH9Lqw zG_6_V&5SOaHTtZ$Up(3LtfY#v_n}fha!MV5;!Wa0!5hU2zz-F?_bZqcxoiF|l67yR zjS3%GE4F!M`?GBS52J&#j8b}>4j|br;8sUt(z~F@E>>d5EQ z60#E-ul;NBbxGK`VWBfJha1^;atPCph2fFbYSM<>)M`WN!(9@LD(c!cb9slrTpDlz zn6h5!)iV1VQUq1Z$1^A8Z2GYiO!hdB*({kPIpPJ8dSHICP^oeBu!n569 zE`IETod*5|+~j8>CpEa8WnX{azDcDfD9$#O6I$@J_ekUhsz8H_!fcS>F=x>nzNgHR zU(RJe5*DCst8$;k9(DafcZhdW%?xY-4~z8cTC;|?n)4|Qkt)fkM4g`5D6q3}aHO+3YA9>!9zv13Mj)DIk4(?(F% z5X!yU;Ia=M1jokHzhB~WXH@uKw7q3ml;PGkjI@UGF{Y{XYBI@Ap0X_`VYBa3Lr&nSqSFUNY=6R;TQIytzUaeUx z>S{>EPcPH{FT66^d*1Kw)^#*2TY(!h{Z8^XlMGe*-*L1D+)S5#I0}mQ^9u)5)J=b_ zm_d3^^m|Rssj6$P)GYP)o+e{dsfmK6T>tsBL|q)jf=yyJ2bIsnKYwa9sP)aO7kKY9 z79WWm)2VqI!UTR{KV9L#5?68Z#xMfl z(@OeAJ-zZ)Zwh|D2(Y9vFI~(%P2dA`a3`ofFT7Uhx7gE!^TrUqg+Et143NZcivG${ z=+mQR&sfT8{}p?+)3f%Td(?~1Nck1Hd8@qTY_-)&GmGwfIE>%K{{=(fMFz`+*K_B? za4~P7?>Y7~!+UdC#=M5$J{@*mC@%AE%Aytc+_P2a`HqfRD}V7_5?o2u`f!(qQ)JQq z+FUVy)XNd*^Qr$qIKJltqz>Y%DQ`9Y{Hc6GN3U12ky^DC~$vf8jw_7AAV$} zi&B-S^)Ne(C6mQ#UEu)m@kj5ufqRdD&d;l}o804@yUvq;zUV*diGR4TiZ{cPhd*_qm_o`ha0li&06rw+pV~5 zQBgytwdwo|4{*<7{jx7h?^)$Ke|Q1Kio;eM)q;(UKWW{~W7b=Hse9Xyxqt_v zoNL%(r7ZeYZZFG13H(*q7ZR<@on(~@5gRt)$2%vw)U6FW4PKoqtCd5Bol`_I6*YN1 zcF@o<=_}gOxD%ndwWQ_Nz`?~^c&T` z)Uvsw{#7P-8C6~0tIATDpd5BcK7g4XQvElhREBkl4`Qx+`h_>Kri!iMdY~%Xact7e zaZasbj4eHMzX(SGJWT3WWg@gvW#Xwd=hqx$j_DRzwcfLqTP#Yv7se+Cj$&)5icVA3ekY6>4uOC@+`9VRAz1_B+GXr?gVC&R#=N~nP#;7eCns zO~er;X=YBED{R>|28=dU3bR1?Owq^V&c03n&wVz>JSWRx{VO&eM;((^gP2~=xj_$+ z5#%8IelajkK$9=W!4K~`vgCd*(U4R1^zyS>4U?1S19^e25aIje-+Hw%a z*QXoh(OMNZq)U3`1#kd^bI=HI@R42D9pC`gwRY1*xz0wn2+~`NvJC583{zRVIT6~2 zbo0!Av7b)lADF)!Hg!%iEF6!&Cw1M{j%+E?|Iu=(?DNJGW$f<`lcIhBPn3v)J}Vbq zzrcumMe_Kx2C-B^#O8Rs_0k5+2l#j!OUJAQp=*dTAcx~?? zd)?72y@lz%bc*uHeq!1zbcaszgr4n&BP8^xtB3pC!}YnX(EiHh<>h^7NmZPp{@oew zYp3L-fvnOTRM%^a9GwXAlF)b3bh7%_3+)b{hQC!AXUnCuSV&r5CmEG5k_`8xoSHOl z<$%B>%ZeH6o$;S%3Qn`V@>4Q##^cXI$B7@xT^04k-nxCxJk53|xT-vzRI|!xQdG_Y z=|VmUrvmt4zw4hwwUm5_YZ3w%E9+bI405a5ezNq`y0#z2%>wP<<$`uP$BB2j6!k~_ zvp^z@BAzHHFH_$1sOX#E`=7?L{T%l`#LDk(@g=@3|FBJ5PqJtCAaB!%>Y>L3oJzvptL27+Q`*uHCUdIYzZ~r}A zw{+DC(v{cWh#w&JjBaVtjcd7#7#TT@l{9KqF~8=Yewtmnsqc}cv!}xczHNFEz2jHMNK6Pz57KFywNkjR{@l!k;U_9F)eM2Ii%YwZT!@+1Vvtd z1f?XWRC%7%l{#BqzvghTNl#I~=6G;fG#3PR+c0zF^Gu9+tB`&^xB}6-Miipo8UU|t z4M59IpMU39)K5o|)8}POX^EcWG#Hk9ND8(N;>B(fsXxF zy$UMo7?qCP8)u&|Dg(K((f9*r<;i6V2bcy^^O%0j!KM5kFk8T-Y^a@&^@v%G{J&v# z1i-$EtNIgE^{OOfhwBzAEOw3rZ+WpzHb0#7< znrIrc?0c>3OKGA=-TAkH<=f;&QH4xJ@4Y1SaEsIuid)~562DJiZL{MY1q89gtD~!I zcy6qej@$#t7XwL%o@o%g#xw{mBP0UkYY52K5Rh+2G(LsF@Kd%*e2SIgq>k4NygK{x zOhp9x(H)m+mawupLIoW^2_3@e-)Cew>>7SXk^%2YnA+d0N+yRQ+~gB=8NQ#my$P(B zr|9%mHY~yK0eUTPc7iKVo+7l?km=cJWEQ(kR4%(sr2gZFq-7;rqg_{RY=yO zq`s=9%LQO%4b(=Xw(e|y%}|mRIq9s{z3rWLKd!z?Qe2W#HkmS~jXBBdgC%E}hnCvm zBbC$v|M@5{laL7fn~CM?)0{F>XdRhMjj{!_m(HHA(uFyvtmlF@ma`V7uBJ6Wt76!v z26YWBwCh!*@8R2B2!U5So869-dXogNosiq;2>5aZuE>sC_AzfmwB$G*CbCw|>6_cN z$y-IW8OurR;+E#>Z!){ZBi#o0y_N*2e65p<&Z$ zhUq42w!>;a=SD6Kwf#d2k-!uOQxN1p)C3U+T|FFLhbD~Hd`wwB^6WK-+G%D$dJM(E zEq{{Si(CQ*C8fa{g5t$MgJrP-3Ftbi7`k3;P{~xWK9As?$uh(ICX?qBR8y>j#-qMt z;8=}4ydyQ&po7-wn^Roq$gZQCQ_P21PGmt@v=B5#bQ(E21zxK<;|{A?&Xbr6A_}PC zWmJS_O+86)5Qi2``MMM?Ks78Vt6;Ha&=62MtG>mMkj9RvlQaNhM|99Xvp<5Bcsy>B zp9IfvE?Ni8A>zecoCPI?m0A@_HTDMq325Bghn%dd!kCS;>Ch_2@!Mt5i7B}gz;LR# zM4+W8=J(qW5{MYiQ%JLvG8iZh`FH*-h?$sKs8L6iQq~pF84ynM7MH^D8oD8ydgiej z0{zEo)F@W63B1T;joAowl?2lb5i=jt`^uhd3Ztsv1GcV$@ALLyDb_9eaBg_CCY!#M ziQ#Jd$J*u@9pq=U2k&T=qx|vMHV0$~G-xR%*8)%h9+eOW+eA%FLD}bmGO^9cb#Uia z64)UG41DlnD9W)d6jT+z>I3h~SMB|dAB_W5=di|T4Gj014g6U9L^T%os;}$YC~yTZ zRPA9Aj1#@;!_i}!YpLO^f`p{n$e%XxkDa(S%Yt9JQDMJ@{QT=$)u0GIG5V{6D^&U) z=#V^pwvjT*O&}Cn`x?TWu^HEh4-q(Gs9IMjHXr!YR>8?J$1zr!AXCMVVOmZHTsP|@ zoWx(CL`x67EM*tvd<7kT;HwhXq8H7rS z&3Cf0;M$Cd25jBj@`sb9n0&*3VuOk4kq!CRa5iM+{u>*g$tSe>;cR4O!P#hP*DXSa z^pV2=IxcFO4LjVyGz>y6+4~TEDCu0yhX|f*w~s%!kKnEPUI-g4sYdw>u-yuf0V z$<_ZP%MTHcvYgC>%QC~w>fdB}_6jb`_d?$QSst(0!3hCTrQMK>*6=9Gf`7RQx@4Q( z%qdSenK!?7w-FkF^7}44iei);E(%c_xF|C9bubZ|Cjlw?QQ^#W9T^b>M%@E@dH)-qXhOe=KAs;W#?IP0f5)Hh;t!q9G=3ag)lT*i3%M959E z+D*^RZ!U$iwu9mtF(6=UK1fV<%?XiZpD`o;+*~t3Dd1lGHq2~BbKk!%IY3E6bN8B1 zQ=!*};&XmH0@O`z&9&-j07X^Cp>B9b8&$@ST^nb``>v|F+2K>g*e-{4_|#|SuYKG$ zowk6R+5&D0b0ZIeyQ#GVrXS#@-4HrPBnPTRSU(+O9cySc)nYJ3Eu}L9%!z`r4rrYA zp5MkC1fA{iDPnjsfK|O{3F2%NPOak zSF5bZO+fH*?u>}fx*4kz!n=)In~u`X`u*uDw`z

?YuPs?7{kHjur1{U30xd?V}im05Qb= zM=^Z(hZtfX#gOsuV)*k9F{nO@A>&aD8UGZ6WS!8`sT=N~_j#9+XAX{EF{|qA!u9XH z`H+6VI${5?&h}yfXFw5Md-Hky`zY$9WwdotLbfo(P{P`_pe1f9#{lRIT{i@m;P+l7 zr0Dg)l$@ai(UFOmPl007b33?oas&g`X$@GX^`mtb_5;=l``^~-3|J=&u+DnGI(q=? z9G(ZP6Nach`=n^P5qy@|4pC5Ne7zKJVc?wm`jMXxkNm(vb=BRC@GN>ApU*;cz3yfq z?#Oo|Dhms(p4aEA-d;DEi+AfF@5>YYhx1&}!(}a~^?D1c(sDoD>U|<$-tcgAUO8@lS z)3F=W)8?$CS3*%HIT4epw5Fa#C1%`>_mjnCU8YDptAa@OX3tweg5xx*4XK?)PlE&0 z%-)j3t7Hbn>?GDok)HI6sCy=+<2`w6Q4$zxxdDj&V~kAwa~ zA*Wo$=>^BRbNjotX8!kjIJqOBtJCd$YB>RmuU9TIq6EkZkn9e{!SfXB&cE_^hD`f@Dkz zUet@hw_~zBx=(8?s#4sCAlq7#_g|3Ze8o3sC@*v=V>jxZgSAhdA z3^?H00S8shw7kgn=BXI1%Cd2NU_f3 zUs8Ml!3QuzIQ^BUSoAY1bZb={irO~1E>>Vhgv(GabJu*eBma$TcVk7a z02r9sOr+G>rgaw>uQuX9!fn51y~Gb1C-EI>oWIx9#etR>f?Vr#@Y{05Egah~1TdZ# zbS}77-79tirM?ceUhuOMAdH=}eGSjgw$Nz$gY5-iX#e--0J`~eyq%>a&jDsZ#l?Rz zEOpck!Is8YDMeeb21KX@htFC7E)QNs+kto;|A@X~V@3{G1+i`c{Ek|kNkIi3UN@`j z*g9+#y*8Uzm&#VnxmHv?XO0wB^T7mKSYTCtaC3LJ*QD1`>_FpOJAzFmHP`a6w%1r2 z%(8nv{IijA2)UMy0-EjM&8wJJTCgZ`L*c<#dtJ(p%Sp;Q)N@{NrL}McbNC2S4jK_s zLHo=B%df)=PJL!e=U(NWNRt=_e1>j{KdQM_82{*acnfP}r>oD_t#i3eF-V}2BWbG- zVUs~dK#26nwXfJw&)!DpWoN$cFg(cO7d+@j%JuC;%oAnKa3?p8l?g@g&fAFvH{~FK zLT^1Fr$C_yMP8p4QLZHA(5bOcC2Ho+)UeB<_9=eLvf9*`W##eIY5%?%W+=L;_tnng z;(kOkb1cM*HWng$b6l8-+`*{t-|Xh=QKR(*!!WINHF4Hnykbmogy=HgwrZmC`NN00 zYOmKY@W`w^+Vb$uTH#4(ZjDRYGiO|DUiO&fi6QOgONMzLw5v{dUa|Y;Ga7IB9w^`Q zl@i1MA;tbxMh~p0(_P<*8R>@ANI$T|6&0gF?&AczyXWs1tyqr9d%SN(%q1j zZUZTNBi?>80%t?-(h~d3?g%`*iwCNk97K*%rbA4(pPHk@b1KEQ9vDnYGMcUR898-mFPA~)AJr6PC#?Xl&O-`g=dM4w4| zGpr#MNlCIaVvfh4soeQZ=0Lj|w8shCOKa5&YF#_&IXA@c^KuMHmb>4pg);D;IEdv{ zy1XuI_}!7XLha0WBT5XS&A~(6-k8|i@S%BgTBtEh?HpliqV84nC&osOXpZ*FU_-~p zid%?m?z36bXvUV_6+B-CHMP>Hn6AN$mCRvJbt~5X`a3p{3Rq97>^wOF!ovd+!aD^d zWI_Z~1a#n0>$C{6zrS%j1^y?g9pQg^kUr<*gY;ttzCqaugDwJF{6`m5*Pw41ha;8o z`A4Ognv0%a@e)O`XsWSEY&BlY(5CuYb@-Ufw?0s8P2V0_z2);e>91i}k6~gMl?UfL zX^y9faF4x|_rQfPR6)|SKucSzE33g*eGSbv2#8|hI|_3FqtC-!XMOOzJ_(rF<vNmX|E415iG;JZ3^lA4m(fY?|xBuJeog&7{Z*J9qVzPa>*KWE1t zjxK%i7H+w^PGI~K`H-ltlagv>E3OUCjr_>9-NVpwdd)<`Tj{=6TSc{w2{ehipIVf> zyFV-TMtw+VIYU=v*Jqd$QX#qS`g-S?xP0fujc|_ym%`(t_KSXkBVfHzfe#p}sOMv^qa7#Z z5kII`&1;40yc;;50r~whcim_=k{BP}zrVrS2zOQfP{W~f^)?gxGyC-pJ?TrEquqg# ziwk`ab&HqF(e6p>eeTVz$7E>(=;8iwhxn>B7pi`7qIpGqbN_+8#Se5{PwEDXO9I69z!?1Qe(DnFj|-5rcj3okxYZ3{1Y zyS4C#tEk+42I+Z4d6l`9H^5*e_p6;E4|i#x_34MV4_E6i*RGzW&NpBDejO2dJ+cOo zS?u)q2-0Z1*}9(qwJtc{Z)}crm0>)1klxp0&~}9$EGXGb&Er!Z&Q~o72!wd#_oQSL zw@nko-tXhuJNtKIFZ<$d)aHn^twDU=-I?bOO_&qkS2W+6gdCzi4ffW10drP36xGsW zTU_)veHq0rWS47JNT(P+GCG4NjK6$4b$XH5R4nUqzj}T$uv<&)YD&?-fFW9K>1*MH zuL}8#LJU#Q%R3?^yK#OhR26@_AnA6@&0JUx?m*CRNW0rVnAxST$cR5>nk&#!UFCdx zUi5dXY3+jXPfV@0Hl%^!nSrBOJFt{CD>ZXG4uJjJb1q>Cqmgf^l?q-q_X%#vv6D5- z9=2U$7Z-)Ia>i2B&F`z!%QL!7&33iz5Th59->EEoHmTl;WB;XpwnJ2w5-%ItVv}oJ z)FD+oGBbCQVY-J{`*PtuyH3bnBLhDD6yx2wYlX_+zwVCPndRR|s)da#Rl-v16dE?< z7er7p183GZ_8P#5Vg^cT4-2L+S|klM2A#sMXMb)}Qb3>ba?uX_oV*cd;g6;c!_0AUwAyaQwPpOjKKc_6^T5e2}ntp0GGp^aH z&__-iV&wBmdpRd$dex`X6L#WZwV!~M@>c>OB?=`oYPM#;3(t6pe)`}fAUW7r`7y-P zYCjQcdwKB1(jOKVc5$fVtc~Aj68)WLs_Tj7-j5>3QQo7TjVDQN{3qxi+&-(^GtAC7 zKgJk8c&7SYq&&Q|qQ9S5&4R1*DJW&G)xF+*gL zBTNg!;AC{xWtRwXNepaLWxqpN>qkM7)ca(U!OlqNF#^}XVMHn1b<-_?vwEqmA7Tr` zC@?VNq>U^@y#M_ZCRD(QW9`+wkxH&G@?|K+)wYHxOv8G0kTn!FZGy4ipf|St7o%#+ zn@rIc3q{YOPo$KvSVUcKI%u{_P#VRy}a{ZGM#~o0R3g4lN zD#?2qHT+^vXm*5QU>KTZ;HJd?4u39QF=b~I=rh#mEap4Fg<)#l?(h0x$d`E#`I(Zj z-$`^^xgx-tEek=JD?$$$72VP zyA|z-F5Eqg811fdgIcuomXw?t=rb@*BPon0w%tTPnq=!&dH&@gz_WtrIQNlrjf+2Z z4~+m3t8yynK9$u5Z#ke&+VnFcb1ZNBW83rM$P#}%;Sm`b7=j(PWjvGC$kNQA zG$m9LB?{lt8=oN|P9jxY1W(Bv0F8i?kr-N-(ifkT z=$0o%NYT~bNp}zcCFehnW;aitlAW7=8iM+7|fBppdm(z3P!q~Z*flt0o zMiY_*@I;n=@I;j;GceVi>Dy2K=$GVVVMG?r6VO&zNu!dvf>^Q;Ne?l|N)*nTmI1%^g(*o=D|?eNLlc0F=J41j+&D9T3ir~nklOw0 zYq50C8)<47R}7FEQMD+5?Q;{M%?KL2Kd1>l$418aY*pd@>lY5pI_F?PWT`33nS96J zxVW?X8X+0YN^r>+Zxq3rJ*gbhpd?0Pm4uGG$zW*Y3*?#6qA@t}3GWf4L8Jm>N^^2w zMH3Nrfv*1p!ewnhd&2|d=D$*KrU!T~5~8NWj7$Kv0)IHYm1ODgzTGUaW~X8inR2QLdVARhnjZ}74dq0=Bxi6!|>rp%W#Lc|Dmlgtp|G$}pO zL}1_$5zYlDkTK71GOYNZ21UKhG6N$eJ|J8j*s-CJI@Fb6^z<|q$ype_E^4osWDS z0F%}b%xS))tjl0}qbmI)&8`+ro%@Hv*Km$~$u}WebUaF3__RROxh@e_%Y2d1W(~+am)_%0t4ML}=N*6H08kO$G;iyr@gV$4jj55E75_Ee+yA9v@0!B6x8R zgTrW1@-tupnja({ja7hT45rz1xifBw3jT41t0bKK#5>l76vD6;n}E? zZ9Q~K?G_tOf6r0!%Wdem;DyP4EKEMUFmYtKVl~h=r?uZYBTCkrd#v?GF>e^%fLR99 z0>QIQVFKGSYDU02TmW=Ydv{bLFGeNb@PaV;ls#kW zqbW99W)`AWuR<|{M49FM#+3JM#7iP?sFKW3H%(}J`fNBfqgQu{q3-r6zs1m-B-u#z z*6!KXFlG8BB4I2>R+zd5l8eeqoYWPN1-%r z>-!k;{k?(J!I&K*8g1D-tZo^>63zy3Y!9;xN_fP}c6dbPV+02p?P2tZfyeI?{!Heq z_F%^2c316DJF1ky*uT7Z-RD%4n+~{$dpGJ^E?zZ;l_sIDUTWDy%E71p>RM;9ljT(%FX^9)S_k`y%vXLMH z!mT>3ZH)I$Sh(A}TR%T99%b(RYD7S~+{ALKB~9PD3|$(tS>$%> zd{V0Jx#aK1>_pZqbkX(EoTkuw9KSNnI+E#7@_#m9)^}= zw2*ny2=e8>cwazkYeh$s5+6u``PI0Dz6TKz5CjVi4f0uZA+OZd>-zd6MKMu|WOQ`6 zXb|ZVnfuCp+RjrcFwxP)nm2Yiaa%^@loHjLe2oa6JSG!`CnI`H_T≤X66@xkU#x zZANe*no$Rb7A%K?{DatEZShO!pcV6Sc@Pa+Diw%9n=L8c@z_?bYVJxdHgT7S&I|Ib zviQUTy}5vy=EcMnUtGf)8&zZ}g{-Q8Ex=QP7F$CNlwD`Szs~0wMeUaNyCS7Y z;=|hf1MgkYOR;92o`W_8g}BhqUQGqO@W^vTBHXi9Zb#_UySniBQaLH9i8n>f1#d;M z1x4bX4@hx}P>F2)*SDw=|r(8eFyd^dZJKh>LU^c03= zP7WWuy2Zed=#GLO4)Ew)G^HqAO1aNp_*0^bz#;Z)vDrfrwM-=|DSxG;CO#;iBG=~c z*909~H4CU+KV;hAup*=v@U=wI+% z>`SByI^_?dE9rK#n?K#_8`T~`3f0ey59_f6ap?+Dd|ShxP^nl;qVY9l;?v>8e=o_W z910b+(HkJH`|w8;^%t}a>3POB*(H=@=?EtM1>x`qhHG8W7bQG%EEVCF>}^yI)Ol1Y zS=Q6Dwu-F_XcQ) zBk(Y9!H?<(Hc|96m^;77fNoEBg$eW=kge9iQCxIod)gQhX%3ZEmGIx4qZ=-Qg0oc&L7g>k~m=aLz ziY~dLA*ejXe&tde1l-$1SLwc$m%=q>Z@>~9CDT6gK_AKCn(=Kr!A3|OCwu3t6Mi*G zm^u|v{OmH;g0@%o3xSK4Gk+m1?h+}pN~M2g#K{%L5>w(6)x0OI23+TYqrNcwpn{ks8>7Eo@}C3j$9q+_ zp5@6FD>H_wYF&klzfxC-eDjz4R@6Mt@98}^s#nvG*ZiVh@)n{d7LJnIUp@if-F^bn~$N}c@cNU4%l8Ir44^-OPV;w3}vQNiJDfoe+<{-oxDcLtCA8G-R_J(kEQ zx%RAY???{MjPK!u+lxg@{3|gMi?GrhwX^45bbRuGgvO^pSR{q^9T3LI2M>!j>Lq%R z@xl$lr{sEGSb9h>salXnV>AM}^xf{2$CLEpo@~bsNYkK{s6nAQ_GkaGpO>%a8JLD1 zp=O6d>I&>NKt>~$=D6}HjuXvo)gj4;z+4w~mj|XTycDfg>I@-yMh33Dwg%@-AInejPI#Pu?P?ss81Ed zpU;vMdV8DiW}iq=xQU_LTke)Atf9iz=5RKSqv27uFtj7~MMFP z8fQ_Clzu>IaG-89`Hl>`<`GGp=EZoQM{ioh(gMa!HWtJTioTp+LaA`Z?@Z9<^m;*MaHDVe~(M+jd=9?-pbAQ&zKWxNOc8)_-*I~pJ=u3md=rlBZpN}xVKCJmLk_#Yw2m*$<~PWlsC^!vR>`+@)hp%^Sna+B6rpCJ45tD06^ zK|LfWO%W#3t=8H+CAhVfenlEe1lpd(-fM&$vU62aZszA7X2%RSUC*mrqMR=_&q*bC6BVljgbWFU9?J{BpRR@6ryE#8<&7 z@oqayzg+>rSUlWB2Aax|N3@d$#7MS4t8A0(u&f{aqt{t2q&y( zt&XmBXs>w=-gM3c(vQpX5!aoxZ2O@8ywk?TK+;nZA+t(>+&h}`P@5m)Z&r)u946M} zV)_lfnJjAZgaq3fsq4LFIL3+gA4d1pW~O)viZhjy++KLh{eQlFhGn1GTw8#EP{V-o zKfQhS_VMkr4`7>Qc0#YTst2E2sy0#US6N9q>N{1zkh%5QH;h{4Zz_K#=iFUTC5zH! zTV!VZ?nyZDT&!gP|p%-k0p?>viWrG4#%W#ay25Lnp=;W7K(8 z5ihOX*oB0oH{=KsMi?K!&<#~%vmyF7=@!~ZDzCE{%54j$qs+NpWTVO9G1v))&@W?c zlh}J=1{b_mp7qZF_mM%P%ox80UMdZNCo1LKFn`j!RYGJw^bx(%_-N~Xn)NF3t+x)3 zd`zrQ6Atf-x4dST42LT2q~2cH^n8>3dHq3c6pnB7b44OH@Y0bc9PfF?mRQEEdUTOS zKJ?v)cdYs{^TlKz&?i4LF8Rp6cw8a+urk4g7&?z1@o6_MbVo#oO&*)lNgE|e9pyUU zB!wa94<+qrNB7mwY@{jePS4dF9O^86%0~Dn2f|z|@s@ zyEbaf{j}v3`Dh4g`hX|s`mfAQGPb-%RB_pb{Oxjf@iJF`2TP~6pj>yJ_qD{H2xm(P zt6p9!x^;eC9|@* zhn9`npH!*sS;&!}>XRG6l9!d6cvrC7fe4ZLMehcWtF3iSeJ_^_{rTXRGIy#MM|T6Y z)XS|@7dx5zxhjYH1DX4in-OUX&Gjwbmt*l1jt_r{LHa`X%dMaTk(LH;OpP9I(ukJp zdc!vvuOqj6T=5+7zC63T&VHIO0DBMLV+9VW7OM zU$WFY{6YNj#19K}8AJ>V@LQRUBi?=2PHek+JWq~ofAJA?FSnLFU77rn71hFymQ~uq zEls^>vxiW)WA1&D~Fx7FfG=FTu?8E++BMXy?dnT5X_{|j~PTc3A@V~Ci@=l+M zpjsJ2gQocv zYlEjnV6FRlA3q9;T(1uB96Y!QTt2uH-5>nDXyq(SrFb~IXuYYusTC1y623kToyJzl zt6i-eJ-vK3YZBat?6@!M@?g@;)1fP)@}1}&^>{XM`oFX24Kv8Rbi*S`ue<0jxdL*}(W#)F&>Lzh z6f}_Z!_4>n)Olg=quk+#<%da9r_E$y?`s0V)_3!Pdc#JbqmjzXmplsoN(tEuO)5XP z^VZua>t5>c#pG{hA@JTv)x|S@U6Z87>2EKd9_AR|Q z$vz!vnD~sgjj8nQ-D_);A+375hI;1@u7l5aq-8utCcG{;yAwFN(thizxVCeFW?rTL zA&|R3L#-FNzuhYBv2|E%y7su(o`+83i16FCJluxN-pRed|2wou(nz4MJIA3>f;>-7 zT7i;m&1_s@NgFeN=`u|noPZVjuBR#@RoAM;6Hk0k31gw z*~?_(+kv}674Q9D`}-d5?sg}+`=OwQ;96Um#tR&qMrWHwO_64gn^n(?qx((}PU(Il zj%}+igV#gj1LjwDiWzICWa7nnQm-$Et-;RDA|g$$m#0Vj%d5dM>))ZCdN8k>m8(6c z0?h=%G~uS3*}oT8dsmZ`ADNpC`%u~i|hx6KB#DC1)$jxmDYo5Z!Y&~oG*93 z!#?ncu6hbK8r5P~LmI)RDyhG?2`&OYZEz1-Ui8y1gr{cnS0Pf)eA=-2EzS11BZGhr zOP49NCwAp(O@53O7y+Tbb{JR*W|{k43pnFK3=RL5B79==Zlw*sQ!*~ah<7oo`QC)# zxFJ7^B~%x$=zW5|j_US7)00j5+?p$p*nRlS`WMCQDx#^+E1q+eSI+1PRpTN%!x^v{ z;!N1RvI+md%rAcPebDb;A3Gby@D@+1sL9rI(0($-!@GCrchzaBQ*zhp5Q0sUbw-;& ziRLTfp1wPz=HGkMs}#@7=V3hw^}j zQD9pb59J`Ddo-b2aJTeK?8d!#*rAOU@D$CmpXU;o4_jiJha;FJuI)L7I@hHMUgo&^ zDM4-tRD)|{qS&=}ZTs$bBkr&jd&hc^KI6BitMFi!Wb$p(JJkocW?UNS+E zgaMa-bwnYH7N`LwyyOL&4@s?PJO8*0_xkzc&xFf z>c+g<`C+}dMY9bDK-F1`LX<4as8%}M67;kh)0(_I%bc3C42Ha_gj5`r+LO3iXu>7R zK9|0Xcd_CQFBP9pF`z^&BrWp%XwvRB%WD2bcM0*UodRKz(F45}NTCe-u5!P~fb!;3 zyIVS%<-iPj^f*laD_#+nC6^X?&4ia(JHOChilRqLcsrOO0GN4)7Dk5O>%LF<91fCQ#myy!>aLX6m%aQm6f!}ZlVmp+{DCM}bN(CZ6a$;j zVU4&QQ0$e{g5O*4Vt<oMd?-<_Zo?r{S+>85nSaxpb!P|hs zQ$Ck&jHu~Cgp{mwR!>Q$Cst40$UeN20Y^m~hKmxTG|Xoh7_ zAJDfQ|L+f+$~TeyE2jio*BPQa?@u;)w zTXA0~lTTTsa9icxjjnug8|70z@%vwNeRWt=-`>4+gS3Fs-69|;T?!-8Juskjceix+ zNH@~mDGdWiNq2X5h`$5hd*9!^@AJHW&3PDR_Bv~=PwcbLnQf+1Zt@*U{kd${#?_!_ z=gB1X>T+wBt00HY`0p5|=ee#IbH({r*NSY=-)>$7j%K?vkiyRJ-`^YngA@kK+LcFy z0v}d5kkmw()>*FBVFJHd=xw0rRN?J5o4oa{#fD2RVPUTd#}6v^_9A52^4ou|GZb}@ z&4Mw*uz(g`VFrE{eTeA4KP`+l!$7AW_@LpW+85zb5!Es&UTa|PC-azbP-g;aNGq}C zOoXeWQq%1tX0p~boxJJSXDQ$!@u1Tb+5H-AZ4*%JDS{EqP0Id zThR17{L`i-zMb}W;oV~Y^Cpchmjo6w77Nqgq%FiY1ufroOs`O8UnV%pH5~WrlWlp1 zZEg=~LPjR3T&v_LpfgemIy&7jkLq%wxn25o@LkDkd~}fu?sCRe z`xY87kufLfaqoaPBkwZ)gvs;~GdGTt!LK@8ptZ$*N z;EH0c1?#s)V>mpOe$u`)7#t11&L~CQ#D66Gni8l~Mr=O}o{6TDUBgp%?&rOWHFwNf z=S}d-@A!V9QCeK8NMHMFmy9^UCce^KJ-0p;7bS>UUkPt%b@%FmmqW?5H8P$TN5TI{ ze~6d8&>G1Mz^cNGuKHax$-5?y(w7(O9gFHSeWgj}BtODkCFK=7RpI;yBUyBGa#L&G zPY&EgcuLk43m8uAC6;`1(!#&qc zkRY_QBeMw0AFCu|zAB&6G$5H`9tfxj!Jns~EQ|^#asQyaR9=&Xqs6iu`f>P5Vsw+L z@K{@6rbm*Hy(TRFO_q$LDcYNlN}89?B}Q5qjk?j7;X%ry)d}+HS?E)mx1tULW=WFA z^53fT3bQpP#C$^!bm}oI9Xe+|-)2e?R?smEU*M^9<>eQQajJBynSI<&H{ig(%W=GyKmf>!l4q;U{d|>|@Wt(X6 z(zXGQMHSdYMKTykP8$Eq#WUsVwswsQ-#H-*>tk)kC6ral4{Z0V$*;#gb( z1raY)n313vG*guT84D@W!piF*C0I8F#OonLSZr@%Y3i~%ZRG}~EX71c**Rtmz0hr= zu_Q~Cj11R1;5`jV`LjAU-Z??je*HzCzch$sSui>Co)=|>R-k}W@ZG+{Erjr)kjLf? z?Z6d$JUA>?Z?{NaKWxQ7YE(E(`#?FOO_DLH%)Xo%K+>rk7*?3(0~*OR)2M4)vHX=o z!EEn8A}D+TuTAA(m6-Ihkxv%A(Vc}#^j~&;@z}Q5X@kHLUs9Mi4AlZ|6d&WniZwtWt9L_!q z&vShCmuK)r-aCC|LL{&+w)Q~d1eTK>{U7;Emg-@f#kiyMsVx0*E*^e+mQ&2DF7xd? zCe4fiQ0+`Qytcl0=H9v%iZ}b{t__d*66K`$$cC%>tbhpAigSQ>m*ZUTp8vLRt*OZB z2iK;Lzpw5y*4UoL){mKYlz|r&2Am=KInfvN+~Z&Rud9j;(L6@q0f zOQ4?^-a&V`reQpKs9J7yDlO@rM25y9x2D_?gu}ayav?hqM-;>A)X8wV;p30>2QeGo zL#J}clW?1cEXjGAiP}r>9EG)bzoC+As+O(3p*n^)vUn&K42hI0Zjbts9 z=q|0tBLCrQ7?C^vC*K=Zi?lY0;=44M_6>hETn~*YVVqgP3vs80CI2ZD)Kwst)3#1C zn~NGYaH)0?Y5n*i;?=USQ!n-=rPp_f);jqpui1-_8C&Y38ZlyTO=3TBkoXZIOM3p^ zHNcm?T|`5GY~V?-Ghp0Y&?CcsOReBtov>ERM?*+5`xyvt#3rFeAWv~(y5s~Bwle`) z>Lu-r{u`G;Uw50|-sS(`NKcM*XH8#QDjg1NS+{GxL9!r^8m?2)Cp%!+QRhdwS))B| z@sBA#t0#*x{gpWh!1%r{9y3OVfOMl9J8rNw%D8p+CJy+an{YSakaUac^y;r0 zFV{KfqmS4K*2PVA5-64)x#+ivx#xPZ;$Gh0H=M1o{)i!0E!v<*%(ErfhpR@RzRN=Z zgH3r|P0AQBNNZHj#*AVVM~;oX3@@sswyqO!tuwQL8uD?yk{Ib`-Z0RD@iZ9ILg=&t z(_)#cT91Q-)XGyd8D-tB-@SI!6E8B}E~+i%Nf8{4MvWxPM_4;AEWHI9k{^ik3>NYO1SUKiXe|NUw1iv4$1NZSHpXhB4*?SG0sWb<4 z2vY2lU)5&vF=W-;@G+nnHW*tN_dVAV+Q0!uzyp?$Q~SY;YPQInExy|XU2o5iaX79w$JL2ENwwCcMb#A{L3+dfx{SeB#$$BjC+GZrPvFeZ0 zP2y@7#CJ=jG2zuYs1>%@BUAs3PrUFm=H?wpaeI^d*R~dNw#Ww!k27O}?bc~;r5%+V zP`S5`)faCW3j%f_lj@>e^M_S@^T=+m z`rA-sUU^j`L!j=6FgC=`qPR@&HZ~Lw$9S7<$sQ?h3jC;5$r!#^GY3I=r7WRDLC*@F zW((@1g(V_Tft8gp7QmjnNE7`%-vb}=Q}^`#T)VEcrnhUnA8?+;7LK-4@1^1AC>?J7 zb7`veKK{*I>-2tUTAezq^F4 z?R-1 zTtO!J@>n&qo=Y`lrDw2=_dHh9WE*x6;7oqjlmF}Rr!f5D7~!n!2;w>xNX0d4+k1<> zm!IO=tbK@V8h1!#jT6{pt*3NsDE&Pb{Z<9Brm@&(#!D_#mHh*2@%fPNtgmeHk$SkZ z&@2MPgT_AjD!pE9_YGgB?(!>hWIe`Wfuk&UNTFTdiBBXkhwlibX%_M&k;NMocfZe! zJP!P_M&VMKS&x~v+`E6EjEbz~wR1y%Jo>z6+D`gsmT6^pExIAYO|E*O`(G6J^+DA| zTu#5g$9)Z7&zB4L)i9{`huNWO7?xF?yyp|EoE;Bv1G^|`;{sE)Et=MP!WQH@Y}W}d zSDy{n;KV` zo3zL|0X@HEN-ZpH1LL5dulUZ*qt?cH=9dwPO{J&1y3`m?FI5Z%D&wUc9ML=1wiTV4 z4?7c`hU5#7HJu1(_2e|8@gfh?GZ47N8?oIn4-?g)5BEe6r1|fBJ!3WPaZY%vhX23GZF0dcr=jMhdV*$RInN98+1dxso}4#b)Fk*<{)0b+vWuBt_;)8e}f z?Zw6BUi#tEj$AjI#=`KEVu7{ih^I?L!=Lvr&{1}=86w~Auz7XM{eJa%kjCLP&W9p& z9J8G&FwUWjIXO|2Jr@!o`6lmsb8(kxlWQEx2{|n|cUQ(%kkQ8)3xPqWosmtSz?+9g z^X!cuA@OgV>toW<(_#|RP1T(cW>eRSKl&usnHWVJiLI>EvoJ)8II9n>D7t1*sY|bX zN#4ExvH8OnG@^!(P}9?yZ~(M1IDz~DbXU#mjRxc|1Oz^v9LsO5_?&PGNX7?#eVZ0I z@clkhQy?WpeqV*WcE3mfJkKof^1Y(-3-ZdL&U}(Jy~R%(dX_oIoa9ue)AsR`>>e4l66$sAU`iDfGeHna7;xnJq^hj7?j?fi2t)_M%f7?fN^jTFH#?#R33-vPB@ z(IWRb&Q0PkIF}I5jp6I(op6yEYDR`;oaGvnoa7q3-wEu2-jFa52oTauv7P-~9kP!TK$B$Tm2N!A+BWoP=*wa z1$vBc9CD{_X7y-YA;y56TI8ZCNCuAVb*mu5A^z z29VZ3eeZsp8tnI+8IZ)DQcS;Ca*4$cX@Nl#JmNV*wfs50en5wG_?6$_@qBgfPcCrp z4<~5tqLFAVzR}zm=q7-qeQ6!63$`6FSs8frhI`_ZHw@A+LS$Xr&Us@vBFg0 znpyI7%-gn%Aq2?jT3RrIz<}`+6Rg=kr8E;pPwL4=FHMXj(Y^6{svTyXsBZ9f$B(k^ ze;O@`88Ig=jgy&47<}Iq$lb(3BGzg_C7$1uDo;HZ-vCv-dMA9*0qxJ@!og|ld(>+Y%5VmP?;7{W-d4ggXoaL5vV``kS9Yu{dD@HzK7L zYaq{7Yzy-17>1YB*vF~C6}HF_RmD4aGLr(2-c~Y&F*tyYmvlLP2(1`^c9lK?@GfoD z1Oi+IrT^oLV&ebh3tHShxt3#t%9(VIDhY{&FUv>vDj%x9xTDDdY%sog43M0A6kcRV z&*Ycla~oil;FY;xP%?7Vc=KOo2#{(a^bVMFsL$!^hoC?P0e%0F^S{Um`$8IZ$>RHm z(*YNsKIZ*400Bk8YV#Z0#EEUL6Q<=LUi%Wflk; zzuCkW=#W#yS6X^iopf;=II)#qyO`cfrB%{AhK(?P2rrI%|F}IainGvxI{!BgmYZt5 z4l|>)Nb$E>%CCNf5b%L>xnDie6A~c+zXAf8(7e&OyChX0$$KYPKvKDaXWv>~3>2Wp z3m)+tlDpyezcC>6$$xIRK>Vz&Vehc3l5Ac8`IH05ryK*{^77#yiI@ed*4u<_OZMMz?|@O;1t9qu!mxh^Q+70t&C zqV7Hu)g25(PM;7EIo(2!kz=Ei{5a)+K?9{d-mG@Lp^@{5HJiJR`O%vB7&+^XU2ya- z8iC?+&BbU}Ou6mA&-c91S=f;V=8RCzM}@RVn>Mw{9M7HbbTA>xiSD=Ab7__^j11jB3eS-(onJ1S3bp`~~89JcO7yxw!A~hQN z$1{;mD1zh6B5OY8x74E8p%UCaaqFj8iF5huF$}l)S!p1Q{!dmug`8~!x0IcA&CA6E zXCCMB(JA~ZpXf)C+8`H18%4otEZqC$q;now`DF87ti0H9;7{QoUI@bb0LS`S+9x|Q zjvJ<8>P~_$bz|BNO&FuUln~!5fI$NaekqOdfqj2LfszY-D!Gsl33=cmM(ZcuyEB6X z+iAN@81zS2=kjBH*`R#%2vBp~AIV^Ct==zk*O+H^PgG`&;aH)Xa}Q2>-MT)c+`2A> z4q3&ehD^GboEi|cOuPR#7b^p-h-b)pF+t=&KJI3`RS)9)NU>+Jex*)*ghrm+29YX= zy^`MFvp)&j-}@(MzS;3Z(q`RVOwV#ZRwNWqA2HxQP6=;LIhiJ&5$RMW# zX4NjsptLXHd?RNs%_#LRP7kb94l58$Cf2;vI`oBel}hfLrW$7)!WY{0dY}YF7{_hwE&uP)W>{>$f7uO zS*4Z}GNS~zn@^}W0XF+a3i7rAWN~#P0yYv9jN0(vyq+Qrbb^*()&aLK99f)M{ly9d zgv%TS@gJ+dgnfr4j)+mDXx+)gWG?>ViVI}6%3i(Jeabc3II#xCT^a#WX$Fi_wG}MG zToTDBjvE>QK?s6!ZwSn`%J(GFsMtnFP+ch#j8SRD*FUbz;Tn;Kd>!ErSH$ucWo*(s zP0^8~`n|VrNzC@Rr8 zNS~Zb2}i{ihos-n_A)V|C_op_L^xT@CRKX^Q6j!r=z>5Z{-uP4bdYA{a}$%GLh`8@ z2WEU+ZzQIm<$#_xzDtZIDWiJ0FKRp_xR`OOS`l66<`V6U9vfIvr!^{hG}LF_ZV9bt zVoovI!5J)kszmCO$$Jt~)OF}Y`P)0X>v|SD9?!s#9rfbp!^QXp8!ZXOTcD}hjf02oIr5JFEBFYew zkx%O_xByo6EE;23)RiEE%P$KR%WmU4sy*%fBBpmv=nY6oXF@kzN-e&srI`frUhOw7Cq9{k=g}l)f>ZKkbY!HWW)iVj z7nC2w=pwWgYN@s*^rm7g8L`D?CS>^H-hH)EkmJ`U1zfU;47g-^;@>X$I(6TL|0yjb zW-mcQk8Ut^Pyn&6_QBx$7P&7na?|R*xNh#ttd%e3zxeT&B-TbrDrDARDLzuIO}k7% zx?%5{Or?Xy!bhfSk^%sB_GjaQ`i2gr9aR)@Cj?8Y_LO<4pJ5oP3BJO8LFhPfip$?e z=%|8^*C6z~X_q9}R{?m74)=wPV~ri2kBy-k9aA)hTbwpoC0@-)pzf56X4c{_P+TBv zpIN3hOCM-on#k!nMuF#;NL_TYz;ivN0vxy&2?lc9kQL(3=MqR(=;JA?(lHt={%BO~_PO@)m!~!cVCsf0&3gYN=?V#Sy|5d69 z%i?bADV@lXtfw-X%Bz;dR*T&)q-8I30~<{h%u7Ba8Z31^rRHSbFErq=jbhm^%;T{2 zpmdx#BSy*w-h!v$Tm`79jdEVB?-g{;s+D^aP1jIj~DIYM>&i+ZCE)vOZjt7x9IAvW3r6dvY^i8+1uBAk4YeoKdxMZGmkib~iYn$fK z*W|r>JLP9y*Io|N@}!aNg8`ouUltB4IS6!~v;NUul+zGa3TWu9Ux;sN-%f784FcOO z*nj-0>>w`z->g%<-};JiaBfnvK^xYgyTop&BXy#eK5z^|v&a0Jmbs)Y_?M!N(BG{X zigzWs#3r9ms{0{io{M2)r=#<^Acp$&1|{i_-@RfRhHDQa%E8^MlaoX7WG39G(BFr0 zTjL1*)bWo>~3@~co2)ql*-?swWEv4Z*jc+v~?eG0g^rSz{(G~~$JoyNkl@0QA|1E!5Jha$pctE6YP z&kxTSoLJQ7t3MZEK#iR6cMp)B%UL?nup2$iQQ5t*W4la!V%6E4@ruB6wa-?ii;d69 zpRL|yu?M4oCttA?r4vuy1ku8n2(|0Hl#|NcUfW~D^)pXLQxj7wu@_B;p9WJIR*9`~ zepcvSs2Bdl6w=&eX(?%=;*SN@w+S&QvkNg;SPq9VVa*hMK0OFkw z<`#GSCj4;SQm)PNi-Hu_O_18PzmOc)?LGA=rfxD*UqGiIacFNcK0~RGTEN5i^uq@A z??2osqe!rdsFcQcdMrEsREX2JH738rITcb;sO+TU)+eWr1k%%M&0_(nhFUiLQvs=J z7tF*}6uEu4sofrOL;t}L^(kRy*^;IgO-M3^1p6POF%m_E$Ndcg^QMqOD=~4_%A-sI z8JRr77k6L7xa)l5m`jiXOQK9>>KgGa)xW(p?KA(Vo8$NCmn)@^K9wD(m?3Z?hTnt* z^s&ufzu%@B-+O)$#Xn6I%iuH1EqeKaqU%N8RF~q2snHA{aIZ?vzcNQo9t5y-HVN*gKdmgDcF3nD~08f{S=9tsh&YhbY zyub)*|L%+&-np9e>O;;p=VcZO-uQe7ZDBqxdw+;of=AK&l>i>+?4Ftci8nIfwcm)9 z97I!6G^LWDH>Et+oolmwtF!sNJY~w#klT% zxdHbtn8*N38@5ek(Y5k=!(QA1tk9NipDyk?>fl1bZ=lN6B!i{h&-Hp(i}^MsD>p1Q z;Y#?Zmg-=w7dC8~Nj4?z6y#Gxtfg${^_w+sUBOz@HsMAJGu)!8Jv_36eruYNBwgC| z!R*&}$Ax#t>&8!Z?y2e2*FUE4ui^?a((kLW06wChG4vI@hPEAyB1ZDN{Aw}8jL;-1 zlAw^+c!EtHIRMBEFFz?M226+JO?^>C=Ee>+b9@<1oi-gx{_&F?OAN3t0}nq!tI#>q z>v>;QCtn9Zez2MI!xO2BC`3~UQsB@8L$KL#U~dgws2NDG)Meru`BZ`k#|3b8ZCz3-9#@FUJ6{~tr&Rux#M$`Qn3M$30x zqS`)!J7%*_X`J#^J=b)cFq%&mF2q2TdATLW#+bJlPV?vxWYLL54g)>EcbzAl$)VQ@ zZ&W)1^$t057YMBucSGI+4JelW7Z&#v2_(A5H zJTB*;#z6yTocEggK?JQQyi>KJiB`?ILkMv<=>B{^y})7dcc##VZ~6DNFA516)9o>u z2POe5x)FIEb;g+J8}&!Em|~g555+<6zRIh5Di@QGU5|R5DP1j)w%oC(Wtv|I9)uuo z+;^R|YAM*V$?(daDT_3mRzce^=;O|;Z}!R=XF_6Lv1iH)4YIeT7vJxRN zUa}t>D$ht^2pYws2y4~Hm_Gy0AsQ^+`|{$*Z=zs42i85qfVDnYe7eiL-I(Ww2DuZ6 z_V~=OTHmhe)B6xH20WPVvR4!PH+jaQw&RRnFXH0OU+{cI5Z;aCSuUvfSv#o0sMRxG znlDfEJ_MLX$#3!|=eaOvfNyL%m%ft0-0M1I9Wz7{A6J?DPxUT2SWh1O>6Y4}%;qu% zuQ*0F;a~z={5IZJExHg72dL{acc_XYu*Kqdlgg#FM~$YlL&{mbrgF!Q9%0&m+5x7M~^-ng5UinlX9 z@CJ_y0|c-@g;n+nJg5Hn`i5F87&sV|jKX+^IPe?plEt7n1z`i$>wc9|ZFMt{sYNXs z^ER9A*+xzWRw|=>1ob=@s(Y6I-ukFgM>~Si-Zo*mvCaSt9%);scZfuw6Ob{5QxO@$;3CH@wIAR>*%Gu-Lo3 zD-BA;W*#SN{*`=JT*JU=Q-zu*{eXwf!X0gE&j_sx;;0F^1&d!lP6z;FND(x2#dOgT zOK#5cGTJH7S{!B$F8$yLM!1i5dB!%1{1Elaj9;PXEaDV@}5)F$-$bV&Bjh_!4unfjQ zursVi%t+z(&csK8DZr~EXUg+>!6{-pTzVE>R{&v>k0SMtDq7knbtbcfgs@fTasd?d zIREPslQeWjv))x|#<>q`n=9yX-Fg!LfjrD{=*P&lE&hvI@&tDXP> zmf%vv^1v(GlqIH-A{nK<8PVYG_b&mkPbJ@t#A5>rgvW0k5NoZb zZH-!~#WyZBw^1NEzz32qpZ{>|nbjbTMr%gL6E^VU2cW-Y`%|YE{QgzQocpdy1 zk@b{A(dH#R!D}znG3;r?F3}41k*Hp$MoRci`!$4*lY;V=cVYJfPO<9{5c^+X20gub$}uaTn>^4K zgs?jJQ~f>0oDw`ITSFIK!Za8TxlLmaxNo+vPLx`&k0(>kL!tpr|aT^YML0eg_U zZX^d*vmC=}u66mYmTeE&irc(*YssylbgBDB~7Q;GK-o0f6YM1VGH=$8cVZRMN3FCemYmW}}h(DXvbC zN3MlTUW2#pXiVS>7%oT4$ud>ek;ZP%<_JpKRR7Fe}D0jAEW=<+(^jG zCQ*vAG%=sK&s^nHyM+cIiSPSQa`2Yy&zpY5=6Js!+MR8VUrrkdQ^7Xxud4UfqHTE+ zrQPGj=rnq0k1CiOaOuw>$*TqyiuhTPX>UN1SBKPL+$0j`6*b;~&+%|G=p<`Y`5Ee9Ig$q485T=A^!`llVz zXp!bkRF6;&(Fip*nu7#FG3pzP%~>9=t@z$?a#a#0M3>Zuu};5*n(B6oB6)aDT1(3KsM%MThhurYs?4L(y=bwFACn}X3BXH8%FedX<-cq z8)?H{efqP}0+kX9DyP!c7j5^MV&>eWf4FLvA%>s1bIkB=DG9aRsN%@Be|^R!gK`HB zz|moBa`?rzpZ&-0dF51G6pQm$eVIN_$x!c*ass@@XyFN8$;>QHY%Qatwy3-ZK0*@L zk8|_r4~6EqFKhGrDyItiDlLzta;Y;z22YCQqva)eB{ifa@hkflCnY!GFbL7Ka~@l1 z8Ogv=$@iYIfpCPSIJHT#ma}4f*mAkQ<$%tIy2lAjh$U6r zpi)+b7AjpbeW}EipJHWQZj8%MUrVZZg2(V5^>|URjt-(z12ZR@&5aD@##FmVyj3%J zj^oOn5LR7Grhb>4g! znlc?NI0hKJb>@{P$XjWhrtiwqr$JNLmEMlP;sl1%12MtTjJ?WC|O%bMG7 z0U~WdOfm6?glJuqGOsMy=TJ{fk^kDRuVco_zW46!lL!S*B8;>Mh2@Mn#nQ&Juon#0 zSZr^`$jl04C9}K*j7v$UeOU93ccPxBVCg}xC z;Ke5U$Hty4OJ;7qBbM3C4^%l~F|)T_TTIqGI+DsD;ya}DPZNu;mgOd<#6O(`6VR3V zclzBH3d^$%=ZR-2{b&57r}06L}6(6gz9B1u=D|$BdtK$JqhnAyO@E zCC@n{ z$p1aK@xj0gJ-IcnU`ojp1kqIQ-2Dad{J!=@a0p58;>VnLTW({sBa3WZ#MD7 zz3~LHY*B510pEBbmYF8vc8?~{wv_1GvBGYf7mczdn!AzNb0dX7!A(=GOg3el<$@-VwTcr^SdWRm@H{1g#X#Jmk_vT;p>9(k5iEj>rIJ55 z+f|SP#DA$#e~+_>|D{G0zoT}My! zleD}QyN#@+iJJduJIs!y{GGmMATENF9aD{@J0|m<0OSJzN}d3i{u_V-06^7zXyP9L zB~Jiq9s!vC1HiOKR0#k;_3O83Clj0ROvr@kNI1Mzj%w%{r}JE!=+5bzZOPtP6H7Q5 zmGpKxjpN#Vpb30i3}m52JzqR$JDXXDG&-b36P=?Ph|Bk=BCJ|4o7@__6_pzPV;xxW zc+oIR8rnSxE(JP{<)IDJY8St^&>~zMDR#BcnyO{N&wUdaI1 zgrZ!%ATSmyEKynSCAyWd!B3`(UZO4e;?;iMx6g8UfS>E-z{vBcdf$2l#GrE^n#}Uh zgvpdk0)g`nmlopYUbL23yvEhnQWTz~V}ZqDlcz?u63A7kruDT25VHL3SP|f(<{?NX(6lTD z=nV1JJVY#F3Fu!8I&U6W%0qqE4^si zbH;nKr{4VNLI2zUOp1h^ZT7ysu{P~*wL@A_a)-CEm+0Kxhdz8f9Xw*b{$7|VfjqXu z(&MvxPJdZ`R-KVx+_yDS90CuJxBOjE;EH0!As%fPMyeW(Bhs<7Z11~T+W4i$-rN~vAXbbPE?L9YXDUvyISTswJDr7ww5KChz|2q296VsS^IIje6@9C>)k&@2(jGV0_zME>BpVL&w{;P7 zX?0Lj2jJj6XtPdlLdBzxWT}JZPJL-&z+0#8Cm;McT=Z*SYP{ ziNaReF)-dYFs+zzlvEmwbfdylTO?d=Up)BL+N7{#8`0!tIzP47{Y}R`k2oDArjk6t z3HW6bG|Ob@$BzQj%)_8pdC`AykM4>@mZO$PUzQc&6V`~~6F^Os&?mCdf@?|!@D|ZNXzF_K`aar0`f*X9fmqI}@XPXjC6>Q(9TPCt77hs;L*^nFd z#LJUR4l<#62d`z0zlRQsEw^nh7dM9!O?71yp3QE~cMoR_mRrNyp3WsLCqj33j(1l^ zIiXkSUJo~CZZ(m3JmGalI|B=yy*LxC?&+v6trJgvB|(YzMh$X}^dQ)l;v5KqA38ls zO2iD7)^QRyFv_Oq7$0kr=ZfIqVh?_EU4`)GT)M5p8nI66-{9ISi1SSa9`rX7x=)ch z{}IN~l@i3cP0h2{KlvGjo#g#}8j&l(4?%f7^sZ5v`5@kH467HB9}a+@ z+(Y7lTO|FOL3h*#+OulLM`JFRK~6iRIpotB+n!eg|tZW^jC9JZcT`#g+%6#PS%&*NPT4bao7>Tu=u z?M-6%dmW64+<(p2u5S=e!FomaO_VECz@<+B6Gjtcwo_E-Yqq1Qq7H&gvD7D&I{4R| zt2nIG*q5*r=a%KOXn>{)J2YJj3q@WvC|4$wsyx20^6&QxS+qfKm@Se+2=C??(1DLL z{QU6U#Wd4l;+>xs#UvFSkI_vE#Zop|Ob1fsu7rAEIY&LEYHr6nKM>X=mBF+KrI*Pq z9fpnyR3or2HXjr^c2avBRhv9-K~>b;?SM*b%L0=ZRA=rlYGUj5Nc{PE(DKu(JkM8n zUr_c(xfY==XXbxaW#^#$P!EzCd5wX$Jq!LJ(?0$o>+Xw?d}9jdOhu1Tgc*%|O304b z#?^a__@zL9^om^j1v+5{s3->E16&|Ryds1RgP2)}v2(6xWN&Ok`=d*l(!SURuO4aI z4ky+?s&M~8B?B?@17jTII(@ ziI8IQH+cRLZQ1<|A|4)XyrALo!)q$7{B@);Nl{kn)TRs-MQV-w9G<~yGFygs14|?4w}GZoy3`JZ))<>nm5g;*_Nd7)qsUXl_q(>eSoHRsHw_%vMvj2@eBhO?7(Q{}}O zEtNQ5FTWEn67_rZVW^Kw`R-FgrS}(Bn?{nk# zHi55ZbzqdUzZS^H9JPqX94RbzEY^xrYu%EsW_!ji=ei)Sd21YOPC^o(fwY_hA*oO{ zh;b9ns&3NqR|c6)QKTD6Zc~yUOWDi$=P!b?i#XXPCi70~%Q7{S-sez5joI>G$2WLA z!j+cULYNYu1&)}#TD?JKR|14!H%(fl*dIuFNl4P}B%L|9!V;?{m|+_CS7sR}1igwT zS0M<;q1df_A4^nQdm}PDBkeN0%lsFxAg^QygNC3l^H=7aP?X*0-!ZNM2Y&AH5$kdU zpqqMd-bSnuMwh#qYT$)?O(WxWQ>~NwxY}N5Rx8UM$ljx-m2tnRu=UfNT2bg~Yr}3< zlK+6gZL6j>!L_!AcGgMJg=F+n{6%hDI&QJjgD>hvD8>3cPuD_sN}F>8Gt=SpNBVAL z1qPKElvO(3Aen-gW;J%x-1_;CtSZQOJ%#N?A*bMC9ho%gaS>_A!IBIYoki7+2zR&R zv6;W6e3Vkn-4mzi`@3N%po}e+`=M}A|FLuWvY$ymRjuXsC8Mldn~?OugANeL0IDi9RyIoHD(?XsI|Hh!A%yA56y)ss6#0>NLM$o~U z$3Ie2&>f(>)ziY-o-Us=&5-gfp||FtY}ZZ3`h9`fiY3o-6DzKKIRbv5zYqjlj~r4htgi6f8xO?Mb<>!{t8clEb&4kkC)$_EaQ+VSkC5oYs(}t zD;R6Uid01?1=&F8G%d(oONx`=Ht2oEdGypEm6OOmjn%C9q4(ksq5AvaFWr&N^(&?s z0#;dD%sC*kXajLzKV9`pnqi?*WEt_F4WS7>I686Wx2Hb2!Zoe=e;Q6r=ugu%A;15E zRUq_mg%grkBVY%G`t}Vj68RGLUGLIj%dM$U&5VC*hW(FbqJM1#pSwl)X2b}L%$1AA zAwFqF0BBZ7$s1Ie@sDP<2G8Huj#0YM%O28r)OfKtL{$%MB6!G`p?{rs=J_e!&FB}^ zc02nPFY{gDy(#5Cd_5 zDPBh&>*PJkw4FW5g!dGjtp;+X$nIUvTCK&%?h+>Bh+fcGeR3_V=4t%vHgEX93|+S> zeb*f%+dReiF8fpYCtu*y;PKwJCS~~l38QY? zd9+AweGwauKuG5(;FsOJ|G5d;{ao;Kqv5wV%+6Ey^j}4XJFSJ3h(j(b#`dx1C^?(N z^@k(2s=-s)ep+$?8{bAW_k$K0-F8t=*B6%B&J6<+s7@cgd;m_>d>!9uTJJCy6Ytv2 zDWG{F!9V%>LGedjc$wqup~a#Z8EDSRZfN|C$I!U#7Kg9NOl?aY^$)zo)-E!-$1j}fmYhxHq%#By zj)M2Oz+V*+EIdhgpMOJ!xw9J>Hwgs8x^hD|hdK{PK<(UvX=H7iZ}lIN*Y*zS zT0W&}ycOq@^ZT?l{1!>`XY`-zg@kb-8`awG$g>a3|A!)6#Sx}QJ3Ck=z$|EPXLaxM z9O&el1s#4?D`^*p!jE?!Y1HwTNOen?s>EEkTF#?Bccp+fGsIa3Kv-B9K}5V1$1Cpr z?C@vVBPqu&fw-t{Q6)6Kb7%n$CV>ML2fcsP32DT8(#r$rwC5U>#pcXZd}<*ogn0)* z_yFp#fb9f zFnoKVxw&!J{-DdDb-8ZY#PU}LHZJ|F5&O0c-NI?`zQ)A2ElP!pBllp*{qAG~%5TCk zv&}V$@?{IhBdC_A{=E+9H7hM}ZG+WEkA5p3N~5k&(d5 z*l=JrS|a)z?0GX#&>&Fe_ubAiV*|%O;VSE4$~Ue#c|gb&RBqo)r^RL2BNdps#K@5p zRHqN>WN0=YB6`e7Dl%N?{Z){_ zaP!E0nv-2ozMY(Sb@c}G?EH8D9f5%*9i^USLkRm-wcab|@6WR4@6lvcTOQoJX6I6^ z3QKk)53Efnf_C)_956>bKZV^8bI>O;xZL!IibrC82$>5q&T%#kd!aaZs3bGk5b_+_ zvukVZ;UN{|$g7LW!(x>HJ|B$Z}FKsp2wlrB-iAw)_Tx{(HvlJ0I8W}b5fP`UnI z_x-&0@A>e4xIgGH=ecL^wU2eIW39Dk81M~Osk$ZRfp00Z?cuGC6{4xlrjqw-d6C|< z{VqXG(l3Tj%1_?vXA+(1J>h~fXH>k2)MGQ#`Xg`a8~E%H=!~Rxl9sriz~D9G!(vxZ zImr%$n7(#YKhR!2U$T@zkJhH~C2ehM$jw@|A%Y1Ej(6yM9BpMJTKl9!&= zbAYMGoXKvL@%pVTHT|Frhc}NBZ|e8fn|Ldkc(!Y(@Wn{yqcrhKgF=R%?7cnqw=WT0 z$Mxo6aC!SC&S+jM+IenJbqDj<>c=XSY?Es1uD=VhPji4w<^nV<=hFj4b-TRJW51X8SgA}p-CWefB-A2fSA(w08!6hi zOx|y+Ww=`aIU0X5+=1(bDL4GB$}aiGxJ*n|2Q`O-Yba54!Qg%4`(1JTw8xH&`Y(he zY*)I~G~~+XRd}ry(&J+}o_p$4U^yBn5KFwpEv3Jz)$pbGo)Li?qD5g3dg7$9>|4hC zYy-Hw+`{k*!aVSXL!K6-kqbx_vnCgZ0l{(GAoY0VHxda3ayDP4XVYoV1F>xhl>7;v zZ*<$K3qM())2iQn=k6_s5`sSSfX(^7m9}tbXiee8czKKW!?XysS~?!6o@wh|dN||8 zfJyQVTmDTktB$)0+`7j6K40vW`||nn(Qj->7#`Vtm3WN%Y=mD zn&CEWx*KO3X5u0VF&hW#Ep?Y2lgVu6ksdLvRATJGomw`0XG$vvdksqOTPaJ*AN8!Q_A44MjA5r`>zZ0X0MJ&M0x+L9hlYZ-b#Ae z?9it1`fC=p{C>&!%TQ(dUg)jG(cYI&e;Qws}6GUFTN@AB3JHE2F=@{ z3~=5%;&hlb`Wk1Jw3t(<{79JVt_}`K!M8{%`8PmNL<2!F4Fm-l5EQ{cPzWM|f`Z-1 z7AybSg#AJGmjcOs-dM0mT$>gN=)kHiiM|%Lsi9YeXAC;X20Y*iBnyUGu!t9Iw@pdl z+8a+v|AonZDTA-NthQtk8}2LFpIToTmpN-_3}DmaD=V)kZy3wrP&nJ*$UauRC&)8? z;NKfg0+I34_f)(rM ztcTS^A4b7x-OTu$14(&-pYKz|s;HO8`skNiuyExOH0{vSp{*~hs-hRK!pHm5$C-+s z6v3>AlQrqoZ665j&1-PZ_TNPhmRroJdV*QNo8G`}?WPq)nwi+Gr|AOjh`;{GeCXLn z?#y8Zy$xGSQ^isZjJ8sbHG)>``{LgyKk?g|6*;ZiH+=k3kZ{DSl^_zwqDTU2uxv}3 z9)Sg`=~dZ30X2NI6vun7q@RcCx4M}6ACui8@wtay$0<;Y=SZM)l z&7IWL$2$j8U6DC5jd~l*ghQ6xMGkG9Qm=L zj?J2spg9!`PjWo79*QQN=Xh2$gNb?=GHP?}>rIDA@wbF1A&U0TeOU3ZLKMpfY*k1~ zW2m29V=C7hedC@JubmQ?Z&nxJoE;Q~p{J(y`4!b=tPGAhm^fcAy7G;Ncx^N#Y1eo? z&7jwDPhNiqihh$62lcAR)Z?6*E0%aU0+SZ=J(I($^jHXFEoSmoxr z*$^LIrF8X>dD>mI+J(BT-ab^njmnWtz|mj+@sHOl%WV4M>9(wnqq79>(3~(jCOJ}p zZl!sKBeh@#)A2z5vBI?%&JSrFy@U0A$#1n0`jM!zJ7ZvTWLUDox3`jKcq%Nf_I2F3 zo3_Mor~mpm`NH>jV8W%XWo$!fOHb4rX-XudWs{jv{VKr(`&6wn7=rt8#rLV2oYU*Q z-#@@B^Hhg|&G0Oz-<5wrrHR$uAenaWLDyY@L0KL!rt(&2~ z)vh-?T|O`dY|C0ca#IuL8x#ZC*FIqLATaRE_0+3M35kfYdxuxmL=h5WrXJtt?4NynyBRnlzfEgP3dR-| zf39~<&v^NkSIl{%#sd;1meFm_oFpPnvcvN!rA;k>Jxkb7ow474-tos2dlrR(xa>G@ zo?y9OWYv$xv^HDuLy@@1su0|T;X=mlhJfwj8O-wi$g1}kPvmwp%?uBVOB7}cx$oQ~ z86&IV71x)k%N*#mA1+5Wnrbo9G7L1j=P`FO_#O?2;O6URqEHm&$Ou zRi1$e4a5O(T1W)vz6Lp?*PJEuGKV-x@sf7e%v*`rEvoW9xu-Pc342{L2>@7kzrWXz zA+g&s942+vS$%TNJ%8V_0F8v&BY#fmQYfy-JO!cOMmL%*%gB#~ws#&_rmf%FE||Iw zGd#px4rF}HKsuFZp&Wf=1(hb%4I?^Bs?FV>`Si8#g7S*KXQY5AdhBp#B3j&?l z8{*D@qX}K8OH)h%oAeCwSTZ_dzPMf-p!IOJrl$QEr@j3FRlaojc-`A0LJRjq+b#Z^ zl_7F#52EVc4NJP{t}3`@^#`~t9yn=FQGRvAxjL|aLFo$-OynnEoOP>V%LQxK^m@~d z`^HI{JDHH`%eGzf^|pn%JYCV+DF$YRDizI{BDki$2Dl4i)nw(HxTX&P`v#Hry*snd zICsOC6W!XAz_>&GHIpBY)nHh`OK<6lS0i66qHy({qR}39L<{G-aaF&=yPM9JUhpnX zQak;sU~bui3t=zP9-fC~^%FnZ3VxHu=*7UH~YrN2jtD0<# z7eiZuI!kj0coPf5c5q%YiIvCkrS`qtS0AqTU*33^b?`&Z9WVdo>aAMsXcF1Er@#@v ze8EjN&QYe1#_u1HT0`He*ODbmYI76aK`{>d5yzt4E27$B@%)QUw8?`+eUeYfNvp;k zy%z`k)INGWyOoPEry3RmpqQXwu-e|;*H8Um2f^lq!r_i zBEU9ZQKW4$piqQu6fm9D_J!pBWY_}2wg@;s!nOnI;j1OJw1(WNZi;RXhLo;9#I}16 ztj&Ed=WtQ^;R{{|XIiBs?M0y3`_>a?vp*410;mIiA4e z64z0|7{*Wy(ZQ=Ls2f((oea7zeKVsok!qu9;w?}rBDpMnCi=wor$MwFS`VUWx3Hrx zsddzLU3=Z-HS!r(m1m(^vmm_3Fh9%d1;KJEBi}%8d&kXupQ4eK#hq2u^{JQ!I}Zs$ zs4L5lS`|4Q?878(9pBi-^*mYKGa)AeO={CE{7Q3Q3x#(N?R97d@aBd8 z1Y=<2QK`zhlm5%)r_I}v2{>*_fp_`h@u16X{!W$lU=6Rl&BKR>x>FlhCCx%j1x_5FB5$)i5l`P>rH&S+qdkyY@sFe_1?yMxmUcZ5o@cU<h+|+ZYN((P;Sq66@%kD^h5MvAWqxuB)9N+Fg5;E2yqXAnnBU6-zaD3BZ8q0X z6KT~_Fw!dRW!;I)2A-oE(BK|9zmqn9=}3*O*<^t_Xa=*M>BUUk98;I$gj)HQL*|_BNnkQs5!)L z?qg(|MVn0oNLbMV_1t8Z`%o*n)+HiH)4q2+L2E6 z*Uf!=B(`tqn*rLnDo3C@budMz*J=1(L8*S_czN-4)}w1bj)sVsIZ!ekbBgPfWZef} zrRY}jAvm6)ZWyY1K=`_q4TR(U)mO{em#CNJhlJfmQqq;oLQARrb%wIow9X|yYSfD$ zeiF$ef$prl=pH7!XCgCnI?X;ghC!p2H&MnGE&JzftVn<_*N72g=fa8R=eyF&$2qIm z&ga`n@#Y2FdRN83O}0b{NA!#1mC7>FWL}L zq2yJy$j38B6Wvtd5p-wFZfxARs~;A=5|mw_B7&=xP6xUv+79E`n~B#N&&GS+tQ3eD z9GWCLh%XK==y2GOh@Sl*n+E@xH8mM}b43MT241kTu^}71`=L1l-n{EqnhE@N>gC>? zcj+c-w4yXsmOT_i3)|Gg6x3)umJz{$hY_~8!Lhnlo|a=oUAv{Ah>TW$cCbnJw4VCEVF$iO~eIapn}QlzqNX7*v5>bA!~gkYi%v>Lsu**+G15xrCNI8G#a)a7;{Vb~8k z&h!m#m=M(R3xCi4^`F~pU+zp}%yhhZ_9~wD{h;Nv<+dPO^dAYFo4fAv2GQ3-#Nb2aY1Ul6;3VrTpDZa!y9D(!?~+AUAxWQ7EOdSJh`s$P1kjtj7jjXl$FM z->V*5xK|(#p-^8+l8yB!yiKb5cy<6~a2eH;>85YF%OX*^{$)E|S{@djYqmN!-@Dck z~^G;Os8s$s9jA3qEc|~5(XCK*HkMC8DM%(fU z$2%A~7Mg22I$CKvekphun=o0+CLqAWD$v9}5*2OW$1wNZU(ay>%_lj0SUWcYjZGjk z`bmphmzTby=H9awx6eBcEjq`;40B@ehbKSKz#q5hi~?7xJld+iQ?Uu;cvMW^ou^_I z$N?dK5H)br1d$7mZ3Nx>y zhpRv2Ye#bU+*v)^Dc$PYDJi9HQBIfa*d1IO|MHxPVrhJ=68PFZg%t?&Fc$cS34v5R z9(mJBKC<}1ps`)Jk<(JYSpJ&?0jG;b*GH-+giU6g4ho7i;c{)s>cW2fHz%ua@8LDo zf36K^%?c6G;dgjmhKp0t#es%fo-i-l)&hK`WNM2+U2Hyi{RqP|xtzx5Sa-ko80hq) z@OMSUo0Ny*#wj!2c2erV2mV?w;N7=J>Ld8=BL|aHp=Ds7vLXTQJ=Lyb$)Tn+laaSV zaLPELEY#UC96_B~c6JJLLfnzq-m5aL zy*Fjlwq9nd{Sfn2v}2T6!(+W!?`Bbx)&5HJ)uUB5Ia81NksOb<5!`aL_R7PO_Tv=z z>oP46xsGxbr&F>k%f;DmPuQF|=+^0UcJktDso+x@mVIyks^=zwq%%tKFH zAqLf$G%mJkSNCP4t6*s}stIZyA&i#x6n`b?b6{;1zHe>yb(pZ-D9c307}iRHWdYqG z+-HgB2C-ckReHTKXfkrZ0;k+($wGzczNFAFJIE=uhsLO(fG8_~M}x~S!Dkcu)|KVt zqKVB$LsT1D3mH>jv{4zD?x-Hj{qxQ%h$j3EglZdi-x{Fa5)C{MqPh15vRYB1?!ST$ z%3Eav3C~ll4=#>x4*J5>V7kY)P>q8|=u=t~x}V_Xfz83F*XvT>K0}M?!5i%L&Guct+TUd!?Y0lLf*67*Mx zNYLvO&x79fd{`hR_<%+Dw)Cc}^81Z*?A z1D0V6;A=|RKx}e!aC_y4u-0#apqMHyz8LRq5GE+*(4%|`JZdhv%n8y6`v|!`34Tm^ z8Mat=L;y;>j-Lccd(0dLd2My}HP_NBM zUbU7)pcml$ox&1m%nCQG^)12;uR#1vw?XC>iIDq7Z{zQa9zy&f_m71~HwIU^Xm{fv z*^PZhq#Igyur7giHYS1~-$Kzlja2wQH5$p&1OF{(2u*^SpTy3BN8%G8KUCu&huW*o zj%?DNxN;dF4J781LJjggM_`&skGAA#;Gu&5Hk3!wlP?c_@0$Fo&+%Z*O#L12iH>^4 ztJ~gOG@}6OX<0nYLKR|1V1l2O8m8~bLX*Y}bYNFkX}&$+w5*TCQ2Phwvd>O2m-`8} z`35Z}bQV=<>WUcr`H9eMM(kTZ1%#%`Ltf)M)yClB7@#Yw7f(GSIs@(> zZ#0UrYd2cLz81Uk{|a=HP`p!`SIm=x*!H^kVE4g4@Ie|S1JL0+;*)cZ_;CtC4(gYD-kr>TB|eKFT8p|!)S zO3rG{Eh8A4G#PlHyb?bkr5eq=jMNN!YqfqDw%WR>Wnbd;Bv_8FDkbT>!ep&(S3_fx z)V~=eqrzHe+l}PK_O6*ji%DHztspd{qP(FY*+!WJKn7TU0yh5s(s%zU@N(_e;5+nv z77H2}bD}dK6GzQR-H7-ivU#f4r?^g2p8)N(_a-}E_(W;YMo*=u3)E_q0||pLkHZH)sL|?2p&uvOwlOm+y!|F22XGfVucZt(#(MbQ%BYC_ta!L9}4fpw|VeF{<-*=mASu}z*m zdzC)@-USd_te82Y`#$l9YODF|kI`l7ixRRlFkSH5G|L+?{KwDrIU5cLHmme8@{Q@f zLOxa$LU*o*Qrs+dS5qK+#p!ZsYp{=EW3bP)J{Y%1Os5|2iutSDw<)YYlW_VYMi8hA+UX*+mzvu;muib$4Oj{Q&%31BaC%qC0 z7>}ZA6@K9s&zSAi%Ne_-duO#1bw_a3=9&oC=khWLJ@U_R*>RZ{(;bhe576N&FSp{+(n_rB z*8sZcBA|;7;lCY6^yyP!9=eN`-0sCL-Nslg72Yo6q=iq}MIn(SQ6f=tkgDtfQ=br4 zU917s=o)e6*M6cgntJzWok(GKxEteC^sGFcEZ84o4lD7!%-hrRrOB0kr-?Tkjb7{7 z6Q6X4wDb;!wR63=`5WWga}82XV^lM@ne+>&C43{wpkKaxow^_<5!#*`O>t+0iEGP> zmOEL(Z1#;P2KKj$h#Ox={JYw}T>plF|1O9rjs<6+;#$IWX$uiG*4d(vm)D~nS1+x% zt47qJ5+z^1@>o%VZmP76kaN>_ByzX6bH@G78+?)=oa zAnSO!>PD2*6gJyW!|@lX;w_$%7l}k81royFI&hIYau|d z$i?;993B?XTplRwKz~(Ce}v8(Dq+ob`^&&vTFXRRn>+^k?&n%H#m)G&FR2XVtqQG! zS@Sh^W(NofX;3y$35OO@%48qW;rK}<%H`7(CqKaw%|0G@XtTZ{kB&e>BGi$K=g}oz zthxkN_HQk_+}H)iw2$N-3mE&ZVIgp`QI^9Y|ALanxBsYU!1q10W0u0?&1a~b4LYZM zy-&kSywCMKb>n-qLo)fs6kp7I9OStorS z*?b>GYC4;HDiR`*A!fXjH|YA_UM5#PT4-EP|6zyShzjCO$gg3<=iR6OVfR6fWQ7ka zB9dbj>i}ulIBR9!s ze<6TXU&fFot%f5_s_%7EGrhU~a$@6aLt^K!_cjf$LP9Yn8>7v7A`Q~P%q_-sVc&k_ z&E}2@Botd8M1RNo_9F--4137{&*S?ezusq2i6$r@-gLIMEF(|3iVO80yxn1OyAB6M zIu+8nhGL~6Y}B2tX5RInbr4ld;&ahrYwdTLM{iWt;JF8m7Z)(C?m3JO`GB1Vx6Pes zfxq!xD2Fi&c@2m-y zCzJe&DE2!HW671NTKadx)1yaNR;8O92AJbm<)`c^vSyU3CTkri93C1usEC-o!^fEp zjOIKxSl|1y@hag;Qj0(@MnaKrbdeuD+2*1$j)3@lm(q;v17gZT6wdy52{hFKTIYL= zCI}9ROrqQYI7Io2L(&1yL}XHZ2gR=mO1f?LeZZK%-6zALc%$-IQNlS6PpIV9`z{*b zsF(=<+D0gh4YaglXCb1aJ2Ul$QZZq+oC^mV+dyK;!&yspYM3+ z%p~EP24{9=vNXVdF#j|9@lx(hgU?TSUsG}@x_lKrq!CnLiWnwTn^(?~5N##T1^$qF z%nVKz`K^c{B{iyK-_6n)CC7l2yToXyly7eI7j&TiFl`a>!!bpkBwG-WC+9(3G35Mk z?t>J<@dTYO7WSES(?s9UvcsXwM;G8xoTVGMs%AmpEW1J@m@#ma=QDo;QYjX|OI5DT zNMEV*Ui!gL90{MbNy4h(bn3J^zs8cV<8U0B1%s8)fqg5M035!a{iM*wJ(0(rdN2w> zS2XZ^m5GR@c{feqQw8pU8=Eo9bo2S)8da~c)vNaC7b;y!7W^|J%z8Acim7s@=|Zvx zUcJK-R3=M$)gLc~c3lae zy<|oyO(OCj7$pQp?33xc0@Sx)GivdGf^RPVg5w?pJ7X0U+!BBvGq)IIo(n}vNuUAW zn=alG>epky6>yD<8v)yjsv5^*Oc(ERPMgYcvQQjzKV9eb>_PB?iEY`EUTR$^|J{^2 z<@pN1)V19l+-_s>`QgSY@c==VqgGn&O0dBr!HKR3Y4P!B{KGM{RJ*oh$$%T%L}ekuf;=%cQMq7C zYF$`H6(ikFC9di?km_*67Flpu1uwURTQ-tqR7H8AQ#R_36Ipq!$$j^*E3UGZO``#S zu9`-72>7%U^KQA7ws%m|?uofian(l$F6x43v4YVl5>~j~G{t~K0uh(>Nj!jQ*H%K( zAs~nayY6D`Q>I;m#P2R1+Y+m{X?Bs0f`mnO(HJU!h^7#2u;(lq5lTp;pRD#VM|gylTe@_qpL06brjNASEDjNrN2cTEJ(fAArA zuDPcA2hVHfe?I+W)V(A4gh&h%Gg&e|if188iFiqQr9!ZHZFf50=j~L$ULzlg#Mf5F z6VZ>2Q==&OM`Tw#xU9yHQg&?*qJQG`RZUjEkU$r;0vJ>bFz8Z1!HA2$Gqt-OKz&|1Y=#%1Vh429lze2OuaF^CkJn#Uz=4G6PezGj`7Ox?tqa-)#=_;TI zpm;H&MWJnv?r78-%G2z{aD>Mn8WY8$et#^Qb#siFVK7qiXUglSX>=b6t^4;M5L0kH zHQAZ1zR1F$Hf1JgGDG+D=EZJk zQe%3l(?~#+qY!|I%OL?#%tZi_YK8>FGvgc}H7qwUDAE+U=<)g0b3)z_NhD4$I!6sh zQ@^P5Q{?&#wOyuO5!h$H#{YpH4JTfDk=O%A!&+mP;)UX-`W9mi%{+aB&y|3bXq$eU z4sBmW)k0jKI&H=>@x*E2AlkJ&MMrG8%Q*KL<-+m!of9+q%xY+QZvuRw$XDdzQG8FQ z$p!Gm9?(U8gf7wNHez-smO_7 zFt@xBMZ+1ZVF|_{)rc~j2gnicaFtoEMdT7rR>A$KLZADa7;?19+A-6&=)LHpKSky4 zXvfg&sAu~2nN|Drto!ATvGOZ3zl-?DnH1iYAmk*b_x)4`v2Zwvt;lh_BoJQfdl7p( zpjVmR&5^ccMJ2piY`M&6yUrJOY;E^w+zA~4mXc33P}JI&zLJenTH>2srw^nD-i749 z{3?S#znvzK{sFh582zoGfNEpbsJmjXrmv|=iWJbcsL7_`gCzk*-$pBZ{PTijlsePf zNaa1*S$h$nMsu#Gl{;5r*U+F!*w%^pNc71nVv}`JC`yD)w^-7bPY)_x4V;57muM*jVJxMLYgyzND+0ef)W!RxW5^<)Ta zCDsT&Al|Dkj}zWLnm-79Q=Bk=5RFLHQB~|_N%dzDrffW(S2e+1_jClZ?dcv&>sZrj zQ5VH^rOYa+`2T#~Rn3og2fY@xH?*1XQN1lbb`@pH#TlAA+K+cxg4b7GqQ2z9BUATQ z9u>NS=Xir?TjBnNYlVU;kMGGDbD418#`mG=)NMv_oO+8IIG!l|@Xq?XM(`p(=i{Gw z=-BLU1iV9LZ3KjOY~L2n49u+PWY~EXP=L|CK7M6*pz?z>>Twhc3tx*Jz3p9V%PDt~ zaH-GG7CEYLDQz^a7T*kmCliuh@qLaJTX7+fb3s!0 z;`7W{A)v194-XNX5|F}_*|keH^!7d$VFX7-80xT8ru9uEnOOFceq36hGKleb+Ok2V zp~Dv`x&FOag2$0w;O=CBfNO%>#f3gk-;8P--+Iq9v3(+vhVmDnS;Rw!mHSc7-IVP} z`xZ?S?>@A5RjcYj8!VkANrrABL0_sp2`V?$qdaCtW%E4-UX1RrC+t`rM1#ND4>Soz zY8gh32KIZk?7gaBaQTYzEV%v+DB12=*Ce^Dy^H5gAq+ zCIz|nn^~Vn(;N6+?JpjtyYUL7gOJ8ukPhjCOZwi{mE3tkPGKd=n(dPHGI9u)Maemo zc--}K3Qk0K+H2Bue>>q+DXj10QRr+v&nxH1Z@CUBjbFpG0O`W$b^VG&2QH@9EJnb( z2k%hw@e@p6XS;bXL}~o%0TlQX(-iF47fnbkYEhp;WfW{_m15j4H22NoNrYcmI4qZX za7C?eU!6(0w~l_4<-&VQO-Vr)v78LxqjQMQ_K^yum1?0z8Iy5dT^#%HNzYoZ#kN37 zW{L{Fmh7F;hDP4|rmOwnOI%6&mx1Yxx$ydj`7N_Tvg?!4fuZ~KFGymho14S#RC_Mi z1jO3Af0$uhuNA$VCy?Z|5vBN}1uT{@$%&n~`P@i(RutYF5$_!lpvG@xmVKc@^p@B7LhvP%>$0fNO;Y+F@l^J`8fP-+hyu^c zljGb1b(=R{Zrpp02Ye2yR+6Sb(Gk7K)@<~iY&*FLrEx8O#v4)ho;~x-nmU>Uu|lfL z_a?O}(}G!-67lvWJ@vni-GX#A312uszc`Iy>@WC|zRCu$?jqjD4o*^mV0Ci83)6Hz zEVzZyFKlw6;8|W~ic}mxe9q~TtS;@v$UX$j_tKh6v5ATggJ`EJjSa51ql`kmA(l9N zWLxw-aRCb)ekKBGoXLhDie6GK(k{|*`Act^WO3vqO;yFX_MoUY>bwP;{n8cKK*VOX zIyaYm#AZFI!&w3~F22PRm2y;ze6@zY=dw*X;T>&aYdUGUNjU*~vMVHBq)Ji zy;+ZaWT|H2Tkdr%^uqQTG(3eI^S+LD4q+7$nN8(zaE*)KqsS+fofV`um23PexT~%f zucOlwRoK}V6%HwVwB(YXy*W(&>9KjMlAu56>txIOjra_zmR^mrl8l6wYa#nlo;$ZZ zWK?l5SE014N%UAeeOtu!6uXVZ9>JX*c8bqa?$6liQ-rQ8@I_vE z#&2mMOz7=-HMzPW`)j$lJ#`D^)>PJpM|J#8|C|zdY^Jx0Eal2B_q(aZ{KU8)l1X$s zrHLOqIy?pJvydNVR^XXZdjNY!b#vJ8;_cDGb021|CB@6!w*BDjO%WBib?H{+cwL2& z>ZYC<*UB-+OY#dJWb04gDV855$X(@n$qErKe-Z1c5Bx%08gv~C{ROm+4m~){GjaOH zymT7WgR;!E60_+*7sl#=Gk1`S=9986rr{ebS zMbj?3tQgOQJKqr;^sK1e{eFi$-=beznc29rxGT{9T`<1KCscunglC+z38svTHI!?i zj*g$XTN{8Qq9N|Owj~mwH5IOVYu#w><|3uBqe~>buZ%A5m}P(LsFazpvEnI^$bSFG zF82otoGQ~9+Db;)Jf@Qp=)C$uQ!Z#hI_Ov-e%<3vlAxt))>!&RABK3tI#rBZbk)!g z4|Ob;vGmsLuS>ba2B^=KhLTiIrfEm{T^xRpNIzP#JU=zGH+@Tl0lq@L=94!)z%r9Tv>ij}o>1X;0cuzvb1J~~|yzWQY z%J(PwTH9KeLC^D6D|Mt$zxX6njT>&Fy`-&o3#8P(8U^)29V(RiaI? zLNB!qy1amVtx<(cfxH&A1}2QWdq>g2V=VEL4EAG)_KW39c7U(?Z_|SGC&LHfRYsFp zLh!utsU;zwar1*V(allCpDsF8yrgqNH9KmV;h3f9hsj_alC3#CHqb%)MlXC@3l<7C zJluM-&If#KSH)|kM0cYT(!ATb1^#NZ<&waKrE)QuC9__zy`w|8!w z8xHkY=ggpe79G4AmcQuUpWYpf563Qr-GCowrD@TL4E5)H?_{BEpk%&ixr z0{=4I*&>rTF@$KxIz8J5d>8@$GTqrCBdMmrwp}DOwtEL19J{x!j&5X15AX3pJ^L%W zeY=4@b{BPrbmw%(cUN>bT?FR!GSxhSM!^32d7~y%h|~Mw(_1srfrLvM|7kPKPFp-< z9{#de20#IhougrJ^KTnRSQ;mF1i>qEU4+|4!tM5M9hn?&EBy>#?Z8rFF z^qO#my*wDP_+uA*+6H%`TR#l^WD5+Xg8wpVgyou50ie;4{60|b; zq6+kaw6ps_fKPb4q(`6#elww-W*_#t4;XK7 zvIF4dul_K3C_QTOhRXtCzQ34(MB(=k)qlJgpB7;;%i*aZYMP%%rL>T{&V7uy@dMac z@E3%=JIn}xMg9O7ftWTJu~YGOlgeNug4$r(1~r!j-x2c)CAsd^v>aK$CP@VF2;-1H z04AIQTmnGK0igDs0}YarhkLiy;>+^P7L@7nC1k|zieM=)SL#2e zSdOtPB27AkxuAL*sNpvH8fUp=rd?f4ujW!qd{ z8*8h9C(%DAB7HUaw!;2-YYO3#jMpPzh5Fz(6{H1ez&yE+fmvB}PcBg?>vWrr_)FaQ zn#N)x)n*VHhg|bd^9l?bSd+>yjr>I)17;+bumi81%mD)tgOlON_wWqnq>KQz>J5$R))E)=|zVnfUROfRn2UJlC*D;p- zOum2TB?Rce)nAJCWceiLom?F_k$}_CDnz8`RYy}GgPy*|4b+CxypJ?%=P~ zL{x&n{okUuq;X!W6ZWzZ5qaVuB-qFoAd`9(U{?v!@jBf=9ngRj8K6=*$)9J^J(SKB z0+4Lrza|+{MUfSU-oI2Flje~XHhZ@KCODtePXAEaQ!<;JlsSJw{0jgex13A@6hqx7 z8$FlLkd>L5OBphAocF3WutOR|9TEtn%AxeaG$1=S09*Pc=SbLo*8!)wSN|ND0Un%G z9y^HQ?3B!a=AV=CUtlAujT2MM0Z`|ecM)DVLXhH|q@NUYh=u-P!dYM-=lSosZ1{gw zZ+!X%=6{kJNGG6A&ze%bw1lG zjm`+3gpKnWP$rz!)8{xbxtfinp4BNOkd^m&Dg$akiO9{ZfU(X*$Qt<l@ohu+V)#*U&zxu>~HH<2hDl929Da|kKBoK%p+QZfl^lRWfEZyUL=B>KzN)u3mGvd#s7&#fjWSzq8H@4E0JpdTTGB( z0OYZ;Xovvf13Bh*S^h_K0D3d5vq7f{BvFLo(EKeT0Qa2~@*&}=j1A0}|BIj)QY@#w z9Rif$$6crlsrw&D00qTL z#?i&1(v$k7M0`&gS2{vkNxD;-LmDh?C%q<3jpm%tu#&rvkI;H9VPx+AOI|#w&IMn> z+VT+9!|zJqEb{>UE>L?5v3Miu1H?oFIe(Dy5B)-0v-Qdm5qR3D|AEMfUZNIA6G9H-cw2MWG z;F&D_4Rd660L~cxL3%)QzeKO1wNE}vPOm^89lbhAE=(#+CVX9(yppt%tnzv#xfey3 z193^wqzqs|cgqQ_kb58a-7Eu^o)k3mq=y_O=gIW1m?Io>N||$n-~G@I91s8uZcp<- zY-R61+4&1_plAQpr6c>HKSbsfZy-GY9{wE#2zLJJ@)2hQ|KQWP8Igt72~`luC{f{e z2MaV`$i>dG!tRGMA=Mpm7iNm48RwWI-b8quhodH9#0 z`~n@wJ-2WiNhl@YGn&6ngU&?f^kC;)nE!?<_vFOnj0z_`Gr(TN(Z%mF;#cwoYLJr( z3fNopugdcei%u$_?Gu?sJV{jO{8jxROVJbdA!O!%M(}?w_Me(^zWPC&qMfKq=g7?F zN}S6M(2UxX{A)8hX)YupV$_`s6p;f;a735(k8Tt=O*(5v^_{tnk-aJDD?|fI2()a! zUQh%yb4We`P3pnd9q+qxfAq4Xh~Aut?WB7}0}k6lEA)Z9fb3_DfHt;(1L*g@BU-@I z`PzV!%%;*dB<%lO3EAHwqDRCjw(XfGG!U5h;OkSJZbuTMhV!lM5zKq&=lhUR5u-&LFSILjuqL=BA4<) z?ina#{}7j{tS6}zAzgnvt);YZ0EAdFc+ucL+5Rh3PYyT$BtT_XK#W7I2B;K* z)r`IW#?#Y^4FNmwV#ML;A4ht~boGan{hI(IPuNPmsi+Yd6^PJ3H0PxDIjwb!{^#Oy zF3cK6H4rT_5bK@i8>xQ?KBd~oS>3Wq>+JIPv#qGfLpRTVYT5baew7*9aDwbNS?>Ma`d>=+TU*cBgRCEb`uDVK`_JC?wA}>`g%Jcmc=1o2J~!7{ z2?bpID@pz!QiitZViDpz{j7@lLmLsNW<%*yRi%l}qBj~=L}UQ4f%N&8+zFgtA@+aB zalT6XBSoH-!2jP;{yFL+Q`Tv@)^Mnjd@e7Y99N%h;&&&kebzCC^d2Z*M7RZf{LM^B4`JJ8|digyT8gVD6uckk>5Aq>$GjEbiX? zpryADy0_{M^g0*hk|0UoYsa3zwU6}3Yf5Q>Nz~uQ-4E|=L+xP$b_o%Pr-zgaEn92SMy z^MVF7)E4^ zv@-_kBi~=6~GuRG5zW;24;=JPDH!d5bj;Y4sdP5=ntA8aHpiBE$&qIh9e!Z($KwCbP!()Gu4Gu@$4UG<-_9!z{{Zs2YmKsG~I^Uz~1k8?5E9H zZ1LrdSH3}5_Z~6G?p-j#I^-+07!QvDl0oDdknY^Gpzp*zins-g+!?-4Yvysq6rj5LOG=B-sSKtSI?3QHA=NaV-u5EL=mhcyxIQmX+sfI+}!|6e_sI6_W( z{^9o$r_28J;kPYSCnlYL_-*aliP8Uj_?!=aYz*(Ng{Au+%V3V5JlPY~{SNxPejGu( zOU<^7d;$yu%sYK@ddCxve9_U_uzi>ez&GNmlj+t#h`E2i=yajK&;8qkU$X%goU`r! zmp1@LQSDL-FN?Z=2W{uW=Yf6H!O{bcW&ZcZe+fxD!0v$KCW>8Zr|+QueeyrUfYlgY z;CI|auuCof9rV9X{%07Bc#;#}7`Y+j6GLt$bHT}X8B6m?BxP+YcA=Vfnb+ zA`F6S@8S7@xwbEcKEkIlyF?JFfk%9|CeAsk=DYCrXLgUH#E!$Q6gv&-2O3Y^q!$Vr z9YWtvV1D$+{m_cW^CHoIC+!1CWaat;L(f^eeRhuBYn@3O8rM;8s*igHEyOtw>uURS zCqE|+w0_TWe_H|MQ?pa*(&G{QsGhy!U1v|hzIUnh%#w)>8e?%MDf zwyo#x7%v;>KK80VGIs83Y`mhd;jff#HmunBXq+{R|Ay5LCSn^X7nJ2uE)!lry?_pE zi{`>--e;%_nHMg6S-pIL6u9DQ!{K7*Xzlda+}zoT1Np$i?rLk3pgtTtd>hY;W1Bj3 z%=93szFw!5U7kdjNuHxKn6-&EYUX}xSPy8exdfZOE5C7|xhKKtk+dn8N>SAn?LD^E z10QkGdsNmRnB9ulx+2y(i>_>jGCYv;v(onY)}9iu(}bIo-Xo;O{Yd!XV+9{8>tPC0 z3G16d8yan7-#@;7Q(v1iX3}dV-HJnhCH%#Wx~O&39jvmd00|AEtYzR>+bnEF?#{J( zap?Qmyz4{sl>v$bmBS_6*=Cr8e zm%nf?jCyZH>SB_A;Q0wlc)GCgcU&~Lj?g39?c6qu02_CJ&e<2t!1lM0lOul(eDFtP zG2q&^Bt(!AEdhaC){m5ZZGLvOBISPxiD6$`2TGy%^DS)dhcCGZsJPI~qMHSJCS2op zrkUeA%-=Foo!pGj4P{kBKG=0753@hNSx!zi{mx0>JZm%S5I`@e+f!koL!7NCTh-=y z@#pO9CSmI^+y7={e&)e$N%EKNMVh-qR=bzwy=(isJ%RQ%A%DGn0Uhe4R{y*C*|QO@ z3iHYfg zbx&UQ>&B3)% zT@LB;T;6LiLb$mYcT_Z!7FvT+Ud>yORv6v+oS5RZiKm}1sj2z@8da-3e9pH=o-T;_ zyZDkQK5$@Iw>&rF{Ls&o*7wEC*_2DHCcagc>K#3eyzy;5TvXl~xmv>On?KC<5)j8LSdj8@zF!G+Sdh+5t=>=Q zyMSI+23}tLDZMZfEI2&2a(D8%mpz%%85v>Y%NlXIJ#TpF%Ah%K=RjdgDnm5rWNch)y>QY|{=RR>F&_se-XOeV5TS6 z_jBo!SruN&ZVLLLRiBIpqX^^4q(_($zT4-OlF% zm=$6Mn#0P>oZABLalc6x+CE?4`GC=fjO5Z+latZQ!|~PZ_;mP+eT+v0K44MChtnuC zOwHgJ1;LDguyTifF~-Blu~F}Dvx$`868o}1gj^pFX2~h(5A$aRpYsYdvs#>);Yc`Y;%aG z_#2k-fesd*Poc}NbRhQ}LkJPcMW`w-qc@s8m*Vf~ur~X6^dpT;1n^N&U}y&0%lsQv zktB8J4907YN+@yeO<1F#&R*d8nPpoG!oGqXWkjz z(XkL+#$4z`SGp}HF5yDV=1QlEJ^s|0K>@(F9~^7S#*FBTkzv4-R`+M~UhZIZW(LPSN(?VKaQ0>{^vMQ>)qj#g4HZ&6G8_B|u5Y5laDNSHVDLuW9YmS8*P!oR@uZE10dlV=pCz(-oB9%+$=(}MP2S|s|L_N1qE@&3{B znl$9NG`t@@e>e#L8G-IH4rXz9xD}}eCBb*$^*REA% z{X{7%%ru^Q$>kAFp)g7`@?4KK<5MEtp^}}$Qldv-RL@#(@6qkAnn@K2TT^|;IZwgd zCKE^Z+_|1V^>1PfUh4nwiwf@Z?R=)2>4?ycs=b}@^&qsIa8t85ld!Jb`XaS$D4H;a z>$}6(MUo7Xa-lj@krcyp!{!gP;WRfv6D01cE5kDR7t0Z>t#-4BI++tBf+D|k`q_M6 zXBC}PnSV5r8au5CWxEw`_S|po+i!7};yRD%j4EHK8JcbNPo8&61@JQ9Woi<&LF0w8 z70lP)>rck}=Ei_UE+LX_0tKDITzbERcTvAHb|%iHrfYj-#tCIeuSSx2W~3G!*=!Yk zoqeg4*+~+Ad`^6fNv*}k+G01mIunbjX4TL+TFq8r?j60}CcH;kc;syP!tw%>>!Ozj z0dh<#TFC4}<7p?EFi1IHSHR%C_99N>60+IwACoV(P{%P3h5Ar<8hASDNPK(_gyQF3 zd~_jp-BPZ#`;xD^inU|LW^T9|Y$F?*%prDrt-gwZqjTx$rayb4Jl-{Q_vV+F>gq-e z8|;AC@SxEYv7evGRaO1+W!j_M^Am#d*QMd=tYiw`fu47sLB1__59o^!BO z=*4_+5UIhc2^)f>WZ{vGH$F^T%cE8r-D(%^mE>xTO=8KSH(DOERb7?T#93pGq1l#L zN<-&Z{VMEF76qTfF}7)@ged~6!Q7oh(Oi(YVRsD$`uXV^2wfzd26?tJO>OTR(k)pm zG2I2A-rAjN5)gI91MIuD=0aZSR<&Xv8?EE58&IIShUG~Qr**9>IhveH->ryNeGLO= z=F+pypoYJl!;D!TZgFj+4hx1$UJ1fU1Z{{i+P88WeTD8iwu-VhTI*H)?Id7{R@)TO zGh>T7`5Kx@!i+X!(|+=(*Ur&t=Ym)JEdjFyPUN*0h*rD&ZP4v+mC%{XBlFzep(M%@ z@J~3W0!y2Umf-#GK4lB^V=>_Vrv4HseU5qzN4Ltq&Xu$i^lL}=R|)anH_3&|c$CKi zM8z&`Vb#_>SqMTegaH2NLgJxlTl!{_5M=L?WIHO*Y(rHa4suKYrO!E?@e*Fo00)A} zW)P!9(5C{_RcmmA50(t^a{@+_72(R%i57EYj>se$ICjQyUUZyx$xe$>2M01r6|Z{U zKhdpg(}=0(n|t4$_m?uH0FG5LmPH15=cI=miHcvv!gys67YJ;J!qo_poW^P($fYy% zgfRvSyrzQU;fy!qystB&%sYO{i+SYf!L)|plLb!KAg`m_cL-?_gB59sd7+-yTqllM zR`+{(!usQ)PJ;6oKJ3({jlCuApP6i00J6D{2#jQMLRO?Pv?io=t=0-uGnw7hUDjQ2 zlVMK%a^J!bSl+!*e$YGed`JIUsrL&>z^4TGuYmc6xO{3S|Bp@BkB-!quO|J?Aux4^ zpdzuUiOJ{oq$l*A%~1F1*K%?WG2h%jn}E;FU_5YUhX~-R${W>_Vsu9e1}__Vm?CPfs!SJ@Um|}sj7N>PA$MR!^<9^M##`G z?mT$d?k+V!$vMQO-17%*#<*X|c5>T!PktKGe(_x}>XOKWbTfuH3w+Se!PehHEVWeg zOeW#Z>Itfr1{tI1{qC=qO8I2JnDAcQv!n$oGUTGl@I3*w;8tU8G@D`X*W!h{6)9D5 zbMHt~e-@UfmNW1T{}O}Y zLc&t3gDLypxhNy1`USug+`f_3Aj!vlLz-W5{mqLhU$zgFl>PN1KH7LcU_mj^z+iN3 zgh-lyHr6fR_xc_vKgWra?sX6w%dpzKhgmuD(0vn!OG0WO>)#}~3;6~t0ndl%M28h0 zxp6%$FY+^by~w;B7M%Jd&xuJ&6>j6=ImMkPXTu9*YDY-ZdBW{F^NF(i(Xb&g`)p=Mw7`~y zI`qc+p`o$m_Uw8i{ZD;z@_2Kfw<@eOHSO)PAw|&$PN3#zQZ}X4& z_sXrR50}gLw?j9T`^jFH$qy}_56Mja{i4I8iQRD7y*nX!x7`OXDitXrWLUJ1j=D<5@+)K;A&qtfV# z-|KyaqcPc(6klr8Q8^^<-8VvERPe&y&cQmW@EF^1*v(XyK#dt#)osI zl;d9KziSt2c=yiwwvy*v;-1$>JF#jl3ca zG=Aj`o5m@jj<1uID=DSC&ib(y``RUTuX3{<~1uE29z!eEd4e2cyh(owA3eJS>_ zE4;iAAKqN5$f@IJYKT^L4d08{xw`0?lTvG|Du;(0mBuzu8NrcC?ze}Az8|@@=a@S% z&qlL&1f6XAyO;BDnesg>k>t&P@P-!+^Y^Z^ejk<34*Jf#Md+7~Nzp2XuUYptgl)lb zk`x8;wHwBVb-_#8VCA}zie#|yJ*_qS5_-1mxs#PNyU{Z_rtW2K%9**BM3EmYWYt3e zZO?xE5_-5*xi5(lv#_Sj9X-@_;-&jlu_vdGZPR-fvO5;~b;lYjb`9pT{WVvf3KDjW z?%mhpwDAQCcCglP{F#6dltdf|V{uyOTqND(D{kg_jH(2}7;ul1i55ZMJ3dugImgXT zoUirrS9~PW*cDff5>%3s<%i3w!^rQw;7KXWVpQ9nPwQed$xSD|n9dZlV^)-wALb2> zJb5WE0;33bc3K+Cjyf@AiaZH>LlBPFF0dV*D(nDM=4iGV6Riv#ku>KFA*h&fLMNlBpQ5f+hEB~EnRP}o^Q$Zx%B>!u4@LB&t;*e=IG7|(hOtBMLRc{NDT8B9;McIiuws>ZJyncEVOYw%u=zO~ zbiS>_MFTP(o3$2Iw?2NQ3?W<+7t5<0&Af{66ASt*@~!AD?QTy#UghYM0*m+DVV~nx z&z+XeKWhYrAzs0C2SnMY713r9lIroqi<5}1~Y-_KiL>)2&|h8@^@ z*YcPP#c}N%OjA}nLmj^ai%GIo((b%GY!Lp|5)o2;1AlmVl-7lvibLo0-Ynb||Jv#c#hQ zg6jHin}Kfx!5J&gh?@YfWW;R?FJ#aK;bu-?Q^CwAE`5@5b>(96pE(rJ$36yxrX3|D zSL1j%1`4VQZKaH@9pp4IMD z6~XI=DGP`xEFEndRRjRKh%A;tL(cI=L>Uu8$Y~y>y&?wT!C58)F*&3lZByBO9_=s3 zf6s6KN_JP!3ovn2x=p~-i$lErrmA#vKe#pXF; z2LY!qlXxr<`@OAlTn57;I<-$xi;7FP;d`&R=H3@^h!X>)+s#P5)`9#B8k?x&6s)&6 z=J06!fp%X(=HsL1(B75$1BbX|!)|zw1*n1>Cr0KB@`8U1PAK%8a5L#>J;RcA5sPdm ztdAkE22P~4aXiS&NeDFeNgXSXZjv1&%J9lhJN73rNR;lc7Lf8|DPV$(tN?N6XBiGB z{LLOOj|34+xbp%kxGRPTW{N^Aj& za}dG)B@UVF#ilUhSTilA69SG;6D15~bNnYr3d=$qA&l>WMd-UDR>V+_DvU_X;_7ed_Nu z7m(f}B*G<>V27u=Fo3@?w08iCG%-X36`Z6CsLAH84`JF8N6Jfn2JTvm2hE-42l8_( z09#uqfctRuO~BO$%#5dLFOlEH1ZKv0utHz6>+4TY%*7>tXe;y(u zsx5&R;M(R&Mca#>xAAUAOm=eeId0xoBbl$XgIx0JZ@N87lstwT9?J`m-a@E%Co=S6 z;pG+)@EvoeCEzP-rsaGZO1m+ljn`r|`10=#UGoM|SJdJAs4x!Hu!Cc}|3}Tw(>aQ< zVA3isyZxisQ3UG`Cn7LyiGBMD!1vb^ zAo3J?s36w|67R}P(pr!x?+9X^Chxk=8TcJS9^W%HlnJMXM@~&xp{gTuE3}#LNfYG7 z5WpV?L$JG5Y%M+od`_WHG*gz`2qmG>CyU%gqSB0h&*9|++f!A|K{@CIG2+)vt$qpBx)2- zLSTkGQDr}a(4Jn1@B|iG!_0 z?D<~5dWGq7WeyWFFM-&Tgk!A+L|#(Rz*HPwvx5Rx&{$+{EBQi}#Lkuzp8xVC!>G8h9(9Mtzw8B>I?f zChh)jV>iqj;K-A>9RRTQUs6Y~_V=0P^1m~C)Ztqk1{$P^bsQJaTyV4~uoY$`S`VWV zl<6i7tSPIm)8vAd9c2He=arOUnO?1#j4and{I}fdz9ctpnfABg$DKdQQCk;hixqK)-~;^2>(jF97a)N(A`>}*{28CowO<~cEk4W2IKhT4 zfq^)&N{H6}O|%GkfeLbYBT9=XP&d<`h&%oKSWwjgsL>SN2RMuHv;u~wl>k?GT7lm! z3QsHWw|S(UXuyPwC|X|hbqrtvBNxD?jJPA6o`M8U5GqEUh;Ua0zQbq7%fnJOQ?8%_ z`!BE*0Vc9{=e2%qXCm$d^=JT9u!ZpQR$JPPL{+pDALV#wQwnFmVh@%3i}n8=+i*SN zf*p=QUI}OuC2nk{;Fj7~wg1#;Q_pF&@iVk+G2%&$i%%0`ZEGsvcg=4WS5<_G`vxOi zaPyiUBAA*V%Wnb~b~hf*A2sOUV8~8dh%)iIV9Kg`YejEYsisMlFfGX!0esU3R|)G# zgbQ(?YfkYe@X1LMnlA8t48Ii+hlv3ldR}?>luiOp;qi0SKo31HWPA2MBl`a)q2M7y z87D-5?|-@@Lsdyp-kLlE9Y8tHus}Z3Nz0{3n4E#YI2w6r>BtDu88p4bAhFI zg@_YM3v;W~*+>&5bz=V}N7P3mKmMPI{PO>mNR*%B8-SL>sz++oj7yOuL zFx3B77Q5gq4kPUVbl0YFXRBUmky*jZRDm@davnF{c_d#7z93D|8u-As_yIM>Qk#2J z;K)S^Cgp%P1~KlKtqGWz*GT>%%!^Hg{)kHTo4Yw)E>7(E;s;gud zRPJJLK#|~kATxen)YCIj&?CYB?z)G%0c`xIqadO^Wu`e{mrFH%_n0frHtU*;h2^-k zHIu$bS2OS%1__}TYd7PXw((vDk*2gD8P_z7%;1NM#sZZ^dYmjJ>G6AC8q(ZBGu9vU zcJyy8p4sZ-y%vnqjrakbDVCc*HS^rm9r{5e!}c?n#W9-qhgbLA_rfoTF8)niT4vSm zn9Y&Tl>_Sq8jSlr*KyEp5g^Rl(M->fu>XFb5VkvKO1Q(v^!Yd$j_i}m2JJf9BW|oRp$thRFghL;n;4)H`#<|bhHk0X$RN=LIeBu z2(p#AtiyIDatE5C7ZcV)>RQ;>BB2-Ld8>PZy3^h!xFXLCu{soV9Y#CP1g6j2s`_Ey z1iHm5kUQ?s@&E>P8PTb-wF6DW0wgN31&fV6z!5GTu7^Jpx87&><)uxg$jS&uGPAOJ z?mQ9?B7h1duFhAJ0C9E8gI~E=#+rcJib1Y|l1quJn>8l2bTpM40Z`JW6#VRbRPtu4 zQi!XPLI;;svv-uoZ`|W}6eMKQ9A!A`gI{Nt& zhij9J#R9NWQbs{AhIAB{Pf950tVEcK5|A)cjJ6Wt`37K!Uk>QNGRReSLvciC60q{|_mc!y*@xqT(A_DX!MBxS$M)IZctOVh=zXsEPE#+ez;!86T z22fXwqW9-L3rNOf*<@p(ornS$Osg!gJkf1m+Bb}kfG2BZfNbza!yshI2>^et?@Y@EQ6y=dEf z)dr7=jl+vINvoR-)8-6Z`$#)Z$CZK_o$T{~^fjVS=nb5u=+!I9SEsjI0FOf2m7_6! zfZESEBmk}*X27z#r|ij~CT5Q1;He7g3JVKnsXu)soU|`YNJqkkIDk6PjiuD@6XeP0a=`FR^f;M_iTAu0-TP74U!S= z7Xf%PM#vBij1DXm(s>^gIhizqfKtq;h=M{6>;SH<;*RYw3}RA}DnvT?&SwSwuyhCb zu&{CSBIxM`5qL2n9696k3Toqj6X>J3Dh9nOK=7!-UF&>NLf`T{pieZ)f)uCYJAQ6* zXsK^mH##k(E@uUs2B5=XX=b60C9@qIr#Jr+rMr0j_)p-^LwWXrGBfr=;R%07p?{2?!o9Dp3P0^HQ)o zG&O}sI3}Q_Ltqe@32+oE zjw1lLP4N9fp5CetFsw30?dbb#R|BL29LbExZQ}yO-_?xcqW}&hV`XT`1DJ*c|EX{O zNqr=kLUmVz(c%1X=8`gP;9Ewtl@l#{gNeatEZs%|?>+=a-Nv|TZvZEo&?9Y4|7hEX z(*}mqMtf!b@`*M-IBmU8v|UF((H8KJwiR^RbwC5_YPd_7cSqmwSJahTNO2r3R>#QS zXk@^Q`3sZh;(&j&X~bBRA;L9R{$I_B$g^!C1F~4KgyGuCV=lXoYk~6=l7-!|=J6Q1 zJrF=vTGMI|{0$pmkn|~+d=ufaVIn4r3#Ef8y`LSBG3+h@&>5~qJPNWx0T`~3n+FjB zF6Fbr$N~2QZLgz8mN)=hy4*-BW{MJePy&F**J(OeG`Q5x|2L^o{gayaf22k|@6#jy zB(;dxN2$FC7}fmiq`)RQcytOsFF{<1ze{-{O!ASi<9~#W^a*MQe0wLL zHynhvvU4?x;HZtrE6(4F!k~VL3lQ!vc~n_ojVU~sQk{d~l2VN5+@&6{1$fA94*hxs&y0UhR^A|)nN0kLctJ69S2pQ=y8h#lHj9cjaHrdh-RBr(T{sEysZJ%YzT5E+14lXfB~3eZ6)K>I}uaO4^XenkXmxDkK$ z$qJCgPG}vr3h-%Ar3WS`0t}gnW;fYnpXN912(8DZIlw1NF-}R3#hHao*7Q&qE-hJS zH?)p<-$slK1)zg;AdDU0?|t|C$I_0o(}SzE(9dP@U;2l>%@>8~BqOb_VelGZy@(;_ z!o!8Qo9a|+TnH-Vq>_e=``W`jcN9h9o0u-TZ3U-(U)HtC!UqWFtIu-D}mEE#vC2iYp+hcO{WPjxLfa!?ngde z#B(nV%CwJcUEC_IfBbtlE0#HClPjdT(L|)8rr#ixUT82ApY%s>(D@zwa3p=e`CZ1M zH=pPGNsIFXAMsjx|_r3Jq^D3ovGK)?9aNL#ILeDw=Z3U|(WPLpj1#H9HP= zUX@qDvS=bRz7SCO^{eiFGHA(is0#@Wc)~7_u|1=CqZ7KgO!bR0!=mw5hcf|=-OkJ> z6C|Y0uYvh7k%5`l3jGu*tZRWK#1_W?j{fYjc&U{1dd*mdJd6*8krK?sg~doy22(UK z*5i0cP0|91VNs0^`M4ZcaGK6-5KTHe;7*2>aBp>72?@?N! zz#lN&H#wctd(V#?+OF^B9om|%&(ljc%R{^9D&k$oNP3in6){K<}yjM#bQ9Y(oiD8JtTis@+OV3VCQ1y*?n;vEn zfHh)UtaS2{i9|}0qr2Rv9$mk&*FwP|*fG};2}l>2G8J}0e)ln*o)$~T(LVuskXCHb z#n)k#RVc;OIWgTvM3Y0`s`#}Z6ZpQc_7CiVK1p71RGshZu2Ndo1oxEDh)eh+PB2!0 zc=xB)H7z45`1zjUS^fjO9tkCMRn@qA**)OLOzh|!JrbYQ9lx?0oULLP9&!{(!tf7_|J#pKVuX$+B2rxvyG-hj_Mdd7bLSbOR<`~3Q@*%l z;FG!R6}UNbbsfe4Y*gtj`YEpNpuLY8Uw|{e*mp3{DA7dMTjb7GPec6E-uU`^ zA)2q2;1x3YI4GP=?O|EsV z+!W>J`5m|7nM%D1PY%2CnFncY~LQqy}FifGuDE#^tUVe~d#dqB} z?Ak}8QI}fMBxnU3)RgRt-L+~LAH4P zbGQ!^OtQ55JfnACS)kNwf9m<9NxTW*ak>j&J{^9D#F5<+CA-sF&ns;$%Hgk7q8Hq_55E!QV=*OEe z(>G`Dtkg^H3v}bODyPI6DxUw*x~%Ia%b$urA)opv;{aKm+dpY((|I1j*Ajl#`be#= zVMcY)HR})-e_}~HOX)ph)5P+u&b~N3-i5I{baj@go1s_QCt4c8B&Q{|{EB ztG|-z34t zTd(K#tIR5tW}dbp%t@;_p}16FOP~agWwF0gd)d;}w^G9wynVeCzgz0V3Dec`O&mo@ zQ=C#u>_)UKTYR5?kO6(0?vKA>1^r$B;^Yk)-rH0CqOo%oZnQ)p4`Eg`@q@71Dj6$msUnJ%hNvo73{*4Un)| z8K9kw>s6@xr;3;H*pHR<^Vy6|G{vJDLfHh_0g007j3< z54*+%b1-{lH+=~8>iViij$U2hhz!}X)GzOg`|>MAt_5m;-~03HEl0nOsFhe-AHUId zA2QV1D^{M%)^TjDA=SsyTKW%hg(U%%;|fSTiFaRWpz^V^n*%EEz!36lZPOh0G&1Zw z&kvcT7ojS98uVV;`J`&eGOth-{ze|Zp`S`GAvU`n$2K7P%!Nunt6%XPiLYlE#27H@ zDC#7DZkK4m4L#&on2K2zOABl&mU}EL!|h=#3#eRHn0JzR%cllH;6;-qY)EG^M$UoF z$0cj{M~`_nXgJ$>%T9Q5)!xs~%yadCutz`W&+=QS- zebm;;VPhb1nFFWGZmZ2SEtwrUVLLQoXXQg*V>B7m)p7TncQV#ug*JZy8~l>AyZ`oO zZ)$`T4&?qqc^uyPH;sv^(HT1Q>c~Z&4NA81-{p&Qr)?Uc;ZO$mV+Kzp+}wj<&b>;d zGJaOW%ZA;m%Xd`&u}tSet;^{sczB=Y&s6{XD=4?GH+UO&#w(;%?*1$K#1eVgm{rWg60|hEY<_5|!^wbG zP3v~T&sn=i!VVHP6{ah#tNb_;&fx1&rU8hAC0aK9iJ)@On}R=I>Kpi}=??%-a9LD3 zBw*aQO_s^_F5xo{1LU?o4b}dr|2&_9Fff}QSVPvG*GdwejxaD6Oe(_n+S)s#*$S2Q zJsy88{Im5AC!f4;7sjz6X?}(OQAPJ%8sotXuT$)kDh@=%QUZrpxiR!ooBqkL*&$)z z<~&C?a<7#}IYpY+zg_S$DH~>(aN9}-PM20*@eXVtgJMgD$MGR0cJ?(!TI6V4f;4SW zkwk6v<2)Sv3 zRyHHX!0crz3&QInLO8tZ{|PVTK8^8ohWE=qc&Cr>6o0?Q5cLF6grz`G7eR8%r%b%p znV+O0quOYGTHwo(Sir?Ox?QOtNA1z@wJ)lT1bl9KO5WX{8aTMUwjc{{<d`0T+{uBflQP{rLP^t}l zIxQ!|&X_wmCiA^rutNP$ryxA6qwd2j;0SY{5L!GTRQ}BkN9ai5Rhar?Y+(O%{5_$6 zl4U(j$Z*}c+rZ?!EmEJG(01G&c|rMQl33#&HpNpwuZ7WEZV z!%6++>Q;LxU-Q}!Xb=Afp6U7v#9GQjYi)&1*>Lu%r}&F(;eke2#tG3!+C9Rn?tg+8iEX+* z3^I>%I`~Rf#LoMK?s?;oW!zsEdA`@WkpE1|kT@a!$d))=$kU`8IXwFV8}d9=VQhe% z_f(ZHIFQ{rd6?Ec-GZ*FKaAT1b%6c27sQ$+y98ygdJOhq+NWS==Y0(J2ZkL<`HU8L z(_u6=f2|ugRPNx|8UjxOxLV}8kKo`Ph}P>kDs&DIax(9}*+6AF7q@Rnsd5%@aM9SU zlY7R%=mmz!{zd6(0&B>tlyAWha!)gEVl_GkF!?NY-afD(4ju`(U~;nV{@K8X_+ebg z^d&s$Ft0w>v)MNW#x87}^k25-QWl9rbBCTh!UmV_FS&ft`zqx0O#v40K zzYU=x^D3PE0itSD+Kg-NvYV9l zd3fCbd{b#5pCvZ-U;X4|xMEge__j+16HQZEDdkTNj5?vsc9N?Fxu|peYcJ+Jfn?xW z^)@EPjneH=nR7)vq?|OXG2@kFa}%srA!N$BSQDmKxzGFEoE}r(LySra?11=KX#7H( z+F$2T_3Zif2z>r>FZdv9a`e=QSd$O-DR*i7f*%v8oQV+>iHofLU7lj6T_0+U$gjFR zkj6r@s#Bw4a-a%wp$X(v_e{n$F#>9d_P9-MQ&l}w-W_VmzRRUo54vAXIN3D3$!#t9 zaj#ER!ktv^`#w@XVU*dhJGrmzVsmrqu~#(9Y;i7mbpgkh;O@Rx@i!KS# zlsi{LjL1nQQvwzV+I2<$_%a!XG4k5Bu?og*jM^ox;^Hc{otDOQp@Q?hhZ1G-Hr|;0 zHZMmiy_XY&ixD)M%Wq)#i%J1i$7%zW+`l!v)fQEH#iOb z`z77zQJm8_YNbUMK9?WChm>G#22SrrPuW54T&bJ6;pq`9&Cdq9H+WJ9Zc_J0eNwk> zXRF7%XQd=U?FMaEN5>l>^zFS33rtJe4?{V>3Y$Qbzic0AsnpG_p)=vJ!%gCZK)v(AhHA_=1u!$@`5laD6o`5OMhS7 z)c^SL1N!W|pE6$mEwUb}_h&vn$VL73uwDb#s!KOXPC{@4`u2;0)duu(GklV99^o8t z$`OE5F*>nFb`;fdobOn#ApmEEb~K?=R@Eq?A^e2VDQ>~qD<%L4%zrvf=#xF!laR>q zR)be}|KK*u|E6u+k2&!+ps%OkAy`*H-p&Y*^ds+-mCAP-S3{kGM!OpZ`YHaV^$3Z= z`rw1Sm2G_Sj#LFjYlKh1p#Kx25A|M0?(w=K!NN265YFLW{rytzY+*6=x6Z8^QshrH zuQ+FRNSyQW772@dmTn$$sb1c2#@2I|WrpW057C{p`E4RTFY3Ud_3G3CTpE|pBRK29 zWDMbvpOXcv!98U0ky=76;82xbGZGe`6ob5<_U7OEZ)rF9BfD+7)Mm3$4bIgD&C_?t z9A~qbHmVk}h~EirsWjO&vR%LM)pnhI>g+cktya4ZI7qO+*uYiaquQz3c&-jRd{?(X z-X{Ysw8(L>VQzQy!G4Lq3(&O^l1$z^mDz;|OL@i&AD!@I*aqx>6*la2x}nU~l3c|% zo@7p7*=oAG*r4%^Kpd*Lp@xak)7`G_e8Mj?`^xiHXdo15cPh;vp=Jr>{li^$5kzZG z&GgF)Ob~vyj79hT8vhH91812T{g+=yZ+6YX-?Fzw(GE8{ zVt|%fn(RTmzw*ffnKEDYIEX& zQ98dL?G5~nA3f;lmb3SRh-lUJD8pk(Q!3lC>j7c$X!&5M9QI3MB73M6ma%-}(%6&m z2^i}yz4dc!Jx9tv>F?Gkdl;jB(yC>KIC0d-z~y>;>}nbAxdfk_$)(>PK8QU(75rbc`|)+?8RvRpY7fBTfo()Ig=x~2}=OtVBieP{oJ zLfSJPnQi8+(UIg)`WYX!a7yC4#$?)^(ae^OZFS*89#OB5L)yDWQ4z#2y~ELLoU0Sd zB|gnqJE@h|;tYqQcQ2CYSTn?SMmIzfU0fmK*^jkLM}NuDfkY%P=lsQF{qyhMc~Z&V z=OXPFTh67tgwk1NA+TbaL}~wf&ED(>$eqZn*CEI9>%yZ(Yt`!$V(P9dmtXC%YYaz? z%bl@AbD)@b+y2;8z1K>TtMTczjGh)@;~`;}E9! zmQSfWaX)!hH7s}LlSi8h>U8;N$DG8*&jh`eXQLt)^wXmru+KMRD60LnomhWwXN&Q# zs{O)m$pU_D#6skKr+b`lFmU6H`kp`gtdFT^T^_tHf|1Y64Am!(I2=Xqvz45d6~5o= zuDeY=7}O*tfhZJEnt5nYhx8Yh0EO)&G2^yqBP!Q7t;CY57(z14$4Rk~_){yDtx!^!h{p#RMVFrVCq|QshLWQ1dvML5K z`gJzm`O@{~5vXOqo4+4sRrUqVjR;^SU)21|597k6aRZYq>5=vCR-0ef4Rv&9j?dyqLE2-6t?L{mG^?w1epY-2c3ELJ_xj?9H3 z1278*SLJ|S^+z*&3B8I3W6n+N!VNGx@)CQtoa9x%;i_Pum!^LdjeZ4-V6r6jzu${E z%RP$G5BuN+&7`uzoc(T3QY8|3_O7QIb++te`vWb+Az{Yr&xxM98pD@LqRJ4vfo-fa zKFCRC$`>r3(LiFuhM_hol-Ud4{x-Cgrm`07xQloFb=k)KZP6U`THm_cCiKv%Tx^Wg zU-#FoOD<;Wiz`og7!-5 zA3kQ6ueK4lKI^T{Lhly)@J5ZI5X4B3jKxpsX>!ghu8gK5f4raJM>=~~mieuNlgGZc zzxjlrxAv7rnqSMA8DQL^@C1I9V3NE8lVm;OSA@9}N4;t{7nXY+Wn!4qaHbw0JQr-zaCeU$Hq#LF!|{>@adl1^ zWtG<*23S2sdW8HV2Fe}jA!=@7TZFn?h?TZ! z0q!4({EWQ+UT5YX)$5HXtGC&4+kVXBzw`LhhwkA$a5G?$)FNnly^$o}k*+9l^yaLF zt)le+!9kmNW&a<>qq-o>7C1%$Lf#7`M!}V{R+3jFzvZ{zH)&9MKN(d+=AxOgj0@6yS0Z2)AhlG@rbW5kSbc0BDgS2#aBPrb_aQ6&g zopXNo{$Je}$IqUbwZChvXFaR-VIac+buX0pY-U>;srpBhE9>w!JCq;b<7`(^I#eEx z4np-SUg)=u{!rTnHFVqN-P={ZY|MfrAus8DzEr)!+EM)qnl{5SqgA_89m|iuMlrkC zgUi)KC!sQSw`Y3C$?kBsd70PYa(k|^mGOriIkcucEW*C#@rIt%S` zJ0C114KHHJznpiPl5Fo4(8AZhZsd1eYe{n@G|zwPKfXeT5hA0wQ$ULWPQm%d1+SzQ zRRup!nn~%?_>wog2A!8GAlLNf3w36&8U^$g zOJ?w@oI7stw3)$cNYrp~*7Rl<2fqTnAfULR$o1%A;D|`w0hcr{JTyj^s&{~#KUx=7 zeTFNA9v$R(zHl0GZ}oHV%Vo>2!_-t_bz7&8p=U*;Npe=vpqI5!>vMnscldx1fmP?( zoEpDgzt-bsO?fHTQJmu}igU)&9R^AiaS{P~1^g;{15$?4u$Lo}&$J&SHJShxHs8W3$XI|48-jG51vR_^lPuUx#!C-ygArRaXj28IwDeg zwaG|-*L~=3N3u#5;sEGkqhZ89l3kxrS2lm9uA0o*SJk1xK;R zSq$7i%zM>eQ8cXDZDZY8RxoGXu*k=Maelt0H{*0R@3@vZ#U^wAZeWF}jJO9qkKw_2 zv!1L{OV_5%`D#bHM%eZ*zj#k9p`{EvgTbv$kCGrV+4%_fsu%Ti{&v*lX0v#umd z_Y?LF!n-Ti)FMd=Z6&71`b~RNf&*Td+`RE9$UPU#h<26*?%Z;AJz`W$qP11Ly?o}^x zc)wYRY91dP`vz>(WH?}mg6lFJ?!;@kX^+l!0zJ9m`EWltJ-L=s+rHV(_R-rYb$Nnt zc=WiTBA0unZ8?_@;TEcj+mk1hnJQT?Q>=_gY+cA@BZk9B%RAV^a}5{pBBWN&o+vS~ z9c+Y0jnU&~6w(dwC**DA);R@?l%42mWizxj{wOr(R*)0rQIqp+c&)hes4#o5AwL^) zwN1z4w9H9y&iD4RIM?+Mb51lj~xAH(`xx#*ZMaHrRPSc=@X1wy|m?f;^ z=w9r6My$KIaRZ1!0UHi;tBzcaSPVryHgmz4y}soe#UQFgH3~YeiBy+q56oVI3>N?u zMAQry0F}8p%--JHcUJPg>fq6Hh5BD`sf2VIYti7*-7a1^#EN%fxkRB#to2wRjeu5C zTBG4&zdiUapt@D+siU(1aK>iM<0oexda}_gwYr8S$h*7kjih60*pa7UDaen>C+xE@ z$qZ8l_zO?7vOcUwf5;wKek=^tX3h)M@)!%HO$qm67ul!W)=oPj!Fl;!nv1KYw$9Yj zVaOEBczM&_am?E+=@R2yhwl>LxF&b8jQLrU*qgPE`IXp^kDDH9WheA`76Fxo%-2!# zP%FNg-Da{TA(zrpn^c5&T!$WOig0{X+|&qm%&*piDTvm-&pJTYv|G(mHPjp%uWjT< zK(A*}w^~#b_jq=@>3UKZ`ofXE#e<|*f#0l-USZ7#oTVFexv@|cCxDh!i!aASKdpK znyL_?!rAX8tv=Qe!{=4OhGT3!$38w~r{+3~Q#>5SKZ{L#b=UEf^_d*1!W{aRur_yb zL4ro{v-!BUBwgAf)qAQbII$R8zHX_w>ohyvM|$oou?z>Fl?ppcM;@{VpY*+mAs620 zTQYEG*=T2GPaBIfL^CdAMjS8hTTOm-J|wGeA)-I9YJrpH!g7H2IvaodbsE~Z!sqer zu!!ULaW!2-RK*pzDFF-qvaE*sjo_g)5t&D+?9SwZ)i|eJH?H9#HI&yt%O_WVHg{pv z0&IsDN>nxXEX-Go+}Nqi(?1ruD}9GdwhJ66QL=c%>PNm4z#(}KV7;RLJSs1(1j zUul^uyy&a1n^vHs%=nR>3wxKTj&F@r-x{d$mQ@5>hF2V}&6`|BB1_BE!mN7G`s?>t zqisx7@6cQON+LYmM6d$jhqli6G6L_U~!9cs8{b>_YUSJzE}BxN*3W~ znSC|>pl5ueMX#nYd8}?DWsMdsH)YDzqS%+a+8YpSqh^RTt8E*rrR_goZ|e)abC^2o zqlF4$w0}ABHM9eo%ANZV!=2kcRq_NYf~uyB>2rUy7Ag}~?JLQ9>(44URTnRi3cM^{ zyKvJ$A7-~#d^fg@kce!J$9<%^{)Sb#EuuBI)OR!#St&mQSpwT$$wl|};TMM;N4<<5 zokZxv!I$0&rAR9c33)KSmk+dpa88ZZD|kG(M=;idi<6d&-;JbzG=j1O0rS7#8v2*f7Ugd~Bi=CZ_$moY71I$)V{cRK6Gg zmw4F<8t!$)1`R@cg9jc36f=~A&4g7(lv?5}`t|WFPgU37)W@_THL%gxnNiW)hYWI$-UkT=)y%`=V<^x&X4c(Sph1&uv4oq%1h9 z-G&4F`QF2Yb$>A0GoN?QakNmKWe`RiK^i@unF0w9Y33M$xS1mwMnm6&RM!h^gqq@w zdfm8Z9P&jvE4kRArw$OK?yOXy`HD=~631PMp#SR1$_Ey|;_( zfOp6Bd9CX~(6DrZ>4!6lyL6k{j<{|g7Vw#3hUHcHEuZzWPoZE^`Y>lVFuZ1M-xu=1 z;v$jLVlhf1Pj?wTKId>s}MRR+e>kRE7eY)cn1BDlLsu!0l!Mt9oWZwYp4yalR?57qkMQ#i7vd};cXSkI|m z-j~|EUD`xwW04GjkH=_{UT`L>CUn%ciZIOxL>C2j#8dbGKz)5U$Sb++5_ZM}OEy=; z8pH9Fqgh{^-ow5s*^*xDRw}L`+SBNQ)H9}4qlCMH8Q%SRjA=&=VVnEa{)(x>sOA0o zeHLjMuU8-6UA927&Yh@>@YcLU-~JMxCPcNIN0SW^a(W2C&g8qsXVQ=b=8U%#;I)tY~A{K7J_?Z%agp& zsb9=Xd61!mY`VMBQ9jV=a%7w-LK7obbaxB{PIoHfq`^cxJ|d2r<$Q4-OMs3Mul%ln zb>jnE*m6zHw<5>Euss!lIq0VxZFbWEZ+g0BCaLX6c(Sn6LfOGKmiLrz^4vlXO;A1& zeyVl&g!u!M&uY&g;=`wr^CD2IWVh``6iN>(^kZI$e0eF@+q(%Zl>k?xu2xpTf=+xJ zmuY<>0BOIe!h59x4^i5Xu++tuT*N;yyw$GsNXf@4~pLcc_dXDY688PpTr zinKP(4S*GNr3yIYa9POguW()%oL3P zo_9NQc!P-3viF^N)JZdTSkP1MeHz%J0jMd2Fj(LU{Io`5t}vA`--AIpu(_!c%MN+ZmsIfHn8V{TLm-u0zCa_s4JtW!11mV>5+Fnis#?9ps-SvH zP&7@zS-?dm>T8_n8C}fyy0o<*#qr=q#>j%%dX&V}nk`Ndf*_1Av(mmxScw298J-8? ztyQv2J626ud1pfxvg9LVJl|pMduYVQO`oT4%N;yZ7%FifAU1+{ zI>+FK{f zpam57>wbSq~MTTy-`J69W#V0T3`;FZO@knTg8P}a^nntFqWHZ#F z=TZ=PBO8uA(8^O)qfc~pVy9&u<+Shj3D<{W59XJ61rr<1W{Eq?5`3(4hrTS0kLX6w zp~y<*IYmLlw5$q)(q)%j=vJ^KMp9;gQC(Ygap zE!6W^jmSg{6(aVZxad7mrAoAyJ9?2gXiDrNBO{=ylyc7n%U;$>qm^>U9=aO$FeGU! z&a-@tX-(VbVX*w*9;j4nK0$hiVAy5ma8l^`%k|rJ>_z<|rQD$-#}7DcJ?g&ZZ z@g&(|T4RTKs2!Jr$+#YW?d18|d{W0HXZXDNfZAT`qNm!9ymI&6vSHR<80 z2aL@6*dl)Y`V|FYi`_^OF~{%jPvFpGa3C31e6_2d44aJcS=$Iac|>vvTj*wrf+}}U zgciqBe%HgWSJ^~`T4aoQrrdM48j7Rl>&N6XO5>xB6`Kw4+oL_vwI(7;b7rJ z=7$!)4qlaJM3KVQ*UIF`jOzx4?pX?}Bh2|DNS!hGFXpt@tkOST#dw&)uPg2+Dn;if z`u$WR_zjUj62Ir8X8v?Z)_Ks2$U#}o<;6{8IMYrWH=VZ zs6+jR9W|gHsK~l80g_e@N73IpcNcrRLwKv)e?n~XT}@( zlmUl(!9v~YS`aze(#=w0lxnn^%c=(m>oqUWf-F*Yi zIGjNaIe)M5eI)Hq0VSsrS+B*sY?c2$77vjPoF!PEX0j_ zkqjzX_57H!ATr4Fr1y+SApi8L{kDPh2)slLrhTy8XUwG1K4Z`z`cV4#<7dWt_d>_; z1|!t`-VqEAqxkhB801J-JOLokofUMXSxtmX-Xf1OQC&$brIhFpvUO34VOV}<9MmG6 z#PY=E(O?6|lTYs)hyVz2S|soc50d1bbU!L*`!wYLB#&RBO0s2)?sY5y*|%(Pq}teu zz>#WET=59;pc7?#k1gu`JX1!!`#rIxsgSOaNMflt5{IDbaW#45Q0)im<)*@ZY$_Vb z@1hd8&o@5H6z~iZ>Pgs>{qB&2NH}Pa1tjUN1VWQle)uVT;;}Sl`5_aP-st@`j!!uR zSZQd3N*U&Qa1s-pUnKBEP9>^z$IDcWjU^K!29TjjSTwuej}t!2d~Uq-Q1+9@JAis0 zMSr8-Qa^-x6_ya{sZ^?dP2&`#Q>9hEQxYPghYb5ET&1!Xu|l<9n0{_$Wh&BV(%|1!d4b)&*pc$cIM^bqkp6B%) zLNXDC^KLs7F4kL4N*AuTNUbhaq{;)eoQ*Chl?dy$=azC8NAh%uzw*D6NWgLo{O5uLUouJ@reJEv9*c7r!+*? ztba?X#9@wb&L=M8x^SN33jJQ=A>$QvE)vR^pB6DCQ>0^msIk^ztxc^eCb7&cD<)wL zM?K4_Iv;ppZ0E^1*rMe4X|Yq_Y0eU_FM`BcvA%qjvx^22>XUiIxo|FofwW%r?S+g9YAXx%W7R7(orq^gS* z&XCAj4H(j;t&!w2W$&$GP(;n+MSS4L_>QpOUbjs7BxpcO9 z*yZ$b$(T`&ILn}4Bd(q9W$PP$`sug(L*avBuW-2p`!#6QSDQna^pRodBU0-D3V93& z)9=i;-H+Wyu5h*puJ?NpNL1Y9cQ#@|m`YbYx(hRq_pX|487`vs1NH=cMt>BxJWNUK zQ?!~EdF*waHz_qS`nCl}Ypm)&zKy7V7(B_?U#>gf?hxm7+G!H>JIf%ZRijNUC9ha+ z5%lwTQSNMDadER)aP7$-kg!wE zgCxBo8Uz`e7`kF7RV~=fcR9T9NLBf^I*6GlZID3by8-Asha_lQ!st5&Cma;ZaGPdr zwPf>CLLjwukJs~xJN#k$wvXb~EPZy=O)9EEVwMzmc`7MFt2XjdXD~`xt2R>|w32Gx ztE+h{>y$a2`#F= z{BCN){{?Tq_`AWV0q6>l8xiso&O+H{>n0*bR#`5Y;2_~czaU%rBc0GWMJKZUcFmW5d2GXkkSVht-LK5 z`*Y#ZH9$S-9s4O_=`p~X_px&X16rKsaqA5zmjy-DJV~h%#`u=m`<=cEHtDIw+kY3NE^q5MV?*af z#P{JhC8Gen9QTf?Mx9)so_jd58y-kD`Pz_}BjiJp#SRGHM){GwptL~HrtCkSY#EUI8 zgs67-j9me!zPl=$n$UjVTyK8`YGbC~}RnJk6=mF;M3O+xeOLYy&Ns-;vFO z=z6%{rQWZ8zRHI0lW;q*3B(qH5lm{_L_GM^;I&4jriTu)FzhN^?o02{->;m+%(7tE)t=J1cI~~Uo zRr_beAXq#(#x4`3&r07r27|rdlyV&n2FvBQq<%9cbJAi%_nQ?I;|nZCGc+Pn(3Wq& z&03@;5K_<{cCk)9m$t3Psv@aoq$cE$x=UR5rMW@9P9JJP8Iic-K;jIq>Rit!%=$^L z0cC|gdT?aNhE%HF$}^Knb~mQ`jX$JfPsxsWx$|ffeq^Rc!+1=o&t6mr`@J}dca|dO zmO6UYfi*aDflgQOap2U7TWtnqp*l-&{e65jx2wN#g@kop>LJLGap(sHl;YyyB8t!( z@itB+Nh+=3>srln<19tfGhgsMa}u5U)vX-%){XVKpl({Ee~C z)_yA{lNv2R&vrYLIwx^q@MJ|rh>AV=wmhzs`5~U9xfJKdxx0k9!AU#qdkOPw*K(a+ zY)4ldvQ&J-g~#&I1Lgn#-6#vuS%RIe@s&~u(H7(-bHV}9?;|*JWh&S!UI2Pywa*_^ zh6Ecmd=Asu*dS8z;U9HW?kbW?n*dZ(>q1n|HiK1Xb`l(Y4&pZ@r|_-XY80scI4EX8 zKG!_B8=gy6{lJj8ykAW1pxFfBNsBMNMH)M+?g(k?`WMp*-}MJzw@(-$ZXYx1XMPh7 zCl2N0%N>01csMASIx4LJE>9_s;5Gj~T-kbhSkt+S;CuGVkcLq)Tbz6f>%9BLPe`bj@k44xo+l)a3_ncsz4g8 zjA`05ZC1R=FiE1z2D7Hw#*?H}Rdq`@7p+rQeBAfzZ$;?2m5aLLN+0>GFv^h0k9)hA zBXkC(+>DNue z#!b^&o)#!A(1g2&aFV4Bg)bpt7RgwWrzOg~k64A5=Xf{ux+gpxGmKkOA_6`kM>w6= zn!M&|K{vs&a5lgIwM3gyZ?}-~OuXt8i7VB20oAHPYR4WX>mF`e&5;%TJ|dV^Wt49G z=Bb95Cq)qmgIj0VRD@|PDs8H%A1}%D-mp?xu~B|fRi(OQpPU`4!c-njQtC0@4s+L1 z(lg#Zltyolryt^c_MGv&f_n9~?Ym7j`F_ORYOEY#ykH3wS9fzvbYY-L3qOBe0GCYN zMqLL4;Dbc=F~GheiNhM@-NV^nd{V^Qc9o9~=-WAkjmxF9lM>0fsgtUWwmE1p!{p@K zol#V&g7j3v!#t&szsr$l*@}&7@}?!N`*;>|9b3vOJ$sRf(Hs}vj%k(K1j-f`nMR zz6oRl6jKW0rWfq6gzb_xlt9y>xP#h^>m5%f59JPE?ge0O+aK#)xHTEHzd{gz(TLQCz*vF+pI!g`V>PfK%K-Be&G1=fk9~?F?N~ zfp@5=!Ki~#o_kP%(km_g-GTt{IexGlrK4=V-i1UxQ^gBle9lA_`$&>fJ3(03cVZ=P z_Uy{Ohf)NG(w`gSKcRG3h;zTWJ(Sdqu`DF~?jCKn(2LKFnxvm!7-Tf#yMLGHkhcqQ zXq*Q7EaL^lT7m$8TRd8tV7qN6kis?F)L#aEC6nSH6Xj(lvbcea*COficcJj_A2|8q z2S1?zEi<|aA8vg!Y?T;*(~PW}gW^>bioF&GO%L}$>U~l8)niUau56(nP1|G?$;@wT z&8nc@tVpQcTFyg497u}D+b7fHP=M(Rbzi*)Bv|@;Ai;zz(qU@Dr*_Cp?*|62-U80y z8JMFinG*_F&3A}X=FWUf06~199zZ;mE1oB#0=H*lQvoqPjDLA!Go8So_g*%=Z-X+@VDV{jjmrnG{H0p;F8=WbHCLPU z`?@G(bSGPB-qqW5sEzAw)=zCfS&pW5$5dg2J(?$`2h5IHsf`wtuP}P%lnk7o8ip@x zlqBaRPBzS*AdX5Ybqi6(@8Ew09IdRA;I*?pVIt1)cJlsLL^ck+q&Mo2 zA0pJBwCA%BWJMlgURBaZfe^o|9@pD2q!<4=>oI3;ME7nNHg=BCA@V>H#eqIRIEg&c zt|W)<{SF=OljHfJ-HoPxCi{>2O4>tHp|XXN zpj3zs6D|wwA8my`XLYyJOS5?SJzFrrIpGesxRkE^>9Wv;%V3atvcJ{41m{cG^S9Cu zaLst-qx}Nka}*Ftg%fv(e2~54RDemhCcf#4nKn~AL%2EjF?IX%=-5DQ*4X%&JO=Gd zli^Xtj$UUTN~1E)<>5qL2eyJpgF>GXYfkf959bTVdU`V*3lW`JI{OUOV+`oEm|b!{_qh2F^kyY!>Yx&7E8nw> zhIwE(o03&9NQugjl<^K>7ouZ3e~%vd|(R2CIJ>}=3HmmYS1(|n#>zGs%h8Kcz`m!luR zc_#O8Gj`+g51F@gR;pCr7%YwDwKu0ldtB_PeO~aHZjtzWGayBOX^>G-#()S+sz+G5 znnqtHmDN5*4KqgWrE$sG9U8>8ELUM{o)hG?S71#JNFwH>1==g`txtO?@K%%sBdX?o zb$(LS+YZGcH92`!WvjuTi9h5?J4z4A9q@~sVt*9oSg6-E-!n#7-sLxYQ42J zTEpmIan#McwAmGlR$lg4gb((}N~w5k+FQ|lF^U|3$SNCvNO?4{z;&V4UKfs3>w8sF zmi3%KY=xck>1Nl_(bi1Bc@<^vsj-&LCv7gQsg?OTiqY0QEyT9gfP*NJd7H-_>Aqp;Pl?AYtza7VJU01?`EXfrDe_Bmm^lbk zKKjAjyaa8LtYkn=BI()iZvDF0(Gjtj<=KJ72i*L*e1eK~>@9wB})_*iN4 zdSbPn?r-a&1p7UQ2a&*iVSi-!MwF!R0`|oMW9f&Cw}I;?xoEJu&kZGe13pM9IXZjZ z%Y+5(y*KUc%aRgZYkJn2UT->3PdYqtXDE|t(%VuwYTdn)p;1k-Voj95Uz5lo?!?49 z&j3nhZG#pBEra^@t&mL-R0dVaK%$aOX^BHAn$TX$2LjdVGFCXJ64BlqtDH)v?ot1^ng*-uFF;dD3}l9^MFI zOOIMeTg^x-r42IJqa;iXPn0MyP)v+S*vEz>KfX^7j}tY&pJTc5+A3>)hpLoQN8YnX z9jTP_x=hc*J8WpW0l zHk)3CQ0%CL%vmj84EVszWe{FWIYZm9`&x1YJ0!=Y-r=;yPc+F+_|hZTpNp%ht}CQm z@jRgq7+M9s%4b+;_j|7}drH=d>m;-9hHJ7rqSHhVgwAGQz}JgwPiE!LOdI;HINFLi z-w7H4O-^{nTJ2{uR9xKSk!c^9k7r2NMzpo4pXqU=tP3?0M;FNnI9bvf8B?hqn{mEe zy*M8&^M!_r@tGqCWKp#wHTOuE?P@kQA~}ha%y8s3&lioiQVrc5ygieUlaks^X2@!EW!C=V=G*Kw&bG9p<<)X@eL{$7m0%H4q+Ss>M&;37aoITlprR!ABdJsZ{Rzsyk;b2iW%=&7_{VhjM(pw&`n6stEBA>TQ z4X$r>t5U_8Gi;A?A0+wYyA@(N4ETIyWlioUfC&%GGibV7=_c$YUj6V=VTriRRGfAp zw6Vk#`8n@`u}64(otx9e`9fu4+J|b4WC|P4C1yXd{q}J(TQZ)S2L`%^m;$QHA;kK4 zX<~T@O6~nU5i>+~Ng>}q7mV*H^KCz`Qq(`?m@ki(k!N}tBf-_`FS}eTPmZX(sc%Y% zRd1^R3;Z=E^Y{S$cdH+if~FkUQ)-mh%-XC?3Fn4})CD_2*@Nhe;-@Lz;$#Qx#Vvp9 zw2gRfPUt-g?W)|`EgkcE8LFy#M6_Fa?49Z|)qZ9C-YB~#tU5u4IYIx{Y z;_{xxjVjJtv;r+@^&|WJ`Y_<7BCIs-0r~pZS6HG{k3UMiW=Q+0A$+0uF@&Fi+)qOo zt3FJOFMZOR%e-@|`#o5?5Fwq(?ioW`n;R8BoU|`eIwp>28!saG{nu!sZJ>|+K3~J| zf?)$srsQspunPKryP+e-3t4TRU=Pn9q7yKzh*Il+=}4x^W3`hF9Y0w@d@GDLMT*D7 z9}qMA0`0bR^muoSlun+(RQgdRsXg#TG&%mQ>z_qRpQJpskNc*44&_B_vLK)$%>Ky|(dB8vYpBF_86J`F}iIkzM9Z9LbH{R|?fvkI~Ir_U$l zEeHm1&89U%wr!C^-T6O~(KL{0qCLFh#~`$iPX!W1=YHvn5c=9CQ1s!XMoiTBoDe9_ zFL~G@r21kml1Tj&O}dr#W#t%R;`^FgyNxuj@*WuRNNVLPy4UNX!Nu@DFv8NzKS-qp zA(h5k^1Ig)##`pGa;&CXMbxXY4V&kP(#9eCk`SZE` zH0-%?{SZn=QVP5^&gS}#?NUM)c)g%wL8@pu|?d55IIHIi6Y?G#xid}g9D&}h_Lo83x`97 zm1k*Q8unQ2FrBBp!A&nt1h(^)Hw-t(U4x+w#85JQ@307F{x zct@6MfU|NDz~}0r8RfOwqtzeURb!(W@p4Vi7+F?}Z}=M%p#&ZUOSy9=5;*eX?zxBl4cwh-Z=*WN53}hQWWCf#DZ>sI&Zkr7+k<01uG5hq-keE0~!9~$gD6- zo5V^Vp>VD5q3OD`5b(L0643fv$wK5CC@!JLyCPRG#CHjEZl~{m7 z8HQkofE!koz&BVr7WJ)il)Om7tTBIV&=tJJX)4TfZi3{r*vo-hF*WJnI0MR&Px&wr zpi`FD)H+&r|6bd&sZl5M17gtAR5%zuSnoj%7jFhxCg2Uxa7~6;-4u8bhnxF0^5y9jH!=q^?GVcnQyhCqD)aBJQq4@QaD@eUEsl=H>06I)Bx`1eyYqvQRjBkBhB zN@z8cKL0|Z%q6Q7L16{YS=Wuo8e2g$Mr>{Y1f9pTr{9Q{{tM5jxM}Tgha~nB?EXGBP+g8!yhHiHCeyl zVxZF^&B^#~KQSQpcj7!TKe) z?>vrolJ~w`?@amqQEJA69F|mHFOZ-d!Qdc?}Gr7vqKKx@3oUQ5il>3N#JRaM8gL- z&CA6TQ@$JRBHI)0m__ZW(5P^LhOc1wK&1HAFm4Mv+83op1rW4C5tgUTgO0lkaTn3i;A|f(0?OON$LF3!P|6Q-m~lAm>|6kUjc12J9e>dmIS=sCd2x4$QZ9auCu!L;Jfb$uMd_JFR5yrxM*n>u;{LOoInh$d<+cJq@d~c)aoShXK5* zMZkDjL+}FM@3oU#6)>-wNkFLYW6ht#3{yjdvj4fXawnImw`6VrM%6j9xr%S!oFZBN zkzGzQ>m$3YWa~$E;O8j5UYUR1>i7V4KaDYOy{}~MK1_~T-YIcc3ctInTyzMK2g1^T zmrCE%fS{p%Q?tfvu94#8>P0{DRWgJ-HQ?$s{3Na&lne3G8SH1y4t<~7OT!-`eB1f~ z&OQi)z#H_SplQmBcOyQ|Q-Zr3k1IKxswbdeDr2$YD5^F5I>)_!`s9HjTkHaMc>h6Xq z6xRJ4^50oR_~~W$h57Sj_XYUh%I=HtZ^`aI;L}8IS$1c|oxS(2kon^`m6MV0Ol-_w zSieElGPN9>)Us4+xscZm5hmK@`!ak%pOHd?Q)ckoX1xrgV@-iw5{%=n~88i z-A8l3-uY!8je~_b>E%X#r3rg+*cwdJ9}Tk~bN*qaC^v5U7NjmU6^sLQDS|D+K+}ah zFbxP#Q-O>-@P^#IzFTiGS{qoCR^~+~*IGbi#Dy!*_~~WbL%m`BWMHX<^9A|yL55K9 zv*;z^j_pNgy_xJb%F838-sS6S0!o2-`HTZqLe!96FcDqjwN&zXDVFuSnDzX%U z;88UAvFd$kfcMvvKnju#gpaN-gG)5{@7M!(;(Kyi;dyXNaU#CPrm+tU(*6)SlLfJ3 zUy46ZW?zZ_t<3(eqU2qIppS`?RNC9CD%cKWDgx!^7qSm z{@2X`-E^GXRo;NNMSkA-1Ddq|6jVec_mmiPOV5z^4@$+3@7Gh^oQELw#hIlpOiUE-iWFkzGo1*(1A*|S z#mV&l!TJBC{Ffcr!7txhT8*s%Xl(04Ea>_dguah8`+fBVR3H9^G5FGo13>yWr+*1n z4>{Ljqh)_px;ob4zoQOu9OCZ{CP3Q#MUOsTFEEyI<(1wmPV~v}_iH5jMD7FM*D<_b zBiW~Xzec*x{ysMxnxa`sQHQJbWzP{nv42JJ`e-v7D|RDGE1`{Em4C$Xr;nO+V1M-K zOf0R~R{(^r*v6#X?;PXqBvX40cR*kL_6O810ztp4hRTmOq7@VrY#9f}A}povMFx4c1c-4{Cm4 zT@klH_l-jbYlDuXndVA8SOGSPR53)oPEb3In0cf!U|kV#yA~k$oU0G`JbuN_7vg}v z^;k;CJehSx32=iJH{=wEH(>cI)#Iv%pHkV{R87DR-<;B^#m)bRB4OXq$;Dxae?Qgp zds9@#|N9{~?}8BnHF3s4%(0h|id~>9`(-}>-x^iC{{ci2Q`lB-Q z-MJDC)NJRg2ms3H_lIR0bXWH3UB~_>Z1X;)RR}wLBjAu-q00_%A^N-t9Ti(%4@&8Y3wSKYZr{{kpNa5(eKyn?=Yj1u(<8N@c z#2_L3T?EJp2*Izi4IqLf*kPLA!TKv1uTu4wC4Y-@^;JoO)9}9~Qf*e~I>@YXMyR&1 z*Q%Va)9xzkAN({vPPu~&avzIaOHFV z`c*Ffq``0a@>oW)fJ5Alq58L?Ux@&4r3k1A(f^Apvfym)`aQ}1uo|deZy*kF^~oY! zm&V^p2ZZ|oyvE={83w%KXg>Ru5+o-da6YLj8?0&B9Lr(4R0M-akG-&0j5G+J8ELhpu;#CieC=Ar;xOt!4oA&d&OQ=&ikQPD?+#v?(S4VyanAeGVt(eO)^4(Po zvhHpF-R*wK@IcCf^ndoVNavI@NTvX%TV7Q*1@WIP@+w(gSg&3M0igI3aJBu@{j2_T z_^A_USgU_<{P(I>1dzrNVlYs&S1`qk0gnFGhpx*}l{7ddMar&&`KKZXPf@4R#LXkk z;vNHr#A#tcn#-@A{+GcJ)&M=?pAiKje)^Z+;DUVqd&2?3xes9l5Xu!ys$pqJlm64D z`QWP9+@#dxBD9V`unf-P=`I8ku4KY67wLHTea*2+ zrNXKn0G<8U^{<1jg@B$!Y0apGwMZwB3S5BrEBw%?HpRjfW53a5Py;W-izl1Cfdha0 zxLws>aObP4n7qa0;@Z1*ns!wOUqwLE4qu0=zfCd#7FcaE_&(tGXEL!&Ty6#N7Jb`4 z&6@!ACO9oS?>s!;t8+d(k96jCK3V34J2{NGRGGOrKFM>w+&Yh(;c-5Rl9r!|t3984 zn^1RhaQ60cc@5yQEW$^yeg9%HVMWKA?4X2TEyttF)wQ&v`jBM1Yxf~`+}PhtYRw*? zy7NRTd+S0-a#O1bgVvgH-X{WVJkYa$A^<*b-4}A6_)j2jPO4T1N(68-pYO{}bKI(V zy{oExgA;fz1b~2;N(I5HS2Y*t06>9P$4;sW?XBs1-))*O%27(^u8kdb`r0 zj?JoB{3Cx((xoLjsQEj>bw9kGErFTuCb38F^O827ZYEq02>&vo0F?3vJ6T+%|AZSn zb3nTMKk^Od+Vr2<2I&(v$&f+ux)J~kZpl5yq55pi{^sheKlQVuJB%3`WOB{5eHia zIL$HuY5G40QLyf-rv9f@zn8-QPzSI9JktV$$qn*11M8m=0+-l-c0ypOIBVWGKfa0M z-%{Bb5c501419HjA%#CuVfo*jk8S=HLe;oBQ%34_eXTslfETD~D@g0Kt1h8Il^-U=6;{b}l zw7Lo4@07mTeEf!cojLCON{HW+16*^60J>Q6YGSos4d`V5-X-+R{v%U=^`xueSs(d4 zBlKpm1zP>p_Hr|CLLv;*7=Vf3LyNAm}-`@IDo@8uioMKWh8GCf%=r^@{3a zDZ6~)=0CMvZN|UI@)rPCyUpL@7KG_KL3GmiF`E=zecw1DH$j%x=>PfX1mIGF802}y zPg4HcF(%`{o9@5I_Nx9|krKSXD7_E|hK^tNUWMY<91iZXPV|4K?oX_KALsRvuljJF zA25*C(f!q4z?%WM%U;FyS8@Nppbg==bw)b|cbjUlXZ&yV{id_tB+dNQ(*VGvU+n+O zAgRf?N>MYT%7kscp#Rl7!F%}MW$6#r-8iN&^ZlxW{YgWKsFDeIrdxZ9TDd~YcZ2@Zqk4eAS@_%Tn z1+`~ai3B$4SMvr_2@=2Slmx`Cy!-jV@0bHZKqV10Q(5j;b>9?wek6b@5F{Wj&?7)E zkSFj~U`v1qdu8|S{y!&`o2dS*b$_<;%^NfRkh`wSz_bhj;9sl;i~l}k{X+C-kAlSN zdPV`4$v>wPb!-4sXVvfE$8re4f0PO^)c=1@kvGj1jMTunJLdl^-*o@i(e@9ZfA;e~ z#=`3<>F=kpz+m==*v<6#YtsA&l)$=p^T_LJ(!8hyo~<3PNs0dnIXKgQ8((g+<3Aeo z?`7_;yjt6D*3BVemd69Klq1jsi0=e7wfkYMBVfb&o6R>A5rAgvWJtrL6- zWDg$U-!yk^SC51Yu8VYKN^(8w*x0xFScUT>n;xugGM?o z$NY@9x^-&`dDU1hDAdP@wk9u%uqQ5FzdEa{IA4mlD%ijtE%q}GIxO}(pG&#ayM)n5 z)vmo<@A;^6oNlLHd|AxgW+e#Zi;aXAvzc%V3!(dWcL}0Y5|rF84~NG7OL@O}&!Q zeh85{^5uib(D_`+5Z#;Njjh|j*aEB*7r9b>XAJULg0DZ=%0r>@tCvo~n{|!`RHr9^ zH$8S&#~htQth{(-4RO-B6%TTpdi=wqnTsK<{XM|eODS52>N+uB$a(Zq$!7ov=hW`A z7t0$nkN9{Kx@K(GR8r3L_N=GvN>?t%e#DiTkXJghI4|c|LZFh%Av>BG4+FbWg|fWG z5nH!rdXfA4i-wDD4jA1tuh^Vf=YCAN@0BsvwC!16y`y<)R(ofeex0`)xSBp}ptw8- z#H;@w_TDloj;>o5#hm~N5Zob6T_I|PR`?iL&pEI5IN1P|`k1a}Dp4+M7!8a%k( zhP>am$KLyneb2b(=Q)46tJYdo>sj-8)||7dR*l+6hpLEs7B$nxVjL+|>$=bckq z?yDa7oeWrVAE7#MK3Sr!mG!A%FZ9_pFQ;{McSG5XxW#wg_dG^TyCzr^~|J~n*p zj2D}(QViDdeEr~Gl4Xzo8lHyy$x>;-i8tYQeFBe7F7jk6AIWIucGe*xAmhNN4e!6U92Whnl3|#&9+l)pcY$*g=l0m-km-Z*W0}>&-?Op)9i^4} zqn+zR?)sqqC#+s~iZg-C^M&O(kA?P>O%Vq$GNAqlPu3sQejG$KtgUOt-MvBAy#@MB z9Q~eHa@B+0|HjVkZQt{AO2x~or*j?sp?t*fx1axBzPj~ay8Ea7zsg7d9-8%E5&h?K zv8Pcyp8cP${%QYDdBES1{R8Yj(ER7}e*pi-;QwC-0t5DXCh%+3gSFYiSl4}SXx87Y z(WkQiR(mIhc@sx?PRX+OUk>{}vZ6Zdu8-uL(rzZO3?_*GyYv6c24mg#x#4$mFh@Xf zPARe{<}(v`TJ^9EljHxb_#aI&t!oC~g$%`}GNdx->_CQ+KW-qvN?0B@5Mdi4j~hs^ z4P`1=V}dT^aRsbFTw@8r2s837Cizz!%+g-SJ9J@5Xq8kMJyrOPZ5Rf4tnv3MSiX41 z64yc;_Oh`0!=5VARf4?s7u}w}u7PE84dSpGX8FH0G=FOnLUbPwvwQw@7&EA%va28j z^YNI9zcurJYxWfX9>xLdis{8uSBfv5jww@qsu43tzuldL_h4+}UEhcgCd#;mT@^u(lq{zO$_OCnu53@x7 za4w3RKqIEBQ@;p8Yq5(}LtTX~i;mfp`}5e@sbK@mtB#lX-#aC?sl5ku zH{roYkuy0jXtR}qUlH=^Ncxy}Gq4UEPj7?#4oIc@51!B?!l@}DBH_cKz@fqRso^BL zj1u|F;NUWwkl=`5C0_PyZ=GE2+^oT1cQ>}DKVDWZ2m5p_1G{;4`~b>5F{0K!D0!c< zQaUHe00wDv^Pd%Ytk+ojZZ z%HsyxbYso_LfN1?@#@w0^EIzz-sN5WtW!_5N1E`D)RYWP3^PHvaF0L!qYFyVERQa+ zM;mJR<7ae_z{Z|U`_to&Z>)!LYOiAv-nb~?LO;@qR@ap}tu2w6w12^K$8U5H;V$Od z4uQin&ic6o+vQl*IZk;pefSGcZRAvKXz5ngxB9@$An2yb!tuYz?7eH zSw%v1Je8Z&ZMR&r#Dx)zyODA$j1Ul3JDP4i(ucqNeDGpmL$CY!mD5ZH;;L8z98{T$O<(3b@FaGd<5Md3w z+cRuOllO(|!NVQdnl-vj#wR+~I8yydn@AU(`|T7vO0A(!V$Y?9dk7jZZ&JMr+~M6Y zKi5{+!&w!3lGf8tnZJRPQD60@Z_sTxHVPWqic(jt6CJ@|kiys+#j9jF7fT8h#4fo4 z2l(R+c~{oYLxEYlCA+&7iY8xs!ui)qO4`crZT*{@o37XEm&Jrze9zCCE5)uZhgBbD zTD*Pg(jAuWZ_nbKR!vkZMtGOog9FJ%cq;?EZw?A64=9WS!&OIk9}Le;+I>!j+cQO4 z{LhYPtur11-k$gORca7t6-Z`g?t5C1;U3_g%#*HGgFoEOMKTHHCr}l9# z2A?@6uTJ=0pt!ev3k-NTOAB`z;dP>D^Y`&=^>uCCWBUS`W_KAC74Y@+ae=+O9tg{& zvbyvF(>9reIp~**5~>}!bVheQQ_uqyIfJxPNn$(~4>A`(&4kv|PR4=FSKF{Nnmk+{ z4a-e*rIGWV?%fZ*WNW`(M0x0VuqW}EF02f=Xf}D+<)d5L*0>y1ZTyiucUNd)?Bvuw zF#z=Xk8=VqR$#+(Kjdar9rRPWbw|z&qI^?s?<(?&?A|r&G9rN^j#lLDOh-b zNUSVWm@3;(N7q4gu%6B?Ku>d0(L6fvp+^8Mb#zsZ8~b;{g4NxAPk356${Or5u^Nn* z`Ml4}tFt6?Q^}F)s6BB9{atX2EaxX(aAyh0kx1&vq{r;F!ozd>~pPl63A@{%2RMpHYj01aMoLR9K_h3l_Rr;pRB32cMWt->4bOs)bQn zP^x^tyNIkw~#Lelfs*#tf-X%Lp6tgacRf zh`H+o$5sV+=fEd*@mw1ITs398jo1-!Otf+c0{^c_#DD_LUm%u*@LF zfVX^1t#}H`s66pNajQx~_RylExWFjgJLnSu44bX*PU>(r_R$6+xc!b^D+1}HyqyS1 zq4pR9y_d4YKUE$6q@C*<)gL3((;0+(rcq~#j z13zpSg@Uze_IFJM=4q108bUYnW_wQBD6qtTwV9?|=cv`bWKP@60f%k~=k>m>QVO=p zi{6+pe$}tH>Bv`=Zk1pjp-i*%NtP(ABZg-KPCsxPBe8lmg=y zgZvlF$vA1by+dX}Fz!sRaLr)c=@nd2nqR4z5l`AT3+j#3eE@SinhDtOR{NEqBI0^8 z>lL&Cw8)VM3mUEU%>;0Ys|lHZt`IX?2*4!8ncO&!&AgRDr&ssrH-Gl@@ac)3R{If| z5i?we2Y!O-Y0z?XOK`BD%0Ai&!eKV+c>dpQw7w~6vB}@TscT;47hPpoY{~rd76;aS zRWxi$lQUZx^l*~YSEX~O>9rL-LQ=0%@>efv!u?<7?P{j)#3f{7b6kHs>L!ih4-EJr zAKHp=V;&(%TNy}mlhos8aHoA}gIUShTOU{1Uwx(tU;0T(+mBMhReqGx_M?7SyGybnRB(U0 z4|ZM1p4I#u93kWd4WnrL)HRk^VL^T@wX+gv1@(qoUc6>v;NP0No5BZKTLGC;PkCGU>k$!w;h{5(&SC-wxK}&4?Qzcq>eaA_``jC?JDD>Oj?9Og@{XRz zH4w4hDe-kk|EzY#elO%Z#NOl>B_J}-jLRIqUaMA&X;vX2HM7rVApm_bjO)0^np+`0 zv&T}yj+I`5^&%vVbTB`fiW?Xjm7c~C^y>YZsTFY^<2jvf@evC2{kpRiG53$9RyM0vf14%B+feC+(2Bgg!7F1D>+$i+?AiX>nw}%Fg+9Vk`>X@mFF_FN6L& z*M=G_65@f*5l(sZ0Y@uh`djUTL*~I-Mm0~DH!54)T))qB8*3WVdo3@u10eC0GRVfW zU)Vm5NX&-$+qk`lV&7_DR~Za38zOFu5OPIV%$uo<@+uNshJuU$H+SH#$7;OIgN@g? z1KxrBOpJg($Kt6Cq%tZh%AWd zu{Q2|p+i{+;Frf6?kZe0#!`(n^)Nta8*=DZphB;KY;@97`f&lkd=;C6idx+}lM;B( z@RU%yFAK9~VPhVoLp!sU#R%;%KEds+(YzD`mTm&Nl#&8YI9Bw?;3d3g*~~Wsvrzbr zgNhS`1ErYGs8GbVDlHr^hF1hh8Z#!O+aLVnyV|q!Bngn3=gk1X3~+Ig1ir@yG=E?# zbW2S+BN@mjhb`xl0*HaWPiyoUvG8sy=DDfWnVHOyWw+G2JR%DIi^vp)=w|Q{(OTOR zqUI+=PEUvqpFJVMg&~^%i>TmVh}K&l5kMx5cN!J zgd5FDrBBmj1Vdx4$2XBS$}MI*F!xZnK2@O%W?)+q8P~U`XF4PU4=|IO^v;_Ht=FsV z&y(HGsFVL3IO}NWZDOzD4noV*SxEH`9D!^rqZ33edi+b6if4KSUZ0Ap`=O=+3pyw< z(Ho`)#Caj$`ts=Ky{>@<`kShqP|QnL!NL@q%Ibw#eH9C?o|9Z@KNgRfBqNhH!X2_? zhlx+TR?I??M)e*0ES1r>@8S3CS#l>1C5`O=1?Xnr5s+un6QH&yK;Rs%$KcF6g|PEV_kvRrcOmtCz}@-3;rRo#mVz^V{>p zpEFq1>1!II!of1+o?tf`L$(*yY+LSoOy$;dMKD3>)vdy=QXK(Xrs=V4HW}W+?d^Bw z?yMx-Ik{t|jrvMxM1<2}ycq+-JWW#LRP4AHC>urGJf$A5N%GF#*=Vq$CB7GWM>j)k z{D;t=DB^t8rtE9$IksaJ30pem8J;c0%Y7735fQIkKHHb)UJd!7r}Zqzs56cLP2*P0lcA7tEotIjRin_0V%Tl%q*g82SobM}427RI{fqR~6~&dD?X&gaJXozv8sOx{+S0|C;fO-kT}k#zAG`R`bx5MDrdvo9-x!$8@H z{}0ypNvW(kz>rZNSOZ2jPrP|I9^)07Ix_ZGQd@>d*1tlO+g@l%exoT_)x{0h2$A^` z>xTEGlli@`+5WJpr%?!YnlCHY*9Npww^WIbA~>S%c*R^&FOLE69`k~gD^p+y8C@}F z<0pIZ418mAi+bKBBc2Y&#Tw_Ns2Ln1BwHj_8j)pt)gAqa7JH$ z6E@)a4a<5j;v!p4UYXJ-L@t7)hpaZCeNq-X(tU(>rbxnJgrYNZP@Sb}6`k2|1CKR~ z0-gsUEY6VFyu$z;Om!6Rl2R$MVXEtcHDIh<#XE*0vhgZ{t_G}rRqdIK z0`3ULsISkJ?tVDsJ$rW7n;Qaf{0%2D-)Q%7s1G%Ms{_-U7 zuF8p8}*aXiG)hu6xqHu*87bk$&K-B>c1 zF&F+Jm?Rjdj0UJ|SV_H{*nyR8YNv7_yR@x^%z6TZpxyliv1!v9P6;(Dz(d7mI>q1}l z#=!fdgTXX0|F*lm;qE|xE$XgwMgp9XrW>6fL+^`<VI|YW2 znk+Qm?``ZqSYPlftp2+5p7ZH{nJoPxwvcc1RRcVDr)5m6-OIBXKI4zYn*JSMPgCEW z-wRWqV_n9slcV$Z@rV4{n1H(^*VhIIG4Nf4;?u>~=TR>M?{){<18T3@zqC-<=H;xxy9f1}Hk~i*NHdF=9C92C%Qk;3WG%LO;%}7wYit zC0aM6o&dso>dx?3nxlMJ#v3Q`edU$Xe%eNg92S$99*&!@rcOdsGP#J1K5a3J%-fg# zQ7@V>Qa<(``O#ZhpcUDYI{w`)>>QeEev)2YRhvq~XT7n+qoa9!VMRVkM7MB4%)vYv zZa+p`ZI~~cn~ql+Hg5ZC60(iLB23%cTIV@Qp>)v;D4$yC<>!fxm=MzTMdT*lWpM`LkhT*@+Q>r*RJ+txle zz9-%?H@+|KRtuhhub+GVmg?TaU?;4U#fKFcb{cA9hvNL!NkZZj3e;iB?`6U@bLQ?s zr7RWb<&%W!>G}@n5Q9<{+oJW!WX@$#)7oznFUspe&dQ7&jzc|k3^Nah@7>T>_^rAjNWmZSF5ap9E34Z>6hsmO#Jjz9)dbx?zqg`Ya7|t($}*YJM?SR z&S{A4VKo^$Fjk6{zd0WouvO#%`y772v*=?@d{BWkl(8)hMEt5_5QKN8Ymod^X=&!U z!fl?hgV~~OZD`iaWb!S)p@YJ!t|nhn=_pHG19s&N=h{$%2}1{Tk_{aLQ|3ZmMoxMx zQtisR8QI23LanM&maCYZ$>fct^12_ny|z(G(VMn|u3~x)c%fdk`6bkP4)8mswK6tH zr7U3HU6JKe;BYRNS4^a!)LujwNcfZ?W zs@|?lW0%*lx4h@g^N!Hg+fr>W`@Zp#dFJ_vZB$0Xn+#n8>)1vL*g!Msj1l=tU9|j{ z2W=I-IVwV6d{&`)dVX|8ASZ_`Z_HWrjT17m*9-3_;H)tw?9FCYf8qx3)?~E zHx2LGSjV9LhmkIx-!vI{W9&z)Hts%kvpNd2YQ@d0Yl*VCF(xlL6ms3p%peM}g(Dy^ z5LWmcJ30S*6h3%diNt8YS~|tBh(rEz{U+(hcx9B@IM%Wrlv$m@Y}^_kR2hY&kShTi z%wx6T2JsK%WpTgWR28^&)U;d}9;)_t{wNXy&Qf={iMBQ10#20^5r|bs1I3;ZYYU1C znQO6I)pU3h7&<$aD&+AtqM%>@kek5X5ryB&`Pf|j#9OU5zD_qq2e=tc07X`%-TUOnF- z%Z2Vld==m<$ryfKMq>H`v&tDeclXyp_?SoI4eXM?4pbcsGLqeJyU2~P(qecUSRwjG zO8_}gM9EZY+6aCu2st-{;1C;?8i745XA9|R53YJJ+$#AdvB=d z{lXm;z3hhTMQ#YOw%FVDAxbl?gZ{-KGCOu)QOjtNr@w4%DKWuso#@CcJ=rA6@Mz!$ zDG>+I`kXnp>w@=<)+Ual=)iKSMZdaQc(d$873jE!vVpXf*m9-<_e zXDmi2_Kgm5)q94`hwjeo3yoklN?W+l+p0(6IX7Iz@`r%8mRib z@?A8B+~h?od&!BpA$p2B#~x|4ZCIeSEWu(%r}2akMhf=MoR0 zyBe#}2Umr@<^GuZ4!T;3)In1$C=B$l6jJMdE^{S|D0eEikXGY?ASYpe#K-i7Xgo z*jcpu+*~%vr<6!rqT);+`nzwx_9RkWfm%n7h(PtWgKfNm@{xz3qW=)Qu+RUO;0;|X zh_&5Q2)IgCm35ls6apgh-^hYr##hJ)ek&@wis5}F3)V0Y(ZsH@Db;HTQ}=L$A|R|d zLP4Xv&A?T9pvQF4t+I~w`gGBdvQFc*a}3Z#J}C)5*LLYm=o~l(!*|+LYcZ|NbITSB zE>K9tJc6fz2N+*~l-ySRMjvMDL;^i4S%QT($QtHa2MkOQ_T1g&H}roB*@16=|M|D% zpZUvr6#Zw(lamtvFH7Fz=wFg&$Q6txN&@smmy}SOYEhB11M~6NOE^h+a!X?ATSq_I zp5po$&$9zH*Dz$YKjCtfOc;DC!f>6erx1=}2U5T@RT3rPn|p+)ANSO|>gTSdkbQke zteu&AXdr2+<++w%G7=rR`T2J?dx@|@3koNYOndpFt7ss~h5n7~w<;%&l89gPsp>Ls zF*tKci~$X$ZpeiY$z>^(Y7ph@)NCGMG&0cX-w}^-Pt`Jy_ zqFTJ2mk!JO2|)zL05q@_h`C?Z=j}EK@)IP>V%30|mpZJFNGsPLCXgVrN*`#mon?^(MtL5_Gr86f>|g{eS?Q=8_mEkBp~{ zG7Rnz0ooac{#J>l7WBcVu^XK7b^*D=5gM~huccoZjhVkFggRsA?=Jkt@ap`$D@bVw zi@nw&{jLOl7rTY=5pATmbgkn zERPpR27TP$q93YOa%8Lv5YjAJG1iTLp6`0mloP_J{a~z{A{MGKd%FFW%dJeJm`;Od z$oWI=xXAunbxq*2sB!=-?m}R3mr;8lLonyj1A$;3NWK{6fj}@1r2goEKrj!aTnzI- z`I5+r#WRs6SOvsA7uzZ~MpT2gY9-IRq5(?82)_+|^ww6sF3W5ha^%B;FaQ>WA+R6} zfdygZVptHCE6$UaDuxAN04xYA6~lsXKJfb_rSCI&RY>IjOu-m)?No}!7@3<0J}Bu` z#I!glG(R&wq7A)_@Dfhna> z>)Z#!K?O2kY(p;?p^>tEZa`R(t%a|(cs*sNR-3K$Db2`(7CC4a>W0S<8LS43t=Gxc zTEM?vjoLZ}6bNC!zFRjtM5v~q4#b*n^S&zNhSv@-vRBU5vY!2-Whm>n;8d?^5&r>i znUnf%a^(vtgPJv49nv67GitAYD-~PMltBR6w$-1$Q=N@d_1`i=2A0@d__+E=AQ-Qw zO!C+CrZ<_(7-7*F0*lTdSagQ$y1v(tsIg)sXsf5rUnAsU)cygJK1oa@K)YF;Cm#x% z6&M7tN#mqcsbO@j4fL7#qQ%LPTB`LaR~r@;7-3OCyjWcD3oI&pd5j96$EW~;MFkKn zDo7N=q5=pO6#$P>ff;(-x9^czNOqC)JSK zF!664MO6bfMI$9_))cRDrhfCQnlTRhJv2bP|e3QR73d)N4dCS4u(L!csFfSG)QBT zFK&P6`S=;D;uavO^;#+IMLtv)_6#paE2{M-I=>X^als~Lzz&_ODnah5IXkoZGPQVz z=v}3QtQwrYm}ILmr@Xp|SO1;{Bx|dsxrgy>xMy*e_n2wdn#qH&H;9jzP5Gqw z;J8DWu((DBn8ZFK9nnuCvKULodNmD_*e)SlZB9}T|}m&yHz z`?Z8_01aae{thH%qLq{W1srLMfRbEV^B$DK%TmPXrfmG9>4U8Kj|r;`;;$=nKA8z5 z5Yl}^%_LH-$Z8P10AQW^C^MZLUkp@lg0yc6l-0z)_d4XHlPJm<{&hz$1sE2bR?oKJ zv}wWEK>G%NZlOkx&f?Uc^pRNq9HY8aZ20J9BEwg=K#a=`v8KrTqs_uVzY~tzSD^)m zyO>&{L6AwlqP-!S2_7BJb`NVOwXsd6@`Q(}#X~Q|IlgAuaTKiIi(69udmWxqwxGp)g+x5aAZ^)>WrlyQJ0J}n4 z;S;b{UcdjhQr2sX@7dDi%T&q~`ERBLW`pzg%FFidzV2yy&k7Kq92MxNCVxdAZ!}4s zI4YfF0BbhRl44^j=nH{cXu#{IdoBUzvhU9UQodp`%}PnUjHIt@D8V+BzzBJLm8#Z= zL-+ib{8Zp!rG3iylGc>cJG_Ki)i-v1J!`I{OmPSgGtkV!cqqWk_vAGJW8$=#B4Zvi zX!cqD_gLBn_uIEWVwDC?dTN2)oFNcooB3>P$$|GR`^CATkPYvR1$UR#rSR#CUlMG0 z!^EfL*;!V%8qX!{K0=2a1*1S=kh6q(oSOQ>-MxKE@d4NOS_^((cjl`TyfrL;*4w$! zfO-9!x2YJpIIioNjbsL{(HA}ef^QJ0*91d_iq3Qgy66r}3CbW>+y@gM*mWqRL&2s7 zgL^79c!=LgtBuT~@V|T-5_$P^CMrY|anhMi9AbZ9y30pPpCNRngvi;~zpjj9Cixa% zEUzCwM&1K^D(`FHC1SWpu8`Jw*Ej@~9Du5z4zp!<`iN*R6>HV4YG5Cb9-I@oaERMd0?zs`b$darZ>slcKy zgn4Kf!0Gd3#8`FOiBLL6M-xi}I&iDs(GNK00*Qf@1qmLq2uM=Mk?F2N%A1hFOq(UT zaKiBmz!2<9Oqh(A30=XT74&WESX$ya4+1Rml{O*vCQYy2a{Z~0831|i5Hga|g_&qs zdJ!?o4Ujah*4PF^hTnv%zA#UP3~z*wmfI#mQ?QQ9!$R}yS>;;nKEDE+C12WGDd@+) zqR{fqQz`)Y=G%V;Qk0m^P0h5GJ?Z|>qCTT0aO@n+WFq|4frrr!99<8tpa!p}AKNsg z><_-T`|XXv7&YGes#5zSCu4822F%|46d;)P2gqzB!^fBJJ96b7Iy37p)H4kir4n=B$i{EceZax`H2LgBY^7Agq? zKaXCU)%p_`B!#bqLXf>TB!)hy4A+HDcTXBHCJJcFrwlTSaUH(SE2ArN{0NnBypo~+ z6#mgYuk53-XeqD!tkU}{?#cp%S;NSyze49+eiHilP;;2K1|dW0sAn<+xp-5eR&JoT ze-ox|&@9!WA4$W~qlo>0+3gxrAOW1@QU!gcofZ~1Y?$OT`b2-jrqY_XGbj`yld_dK zT_Ufa?n42A8Qyg?Sdtp7e&TH_XUvFMGx}HCup7QGZ6lpNX`6WaN!u7cf3+PfnnVp# zX-Gg=JCVjzza&n8xAed+_vxcwDVXkw*yEf!3!uTVrv^Vhm4sQ^ds_xoAw^mGueu`w zA~eR>!iSBwa!_kUVO@>|YgcJ({u$GxT}$E|sfuL+&*-#jB=;z5Bs+YBoI%H>5C!w> z11rK1($3mvX2gU}2HVC#`n7B-A=odbqzLYkpd|^``OL3K56d8oN!Iyg zNwpMnb*T`A6y6^X-7ls~EqM^`IQp9+8JQaDo}9Y3|C3WUw`YVgu=Bg$*Y!&vq@4o4 z1m?Tm-6;{ntc`ze$_8^QW?6!-<@GbUN0eW_Jn(OL&1jcbtvZRuXz_OPHKXsL@VVlv zk0O^Fc#OX3O6ND}OoR$4!*AHei}wdxhu>5Ve}u4X@fIo7c4W4_F-wHBdS9OJ%`EhE;*TrTOo@m9`*97IO-oL$g;!Z362obfuQ14Ob znDeomi6uDVLYRup$3it(~n4cMH2D!5b_QIS1OGr60s>pRA4#h^*-XdQSV8A zW#CzNsmZ~zXiM|M&L`LsUOBGWXTCV6hsKRz#8yV1Po{n^VkiQv1I z7`iyw*iEbyyqz{Fa1wFYnQ@g@nC71pmPLTN%pACvxS!*slh3?d*4wYjntyGX5)8@t zac|kbGdjMt$ye%o@7AtOo7g6po}Q(69_0baY}YDlXLNOx!iG*VE|;xf0lrcN)+|t~ zLHhYh12Nn!Gs(f3{jWL`NcmB~qOzYoMJ{ivEdM0NSE6sj9p()AW;V?IVXN-@W}#T! zXEaAKZEWD2>Vo~LE)=nkD5J={&-(X+;Sy1hiBNA}e@<&(k7D87S3!Yv|8lR&8v6!H!=KKo0Bm55Q1GQR> zA@-wOwaliQ>;8x|4q5Kq`!02)b)tIgilJ2HKK?O^-$eCck&YI9ALLNY`x+dCWYhd^ zxz|a`ETUDo+4u7V#x0}k?nl3I@%LTwH#%QKh}W-Xj3ggc_NJGaMyetzta ziJNU%7GF)&&`^0}U8bF*%Vyo9U+h=Mx>%8|vwB7owUG+-8qIUe<#iPjPn(ik;AWtEI7C%s2mLd~T%EXH!xjN>%ta^9rIY8jQs~up2==DiRs9UwRNYaz z}GO+gjkrAo*SytC*2DC=*{8b`1fQveJ>_^%Uq_G@nKXdfC@KY2ILtDl1 z<42qtw{DZ|f0NVFH$;k*F|@#*QJ=NnK5nAmKLtx=;$qVr55>uea?JIgE_{jJB(a<%rxXg^g#iFLrF| zL0~#CDWLp!)_7c^_Onlh;FvMXq!&Bs7GL!@z6uD*`t}#vzKeoO|9&v(9-Vm?dg8o}dzX>i#|*B~!_FN|dA+JTxg;sS=J@-_ z=6(9)6*fUQwVH!(i+}cNkUf{bD7K2>POppJBl1@>9guhx?Sf0d&oPS7XWjkG`(kZc%8-9luPSM%lP^4g1vyI0?%mm5Nsh?gNLm> zUW7h9E6?|Vfe!~evk2`yCU+<2i>hJ^A}#mNveF&y8~54+&VHo@iuiin?5@iF5PZ0M z=7+Cyxznby_q9GE1GdcRrGxn^2bGUwv20V=&K&$Nt~`=We{T>YwZ6?kmbZV8e6(t5 z@`|%dV~(}DBtH`WOJOfH$>i59nwX=5cxfbC_0n7Ty3$olyLk<{uSK7E=EXADPMw2j zf3>LO3(YC28y6P!TMtSpxL$Y9tv4i5e>LBBcdUC!PpRk8{tes6_*G^B8i(|^3}06g z>UVr^D>Kt$ZPMU!IxB`Y4+xOo#qhn==U7_!c3(RvehdgWR4b&^-xsLDH`C(1`5?a~ z96l_XGu-c{Cz(%T%IBbexg-Z1hx0tQS0M9x_94Hx#=(@)e{}W2uK1|K?epSm8|giP z6U)*fo6*jj()%s?oj=etqIzMuz_fD>9MmsaiE)tQ$;UlTEp!FpDsc6D zpvY&N1MGI+m<^GSMkrpBnAC@c;qZk6n-V6j;Vy2h-Vneo>}4v@ng?yQa;g7>b2>=> z7=V1V*`_~bk8tZ;5x#!9))7wAKLJnH!>IHZ7S6>`hjH6VXEO1Jl$&O9E_`s%1>evc z7_NDXgtz|!mWdbp19#;NFYOGjQgw!G4?RsPSw-Fb@kTQG%6S0SSSPJ0;fmG+FzD_1 z`|-=Baw@+D0j+A+yeZU%WmK9{xE0Hn@+5eO!cJ=+Qc=9zP(Pe9!IsMfLM=&Gq9~rh zG0Ht87Nhci3zt=voyS-)1CjuY;VANQ;5iT%_HVxc5L?=hyI)k?LIPoL^uSh!6VnmF zdJ=UG34^PYDx5}4mwdjXvK<_gF8XGNti$2gSKe1a^Ubc(uizIPZL6FKI)r>lZ2T6J zQA8KWN#`#vrZG>>NbNTS>u85pRe3)mfB1b&C&(0cKL<8S1(*I3Mt&}Qgi(9-QV2LH6o z>Kt_CqX#eSr2m=#o*z4#fU85ZrWJsg9$rx`%;r`Cw-EMeNg(4V)^n_mxI3A;br?** zZx~FMJXF$tpU(~2jc*vBn|yO*@Q#6nVlOg~oV%Bu^cyf%zG_b(@jDXe2btJE)5cOs z?R6!Vcb+Bh-^cDb<-UCH7M#HL{l@95$%Z3U0nGrEy~HMHoq(1l=oNJsjhX~p6JbZ= zXOxZ$AAYzMvZmKQ6=t#@OEpRfbl^tUZMBhB+`mQs8*B42LIZZBA8U=$^B4b6ZE^}9 zz=7mNp3q3K;vv1+Df@36KlKk`G1+olU5y$=}d(uOM}&tT|qk?TXab#*JUcm}_c zpw|ZPT=C7X)4N$Nu#;&L%Xv-*13t4Zlex7gu1c^H(;nY;1lh z?lZm*wEnTK8utlHWT8 zr|0iUL7|n2{#<*Zinc4{0Ug_ExH#H9WN~$2M(8PS*r-m_Vu6-LkY?LqZn2=(^z15^itp2BBvcCC82ir#hk`y(#(HiwbKwQLux5AK zUvk-wF+FsKUZH-z-M%NLcg}nYN?oBI0VP`rB;UhLc(0qvrO1y77nE>LT1Zf3nw?s2 zS=W+fzE=h>y)WV`qNZJ@XOKvtYNx#D{bN5{Aa5txrX+H;(hT!UetIi%Z^@@SD8t&w zDd|tK74cT)f4~+5z%LuGUv>JzfBCBq z-r4jeycpWM+yZXVD-T>U##Ge+J}lP7dHv+=?`>E8hYU;n9c-CCZ&q@RWV$5!1G36P zx*EfBJwv}spM&P)Wha{dXSUUnik?hQtA^pHL}I)?V$E~GG)DV!-obN=Gk|W zUjaCAv@59DE)x)xqu(q18r&U+VSV|{tH71Fh`-e88`}efr)k}MT*_#Ed12u*OR$>w zxiJCAIFW3yZ`tLax&PV{!6_`KMqCc-kwa0s{8o@tqPm?MLK}9HCbr&Qt-}+#DzZi9&7k&WGUW!C65B3aI>=^Z zI&dU6ix{z2rX}3+tb>-Z(-bdov^x$_MzS4AFQX`kgB%G2Q0oq&a9rWr8ogQJO#&pS zCvk$e#0%lXK4c<#qqJdWNu{XW1>8Qux+N>nZ@WD2|7$h0rsG9%uOA1&x))XW@NL-H zFLua|9MCd&U#-mJ3Qh)n>-|yfPJVQg&!_}Odiz}?A_CUNV4*_duKceNO05)?@=_5a<3DIC0-v{glK?s`&?s-BzEfTr5IL8FbT#{aFJlV z)k<@fAO!vB#>InkbU@YbrS6vdcG>S0+|S?csHzd~gi zij#lOzNLxWy+`Na+OuP3h-guYR^nK>pim8mT}LM5@-6eeTRmQ1)KtA^_meU`jj!m% zILs2aiRsn(IAleMO%%`Pi4JIyDCbwFbQg(JjUzV!163#s~ypS%KA0uAxdSW zfMbkiRvMGl;^ibQGs^@mB4rOSfB4qmL1&xYDjGDM7M__H6B}bIajBr+CA-wry7P1Gk z?$Artn3gQ$tB2RnfaFB{KaZqtawjE+GLcWlCSyH0=TV89xPv z;gDFTLODxsUj+Y{1rrJR`ax#&nPt8>Sy;hd;_^=$)=J|#b=Z!v?KID|(rU+bDH#TxmV zH|Tt1C*2Zm?TZ*%iBXt(ZJ%63$u|w8Yu*x_Jhvb9>a}y}*@xy%yA4a88a79+ZJ7kns*%@?XEHFL`H`t6caER;@d7L+ zX%Sb-yX>>y;M_g8QY83Y*@p2oN#g%u>#d{O`ob@7+}+(JKyfb~in~K`D^j$$TX1)4 zahD>+-JJqOio3hJOz8JF?|Ns}{6QdDN%%Z_@8_I*Z_d4G_z3$bR>E9IA->kXm?xhz z(K{K~f!vT>s)e_$UwwiiN^%Xq(J;!kdV3GJXwZ%jT^m@6a7KINS=9s!rhlzKdeK@B z*{Ij|ao-*uvylRw%C52cuML%*SPlA%USfDt@F3*%*PXU7Q3b1loHE`-85O^q4ITJL z0B(=cE%W|f!e&z|^)t>N%*H{+&6L){09`6O{oZcJk}zFDGu=S2RMR7bkMpjqqm%D! z!V0~N>A~{tP(I)jF(AW&UtKXATKk!>tbF84!eys@z$auhzEi?2|D#-gr?h zvy+k{Cxqi9IcV7~l(G>&7VBGNA;PuoP^I)i&&FCHEt_aTaw#Pi-N?W5kqtYFO>agu>L+ehwAhH~5pjLwyOp|Rdd1RJf zXLpzpoA7YO(UVcWGocv=^{`Xg7b_tSuYogDVQW!G zm9Itl)yy3c$#l@TEtKy_p@rg0@Ug30qKe&MIWc`JY%lE5Uaf9PYK<>dYvE6viYoI) zv;Cr1bys9=t|KM$MoV4AmrSWS&O287q+`58xVg}8>5nR|$c5IShTm=0A#Da`loHf{ z9@&p#u94;(H{drTv@|`0pS7)SUgH$&nK2x)YdluwY+dgRJHC~)C~3Q>)n!=Wy=gz5 z)7&dP!`4eDvoUZR{RejLDmSfeR}2PggYE5~nFwxFX3cyIKTl~*WBleWCN(%w3PJE@|=W?NH^1tV}SL z$A4JYu5#Ggc7L^a6+MwdB1^O7>~jrxZmP&QPYyA0#75Bff4*tXP{D*b$4@>Sptb+d!E4O{6HmDSg6?O}js=n=F@jt0<|4CKf zSOlN>clFyrI=BGrW!3cc+xx?TVVG_Q_8X^kikZho;9JlH+**E{mymec#xjx zm%F#5DzxV6{FVBZUc8l?UY?mrR*hXTvL+e`RpriQ=*Qep*giqBzr_g*`UaZ{2_a|hDwG_t3hNW`i;(h4e z{^bc=A8_EG!t-KVRL6WO_o>APpVTDCXC~W3#xuhkxX*fz;xw*T0N{tBo%{fgz`=mK z=sczGHhUc-KZZ}QcYIFaCCKZl@LrrG$kDkt@7n#(f};l5@7&B1P@ViJ50+9AIx-`r zAFFZGpA7!c7e4KFq+Tx^3f{FBOkA(;)B5Ont}ctP(D*24Nk7J%la9(fb~y;&JtcoH zK=)PL?cg~jzbj>WSPrda2MtgD_Td63RmL9@;7i{yt)4OOBy|JgeI&(;jEt@(ei!Etl)%RLY%%IKi>9{QFc%%(T?qBjkH zQ`?+v`B=i#zx+2tn8Vr0uk0X*DB`Zvm;bIf;~yXRw(uY*h58I#!Em2%%qRZg_j-X#3knGH(`s{RjLCxPkQ(v!Pz)o6)YV7iDutTrRQK}CLf^|1pmQr2RL>pl4 z{}TXDX@ie94e<;5`Cxb>QDmjzER>mgOw$bH@ohbd?XJqOa8JM?B+9PX=~Hu_Tek1b z&P%zHNb4b@V!_GodP-={i(7r^MOrHX`1*~<7uL18*rF9iVO`iSzbGfi4&^`il&Mpv zj@F-f;S!d@ZP#L!eeH`cEu#mNOKvV#y9`DNqH4WCO()Ppp(spm^h=xGAMzgA2}3BK z1vhYRg)Mz;r0wv#$+i+$(FlL)0Zj4uI-8xQsu-`82xHr&DA9q3l3A$0%QA>>tH|HT zYz>ly?GxJ=$$jq+8V!Z$j6Nr$uXO_{#+q4QkFF-(jw1bDi#t2tPF9}C{q9eD*H&My zm+scyZq*jy6k!|;R`KMarZH}JRzeMZvl?*e@Sj@SnuUvB^*>UH*S8Vs53Yiu@@lVi z^q+WaKQSn=Q1iBPUm(f|yqQ z+7WE$5+(M#TM*e3>q{3Y(YR%PWPnp+gqLeyTaDu`SO=X$O7fFBa?+Jt=0F=%tNRhY z^@WKHbVHSt`XfPcpdGp0gLm(QH@TRx*mEDV{pfh8#TSpvV=8;{Rn%3uHTYHG94BUb;yc_n1s;BT-MiE_QYvDY^?@u& zbd(HRFS5Z%-q={!*mjle4~b6Qrt0)t>?BjLh)ze;gP+qhQU+PDR4+b-s*{j;7}w*R zZL?QZG~9#_wzd3m?uJ+WwvjG)>)LN>??mQ>3{hDydu_JL;t|D)zrREg16SZgNKc&jd@m$EufxR=GzM@n~n8e`G}_MxwT5<=JE|rcCARjd=4$&FQUC zA&=TncQ??zVns^zqk9yo?gfED!Y_~Glfc1MNiwe^4-|6O4)H(w3!)vH>_q#H)i7k` zD9B_-;=-2%ZtfFLdvv_z_OK1%J)FM;B^4tC8yLu-*Wk(Wk95fL8}1te2Z!kP*wx<3 zwrenos3CaWE5t8@-2c5h99fW5<2rj;;srs>K11w6%dfkd$Ub)FROE7b3{on(S*7)y+<&-spoljVaFB*}Hrblb?{$}TW z%$gZY;a2s-i=nQyqa!b?;!aXhPU|0Uf$kl4*~uu>Q>3_4_3)T!F)RnJpQEXf%eFdj zy(({2lFaa-reR>=7hINoF&2E1ck*&7XN8HNR=PhB$?RAXH{S?m9pSikUxz&oOnZ^N+$I?O~8du zqMOqMk_{W>IK?c35uPk%AyK||hbys$Azj&Ef+)uh-{7?DFMkH#p1s^pz?lNj<9vu@ z=f;s^A>+FmnbNx=E5qL}o79HgB+`+G;dY<_XWIaKcgiT7MhP92RhcuDFG*6V&Y4MG zfY>KZ8@1DdHV3<)ob{Zxm?iY3Vm%cyl#g%yl|p^9n&t`~%3cy4-s3_^Zt<3r^hrIh zpRAjtglXg>+*Gq-5r5r;UwUhY9RyB5bqDXAYO*k#*@}7C6YrGn(+7%G8>o<_Z70FQ z9_VKMWWzC83_DwtYQfFAzi{z&@k3_rT$#!;8P9 zu^AJB4t4wPARd+RD`P0YA#Qf!V+ zzap54AWko|s!!JG+_~{R^B8Tt%}k%wB_rfHO_mxGLWVZ>PRSQQh4Vc6Th}l@SPg zRT?3%J10e3q$Sz+)`*X7RDll(JUIt(*RG1Mc^BjRg~#SIX5qCxj(#yKMgbLc-wvw}8Q{ z9l@e8_*k$GWL{s~Q51x@z&ga<;H3>#hi42n)kF;1Rb<8u@{KgMe%N4-xH^H0AEf#7 zw`Ikcs95@t2Qk*zHQ#{Dy~2W*2o9SpAJda3R!H}J{@0M{gkbDNQ;A2EwYs1rv=CZK zmua$bx2X?`6xkNq*+vcVpy{`(jdWcy>eeAs-iX1jyMV!c&y>NaCnPfJ%beK$Vt{J{VjrCs3~i85D0pVnfDT2#Z~zLD#-*_|GJMj z4V#@5fjqHY(~29rvLomU4^c@~gLrhBA~=wWEa;kgmBv9X7$Q{We*F8KAj8wrnhu-n zh?yM0t$i8oIuatjpL)HpbK!3YNV8T?8#hNUi2sd_0G&YF#T-#jxT${W%eh{1j_v7#_ z_V*Ngh>Zt7m;V2)Kz=-zBDYsJL^1d>@yHaymR=WjVrFguL+cC7VNr)>pF+evWz8B+ zK|^+|-#m#LIH=~I31wB=u7bzN^ZIT!bip5uJn!REarnhW90V%mcLk%<)v_A2d*50q zn5v_Q>xd(~BFtAPB2u+JKBc!r<*`1_`tUmyMYj~-$2XOP38#fGr2TE@EBv7ErbnI6 zG%GKm**HfjtqHyyMiVtWpR=9nAKRbfuQR_-3VV85RE}wEQwxUXXoQXEcwb=z(|m1Y|m)w zwz#;Z_utJub*zc%#=2g+4ij^uW`!0jk6;qDlf7Ljn^?*x0E67HZJ-P6%%^g5^|sS(4D5Kc_0 z#vE>}6C&s|#)n#O7V2o0IcA@NnD-9hn^<5#cJRPOtyL{^Nh&*$xp^($xT3&oKOkB>G!1tfk& z+fGZcsl`Fa_XQp+D8sRGQj=2>QF043%?3 z!#7;2NjwyJ-!uk}8;cmM`scjSIiQeHwYcCOgzDtt!}vNw@BE>eM=n%Wi5mMRXobrr zi5}NP;*4Ogznn4GSkmAxYpRecv~ZRv8s<_7n&(?7Y2jWXZ!zYJ8ggRgek~$6j=;Io zK!7=r3N0LV;Pe_w_~u%d8?LCpE5U0O9>H&K0iJuw0-#h)7) z2^$|O{cQC<=Wcr3jUM>K(`!i4*6j6_)#8Pxug{vEPZx8@0bm<37g0$sozLc?1@-7fRq9);lc7y!2iOi@cy zXp7{%fAj3Q+2c*9MgbENh7me^UajoidYPz7Z%?9{vy+S*B`!j5LT(}aE>!nuD(I8A zr81^SaRMl$y^!41R7S97HR>Bn!W*=j`{T9CIKSShbf_}3UhKb zeSN?d`HHH9Xxx_g6C4A`$-6|rNm`sxxc0Y`&u!&}vn4cX>31TO43glimcK?Mo?p;U zVj@BSH9dr9M$7K~;_4OQVN3|v2aa(n@wKsfT#SS4CG(bF@b0CBROO^wioFP|%+9Ot zNV1I20y!eTe_9Y|X@zE3SSFpa3P?^0FD~rcp=AxOAdS*L1t1m6=9>+n2DnAAmB`U* zU9b_G&61l8YnFu+mY;4UR3&6^_OwXf#^@%tZ>|4w1H0dIxgY>`|3h|ruQR1L@=^RT z`ZM0`b(NBc-^0RoT)EvkAkq&`PqS2@#a7|-?l&a%$FrD*K#wiv*?eie_P8{;^ca2- zdDYWe=KXT>V{@YNedJ3QOJ2$shYmEKP_z_)zLY2OGSt&Ti%?yl@GKe{o~ZGbaKfKk zI`d`Kcmj(<0`eu1EwOSKF@>MlFbG@VnuJAA37}{w579Yq>7& z=etkcjpG*hY!?5%t0p_{$b>ryF?^#z#dJR=d zQEw-9b*%;Ww!4Ix+)$owWhrvIs7rHzIBY@zoE*rNy`t(H#7Q4Jq$Sw5!qP#jY}oz8 z#L=PAjeU++!Z=ylqWuOY(b&P%n+%4WR_HPHSVmFsIu!;r^!**mFYRa+e>43OLf@_6d@Q2d9pzy6g>||t z1ix@+osDQXVv#BaS$8xHO6=RlM5-!pQ7z-moi*=pH z1wHbH=0Y>>@8VUhIy&{iWf^iBC8`zerjp4*$Jrf(R`K}Z`7+Q?=eX5uf3^eTVnod| zGap|NEu_e%aQL)wpH}0WQO6o*H#%f{Eevy8;FhlT&vq6pJ>Rc^qv*m-dhh(`ER8pa z?cNT}2f+E4lc_X|Tzp&kBKouVR7X?Qv!RO#Hf9Y6k4F7md_$Htc_)+2*tPbjB_(oS z@4J{>@pSa-yh>F;NTuw7>DHWLk_^vlYvLb?sRteCjQalLAfooBnnQD9bj#{f(Gg#x1}hA_PLM<=Cd+-S z*!E$63{S}+9oFObjb+xS+A-;SorIgA?Yrnzw#Ud_w@6E0R3b76-^ZCStcDv17tGJm zUtd!8gE!mbS@DJMmvE!K7gIBG@a^OzuC2ZF7z>(s8-T1GdZMhq*^j2=-fM`ig=+UK zTUe#^CyO;mtGGSYSYoKvvGydr+6~hxpNb?dpF{>m)MsL}-(%RE_=OVVsD6Jx=&?$o zbf9AbFO1a6JDu}EPinIKegA$kl2kW06&>b9K4d3sd;!<>d#=`!6VLzDVSOE_)`9AI z(4cy~7|%)Zvt5zt`eWrJ@^9{tmC5Xm*A0BW=R55EK0omiI=%hF7yHiV$E`I(@23s> z`%x*aH@@#3zHh_4Z&%MthO2&0(Aq+eT6~w6=mf9VNg0G^F~SMXNoO!@|a@huzM|;z62UKVPmsb*dCRnsb&BYC~>Oy_wLTX7jAyDvlY8JL9Z>?9EC;M z`au+HJmPIcaDs|U@TJjaa>i7fGrgkA6S)nlm(ChxYk(0YNLuZL?h{1}*9nW9rV-B9 zMN||NCuF$ZmL*cS71grvRrx^U#&PU+K_hJ@Qi1_H1~!|h9yFco{%nKm?BDLeHUgD! z17_Gv9&P1X(oLMurY)5y1Fqv&VWxkXNLmfH<|Xp5H*Dnn#k*_9L+N8KefV~Xo19QF zVjdtQmXNb;f2C%Ho7ORKcC#-hhV#J@3uYpz7YtK8ani_EjhT1&^8j(D#VoM7Sd z%{hI#MWg-7zWh@9*Q6bGfW7T=GQ6qIGQq-6N470j9PSv+D%c^oB7qV$CGb6WS!x zwmW=tjz$f-*sFBpRSw4&MBrmhmvDO=L?l=2_W9oQF%LPse<3#Ku|rcPY+1b<`VBnk zVy14#Uz&otwI?v=1(MbY=m;wu zD;m4_LbS>qqln8LP&WV8Wnu*L`BvVsb+bq4%h?C$vhmHWoH~R}6rYaw-OPt%t9p5K zu|FB7uBdLNp`${PAWs2bia8xBPCAH45~Gb7y?SGNI*U&&;#IQa;jx=aD z$LAUkpyC_)y`F|nO|&E6I5vpc42Ll2O%Z<*Jkju1ZlaHUu_S$+;B@*ENsvOe0xZsy zSsa(ce;!;2#|*NY3p+%)#vqXd{XoCr02TS>@Fos>ncD|AqGXo*S3pnHzXHZeT0eBN zKVB}P_IT~k6_;r@3Xp7FskJBsn%=9_r^1sQ4gNq0`e=Jh5PaCq0ZMf)f3KhyTmkdX z?F*JwrfxsHL1$h5m=nZ6M7~?IU{j@c{7D?Xwz2iJSOvm&eE8y~cYNoFlVGo-=emCx z(s|EN`Fn;$GLckrYkUP{h!>fkb0uEx)D64azgF{tD~LrR`IY(6@(}*xDbnmw%_`Iu z0guWS0k7r;!KZTY{2b$07vUNvPVor0gh~}N>`^y&l8bv|Ad_j{4P0ef@}Vi*YEM{E z{W<7;3|TP<t*RIe%>*qdz;Yuut3 zd*;tS@lT_1=BzuFhC5R(wLZT#u;TPT>udUIbhrVj(!9IjVEOxY0(}>a%P4-!JWlb6 zF3ZlW5g%ZLR?1V@{XAM*hpxUQ=t-Qtnf~$7h`q$PZ{o+p9UC9`l9a*XN~`bY^aX*mCY=55~7%tj&~@qKhB?G+X+G6X~-q~isJ{s+x+K363~$5($o?fziStw*IjQ9T4`OY|J= z{z_=b#TA_}T?wdTD1X2f-v?7jw8Q0DK@9BQam^@w=??zmq0p1&WDt(RWL@t{LqmmN z0>7gp?)UEjmpK3s3Bd)Fx1kN0I6Y8Zo`{YbMi4XOlq{&IIljple+yp(bEo$q#)3G! zR9r3~ori}R?Z_yr>n8?AOc9jmfDkNkqTkUlb6A?{QzJ3sEHK8dBdzght2f~F9d+DQ z>eo`eh|;k(fjM0S71p?Jt|bs(R%^^Ry5HF6Q>ZD%PU zM_C6^k&2-Oi!Tb!#-DSj-$E)U{mr)dTs;ujQe&EqECc>5{5t*P`6vyyH98(B8^fOn zyI`@xrj6ldVBzI2+cUZu(7ER2b07r->bMNlm&R%O4<%eMzfw>;iR#^lV^fLEpiB2J z^4oU4qD-#~JYRKozCJA3)97MxZ6;tCf5u04G_Mo$nqdmN+JMVfgmv_SpwQ`OhDJj> z3JXd>K7)!^n~xG*X8%MY{U986g}U6$4s$Ogp51dt^NA$Q0EAwq_hbuA-3q{(J?-Rwk~B~(vz%50T+r#LnUKkGUDX0 zf1cfagVsGbCOlc7W*(xSIgH|nZO)vW(J$n2pTp4r5R$nYLob1vJaD3QmMoZn7ryuk z6LgDxZ|K$j3^8<_<`n89A3oD@(A?b>h1HO3(f`ewn|lG#|G+dmM-m12A@z!$H)GD0L|avltqO& zH6LsJ4*9!KH)Z#0lXY@82is)zM(i5ddQ87SPow9-&8&m0n6C04bY9qdAMogFan4=i3hLI3YD)5& zC#_qwqd0IXu<;`meg9Ntv*5Lw6cDHPn=tT-eO>K7;*RX!)HC^pV&D%;4*%7-_aYfD z!lNclS}w=o1D=x(V%l}T2^~X#$>$G}{D^oLCXSS}8;%X`>^|SW4@9^LQT_>{{^JPL z)NS}RP(q>Vl{d@xT}QIS>oG;z3PT_ zllc7H7^OF%bvOg`%B{lf|YxmKuVY2p=Y0es$^(z z0#!bfIRunxkVh{Nkx~tw!=_D6%lX7)YxI7a<&}N~A&f{y2Qzn5+pHNc}8dNC#Silv`}ZjZv8X z^m*i_A<%wN4~`jLeG~k__`NG|P4hQ34&PHLT~a=ElH;*@=G=GPMhYA+>m*7XqTJI1 zU7(Bt2k>BP0u$-Z7CkpAv&U-$F*qtsd7FI0>Qa-OtOOT{G?xJ090Y_z%+>xo2g0J( zgmuQrJw}A92PF(ofRv>@=+21Fy}y9+oUJpI9n|MQCSMg0cQ`PMnF)7>hFnoFi&Z-k zm4ST>yhaGLpT1`pz{C@$W{Cr^1Bl1MDeS&>LgtoGsMTd)$>P)*|BwbK4$W0%W6A!_ za-oK1D0D!rgwIV1f8UoY@1eQ^g6}tWMok z`|JV8Dn#$W*x{m1N~BJjzF+1ia~1=bW%>%_VIF36&?e2$P$vn$lH@ut?h1i8?2yhF z=y5nqfbo7HsR0m_BC4*z9Qn7>;S~JY{|Q4B7T%-^sFwbI4ojBq78^+UBO3!rFdLi# zjhy!saOci{Rs%N6d$X1xa)Hxtz_2C*pzKH`W&>eudMU8x6`YTq8xTZb^HZiscB2j< z#4;A(R~CV=c7n9&u_6*tZ;y&Wf0BJyhD2r4!wKFC<_}x20|L5{MUhB~m<(J9#3);I zLTgSblJw9J#@&FqoxrQ>5G-?lWwljhO{^|`dMn&D<)0RyZzl*lix^0ISu6;_Hfq3J zuEqbC$%EgqkqFsyheUd&&47@_aKM_^I5`D`U~3wXNoE;hf2dUu+RPh_u7MZu2RQwI zWGQh}HIQ<`6u?>6U_i{sCOG;}DoDBF>sMen z<~h{IL)3nn5C9PML#~-jeXuehx8Xm-ORksx{~5120vr)jLQ=ZwkGNsUhUxFYjS+)? z@wOujw>Dps0MpG*LmUbIxHhi&E6bmAYbzkqemNRQq0Vg*TzPq9$h}55v@@e992<|G z3sN4bShnG%Oj?JffJGA<96`)gzW10jt`I<=o#;dT=Q+v9x`NYSA{AYd1e6__%pT^* zc$BgoN$xTMaKq*pHaE^z7Qh8unQjCnWSD{e3}#c~oGy_833-Fjss7K1+XMbZoEYhU zA|9b624N3)rB4xMg^}$N7jms+XskWn1p<;5^blaPCZd$p$($7ce2ia#HT6ZHZ|U-o z@QDoT1RSu^VBZnbp_(AY0hDU~2NFYhzYF&;MreXR3ZBM^w1Y=B6W~fWcw}R@{n$W) z*iS2e_E!n9aIpNJ=?Tv7rWZ+B{BP5{ME-U6%YWUyl8t7{H)Qx7KjHwjaK&4-57guP zwS1nuwG|epHVPh2%|1$WfAArm z>Nt3RVm1i8O9=3`+Vuf=xb|20R@@te96r5d4`D1UBzd%RBCYYd>@au34l=irS@L}|w@ZqV-~1JJw&i!c+3HJKp!bX;$> z9siILkGF4zKS?=grtSJG7S7IPOd_eIlplKh)Z=$IMlA0zotE74M7GCxOTC{e{gUHq zQQ3jw27y5|3Bu#7Xgfk5k=|+vAPS-B`kK2XH}e6ZUVuG_(lj-a#lLpFo#pj0Q7o{y z7dRb8E^DDYfJr)jkq_!5wKOY%xbU)*LR9))gVPX%$&+5N_^F6l%kt;j3@}Qv4~k6) z7MqUHo|usEd5b#-PJA)aN9e#W_AJ84taulRRuHs(XjytNJ0CLLGNV0E%!js4*d-e9g`?oYV;cwTLXfl4cPsw24Q z3~Q~wEWn~I3^Q4Kj+zmlGMS?V$Dq%$#R%5DhCbu>M!(?q--FWurp4|xB0P4j@-`$q z)U2e%7{v5D0vA+$1CG#mtU!nFCz4??TbsYmO~}abvCSG6pmUAsi79v$qN6qb+(<}A zoX86pIQXkJbSN8tWB227b_u~xfXZY+zH0nz=)l=8H^jgPb8gZ%QkY(q+qMP!x-$ot zVEw&Cavk#>(Vf2uYD)qot+zG?KQfG;P#=laq*}cis%;+o!_K)05p#cO{@^2&w_raq zF&p=i`3ej6BWN6@4Ix)awF8?KxR1?i1cnt}umi2rzpJ=ArNqAEOx%g_;8c5|G%Yx- zP1_$CXS|s1+O~e5h{CFFq$EFpqW@zfcssFZR1sVjlFPe<1i8vqL{?x4Hxi5+Q9_i< z=I}kZaOM#V%og%QZ-3&*Fd4JNL3#{}x?@p^y6{|DI3%TQTXiWoGC7C+I_7<`>O7k;-rDN>-|~E@S*tA+VG0jg6AffCpn1}Rp*-=0mzw% zdVIlMu>bfR0^a$k@NIa3`%w7V!T4A6!D;Z#(T0;J**4cbT+kevG8a_a!mdT6tlC0Z z8^H-XgIwK{vxElHMW!vsFs!@$F-qN({`k~!lnM?gJEW|78DI1ar6sKnKS$tGr%;Z6 zMbR>93!6gGp1Ux?{7sQBw;`ck3(wRQDJ1I}im%2XV1Yp9UW4)LD5{64ttpDdhqL8c zZL$zN$+jW1INOPC_1^-9gl%{OIetXSwRPE_X7_9`WqTu?%|4I6G{_>ft~h*Ad=B#n z27k?<{=-a-2_m(~DALj>fAhZDJ|wr$P@P|3YLPo(7D*t1{EKl|cbAWMDY0b}j_fq^ zoRLH}VeLp_=7(FO$bspf<^s$zFM2J&kcn-N59E_`T(NYO&OUCYLY0E z+`AI;Q^oqxSQJJU(8qGEL9l=_cP;nv#(2bkGE4Dpx+z8fQ1gM#hM1RVKhn4oe=S$= z7Zis1Ns$Sm*t zCH^uY>>5US`8ID`QHeo~4&l#)U}A;|q5L~+>J>qYoFha61p=Kll0fB+IbWGllDrXp zl3gBl9ljXCKI;e7fG_u*Dma*%wUHq7yi;U;<7T-p`5{)O;|z&v9K_Cb$$v_Boll6On+lS`u7%Iwf1C~ zPzVzgA?_JP3~`v*ZByQ*{%ln6HCVXy#4xC*)y4U#C2=%Nb^MrgO3FOk3H#zG|88u+ zey_zboAoLR^Yvcs}fVpAR2k#6Gu^2Hp-kn<6h- zgGU?ohUO-sh%Mb=xX+tknSR2xGMHSC&TqM_{|zHpOu`KEj4wveVl?L9{EBj4iYI4c zj4!9U1ALyzWWd<^$hS?)C*3#eEro}j^ZhSD&62iPTXL9_I5H{we0=VA3}~XWsCR!G=YJ-BCNF{sH@#oLE4#fQs> z$EXJ64Nz~lDnX1|VeBI1yC45Kt|dP07!A2Y%8up1oy6ETv@>f&9Tq=ap8Fk>dZfIj zf_eaGFy1>#B{`!t3Q!NbaPYa|nbopaH2hD% z%;|ZPnT*lS>ALpx!9{>gu7PWPAfgsBgR-Xm8s$C)b3spvMSWd9PX zkYnC{DvM1;HYIqO?m);wME|JShXjJDJ%(GOGW`M*br!2a}C>Ix*~k6Bkw^A|yz+{cvzZ zzFr;IOV5`4N({B68}oeE`Eq#_>*sfI656@JO0NI1(9dedV>bvE{_-j>f-AF;N(I_HE%nO(qt0@NUAEgv5$BCH(Fi8AD~UWospJPlh_tY2V@(58l-?zx z7Dm?)O}6rHe@xnJ?KwzO%7>(lLI`R`;UL_CDP0=SZj#p^v2?SW^=DS;W_YWguUpi7 zYC1S$QYpKvYNsx}G&=^Yi}Bwk>Nw<@8x`tHGpCChDA|G=UKVGz%|6p}B0 zOybp*F8c?A?{I@l;7N|02x@5NaT%>EC6;Eds^q~v-knUbR?F3dvQ^2HZ6C^2uu>Zy z11`yDBHbb_epytn`!1^MfZ#tpSp+>SV5^JKV%em4!so5K&r>?!mzSF=9$ynD<8awXcWf5{XRr=4JDU4z(PjJ zrz7p45U8X_n3J;Mji?hEK(qBIu|5*aKKR~^p`jC~86WO~zxlF8t!tiDUPxauEn*zO zND!?@onZ~0pd&zF=!PJ;)IbW(KUWQ%JcteKG*r}8>f0JZvk25qPfh zF}UZ33gI!ILb#!VMFC(vZ?a;0pR6F>Co6U%XI?J(aYeqk_w*jB2H_s(TpJ6dlcKT3sOcY09jIoS zTKIS0ewqGc)_A)QA%A=R)VXKG3C$MBqA}tIB{^C64cavr)48;WcrZt9XY&fe^rxKA zmzEjoAvSVd{eRZa7XGuInT|>^L?@i`X`rc%@a>?(QBVbI30W_U5_^8qkH~VJ)BdQ!&)Rc&E=dOA0 z*Heo)yZAL+S4c@q2u*?_$otFZx7V$6fV8AM?5e&L zl^;5u50M^4zEEq=U`%CdA|u@o2L$n0%OSRW0m0t?*yScnW5ID`Rt+W|cYv@R@j-0T z^6HFxLGsPlfWBLfb7itYSQi++nb+E^SH}O*tB4frkU76nkTd@1+qy&49Vsnx1a03Y z)+GmC9LkU#W&hN?j=u4HM=M{kUbHEy zp5IJcd$#mHHv zdIgAZrJFXSgs9cwlf}l15MSQ(xm_#}W5i0TNTuBXK@89UIS@|~VO0K=@lL0;*|{S- zu8llLsZ)D>2;X-_wBG1v2>{2=DuCLXA(qB)@^+y0|ff4?fQ1 z+sZbJC{^tnPQ9!eOf7Xp+y{v!t>U)(g_@R?^P5->f?)t7&SPoD2`maW$dA^9C20eU>ijyqlw}T+5gp>Z zr3^N-?XY$MFE%S=pT)AR;o*@*Qyj@Hh)AM7pI^p1RD^viV2%j_dWe_i<0ycuZhVS`w zV*5jP{~t>AiHzk@+85_HV-#omj|=jMMH;>i2Pr{yEs#IR_14s3nkV6M_3sz9A*C4$ z@3pvu8<3t71LiCqx_9sx+odPaJDwox*?&p~myC>8y_S~A+CsJrN|hl|+pvq${p~3x zE2}r8Pwr9+zbnQi;@VTHFm=u#Z!=y#+PiaFw1-1H>7D4ZU>vC6jiuo zXqy(k0~Eh#@>ympFrOsK$UNo47WmlZ<@s1u8I3_FUr; z7*~fA88_7+8I$SqPO(iQh`a6Y^1zn6WJ`kL&qa=ICnJCa;FX6MAgjChBs7q5V-mua z%Yr|fN*Spy6iB9E@w9!@^-fB)p<<26K*W#VuL>e)$E&|y)8-A$zuPrLm+-QFh(>IH4ddB@Gf%ihxL$qJ$tw4JaJ~0@BTp(yh`UASg9MN;i^<2uOEI z$IuP)yYIorC*JqGzt1_J@A>ci;p~~&_g;IgYhCNwYsO*bVZg|>s|HF#j9>inuNX*? z(BI}l57ehAVEAn5S37Z!8ZG=LS?RLE`&C(}K26IfSF5G@?a?0Z&2Pn`av#4^6)X}BocG2^DKc$liPFMMn@777}8;;)@d~;;AO&n!uQPSoNqDkQqjx+kwQmI^Z{|gu7 zu9vZ=-`y_5#14W;NsikNI$~t26Q4Jh4eknH>(5bhQ0~@!cE)>@{*s`4`>Q6l?-Aom ze91bW5NdmOvs)%OwcUP6Zf9!=FY)X3*6`|;mS{+OPZ5(x(X?5+i-&!STiFc>X?dl` zTJ1)sshK{JuZHOZY@gJ2J(%Q|s?E0Yo#cZfou6s;YOho98u{*#?u7{OVD&H8R{R9;#W!7=+Qgy3OEUJsZZD z=V9cs4JuwyrNxCIdJHdJ_R9i3AzYM}Klb3}lG^&T0s1}u4Q382Ig@b=0rQ?f{0EmI zyf2uaPCRh`$u8uq?8H9BFPCsbt~HRrO5OkH2{Ns$Wb6%XRpci8$_d)w-DjN)4@ipo z2D~c*xjk;?QIw;P+$p^|>;;v53lZpz{_=xgOyIt2cXfyi5buKbDPr?%y&8h&d$0?Tn~`}(%JsG@wkv8&mZ zkB;~}$e2=wtMZj!{~Q~O0S6J14<#_r#}PgoB4t>=AL zPqdGUX~Tl#_39xDbx&`!8^sJ(`XQ8_&SmM>v`t`m8%B&tr{n<+N$SlNOnDczS$T^+ zn-lnCUbw{ckspY44v2Mb-%S4<|Hkp$2I)7Bj4*1q%KRKR| z7_Z=7+|O<%UmJsn;Fd&sl-k!3*?zJRU*hRZb=SU0KS|U~TkBMJR(5u)O}0+g?LrG=Rn5nHOA;>xm+v(mh>3y*5KRq>^S znOC;(g|{SW33SdK`Oe?JZ@;)k`i7L2I@3pK6YKzK6Ys{hXX@3Y0>$6@)|cN-ZSwI( zzLyS=eR(^i$s8$c+p-|gW}~luzWhNt^NjZv=d0cCE0H4}r8%`kQ*@=DGkOE8WUZ90 z#a^rOG`42g7(1{%>HBJzd=N-j@h$RN>;Zb$HS(0o5jFkzz%kx2QNN;F<5A;9Z~SDc z6}~&K&t%w(8jPKL73Ji$TUK<3KWmuCh@v1*t#K>-IFUi}fyK>hX8im5_aMYV%Z=Jy z+p1Ho`;K_yBSVM=Y#Z-ma&Gb3CkIv&)ySR+q)>mI7`fu{*aman$oaHKkL>pw8=}Tz zbZc?7SIobLy^gD;Ba5rO9~2R{Zrf53l?4GZT+ZZJ_uwq5hHGtR>_s=iZi?rTRm&qw zOttw|^SuUH|J@Q%sp?qb-u&_VGa7^08)U|R>D?KBImBirhDi8qVe1DfKZW0dczRQ7tRCR@DPD6!xPcy};koW1v&&hhElef*5`o1CA$^j4V!9Mu!!;`a&gFE>r zV^bQLno>4&WE<-Vf?=6fm~J&?LUgC+LudJ|(Kmxs4(aSE12SjWS4c=U^IZDJt@Xx= z?vKX+lE4ZTV} z_Sy2jP^i&f8-rqXD{(KE#2H=ee#3`wZ4YEsuQf0A!~AG}?b>_O^fLFSLBD2C7DqBI z)31nz&T=gfl^+n_wi}>>na5gna#Gi8>RALmB-gr{pH_c>kkG3S7%<}rM9DEy}GC& zn(^?R_PP)1rWED?_aq8HcD1orJf6prql!`i)|vo*DFKgKst|QS7+bs@T)?|ABzByF z_fSt~f^(T(u<;Jc`EtU(c#-$**!MK0p7^KY)LnJIu{(I*v+Wx=MH;MD#VFsBJB}72 z6iaiRINN^gf$t&ZyhcXk@iCelRkl6m$8f;3Y8!9~$6R(tez=PDDi7nFx^?ic=hUrz zV(c~oHqu`MZsb3t%LK3g)0LJgwJMZ{z|@Ud;NpkxItX3^+XB~YFmI&a^9Z-UsUrKw z_LwXe*VI6v>{l5+jLVZLUIhBDF6NA*nL|JaAt``G;QIor(0gHC)r%ScQcej)Fo$je zl@6f;(C={vAPk3YE22HBLgSb*k;hMHd*(3T-%Mwd>h{;WQb*#x`W|!y4qV7G`;VJ! zsI^nLy><`|)nY151`sOsSDZJ7DtvlDQ|b+H@br2Mwiw99~6b=Xd6yIo~QpWR~5;Yv3~ik7eKWFsJ_m zlVE$bZ>gI_OPW$lg!3|TE$QP|LWE*y7>Om-tSt)eu+9xTjLA$=_y!wyN4);aO&W)w zlON>+u~1eM+K!0V@^pW>$@i1WB~r0=zbv6Z2el3-v0JMm{(S?M@58EP-BK39`8Iaq zAbX(pm970B(stzgVQevWC?Z&I01J5KTZ$I}e}3Hz-uFGcI-jLk`37+A18_0m%mdIW zdj%nGOAxzY9b;$<^G68ihK3Wnpp@1C5Q#Yih{B!gYXXGMdRf5!5P@&a0W7xWU?dLG zmX~Yk9#^e1Gq|$ll%Q9I?mo^sCaa4hPVCOQE438cqm8|ndCntKmEU}6Rz>R{{5@5# z5=T{vuh9NDE0Ez~2j-9AAVzm0#Q~SV6p!9y_QC~9@9N*mVjWcx(DwkZRohc(7-L2D z$FJn}gK=hhl`je`zupZ_%ltPb$XOvyc1J>{YWbyvJWvoSe=Qq;R4oACumQqw?os|1 z`=Kgtmkz8b1Skfc?N4IIno;Dg2mDV4xbrIjL8%TPERmeOK?0;xe%ahn-tswlbKxGcTIbq=V&HTUem=vVHn9Sc$y$}S}KkQs++#f=h z#oJ*;$9l{9AG-7hD2iZ(ZT-8*lK~k)Z4>JbF!928IZCjsGVK3QBcQ74!6MzIlZ06J z{elGCD)&!qRJVrabRUX=gxGCC7gzEr@K3!WPU_CME58I%7jQ7^uLe;PxTQ8P0F*75 z&T)qaF@G!Fb(Erli+)M4amo63ZRm2g*^V>N{ZjFS-q&bR3z+S>c9~#VJt3mPJvS_$57K4?Nqre+%uUCHbY0 z9=>!6sY3rr5tOXo{uhHxfRf(+&*DY_>|g!k+|yMDq0s$QG`SS=C!>Y9#%LTz0@Ubr0S`N%9Kn+ZaqPd^)Lob0T+RP;SF`OOq}>4B`sK*M7hVW2b$-u1kSa@6&=2()#Pf*CjM zCg7sF;68YC1GxmgW{xsbbxM~qIBLYP(C%^f13Zcl zCj$Zo>iaQKK!`Zmuhx0@@lrs~&GZVw6$MYLJJXg<`^pKxBCx>%O#B%8o(j|=)oVpko}qi z6%DY>dXI_zassH1Yw3;b#8DI$c5|s?=0pMJfS*{``F3WJtZAqc-2HfTZ z>ksA7Z%3gh16ei;hgO>jupO0`w8tet`t16K6#qJ#OFVa|1M>4J!_65*Rth zOGo^2j&sj7J-Clcd_A2fVmZBtpwGK~1iF>#x(R;`gFma`@iv-4OsZ}^y-Qn>8 zBt@SM1f!KpF9+ylK{{lHx8q5J>Z6DSRzH9zNDPo~PsMJ=x>}z&4BFuy|uwG1=tiX@`t;>n1~|Hg$@GX1J(I&c&6O}(CHV|dF21V zN&akCxT5T9qmOD-#`0aFG29 z5$OBDZNhtD^xS0N8JZQ;bYb%Xb+AcC(f=1X&rxN7;u7%c1e^hyXH?!$S-sz=3_i(y zL2aM{)T&Yd*0=8}4+ky>le)72---NiDX|AH9en$sKYwLs^m*g$J*$L!wB2AQ3O2={ zZ~%QJlb5rUA$=b}1lFtV4q$T&K1o;+^SklO7&k5DK9rZs1pDdCNO7>48dsI-I83xp z9;(O01X^V)nyN7epkD+!Sk<E%HjB^iS#sF>s$N@IN4(tlYoUH;5$DCP* zmEH*<{uiN`F#-E8fHk0T0(*?2GS3dkh5|>TaMv-r}1VCTHL#<(U9-clmfU?7;8!O= z>3>z~pZ-mtw-3c&T)zb1f|;QHy%w)XL{T*rjI$je!NnnP(Rl&fHU(eEf(rHPg+XN| z9a%7uTbGq7(Pb&7$i-i=Uo^&3TYMFcDA2QzZ(c=W{aOmbCL>1`q&*5?r#N~DR#p=} z@H+lN%D|)muUNp|jMeH_{eVt^T>?sX2`fs0xh&_u%>BK#IxlJq0i=R56BMb74gMGsy^Uwt}zZ4h6o%)MY3Lqt*Xuw+{Wtpm| zvjiwGrFrMk2Znmd_=j+yTwgLDG@w-PH+&m^;j*TaGiqfVOij&Bc zR(60Apa4aog!4T!3nm0zA$^4*hNbK(Ygf zg0Dz{^9xm8e^egW51?=ZQ*R2qgK^OyfIScxrYi7a2+Tb|K_EQP(O%faQgHmm%HP4) z`52;lfQv@Kv8amxDC@s zHAz4q|N52%sv@_Cw?}9+w!1si}L|-&EC`JJt;_uq~w`@a|-aq=PQ@JYL z^Yp54$|LfOE*7~Y0}69jTMsNrnSTWe*pdErtT-RcYPrD$WidMRXyG2NN| zA@Gx9=g_0Ir?NNq&Duq@E=h{U)fB9)SbF~0eXpfEH6dn^_W_$t6561CuzKg@>+0Cp ztNc~S)ZiY>eARuR*s0E9s9JB&LbtFL7$t>(xv;@K)3Y)PT9KWKiv4Fp$$LY3lxE*; z2KAwyiTn-Eyw^>%22X)2G)0AXDu(V}Trp#ex*|Osb%ib~>Iy;2r#sL+7xThmo`r_e zp&L(!z(+v``A2ofHKiYZ4xZ|r>5hIjwe%`HzrFr5pU+!V+EN$TNmSGvG$;BMwXdj! zDeBSubJT$MvvW$RrR@=YuLY#-Q9@9kT!@EU8e#jx=h1oh;=@5jod;eD(}9 zQQeIisMAoxs4Z$pk`mrYK5uW`mAswb7qtfl<7tLkt*eY0#D&3u?<`7TwQkzOs}EUO zI&_YTR!_9#p$P=Mb2fLc!Hdy%+7lv{dn3!T6$Xm6e1>EI%OWL?x(6ok&#QFzr@{PHWa zF1qFD6x>ztIVvZ5T?Qz>AU-I=)75+pzufBkg0e&xk4jBSe<_%u6dG{o-j$4Vmgu}N z)F+SfMePo1*kK0;F4MEb^L8V^<2yrO0B@gpgM0EZDV-&px4-QKAp%gm226cIO+7C; ze~dK#idyy-h2XDg;91^o6ix|?sOvj-P=PKS{b2yS0CKBLm)fc(~bGDs|UK zJ0y!L;fY z%TLcg%&zMq89b7Y9kJ$U42){p?h z$0UW>I2(zuPLy7|X0Us$2gB~W=!a?s%MUG16vQ8Wp4(trT7UK zai&RF-y6zc!OjiZyD^mr?RVh0MgJ%z>ki(B4*~+W4MMp+MC1k5cXHP{?87lLG+a=Q zW1=Z5U|u3a!$P|PJZ418w^w;*{2C2SgY6O;CGd>vOKuk%drOBGCMJ#!+^9kDwyV|4 zck0igMtQD!74{!+Kcxzx+FZULFMf$a}#wFOas=G#j$O(=Q8Xx3D&C(VXX2Y3(y(DO)2t*Zq>W= zm9u!ywv|4;yzVfTxs$?RZ@b{kGHz1qIV_A`R=EP5ocE4wBVF2^ z()%XqLrCRcfauQXt}kmaSKkiZusF$C(a$KQagFG`uK3|@r_p9lVSP?B#qB{Fyl*_; zoZC2sI~&g{vA%ulBNfCKp{d0Rfyd@jUow2CS}90I9Zl~k=4e#HH}b4j*6GMLT!O(U zO%kVV?ryRY7HQ$^bc-0FQB>G;Ur&`6`RjeOV9e_YN+pkW_Qo(JcPY1RmR zH#vLqN9AS=?QyHapXTDS)8`ur1k-0;(MYrhnho2A5wvH_7`vN#ZO)SsZ6qA> z|6EL+sp4;C;wa#6l~EPrH%)YTyU>;~qL9>$`Q23iWuF)W%a0Pd7{L{R@}ChRTG6^Z z48@%vNf`?CK@ajZZ|O|;FG3J!+8J*1$OFVwT^;fq_zrsH%GSuh!jFMk@vHGeA1lq$ zQpCk2Bu~yRoRkcDP0JAeQq_!U{`m%?2t83EY!*6UQS!5gBJ-9s7A`mB8V?u4 zJBzP9y%_c0W6Xtm)|}L^vnj6hG{XfgYbQOnPr0o>nv*EzcLaaC>|0tn3lF zNFtBVj;0Pkz|&sJ$Tf`^TAE)Bh~jjJ`=t=!i}tq_ zUkYWkXBJbNNbj84-knKc3Bb;Aiaib_qsP(@`>Z#^js7)O&97?QzaE0iu$v9r)bo{p zJY8;-D4;qMAK286b8m)1VTPZB<1p)8=UEE5L=Rrj7j*2ObI@9ExeDrnEdr#974^k5^!93H=IvY9z}v_hlmO6kFch3!blb7(FsIQ&g< zNjr1vzAua#!GDF{i_a>v&4!wqfekHU>M3>MqesmZV2<*(eD#*r;`k>O2t5PZ*xvZQ z;+MGc^v7Z8WZo94NYM9y1*QC6eSNM6H`o36CwU)H6E(yXs!qLbYo4~`6?!3t7N0#o zZong$ZWG&veHms^J9NGOaJ@8|y20v&$2+vUUY6#ytTzazVnI~fu-(&3LhpH*p(r3by(?bh^)H)L)`~+bC=$4i7L$TbC@62gLv`-c&1F0w1If`pzv%1@T3Ot zHGhKW(B|3RNvvzDH$iCiX{cxtb^QzkV8DYKJJ6xAf~$;XBIZRDkKHIE0LoD zLDbQwPcmfT5XDVes`l=L+21*E89ceiefQwi9x8d0VDk3B9#iQ}^>vl!b9tIY$zeltV z<2>s#DS8l>pS5Wi%`HrO8a^bR*qCo29GN4NzNr*kU0*X?Xy{?5SO2(Cg=-T}6{<*8i zw_7{>3;}te`GZzg{bA|>0Ye?MX~WI?E&JLnqjbuk`AOcocDX!S`dxbCVkxxU{`M|@ z_o>bPz7gIDYi1`1T0TqO+k;9JGCx9`lpEYY!CvD=vDE zK7;7cl4rC26F7W)ufQrP>~$U+Y^84Amn};Rp{RNGn3XllU7|fWFAcKl8T^H{DpSLO zEdMnn2M}1w9x5<74OCz&fE5INI{bhwCZV25#{sRwP`SF=q%+8Qf>l4nNHJauYIi9H!c#M1-X2ZQ{o+hKjcgb2@bc|4n#3M;D z6QPDZ{J_aa{~>Rg4ad&m++EcJhg(Bo92<`>5lZX8T}gh<&Ocw)(tAQa6mjx&RPKFx zf`+>vt?Vw&thUmq5|f0=Zn%l?BmW@>!vnTJ*D9AaE?-_fVX^ufn+1u`@D5#g@)rY0 zxXT80Say->PF?Z6(jn5Jh#TEmZ+ESXd9j6B>k}4?ET&XVSCiY`Vm2-(ex%Z2p)jvx zyeAf(GweYeo@7ql)d=TQ$alqU*3db*OMz~bwt^TQumZN-KC#jUw*6K~rgjo{=f_lO z>{TIC-hr_BPo?CNB_=m{{X1W3m1i`4sfEzWXmGU?J2j0X3-T-5mq$CyZ*#`aJm0;n z%SD9CHn(XhEH;e0K*$?`X-KIToC1Go(pN_Q#Bey&GA)j&bgi_VbO_wh8f&=Ri17Ni zr(Lc6^_jIy1|uCLP2X>^j^gf7T+eeQ+1h91#4=3HGPz0l!mCX?*6Ol(B=d@Y1y*(W z?8EiZjz>~G3U2vO6^digc-a{xmcaLkZc24ed4}Y!_%MbHS9NHV>uPV21?E@ooBJlW zrB+(sbQ5sOZY(Ev@F~Hse#g<=r(n00Ap3}mh|$9A=5k_DLs9JPqt~HUt$n30rF9=J zrYw$)_RpuVgHkpRj*I$#z6POsFm+vzNAb~>_n}4}jW=d> zhcv_j3~v^AYE6q2vlWcVrz%d!6j`;>PQMJ;xc2S!zUuhx1r^nAI|OsPkB9Y#<+oVm zTFYn60c5Rd+C4iZH=>w3{0>N}ZHU>P9&p*eZQN(tI5sj!hPL0r#2mACJ-t!*_(KdD zCf%E6*wB}HOX}1n9)ckWF59hP(ji6W?yLf?;VeT!+pJ<@AdlPUuW+iib${+YR$Uf8 zURPQG!&7YTD}DT6LSZ4_h;1l%fBJG@fw|D<>MXmr!xh}{&o|h3_P^H|XZaS}2#Y0Q zu^!>z@Q{&+Y9_X&|GC?Pk&E4|1yH*M7LkLyh5DIOANAV1v*zy7UU$h-5yMd}Hg`>m zGta^6tc6e+UZ#%UOR=k>E?n6#x6^OF!c8_(u@AwALA8`QLXG z7NdOqDNPkE&x4#wY}l**IL+H)JaDtlK(N3{E3~nk?bG@V2kw`xz?TfQusB{TCRIC% zGhh~zvTzPgXR9jamVXAQpWf}b*Y3biH0Ld66$tHYnPod#XYzs;Ou$w^BcEK z{fhw_?`k(*spUf3DqOST$hSW?54Xh5PNrg&kkCaYbxDQ2nxC6fNV$Q8g%Nho zHb+7I`bsx}y2|=CrQ1olB~%=H}*|W%{2ikE2cuhf=3h zejHaLg`yr=64Z{o{lTAAf3$t1-*CQCsQ&~RA8cmBulc0Gi}&ngYxjqkaF_#9+2RL- z#F4jNX`r2cc$Wh&&yz8^w>^4UIZ=?Wr(f@c&3%(dJ4Nps&0$Lu<=XmoZVavdzT{Zb zmJzUg%t^d7Zd34);M1Mw5<7+ZJ?017nW8J3FBA}%cf~PiwjyQ*zDgvm`n{#o$bu8$ zvoR9x+;Ev?;c2VRM!zK^ug5%f!Xoc#K+ zHSuQVi@}6e7iS;&#&B`Rx7p}&B&o-YLM_+iUqxjphYM+3fwW!=iAN)AjU;Dps*ry$ z%ZkVCe*>3t7z-ygBLH6>1C#Iz)m2RY$-yuNj!mnyq5Ji-a~cJ%h4HlC;;R-8djy4S z8;6`zhut+P>bjCTC`u7c6?bg?GJnQ8Wi4e3J&pUPJa%pgF4VsFXQB1n= zby08W3HSH6IKBR)EVuJqRW8%dKqx;tW8*|d35nwrzw+~rKicZuXgZy=_bBwxY-Phw zVu=6Fs8xpL59x)im_?1!F)-*0*j<(&!tXece>cGp;R`*&ebZ1IB`z3ND5j(y6{$_Z znC)Js&NHQX7)TLI{Ox2uO_K4_x75sS$im0Ga2H)&m;OhpWAS&2X_*~?UST1!soz;x ztn$OAe9%=iJRG3s+Q^Z~$I#M+z#GdH72a5Hguph~b>WSDmM$@n{^_Gn6l%f)5sB-m zVb#6&>k2gPztyHD7z*bE8n2&`78=A0tz99(Ftlej4{B$|Z&O5BN6#pefgd-u?$M3?5;OskiVUp@rErd@fgPij*T4?YI&}9w z6ZJT0lJg~OaONrm)^HLJZ@@lP%ooh+zF_>ZEAXg=d4u!4RV6&;3cm|EX=EiFe>SN` z{#My~LC5hv`UYo0yS--OPM(vdxhcO(?CZSwg17#`fhtcdHaNv~TXi$DOU5A~u*HJ6 zjsz}{LAvz<3@gYa9|kkvTB(I3W|7I%rP3j6c^Al}dtX4y%^B|*xK*^RxMSEN=LDqH zFU9NjOo2S#$Of$c<~YQ}*!V|g4JYtB8oEAs_X{}cp2XE~B4otGZCj%m;J2BU%gYPe zNO4@qC3}KvEb3P);ieSBx&Cvsl{Y6KZ^~^oTdz54W}5ct&foU9J7V(}UL%em;E|6Y3#hD3+7i6!*48Zti8OEgU zyny1C(gw^`UbW#3yFIO4^ULia_i@!hI)w=%pKp%}BB8h6u?I`nSGjZ+`)jt(Z%#jL zdW)lqcKUO+13p(;8e!y9uem6!qUBboB%N~lnQ9?Owe^pHwGuWj5nQiW? z84K69G$;0{(a-Q-yRx;bmQWguhh!YWEvn|@0;LWST1|q@wM%q5Wu(iX~4W|LzNi?hSb%Njt%+s9Hl^7uGI*_C{ZIDd<`;@QM zRp(%DliMIS1REhC$susn>}J0v}(&1;o7vvLfIDHwr>aFBgPz1;bTKLg3@l+w=t)+PavPoJt?;$i??C z&me)yxS9h2oOS~b0xV`YyYcKGqr4$-0cy>FEL@P?$AB%J)=L5foTfasbT%HiCfb+ZD9IQ79P4kVsg$~5NuM+kXtCG`>&knLu3ZQb! z7ry=3ubt@xMd-icI|F-B5{UmpKNk2rDlJKYR1IEXtp5d-bz&WL)LeDuH6fDFHpsKW zm{WSqDn+$g(t^{4qcwsyuV@W%4_9A+|gOV7cS?Kr=3 z4Mf8g$w`={n;_qf7HWs7Gz}+m$KDX+PQ$E-G_A%eEwukm-vQa>8O~}FF&{ucs5O76 zNnX{YlH$;TP{3LsMC7mlxEOZ}#JruQVASG*z~mo7;pP92!JUJ#A7vZ$K&;xLC!m zBVEV)S;u=S>DZpO=d_+*g+*uJ^eGm%a~ovE*p-<^^)sY~zF@S>ZlItA5a~up@nt)R zg@9e`&1VD6kkXHT^4AWK=q89$y1dSwa=KP!$BvXvtn=epSV|k9&adE4d0~|nL(P!K z26HeYEKE%m8*EJ+Tue<9tC-3Tt9cQfR$6pT^mcN9sRq-q-tfBxocTDmIC1W7eBm1s1pzLQjPGKkIADYY~G1LWcE5tSdN1XN4~!1r@26XIy5PXr9fH$gr> z>?gfbATLtDAy%*rhoy3gLu#NTv0k&Mn z)heEXCi#kS(Li`nZ$2%(ExCp=1%^RL6AI$`)`!#5o?%}>h+BX+OaO>OZlECM%KCmQ z%O2}0e8l}WP`&cykF0Z3Pm2e@_Z2E(M_jCWYvJ(zb`6w1?2GG^+04N_L*PtSzHlSF zSy=zeSx!wvQ4m~p^2LWMG5W6FGL|~vDX3#|CDRt7n?s`6YQ}KwuQay&lg5C(|EC)9 z4}<|4pQAK_Sn~$(=K(?f@Scq(%NsK=1Ev)mD$N^oLuB-tN05Q;R6F3byV1}N{ACmw z!XG}%@vIqwxwj9{SmJ;Jps}_$Kx63x9ZF3@h~oxbGvq0`E+J7RZbLcarN-lOlt_52 zL{0ih5ZB&nTpG<%REY!*JGT!GWl9VlcCp>!6cKQ#fgP3#^(W^EE{wdY zAc^}KE=W9yB5@FXL8#kDQ#Yl9mwy*x9jb9ahzr>W4?(SH>iMs=Lgd$B2Wkc3|2oM3 zW37litPDMyp#rqH@T-i@z*)@N0?SnYCV=ydAU`O^!0>a^2fq33u@st|M?*-8r7cA6 zQeoXkPbQ&hSeUt*hm7Ck&v(R1WwBHB9!JgGh2Hhv4`OvZ<1r<_ph;3$l887>1?PI; z4T%%IQXt1q>)c%1#518e*O6i5jRZu_1KF!F)$LZySI|UcHXiv>?y{!tuI+&In7)(B z-*kG#2soff@TXxy5p9s&exjED;t0Hbw*Xg>T&Fcur4>T)zl;2Ew_PK60{&0fy$shT zAY-x{kgn@$l0J}_ekAdw6o=t^`kk_VMj6PDyxGM6X;!OJH?esV7%Ey4D6U^jH79S$Bi` zZ4=})KU2zxHpLe5x+oCdFBs=~bOgPFVtc%}j?+jRB>wMIzm086&hZ(oAhhqrKjcJQ zJ?C1%cI{QoOuFdG6`(8YQU46dql5rf{+(jCU>b527)AQP-`SJNSzRvR6sD|%-DL(; z+7d%Ynlsl9@>LP&>}aN8E#F%pxqWRA>yk?a9oR(lVL%%Pw9vmh4kJn6X#5|-jq?G2 z4)#r?pn7c<7VVL3qvpkGgW2`*CJN>h39#WfRZ6>R&_=Y^IthvWF{Zzg?0H-09z2nx zW4_`zI8TpGyz4rV8nt1+?9fN0bq+{A4dHWbP7ZW$%>2`*9=qs9L3#w-|!UUnr56sN2FBpN3TQT14Ot=25ONkTPl}F~2fI zri)>m_veKL29|3LC~L&JkM!(VPbg>QkP&jR7IOxvx?sBtM|81htoP()tkgc$6_0T< zI#SN&VhC)gZMtzy1N}#DeK>ALW+M6}2Mde-t6Wsn(hn5^pGx25E&UdpH7QT0QsMCF z^$UrV&E3w}haZIGl;cQD1mt2YLuB9@i$d`j5wa1CvJZ_v_bf$W?@YUAyojC=Z@Db( zx1NJ-@~{n7_(H z)H@&eW8M(z=g-vIukR(TBL@Aun<}|$OdI0wuk@$cuZJyrC}5fT)~L6iE>m+$I4{5h z?iwCqKB7$EZ_sOAP4x?1S>^C zt${Plj%v-->a_Po(85p9>{6(?>6K2^*1gk!=_Z|1ZVt?ZvW}XH)fyMv+ErXcED0hx zfdS!tsKq}S^8S*k^BWhYj>b;dw$i048EEMXu~rA+UfT|K1A#_A-$a$=l;;KprZMg= zL`lAh&sHa*FBxQo)t&IO`#j4Wtr}6DX;1ZiRx^2WCD_*;k^c%Y5sCl~QV-xD zO)zYA0a1Or1stS}_&4kE&`rP8HH6f`eV)}UoUE1n_+c!=vHodA^v!^{sp*6ZwV`Wg zX9t2tevmuMq4Acc7n{VWaa-n;-(jyFhw#>Zs1Eb_G*4IqDHO}}`wF6VgDN3&_GH9Z zKsmAjtJ9u*VH$gjAtb5ErMJO_!*SPR9kCLOu^Cdmn*fn-WK%`*zZPz+IrQA;v64)j zTy6<&&(pF?p%fc77ErxX&zP{8ApW$7m4`3v^UnEK_8a_`QO`=~YqjA@_g$HmJ0Glufm)uk7O>=yv{D|JK;Gle%>#C5f88#M#Z& zuwseV@>=lXGABJBgh|5k!OR$bki&k$GwIo7S1#W~-5aUFcX&!VT1f9>nQElCGO_z4 zK4bUt$HwIQpe`0+W?jnBcwa`!i{W@0^`Ua<0g3%2Ib0{TU6xwW_ zsNR`$Ff<6fF<0e+pJ4daRd^h;gexwb0;BUOpTvFvhUt37RtbdPE9;%>GlA4ED~+AE zXrD0S8<@sLPAQjr^QM%X>4>BrzA$JjoAWy)Nr-KoduGjIXfSw-p?kHf@p0LB&K?F-cWIkR*(lEQGLQ^1-{rh@Tsnk|(jf!bnJrU66I<;o-CR-sg&CDpTxs@SZ9m zabQ9G5t?cBc&)x4MgnBzdrkJ0#>eFET-K-(%5HW=`B0*nM!el|s8~4NXW?HIr@%6O z>W~U;_n{hm7vGG@)10&;Am+p_k}DQ82eI0x&zp4lG{4oG016n(CVfla%}<$Zs&nb??b`g>NGJ{j?kf z0}T$TG`X9NFF)efX^#;bXyhL$;nU-H%EWsE z-=4^7&= zz%0=+fl^mdCk$AOF?aJf=BZ7juIFHMQtzz;asW_bMsJu4qr@}$6bqDBgoi5(DwC6pL&PSiNOi$>+8yiudpW64o@Dsa)bWq_!j!k z)gbbSRya}cO(Sk~&jfu8OI=m8wY9z|{VEuj5fW*?Gux0VXuZ_tHN4&k22m-l7d0(Rx*=5Ib%#5-PYM;?O4y!MwB zTqc%w7%f>~vS~IG5aLg5o<%aBTECVM)f}kPL<~R=ve~?k=5~LaYGP+hNb-#4?|}as zwA0sLW&66chd2&)$aReZ-AtmeQyRg|#_SM}xBv3R=irqeC8Y*It{%^x+&QXs6&(47 zn4FM}o-6a%1wO2{yFFCna)3a1o$mo3@bZ3MY%AEI=i%vjaC+Q2u z-1puYDCy0~fXE4VttXzX^Fs@EI(2Ukb8$aCzVEtL_v)0!Cx@P{k7k8|E% zR@yxHXrl7dV*JyI5xo4q@|-++92&N=`f`f)r)*`c&WqbjS-V`VkF3VW#{#KWk2rpE zbbeiva{u_1&1q+Q^2@a~H@w5^EfsVVCqB%s1+@NeKDl4b5xS13UX?{KbH}#N#dl&QmQnTaov{XB`x+bmK?1y9rl9Ln{}DT%aMMsLn&>e?DYMQ z>1?~6Fe;{~u>%Q@j`CZGee;HkClXUkm1B%D64N`syU_sfj`rhr3y~1vH6O_^PufE= zgA<{rEA8lU3KEe|3FxskOzr(C4M}U3rdclEsxU$S#&xae=Vb958s5{6nJppZ&(~C> z)TC;YzZg!~^~gQhSIFCrez01~wenP^sm<>FPUIZrst`|fOocXYrYNBl#^WLvW`)G# zBcV;uHBuLUlxxlz_Atwl9`re(M&?-i@oAx9^`845^XRcLx37x~H`)~yM`5P9nlfM~ zAKUpjNk%bi__h1S5^2(7pS`P$?$;fQa~djt>JkBMkHpNYVGU}ZLz8^Taiek0;C;E~ zUb_@CN7q5l~#Sqc$`j|;6V&NWH~+;t+P zz*~O9%7DGTTj~1?v=WR+Kj8PBgJTBf4DQj35tiH1zFePc%oZJP|6J}xYY*8nASr;%rGTn^(~1gHO!NQ zj4$Q~R1%}h7ng(T?7q^X)+;<-qBjDx@{fxShpD6q&Sr>Mwmx0PIA|!lM|3U5^;*St zuUn%B&yq$Nt!!x~4<@(tgx^99v>~Cc8ySz7tc7|ANHV1(&r{EXygD0B_a;u#ysPWH z&-`qJlh65W8lXo@CrB@MwkOOYq>q9fG?Bx5hnq2X7pv;Jx46JF{lZFPf^=XYc*kIo0)?D(bBF9T=xV z%vaHPFsr*jUl7_ly)uITzl-^sb&?S~7=qP{30qv4Aksf~^;xnj2p@KvNDOhmK_ok3 zr{mCi4_h^TfAwzgF-OE?2BD?Go`eb#h)jo!9gYo!mHbt&52Q()E(mV$N7E<>-Yo4D zHU%RnIJsNlRP^?8!>nd*uCh{ewx~LJu)My{%0PXUIaqz(h1U$g3T;2bes&*jk$Ztn zsd|AGY)^cKEmZ|zcQ+0&|AXxdet~r!In0Xsq?@V2F_6^|m;B`u-!L&M@!~ z@&eyVjxBjzK!dN(Vr8n`Q0R&@`nq7sMfd{D*ze6%vcv8Tu#-m>(|t)S>MMGQ-mx!p zvkpVef4>rIuJJ&^Ga^2zH!}6~9N-bmnerLC?>aSao$HSHp|F?UyC1lX;b7});J9MX zC3SO1bPhNX=bksxD?T{Lh9+$*6fix9fP>y3(-@!h*%*_L^?cv3 zdunUX3o`#RGD9OH>??QgBOTMXNLT6F`hR`SqoylD+2CuM(QsEe#^+gHPoFkuZ@ZYh zg^BT`V7a%O$&BobVCKwFb(8rW7r6FTzKEa_#PwQE`S)`}oh=N7#dYSrs!P;5B`tjm zo1sYvE&VdT+1u0_@(_56&N64RR|W;?K*tWkcM7l^i~Hf>LzAi2Z~F|l&o-Q~vr(jD zuYi5bdhj1?PK?3Z)~mMLE)^eJGGDv@>LpVR>Kho_l#eBxl=l29ktD|9#Fd`}|hvQTl$3 z-iBCy701l1aU9j5QAfW`G`mCVPbWpBVAg~*IPtN4PtA$@E&CDq2Ja`1Ft3a;U~H!? z53cV@`;BIA5AyO_G4POoy$yO6%~Kb(J^?`IQy&dq1QHcezd(C^CnS!1<%|>b%0J1@ zXqS!x!EU4k&4Zf?zpJl~{`{>}!Ed3ThHo9=JTSzc%pR{pr!@l-)qJUooEdNAQG=yE zB5S_;_LJ?kf(*ig#H;V~wPi`u69mB;}GJ5)QS7JE^;fhoF(vNl_7^j9!oz7`;IXCTI4W<6)r9NRKbKoscY|9ZT(3WTc78TCjTSPBg#S+qGXL987Du|Kuoo*VC|}FI-zp##uOarvt)X{M z{tIv;o9^)-%GX@?`82A|GIp=97p;_ff6!HdAU*Idzk4^;#RKt(am#V1NYpZzFxJ|a zKCzMXNvQMFWqB@dv;{J5;EiSj8zuOGW9gAHs1U$^_dyQ8mo_i}@TtCivjp%tw2ySn z(c32Kn)m)91+}K)W>olOF;2kuh$SeISd^koFZr|lDC2IUe>2nnnfX9bf#Q}U=DT#{ z-e$%eeQu;Ocfd?5tPT2eAtRLJfS1q3Dfp-7wwO&R2l-tkZIGG<8jyS4GXrGNyAP`G zVP+&9jgI*e_THB4FTu}gfA>y9EpgNTQrz+J$bd7ddKKNQ$;+L#h?0V~d$w2FxR9_C zS&?iFUFUE*JrJ+D5bsPo7q2E-nD4T8OM}EJ(5&T(suVnu&bL12Iq)DEIMA{bih^!$d-OR{cqAmFZN9~UZ zD*P+GR(Y3z(Yu7V>4G>7?>=w=29`Id(nLn#`qpJe=3fF!1OhLJQ!mSX6lP4HR{$aK zv>4^OrdNrLarD=`W8Z7d{+nom@pskzG4TZ3T+ic=cHcad ziwD_{RU5)Sos*{T1!mou@&LWDf*>Xv3|tV<(wN>kUkkJ}zBV2gef1@n9a>Qvrf~72 zq+FA$IvtAY=jOV6z-1_z1E|C>`{30vNIOIoj?3XV#T6GYu|b%w9 zd-9YG#6_i8j2-x1TJqILB_1UR)8Hh-7EUff zG$2(!E^=^!Ij@~d%`PX;4mh*_m*@MM-FJCYjp0<=AomK%^@v=I;;fc9pv9Sd_F1V! z$%|4I#t_N$&R0RP2K^eYN9Bv+#Yw+~1)6_5bR5v^XCZU6XzV<)XfPzagVFAbxBA7O zlr86HUjMc`T!ah@|2?z^WNvdkTU;kc6K)#L*#kc!w#@9CDA^P$W=@PMKc`oGE8zRC z%vBoAy;h^pPumS0$BfU>f`FNYP|f@K;9`gYayOOQ`o`=<;Ji@}@s z8?@UuH0Zb*z_q}xF?-OrQP%93)G7y{skzOVayf&HLP)Rod*eAnO@1k@N)apXCwpFu?}~nj%Ub6-pUYYFj&ARdRtKj*oG4T~ieD zT#cmGd>uJljK?Be+;UM(&r{wC*&B+i8>Z1^>6Fx#8}z$`ZCMW{8?033t~O)!Z#U>p z9(9OVi0>z_46xqot;R6SY4%MGrRMndWY)%_5VKK*R@q@$Vk4la)*51Avo5@PV2Z`V zxFa_vkB;NZWT)y@HL!=7()7wVEDf!hD|>xTk#$<(fEWjC57T_ECZN4D?gC~R1 zwAoB3;4yq1948IL%QXSEICW>asEVLIs5{ygtS*o&?SSD5Ra8chSx ztY6T|UeHF;UeGw6(Jo)mym0PETf>6xPdxfMlDMnYm~PTNF|b+N=n?9YRGX8J{ze+- zE8tw+KLFxxDp<~`EP`#YMqA&l2H0R7lym?^{snBYcd9MXk4Jhja5uhe)87(UVw+&` z+-o7nsDC?UA?x}MJ~KX+Dcz$~U@+V4t@(i*%OesPSTzE|I9mb8;zh$J`rPvQWjNe zrQwbT}ordYtCZ=cdfvUo5T zFnXo6KaXW0D3WpNnJ88Pm!9RhKLoo#vE`y46`$9g|7c!DSvd;pk!FGd)f_8T@Fg1- zFrKqvBnuUtAyp9V#gINmtkcxVJudzi{~1!~#gNm~$Zr=-ZhL=9WxrVR7O>>6)6IC{ z=W?H|A&ig*3G2=|b zeBTkDuR`RvPRJZC;o72-cNQ9 zSA|H_NiKY*Zf_mOtM%&2SNqKzEm_HEJ@2+K(bfX2i(3F(WpV@{cd z$z1}_-t#xh8#A=9eL8G#BT&5=SXzPVUE6um5Ni;y0icaBaAlrwT@q|SkUV9` zTIB;>Yo%&Gd8DTy)mDY>?{aQ%;jIc`Za{b>=v~BPQyKLfprvw~L@YUYFb^{!F zM&3U9Tumd)y!rpZ{HppIux={3Hprfi$a2njOszd08cln+-`mB#!gJjxy}6zxTa$&S zTlRHX&_u}UzMk+H>=V+3ME1H}&1ko$d^ch%J6eD3fl-H|YIub5wMTjHPFU7QdhOhL zc`3Osty(JlxXMu(bjnltPMZ_hqMLtt4Bg9r}i`do;^Sd*b1MXLs<&K93R}C!x;5x#DyG-?v5t7d!y7JD(e!roX z2-a3s#a0%)qSj`tI++5L8gso|Kc`y7D>xMp?pG8$yr(8O{Ja@$l21+??%(niDSphH z$Qv9N#IAgZ5Ki}=Qo;LERF|JG0;x*wfEsf7YMwGH%{m>mDfjrm@$trZJ59O&81ucl z#nP60P$jKgyFWVw31N_Dc8s0eCfybKs9erFU(M=wTyIwDKR~&K+wL#_{T;X0YkS=I zm!j`?e+t%@BYuR3XUrOni2THIReHU z%KN~Z0_=B}+O}IHO!k3Z<**88_1M2>Ct@^g@A{~COCq@SYr_J`(5D$57i*VebdU)Xw9rAc;V?Zf7z{oh*GcHmk`c?uuI#^?5 zqEV;?sUi{3SWpDr8We9^iyU&jm-zQO>QQd(_gfj!e|4|=ED7vwslg#|p?Jv?R~2ON zY|6VEv8<~_GoaUB-$1gZ$W$CBir|&i`b3^=&vQ^@YHxF%3f(9Cj0rC|5RkpB_V2C2 zjIH2(fL{wo!b0GEGV7csru`R1vbTwO_Zl50cK?%`6BBrwvxW`tBoMAtX`BFIOWm#w8UcIq;rjxtzc;$M|S11d?g}zt;|D##z~@ zFqJ3|esg2x1JQ&FV}1pbiax|2tan#k2|&oCUy{^dVufFp zzogJY^m>pPx~XiI?1Eq9X5Ef88x#DkZQ*m~4)Kg@hSwK!!kevgXV-1NmfDi@^Y9qy zTk{(BcKRW!l9_J#jg1|$|EfoG4E)|-z>itjlx-ftdOhUoh`AB%fd{J_W2aFr4i$_3 z;e>p6=)v?GW(v7$_TJc!Qru%2g@4mFzSrVUl^ESKQT)~I+|1AWsI zrtrzp|JnK??=WjGixG~xZbpkk}UJ$=d-T3`zC0wg*h(}3?g|9U;p($rl%)_UixxPaIS*DFd2;v-S zq{`_v4@A!;24!@1^1+e1S(vR^_;&BH31zorJVqm%*VMP z)>Ti21KUZ#1J>rXuaknQ^MnHu?#_37z>&JVmbQnLy=Y_A_v?*&Sz>Cy4Lr=Jt9}rVR}meI)5QRk^ZO(#7Q0t{J%sZVYs;KsGi{xZvuPoUHF_g&A;7 zY!%eVvoVKp32|+-t?K-GMm*l!k%vDjZkiq|h`_&yjjl7>91>?81)*;a7dO4C5Fo*g z=3+Tt`Yr)gIx)m8m>LnbwryFS%9cTZ+4vYM%aAS+h-kIBK>tf~g zE~AzCg`e__ZzD$i8kyC59)4whsO4wK3B5CJz3rOvOjZr^nUK9+1TDurjGKYIb|ym@ zqd}ox#PuQ_&U>!`(a?A(UBZpAQr4vBWw zrZ1t3>A^9Jt)nZ&MA->S-~JYHcHI?pdPXe5lYdAVA#u-zQsg%H*J9KgXRFU3cMyjt zFF}dKAtAH_Dj~`ZQ6Z0SSEsyVt?wv2RQ-HLu6HXt9wY&|Wy*luQx;BN$C-*IC3-Xa zvSDZDpwSQ{4&}t|;R`QHB|D4@^eQwQtH_ErR~G(kXYUM+@n$La6v`fwy}5c>a}NPE=3L=UwYpk|1Q14rs>Mb?+`ol zqBNSd|Mu$JKYr3Wb$kD}Lw5IT7q%BM54ZX<3-*{dMK-*Cp&=GUQ>@f}!!DLW*f%~; zl1su8z8!y;T6EerQD0zv# zyOq6y&|%5m0K~015Vsyc+vMq7z{ zDJ^fCzc)RYM*r6}%UaXl6`q&_bXsh+kc>9sFh$plO5#Pkx=NRlRD067sQdQHsHaQZ zhsIC#k&`V3!&x)%wbYl}SNX|10mrX9sAr)uFMs5^j-}P9g+ilhlJ zaxl#_N1JfEw#?e;lQqbj>mB$b*Qq5=Y>{qS1o{=;#t3?$31oqqSNz#nNxDGcnFv`Z z+~wo*>=;7mU5!ZjzpcG|ctdROB&`J{PMUn`*s6J>qt(V+b(UA? z&LY2-KF_dGVCCI6^K!Jx8U%>t&K#;m&=0fBN$Qz8d*EvRAvQz9l$|on2P<$3uJrsh ziQOhzdD`%}-)+I<$<66sh`rxkB!)1F^LW|GsGnBK1l#5aUfFR@x&r;hnZPGkt98Bt z7s&?R9qqv1zk_!&;uTfbHtTH}B5vvyTWj6fvLM$E=cQkL{G|sr57;$)nvA&`&<=c` z{v1D@frWRcF>5y)`l^LKv;LST`ABQi_Q$J~ckIM)xPOpkxL@v}e{jm1#rq~IuEFnv zzOQk9=68Lav893vMEwAY#dCV?PJ1Qt&v8~?P3DM#n2Fo6K%6~a&-2}MXY_ak4t{OR z6Gxk8Wo!ly4wJ{CVzi%mo==o?gHJ}F+ttm9BIvUl^j>zmqz5S>OZsg#u`OY-rCam1 z%$)_nzW&aLJ+F3Mo&C2yi@I3CH36M_q!~Vw?;MH@C*<`SVJciKpBy{{zXLBBzvId> zYr+Y38*lbYt+8c}tO+9Pu&v}E`5@-Ilm#K_iCt?jFZ6dEZLQobVd0q1B3ki(lNzrv znX}lC;wotv%3tnWX@+ZMKO$tgr0277@~IF}%(F=XH=Hw=E<(qjb_rTW2GE{3xro|k z#R#r?qN8^m??IuiT*Wl7@ix`{%H^PkYgO|Ruaprv>0efmv!HrHCE)@k98aU$D{8xV zv*tf^g-3HC>I(5LZVmm`k#99#|=69iqq8j_7a zVu-1qXszJH=g09=|j`J~V-UZwDK|5mw=s;b~nYwg0so57;$96i4^J9p*qz@$TX3h2&D#I`V#ue^60ko?4?Ba|W-^IY zr3cpeP-gE{#f0ReAyxy{RI!tPc?ht`*LKYSYvwq0ZEfIJOJv?((!+p3@6fUn^6@FCFYu{Jt zyewaHOou<0%q_>&OB~k+YJ-)|z#k29rfM@CV%%e^dIBADF&3GiLmmiIg-jR91adF1mkTj z9BQ2n^A8T8soi~YYiO*S#4ldEve)&Vm9NwFno&mQFa)CV(O0rJajigJr$`nC>~5>0 zDrle)wt5+qSJv-(w2O*Yiu_j-9bAA~#`!i+ttoo?-{vCq9wK;fVKkTCp{>FUS0{y} ze<`Du5hQE!r-9~Qb6q(|5O`jTk56OBVT+HB;?Un&v@3wm5BC>7qla*zP0;;TH|$6M z$YrmO6~>txFcm$ODw|rujwy8I+(IY?M-CX^XEXT_fYnfN)xGR}HfTy6iSBsC`vb1d z8Nv>o>>B3mt2KPWB)%c*%Zub?Qnbxp|s7$*T-{cPphuy9&MnHMOq| zTqc?*W|G=DKxzdWp#cDwEIWU|P{)?$8ydIHc5UcjlvB0N$284rQ@}*#|5QHuNbm@_ zD6|iiXK9#wI>QQ#mLa}@>5;iFd%n)8FcuCO)R3jrk7;5m5HADXJkx#IQ|vLblXP&! zIdxq#ht;G9=K4_a$KE975HjG51770u403Dpsj@UYC_-K=ldjy}&fNZnZ;V`EvTYBrbMEOnCrWwE5vMYgxSv@RO066>tN z-a3qs)QmbdNewV#zysQUEO0SxcI3F=ty~Y}GC)@=5XDSCeM$Zt&8POdA<&S4peUm{d%8+E(|%{9aA%kh-f_NpM-|2SZpYUFfXDN4#!S1ZyfTEV;fygwJV`<516T9|~%bU1|IR4ZLV`sT1R|$WQr4m7iI1 ziwY5N&rITj->0IsJ>|7LWz+X}$xhsX3zfRkv`km|)I2WxXB15C!_5wvk(TE#7mkff zr-G18ffg(ez!F~k!nT?zr==0_`RVr@Nb{e(GIOwzoKfBItojIxXQfDXifxfgVxyW?73l}%pXGbg`vyG)rvkEOkRz)i|oS8Me0118D(;KV*NL0O$z_WfK zq4^&PYk-6{Kq4uw@rA?>>lYI4wwgH5XA%P+FY9>9U2dT>*!iLWK z_)ux%n*H$*q0+V#zUC+TVdLf>>S9u}ph=p<$f+N3v7*z^^iWzIX8Z6f(uT_tC2sYP zxoQX3)DoWUpXM2TT>(--rW*77MwP{6zJg~j>9u21qBbThawt3~keJtF!P_3YgiaCH z>-&L_rsC$P{&-2PDcU61BJa2Su$6R}_;hP$wPY#WXe(%IAUbA+TS)p4x!f@2`(fYL zUovwEC;9$Bb?7*5$;|9q!PU%d-zPt>2Z+IfU|sXat1r;eeVu|j*mAC_#*NXhth&=M z&3V_#IA=K8rjC>4E;T$~&YKH_6p5oOOJ?hSqMPAhN>uJUP1B!jUQZsaKujxaSNSy! z9VMG)>OOi8X?NR0k{#;%SAMN*F;59ig@I7hPt8jjSNf*muf7!OP8^5+#ms8%SsS zu3Mi~!J~bN-#rG!@3vEr$QZ*aVVfTx45f#_ubmBs%D%y!C!-h}c^z^3>k@w+348Oe zC_{H8TUUil;Cn6I`TDs@PC7%do`dj~(RW=nT|=;z%~$8|y4NwFpp@gcfFli6QNi~g-fzCOsjYvh`Xu~%X; zZ`f&?u29o-xv@z0|3aZ9lI!&rMCUOh<8s4YfcW$``^og-YSewr)|ua-CRo&`tEh;o6|*$Yl?J_oC!WLl=5vRh zw})AS*6E}$h3{ku8j1aS5eZ+x=rHG5%r~-*)Px_UoY86er0k7#B-=QHBl2%>eZP(9 zu)p_yEmsaciRjuDUa|GQ)i&M4`66mJac~wf2j-8G@tu4eaqsWzWzIc7Y?z}K;-vOP zd)(^OX;)C64wl)$*&6rSFFa=Wx56p&KFAuy=y;)TwVbIFe=XOCeq8^_r*zXa4B;_`&CR;=GU{f!#wFEZS_-rkuX9mJg{+OZQ?a%PGJ`a|NN5#H8? z&rw04Rt;XxQ9p`8jGDK$w-tu6-8HY*V*Z#3OQ0fD|)``v+s1H_Kv!(&;) z+h*NoZyPi1)@h)NdOh>})Sz3FnxgT+EG7uNF>_7P^eZYTIcRa@HHoR}A!oJwiHLe? z=fM1z!g=kFa`5GLN47qSv&E5Z5R^)D9l2`ml8Wla%gHaJw9w!u9-8FizUP25K0e7o zCGx_ZaMnGVeRrFAUI7mKJ>NpK){)Dw2##n|Zo~uSvCAJt!Qa?dH~yO1Y+KNczAF4p z6xNom+*Rmyw1S9^`SEPkLR?7+HJDrXh?Bb*3zR2H0bSHyifJ1OXTB~oI*v1O{sYn` zsgga4TC4bj_~V`(P?z$L4;oxlGY+z?G(5^o824qnIWpg_O@Rhf-joX=Z zjc{gYTzZj@XBVy>=0RIV$8IN&_@F$Wws`{A^lEP6Wn&|If$x41 zZSqO#N2C9os<}rYQb#M1h+Or?$LcaUG^|hwitn$DE89p+6I}wds=1*Sy?Xp=!ceDd zQPIkqKrhONwfLclPrM`w-Po3WCQpwNEBmBfnKQPdbm_1Ee7 zl4eXl{{NA-dUxWulg|Bgx^r*u$ve+z2+yp3*w!a{ovY;>Dgy*}C<~}x4{3&6hnw=0~lUB4;{2+De)0HESxv5o#~@CuzI2fHLiqkMz%Ray)#C#V%VYH ziO-G%2~E8UzA_pQ`2nk-AX5(RUG1ut_EK^*o1#-a;^b${pN(oOuZ_tcpI;K9+>eZS zS8u5;nM#b&Hk)B&e;xD2`G?isN@Sa*n}}g5CpJmsq0#XQp!D}V$lS=ju5tjBXU7he zFi-0&u}qy`QnTz^Jz~NEO)p2Etd15t6fL!K)0Ibzeh#bV#z(`%1wkHY@;-RjA5Dg~ zxfS~!{ng9*K28TEULZFHWX=2nWQD2zk1WM6|EDasjf@ed40gAT7g;S1Q$Y3^;Y0(n z8vm0usSe1hn0=N7(tnY4{_927;6Y>rEwnI-%g`%oo`8E{d#GhzyAXd7h`muJnh(au zKN;CGIYaK0kJ{X;uU30kE%ce8|J#2o&uJG9q#YCVf2G}qLZh+0noM=$Jxq3?y)95( znlJU71GE6G97dIG^$+uh+&Z)|QxS=~u|315_O|5-T{1^eMc7OEv>|KL3h(JB6 z3o&gCU>az!_<7|T4p#7jo2-Gpnx!xa@{#W zYGLc~gSMrH2EvtwWGsTEIj8Aww$^5t3I8;U*x~Jw8(W*o%}Q}X()CKtH`ftVWxs?x zDlBke2h+A5ez!F)cp!y3s(|owc68~q4YMnXEJoGW`|Js219V^?Gc%1x%Z(SuTpd9J zULk$u)=qnb_$yxwG<2=YRM4!yJhY~#0@1i@H@#7wY!fvs;C(_ z^@EB}3t5Oq8$`wV>zUlNHLjEza#p=F8{C2mC}tT_aJ(G4zBIHcXoGrYve0Jd2@B^C zm2Xh~1Qe*Ea;_4q|MLr?`IqLOjOuCv4iuYlSQ6(Ow^=g$rOhs$xWdc2UE~b?#9)Tf z3kxEBK}QjPMo%XN(BG54pmQM*e*@4#7))*y;#ViNIjiDo*39C3%^yO$VS|co*~QO0 z+3U^4IUB@^>qXTbd&uZUS<+Z^Ximb8NnASFpkyMH;zUD1?xFZpJw?tvT;h=Y9`J4? zq`IB=2P9(1rh~M$t&T(-lWl4G6}GaJt^4$=!$13Vc|p@qxD*$fueH$ww>0%NOJL`I zCa$(N(4Yok0Bqe{-0y>A^R2P#j`i=NGs&B)0vd7hED-v3&%(H0xqTke4 zGt}^(E^=$5hz0|TDe%USm3uIEU4+2F#hH}5w*r-d;-f=f_2k;mU~h&2@8`x=X24a2 zigwpz!m%Z*o_{$mb{uAlxzHlZ71)fB*ZN1igEf|$tq4?CyDR=tSLObQ6vY~wOjR&Zlays(62DYJ#(z@m2ql;oQ84NRh zCO`FJgR~Y=$PqP*E&cJ8{}6abH%@;dwz6tRRNfMwQKiSY%s-llkpG;dchwTRsC7)E z7O2w&R*-Ca!H!Pz;uTNwp0RkNMK4}YFLHngtGtys8WZMht2W7V_eo!&oN{(jI(g)mMx74A0xe9^5+-*J+k(Gelf zlBh?bJc=oHX;Ibg7QX?6dTs-y7*bzlxz%`CWt>^@OT>jVGmf*!H?&L~V+>#Lhx3}D zzEhTT8X?RLmNuhKF>P2)Bg>68k7RUa>+fbE$c<%Hf7Xm=Z22mJ#+Q#h%z6+{Hoyf9 zOM%>LZlkEfYwkGa0%qr@JNo2VtOEH#vhMJ1H>P}J`eikA^c)fYvg?0aubyf~n zH3qJ5k=7VTM=5ntr9U1C8SSGv!=nEjqUtl3RD5uO95PEPox;Kt7OB@PYZrX9gkviH z&WB8$sR=Lp;8eb>S1wrzuP}pYQ=3IzD_IH$(*nO7j){JLJ>k?%Ez2GSi}&f*4V@h0 z7A7ethH3>_v0xa7q>Jr+9Q#`PrD})Q)vJ`ZWes<_LuPB7L|?xH`L3I^af7 zzgn8jaf*nOe;=k|1(WaMs;VS0=~b4NRv(ru@#-eJ^&E&@00Qwa8ue5#lE*dc!9=$P zN{bv>H5HPH=oEVE-}zq??A zelgZch@FBP7TF8&e{forKOc`%=$hfFrQ+>03jf8~r-)V9E>JI_Y0Fm&0f$>YT^0HH zJnmO^-0$xS`>nG4Re9#pJ99ddcAhbl#xfF2n?DDvC{jhOYdk}&U;M@nwOg>Qb4dMm*=vx5CZG&crKP%A-5Yi9L&NJ;}q@RoL1whR@-yM_1$Xx zjS_sYs$0ux+pi*Mslb@RUs7++w$n_#sVwD^X|pxw(uD!&Z2)@v1)3840`2qyO~M2~ zQ-YtNImaqAwTdE{WZZsNFK|vBb`+(-N0msvQHA75*gJ?ATK%b*REoM%8>$H7;?etR z4o(~rD>AV1Ubc94!L)UFHl3W0r`IT(T&3owNGw62+mv8nD|gt7?6dVzK{IF_1TX*6a{XcHGjj~- z0a7pY*A{$R=5GFcpdptWSzlotNiU{~&D1MwRjF#$>66R7Y}eO{;eL4>6JuJxsYmkJ$2fxHn!IUr@F;J zfOTTmT9kO6Q$nTL5N_4Ule9WPgBkBMV|6U`Nu=(~TY0 zKdSsT!xJT%R6`J}qTUlFpBJk~qB6=6uA{%K(&2{R2iRQ7))EuH1m;(~1e&db!>@6R z=X`(uRxXc$ENqZeN1?Y-5NXnMkwjLlzITctcHd?V&73xS;LIsQ_@4}haF!7`S`%d; z&SOQfKjU|P8upv=nSz1;;+hAmiTUfMSsxG|uFfPmY#Y;Fb7Dl&-RSn;F83X`UhmkU`4_a?ka`A@UD+_cq9o zONuNcw~izb(}`y46_hcE5D{<(u6FEj_TjTTLddbhps^}4J>{c6=MO#~mY-i```(_f z`92>#0_5b z(%W<7_%f%+3lZX)-XsM~a0F?}9(aBGxwP_Ca#)Cl>XvRR?y-u&*Rd<=DK?CH^K<7~ ziUS>fEoRBPD{oTNSeoK2F2H^d&gIy9oIN7C8wD!%Y}cpm4`{ykD|1B|cm|3Ch)Wt& zt^NlIlF8iOFhti4x_Lp&r0kzW-wW}s8ajt`z;pWnuD< zQL2iMyG8EV*^i*7hm=L4l03DXQgnm_GlG>%Q@TLvYB5hq-W;!LoT!@6i;{FPn-TJ5 zIT7cyI#w7N!{ph>mcgqZI9`fu!f(ibE(pLs-M3@~3d6cTX0JUx#Q4!jF?Y;v>NKOq zjAB)tBOMr(9ylWCJ3DbOU6RrKA=pMwh6Y@VGW{eX-FUy&9zQ2ld5lA^aGZ(HrjTb*7$;Oeh|yocTyd-oBCoN!X>Z>f-k)wGJ} z8CnX5GH+uo!faYkQEyp=RcFDi=}S&=;vZKku66kO-jDhnzG0wm;?_Vvw5)V`Uu#ET zyrY6;2eeK1c^$y0;D9!0A}Xt!vwNgQ*vc40L217^-)b2aUe>iJo!{Vp$5-VcMW4Z^ zC5-;L>WWwLG?c=zBzzN(_ps(8ZTK{>mLV7YX{fOP-Gne1ioE!`4IDoFP`OGA;b^;1 z%)RoGAYbt zq_ua}wbYIz=C2BJOlj-4fn=}N5NNk@!v^b>vs5@4uQsn6Q;a+Nj^^>7;I#~aSlLH~j@M?M0WN)0LLLwM zEVmB8j-+qipZP_*32>OV1jsvjp_LpGIQIK>NjVLV>-t{szXQMfQ2x%z&YXO%LILW(HO<2-VoTFgn!bJrf`fG<;MfA5@t zZ184$xHVE2%@-QrW^J%hHX5bX_GcL|au8`8CkQ9^<~gsK#@M=E*g zy!&E?sZsc3L-lneQN4ps^%Q|p-oHg;^rph&aMR&b5A`V9J@cF^5k>f~x=%;b^LF*H zMiqF*ARh_MVR{_#N}}cnWsa8V=0$&EM7zVGev_X&9`jVK-s!-LLZg3~Z5D}N zgq8DXnf&{8_Bcc&HsU|n%5~x{9Z&OY>3v{QS`pe1yT}be<=@bX>+fGb0zcqpaKZ~K z0z>mX)RBDKHA!EYvD5>yO*{pfhlVRX=@vK`H z$?3z~;o0@g^p^cC?jJ;^UaD&1YdUtm!v^Ex-)cd%4DM*PMZ`+3_P{+~G)q@u_=Hpn zUClr!hqE<8UANq!rTgR##+Zq5S$ZTqL&Kl+cC zjq#L9)_u(;oFWPhZhlLJQ0T`JiLa+4h3Ly8yeKpuYL%%>bO5^kpNH#-$Y8KZB;(bK zJ+G&^{hlrxH-+HQ=Wl6zyjlWOXzP@2FVqcw#g_*N=ktHEY)_Q@wau8wHS>m?%ztsATt0C9;(x<$}vhrxpoiQUau5xuqT93zF2~ z3l!}KfYE``YzXsQ6ug$@$MoLI%013YIxfB0cf3STAlaCVLiL+pCjZrG1EC- z>H3}Ss>7qlzy*>C_0pUH{DRY8L~XCpzsdGZe3mHLVpF*K(U~L?^O^*4%#B6^lp~i_ zs=-{e&YcRfjO*gk&X+;C3`W#fj*5O`XQ zRCcWJ+UVu$hv-q(?0-I{MV~y?x;;Jq?4>{#M*(q0PqQ=13S(W4FloXW za$t_%(4*{WlL`jKeYhgW(+kVkaAuRY+x+Th{Qq(K-)FW~bl#p_?~9HweVwTP$5(-K z|BZPfv;86a-0_mica7zL4f}te`(JqUah&(Sz4S9@=iI@|ih_JuZvsr4s3DbHNecM{SsG2BykeAAUl z%ZQr6b3<0c8UF=kJs2g@|Fj*~|F+%Gy1vCoWOwhvv%d}|5vNxKTMnXs0RK&4>Ai)c zZM-^8mouOyweKK>{XVGE+7NwdUpVUdL(*@V^#i~+me?Y;vx9Uc0n*Ex--iO>p>^B% zdBQ&={g&wzSGzc@W1)kyZyi7+{e(yM?Cq#)5U(K%<)$nEToFRarLZ5va*mYF{ zkn3kVScC=mFhjNLSCCz72a!pflT0n1^sa-ZiH^Vi61r^-%u5h$e+F#_THal|^~*m0 z&y~_e|HTT|e_Mgb9#HvNE20&)t1|rVrpVTXRoZV1t z!OMO-&|jK-#YXt3aH71Jx1SY7k6UV#R9G5=NB%4&9TlTd=FCK>Yn{{FA#62;xiOe@ z`tr5kx+#?~BZ0OARpjcGnm7>d?zEFSNw!Gvw!x%a?X3&BwX^w1CqLP7}(6Qa=IJe5W(AK{CNPp zZXA@NN(YeBMGsTXxiBbQvUhldi78#ub|wP~yQRTFjvL0pX0DRCs$!cFi`4xYgv``J z1W5nw3koKeiJt60W%&;?{1R>Lr#EQsJ@r)hp9vMbt+k)4$%Bji!&|rpK~@I`G&s+G z1ZCWhAfE#A2Q$ds|Eo*4nxoiqMLdKWG6~Nf;Lf|U;8;6mWK+yfDusIbzvSYl|8zcZ zMgu%B.|+#eiY8vl`ury&XCk+wgp4XI5(LUx)?gE70J74KnrrA(3&} ztqlG5yyK7pP79Ls%F`A232s?GM_NflJz-h|gp|CL?1{wx518NmwENdodMM+h)w z2=*RuB6g*HsOS{7K)Lw_jBCU$a`YJ+WJ?$PyVw^{!!c* z|7V>vgN^#DO8o{2paDwFDp2=8#`&G_f4>8gD&4<}Y|Y=a>;IcXo;@uIKgR_1+(&ok zVhwpEPWGP`p(2Rv|5d4!f(g2S(x`AUi*w{04b}k8A8M`a!3DaSte^E=R{vTE7eRDR zXN!m_PQkqgWKeav!|}Zl-X-RKdS{Jf+};3|_;*P!R0Ri5QuhXJlsq%NrQSQzdFC|q-mo`pP2ZU9}w!$r!3$v`j1HYKA1u6KoL{Is}7 zTzx>LE=+q@0T_2`K}Ar<8)&^vvH%AIHUVP><)=kF1PMw;hE-Xh`Jl$@0m>t=J>dIX zec-nYYE$dBCX_UQ$p0u}fcKgL8fMoO%A`xz#anmsmzrw z&}ONzK8eSa?e(S>zlefbWbk%C7xu8NqUdGruqv>DuP+M*C3+VRWYq7uZg)}KB~9Bz zc|jc=WY{1gs(*LOUw+N#18(@2mU;nuv>E}eVIhbIR0NR0!C*lxAP6)O$W`=L_A@w5 z!Mgt&(yx`EZVXU8Kd9sXQ@I-_N7G|6`tN+YdBR<)L6-Tg2cS5D6$H9h0Pp!1OOQx! zHBhhPO9K7$VHm8RY1{`D7BewcTOj+smqPYs4;c*L7lsBoKFEoF?+)BCApY{tUk>rd zw)=ozZcWGpw5x=d1AdV5kNR$A^|$Ik*%a)%VEzBg%)`CE9SHPl59kFjSBK6*#!zuq zVOmQV2?(bu1XM94r`Xz#SJbQ$!JzLggYo3Lm6J>B2&SzW`_t#3Ef3Xv!W; z0?rRUqu?I;-yxW=4R|e}y(YQD;%;^@jR&Wn7|VF@?6C}>oB{fQX$M~mGB#Prbt&l9 z1>_2h4fR{BIltlyoJ4?p@;d}I|DO6s=>0e4xJ*3wmP>NP9~N^3JI{=)-*wnuN&@>k z;I*LZ!GZLfDB!k$|F93|r9JU~MU=A>k^WERoD%VY=YSs19||bg;GPxeAtP6NY?*-j zc8o0t5#bMx7`^MD#+n=GB7-(Sz3;}!()8GA5*~sz(AyW*%1RJ*Ps{z90=0Rr1Bcu> zK=SIsJ(`W>2DjGhpzeDeXh7fiUB=HlgQJ0Ip`7-ix4r~!L4nP`gQ_DBP`$y9fOKgl z;rF3d7I^Lv3pDed>kvij0$B`4MPhxK>^qEmjCB$4hi(laSf0LzyiK7{o0|~8uZ3j zvbfxT{uL7&P_W*}FI$hwneX{04lMxJUhFN`3@tbS;R8s3UwF7Y?j0X5)OFbYfTSs< zQE}5cr|mc%LZa3@m&aRVUtwTuJehUTbllbaXR0J|<*q;?uleU8IFEq=$v*6xIwNFQ z^F8lMpDpU@$wFiZAx;!h7$pC{|g8F z*JH4j02?`R3|@E|%8jPVYd)CAK0i3t1fXPSQ4b_I@IDWyB}xt-RQQ(|&vib68uxr+ zpjwUs^z3pZFXzs*5_yfrMa^ACvZWKV%e{%2K-7bo&s)xu6Q^WGw0Nw3;Y4+F+;X61 zY?0Rl>;+=_2mkymH9?*6{ev*#(;>iYG-DHv8ozitYE&vb7_wf?<(CD)a36f@x3htS z|L?QZj8-j{V4nn|pOCiylc=MmR zlBjcM#^ZLZ-z1o-&(Cl8F8Y_HhnMf%oNm@Hi-#?>?VCL6HDk{dv>jNoUWWwVJMO+nk(Dr}%`+9HC*y+#=nM zN9pTa+Px>`85EpNU&?o`hJ@|72byP%o^<;EU~^qayJEOE=w`tn-daA85Lp`@QrmHg z_beZN8iaak=|K4UMCWeMkByQSSmNQ^@uf&%O=>CiT8CE!fiT;|+QlyQso+%K#WI8nVTD!+j4 zH2hILBn|@-?N%(kHoUzF!g5;51j54GC=9|fR7YXW0mNfvC57$xs^Lbx(Xj>s*9ECsZ+DiEXrG zyl3HxA!-XNS5o%pA}zNYVJTwH12hP1;4NOV@c~dXaQL0e_itR-fD*!<+eS|ll=_Uf1i)wr+@o7 zXkhgxs{h^U2xvg?-U`?SxI*I|H1M!w8oc1w6@M-PU;zt$3;oX};647h0@(KNeSRw;${k|Z+y8rm7M9O|@A6cE9pHt02{}#ij)mbGrtp!@7ca%u zgQq2oAKjsp;LD|35YR3jtB?=Ou_bPIcQ?1D`GDZJ-PVGHwnLNz#ExBHAG3M#EvvN;r6`plc1_w9-0|#VcGkb*0b>9)6Ey2-*@S= zXZS zsM6-?j*A_#xXmXQmF4eI&isuq?Q0Pe#?<8u>?XR0P)%^lDpIAQ6W<|0sG%WbB%on1 zAmAV#0W6+FlnCT}>M?_WV334{zyU^_%;+60ZA@*A-oLlAr3b&T(>a-&B`M5X%rhXl z6PI{0oDnUr)rdXGnNhQQS>m5Qv#A=fE0nA69JxS-b8(!tApu=s^Z~EbsGr+^<9W>F zra;gNTE%KU-5c~SGOy2hk<;@&H$R=35~5mE)Z!F!@epia1nH)~@D*K%^TiW-A%99^ zg`HKMr^)CkA$()n>vfU@+!YN!kBqv>_cY282b>Zn6o6OUly;wpdzNBRguce zv?{_tI04!%ONWM6(24rnBVzf)a|UhEW}kH1VXH-@#i4p*tLN2>>(Ep#pZ8KCqTqQ_ zEsZ}9S@uK|v&oK;jX{p!*t79ay(3W*iVl5Czt0!^qL&0Ye1YX#0`;wmc(2)p_?O;n zVzPcwMhc)OY@q3Bu4#T@^t8Go%4sV$YM)QF_$Fy#_guVE=^NgW-8;2FWG)Zbv#Tn|ozS$~aqZsy997N4MzNJK;n$xZaN2BMK1-hJGPkyJSj2Xti=~I{%`oq_xn-7;k-A~ zz|0k4!9q#jQLq1kO+W4R#P<-ju)NhUJUaRIoT}AY^O|a8iqUV+7i{ZJoI~+ZMXZp< z-KDphBtlh97h>_$i%te=`zoe69aDw`_T9ue=RY{T9k-hhA6BK}%XPKrMcv!bJYbxa zZAXf~TE9XN;q@pJd^Zaj#`tlmzB=_3`tJ10a+CWxKxJN;&+TTz;QGv9j(Hc`5eb_;SreT z7vJ{zwC=yPUKV>e-EK`@5`X$ot$udeyFR#E(0sEAd|44Hy5$>}cDcLL&-WE3qi;lM z)exuWoTlOHi-99v1fYkC?m!S16!wYL|m*pf)CG(-eWs& zWr;6EI>T=MCB?vryp1$|7wsEEr|k7G@$&8YdNAMp?)LE#pT}i?BC*!})m8tsV{?C4xtWj zWDTl2h?ecSzP5zZnoCFaCS86EG2W2CGWTNk2?pa_t|zSdXwgSjFdpa+?EZNN+Fx3d zpV4Kr(q$9Ty-UAa-@pqI(uhyke$nS=rNggH(dO82drGkAw^~o?+zFl0B|^?MKDMY;4+N7O3k75=AlJYpl)^E z!H}Zi7~r}*eJ|L;kZh@F2<4YRn*xZ^_*)d4D{@FONEFk55oHRkHx1pjiP!Q-goI(h zGCYwIAIfjnt$_0>!+_n%Tdny!R+3rtcPmV+E$n6}csQ=J5H0Nb?_}-~7}C`r<5aCK zu_nQZj6&!w!*w;mBjHr?4dJxDf${r+Z2t$Q+Y_2%b1Qq%GV+!dLo+Yy1p*cZlrl&! z>w%WkJIr@N)#wan?TzN_$RX*FU1`W6f~Yv-op?R`FVXO}4BI8qQFPkRnkE|`6BzV4 zWz$)lI+W(BgrSPqPoj7*M(S)Rh;OAQj(j#y(U*qEC~6OnsM(@ zL*kXW#Nsv*uaQ-P+)a%(6Q~S7rst+pyAQSDNq)1yj(Aq34N)JTmIjHIq|;PdW@={m}4m0@3De zz9fa`a_pW^e)x3Gm2dt5wmC&M+%fuYu!yRWV;e8 zNRbBqZkSI`AeEh9%8i}k+1K#&B||XKrZ-HsB1pD48IwMX;*Ex_=*EdE1%^pcix{tG zh;jO%;Xj{Td`!wJl21_b3Kfg4B>?+09s-@@Ey9Ne764hd*oVTv2okB!8iP1gBw3{G zd9TJExxrx9H82f z_gexcc`~nk_pB|g(iZuej;Cnwp6#|+O&@)-Ky$GL^m&$!DlR7T>$2%bN<9k4 z;4{}vDuW!OG7rodz!rzCb=`d*1wr#R`h4x=D9Z$igPddnZ$navs;$UP8l7Ia#a`b? zlAV@)ObiAxl*nRBaqX)S`7K$M_cR$HDK@_I$$ZMZ6MV8wkZM*(%%ZEWUT`E>>p@pt`VJZE8<}H? zVY96&)zzp{$SV06A6mvH{wQQ9I`k;0e`;|cB|Y}|R3U;JU+>HIu)I1k+i9l(R>Z7V zaB3c&AS<4~X+}d}B8h(gCD~S9`X)1D1#53+aH7>q&4ohry5#pkhZSDi>#WRGR(Dnv|F+csik>e-MXTT)v1Uhcc6-j78Tv*yMx%#*HPRSU{cy zZXw`oT0hS(k)$GVL8`ebICi{eWDX;S&cdfavq_b_gR3A~0e=mwuP4PvL;Gt`>_wR> zRV6U&{s>l8iL;qqaFUZaUZmgkqO$O;f}AXExS(?aF2h2KBz1P7C~D?lhp4T!X`a8? zJ!d@vTKASxYwg8kZ#_2L82C>5{7u#JZUid_K+e!FIfh_4&lr}YG*&-J^(ghQC_Cuz z!xF9--0Mgg8Pog>e>Iy??2R?^u zB%E7acWSd6nHVOWtj7E66uL^h7K*Q)-mtG&Rp?Dh>P$&QxGO+QagUMW4_-M>+$ z(Ur5ng4Lh>ru@a-dN6kR_693xJ3m|f$U7#{Y_l0#t=84q{dDc%)?_sUm31){^ zW;6r&#U4Ko6{TiMiS~k*g%mE2wslXhk2}YOtXo65E+yD3McYg6 zabJdZt(KPAMNpTRiI}7QgM?E&7H0qx3g6DHsQGfH^rUS30I}tbG)=}Q{WDfW_`;;6 zkqOO4E;Dc9TDQASMJKI5&Yy&2T;E62Q?BbG=$35ioLyN?%mz;b=p&W}+0SG3Yw{tA za&j~S)>`wSSb41!b(WMVJfOzEB+q}RR%jY%ofN-+wnwL_JX@KvnNk`Wv_Q5yGd6jo zwtrM%SDA<0=S?zFZ#ItSH%!aQYi3YtObEDz7oMdW1tPB(@B3n5UW-wiFKT!nss~}a zj2nZdEv&B3W;QN*ftQ}*3XKnIEF(xZTzeR|3*-hzySw!ZM1)he0y8iLwD{vs^eqfY zQL3fGku9(nk*en{=&IGp{pU9^-9a}V$jU3D;{5ohdoOqeI7 zL_kcKUwv_q9<250D$)BBzmVl2j)n5@+@6Rne` z88i$RWcsGYV1$;DJBo33wXxC)IZ|L%*VpU6_b(^$*gZ z7ry(XqbJ7vv3m&itH6}*>W0c(37y)JXi{;>x2n#z`3p5CQxGkh0fSGzyDp!}f&T?s z-SNse{_1P`QxfY%93x^mn!j%~Ef&@y5+YzPM8ICYfW3SHd#O6j>#g?pw6Sx4CZ_)n zN)%-bd(qZm68&w@aVbX2DzT^A>`s;PRaJPy5fH1(>tujHlj)Z~sU@SlVyMKZ_=7+-GHepO>8~JGYI|+4dUivY+|!mTU-m8L{pzP1C7soR z3asqJYUObnnlGZEzVIlGBQyswB8-TR`y|x`WDprKb_1zAInTxXRc5~0TG~76>bUYp z+q8^a5h7xjlqh4@HqMv{f2U_S)M9B-bLtOl7MRjsCD~=G{jBQr%(b?y?HUX5c%G(# zjV7du0Ly@>r_GLMF#lO`iIrW;sH194_OiZ?4OKYt@nKvi&+LH73J2Kd)31D-XUfWqaqTky^51utQ+(q z>_~xEHEGr7-5Z-zVh4%rnsuwrZlWHY-4ex@@5kS+5sR)biAN_c7g^xU!flo6_MRnV zo`EH0(>*?aW`tqR#wdR98S?l!bCFNO>-JGd(dDew&mK{Jy;*PDtuOO3SM^L;XaG`G ziyC-U;wZ@dFBy=l-OR@rER_Uw3!{$2zimu1poG8Zsd*VNV{gQ6K9TM-s7$_p5)p+= zApxcJB!b)K+yGmih7V~n|hi5G^#{*w-Q`Ye(8E!}&(uz6{6 zWbG;=Ahwu+*kT4^3lE4bJRr6*SNoStaM-5WOaOP3S6aXl$`foi&S7<^4(x&O5NO~1 zfvwyd*pn+i2K>w}sbxWd&Qg@nm%ho8xo5)3Z~IyBh^}S=vRC_E%I4m)N$SRo^?nm5 zyMe`1=S;}dV>XkZuy;(?QMV}|h&S6M0}(r_P{ms^uSz#VPuYtxdBi+G9wji9xtgxQ zSo_)7DfOuQb$bn({JQE=U|tY1GLSL+W|78#j4=*m3}$e~zymUdF_6%i2`;~g<29L# z0vX*1$msuc#0E`8ZRGVKwP&mZM3SGZwV!06Ami=AZ;Hu&#dXXL;-e=@Q#Tfaa_29^x&bp0?jH%Y zSM8{9ybG6V)Z2x^%Vrv-MQx8wqT})#pL{RzY)!*)fc2*P*7!TEVId~*58RVxrAF`i zS1ey)r{~V`tJqOF6{y)~&||Ddgjt&XOcft-)UKXeQPnPGi1lrF)QD3~z(xi*G{}Vo z8_!gzo?XXw%n;z!qm`y9YphILsV5;cVNt4?Uxgqlya7#^iSL(N z>MuPJ<5REINyzacpiZ`XimuL7VKFpjF?3?l+1F7rd|qg=pb>hcYp%ZR3gshJFUgw7 zQ?t44EYUsK*wa`#J_k$MNTe&d7G_RR?46o^QxkSt zq;5E*R&+8VN2@GqlNfuIUZv<%#|1i(N116yRIT}#vq*o?_BDmB{ljobPi#r*kiFBH zcLcwHQ$xV*l%s4wT*F{msMK?!vK8*XB@d#7q~`Rbtec2ylcg_%5F%uHX44hlikk-`ell5;$8fmLx?_ABMnl~-aKi1 zZ`5b}PSE0QbuRzZuvW3E?PErxn0}cUz1LyqacPFw&!t1DH}cf|8q~9paEmhE=h6yF zjg^94rWUPn>&oBv^g$+?b+wTLvQeB7RgvpZaGUgBsJAgPW0Q=t4Vd(gY^Wn(W6)lb z-W|Wp`OYj6(OStWJ+G_3BeQC(8unH#HfJBUw->p6JdZmD8p$W;_Om|2#Fnvo3_T_+_?Ps&UJ;-a5`JY#rz2_qA3n9qdy>{O`l6d zi&1sj-{QTODO>e%iD0Dc9%RF5ip)_&7hl=+X52)RVzOQoN&Y@TtFTlgmm8vlEch8w#SHPqUW%ZpAwo*%DSN8SJ zW6b|!s8XT|Ez~xkMQp2K&irw6G>9w(G|7N%Jl74F3W0Dcab zXmsgo#er0P=Q^z}q`ttMWKM%8`!tWw&2AW$jX#bfNwZNW7_Yi6I+Efxmq>_#X4MS!m2jFXc)z4+=1>=l%ezCR?v>+M8=t_tsk*tF{+Yu$ z(b*;Sb1gu}#sEww6-+0V8B9mk7DR{Ins$2JLz4+i$LxX5`~w{eFrB@`2RdtDI#cXm zIvZd*ibG&J17JG#Ltr{PU^?Q4Pw-QSDD8<>ncK%h)wc804**}A!7U<7sp=d8n%41b zfJhiOkLJuR+oAUlFFM3w@;&%Mg(s9qLVBvL$&je=bX%9Om`N+DgPjYv@_)2C>T;bs^dD55KREt+q zsEM&xOr`*j>;%;h^Xi|Xm}}lLZF=)OP4o@6+95wU*cz1b2%-sL=9g!NCFnwpNUMn1 zOj+n>uTV?{KbTQK<)HSrI$?zKaK1m9zC7lA=8R2OppbRA0pH?KMNKQ#y`oz%X6NW9 zfd>DHXr|qDwvD95$r-x-5Fo*i1p)a8T@sS+V)JP zo$hw$j(U=bOO>a*e3D6w6AoLQC!?N8Bj^k17<5#&O*a-+YiIEBu|s0=&4CI8%(FMl zur(dwVQCeQ}^vpF*I$eY}DwxK1J?mc2Mln{}obSj0U{`G_Htg-4dr2Z9lWm>Bwr^_A^au;w zhV&@-woA)vyFkDaO$z~F2eO!b(5@Evh}f;2p$-JBToGy^UJx+5X6uB8_)!&)u@g0J zxc`84yAWx$d%vMZzHW`p*3*6>#g%vxpQ&e6iW^?X<=cf|6M=%UEm7)gyZZfL^;o;M zxh4#tI>IkAPTNA8^gZ5u!ow1iD!g|-1hc>v4_D3`^DO0aeAW89&#m7{!%F)oBXzVnaJ{Xs5qnid4sDkjBEz%_J+&{z0(c1)#uwIo|KJ{oh zs~?;X|H3VO^dc97HYeg0i;VFN$!q$08P)gNcEsUa!g8h8=>ToadiwnOrwRwJ2>ZO( z;!$Ghyo0V?cTCEo=2N}kt~fH;L>wDl;Ss$){qW)-(I;r}Wur9PlU4w!JakM~@$<7X z#27`XgvD+qTxf-hi|AQ0LZ2Y;Lp_B9StvjxB_v4XrMi)4>1=Rg0>hB{qK(VU=@Jrx zx+&&`q(G;|^g<4Pj|?t5>^OhciNvGEgV*n4cD`v5`PNpCu96Xc2nt2nKZ3zjKPn`k z>`PXygP~qJPQ9&|4PLRr*-o~A%(XJZ@s-RS8KKI>C|$LK#-)a)ILFOp2L6T`rv%1yN>pAIl5D-?ClMC`CKj zO=5IDeY44kBNQo5Kztqk3FoYEA9d+`V@T4G`2nj~_a|Mw>N>9Hok#3c@MfLZh;a~| zT-uJPQK3lVP*^B+uwHH6^WTs@QyjclW|T3DzGxcZ2o1@F408NQaW5xAQO~bRZc-oj zYP>OY4tT;XV>Y4WD4IIcIlu(u@?L{g^i(GbuOprO2uQV-HrZ+j8FqdA6oFGDpfte+ zg$^%abLK>#vGAV^QDE@zrpVT4lWPSltsQSPhE9XUH7Ge!q|OXJ+w_t|cn^|hh;gKo z9+9Tn(w1cbnQB$S3X$b3uJfH1I*UCz>o+!^&k*957?row5o#5YUb>`}fQMk<=K+5U zpme~0!||?sOr-{fa*4{sHQq>H2CKv>OC5reARC$AI3*+2t)HI?#h21fij>sEYc2VN z%xjEi+qhXg1gnTFbq2>gG7Pe_%gEjlDkyZ68h&8GzPnA>n~h$i-anzM!)P^?ViHCM zOttL?$5(rZQ>H%7d(I$}wKi@dI~K9rN@)$F(0w; z^MPlx6*DqG$uTNTQv(#Gsk2H_;gmMVGr;je0ntz^_r(epT7fySOTJDy<~2GNIDOH-j#2<)1|o$#118l1CgoLR)AHhL35b-}q0St^ z+ZHT@4TYzv!a`>Am^OfVVo7w>calWlCeyQ?mK|d65-0`Ef=QKwNyURny;9%w3he-^ zCjL-oiQw%3R-YY63XJ)@JttVob`@ZHqd zqvk9_@b^@&{+4cx?C8OyFrQW)7kV34FXwI{i<}P@P&EM~hZ7--Wyi{`(0!tmYDb_a z;kjxxc0Seem)Da1is{uxuqMnd@Q=;Cr1;Zt3*nHtLZT?*!b-LznU4GuSY{xrO&Z9 zy^+_-tk5(XD32fwh@N&P)7d|55&meMV?e-G8@DRgVU3vl00yd7o-NW#rTW@`gOm-F zj;yCc$#o|S?bIh46_G2t>$RZ5fj>OCh)X9t;`=(43j^CU4u{yBT}HKjK#Ttpf+_s* z&d|4hHC9LsA^x}`g)xgCaGP^kk9M$t_?2a`O5lQAtaWv{vX1ehQxmf)g>TuJ|dupJ0kz!4H(k-gC6Gm<*9EU35*E#0_>92Ju9D?yRYS_R<|8k-RWR;&j9M4rlZk-!KTl2^-AbASZ=d4P4;m8v|BxRGryq)6!$TZQv!8% ztiSnCiIhnB@osv|qqq#@-50x0G|Vp57n4_Y*XjD8>m7g~sd0L>xZb&Cq+55Y#Fk7H zMv~1H6@yogv7JHYPwMrT1L)S-R^y%2h`+@yBCDB+w}=dD?d-AxRcy(4d7_y?BP=?f zVC)GVsl<%OdqZ3x2M}0HD4bZ4bBp2qyT*(m08AfLhmyB9LH4k!LjskLKlIy(zIo@D7(Dh(BGhjI-1>7aBV_-QYt{;25 zVH~z47Ga#wyccV6XMiAS!0^_b0>07f$|$i@f}#wtem!9QdL#1HP7w#d`t+=2fc3S^ z^pyb($pac{aEe$Yearizj7xj>MN4qN!O&ojg$@0BR=`17SX+Nfbq0+VXWC*d{v6L& z^f@3A(6d$miNL8eO>;5%L|3rB@5355Y%Cq*z*O)dkvwyDy^jDW+kn7Lz8 z{9gAIf}!T{H=>X){L1myO(4n-VH~R$SLlfRFa5)_0g()>HGoL3(pEquq}~URNEJXN zR0#GWPurPZdcFEpXi-MJDB9v8>#6;0<6~XBV_uK%_`XO6$OYId@=b-%729A0kp zyxBb;E?(wox;r#KF)m1>yFzXOedtFpx5V$5Gp9aOPpw`eHZk0_-PZLZ(T|9aN1ahf z)QyQN+w)^~P1;ut{vvJzspn@u6d$#==rv__-)vng^L1F3^hP{owuY%;YTv&|rNT2;vjp+|cZSWQEdbFCIH$&$_%jBkAZw`L;H`f+JxTOs< zasL=BUv@iWTZVZvMU2Hc*}!9?&g)_yya!96x$RsVC#%^`1$=3(5tb#*YpI4Ja%;co zLD>8qatLa59)?G?5SeC&XXp?ZjT$SDYax=%&b?l2ATe<8dOZe23`3A@M*ozD>elLb zUrQ~+*cc(cs5XUU^~B{{4vPHZwiw;lGU>*1NJ2zpH>V&sr>t<_FyNj?^Wvu@d)l;= zqi3gMzux%p{oPvUGT;5_m$r)YMS4r%Gezs`#mAmMcW;ZohQ7_mG*I#ziDN)!HJ_cO zLoqzxTBC`xq~`VdIoQMd^F>E{0sHa!auZSLTBwOou*;+y=X4P8#1vymE}bVAUYCec*MHrjrznf~f9Ad(wW&Wtt1ltS+ULvma zf{o5}n17^m{wCByi0u0mH;+S^qTZohrkY-A*!w_f=0$@;ON6Nua#PO_nU>39W`w%t z%nn4R-G$Lzi@@J}r7#O6i|nUFoLlE6=5`f%w;5EBr$h>1P329u)nHBa=r2VJosNPk zoykbhPHFS`PAw4~#Kk10L}*W6mew?!l148>;L!HYrBoIssN$a!OwolAafiyhZJk@T zQ@Kv`scd#WC}llAQNg#&?wzZ%46alb%dCs0z>~seWqJ_^uR5RIwR6`o$2u-h|4u$n zrH&zK|NTXqCX`_C8O~kA(;f{^GnhLi$VCG`dagRF+FR7jp)QweVq1Ylb<8<3=+5Fh zR&v|;N6TEyjzrGgg{8K=iAPl-NNMFoBTuNKOP`xqd~}vc3qg^!E!M^*Zu2ODK%iXzj3$! z=o;hW9V$I!%4@+BVR}l!Z!@7^0vdi`$Ogf+2hW71?kv%&X_GIX$Pw{zYR=}Y?Bc?Ew zs(VfwrGDyFOvs?1gbl!|05$2=3cOrEzMCO_A&T@fA;}w$qIU?R)yu`0QqP0Vt}CIa zc?+VhLpwRBcH)C{?1_8`*wWOQJcDZxYDq3aNfz2=>P+o+h0PNIJ=H7 zqHYjxf-b&LABzsD>FCK+eFs9aeg{7`;x`SWzm^U%CcBr zCVG#a>Uc zDdc!?Zs@*A_J0=P)ZmX{@H{SbA+X+wj9~d=$7M=E&7DX|ZjVIFgskF6Et5cqmmhb?qD~l7srf`R^8rL-S8v<7rtSw4q zj3H7q+|QP>w+Vu@2howS2g&qnB$J|vm%zq0dOJ0PiVvS)aTuTu4- z*_z|}(HTuXeL$q89qHO9Q%04v^ApMoo9BkhcI?;LD+d`HW_uRPZ_EhS%zzYN*o~fL ztGu$K&^kMzW+)Vmog@ixfHl-BhBM4)STQp>)F@anJD6NCi+(w@6%oKZP@Q`>kTfVo zW!yXagM{w&TvF)Br=&yGbw^=q);*3SO*d?(kM9tMns%)&BwJ_MG>3ppX1LzS%mHLF z>kDd3I~C!GD1_jkTyMEz#J;)~QRQf%yt|IsiyM;7*AdC+5)-k7<(8U5O)xH4urflu z)pZdTB7VRJV9b+~gEnIIa~2%fud7xLBzk8j7MmgfTg(Es7$O2}!HJ(t&7P>X9}@80 zr#!E6{5NtiDO1d(&_=wZP@B$KZuAJhA6S!L63S<($Z0vav^#{~B$lJ$MV9lJ-h8DT z65;VLC$+K>UxjGJNOGTFJ(%|?x2#W+bmt!Gay7Q8I+|ZOC{UE56ndFZewbhj)S#g% z{~>G7nY1@7De$fV@iwhn*(Ki=>@T*pxfd2{L)>9EXr$r=g%>~KY{+kyB_pVpd%F1E z_C8fr>YhYb#?}-5C_79=68%CBHl{3bSze+`7_ouTD0q3{YR~W)dAm zM`h}^^_mZw2K2r-x61iUwizh0aDI$$Ew~oW(D{h1gV@Gp)Gs+_IYsRWU#47n^eUR} zu~RN`k98N@+R?R;Gz)@Lh4^f+F%138edEs1pDiDwUoD89p!ktEwk zf*@r;qHiT-ZVqrE?Nkqqh6))xqj2qT`mg+>}_u z^lMGTC*B%ECgxKHX%Uf1@s2^Cm5iH3x?kr!+YEd&`?;4sI|2!v`Lp>>9gMq2a)Gtf zNJWg3kcr)mXfSRPbR(=ge*F+KB)xHbIc)wa3)tz&RN}p0Y z4!2<^f#gc+RtZ5XCc<`=H_U?1X!D15={3P^|iCX!#AHo&A zw6AbCSi|2&DZGWKEt+lTonlauq^`kHa=^D zER}8S_6@L92R+17yD^*GTK0XoaHFi3X7@O7X^IX`aNjpG_#1X zK42U7>y(|Bh;hHEuOd>qq?oHbFX@AIWu!+O&RU$OCvL8}9^2HU^h*|+eQCVM+CdoC zh9JSRCF$!{RAgotF_djOA+hG;THVo@ZtDU3VeHv;da3Q~*A7jvzzl}`cC)ZNmnOTOe+;pqFEe#m|Fm;zh|Inxm<(30#n== zS8Wav*6xfTPLn)QlPa+rj(?ByVzc|{p>*>Njx=6K(AC;}QJ~Yf{Yy8&TE{v}`-$aA zYVuGca{6jBF+FtDrnag~*~=W|nOJ5#?6;Dn5^;@fO9GqYFyx_8lv5%S5x{>Zu z3F!vu-jsBABOqPU-Q5k}+8d9@bKc+cz0dbt-=EJP?9Ezp%rWk9kC=0z*P4F1YVDa< zPlL@dW9*xwt%_}*2hR*mKklv~lj#sdB@wV%j^S=0V2H6Q=6l*%!MWme$RQ<2oT*70 z+>Z0i%2k>bc!9|4GvzFvXL$Wwc&M(CS#8BikGt~wTE|wF6ke$n$m{p$QK^MHKIyC| z5j-Quo9f2e`N-uQmD%%Q+pWqbE~QK#J(GrUc0sB5cJk4+gz-@RKwGiIgh$eKA1hfR ztg9JH&V$BffBmhcbE6M+I}48Ux@@Gu^@U$v;W_Y-J7XT|-R-YQ4T!Dk#_uGzePXSc zxUJz?_-SxuifvZIBObHx^C}H^(QeHh$Wl-lzw(92^PRz)aB~#fXjHxlvbVS} zpY`Km&Fg?S8Ozim_0Gaefga1Il7}Hk7@>$8-oRR%tEE+6Obl-ue6*RcC5*>{nxvgC z#7J?PFvEVP1UF#3psqrJ%5{J~IP0s7nO3W%;|o37ka` zG+&uS#}BcWY@KixX|~T(>gh@(8A$Z{h$h87eVEG3ka~u`@}T!2eA5@QmxHP~&vzYB zg)%A)haV^5Kf0WN!ihYlYb^U%@PPe6TDg{|R)09pO&wkPD_#d4OhiMLLKvf{HKwUO z%mMvAs4|J;H*ik|VoqH~WQ;>}bQfvGVxT9l^tKuKzw2P7Lbp&+XXz6^h_k6vPDNf{ ztUa4JDzgrjK!h@nK0eBT>P0k0T*s)HpI1>8Q-bFD;Og2nFbgunOsSnK@jfychc4^p zDo(DiP3=j5Hi~!EL3)y6ek!VnfMmY(T&4zTV3x%k^jrtK)DP{6=6eMiT(p6NPb~=M zyi#2H}bj*fhrwqdM&vNS0Dm*3W12e{gHBq_t(FbNL?EyoCQ{L(9fFbr3 z=Ze}(+pi2z=9MQw&=1OH#zVx~2AGS`G8K52u%Mq@>~74IA@Z2at62??(G^3{6s&#P zLt{UAD%!_EHlEYG`=iOkU&2no3%gB0?s3X#`-H#fsM9gG(;RA&fnVnjqTOa-*E}a7 zDHmGd8h6VWQl-q*UhjHffs)DKxR-U2`Nl@iM~nT|N_(ysBSzGu-hn~qDt|QMOhfm? z!k)(riJZ3J$Rbx`dSZ8RNWagKWrw+do_8;6rZY(FoJouNvlol`Jf6BEbbz|eM*;=K z3A3o@i}W_d9=QJHdQ=Zo%;!tWUxf$IOmElo9)4HpxJ3y)Uufy;B788Ph|Q5KXXaCk zKcVrb|f zZiBKAt0QiM(1>V8BCumD**ol$eumIzpZ;{d&QVJ)tCyH#D@bC$Pv5Y%^szISy=GY@ zn;i=axz%cJviSq}=iguq%NyCIZX{}cJpWLEo6rH(JhA&hh!l3sYj^=?dwbWc@8vVO zZ8ORDl;%q>OiXQvOh?;=imRVnQV`<-CS2qUh=~(UZpj?iS|%($eAGnk3#ecP?Gmhw z%q)MF(;V}%nVxPz7@n}Ox%XiW;zK&vhfedBG4_JKzFoLAJU;q%IK%ILk>C8DmAA4n zRkEg^`6mWQ^ktWmxOAJ@^f|{rt+QD$J7arW2)`!CktpYoXS2Cyr_;SgI9mo9=`0&( z!*)q@{K_z|zHMg$^Keb4Fd~X1p*jcOEWdSPW+CCduMMp|E5Ch;nILN(jieYNQf8W@ z-9E?)i8LYN>;m+Hg~qE?CDQ*dXxlVf{If6-CY~Wn;^;a!6H5s1o`Gq zUmvcS7Y}}2)>S(jYcj9%_gB(+&@8ov$e8XTAj^!aY5P0UVA=YD(t=Sz{7m=BSM~*00)gv(~T1EvJ_Z zA`7DkMoSGoD4Ukcy*1L6+2`EP_&P#A_twnB1;6S`V3{kEVVvMV#nNvQOt{HQGoCm9=w z+IhkA+x(ou}ahz3xsh-Lvhkft-`Fvz++#I(z z#@ZVB>$Mu(Z!7apZ-9sq>=Tu}sod3whtyU-p-$Z9#FpQ+o9ve$2ll<8|)n6e6FM`1!-l%CNHXt%GWX zX&PsyZtR5=e>*I{S5`)9Bq$5|9UgniFh#r>h~Hrs6~b8C#7w+cKXim*2Yq~Nd-k}Z zh`4CbwE-^bVR$HWzg6TN^o*_9pTTLTt$h_S#C!Yl7tWc^G^*5)7Cnvxa&6P93Teq|0de%1ZFAh%VCr6wuXZ|)1 zXK;G)w{!^l4BZYAoW-G{ z7Z|mUu3{lt2OChB z@8YDkwDJTp?iAkWZc#;v)+#5b-Pv*D-@YNmLo4pPl+To~2q+V+`|*5hn8-XFnSz^U zh)hNFV52FF1C!g%L9DWfyhcGkiY@@F31y9TIH{bR%)$$d6H_Y`h!@dry`XF@wPb(d&kvFh z>xq;O-IhHVk`GU8Y8QshWDjzxWS`A_r~cs6y2Vnc{ViY~)-{9G*OENfDgh>nlRLAs z@Z6RJQQ;`3GUWEMw{UN6L3v~Ds%Y)*44dxuwwkC@YwqrN_)4qPz8SRckto&9>~jEu&^pzi)n+Xfz7!tgHsu*%o;vsPbBcMsJCWZ(ZLufyTcXd?ptNsd>gg%wZD`w zdMZ=0^B24?Qk1^LH`cxx5m?FofvDBFf_Gc4xh_l|dxa6E$cVNVE{)&IB@dhDt^^C1 zaHU;UmsLx{7l*y8$Dl}9l=Ki)UaCbo9+VhCbFbiS>1B3<_`eQwC-17c*3g|}jD|_& zq&xQ%8GA~pIddlm2YPgY9PxWWBk~J$_pxeNl^ZEMphRFwmX+)I>jDVYzr$AII%Lj` z+4sV8$z=3;R+wpZ_k*PaRV)~`yNS6 zf}Bc$8((bZ?BaM}ahSgulpX9UhCiz2BLU+&IdpVkt9LEV-M(c6lnjDLsx**@<;P6P zY3@N%GT9fAajK`kE@Cet_b{u&_lWP}FCq(*r;w8kB32?Sj&eT0L8~vw$?I|l-O-*$ z5;QIjhsi$a1WP2mnbli0);d$SMWwuG1rw{o@4Q7qqrT^`B6#+ z|00q-w-PBH?)=|9;g;{dCzx^z-ryvsK|I?2b@BR$a*oQHbWZq|<%m*?rxKUD7u@Am z3imv%h%9LebC%P?@ zr~StlJt5xTyhwBnZf_nkOel06Vdfp#e|RY#%-*htAyu6Ij3fkoV^M(-9^Z}~L#g)q zx!>xr>yM2QF*|OJT8G_YdqrW9JZZF{;5MaTjQVZOgmRaI^AZ=Uz*_7zJDA(8T5Oy7 z%$b0TOe$m7Ny{qpm3DOH+xiKo_=-FAnxxg^8%}m@y~tzagv#D0BF&!n%{a*5gB^L=shV z+@20B3C~nkQWGVKa-uoAdo5evoVJ4+Z%+gIf^Y0D`Wx@|d!#(Ngrz%%gXqy{yD1xO{WewI&1rR=Xc{N+G&cRy#f9-S*y|hU8g*bQYe+0EMgp!|1~c*Gm&d0< zXf+zbR9v~&j7EQ;+W;s60 zL^EDu<|5i{YCL8DW2=Xag24;$J_$DWlpmrG6@;yS8hu7?zkQw#q z2W}%iYq~#85k;ITCScrd!ZB=Bov@sYUM(pOaS`T@&1>#5soHmI&WYo&L~Pzh<~db( z=o*b1=&ld_*yvwD!{wJM-21^`hSZB3>Ex4`%9b13Kij~-IL9t)mMZ_in0TFjdk`+N zrSE9sq&IcF?2vjFB$s3rFq4GJv^p`$Wq%PDdgOZAOCDU&r8593gS6TFZwSTF%kO6vBLQ%0jm8wC+)_QOWomX}HE^Q>ae$QIe{Ek(+qs zc_qQlg|u#x#*9nk-X81P1XXQF#hF`Ov|-oS8J*a=rae6MnLA!_*!uBhA7`sj+B7d< zL^LwppL41-Vx>jm@lel2QgE!{B&#iTC3+?mkC=#){jB(Lw;Le@e4})dm3YT5@Xs%F zf^3rNOQ>{R&^k?>#tc3QDw!3r>U?SkSa$%dRY=2!DrTBuvHdV<98=6M?1mOsxb&oWH7tR zs@6F}3XduK`;ycxKyik}!}mJPw;?>AFk5`A4nxq^xT&w6%U+*+h6yO;{3K)L>}HtM zoc$fhijI@gshoUz=?$HmK!bJ&uL`L1 zWU){=yrZL>Q`xRKk5n#&EL#bW(~}epCB3mE~Kq2IGTZ)l;5mA>Ldx zh|;G;iaxoTkv@_%H zT^&+0f5^)t)P}cZQReB95lpI|K~+YiX}`!HU-TgCyMAyf_7ZebIxT6=%@2w)Jcfay z?B||ET`!nT9r6~Jmt_N)9;pP=agKDK)cG>IHx2z@>z{{D0H^Rij5W-Ps}BHJVR>T8 zQa~mwRoa_4v2&~Ze9pIY(Np#(TYte7G>`;=?ocmQCX(_<#duO`H{orYQAHG@3sxuG zdFBT?P?h7@)}CJjU^$ME+<7fhelX-GuVfST2gVc8YGMwW9yFplAVJ9{neX~n?ZT%F zcQafc{7D)oFf}JB`#`Q9z*t`wG{&1>d-5;9 zAMe9Ja_Sr!oKqjHiGOKb(WPDaigkB2geoFv2hRUf7;BDE&H$>LUtsA7FQZVIu4lIk zE}=D8Gjf8plKW2yt2oOJV4@BBj{fQXwo(7DK#32}J9ysf9kuvRdR>AGyf3zM2?xAe zO>?e$M;qg>P}A@y&!HiiMR=cCsNiIU<9TrpHl@}P;~NlstxM<}Bnfc-1Ed4_e+<*K zBx*?CBI|o-)*qG>YN&MMNqY{xd49qB z&ckOfjUSmc5`HjRf~W3H03zN5ZYcmd7U@-h21qX5Kw-YA&gd^YpNnzleKjo$E-1oK za6#Qb?Mo*OqW(Ne?cn^CNm1$rw=>fK!m0nmYYeBcX4LO8Q=B~mYS*5-X@mnnGSS_5 z%FAQ|4c3t7MWtL1gYBhEe8U1f)KGH_)21#U2Cxasb6-t2p1Qa^kZOVfC+K}OnGYPp zu%AP-<$f=%yn;4$3qR-39$374vYQWc9K|QORaTv7lGNVr@hhJ~&R|dgD*5+eMh^0v zqLrWPRh#g59|==} zwfakM+?$Gn2#Xkx!VNVzUmR-I#`3H#8Zo9^JIDf|Xm{p6OwGC#u#^{MqU<-+{Kv z-G-8X?8s&=|8WWJWnSaSb1LE8%hI0))pu1IyL+?E4V?82Tm3{h1GWm(=4+8HhswdP zWH*C)ZthMNZq6L;oUFPxBZYA9tb?eFS6sr7e@KXr9xwXyWK-1ZL}nF)s2^xu$#R`F zG}N)}BwcArmG^SkXR5_3+%27A@SdU2t^%330f${`_5y^f*aa-i7MAKKTHKw5bXikx zbIOb9$G@Yi4bfc1#z*IFba;D6%hVjaXiDn0tMx2CU2(2)!yn$+qGFhuoWDRNeHQJ2 zi#J7mOV^ulr`_@cfX*7ZroHw?sH*8D6>ebGN?C^n_dZpY>yVrrfK@Dm-VfpoklQKQ5-e0%8MUFZ;AJ* zz?&W&JCklj=Sd%nzrVb$|FP!!vMnP|n$a;&{YIAVcHzuJLijWq+WSI^tOZaeBD?iGV?^t_lZaNwVLUR+EWQj?IAXwQ5(ss|-hZE=>hVXoYJ zcQ*#?2HVElN{6c?4G-5TW%$k*Do5E_+dXaXB+W)LCs6Mmykn|9BHPaSRHWhKLtGwb z35Oe!#+q3BPjAeYe8Aof(O#tj-WdzSzjU~{CY7BWd|P!q;WJU>UMX{(<8S(()|nj2yFBWCVs5#o?f9= zdep>PMU|fYEzAKofk8B!uC3|m&fD!?2PC3 zy0Gzf$#QNjjses*E$~gjp`z4zRn<+={pOIEnXZ6FDVp+%S+Qs6hf{~IovX8(r9Yy@tBjiqbc>O9XU;r!z66RT<`|AvR4zicIDkRh~gZ(JXH? zF3tES?K$?Ow{7OBjBCH-X6($wj1Qmg_5fE6j$GzbtSmPH@kKu>4vf-nM|Rn4i^4jK zy{86RUdhAtRSaH*p8wRHQ5TuAY^=2nO|K1eu#t0QQGGu1fKp?;c7yw3J2S{6cc{K= zW=2eh_cHG`*JXIm-cpmubhkINm5}_(z$QAKnZDw{5)0WW?%7gm+qEuFeS?ioAPq&U z(L5f!WZ>ZL_rucwslq#`+R*oN@^9Xu^hqqtXCNVB^*PthkSEud$@IQ%jqABuzaKMbX@2382%uiUPjhN(KfK>?u{RQ}_lzuU5fLs+q z6+%St5-lY3myG)DLy|@H+i5;8$9TaG?gBTkMovDWK83fuM18QV;EyUAd33_bd>fkH z$T=(C%E@VLcjH;K8uDY_^{|1bscR1q+NSblkq$bKT+C?@sRe=Q_a=_8IbWcy(Vf#^ z_*Gsca%jQsu0L+5pWONbbSs1zuwoetehdjB$rU(}Hr+_s#BStJGL}~?yf_CE@-JqEs*z9p1-Og5!Yo}4Et@M>4L#%s`RJqo#{V8dw*u7sr5KPfPX&Nj<7Q7o z-75@{5wp9OsPGnB)Wuz?V3Y%{D_J~uAI&^IWa35v7{*{M;ExLFXTL!F=H@S!<^=v}>n{>X7UQ!aMErIKV3uT&UMvUf zlh~phgb4Re=$Tol8e&_ib*};9RC2z4SV*j%{tCq(K3k?ih)DYf5kNrDe??H@H#?A< z&obqIM@i-{ihhOvca-9PM+pKB&=9$)u)}>KX@p7 zRhbiHtrqu~m>@F>oG5=$4n#Ds+uS658eEXs>GuKrJ>Kx;m7JRecu;K7)4~#J=3fOv zQTY`d@Za(f4*-3TDJ_1&#-x8|1;p=M>-Z^(%FM64oSWc0{WEJU)A(|MI$-!Oxy|~A z_&?Nz0;%OUln*vv$_^;#1+LX70>R}0$o;B}zkgGTnwo|r699ofQixONcX5#{0t5pn z#2LJRR7n%~#}Ly>)>N!2MxaJKrQg#UQd{Bmqyd;zVLqwPNr>6!!CSd0%x$UDW6_n# z-hTYmXy{fHEPO;LD?%b|rri=TGi5J>nJUXyc=5V}WbSXLP6NG9qIzR8in*#nH4^tFS|KIN%-x_5Yvk0V^$V1h4hl41Yhsc`X^YPSby?H4%>uZ<@1{Lo zfN;71pf(g@_8`uB7!%&yPk8Xy-JI=72v9A6Mq@=_ZiWhe_cza${8@qOjX;;5xzvkj zL-}BY#D9Ni%2}`z<3&2SXgd0egXS@Qn1g+3pHtaHjli@2|1kX^Tm4aDkey8LjSj zbO`JD8K3tRdEztQ+U%_zS8E6p?&ELeb!F!b&Pzz~Xz1F#(Yl~xD2*5YU0 zHBk7d}uL@jweRCVLVx1TOzSdmJ#vSVJR} z01Q`Sy!K>VJP5k)rQq3)3e_`ZkXi(SH}(>u(ikX9m<*stnIn3u)CXA)yG11%#r;em z+l8Y1N6!KpS6=r{7NjNtEKf53>gqu4hR6{8&4}cR&mWZnNDN1b|Tq_TOO7=rPcm@G_-}vfsr)z#Q z7lAwe*UA8?YlW3DNTY((5hJ(_+;{Rk@EY_w52!JGpiqOr4f&4`z&SfeCOiYyErH)1 z{*N~QZ7B|z@%Nem30H-*==A^?Wh61mdIiisDwE=gW%@LVjBx!Pu;l$4qrDM0C0l?F z_EL-(>^Je>eov+Tj?Uk0OqL500sKFhgrtmaB#XReXJJPChf7cKI)=dgROgUxt zMCxw(pGyMpwzWWXAp6ud;V!$8F(3a!WwfAPB!sl)0_cN(H3qD8UGSJ%ysRU>SlM6u zl}j7olrzYpr%YbphfwN_yW)eR{ktr|Iiu_sD1!sGXd=iYVpmX|`a0?%65yUOu(<+| z6=Prl!~kx{Cu~Z;UFS+w<8%1D`xwHk9a{(PkVWk2?&4~BkW2EGev9T;4zD^v3 z&y3ZBG_V<6K^BxRBrL!OdwCPRdS_uiEjuQ?4rCFAHVzPlF=_2czfKktMUa~6x6}a| zK{%WY_8CA#nXp3RGuB@cfS*2mXqZC4b`Q`K%!C0fDu5FdfD=o&OpCVSc}y5JncsOo z0bl`vllSl2AjiYGrUT0TS!ae!ki82ekiE;l4v7LM!3q6i?FY66lyBxkfWx?Kf%Cn< zyF%ccEg2%nVRsbZ+yNh?Hvk;u_7b8U7Fc1y2q8ljl>eGVFqbX=r!QcX`KVOn5KkMH zfGkgKqHya3_7#+G20R@{WcE15q+ev9LC%(Y4X#_@h$lgLkrU=_;NUZMU<^_kz@&TE zh+aLhT#7Earx;jT03m>Nuv%%z_7E`l4=;Y{dyzCE`DqWr8D#i@57?5w=96`)q`!#AGg(=z$)!UYc#nK5seMjwcvvEmvxgc_l`ntpJeX}4|sl`@Qr z)8G^60*AnbaSn$t2Rv)W z`96cd^#ZgUNL6G4-``aEQ%!+WtIV_HfwMVNAXx|I2TUgT8`u;5-8I0zKsqjvZa{CU z{M|ENgBP)1Z2{-tTnM}vLh$}3?;l`+l&sI1Mlm;`$nV7z)yAIL;XzfmYZRx+hOQp)>j&dp*zm=K0hE1g;5MCP%I>9&bmU-uC9suDDa|TAw+igKSSo_%7e&$~jwA z*NjK7rsk3-jOJA)68cZ|)hErvA5J>5CCe8Q@?eaIxNt4t1za^Tv5&IZSHG_9!t0@G zMy*4y^K5Z2ti{-KBTLY=(yic*kdR*&EoF<2F(8D>AskKub49|>2oZW zcwMLXUFcBmh)uj&_1no+hScDdlM3HW{Zik>5)~>b$GPoE#~g$TnU!_w@pR^kcaG58 zUf4}o((9rO_&vBPsGb&x6vrgJPUhTT2u1Q-Ieo?L-kF+7AA;MF(>6uzf@v(CoB-IP zWBdqmm7EFuskrKa!If`GTStfEl*?WAd&T2V3o!TNdRws&xQv-Q4`+K|_Ufrq1|kgD zqp@WO9MSZlqqrywyvu}qS@;Q{W&rD7Y8Cgdcy1SBlJCeB*g2>jV1RS!Drg*%rYg!c z1l)Q+_2xYqG1C=M4NKp+>CUbic4DrAW-3plt5 zq?+T_x-hTTVgr7h%<8qOP3yHTHtTpa&~)mxj*3s*SJF=08SaL9VaJYouf>J8zOBVy z#Gp8<^|Kt&;oI6LB}?w9?g76il9ne~u4=t`1`+6+Pyq`hURnbJA5_2s_$$R=0d_$h zuDKtLwpq>24PQNshwD#V0rlLrYZt(~#UQ2{G`B7cZZl~zAr^7*APOs{p7--)NjQyN z)n9XDamkMzfxjiV@4sgl?!SAf?&k<5tbum$$F2axS7iBM#HSR>U_j<*MPLwzvx#fu zPiLGPzj|~fR)FtVe}tG(R|4B6^&JL->yofdN;Z4DbpzaK?1kK!DuGN7gXlEFTf69T zEuIA{)P~&2g@w31S^#l1Hv{78au{pBRD&PbH`!u1h;JqjAUGYSAT(;^?Q+f?^8|0q zT0%ytKoBgu0uW?1spDYN8`jEe7g={!j5i^=H4jHN0q7gIq7ZpRbclSxRw)23dBX#5 z7~f3tPU3DU*5V=fmR3z*H$;UA2}C}?IbkjSwsR0{k`F8I4j_B$Ed;+s7KEM}b|5%0 z9`zd@#~b^#gLkvXJeRf@Q{a1U?7n7Pb3KjRi5KNbdn;PW!PD&hEH@z#kq4s?SY;qc zOuNJ&*5m@gzB1f|a3>zwTv}cdy0Oa{LQ=pT!s*6&EJVDT8tmU-{H<^@3WLfGID60` zY_n(RLd0KmfSmwD2zxL30YvG)F2K5Pjlhl{=e($mX#Axl*GvtpWYiVHVlFQL`$wZZ zDum2mBHh01*AjQ>Ed3tG;5%zP&ck=>y+?##$L~b|xb;rA>0k#rA=oUF?$-a9aw`m$ z0K``>z!W$iT|;jCngZMa6#gOp4-3GQ=3^eX;k#$=?sQ+@gfw&B(Z}9)YA4;_==VU% zy1#Kr_-Vrf>6iG?b*DCP!|C?VDfbd!@imCTA4h*q`M+4WpYjXCKLGuQi+^hVCz$^r z{@>L4|A!b*7(hk~0nSR?>HhD<|BQn-Hz8feJY>Unu|P=v_u_xX0rO4B#4(QnKq8Qd z|9kO2;$UfYMh!W1?(Xso_^a#AuJ4@t`4VvG*zfbwg5DyuynZ5Bh`tInCL};%%!|+- zTe8sCsfxUGZStwCK?npP-5B5|6|^O1sAs@){N!p@-?9(?|! zl>rAV<4)t=&&L}Xk~Fyw@vL1N_BdD!t!&VzUDCuDCL$>g`IiTMzWXy>p}XBxB)$s+ zAzQrqq0cXFn}st&&Eu|&m+3qLFBSxk6hu4N9BWVTFb*%fX)=b!d_E&uOdBS|gm7I^ zMx8Bm{w2YMg#;NHAgU!meQIc-6HQ1SEK zkV2S*LEZQ!9TN|XML4^_@ zB-KaYLQhdjUh9XN%}sFH)cy&75s{~7$W=8^^cowU*nzbOhW4XZJy9eIR1tAgvg8qw zvp52}m8>?r9=ewA4|tNgWjH;&D;ZYtSqc=@Rg4{AJVT8f0szUn`sCsQ~2pw)F}_%s94@x)gAfOYK0Rh*>Udz20DIXZF~5J zNaH8bE_Y_eEgNt5Z?xPm z*H&XtX|n=)3wbgIyi#}s5X~bpL+y4@+HNkdq=7h@O zu(=%tLmc%(rq^cu4QcrW*6sD}mX@Z6P4UIbNhP8Bv{~}ZyIS4N6$#nt093kNNjkdQ zqpilfYtWi;eq--tTtRk{rC|RDOD07Jb=u7RGZAsJC3S=TFHOHGff)z0y` zYiQW2nU8qbAuJ%eS(m-JyB(g;y0DSMBPZj8xcUqGrQ`i%p1PZ1dz4xy*9+jEplUse zMej6(DxEpq!s8RTyJ&zD)wZ^Z-fx+yZc|qR??7U)Y#61n>?WQd$AFQEUwJR98$l;n zKL)R;8x-#Qj`e{*Jna~$ibAz@?dXVZm#2PY_z^bC#m3QRnWqd=B32-H(Sv*=Mds(> zqhCMepS;j`zI~1B6H8+L>0ues%SMoi*T)i$aeBGF>`CDuc)DY6c((;colVeA>99Jr zn^<&Gr$*nhhx^&76d}pV?N#0!f!59OQl({s%k@TOCC}Zd;>56vhqZwV3@Vlb^m50> zRoe`ktIlr5r2wX^#VeZqFYBKY z5bMyvJ~a7GQkUi!PFnbg)*HUkjC9z*Koc#lO4I7_6PE4Z7X=Xq{z$!(`bDH6rb5;T zrH7*4{qcF9uaj~GkNlq^;5)XPa4%z?KwQ?|meYKDx750g__m|rE-w07$(hITj7bA< zgsyzPKBw&EU1qE$EW>%BX?fCWrQ+-!fpO|xcY#gTAW31AFs8hK=|$bd8ya7-g6Ig8 zuFU7BQz17A3hlRFk=n)&X+*}$T*XyU!V&Oit!WC+sYdHQ~ROscSh7U`xWh zN-cBU1$1PrY%p!ilyf@Bmb-#9k*Ul@dN7Z^X?I`~pTJpn?tKefCNMS~!Lt>}yRa|S zH9?V3XCfypF=^2Fu$rKdIy%^#55Nc_bG$#i-UUa7MDUm*6K>1SKRnpGNy5C zf@AMtPe}@h1(R82H>SBywi3N(8LKaHq!+oAj+~`N({h}uZBkb4 zLPdM;xlMU0*6RRB(&Su>vW)ZN$Y9iuAsfO>KiOSUmyaD0gJN#@oB~A|h@J+%t@M$s^OGLaP1 z8@(<{`HRHsM*xXD;Sdr-{%aC>j)6%TtHUd7$9T>;{sqj{7JjT58~#^{*6F!3oC_|((4Qz%s@LgJ~iwg=i2>}5&wwmV_<*Yd?CaPtbcm0oDbol?o#hstLkVk(`2 zIiz#}INWCJ&e&P){#0#^BZHi|-`UVYh>dy6>7@G3M~6sa$A9`=6l=yl#8^w7em8!( z6?)s5_qn`xBZr$oIPJycYE8C_xpo=;qunt&=|u_b_V4l zr-=?pCmpSRkT^yVDOR&2i-Kfo*D&euiL>0y$H@9dZ%N{5SN1+9xjXpbRTA>C#Ycx7 zh4QC4dD{W;>%%IcXak6Ei5ZzcX6tqrKtBn`cdPN?eFS}M;QX>c+P?H_(ul$AJC$+& zk}H>u>aWSKABZVUdN7R{s3K>~azHO< zEVAMVdmD-R3Cyx#!~sh?_m*0zagMfQ@xNJ{sH*5fs}Nh3u#HeF)H-BrlW~aY&PL8G z3kx6fy>c-W=jy4--ZtzCF~Bf@soy}Nl>ZTca;tOg_e3Tn!XrECC~HL{g4ey} zPl30eMO(>C^oNrrIu=+DeUVKIrmU5W60?^+Raq1BhH`ePf1*TDJE1AXUo-cPNhQuh zu$#cF0OHa&I|zAzOLF$_q7>PfzERfJR&tL9-ut5f@rOkG-XE8He?+4tIdyZqrdb5= zi(YUoru1Yfykl3=?Cv4eLi;-$f0 zY=v$|S$B@H#MBJUX%1PzWIeGt%X2xLqpY2uWadm`;vlr%(9PKigML2R+$)vvtf&3z zo4w(@(|q)Uemy$aN{|q|Dm9UK&X^Fy-QiO`(t+Te27{f?f_E2-&WH*V;dM##b^(P0R2(TJ2kjsdIHII&Y@?fKnwo$C@H)gqQZIiM2pR-2gAPVWmX89E3;9bYRb0 zDE=c|X#Yi+RjeLuFLFIsEENdtW)SL9aOt~lg%REwn^A8>jq};6fxE1%Qt6zSJtGS8 zSSquViav_g_`{{)7=@`O*29xt^@v&(dXpX~Wx%5L4sbT?;~;+9dE8FdFN@4evGfZ) z`q&*|>t-tL4+p-fE*n`3bfn7F({;BM>qi0IbC3|ZR*Ny1dMnK;f%GxwkQBm#9x|ak7$lGWS)^9TS)St51ds!`S#aEMkD*ZSb4UN}mh}Sg9f?|Y@PX@ODNP8tYiSVtG$NJpoJy=t3SHfKr_P z#gsBhoTqk1Dok4$#d@9JQx|yopxo4Jo{T^1c()?T3)UXwYc{jzUVXvChl{` zOZG>B#P}6ak5{VkE5DV9FFg^q_zG2{zz__i3LaVYJDcIaR+1RuV`2VlY+~VPJ9_H` z(k{+`^dk1IcO&#m1EL09nwsB(?2b{Eq6x;7J6{$-?C@8Y>wDhpsQ`Aq0d~d!JNdc+ zizRjn99e4mG0t?sn{S|P^9=AMg1@uBV~$(RQt|B)3ZV$)eqLmRuQDdM#VW4oysEOH zVwm}b-2k7Rie@6f&d4?~louu#!79iO4`%E8I12+$kD3~sFRb$zbiUh`Ct0eUAIgKR zpQ%+p*e5q;U)7GdShd7FPEljp0+<_nKQzwB(#u{X0jE%@^WM4G9Y^MsTbcHtPRVru zmQC~sv;1soF5@N1Yne`JAy5S=hiV{w?5y$pP_rEJ>hRr70Gm!|q4{duL;+1;7*unw zJrpT3O8fU&{D->Q7%mt=&tVNJ@)Bf6AHQy~$W=?p*qIG`8T*4d$cf?Mnl$r>vDo4m z5%W>;$X&IY<82rD86k_6STByr{=vE3AmbSv`;_|a)?uu8dhw8Ph5oCQis};B zk?e)FXku4rA?Mf_{sExlP^y< z52$-}9#r>Tb>?Q?roYEcATvr`h1L{h|?d)RQJNq(YdOj0Fae+hKXHdNXOcH@4NsVeY1( zAl7DM!scfJ2{8U0L?|D{a}#9Q9+$!DS!(5d6rZe5_tR}6)#p3+*=wQZ4I1#h*qmsk zwIl>ZaOaen7vOy-9vYPu$VHy^%c$Z&>naN*k~Ob-Lj=2>jwTwQf`8redge#DSD?sZ zE;7aJ&rOaJs}PPNw5~vYys)gzR<*m7WOgDM4jv-Q4gc=y@Mz0*4oGG!cg% z8L=(m5l|9IoP(J4FvGHh9dL^1(87M&2%#CLy28coP=4Jpj#ncql`!OXYVOZ9l}xz2 zNcJdP;Wo{~D*UNRLMKr7$^9!&1lFf%6<&P?_^93*5_p-;j|p&5qV`DEIBzK*4(PKX zShbr*v8}}TFq*?Dy;iwhdEn#qq+YQ+&7tCBu});6g81m+DzSgZN4y7}xd}tek8--?{lfSF$zCQ>B+!YM3~b>(a3r!p|*pW7vmw=K+bCWn0f}*{=>TL zYdFMhDvY2Dg0>X}woJp9?+8NcVNVrA@hV;55zTPkA9AgB19+d!mD;)WkDU{ktX&ZZ z*}L}Jd+*V65;v^*UlFVgmh4rVG#GAOBvI|Sv}vzD$I7E5vnh(hDVE=GsnadepDA^O zvv=(A>m~V49LhB(w-5}J=N`SZFpkZnB*9nMB^UdGy@}^@ z{5!65t>1(9Ccf=+`53mHsoTsgajKqjjrX2ybI#d(a|?Nf#MRnz_WCRF9D}r~*d@W9 zy!8QBfN*%F;oAg0I$L?(7&M~I(7i#^IJK_e24U=Lj0Y5Jc3OT^t|4sU3HcuyCloV` zZ!s^D=0)BV*}6%6AW?aJ*sWR8ZbHO3uh2Evl051xEvUd5S}Ud$knKLd7n< z{%0YB=5vDXhkhCv^#@!uy4u4^`;JVhp=X|geF)i7{ifUHjX3*U#+)jetxjdjF0#0j zf|G!f!BN`qKR|mT$24?ukZ8L0FFroFMlNG;-SdZWuEZHYJX8KYQpW!|?nV(zt?=7y z38C68BBL|!nwE>$r;DNrsPX24hpSp)M~@}_V8q8S9+J1g>dw28VFa-e3hXGdWtzxd zKK!0^lw&kwzh|_d+Ze3J6Cz(|%NJ_JUA94$(BI6OT*0=@PAFub(Eq-@rE@aS`dZRTrjaUwV>Hxke1fUy0f0+l9xL482`%%RL)*v*?P|zh&9~Al66IXdxYX zSO8z`+^DHcPk1doWbzR-Sx_wP2xebr!no8ct7$VTS@t{s1gQ_2gvvF2nsZL^xoiQ&T`59MOvy;T)ZgmG39gy-UklEs9XFk2m&EWF@R#igSpc z;x5>7eKujm?J8&gC=G_i)%ljX7f$VhH6%JwYC@;44`jxnNniZ9X0!kZ|&0eVXqH8vopqc_KISs?+t2H{}%FQP@dr~9xYv~8K;rNLm+(^U^V;N@~rIlC- ze->Xd+`c6cE#oTLz&Km5N`ID6N4A) z=}-BfG(H_Q0AQ2lr!?HAIE^JZHKRxW*u;kYTxzw|76 zsbWNaGkqF(ZWS@SrZ1f`i+0z+iqURH>LMX=bpB#o> zN)XgEq@iFJpFsJ!uBqA&Al3&0NB7Bes)u)siQC(X;;7L*9Eg(LL$nJLw;nt(u8e8j zx+yf)n;V7xS=p~sHP7Fit3EV@%~WBWu8#F#nmMrk=9L{$h5EA@rB`o+C(d|s-|Ehk zyk9+XAU=ApC?xu3ob>SvdhI7_Jy44Eo_U(E`ONQ#X+??h+>GqvlHk6b7LDe3*^AOw zu`@-}8b8J@Fg}5Lw?*2^|&YVUoz0c37l+zdmU%4Ro4}@`eQ~QJlb-#3WHp z$d{~Q3xY1~G~v}&XA(k;#D~lQ8L-N>IvXqNPo3I{jFI24OCV0=S?FvOTM~4&3V}4s zgwb`=Tp|d*bm7y4Z&La;IUm$@o?cEECp%OOJB8G9?iJT}FsL3>w^C`RR&gMn;yAyw1Qm}9;2+uJxX?^APwgovGc5I~NUko=(Yd&sx@v{QsZIO(!gx*%6v(`+8Q|&Ei**L#z>MIp0KyZB` zYO5rwUfs-tCmhAL^)omW_M0|>29nyv@ygEI@s&pdKh-{UM1$eaT09To(y4c0FNCoy zNZdo$2bDeQo=t>}M6M5&8%i-t3uYrl?vCDGk7T4!0|43r04bfaw<&i78IDab99j9a4>e#kz+crD4ZQHgww%x(E)9*Rwp8HkZx_`3j$xhXnV~#n; zgO$A&fyiM$2N}WdtN{iYGvM4T)ixP3I1$c=*1jL#Vx3VWWn~>C@TEAVqqY49*)A4T zISP$(9z!1}ix*zJ6`ds_Os&}LKc_U5W+a^?+_4-47l?`rR&4+dMi#Y%4stx9MO0-c zfv@SYX5$Q7oyEh2!d{43E3H!=mMI^(YFyE!u%?ygIr-xPsv)Wmx>8o?FmZ!UypY_g zaADYLUX``j&~_b=!>o9O4L}Yv=Rh0*In0U&)~8d#8VhcM=*$XE>c)7zzE~(>CqwAY z!Zs~N1#M9wiBA!JmFYnLQ&kiPb?vA!qB?=b{BPvLJ$P3{}zjSDg4kIP(78|>8c3T+~=+R7t zAA?fUWSt6B0}}^JR=@OV`5R1s&RC~IN?fJ^wwFeFEWY-R67>D~)at!z*8`l|zHY@g z144N9AW`3w&rQK!JNf{dl@wFT0VQSKIWhW6@!pbGdwdh#xIpOuSt6o!e>AXzbctcF z$VqDvqBOL`^l{SKg==LyEF3n%ZY^OQWHPIa5d7rKFjuoj5lSX#gIPvB1~xDM4{dd8amBhXUpDqnH|&YMZb@+x!cg#+zr0o4H{ z-45+OB1-0hJtMThKsDn_J{pa)Opa;`JR$cv*RN2yLmSY@e2znF?Tj`nWOWW%=eHgO zI)aJ=G`G1)G>TpFiF9Ca8WT#6tZdFpl>Y4Hgp!!N$us8_rQ^<@zwM~g%pO$&HSdK; zvV{q98-I8;4Px!5O<|PZOCy9g?+IrecV6zDI zTV?||&~X$h^)_LJ!Z(zAmh8m6gws*ufUOLX|FQ8zO@odJtsQ(o>C7;g8Y3Fokb*ZVo%CkXo9`g1Z?j=mjoW* zLjB1Lu=~w~L=#V4ntb^tgco@w)f%}!W3RMRlt@lvPc0q+YwWV>=@n?;39NMhxmROQ zikMU9`sy_IXRI=BUo)Yiu2aZVk+(;}P_hMp9Qx{i zEthnyK8)tKt)E-`#Pkj>BOpAAEv$sF*$#X zTNYJ9EVF_3oDF1JB%t_SsMuY<3aU?A_Mv9q1GG|Y@!mNF{0|ELA5=mh04l!bAJi!T zYWv&*;vdxc9if8GLx2`OpgKMxZy6Sc_vyY-Dg9nj7JE|cE;?DcAX#Kh)4_gkT3}7v zMnaQI-(KAT{(-^#N$s}HJ>7Qcw3Sj~kY0V)6_3ZPBj_6l^xC6NR3+!BFvfszs#jkv zuJepV>HTXGDeX0!V8J1=!f&_uAeGvpVb~J@g!Wq*0EF62z6<~wWF6JUelL0^Uu|a+ zbfqxw_HpJ&jM>56&ndoC8D+fBWrKvYGDqF3*e77PSA;(gd*j zPvS_qL7vZkmz0QK%$f4@oj{qgeW@5%3u##&xUay<9k&@#poz@$&bkwClJ zTYcmkRmRvbxN~@do=Y@v8*D)SHZAkwOi$JASE6jR*Y~Lx4=5 zIk87n+0&x*n#BT=PAPG>{@f80;E{Z(_b(%`cxyK#uCY~FdVYLN&YtI8S+)NDC%tSs z=h!*h=*^S9Vw{|kRo>GM4<1?N-%nGsPBc3WMLFkdXaF%>D27^`PoR=c1b8&AE(>wL z!Cp|8h=)pfal(`#0~%v$u222&_$f92yIvvEEH>7O_8V=;H^SJ&ve3A!G%)Tc?|R0B z9D+0=BNJ_+4)p07bnW_-av9a&Vf4qomsjT@^GlkQRkax)k7$S$3nn1B;d7~cU{cPt zG>G7D!1sVxhG-g?6g_HZC!S4q2>|byn40jva2uYkW0@$8<|wz()zmjcrxY4LhJq04 z6=u!GrEp0mG z@1IrTO#8F0+&O+~@4Ucd<)CK+cI=cVr@L_SS*_fVxL`qtb;|Oq zP13Ku(FLgL+bdx8GM!BvPJXS02bC51bv7lS#cP^*br1PE*0ha!tINdvhISCHe0MX{ zQ$PqJhZ1U;8VeO^8-Y%f>63+`XLQ6cAzm8eXpe2i#cZ6;E^IJs!0x$E%u&vSr>UD} z4FQIt?enIPKYTf$l|#$Vr$jjmHl2W7t`T~Dt-uc!psji@{RQd6*=yPxHj>b|A7Srw zCCkVto7>$juwX3AtZ4alU6@W6$Fx(a5Dv%8467P8-D)6>T~s?FRyP|AT`D$GLY+&+ z*8Mldr?NM*z|HM;enoT!t0Ov1Trw>P)a7rQl>{O35w!mR+^0JdpphS~;T~28WA5i; z=QNENXwr4T>i{=^Kc}VfF`5nc0@Y*->PJpm*XnF+;Dm22K^Ag0;h_?{1H7YAlRau8 zsfiQ8q4yk~_s{sbwRRon0Wx+tqnEj#lZ-G|Mc9mI=Y?>++9! ze;a`Mbn?&kb-Go&zcZx`?M#PW?FpIO?VK=OhlFL=rk-$s)|1(@Amv=ybgV>i6aX=B z1^r#-uYho!)xn!n~?Z>rsD6-mYRBh1za@)BrsiN zFxk}Mj4caAt*e`)V%JQ?3D{;Zcn6>jTp`RA$WJ&-8vgi>0`B4FQQ;ZQ1|NA5X2mi1HNvDg1tklf8eAwWS6`0jVwaCkL292#=8qjxX+f@Y-=mMl1)30??DY zt%!*yE$p_iWBWeTsFuY60^*i1oK$$Y&<60ZbTlDkhzB#i6cn{gl0!2p+wph7FR~b9%3FYB&9R6L|j_kOHQIuB#b0b=;4T zU@88vLb-3I66QNJ%s@6mfrIukfJ#-!)f z4|q{K5YuCp#e@JIbCAmnBH9;taLE@qdB`yTPwaeocPKc7*uJNba+9Zd78~E=i03Xx-zS4By`#qBfk$tWh&;Ht;lBMK;+XqNHt3 zN!Sq7wSOq}bLke|(D-~9zozGMwR{3G;J^p{6m(x5>NQ#|7BZ; zCnc}10k|k48^C8;x zWLXlVGnrY+1Bi}_92dL|czx%Ll;y|-{|(j|o3Qvy3fM-fMajmW500h>(uj(sJ-t8& zoIu%fRwcQ zH{HNPD-DD9*p&+g>YF>!-W(wyBCHe$BETYBlY@$ibmrrfwJW+1;=O=K4iZ10utB1r0PLY0!xhDHwtvIeB_Ta8s>q`YCF46Ka_xoUc+MPXs+l-NHPD;rLc*n!8%eI_V)2BRppGPzQ(FU=+m;Q$+`zm%;iKFc zK?0^30M0s=7nKt;orckE=*$J94B<{hGNXzG$fDoS7@&5+UTwQ#`3QmmTNRNVf1|_A z!&K(0$!44p`l*lQi5@5p-88^70+v-r9m!7b|1HQ+WTxjQplv~blf~hCdX6a5h$ep?M&OmX5tn;}Vh}Lr?e==H%>Vli}I^qrvGcXkelo%-IFyO^^s`?E%ihW!7 z(Fo8DoVLh-2cX+L!*FV}PQ4SY&}?Ul0OL156tNV)=Zs z^AT0l{4#)lSF?&{1OMKGbtN8Du1N&Om{@~OhIYW6uah?JiJ<|FMwW!bz_M*?wC=CS z5ku_6NQGsa6!f6$`IkQKUg*~!*J*`?pnyFy$LmN!uV_{@;3yF7*s;NoPB~|ORsiJA zD_TIy078S6pi|l-mWv>&a>LV+ILJ8G^nKZ&w_?JV0kW5{a@~;Ub>()JqE^u^E~W@T zY!bE%EDkHxlW9_r5!8}oB8PIm1j~ zgL;?9hp}D!J!1~$y?oo->+k$Ffp+%`e3ho<2lGXj_rrO{XS>JyS@|+=k#fpsr!)yr zh-9`P>!LP!=boG3K2ZR}TXQ_YkXA}lO9JsRwL>n?qAm~5`@#L--Zm3`gXR{gc*4(v zdk_m#ebK^JWrZ-i`Mr-uO)6rKaBWDqzn9aavfC`G^5|ka=ifjCe4+f(e0e zBq=1G4l$AvqE;0JzkTwCEf1V$oR8H76a#P=_4UptZIp6d88?i;Ikb24@@;`ucJjFUo>T%vE;xihWjF2yNsJM#*xS!04TLPlAXNI2E8Qr486s&xS0FI1k^ z);yBF2}EueNnD9BJEmGmK|rO#DkBi$NX? z;D(x2y9^u(Y~G6sOd@p9aYGe$Sv{Ze}(3gHy)Y4YOX+e^;oYGYIHMiGP zt@KVw(q?Y^&S6-}fiyEkAa`KXq558$Il9P!Xd27;t6*Fjp_BD2swDz#QcGN$cTfPg zsU{}Im7KwP+NwLFu7WqxNL*VR%gtHuPWkxAfu#3fkZIc-$J7Tm34d#FKqoWYw37Ro zBl+XB;4w$aX!hgQO@ zu1?{Is$CG<<_vx4uFgZ=vr2?qWxV41RWZa^K)<}UCf{hx zXt~=)aLM_`wc*yu-x82av%$~#eIw1rFI(g-0nSB-Ch!aPuQ|g8QOuJJwCuds_oNQ% z7Ri{cEpfM&@xK+R9Ph&+w=}4iID>T2p*|tcgBI*EDcEqHN}~a*IB<~3ZsMXI|0JXegR=tpr6x`g8&FoV3S|y3Hsl(Xixt5j|XyM0}|c)w`H_ zfk}u(X<~c#vIxm9q1&STS^Z*c!Az`dABiMVU~}x-6)|Gx7O}`X;RDi=aTV zQO3{I&XQO{b_oPb2;!tFFt6=nGqsz_L*rRqMy9%~$v3yizcWzGA;GD44B7>eTgi(@_q}pi+vvUSX>E}H*{+H$NVh$Sz}+o`Z&Aj<+2IF?s6RWi1L)cXeh`BHaHVEh6bKk)Pc& zk}x&jj?Md9!)F7(bh=%RkP+^}~G~g~F(Rt|8 zBzEr8%%crrpY_{JGshFsv(^DS)PtXXw!Kk$%QN6v7}`v!C~hoOaxp+g)3-_;H(1LGMWyU91%h3y7h*9^(&&wVXPrW3-68-wyIKoVLPPvi+! z+p*cgNBT2)>c77*Oq}#fERct=2e4N|l5^%CB|ZsKxn7!VW*4W*$zIe3^DkYv(G76x zMA~Lk+NB@MH3bqnS|qo2EDu68&$qViS5w8=m@{xTSa-OCfF!6Y zkwIQ<^av@})&mnE*ca@=cx7=xe);y)k7){mV4!VtT?av$% zSjSVv1PXbSUj>?{R-sk317dG?H4IM96s-HVk8Hg8#)&V7?wgl@`O zQ`I0QZ@G44EFS~E%_zS7Sa{gl0)^Fm5rm>qj@5nk&#h8w+zcZ+C7V5+I+0DFx5k|FvrC1 zNpU4N-v~1ERN}OLY25dbM@G3EdX^0IKX2Cw^OQRuJfk^HORVE+5I3*qYZ!Q;WzC>V=#x%)QCy4&L*lY_K< zO7~f_m$iW??M7QUtA!|SHW-WTPJs0J%avi;*WU`UJ7cvx=vq#N>2@wes)4iYw>x)| z$=&}fvgHA7X1rS8gV3UMUZ3`LO5KB0$=rjqg=xDoM{Dz8%$7$AMae$zpmv6z`>*9; zY)uMPJEORK{GEki@)M=2W)0PzsS~C%Jrb%eV}sk~&5>Yn-=r0))mIGb)AL5 zFT&|0t;XqmwMjXUtUny1l1dw{SkYoG8Z5@dwrh58ddH91lUPF(2Nu3Y<}FiBpr>Ol7EleEVOYDj9u zxo9;11w1v#XmnQVg(yL)ktOm2SS{q*!HQs|L}sn| zh0#E+DAaD$!CjuTchijvS(^!}#gqc}33hjRUB9_pTh1n2+^~MsVRzCSrp3JqMj%w% zf-?~h^U{XT$KbfEQ-xndhFO_XTuEFQvzVO$T>P$TzFHbid@m7{wT~6e@AXr@X{s+c#AvQ=9W^U0^h2B#3wNwyZaWkVVQvb}_ zGAc*+N?0*OBEK>cLu}g;-v!l-SV!rwWG~`dCI3BQ?MT!1@K{Gd7Wj*FjLuMVCC1R$ zfnH+6_N7k9h}eNYB4T-UP^(pLNbx0P0(He7Ui0`r2l>gV{>G6Qwu45*))|;sw<95& zU}Xq#Gh2-y#jCR;$@@H>G66CrAaJA?2u2wZOCfow8jmmE zLj>uTOZZonFcPZP*=_Jh0Fpcgf7}})(E~=uWgwJ!{!JI+Z)_r7pO4vh3>}`WPS2OL z=!D2beYr>ER`hUvdWMAg&5==@ft&fO;8x1&42tBUR|-Pjm_k(oVeY8#WJQue2?O=r ze9Y3kV-97i1CC{hAK;foiX(GW0%-@HL0x88<>rDwy1rntXU(= zS*TMj!ZGHQGLTm$L*Kh*K@$a9-B=ucKzh=E!~ETv6y!do1Ln)G5${$}h2lHwK>THu zb>RB}v|~2#_wE3wUATop*J@?X7Y2h4k*QjfyaW;!9Y&7eGMt?J|6SI4Gd1omgl_hxW%nF)c2SyX(tMmiEt{K~&57>d^>rbHn6s zVs;o%V&N$e=}E1^qu4Z%b6Bvkv2>6%Gti^ueVkc+J5MZDzYNI*QQtx&DlDzSlIENc z3H;27_aftJYguYf(lOxts&U|cYpVxYkL>CKdWR@)O&mTC->$}WxytFPS0C4|Wj3mW zx(d*8LL}y4M(3qI+YKR7abcrl-utPGmpyq&=PPOJ-huvVL*#O@h#5Ir(b5ZJVG^$q znZ-!Uefh|a_(LQ)bz*^e0}LgNDYGH?M4_C?(@|`)W$^+}k@}Nv<^?_NAce3_Sra(K z2t(LfB*M1_6|>Cpfl#l1`2e1x>hSkv&*bU%nQnke0$ufioH`?lHS}l{YY;jlZvRAP zoPM-`3}rZo{%vf4uw42KW%e&|R6CD(sKG;hA-RxK?)y0enT1j>NIl3=@=HsGOZr1{ z_x599{GD@=?BW!DGZ(|$5Uu-N0TRwTJfYu1{e1}SE8Pe%d{M(ud{Gkui0#LNIU=* zU-p2xGjz$QZ=&@=1%5`z3HPyyF~DOLuGNF<4=S&4+Vt z6N~SAItlw>FwsrE(4rmqrhg(VhnOIId-ByWPe&f3_+HoI!6S6piWt1SXfeSp`>^z>idlsW4yJ`F1+#gf(Xbsg3=J+wz3fj|>q$OT%$}w~*L^&P+zGrQkmj z0I#{62;kh~1b7LDKP@GIGj7X|tiXT_mkSHIF#E#2o`5#-B)d^R$U$IckNqA6xo@#a zoVL`Iy`(D20>WhGC|A1kiV+e};>3_uvh&?JZf5YFCD#Md_DEJ%BP?uX^afKVOH(F~ znbZ92u)9C|mogC?_h+SbK&MP{f`wnfet2!OZ}Fjlzm$F5;faIP z3gl^_dzlqJ4)`k%_VDVZQ*x#WW|?(MBZ~XpF|ICqnL>q!!H-ihI^R@OIpdYH3XjIoZny$S}>o7e}s1Ne3js;=kM&ajb{q zcS?Fgngh!1p_NC((PI^1Ob7}}uh z?RH2}-1bN(u1q6iT44Aw#_?2IMSHW2VQ0jrH^*yG_@wqo52&V2P;{o+=@C6FFrp=Z z7@q`#B35X+PL*;O;Zf*M@rtO7mKyd9gDYF1{-e955MGD2cW(u;vm~v4^FHz1QQGt_ zNzLyjl>&rZme-t=nc`nckjLcr42onyJfZ5NXSm>&6{@0fPr9dOiVJL}m~7B%UN^YH zG!EET7Iim%Vm_mWG1yb&ge(%La98d z>6!5C5o!ku*4SPXYRB-_fbgjA*#&+CO`R#7a_9hGT`#E=EWfvAlM6}u1^ZR!V0cZd zEIj>PQL%O2qr&#sp*nP|LNqk$(jRgNlCm$I4byh+w?LUzDNx=}K^6BG7S4b;q`D_6 z-lysi3_awFZLS*O6z)^Oh42Eu;8fHBjvP}dFsW?q;~+g~{-02>Z_u1-vKwmHs9(bS z>#EtN?aJ=u1pZLnix%Q|&8QrMDwTm=qp6JHY%GeHEwlNks2Ao^I%QS+rnsF^&3Sxg zS~2$L%emy}?NA*@ZQr3i2=hLoWo|x)58=Ore@?G0Kd9Q{sC^^_Kbq;Bce&Ykn^^*% zmR+8%Wodo0rpaOLjWyEnwZcknU<5sn+3v5F62TSOs(|idDkC9DiW!R(=OY9C_1@${}K%L>YCRGyxqETfi z>uICDWX8VcxHHDP{a6G-r>L==mlErD7c z-d5#fZqzcr2IXUE)H)1~J-Mnb>&j4@hYsZ((4JpS@}#n1;X~@Rov+PH;kQFJ)o2eF z4a(=u8W!MljJ4Gd>TxVeirgxU?&Ec+Nr&pdmu?U6@gDlS(9#0K>bb%_XvNOD4YtD1 z&ZJA>2m9)^USSj#!X0weXd1~R)oANl_v059!j>gYT9s&d#fR#4`YMpsXycuY`mNo{ z_j)~hhzzyL#|8pVXWy5hC;e353K|6xb|U2a&^R9c6Di#zAX1#3U!m8dS$TQ2%9b{t zm5q5F_v;qIUYwO^e=nBQ{kWvhEjpD+Sv(gVnDd(*CFRVj(8#Xj6Qk{f|HP?W5vm6^ z?xNasH7W;Ai|SXZ%2uJRr-ari58yng*A{Z#s@HA`cW-nl4+N_(FRBx{n^&QIcYW?q zt^nlo0g%s-z{rHu0rgz9k-rZK7C}WsRDvlw;PdL=jsWfL}fnk`|EJRGC++jb)`0lcxVu z$4p*9NPNp9vPd;jnt-VxDXew+qf+bmsa5j_suDTrW?2f1bkpWlzK*dDoxB1Kc%$yf zWjfVRSOA{eU`t15v!UkJmJZ{qt%+Stlqw^Wn{&6f{p8HK+9IDiBa>GXMHutmfSG<& zfak4cy=wg*6yLl_5haVslC)}}vX)HUDSQQ!D|-{jeJlNtGiE_s6N9J4$ff<&xo`3) z7DEhPO_6fc3uwzu9pR=DG&_T(1{diT5Ok$+UafA%7C8MZ8}5^)41AFKzSyY0D3mQk z0zlJI@6(CeEUK`+A37OKw#Y7ZYyje$VYbT*1;nT0@GrhV>3{JV)PKe26ykFrZivWC z_ea6k&|G`XMAQ0W|6TyaBysr@wCSBl17*6ae-K;Xqeuc1?Dp>0JhQ^nqJGYE`ixmu zoLHanNn{vfXq{THm5xY_aYuTC+H&WL_j>|cfNKUlM6-EjZdk^Q`H_e|Pr>yx&Vn>7 z|7N|i%Ovxj(*C66*|DJbb(iG!z#o{bPz?Vbc2f`&cbSpKY)wX{00rjQC0OY{)DrrW zY`yOFcEP_mgG7XPcz^c4Y(nnvCWj#;0BCjHrGn z9Fxp~KiMQrCYS@*GL2RS(r?VsO|)7FIrR+XvU{FViiC%2zT|+8w9HwRpadZMmp3g5^8RL{8mjVpL$I&y`|}Sp*+CqLbAcXXf;- zS_JbSbOcU=#*e$P6FcngB2Bf(9-+d~KX*wU;|lN;OArn)=aV}YU6wNoGH^7@#HPEl zj%G0|!xB3s>j6|QH_Lk1x;YOt3Cp7Y)t%8$k`++oeEBp>r_hc=SbFJJe7 zc)X7eczPKxi|!M8=BHY->V?6kpTD9Kx=w^EU=D!FRx8zJtUFHH=7Uo{BJ;$LZI~KI zsz$+xS&IBSAu|h9jpfpsB{*`X7#7%Kys$B~;Kh7^*6MHuRvN}k;xeSp*aW;fPewY{ z?s=6hH}{s!|0Z+)cfb7`1J``z>!y$bSMK5v7Q?5Utw_K=`-q~9_O6giCG*}yhqdQ) zi{xF$#*v#g#|@VO=X$ywS@x0h`$l`1^$zf2`W|G$t7Tr0Yqpwr1=e>}JGji7P#c)G zHr3e9R!x}7`jVNyVjVM@B)e#TxrH`WE8%uU_TKl@IaIukI>_-&PRbmeH77bN@TDkA z+dUvB8h7qb5HZK!F@rxp$UpEt-4fhCisc0i6f99o(4#CNg+_{8H0-U=?ARAj%A4{J z>ZqmB>cyO1)gphI{>h{D58md=My%ab{oG2mZz*|2OMY@xX`SI9$a@aK!r7a8{$Ao0 z?bGKm8KW9k+`#-n@VqHm3ZloGbPey_60^Ckd{MU~t2McQcu;?#h!d%C0c*1Ua_ef$ zbXMMoud1YOp>4gWY4PLm)S^<-Moz2pJ)`j;AeW%5f%z{c$Zm`eOEKU1+Re1llC4Fn zqCATa*n5GCeqRtWRiy?|b@-W(MtFddf-6d6k$9_EM3vl9^|6YAJqliUJhFL0z2f`^qPeToRs;u;B@A=)0bLOJj(#t2+dcX)I8C{iucSjQZD9xO9#tvpn!Y+lh#0HLV6;Ypy+5;+`J5bPIvEE6CW( zTQVEPA2ur_-=+XHN+1Hix|SJ;vG1C|JuQlMKXi#%sC$Kwv3hy53tBA#!b<1>BfLhy z&xPh5p$>|#&vc2kH+qGdm_dRJ)j{A|W7@d_!WNpqP&^X2l81HkPNmWipi?dbe)kG> z6oQk_UBl4Z8H=2k8$gxOP>#lYJ|9(g4?O&WSRC(FTe3U+)Nm_|mNa+8pb}Z*Z`3bq z&>2CZjX~g3n?tP@Fnk-GKwLH3gP*D>V*%4K+naKJHw-O^;%o&*A~xHTQAQ@Z9bgG@ z4kev~2}TG^u~;oe`LGBQ%coH5IJg#!wK$Dtm6`rq;G0E2$2W zuXoAerbBv=xoB8LsNaC!my%v5(0~XhdMQY_5UIVi98NpNB&KaJ7)hgHz!lW*{~1gg zS35Ku0l3b_bwv`%b-!p8yixoN7V@GB9{Boo9FpMfAa}5#hC#)M^SMvR6}m=BS@-rR zW*zIOfg7%1*;L|DgT9#JI77i34J$B7Zd|a=KrADpz)&oDqiF?j z0Y~t_$2x=1)}l89C(m4Ivl2Par@oF)ksCD>Jb^lDZEu|K94 zc=QG%rFg0rn8?%NHCuvJsDihpWTmpN+=iT~Lc@r5xp;z8mPxyq$T-Oiq+yY%h;(C^ z@j{}n|BLvn++V=x-9-d84C4ti-YTk=c)j*B%RtQggI0yX&_;eB_Edbmb%!bBhP=&d z!Lm6ZCjCYrn&`kLoXG517?z!p#1Pg@Zn6n8Ue#CwwiUlSL@~4Be=-nFG&~$-3mX>0 zWFS@?RR*4*FDQ7$EE$ z)POe#m7DpsVLBK)*UAxGFzH!XKK9uZGI%zLDNo@7uu@EWa|>xt_J*5>Yxh{f@nHJ!TgY{CwY|tl-1it)$d56 zh8sp!LVdt!LV`HB!+P)gAxRu*04zg+#fmWy8&s<_5IgV26WrIjzyzsZBMle{+QUR9FdK@M!SSQhC%H~y0kQcfJyhmD z=|M~Y(rY&(Vcx|_(4_DguNr3BsQka#4J^ZVo854ox92bt{ihI45X(T45ZqL01t>>`|r_)fmjpsP>AL5hf6fk%S*fF zU~H#2{`elIyc7B4tTSwwIeTzo_mAL$|EYAPT-OMqQjQyR!9&1bE&iJdhTZjsOR{pWH)AYU%`E7$kS<<6kNb$R5!9S{n_{s0FFm!Jy9OiI|J2>}S6 zMr{qS*Aq=VL3sw>IVCi~|7!6urYnHSiM{4NZR6t%Hb8A)(DXq>aFQsp7*wo8+QDq2 z*F0Fdma`gEgq?c&Fp4N!S`Ce)z~g$X^T;*JJ2RO++7psCo?_ZiNtEezR8oxJgv%>& z6)`+t0KW1OL+2ghv-L)Go_Oh~s93olKp#FK@!ielFzs?z82x5wf2C94--S0QdmrDi zyPN0w#|*63c^;MhbTl_v>u?sma_g`Dv?{EnhycqZi14#Tq4%1}L?+p%8eZZNh8QM_;zR4I4(NY2vTXt5z+ z@|5}3jAeaK(c{nn^(Xjg$8c7%4~`P)?I6YHFZWVix6kL9%l7Ae4DaW2%9Zo9IHzHg zZver^ibJ&X0)^v}8Px<~Q{RRu)r9kV!O@Iz>W1$0CS@HA&a0au=Y2)0{O2zWQz@51>fsl3s^%EufG_*@wz8hn~UCJ@&$o#v@A{ zV0AKCn+F-7{H-63&eNkl8QJ-13)i?b{zvrN91+_4>>+_?n#&F`>@F0`PIxmOrZm^D z91D*)$h`Ewuf0ju?!KraUa+$ga)-E1e<6Q6%#+K@5%z>H_F6y528Y(ns zFs}byu0hlAPY4koYqXD!#W$1u)9?Qc{F46<*c55Y0Z3F9m-{5QAI7mhoNE&7Vu5Sa36)D<#H7lG45P-`~N^<5%>N)o9=$Qe~RIKdrqNv zIiK{=w)T1ZxZ{0a-b3K^`RwP-d3a=1Ifn}`22g)pd6>$?sl@_>ix;v23ka7jb82?f zo^2}2&`m5Fr<$FHryo4iPea(Wr6DE&etx`&X=ko>Z>1pkRC(MEkf`BRRk+gbF*|eh z{w1rqRl%t&(40G2Z4?|auwgy@{yF@<=X)M>yy#ZsEp`IvA z(DjFeXu(Lo4PV<#7$b)|<*3EFV`ik{L97-+I-hbe(3Hp3kzPB?H6U6%&S+`e66;3X z;`4i+EexqHSjFeT{vl9SLH=heUDDVisQwcZMU&@DDF~JW&PE9X2UKLL}Uy12F$w zC)7)AQ3)idnY%p+z)Ln-U3d^QEkOMG?ZA9=Nk8~JCtz?xoPzOXm`AP8yi zc`UsAeS0^8ZSz}pWsqpqmTX*bnclWdQf_hS%0A2RY5hhI?PvQdG{T8<-?3ofo_DTJ z>n5jnjA{}B2R_|#8*eS+UAa7XjZEX^>D6TgFUfk8*H>@2H|m7dOhXwrzl@zO9JOhM z1hfUqU=SZm>Jh3cb^H+TF|2F2iMoWIsTa zC5>Bvm^$NoDi3rCLdba>f2}B>>g(LHx$P@gNurGuVns!WV+MvhbXQ4l#jN>gGZII} z)%91o`0;yxs-@=lIiwdV_D*7+sh2r3EC!gDaRT0|g^vY)TDoNv6ZvIn=io|vI%8Bq z!i%>AbF17(@E(D|z}fxhNXWeoQ?SVeFYv=bR89wDoab?WxIFgN>qT+1Nk&LW;zV~1 zw0GEr@JGK)R7iUXIorXXOW#eV+;<&L+E7)PRc7}CQW{Rux| z2jp;9IcVuoqcUaV{|yW%p#KXvrCu~x@Np!kEU~x6V4A&*t%$4GIEIZ&^k0TG#~&Pi zD>;F>dP#lJrFs45+_#}<4(fw_5Vnj%;oLtPrsW4+lr$N>awxP>#%0pIc$@kE2Mge< zKSktW_^UBZccb+LR+CwO3@hE8fzac?_l;J(8wcsuK@E)PyK)FIzNl5*VGO?%+*#A>bGj{;C)A+4R z=SU$(P`4vu`*F{y7&*+uG5ZjJnaYjS;@dPkKYlG&F`#sNCNZfVM-Y?JvkmG+ZRcx` zR?g!9cI5ESw^v92cI06G2!)!Stxzi}K`_=V-pYFkT83XTfcO6m9E|H7@`T%qj}^xK zA6*~+>00|Aw&!1L@8f{?BWv?wV9C9}RHPc5LwJa-l}xSvC%>;>^^}>;Q}-q7*T(|= zK!7O&$*?z#CtjFt)E^<_K8}AD&^on8nZ+?1uQQ_hj5uC~q^~2+@1*J^uK+~XDZcx- z3MCI2bUcLMo1mOQ0<4}XOsbC&-CI%H!TU_kHzd3A+sya>X8ZibmdgBNv4^t#}FaX+Zt8(AswVv6;OlhB9Q9iQ~GW(MOw?_vc~#T74VF z3`<-kt0C$2}NaCG4C zpKFMHc>v>(EbzFRCY@4;vifb!7JKxZ4Vg{;e0E*0L$dTwr9F086?(Y$hrVvU5bkG0gSkMan$JMy`Jq+; z6#&yRagkMo6<`!Q4sNoH(#s@Ljd*u4oKZDLDi zi-kDUe`eTx)i&)}DAb`u9Y2$!E15~OSU$}9P^aVC?nERD_lVRe^-&0lvu+Q%#3$yk zcVGHdXJ_W!@js}#rg)@nwPOZTIJl~a-BbcM2?C_vAFYY6QP*Ar?mB7^%k}RUmz(V0I_2>kk7<<;u@>OO`i(vg_Zxv!T zk^SIPJTiZhVy+m`rEsG9pKh{Ia*bRrStV6uUS0<-@A2l1u#yN?}e!HhM=c%eF%*VHD$AX6(fYL{OUnX+9_FQ>XFCs(y-!!`Ng zT9Ze0c|esAhRFxvEj~QMa z#t+GX#o}jMTBDL#5h|OT{PyGM{hl3i+RqDoj5Cznm^JT;wbzb6P4`}hm{q%Ka?OcV z_T$Ow(aF>oI&NCNAeQG91K(!5>M-yV*L=&;e(m`NOBHJnO6773Dfh-{ar8=otgEiF z3*e92+-XImm?!V7P^gXiRe55SWly3gqbVjIGV-FA$A#;j#j9{GZBF+%(o4Hq%G+gfUY`hKLHng0T@axpX^p3Z-HjVP> zI0fM&O?usnRjxG_)K^F`e-zgdb^*`tJ?qrp&B#0nzf_`RT~C2mwt$AcU-P9#r{2W5 zel6Y#Aa#7ml{!G`d9gb>+QFAKqey;Q@u?cN4liB=`^$6@qt2IO1e7hXOiS0k(Vb7k z+^;eDVp6lVlF)5)d9n6ZD?6;)W;SSoc`AV9iH;_so~m3lw*sy}ycz8NySf0FNuhUN z(8Z-?*&oq2wr}@9J9k-8=PL8x4TuSTVs?b9tcahmtZl-apn;T`s{1Ur5cx{MOxcpV z%6s*#>w8P|-H(XuH;o?}xXL*gp)^%7Ch~lOyi7i8Irt#*Alb;!>CTmxdso73dmb}j zLciTaTsL{vQ#hi3inI2z4e{&>znC57OVgl+t9^~;wtCgiY^eV4tGaz`t^!oAeP}JR zif!aMrZp+gjeX|G$cUq-+BDxp&ZAGZNq1-Ham&4b(}!Wz?9|dm<|403)zQZ0waI6{ zHftC0yevULdU5ua3`=48+*&?(l!5VcxYdhva>mf+``ruYOhvvksy z>Qz3~8nkgpKb}LaDMM6$g)~rqFZDfWht(1iW?m@l5k@5}Q9&i_d(ANZQrMap8Zz=W zO*M<&l%tuT6x8HAWch$4?iHl=D%e0PRD@|#oFOi6Gy~KP0v`sYz;ns$DDJ0le_SjU zWlCW!BY(G)5>h1EcfgN3sJM}&UxU?Z$M9}R^D$_lV|kbeQ_6dtDhb^0RCzD9Pac7! zf;LvX1Z|8a2GnRC97>TRrd@f?L=8$1QH?@8?7%dRwf;Q-Y7|=?<2u*n9 zPcir*`kZ9dngCwc#MLw5C-!K3+7c%{8Rzs@Eg4i;UdE#pD1aZt)kzOa|Fj#hy8slY zp4X;;fjC2eMSvc#K#-}jtL%WjGF-Mvz!I!K`6mW8h72%t5HQsL!M&QPcT2y_o+LGK zBU)t#xrG379V|I<8?-jhhP1jC*&%E&HxE!($pjJ&O9s*m!lFtd;M>lvI9L0w5juivz88MFD`4A}q=F1W+)@yi!DvvC;U-H~9dvZ-$5h z1)E+3?7qQoM*iV`>w%OsC=?8TQw8=1aN^6~odAad{l}scSmqmw=Vx$z=q=hdg_Ak}681ang|iWE&PZj9*#)62=FFYC`6xzyuf5 z7N+|faa!%rYm2}#asLSMpV65F$Qbvx=sqL|9Rr9s|E>|l!?89MP#k0cpvXZlf1yM7 zPw4DDpaY`uuRH^?2aJO3>en+6$4vkO#y}Yb&gBQz+K_OlJl?Y(5VaJ;8Ongc`WtiF zx)o!}qn7;VmHJO@A=;nTmca(1I~buNP_1^6;sBc`@OF(jy&R<(=s*{-9^RMhi4bL) z7qZEXp6a$k{P_J#d>lBBqw&L-CP6ZkKSd{_kY7KP;LYJAGb5C26~-%Axv|^{mIqhDt(Y`pt$Q?fohP5 z4Y@~)oJyncThaYjCvQdN>92Y+%t&JSy}>l?vqLNbYS!9WB6cxO!R`g14u2vg$JvCl`Vir$vq4cYI_DiZJsIj7&uwiRcX2P`$ko5|n;P2H9$UeJJMeO#=WG(Ag zxI>G-DgQ-VQVtBdeM3$k$1s3-m&y1RzbfHFIkAlSxa}2Mgiy z04WGls{?9J54G!0tq8!s7|fdpz#B4#@ISRapz0>~?0tJExFDrqbAF8l+(4hs%Jv{y zbusz9dObA%hi3P8bHQNznjL_hV!*sn530t0knC5BRSU~nss{HsaiGUR{iibSV)P$+ z9KgZ_aK_>R&G)xC<#%snSFxhxT+@1)M(ls?YxtuAYy{#6fCbDSzgjC8q|vQ8reAG9 zUeOGIqX`wLqAO%A0r8*_Dbw*ikOjZZMh~+LKGAo2aL>jkbb|lWpkub$m9tll<=IfD z2x`8g_E{jwpgQk~!T@BA7a7R+v=G{d&7Uq{!JEN(3E~V9PcJ|$RxP~Yp`B7-7R&Uz zdYBK<)sLnL8WC<#CYW|lmR z0RxWiLM|wVnNV22NLmC<1O^q{&2VhI9m9eUoN(-i;*W6QpwiM?fXN9+ZqOunhzlnq z4H}NR%%~AO10jKW9X@}701Y;+aQkL(kXP6s7`*##9axhUG|5=Pq`epniW;yUj9qr! zi5OPUXTSlfrCZNSmC zMdDbEW}`q`EZZatOAU~CZgUt7aUXpAo9V?6I3WLjQ;xvVT-z!9gd3+geX{;7upcxV z0+yCyiKR6E=3kmMOVLa7%)!AgZ14lv@C)ZcXi(8iOD6_#tO;b< z@1gh&aDUdJ_>X|P!|1n2OW^<^)1#kJmT?0S(|p8~!mtL?ZVzxc(k%_p%MbLy|HQIC z%l;JrAl!hCbkKbX$m@S{RuJ&I?Ike(fa6#QjJe=_Q*9~_Am4-mCV^oDm36SgpcDbY zXxVX1{Qq_M7r{U|2l5xF>1^NrhyXYeAfx;M>jM4~yN4LUg6FnB0zd|6cneGgprfEU zO*>TOR%s10$Ph3XkC?zQ)n|BwbGL4qn$C2>B}~Fb24+Fw>0fVMdQqc-5H7@1{tGZ# z03!W|;39){f&&lKtp}sP>;SRiKSlm;Ks@B&Z^3y$5L^HNbAX!}FsAwph1&xUj4P#(&Dc=BVHE@0W3)>h$OQ0rgk&U%Bxga-`J`Tt7;I z`@LUjq`Yvmj)jc732-9Pg9DVC|JS4fqYHBA0a4H`52z%7>w91uIED}D)S?M%7Ct}l z8(QSP>F9_|%Xpdw`M<)*H2Et>fob+3Remdze-;m4t8<-_9{mxO>_5!!h8-ndLkbdu z)a@2Qp!z6e0~DP~AXk}E+-yKo#k=`pr;Jvf--d2r%&qzDwXOwCdp&VA9iiT%c2K5( zhvTY;DI7cwU^&!x2|t-%qG!v@=H3HptBf;Pz9u}G9QY34Te=;l8TF5i%N<7G!ycA9 zO7dsT_oo}c!$7aQiM)a5t$LrW3oup-c;8>9-R&F(r8VC#5h-|HC-0c)-Tb`fxWBqJ z)60(ku!pB(FhUpe@eSLDqf?P~LKy)DA$fXh#|V>)e&d5v{~xlJ4R=W+=wT{8m?rmL ze50d8%}>2(&`8<1olnkB{bOy^pLa5flv8CeH5E{4Ul6DKou1ET9(nxdXgZK_)ov&^9t^-Q~}0x1z_~6q6rdQ^VLiyQOUCQtGrm z$r@AAoqrwi#bYv&>cm|;*jQfVsnxV?n`&W+cBf{rihNyBnab$pLR`NTe9X3FHCwzC zeI`{y*GJWal8o(gTPL@OwYL5(clR>oX30 zQ&s57z@}Qo>(-j){aP5j87FcfJ75c)k(D#->K5?@FL^U0#K;J>kN?I%GxA7ygQ}|iB9uV^+1`3e%BUF=_@&UElnwjN~{v z!>&WkrNcv~o*OstS`ECz$a7WN=b+tvE8yJ`6c4+{e}GP*0~>cPhc2<*Hd8lXD64k7 zfnDUfU|FRyU|BEiocI6@kPAbHH(JDNwLi}Xo3(x@)TZty`&74V+Vd@P+}ph61BBb& zEkL?=f)$IP4j)4`wu7vP{_YRfzzGM|`va;bbw9<2gmB;8TOy%^n zX@lUfiw%8PNe--R2nMeVVguW;^a29B1Ebs(Y{M((;p0!2QCieTdteE)6JV=zLw3QZ zaE;(oYNQ?aCf0j<$8`alblBX2djLTxr8 zKM0e5uzyVALDxSrwz80zLYBw%)DgaA|irVD@p2Y{D(7ux<5MBAicuqe*A524>!0%Hhl+8po+ zU%F6;x&^(S2kXytya&HMbPIM3un6QK=hy!o_wd;?if4lJC)brb}znb)KXaCXM z|NmnCO~wE7wcP=q0RZLyJ^YVAusq;H51{+MhyM`>wg-F)0d)WO@IL~<+MX3Uar5nE z3Gm2<{uLsh%N6WE zJc0$xA$gRocw^~f0r3b0AN~<8@Q#}`qpPihm7}?diIXEE_`uBc-0ih>%7^~QWG0Nj z^SCRd_;ZK>29yBYQOQiT?Tmbnm^#OB$->seZ$spn`TO7f-Wq4k`p3i)Kn@z1OsmWYFGjwB;VOSi2*~7eIJ7k)TrPMqGHpfS@}4?l8ho zyjP3o-nO-Cmo>AEA-Oo6ZU#}W$A-ss$5|8rtW5b*sJe(*7WJ3KS^21<@-$-H_-rF=@4>kHMam! zTmLWE8jH^xxkK|?d{$)91fpNpYOG(Hq9&L$P`5|Tb;2mEOX3BX#OK@}EYzVfEj7_* zx$FFhE%bg*3|s0`?SgehbJ5$NK~_-5*zgs(!QyIf6fN_67SESw*Ntg{ypM{P5X~BO zPy!A*f^M~9vwoZi$o1>^M*5(7)TWA54}H^P%Ll%a6mgp^msT@FM4ys5;dfV-Sth0X zQxMq$y(oVJkpp2K{?biR4_O)UHA=|`@{n;Z6s9=8lXbl7)InSN1{Ff+Wr?S(jFG(!xEo~9%O9js+#Tsi5Bi99 zpM=pQ&yta1kGC22nev;IGt^$OH^eR18=d@-8HHX}Q3T?Vd*|@;_X;DBVYvFGnI2Bk z9|`esBwst{P3r7#V7FRT^Ff+gx1arNJYQVwffak~jzm_Ft)Tb#l*BKoH2{ULq%&F)|UqDF5YwPAFkWf!|nPG0saV)gb22l%2=vLThu(m2QAew)4A z?j#?>l^diF^FO~X5!?v6SZwyW-Z?&JeA3K+e=r$Vz0%x3CINA?XIe3*7DBpV~_Dma44|H;0VIf7|G; zcHI{k&XM;UPP@O<8(zFWTFV(uYec_7pShnWY_vFS_vF_4?gcC6bF&iAj#s6&@`wrNeco^b4`_lLlbPHLAgd*xh=pX+&Vj(c+K@S-*x zEDUdO3+;|4HDOMtT~L&3-cq#SUt+h7KZmNneAg@�KMZXOh4%c^vgr__0k|{LM?w zdh~gY!fRAFm6yki7eYVP9I=b0T#pm>lBq(LQbT^|Ysgbt)N+Vc-RB6h1qwGNl?=&H zdgAU6IF8!L+0wb1IxG724q&$^SFZ@{Mg838W-W5v{vuw)iMYf3^4nmo!z6J(zqG?g z_1?ORc5S}Y)|0$?W3OBHu9mj+Xa`+%PvX_o=)5mSIB;Ss9Hmm5@K2Dv+T^|3#8Ib2 z+tEo_h1UJ)VPBz@lN!tR1V%HE@Ccpx6Tos=cF>bis%wflxg4=T#+TSu6qbcczy~o| zEK5O5H<{X{JS+A0OnYJc>DJ$WS^v}XIf?45%vophpsMw=UaNN*B+NZ|$}xyZ-% zgd53LR{Sk3iA{7`_@`bc*^{XO{Ws0zArA>Y#QIBB^vmYY9G<#1Y64c5!*l4QXH6%o!%}8S8 z$n<>cqj4;J{E7L?;X}3w(YwS)S($@#jC@}(k}s?J$uN=!rZonLlon&5t!*D7YzvX< z`52KXa@Nz6gOb)ViJyU-^5Dls8KW964oUdU1jmu0za@!aPk1yJ3A|9ee7K}FJ`xzANIYivkYqXra&8`X5(viH@20b_;Gg2$3?W30L#ZY0zYnA**C%vH@ZSp% zsSXXXwY%T2@^~jzopybdzETt;?wQ#-Q=U*a9&-_U+kxMUgY+6TEhUMxiL*)2^HgjD z`|*~L$9H%P=%9;T=$a0WsXN#Xj;|f+jYj5X+98aDP+3VAAh*yLdnlUpbx`#Vkx~UI znsPHzYnPtp50nXc`p=`YRIw@tBTuywU9X?{p^_e+MtEYRlk)#_MG7WqIuPBWWi;gB zNxGmsh#>ACBIO79B)9Lr#NnN$;(zJOxgUGLvMznD_x`f$*>MC6y0qT5n)tf(8Tv7W z5ocwmr-NzeYK9ARvHP#EhGdHm24J1TDj171m z<_l&g+3vFFl@=$K0K6A8Y4W^{pwLS)3b+IZ#w?qO=<&}eFURXv*qF;JG5$~mW}<)L zJCojd*D4;-6yU<;kN0bH^gLmg`UgC$oXkWWo#&FGiO7k^&z~|HH96h0CD|@BFB;n! zZAmX|_jvYt8#Wmu1bt1E9|C^=o?ubG$s^}_Kz$8yJq!-%coyC+XLN<0|_O~t)3>4nCoPqr2UlC=7~}xa5lIH zLngAmgMUda)amIz0GotfPHZgM6B^A%f-m&de;0NZ-GO*D7q#7!gln00V0yN90LC51 zwqlol-LG|j;75li3icuurUCx|hGbiRBIAOO?0WrS;=ZY!)qmRoHIM^E4-QoS#es#I z0qjD$bvpGZGle8ZJs-czJ_5P{@g6=BWggamOJX~p-Q+oBvEYGeP-cW)!Y2J=uL-;q z>Kjx|EU9>(gskKP%8UURzs021kV_`@=XtQl5RTs|mP`f`el}AcFL(^N^0=A&w;hN( z6W4E2kH5@!Mc8l1|1*j9r%ZrMVAiYk;PvbCyu896P+!+D;1~M&H0fIs%>c~XYoo<^ zZzdt*rly!EQWe0pe@^WI4o`QA?XW2*}FGuhl>TRR?>#sf#P>S7Tklgzz4{Jdmsz$C$ASanrUqh^i=FFhIM`WeM+hX zAnzN$-Thwbx#QDftsc+sp5}M8?j34+FVGrjUtCRkwIk9x84s@q#sFf0p znACY7a)oWsD>p2fwoO+TCsI+^ zzTUr}4%AQS4m|zf4?OrQ2>!hd>vU%@A?1Jru@J9)!jnY}s)6q+R2_#Yu9!7PvWBe= zkAxL$>o%3Op)+>#I4An;pJsO=U*)$-DQp$1>bQnI8uv#+&qpH`Ja_(PQbaQ#Lh=%J znP|^CP_#{WU;BQ7=ZsmJ4MOSFWO&s&0t1dFOQoUt;7DLPgD_9v83G{=H(n2#zWQfJ zOh}nHex+dHfPhyXSWrj?7xn45snjSL>u*LaR!2imNa1#Sui>lVzT7&`=wFQ4y&~IT zMA~;)C4(^>()+;9IbwRVHh#cW%DBk*>8*kv@Cci)M5#6XZ`%`o1eTUFy_o4agV!vx z`ApC;q7n^<>hM)BnuhYE;+A_S4(`^vIg3o&jdZSLsIV`kCg$BEsp(L{;!v-i@8%;E zw*};B3)Y|%pas41c!q7bl}?yigA#@e1P6|KEUc!K3X^HR_`}l~1HbhAFQHOJr}}c4 zbnys5@dWJ3f;i4b&c-^(UmYI3w^{TkHHE#>PDKCV#HY{YC$Zf5PU`V~Xq=D)lMQU} zQkxj0{z#wpCi$Z$d3GdJkDeqg3kg7!R_NA_$Ulh!qm^zN^F0@<0Fkk8Zuy)53^8=JzUAvR{Uyr5^a=!ft{6jlHn=|^Y}jL2&F z95*{635TF$AS?%mz|tA$t)y?(Se~ASk?7=)C{GSOm83e$H0aVE_*m9JijuvdRTG7$ zD5zAblgQ|5CiAmZ{&liPQCf0!@Zyl^k znlUbci?JnYJ@cLgN8>Ha6CP_O6;)Ejyv{(bg<=gBYYm5mXvEj$`p zBt!qxt2o4QYYuCP5sd7tQWC7-84Est=Qck~bbKji|7J1w0Y5f;rGU)-$~7q^cb8eF8@5if*dbUOn1Ed1YMQiqkcKM_{tLW|S1PE=YX;D{VOM1=PtBFKM< z2pqoQXz-^gVGSyPTxIDhG8a}4AA-Y*fT03?CSeP=uq&T4`Y3 zKN6YFCkzu9`J~)whC)v-07)6EdW2*u0ioiAm%9TFokx2!IyH_WiuV)b8Xo1AsME}Q zOC0mJEQmbxPW&$_rzBp4xA$|H$gqZwb#a&^8z;)Q=d?Frv^za%T>Q}ZSeV!TKG`7{ zt_#s1-C(mcMjxk=g^>GcpdhVN5AbjH=7>DgZlOB&2|B|2$dRSI$L%Z?w1j9*jLI6! ztCd2B#VFhzM`)vcPOx+VFm#mMFU}vIZF&I=BUJM0`e%lX86?DbVRFmlEeHi^IE|Gl z6iRSKA(ia{$#VR}Dnc|T&Nxx-hn`vc#K*&*G~YiDuI?nH`8^@WUyt!4nfNTSmKylU zp>)1NnO@z6A!nkmI}&C@?^Azpq&CA2X)`4Ym&4s5ev|FI;>xbD?KV#=#8#2o z!fSp+XWA}5_It|19H$8k`3$k4>7i!4KIb8qi9-jhb}kb&(Tx$@t>EXs8C zXijNnZz#(1Ub=_E*Bd?!Ym^NvJ#gD>4C6mV_FjGOVQAhp@(%?Y*9Gw!MLS3*Gkr{g zpkFiegx96B4vR+{D|rT@xjuHpO7DVDYmv%gBiQEriH+&^>1L}Ld$S5ZH%q?F3M&o= zCV#jD^Wxs(HT_!T&;7-U1)asGo)kIaX@(Vf26cP*x6NSzsohRRD;Ujg*y|NLRx9O^ zI_Yp-ZX*s!`TjI8A`t_{iX=C09R`cPjXII5V!lU;ec&y)9K*g}lRuRyI(#a5sdMFrckn|4|6ax`i6+xzY5Yq)P-IQoYNC ze%7{KT|GZ72iO(kzq;}>9OTNL*>vGbp-v;b`EmEB+Wfe5JWcY@M%8l zm9jrD!m@H%vwSx7Pa|A^@pS(BmP>QN8^4h=*Lx+lVb}uqQ2W~fzg~n!B3A>Sb2^ou)87?{_~AoK;v&+0RVYGo|UY zyP$l9Gk?rOgNv;B{JqrYNWXpvMY0Mjm#2Mf^_Jq}F&Ooh8=M|VI&nUlyHd^qMBA%H zyM4gZ8#@DZ%D5#e9Y*o#{hk#jP5}{V7acKrRyZ41;P=n9yI!||oBBpO6xf_AF|1WT z)|HuELp_LJh!6a319@+QCM?UW`1Cr9 zFENsJDCNtoSmuU{Uv(R(@3(onASU9NmQ@g_toWes)sTLq5V4VCdJO!Tb&1hvR(htl8oRc5e5_wvVV;S zJKmOMCaM}f=9c?z=%koSjprn(2iq6SL`7Q4=b6)U?@#d92t4)ZYOtj^QIe@$A{;~7W@;qzli9b{@#_886<<7&Zb4XdiDNX=9rt zW@7x=(bg`(wP^ovKeSP$8xhn!HZd#P}?WOdTK zWrv)hRXo(&<&f(Rccb|c)SUci7Tq!o3QVOnV(L9uRy~%!^5)9pp1K-gy@t$jor=0U zEJ3Bc@gVM5T0txZXP6Ge)@GkO65ADCkGM0)k`2;&YO~gjZWHRbYv7j*`R^|-kBJm6 ze%{&2%e$u4u~ab%AV?4hKzN@{>gR6HjEGzis=KD0sI}xC4z6$Md=R+L+$YW)hf&<0 zTkvx_+VHtKn?DOoDY}Z?#oJyT7Vx@XgQ-0EdZ9{x`O_RZZ0I0z_8F-F+TCgzv@J4% z0N-$+rwQZT)do@B#`}YI*Wg;&uaANUYbU!zN%yj@FlY%EcC%Bx^W6Q zjZ%}bB1AttpxIzXp0Xk=_A&m)>Bs7m)uceA)9niE4pG=iLlx4Lz_%rf@A_;tn?03p z)v;Vj8_kQx$CWq+TrKnF4E$p9ufwE@s^q>0HfgXBsLqjk-`%V*>UqlvKHuJcm&!Y% zw{uc8A)EaTIsDa-6`|wuo#w_=O*$E=>YaImVV+1IQNKxs$`tp!632|X6=Cxin~`3N z)2rnz1f`hBI`6cJraaby>}bc!mEOzqonvIZ#u}o=yZ+m(e*dTVDN(v3nw!p64CIhL z3?Bj_suZx!ivmLB92q{a;aQRJ23KRf^W(H4ag09Gghk-8A~DJ}V|W~YWZ2%;z|XvH zudtDRhN2DM8a4eacS^{ay>eQ}r4tp6N1x%vKtV}^({tC%3an6scB}LyGhKK|LkSJ} zR?Xa*7S=HK`6>lm!)f5lM_roK-|rS`*R^t~s7C?})kOg^hpb561AeEP!C`5y{^^EoS94RdbC^u$hPQ2bgOtyf!M}4D zbZ0OFC**X5hSz`moWUE(RYqQVk9zH#pJZ52bzkhulqPlc#Pj$8%^ur4onabkSNTQv z(q^oD9cB0GJmY*Qz$NwzD$rVy*yIuJ7F0zq zD)DUQf)86gZ_>~is!YBoIdDH$E7s(5eQ8W_dr%x}5?fEKACclq;m&e%@T|lSYO3d{ z#^jU7g@)}<=*yO#6tZ+Yp~oGA)i~sc^^HUPLEi&G_ev-aP6GrDq?&}Fcu#N1E6I=VeQdy{^N+w0%7G@rOl^Yo0f#!~?mH=W^r+z#K#O%HyL*YhLL^s3l4AaE?(K;S@x)u+N-)9PR94EsgG zX?RZ`XOThdh)f@ISM;^>2%nn`3czX58qw9lLr%>+)rfWPfS}WbfhjCQFU?1U)#waF z)G%yE)G!G~)L_X%EnT)HhoHl6c@+(%R_?EaSsI$4Km}bGJuwNVaZn)H(uU^M&s(G6 zQ)-ByaqCA^p#e=FXo@h1tI1SpY~DHYF&$A@E6@dD50{(C=|wc6#x(6H(GJ=zYWybl zmOBKz^vT`ym1)3^sW=&<}0uKCU*i(qn6pL%os9$F_C{; zs6`4fbisFWI*~tV+pFyeZ#;oD7@}Y_(fg#UCLLZQf8x7ar&7p=*#y7ODv($l*~n+A zEl2p{Foc+;H(e)^;*e7zT_?__lfIqFuTt6WsrB;+YF3}aYM@i;OFqYjDRd(wD5aEZ z$!90l$HZsX4?*P6k0W8%?~N8~32lyfTxk8sOb|(<7fnjFg;rPS6Go}fM{QR9I3lG< z_3wt$P`|K%)A(8e>%!OL=iIVf3{%KvX5Kmyn~o`L708b88uuG>rP*f7$mmOUeVu}x zRt;CamhLow9%?OZOZ&S39>jhJjQ}9;y3csPh@2t8z7To?<20jhZ7UxK`K3BNs$JQ2 z#<2G>z0bZci;P#D1Va{pO10}tmP!25hDNA^j)mdOm4q%t68#9(^LOT?LH5EFf^^>b zbTEQ>kLkbj5QnQk^e^&!uFzF(y=jDsjeJ~){sv|uNfiofpVMRNCezpC_-Q-&J74FO z$Mn6KE54YZ)QR{TM_|9B@?G-w-lLV4L!>|hzgFj$sRCWNOfew|QQ&A5-C@jpO=1Ao z{E^qdfb8k-*kr>)g9;0PjTqX$ViVJ$!4ZpNL>5BI$EXiT;NgX)w|+;-4P+yhd=@rz zVd?@QWX{-6B!DY(Jeq4|FI)QRc`&3Y^)KsrM0DKRq-2{wu+$5KVOb#T!|k9d?D~nc zl5Q`IU8*7+Y~F^faWvRW(19lV4U7F6-UP^-dLDmA1pu4{k}ZiA?y`E}Pp{bY55Jaz z6NjCKUWOD_qgt*d)|eVegCeHY8@JvWQmqOCqF|OJ6T(WS=xu3msVQJ5oGdA`?Y`uGc^5pG8Aa!;?}pfMf%6t5x=x}GTEr` zjbnHjhj>gXHb??tDkN6J$s0!Qh;6Y4sw~1*N?zN7sPZbk>|TsOH?`F6K7#r+#@x&; z$C1T_B(~SJZ5Hb$qQ>_-e7EI0^r;?j;&h9>Sc0LyT-QS~458ecPiDjgVR3EyfQ1hk z7>j!`Fcw3N4_G)-fv_k6iYqQ1L8%lel$`7kTH&wMX_OKi_G+UAp+OSitIEQ5bkjlK zdH}!X8%Mvys{m2p_S9LaWqbY`oW@#^3d9cPSDvx~zpzsnx@=#QZ=ZgEW;Pgl8`m~X z$3QFu23$?%N>lUpk$B*jf!_ooArK-OLrqnE`xNe6|DO3P56##yBo-i{UAg65f;YIh z@_t$lJRoXh^&8Xh{z(Fl-0)5f^WXQ zs@5~U6zuc9s)4{!7!RVr*fNU?W#`2KcHdt*(8iQn3#~vFlE%zSN>+J9TIBd}{T3>^ z0F<+y^;DdX%rE|_xQOW#mGxub+ z88h=cC-e58zO_J1!3|`vVy|1cVsC7SBAe|a!w)IS5sLPuM46U`Z}BtpXQC7phnV|P zYKSr^yAXB4m5THruT@Gk&Z38J6#a};`lv(N4sPMZ^Kn#D#HV)53P8AY!N{~Om$Sp}$mNg=k0r;9RHSfi?E;+uRaXqCx?(`p6$7fS7*KV?X?t-k zkT{v8j$UNUPxXFr&o)#!M7!&v5p%YA-I;qdw~Z6P;L38miDPn(SFP91|0@3-?0*B9 z{vi$5SzM!pPheyc2*JpdlX2G`5zOrdUzCp>-|_RbC&(q@1vWrloABnc^$(9j7-pea zQ34h25Ryrv^f6zmZ03{3Y|NUa{E8{PfM=K~EKYAAynEoDQn_dymA$UZBru-Ma#@J! z7qx#b8kGP%+&fJ7Mgk_+pn$toF}5bosg08{Z@_W`_T{IqNshux4DB> zm`-s$WTnA&Ge(CW?~jS3yJeWtwv?c|X2<6DrQP1f$<+E0{Q8^Fpnl@I{HBSp*b-Dj z6)vxvTB%z*ZU~GW$mL}wl~}mtq3$A1Qy&ovh`>D+7M?9mQ;v{sPE)O1jV-d|H~;c! z)hwq=5fZJ@f}lw_p-SjU17{$i3ecUpOZ`GOS2+V2R75;q5%7!(cfQU*8$EJ;btQ2cZUyseThDIRN}`3G;66eGM%(g#4a-k#qlH_; z@C8ONEDMZaSgr#=uw3VaUX*iAE#4dAC_~-lUh%rDqLicTx}JQV@_eSu$JFsL!f5b0 zjv#(ow^GJCqHasHclW$%YZ09BT7v%T$<3aZTlHx^a0?tOlU?Hy$R9d`k0j1Xsj_mY zqeQYi$Z-#w9VcyY9BSjs3?ZehciV57y0VGHaGon7GHi0H4J|764I9lO7i}TR`WMlG2x$7`@IO`JS#Gbv3=MooAYTYOkvkGU**l;f#B_Kn#Y*3z9 zV6J0z(502i7XPSzqgG~Y*3*$*oXH}fOt7;R4bee5Y&1hcR`EX4D0?5elbI}_^y1&^ z5M`un@gxQrUY{&;*FovYSBc>;qZy2Lq$p*Rce2bPRNc(Gz|UUyFKhT{g{Mzr8{x#F z?{1uao(eb0XA9J*urHh?ATu{2*s+KjwK(UGQgtVbTth;|>E4CD7&aoY5_Qj7c{)cX z%+(`?B8k08O+yINdFdWLXY4P$xxw5lFQzbNU(D1$%BMBv4;#;4a57Jlj173<{P z%*j{d?uY;f=!La6I?G}aA?ycs64D3s39Ot3V97jy=Te%9J(~zNqSz8%_ebw0haji1 zBcPMSXO6t|Vy(MOTGo(XLAXGrh%{IUACRMsgfM7*BTDyQBElZ2Q=r}@a^8nyR1yx< zpGboe1fc#f@5YgEb440dAfW1Dbzjw+AT+w*wnw+<3$(&inGz@yvVysjiYth}q9H#W zE?3VH2}Yyq0S$Y45>NJ}`#M zPGjsS|1W=L#_ukk6e2ql9UeBi0P`c%i1X$XVd^r@*AbLY1l^@Ufx(PnMz^vr0(G$? zmIn19OK#@8Uc3uXTBn$@Cb0TC79CTE=qAq^@f#v+R~9YMHTKp=V{YUfWg&aHsNpsH zn0}fzc_iJ;5R}1=1S{Eig1JDMQO)G>?K?i0vn2m=qkAZ#7r{NZeT;KH$!R6$K;U;m z^0N@Np+jpec&7nCp%_(+b00H#k8Nz#;fVJN&w4`8sp4eSJ!_HFhsg1b_2alBuK|m4 z)Q+p`#6^?L}kA}oPW*Jb&*lK>(t>)UlS4d@`xH>}0pY9iOMadX?cUN#qY;Zn#B5qcO z_SIMSTLynS)93#4T*?L=^)>y$;CRHZ%Gd=@Ry}haX|R{YtJ3Y|uqRcXAzbuzG4#Gr z2oiF~p3a9?_~>P>Bh?*UP(5T<$&HNTQ<*y2z>Zj=kLBa*{?Yu9ZD9R6KW=4pf+(0x z>XLHQ)6#jHmEqFFNNr zqVhAql+VJvkFl5Q&Y>lO@-%rRb0w53oZfIiLp2tViNk-&y7f-YTd8#DGpl4tL%tGE z0+Q)xCJLET#h(1%IRK|0S;GkW$t)mfqr zl)nux{%mqFA-^T1Y2xKUngeh8`GBSY`R0dJ>-F+=zUt*fLAsCZe$g5zB0upp(==(Y zM*Bmky}kdX&A$?AR71TL!5)<_4Q`ScCR3r$sBRBX*cz;&(f%Srs)f8mHHxgaYFOGz z)aLR{&)egUpO5F<7_IaAqf!VOcVcdoNyZH2L`rxjJ!JaTrAUUn|F=HszN=gRZ^_Ck zvTpux*vshK9h^C2DyMJpJWZY|TLK@}W;USEnqdL45js^4dlyflB2Z0jfhoinr@g9b z+#D#riOe$T_yhY}K){mMWWN7)l8>KGrSa!ipU<#7Hy|wDa(9HUX-vq>ATi9KH^MPd9WlRJ63dCmn-V&*h_GIBd#JiT6jM+%AZq{`!>7EPy)f zWv;hj*d}`VS0$}-Z-MkP%4!w#XX$ML7yfunAHH4fhg>PaHI@6*EM`oAy~wHY2YKPB z4fdj!0_?@wa@><MJ_=mZ6rUl^JH(|0=3bqk)jWLW7_X+UXZZJ^RlwR~HmQIEjN%{C9` zKh&#(y1AY;T{sR92w8&ic?^TDbAVe^qpgX2kRw=?O-+h)+O$`o48OgQbIbDm5{=@U zELN2Rm1+_7qo5<`3xuma4|1kl%hA;Ei#$suNUbQNOV+rScxiEiGi@ci*$Njc4!M`o zOXYRa)86LxR0%D87)TI}+1l@?DlPNGUfXVpQtv_B5komQ-g6>$;c5OfQ3>Bo*WQ0Zv*4mv_>`Y;H6bmv1(^z=+z&R-6@UXiJh2cttCqwQFIU(s#%nBmBLJc!5$sZ=5uXV{NzX~bV#>!haf$G zwDh+J@8@05de?R9`>l1bhYf4b+Q0MvKaMkI&)#Q~R4px1B-zqcj4Z48qhraI($^xs z!{dXqmVV|%I!&42I>NH?0bS;M1A0S7@0+yz%*7t+yn?JTEQ_-!cpEhsC~D``xz)H4 z+G^SR8I-JecVNGkFIx&x-ExP6w0>L`>Dt{J(bOS89QSA#R+u@JB{T>G>1?6v`BR&YpzZUd8uY}U$F2sN3&&nO2RnZNa?R!%h~Z4K~ewcu^#6q zge~phTDVZ&<6}89?y5r%)(?+cXWe{s7_z&3Ltw@+p8Sk7bZ#&Y1=`GE;;7q$#u()8uTlDb<0ldJh>K2vl?z?5Pck{^Ctq8MY~6@ z(B%=K&b=@6B29$iWkuF?lE^a~t-~hQr>Id*o9vG83^U8VN<$%Epbc|jFvfH5d^;^9 z+pY4Gjt4C7C+8nY@&x_2E9lCXs+iw9x?z07)w*?K9-`+rji1UU98oes+W_2+T-?YL z!ThE!a&b`xbWM*k&u+twc`Dq8fybP@sU+Su0-D~!@ORT&x5pgGnMi~7%_%KxRGHsy zu4D;T(7r3g`}nPJT>$g0LNd{%>Xr+Iw3 zT$D6#3gyOGS;nOZ8v^yYLkk~w3e2;NYZ6^Im_Y;@;qk1*V?j0PGL3)^oi{psk93cQ ziRI1Y0RwQWcCU?RqlG%a)L%{YTRV27x>Y;!$}KzTxXWVucW>D`x=HurYK;=23KJ0@%3G|b#FVDevtdT4#8$wyDW~0*S(s}o z!4jx7`7AkIn0VqIg}&S~QcQHowh_l)Or)PO9Ol9Cn`8COl>1D$4_OFN7=cMU`BqGG zX#NLAQkSL|SXKK~3_?A_ARkLLgO4x!L$7uY=WbYJ6*tM# zE2VY36_ZnI)jnVT*w-n%lr?Bu>`%QOi%|jVs!T%rtcfn_f|yVpV&H-pt+rZ+Ap$L6 zbskk_Z`2vSTAQOhvvSTxWNbzAv#h4IEkFNAbgBF;j=$W@j@)f%$Fe;+YuKc{{*hog zkm=XhXX8HfrCIp_^44n=S@A8Sy;W`yBT_R^p>Ew-omtu?oRMl(O~lX0nK@-L_-v#9 z8FV~-M&2-)tC#wMW^U3$A9vs~u^^;_T&Ai5ejQr&Zfo1GE4}~?SX|by@7`dy;V5;x zU-B5~=p>-FIXwMVWF1nKjkxxRUX$HCtkdx*AaCrJ_F7?|;~L#BE5q;{?ol1fIbJO0 zDQ&d>yb1LMs_!UKe%n6@qSt(&;~g3+r$hqc`qDr4ewjTpc0~13k~NDfm^enjHCVv$ zBqE}(7>MhGRlX?LD>E(OyO4nLYEv z3610Nr}k$f^>f>44LExfao-yP=G2gwTgGG}qF4x^v6ng3bcDUi7NL7TmdQAfT0y;Y86Fd>~gFrL-Ja%^fAf zOa;~m(*t~GMH*1@*CYaH$Dg%<_1Hl=W;cfu^;sjBhAVO(er&2hQQ6#3O+O|umV-PE zHTSZc?qXPOVT%pcx;npAlYXugE* zN17T86TPF}dU@rq$08q@BTuel`X!p#{55UzZDe#f{w@*+xM0iDvCQbVNC`J0HQeAd zsQwly@%x-A-HZ|@LXBr+`kFV-E?-Gn@Hu3=mUI#wggjESWQ(w=FA&ugiQ`v4(t_0b zd~rnF(-f*4z}CcG;VCLo3owH9xII&ZY_vjn7ngBm-6ntK3d*z{A74(@LviU$fzKARf}Y3){Hr&f})+i8b}v zqrt-&LW2b{U)Cn0Qt0w)@@G))zLceMn*T}#p5)1WWz)?sSkCrN=UjvDj&!jcu|F$l zc=CMhA^Y6KHU;d&AyaN|F@!I z(s?|`%zDOW@VcZ8H1e{$y*(Zw%HKNgXIf;nLvr%%g#(_ZH|x9eyRz@!F+w(%bJwST z8^AWehVTPfv#psIL2++o1v@p&;p?mW+Gk_@FM6F}#*T57_q5Y<5qUhNt_%}1r9d}R z?94De^W(InrW`TfG0$mUh%o*0ND?xUkEj_t;z#H>X?$LD0gj&h{uPoa#iWqLQnn=1 zM&h~>5}T5#59aaXs}9Uc`82tzU|2;>gtWH3ftwZtO!r}1meOp z*Oc?j+IkwPtT>Ae_!d6BJxA;74P2MrcVSq4>gU?5u)k1kAWbZcK5%${O`F%1HN~TE zS)poik=-9sgN5}9*kb2M@o5!TJNw`u3kl5!up-XnlqYn$*;A*l#8^lS1(2ZKt1JQRi)tu}r0C%rseB{#^aGxO6^gYN2B@alAQjh_}XUnCq4|3{jY1p38MB z7)}H386}o`m^-WyP0M^@*)McFo@x$XtsI_H>mE<_s>xJ`YRPz_rGN_~xtOny4>I0f zx7RI?EHsFuK~t{w&pGg#ew~GR@0X;P{AzEy+~at6870t}b8vl~)x2SH6?J+|5sqe4 z;*!7i>EcA7YJR@zG>FNnBIj&)6FEpWQF*{O721F3;2<2|yRRyz-uhr5yQ_^h{=>s! zPsL!gdV`bNE7I{RR<_dXErB!NJ>yDaVbyvoe9=aW9{1SmJ&dC$kzd&yqN$e+nD5fs zadMjEuX4Ux9z@a@`yI_lyty2cXu>nJzv3!g3Y__DRo!0@VD8%b#95Sc&x5-l29wcT zmSV}$r2I!n%2EOrV?lAXx->s$CP_CIVBr1qEK_Tp03km9&s9X(w-hX9QQ{lO4reWtRG5&n&a{P^;*{TrYC(D?$6f60hB@ znbQi~GKXOb+RTOpZrQ^{3ZBe!1&5!8vlUcdgrdj2sacL}5ZOtbb18B|_+!^CFRk!% z#sv1Y;I!%EG*k#f-?dUQ=7_20&K6HDtErerxsJ7PO)WnVoF8eL{j8LyA3*?lAe$a_ z_JQBI^dl9AP|^~~s|_?v%%z7hpN7+64RVnRN|-Xfv%or^S6(R^jn8D_& zDGlZm=Y?0k+_AZ#J~)tnoNJN8RU))g_5zW_*U?(|Z6F8#~te+pHAcix=5hmz)7 z6++@qdoNx&Vvv;#%ml?jxqT^UgR&KTUrOW~ly@o%=u?4;r0~!!ZSAET8@V zIQOThrWeVK<#-1aBF+7mRyg^&7QU%O5|1D($JGu#UZcl97e63f?ovcCU+yVt(M2$K z9t*bh=DKd&&trN^3Mt5ugD`Vz4u^ft74;^FJ0PHoe;oy`x%W)UK)=f#C`Pyt+o;yD z+mISD$J&qAx6@~q6*MJRLdA*^&5;UKoi?MgwzU`#(N-YCuc;tIw>oq0!|K=m(enH< zT%$n3Y?$u`8?I6iV4ll&%NcG^z-JcAKP3Dd+yf+oO1;R=2UIc$XqJnx8#(6wphIKL z&5GT2(YjF51abhr5u!em9q_2U^NDk~!Y*?K88*b+mtqM6qKKuayw{s+P}TYS?0@9W zw*9yTu>ejz^qJeSpsxeFQ|>7Gm;botKkZJ&tc`SO!0^z_7gNa=S0CZi+$Ytjy7bkQ zL8r*(j^9tm(VI(B_;UeWi4@t}sea_qS%oT~JJnvNvzl-}xn=$TtL6Jfk5^i-QQ0d4 z^MvR|eCXNJ)d(ihWKZMgYv;&z9i!6D?^2WJh|P8-k3-jt6&qM#&iXdBjI64u&s0}U z`)Y{B4ECkSLTwE~Y;z6DI**7aU*%z`-ZXiTg1A>c{9RPf>-XlGLF)717X^Rrx};Vb zXI-AoQ+j^gsRp_(<|#@Nlw(ZMh&5kz?+CKIWn|W#b(tBZM2LwCKJlbL>&!je5iE#N z6Y}VMVx(5%c4v&RDZB^dX^=-N$$%;~eJWC(v)DDLQgbg&WWXq;mz;Tw@?+f{&D9-2 zDGXp+{cudJW+`%utu$MG&IPEP$;GHDfogF~PYMp=P|BbagKwJyn!?%}FJX$1V$E8u z4H=j|WJj}Bd*cO67LxuC;j0=B@N9@cXIiOHF=Qu5fxol87Z+k5SplRe|L-(4i=6qg zTD{%ff}M2J-Y4;>_AV2`+xw>n2G0BP%TlvA`G2Qq^0G=7#hNS8tMxvY<7tC=wY*iq zS%y#C0-aBoQCmoEP!AEa2 zxfKrwDkLx)=D8IOM<^he=knZ2h65C$n8h%dvRsYls~_z~h?qJVu*~5?kP%@CK*N(; zzaRpBuUN9qa&0F^C^xvwj08N|??8FniRs4UPB$K(ufEC9d7#G%Qt*kPfFz~`18=ww z^jFe^!cM6T{0Rb@`2u*J*tvZTF2VOuTZa5h;7zs3b7f&Z%RV9w`rfYqo0kiy6kJEv z-pS@pw{2e)EZS9qfg$XgwVE3WFgu8&W-Vw#1?CH(()7{XV3Lc0oO5@kd4XrKQ1Hd46C z-$yIoFb6R*&_m4UNo~$B<6e2To2$sll5O}A@XFbry`o#g(KHZpvXxqDoCDeEP&nRd z>y3aQC(3Bd8Jv_42SPJCds>N_@OmCK4Ls3mi#Epcm(-e84()HZ4KMs4sHdx&@qlFX z4Zb2#fb_b?1uctVb90FX?L)17)JW|@>ToMH+PHItx%}IyJ5tNQNLN?A8I}$agSp}( z404~+h2$67pFZzH#xpdjIDATnY)))!S5}ludux>&%NAU-dtfIOg?}{M^Ul><_+z0# zV_CbzxH{`JzP>u=;BT5SyIN|x^1pV!*wt}ATE4!zq`p2#z?Zn*U(-EbTD*3Qy!y4g z`}XXe)4QwlD2eOPYLe?n2kgePy+x;{>!p;MEZa#T(^eIhxd@2;WJm%qaxFD~0fG3X zLvGXzN^2c01qU;5SxmlIOoYs@nejbj=?tQ5JE#WwXtR}MQ|o-^sZtGEZmr?pV^&^d zYP2cP5)XSwJy0d9OdVIGTG7PPaq>kxwf3<^SDag`N^j?TNR|H*7)N+;!NE(;;qnb} z)pt52iNo>PU8;o6Q6Te?7oklf30RGKMKoJf-{oDp53>ixV#773iCP_-3FHqvpYZB* z8$Y8grcvb5aFR%u-17V07wG?$Pza&_PBtVlIj{F){6y;bW1EO$rEOVf2T}&#GpRsy zE{W_G#mkAV2tzONC9%sewIG^$`Sp)fW1Z~%5o-l&mT!+T=p;OJ52xDSHSyb5j{GHw zI@!;;r_+40=Tt!l7qIJAx3%~M6Ax2BYZg=BctIF5?}&A~g(N*6-|+%yb0f0Z4+y@{iFa^=ZR~y_ zTTxwsP=m*_m7QdGju!!TFFOKKD6d&d^gAq_TiDW>A+@jf4a6}X4q*u#P%HK zpYx8}-dWN-6kiO$Ef1i>_r{jKJn6xABu*cPmx1T`>MQ+4MJz*G=PhYsvl%FN`X z!c|Rz5B$b@h~FweML>cO+a$OuPG!~8suyw%rs5UD^A3UVT(Ic&HnY4YDHRMhqXcl@6QgsW%Eqm;46$_Ta{_8vy~Wcc$CO~eSh+%-`nYh z`+LVq*lqx|k7ka8$MKIRyN)1{=$!4W8vf&I+&a6za7s__^cwnZ&Q+z5AW7}oMTViu z=6h!^_4!}wC|#C!RXWIY1j-63@GG-X{xUTUC?Jkeol}17vYJcW!0W9o5PT2B1Kv}@ zIq-C8Vlf`_!gR73EJ**z_fw@NHpBBtgo9rBT(oTMM=l#4-!zy~tXwXSwr+Lahw2c~ zIZT{)70@{?WpT(FyopJ}`_xKDBLYg2(TjmLA->XCcL@90P<1A^NOyMkFjLkYtrPFn zw>NDwRf=?5tww4*}_O$BIL*zVSigB@watoz)_f zLN{-l&cx=Zf;%!&3X7c~%>!VN4|NvFU3*WvrY>(pix%+TBmdTFgy^zYvT0hgMwQ(i zcCJ$;$%`D=M8_TRQ27*WWU6hf)YpQfF}+D%Q@SUP@F#T6h(edzBP*9iQ>n#TZKX74 zov9d3o5PQ?ygOd1+tbe#-YiQ-ZQgMVGR68ucZ?WAA-%?k1dxnO{*JVdmf^$ka}`5m z_68|TABAK{jzXfeDm<*Y^Hz_6lU5x~Livt|R`GBeK?CpBgBO;d-ul+z$JOG_sosyb z&!(wt9lm(xd${kLiekcZY!8@PxqkL0RwgwM+U)u>8le4{Rlu!ss;WtP1^)(*Ms*8(H zpzU6J&MNT7c5nVXCBHMD(Ee*wKU{!gQeYy~lb(}&ZRsem8HrK$n2yuQz#KNn@KeAJ z+_>=L;u4eIWv6ubdy{UKQ;mkDW*&6vy#MQAfS3)u# zdfbbja!_#r+47H!FLorIHqzizfgCpZOEc5{q7EeZKf}c$Ps%S}{AG>m^LC?BPtN@3 zdheEjI<0y-hbbSD5{^nD0eMct{dobcRGgMrkw<%(Wp~kPD&%`C>CBX+mJCo?(Nu(t*43%smx5sY5 z92T^5JAPEUr(pJ1I@An3-LEVgTdAU%APs+h+px24*USuWFfl+niH>hfKnQUnpn^Oj$5^Ot# zZ@RJD<{b0B3trW5%mV8Wd^T?wuGw4prsBE2@9^`P8t4-Tm-c%OzHQNPu$+Sa+sxYz zs^(v;riFQ^ts^I`JQ~R$-{AI)n&|QHxnXT{*Xi0fAFZZu^qC&N2!CAwsKd~o(U1f5 zps)q6o7!g;|F%0tVHEF2Cp-*`yn_m1nO!;l=ZWw08SQi7Dd*x`GME6zuliz?K&Q>@ zb@RSTr@z_|#5|=(x*KaF$4i?RM|E6wid_9m1GMYk2eO%6HZB~RS`)AuYUjPfpl<}h zgH~=16Ho1{)}QE_dw(4xey%x2^7z3KsIOZ|6T$GRk6@?(xoM8A@LCT}ZoA8&J#i6e zzbVEl@`OZpG#)J@>bA6btAO~h;CHbq<*=;1uYf?$l8w7o*QdECq|J@LpXxAMg8#-N zH}obc+ZY3U7!PpL`pkAnGPGm=Ll)cnXZak_8gA&lUk1CSh9WBL zJ1C?*o;dQ`AN$ImR(5=9Xo?^Izi0@gAEhwrFVE}uMzGXHZeX1NI84b?yirqMbVY)4 z*0Yp(jz6=_@cylH3f<}ba>_i(D_}oj-!7sa?~uHAmXzgZyQCjRI>}pfc+ixOJ8@;l{|OuETU1Pza< zr@79*<*LSW{RCct?$&cvQpAc{Z#z1DK1{rFG5~>;{M&GDqk)5Zx?oXqrWC)3XjjhZ zIJ12Vr(x=&6&E^nGUTmz!}ZVaz`YaA9TUuGk6Hg=9`M&%Qdc+;@$>#xutiz@nlx^% zf;3|02>T7A%^ydk+x|{J;xps?j$N5Zy zBTAf0OJLye>Nr8Sui4lNmZ3T%Fp*I_Zy3d8yV5q4g+?}@YZb#JKWEq|>I^!@vp2)k zxDJ*XF_QjggiPWG69)bBZ33xLq%@{d;K#lkYpeW&=vTFOEmvv4h`9GQebWat?R;@u zWj^G+>V5LW{FbyoETzWV1U&j0xok@U3oq(+B^?f~B-?}DoxSVZGGoy#>TUHHQXm$Y zg%(--Wrjyv=3dAKGrIsv7?crY>vcXm-HZx8Gz(Dun@+)+c z@4d4f_xmM33qF2~;+t8-^n6u8GM9j8-iwK`STzK2;XS)7{jB?wJM$NTnCpSweb%-z zB|K3stHBEA(9_8dXEwpgcFddfpm_mDk zunCg#a_K%Z8I77Df`b~1s_lOK)uQ9oYw*vJ!FOjX6B+N$Bw%Y@cu2+ok^yQhbCNDS z0gjU~Zry`7lUqb@={&T1qYD-F%MikyjhrO0u@Imq(n|d5_raOkgy-D#*=dp_RA+hJYt7CGTv-Xm&P zlpp6lbVlSm0WC5>EN#=#9n zKY*c8GPD6;u<^WUB8}3;pYl>Wo8xU*w>M&3?Fi7*ffp5B^C@$4>Yf*CWQYUzly15h zTzGqRkfX})1%KMkFp`d%SS5}*DDxei1M3!pK23oQ_ovN!J&aCqaJ%lMBn*x!X;~jE z^$~RTt*-1oBS%Of%Rw1AiRyol0+RY1M#G0Le{EYhs-(_jT!a84^=ICM}5(_=JTP*&)+RVC{Z zp5Uh6s*fA3A3QrjFFy|cE^0RuxjB;4bhW<~b$wtbDc1DuePOBFsZzg%JCuEZ!ljSZ z@G6P{Km?0_7LBa}rjCSN)2?yt?&ZK}qKnyDr*W4JK3KunQKF$2dKIJRb4uaCoKb2E zN-Jz>ls4vSjA{srQk}3CD8;e~y%&{#RW;P!~a2Ys_A1J z@x$p$6Yx@BHFI^@@-v3@)=f!UIszki$2@4#OwN5s&GBdd8q1SB0`OeAdcYHhsK<{r`DyR!(Hf(jI4xenN;^#f#MxfM8oI$C%I(~6K zX{Jvq3nA9tg&N+ZP{%Ag^fLJ1-#uClhzvh5n zwZ}k7#4+t@A!kd!2s5}hjTx+1)i>K{9nU?H&dZ5FzTh(}p3${!o~7cl*rAB!PB4Dm zZ1AfdsGzID86?(`cde;P$RM1aMsg;0IjeqhxG^oF$jm~mMoh#9<-5-UYWt#fmn128LhU~tfU?&}C0;S;% z84Pe~pQWlcE}4A?C@iCQmYc7-dDgq)sU=ef0s5#ei7?11+oMu2+~RlurxaOQOYEfa;0f%%2b2OX{!zj?N>v5O=jYW z=<762&IxvGFb)dvk6}c&y3>0Vc%Y94KJ_azYNP{C-I5_9TrEd0#3Tjhc{dca4_Z1V zaTu8Fh#KbhwX?2_Pc= zrPSZ&9?3aCK`_8-%ExTFQ~#^EqXsB3L4pGgK+hiN;@GQ9JkeRhCn32Cr)&C6hd#w} zW!6#D5Dqrpds<S5)p8_m(^Ne-l=|#gYO|1EG}&@70J>*Xr_WFV>R%5Og?|{s z!u!ca6j6keNNm`$tGS);Z5r7l+ZB@Xd<&8=XTlG95Cs{5_wOGJ3c;cKG zF3(o`@$?4o)4&zcf~C>_5)Cpm^9eThtr2$~RM-_J?A|qlN4&zoXhV`0ydY{j#20&h z!J*eV-e695Fv%%1zgG8W6@I*c}+R_i5^6JX&d|076v z(1=}RjrkyK<$lKEXb|-Et+KY;ZCU>%jOZTh_QnQ1GDZtNT}LHX@KijITn{Q(iZDSB zH0*8%U-OwyTa6_J1^d~WC9e}Yk!2-3H`p0}+meuPDOLYNwE&;ug#n}VN4h2VuxZWh z%~2^nQ_5h-*YqC1du<~=1PPU-ZDtx^dHNq18Od{+FDZf_nJ)%U-w6MnCQ1fXii zAL7zL1^=sTH-ZUGI@2owf+^ex<~xZJjK2&e*qJHjgU*p8abN8e5Z#Q`qQ#8TNSc|Y z&!E6*l5D^t1eIEo-_Yq`}a zTWJDH_8MDke1J=@m7<^J-}VseVHoDWhc8>KSA{_5jDd!yaqw~xWLM72rM~^%y^!`j zs~3(gw#p(xdrd{-EzB>7e%=M9Vu4YF)Y9umlFo4RfSHGi+6tps zk&;W6yD2jwc0brWo-E5Rm0k9y=i`Q?822gH_l>4Oq1B&>igNlUC*$P$aPS1{@;(SY z9Q2O4b*3l4+2U}H7JIC78ePpsx95Tr*VfSQ@vz`H6Yk)b4BU~w>DT$}i%6rc3E|D# z#EiyUdQMy5M`cdfA$eON_{Gq3t}@$^DMc`eyDXaVABH7zqEmdwOJehyb^{Z}mj_$8 zyPAh&viXyV-U1K77*4hrzYZtK$V%M(^aC(O*2k9yvG!)7tZ~lQ24K8Txoohy0(K{J z=`frME_(yChzt{y@0@(({x%*K$3Vc~AvlWLj%{EkgzIwJa*(;5Nxwu9vXPf)mlqO3 zBQ$4G#cW0Zx^AXMp7Os9B zX-iODY@Zlk_|GI}Mh?zWe%Q;bYnaibeM@1`owKtES$MUp2F3Ixr=H%ItP?HO6g4ri zS#r|AWmUd#$oGeZG%53y^6nw>FrkcB{A10-Z41P_W*Zi*llY2Znc1n*P2U?rnuqlo z=@i=+tcbjz`|7f#qxKBPkIT}`)$~I%+J^%{`0J+SOQyrk>ehBC*)ps}VYl@_{;<={ zAfa(p>d`PTl)dQnGf>2uqg_ooujsG$u-Ln$qikn)L!N{tSr#?q6Ot>&fpDq=%{NTi z(f*-O#3~?C_;$F%jxP!A;J0F3iSw*s(tAwZFjE&{ZsUWVl()OtGAoC%xNggC@_X@(AwWM!3a2c19|&{Z75Gsz>Djn}3xLk!6h z*xBWB6Ic{m1Mqd2LvAU~)kZ`={s*QzG+m%jR>rIA^fBz$&cujq)86lw^`O zlG)+jNJbVQ1nq!jS79)Cguue=?rpC04F6n2hbquEt0N9+>4Vg)i7Srt)$Li8$MF`4 zBVhsV=yzS0hg+`T3|%_4aHHmA69@AkVcP){8=C>bj?VALj>{de4M=$|++9$BoiA=Q z7?znhXm(q%-4g>Eiuw2OiO>-iqCRdNUdqg6CCZrk0^RLW-%HZP@Q01Q+#_E|rC8yz z!1gDS2!rADVtpI2+-Uyn4;#?qmyOWTYsyFDqbVL(qJde<+$u#swXv7Ex#&J`FwiBV z@@rO?zoWCMrTU@m0c$_=xDhBc0@l6uZuV=L+s_T^7XTckgJN`<+jg8p6_+_vMu@&X zb6Grody%QBf!?&Bp?n4U!Y1T#LePBX@~~Q8PRVK^# z@lL8{L^GrNl)B7XTm`pwha1Jp2ryascw|iT*wLP~51MU!MZ0zAcKS=g#v~8?vHukv zbR7SxD8G5wFKk8#sv~^XY;2aGGd@BCdcKvk4zr}%(qw)jk}M2LwS(Oi5{qAeYle;RrV*ScVZvfEpQ zrL&7nsgUWA)hh%8Iks~$oqvzDA5olU9sfDaGJ z?=P!2K4j%X46O^ieYW~Yt680k(;t@g{}4uWP!-~TE=wzgMeixLmsaHg>7{vJUkgaC z$8gpz9p>{eL&DftuIw&B_+y8`A?-i26?NCs#me>Pj0BCFwS z5ZtJk6&GLJB#$1A)jcnfg}QW9RC^nQov`9=H~jfqnOo^HYkDj2GG~v?4K3d0Q*`Ll zQMld=fT5W3UIf6ZW(1*Mv_nro#dj3@IeE=&o~_b>n$`Dc{vT)nViXYLdjKez7XSkD z@g<*91OYxwXDOfodJ1h~-syMaHzmH`dMLqiZAu~i0DGWp-f>2li@Az#ySWp3v|1H}K{w0H%qbfw1iu{=PVmu`|zng;k zL1jyRAvT1isQ|LVqS2URmdGsZ5coQ?9I&s#C4} zDCMhEnUhPvaIy-T#w-~oI1Msh)`=b@Qv}vZY%%;}U9A%4EUP;UAQCunisbcK8Jj!B z6<(!6p>JVBjm5A~o7aMLvL0@1E9ip{w^ydAtV@UA+K_1bMy^yHPhAzAp`Cu)zdH^~ zj00bIma^j_9Hb47*kQi#ta|opRepQvJY$!IE0$sRT3KU8;pzM;sWHA2KI&X1KF%YL zwQssUcc#s#P2fgL-=@CK-ij;oTR6TN!%8gU=~~OwsfX$6e9|ZswhjrB9D8UNYx~^V zOj#XwU8zt$|8`mkpFH0uo-)QfOgF~y&z}f{b0EjQr=)lRg(5pY8SL$#%YtTMb z%r<8~!V;1>7@8sDn}v?qdQ*vL&&ubCVZ&4D_MhUy&C@i;c=nLQ0% zSJCjufMxt}G#|gH^Q~RUZ)|>_7W=3)u23O6O^aY+GRdJLbiZeyt>}aL;DEoOP3=eX zwdNAdEM}1jxYqXeKv_lQde^{o1ciuxqIHg+o)cwX*@z!+0QH)O^ig^+Q6BW8Y0jj3 zv&s-Bk`Nb&R+XXux>G_Rk^?z9H?`Kyc2X3NY74DIb%14-?GmFV)`xTv9;yIYxLCQ9EsAU>QO~RsX)w()mTvAnJJl!T2o`_ie_Mp% zsfl$ZBd&m~w1K(xX$G$qt5MA{Zio(1L~+JbOyhLlkYMp^ijbo&=3pe@ zZj3a@L!E8cxu^3WB2`f&LnV!`g4)5PPAK#$dnhOe7J8MEh7e|3q4P-Q$yarOc9MpR zB)|o#)^x0_;bnRM(TYbeCg?ngwz#a~LN&{L&!|e`W4wZj6wwK?dOM}sTwP} zO_Wwu(kCem9*;T)CM|m1)}B<^Us$cNaLw6>ClQE9?rB9<<|klzgi>Ptmg-O2L$Wfk zo=_9D2bAv@B+ZO(dVHU<6L>AZM=R29XYtBw<@8ZwVnpGE_ws-xB4$TZ_{e0^J~C_J zb*1bEg;-o>pC|E&`Y*u`in7S?^H^wY$MOJ-Qhr+qI;D#%@K)pX|51zz7eVt|F{#d_ zD&TWnSb7@z`H&la=Yaopt`x|lm^9j_4vb_qq>cQKVsB@e6b1FMz{>-!Fn7$f-TUqO zLV@|mux6DyMnC3#DMZrGS^*iIn2W^5=nKs;L1xT8>7a9wRx#9^aJ>|{(jiWW70M&hcZxOig+WjF2|R0GFKCCVz>E;IxsRUzer81IJ2`ge*gFV3ep*_D~liJ#B`h z+-f9ivpUYU#p!te@u2xydCKd!sSy6sAqr^;f~BC8DIxPn5J_j6q$)v{w`3iL_7Gvi zucFue+M3MYFj9{nTQ1HrXSU1B0@Z^@FU%k^IBibf;v^O*9;cVE(F(8$$JYuk54;O$ zhWv7Hzlr9I<=Qvj3F0}YV-%cuT-5@y9OLztNo3lpFX^QfetSJH;lfnA0=h>i=HJ67 zVp6E+!velYZ}M4>N*SJm-DxC}a4Q=0U@DJA$iW6B*T>&-iB)zZCCMkPBD3Dzb&>QC zrUS61gbp7(NuH`%q)pBunW|Z(V4D4I?Ir88kA-DbXqxUj&a&BYwqc^WR@7?w8m&~nr{UWC8qw6Vi{4@{@i3Y zQGLq``~%}>oAubmcfaRgjdL$~CIIAaNMqX}{8{%z+F1$VcJS`Nx^L=?M3 zC|tNA@=`tZrPhlNp9?1|bMMLLV??t??TN~t6pnm8m3JX@Kjip(s6;$`dJXIlR=D4Ed4t6R9t&3^C>4@O2v9x{v@1`*KWq zmwQ!st29jGB+u1(Z=!O;E&fhy*6lxq5uKb0%lrv?cezL7OLf*4AA!XixljgRz!4n} zOCkn6VS>`IyrZH|z^9+Kf_`E{a&Tlb+;wS<`7AQinI9HSL8bWNb#gxI1U^lT8FsR* ze$bERhZa$3I_40m4v(kZHi)<{f;l@sy9vq%=q8JCxS+Z&0ztb zzL)m&p8Vbw1<)5iVVb8#Iq?{b0OZ=c(m6e#sX<;&S;^u$dZ0OWx94HresDhn!bb0zH>CdSFgwiSxGTCR2fV@F)(K{iTP-~3;VQ>)sLT~!{waK4iA~%oJj+lsc z1@N=2TGKRFG2%jE{iAfnvY~D}yuR8xC;NnFKT=GjcgS;~%V~Q`Xs*RV#*w-?khELK zM#k|3d4KJ-0J_r&vJgLMW{}6V+&X8Md!P%)*F)GgHHPFEnHniPh&r%l+c7aFC#TIr zCOw0(HGEbSJWkpTO-osu;G~-h7!Gesj?v+HsDD-1Wg%nMFIPw!!bewTML+(Zf7t#0 zqtLXY47-zc z*@d0{jp{HS*U9Pf`8f|6quG>^p>tC2&iT}pbrI_yh~w4N9TRRk1peaJ@E@tXbO>K? z5V$hMA9x-A*tfk#Dm0Zc;z?@#Bd|e;k`F})R*_A+IdIlPps#C0!%T#3P&Lj}#xY%J zE8N0vp#Q)wF$T$J^B)|xcbXR5|AO>CoD>csbi0&rthKXr$K%CWYy5%!?FAvAZ7Swl ztYmf;o?cZqft}BGtBYmJv8)>|qx!q*P8JRNj~5N97JgiL;Hz{RrpB~Vr5^3TdG?p6 zQX}UFyF`u`S!IEDX{y3nbHj=wt$A~c#EO3HGil9S08eW6-2M8wfC_O7M~T6%ZmQJA zUO_qzWXndbi;U4^09bfa^yWZ#-3)2orO(dE@!aB|qs>JFzrM3$x-o)h|H7d9(()`U zWv#QQAytQ(r>ik}#VJ^ju1X+od0quM*EX+;Y;6-)L5{SEt0H^b8XX-3=JC6pk6!1FLTDd0bC! zt@7;OUi$%BdtEVMB`7;XI_a|3z`u2}bnGsZP9=fBShF- zf^Jm@(g&@?hgksc*yq7ew~dC(0$w>_An8Rfb8-r}q1_V`#A696_XMscM`Q=>p63^_k z{4U^h8mkdc?ewcoF9|oFz?CBs^NX5GOHwoI3=v9b25O_!w?i*|R?yar}A&*LY#eYX^~zle;FtY0!AEW&+Rl5*mWkE8_NUUHjTw2qN0<^azf zcP(~xi}fz`lv!`!_K^SNTRafzw;JV*gN9y&CP?{@Oucr&GY=NuE=P>Ld$zFm!^9H7 zw|82<*uN$3#C5BEK&?OP4 z)ax~%mgK!*|Epe0r{YR>%^IhUOcwBT z(c1>=mSiq|ndJ5kOw)XJZ=MS-{z|A&6n4VZl*3&HLra`+@(Ip{2biINdnZ}SIJEt8!|he&K*)#?r)zh%YJPvsyMP{ zpe+7&?ZO;OY;&ktKWy)4~*hL?|6E-cc|FCeY>mnw++ zDcz@DQ4!<`ns2BFq*$o3o2U2cA(5z7!dg)vVIa!*l=7!Wen+F}cWaHq0p)}-6}&fI z@YX`c5ON;+vB5VV7^KgSYfTMx!twV zzrA68O*@Cu7kiZdNk6VwHeZxWe(!LeB{*meqIDaNUyKzV%On(3tqi}%b`11xVIfRo z2t2f=et5$tQ|RI4ep}r!mf8+fth7oD7)CD+Q8C9a5d<5I@ah(<@d+?KZ+TF^QQfsSMexJZ1(i_0pxA4&|U_NTzhk zHqUOSlyS~BchbxpwkZ!Ok>k&U15eu~$48}FT2*M_QnWo%Ei0+85jL9z(E(pNIF(c- z)PYsn!jmrO^MAsDXdAcR-h6%f?F)(i88(}~IM)`b7Q4{K6}Aut`C@P-ULnW))59PP zr%}3_XT6$DmYT8O6u_x70aIYYBJM^j(rV+9HU`RL-*R>vxvBmseMa05N9I}eC1G&Ks{TU-jm%9Up|of{E*X8Mk5Zx z-gvtUp?YUQV0>ZcOtN#8m`09isHgB+T%e!#f;{?I4%}BfIhz#{_9nb)+5tYz&&nMS z#nVq`j>i=BJQ1lhQN+gwf_f?;Yv>vMG7hnX0#_!hPj7CF`xJ3NTzgWg5OzH&vt9}g zEESRt&H-KKJ=x1{<~=5X^~rf&ileoe#taE92HYLN`j9}#GtEPTDbMi<1Lq2t5WCyd zghh*GM-?4x->-_5NC3XV?9gM;YLKZP{@VwMpC3jRCKWVG-?6m8*qvzd>6tIt zvD{WP?Ao_#=1th1ngIn4?Y-6Y7*EsYRd?v3SLsSrWS8zRTUySD;UH~lsSAE} z7B$|t@_x~{M|Ul~Y*4c;viOs4Af7R_q_4BNJ1$Vi41a7UC9zq{eFfE41U>?JQ3ct@ z!Z)D;(rRC-<50e84jk|?JN%ZAh4zuO$*Cazo&nCdqSP8Fmv|ueTTG}JNGnmL)lMnE z-9)5S1Lx;E<8F)X9Y_cIpFdFEgPSgUQsaxeCZlT2n0gAHpHkD3s{ zg?2J%pncK<3~cXoUw?8^pKJ5>zLeDPg&2%ct5)WUPrxm@g@vPTLnVw<;^eV_-Cl)|SLrQ7 zwYD#gt|=0pj;$%8n$uQF{OVB)?y{p@Yl@uWNvVntX%-f81|&R{R6?Ub$kY;4zJW^q zh~Jxc1*=o=!)?^wb3V8lx=G6k-P9s(l*>Y^=9Tu;_Z};996bOttMq;7Ce9m~mzO0v zB2uBZESU6g(2!}j!*z>u=Rqq>3NhPnNgadn3G{5KPkgBN<%7)658vCCZ7&7s$k|*^ zDXhq(iNsY=pfZ*KH7j#$8T`=}Or5U7<-N6Zrcw^i0V+2Pyj2w#UrF$594<0&8l>xd zADWRW4Ve{Lv(8vh5-pq61iRz>jI5-^oC6X)^|DRnP}jh{rg^26sm(dfy-8rWD~_@~ zbX3a`&d!Y&-yO)N{KUK@YC(l}U=E?(J6oU-$l_!y!q?jfv@UR$dLT3F?_UnLOy$f| zd_T|_==v$yZ2&D->4^4ALw;1~RWVX@O4&J$wv-rJ4TkSImKSAwrBykzFH{N#9T%NE zYs1}xh9~;#*S|8n8jEoB z0k>98<4P29JxSm^XB?$zyg#NDAaw~nfNm|5#W_h&Ca=T#TGJ5RUdG&_Mak{mE<>^t zekF>E*uEppL6!b%ELVmP6=8_;p1jfs{ETF!i%lp%-#}lZPX3q4Bj>4I`MyWh7g8%b zz4Dyy@#5Or9W;VMpcTOb zF;M8|H<{nQaL6~-YlZ|xZ4U=?u`uiC>6x1c2k-gLi^8?3VD-QFSgKznb38e^@kTvP zj0X6@|M-pHpBO6V1nm0G;KbjJD5P=lF+?6QpL>?~-KqXI%zcKHlpEijqmJGaOs&Dt zLHDzI?J+=c-E)Fbn#x!JgAPO#+8R~!U!}?R@L|~nj z5|E-y5P6s>KNe(Bbq>8!XL1%jUKfyxoOjI)N&7Fd6?)&afJ+?4^)Y<#zf;%#_Q8Ln zE`ZYWtlnBc#($-*w$?-|6DphioiC{l1Q!U+ax*bkDGL1cM*WvP6wK`OG8cA82X^~4 z=r5M=FShtAYZ3QaUqOjaNXO>C^2=XOgT%M}Q%B5U;)Z|0m4Cq^Upbt}D?OS3=g0Q_ z*B$x7G2i(PnZ5zW`xbYhhjZoz43Gnf;cPRR=WOKkc7+M& z2!Ll`Ei6R&vA8;ubLgeIp|faA-OxESzE1fpdaO?Q9D1Ry@+^9~hol`t&t_KTisL@= zXMJA{{}pe3k#}VE_M5sTtCO!RaZXP+P}zPQ@1ZpiyBwzU-|f+iu!PRn9a2C!7_-mEL zf-#-3KfxBQ0~Ea=S&DAdN%$3X>@VRrI_l~E?k#zwDWxD|!tmm-bS9jqMLQpMpe{uV z{Uu;pk%*iQt4Kf&gjFOVabf=P$i^`LMC4?ce*&^Mi{w5sBkK#PJZ*wJ`1ZYrECGQCEb0c#D- z3G!!0%5{>x+W2fK%%RB6nze_zxEzcq!Bx3``|M^?ta9 zgFFQw%k@ia1hu)+YGc+oK2TK2XowmjjzrX?&|&?cEI}0<=x(zdYKR1Kpk{~;8vtbp z^5;M!%u=aw;>g~bN;<4RlsgE|f$lY{;_fGkI_EXLsP!6goHvxrnB=puK?xCRj$i1X zU!P2~^yy7e+^D?d2jrz1S&fq|iH+J*fEq9TYF$Qc)akKE@LxMEC^Yk1S zWF<`W6v?YVS_KGe&l87cTxwh-PzXAI8X}L(t4U$NT0rB1D%j9VX3kU)1!P&x5Chg6 z8WrTvhF&l;rNYT0i)tzvu$Iu&AUqp-`2@+Vi{+kX{NE%j{r6`6N6_GpJOL5c`vKn# z<8`B;5TRfW`{C+dCzAij#N7O&h0_0yDKNlSaX(LqCjq`V4>?3cj#6zjRtJQLexeeu z2O^hub@T>*AUpK$IOSwn7rduu;}RbTs1wS5o^2ULmX;fp6Xdi4F{Tel%gUd}mc%>{ zSz7*oZy9b_XAq^O(bx2&TK@*(mN{#B1aq<{PEHE^gor%gi3jEg&jy;v-v?uwcra6D z?NktDWO$7UJ=PxD8&t6ujWL_0f~X)vYn17+cF^`9|GnsGvtcTnGBTeA3AruG0Z;cZgMXl|gPc4h8sy|vAgzMZw&~fxL4zT}auubXq4G3HBJoKSffmb^?`~8`E#NN%!a9PN099`0d!d0BT_=TA!=z^ zMbCztf$a4B{~qA^8EQPx>_=^j$B)-ki1XCmdg0|FEUbXMfkloSmrSA03;^u&b(N?C5}RBq`hs2)F-d z);zr?<*P`AKvhH?X{P%%qW~k+D#73L$&YFK3`cY0fvJQI)MOM0XF4b-ZNM?fDh&2? zOuw>$GQ93WXf|f?>;|%w{meZD$tfGCZP6L1EiFVyY#{V+Z>ZPn<;(ZuN6>)85A7SM z8_TGmoi=T}zg#8yQ`i#7Qj*z{%$7feEhmuk>&t15KD{Qxw%{PtH&wzARJWOpPNcKed2N!~1=@GCx>pMAlwJ zXO(QqkcyW3o1yFeARhv*tFYW5$2q^OX6Bn>OeI>Z?4LY!2pihxYgHySZlQ~0QN4;< zawfASU}SH|sQLvY)vsV-18nL3)7X-m%$8)f6wLeyjvv65%RkMw4Ai$VMcD?|8~?LA zam33%WTT37o$`ODiTxjSxIZBnAPQfdg^lB9&kW3GS5$V+P?d3ia|2BbIcCO9jgv%9 z)>P7BJ)zD){@iFg=;YU{Xk6&_Go+XVk4g`jEy*z|py>H$uw`v2KJ{WVj!?De=EDtC z2yeg_596N32I|?E{&NSEEGbAUKvo-HZ_Q=_zIY%95O}Z57oP2(HpDnVaWzAk52k z1|nN>{WP|WA+zPbAj$Fz!~=+I$@$aRGMvnoWVYP#A9;lzxYa;Z;z_>;)H5~~P-h21 zL`CF)`bN^hzksCrH6oWzQ9x;?X+Kb!xs>H4gT#MxF*3A^G|^?pmgS+^^N!$VZ&dbUIYjcE&m=O>fTt0sEW*& z%MDb(l>%CJW64_GGP>z1paKpkt^^7**PJo+ zW}?(UebL|UXhaR+Ku`6M2zf_pw}l`6F&mV;A*5b;hLTWfUe6CFH_nX4i!uW zI*1axWy1e{2RJ1lU8Ge+I-x*5NJS`bInd$9jL=`5Lsb4?>wgY0^^SejiTZ$NF^qgyaBO(EKWK z$Bk!-9Q6oFUjypkeo~_?vA+*M#QDkOulNs~JyDt3_mfbHCx@_NI`jHqSYX5tneVK$S^_6$)uf_`Qa8e(R)|jeT#+lxvf4+r5X@6Jtp_A!5 zjffNc176Ti=v}KohV}cmAPNEKY107k$}$N(O}Q)OpF{cq&11fzO#<>XhK!y@#$nws z8ZCgH<`00N;z%H<+;%_E8aoK@^A(#HzyoR`;{lOTt2d0@{RJ}Gp9mS99+iJ3NQoOw zDj1eRPJeUz{7;=ae!q0C_!Y?Uqy@E>sniKvU;nBRXVAouSu(Z66#4wJAZS5HHvkqb2@ zv{<))Qk2>LN32P*X}S2n)3n5Me1YEl?#Y1so&o(@&-<4zeuBtnfcyIWG}}_ihAb_~ zctAfvU<1<-Z0C9f(|x{T{jO*JHCF3XUy z$NoJCY(V7F=XdMUVS|xNpaEQy<&PyO`$^b<;0@&VP>~xBn2~{TiNLtOz$$z}GXD~} zEZAV=5LQ&O`gJ+$Yr4E*T`k#MkAL*UtI6U zs*JuHnfNEcJF;;~40HZFR)L7kn@wy0N5tlxvc&vz0MxH84-uOe+M?`}`D49`$d=*1 z$1>com!L#DUDZnj>*EAk6)nQBAn0UJ1uJ^|pLB&u4JBzFK@vtls$$QM@UlM^2YvOm z|LcoPvSkPWK#*5~SXGvZ;tE-M|I-|C-@5+`rX{iE+;m8vmF{l;g9N4UFv_rd&wcKn zw&s+4JBVNZxc-LzR)Le=RPCu#?0bOJ#rN}fKcW5Yuh8rC7wBvG3*ewC(M|UOJq(vg z=qujOQ1n34S0dgy0Py!W3Oh)6l%`t0!SlB3*`%rE zqHp}CzO`Q@Ng4N-Z0Psp${#duW_L=6C$Uclp4in$G{vqc2t`LqpaXcQzTeE`$q zpd|v1gl9fzyD>GMs&A7zOvaqtKy3#ZbCT58$X*M++Wgh)DeiQlE@LM}lK|++rEd@~ zqJsR{&o#Ya6!*I(|x>Sf36gOqvo_moX{?d^=%Xg@S^DKp_1CYSZ3PD@J>D zB;y80btyfghRmI7H=!pkof|MOx?MQBlpORSsB)aZ75)D1<0p~FPrHma-eb>%b#n)w zF046`R=T4;iaSldNhRR^OH*UN-XdS=NM9zD81FW#xQhd=T>I(U;^Y>}KhTfV$}Q-< zjw#Xh(~U4oa1R?lH22P1D@CA4lr#-Wit}eEx9p~%qSyw!-%la&p8qk676k<-eiOxB z;E6X#6zuHg;BISe?cpv;`g7!nh_@r?!M!t4Nn$%2XJc16g@!3d&YgdCczams1%}Jr zjeSS>^lIY!+s<6B!qIEK%D#6ZPjHhZbW(<}H!49n`D76NSv!#d4oDj-PtOJYd9S3g zRF$45yLlW>8%C=Z3N>DNHitkjq)%zTOwQgbv29yco2%p5xRUH=QcNcmaxH~hE?wAe z@%FN#G3t=2#`Hn9UhXJM-JL_DH2W_`iCJBCeZ50{`Fg>`X6?-VREyJzVBd$^SGQ^I zEEoXu96m*Tlg_zV&QL)0x=s6l&f#3UeX}tvyKZUj5aFIN+h$ocd}`N&!!N9@Irf#Y zv@TC+4Thb0AK{ToIKe9Fu}9%!0Hvw+dgDQ#&WQ1<+UpFpqwJZYaj&uEEpx-C$|EN- z4sx}|sY~t%&u10B<#8l2=dpm%v+&|=w*tMTh2_vLse3MDzMdOwPN@*6n*rG?yl1(h zhPSzW8(o?ET1X$Um=VPKq*6`h!pv$x`%Vb0UMrg_&gs~emTSg6Ipy1S^#psjjuDH!x-zx|Rwr@r3Heh)pdn}bM zmTuoj*p}I-eI8tL`jB^NFWePtY~lI(3n_|M15GE&1xH3{4(XXfb%*P&J#Mhue4Wdx zT1TG>DF_b=tPN@#>E4TO?Ndj{&JFQwsx#Pbma|*MwYGz%5k~Mn&=kAbt0P+8bxnEO zn<0%&3P+C*&o#unCGdJ;+A2wGM*1hy-!O_(CVK`)vB1q-el3C)>e_XAx(B1ac~N*K z*mdw&wA_{GI8`r;E4O2i*DTx7lO>k{er7CcFzL7r(ENbe%`pzD=Xy4CS^V)%8CZ;`Q z@WD*#+T?Q8+G_6^)@j{MIUN>4rh?7hjuJXDU80nq45MoV_dL{|oA$yjddbryzU|!- zfNz}E<;H)S@1B+s4P3j)Q9krIRf{WIb9ilBG;kdec*pxhm*D;R)VQ_u%i*f>_MHaB zJq=~bNdJ|I#@?Kij}O(sRqGSjW{GKQ*6!AOsAIf+J9oc#D+w&Wbe5?+Z%cnLJ!a@3_^4HSurCBry|2yuFs}EC3;)gV z7ZKqvLTTck6J$%McowPIPI$C=cG~Y#ax#*zbbsE1qDwcs(oiU61 zbXUV28@4Xxygg7F>tfD61A^O`?W7Z#kQSNX64{)LA30?#w#yYJk&!6CUK>2+mnDyQ z;KbL??&C1y5=0)h|QsrV}f4Gy_4Zx1D*Y zLVMfn;AXhciJZrvZLH503O<~z7R#%TC@-w(7H+yvL758M)DV!@Ta9d@qG(X23|iH_ z%81gahSGrxMQa8fXn$43K9=B5xD?EQ`#1KemYRw}H&vJF1b* zz(D)IGZ0Q%469^T{T%Pwuub)VSc~)X3<37dAw=?+#L!V!d>n&*r*3TG`8C%&0Ckq% zp^o0sjKjA&zOCmdl|fjCmD`qMn`SxTn)@tGoJLYQG>s*&j z%H?kxJPH%`(eF8NRqWMHqlCvz~r}(e2}(VpRp*(*yIfDBp{S%UyQ}M(X_-&=YO#y`$Hyi1m{3)nuxFa$PwfJ| zjCiM5H9#jXgRk7%jfj}9UeDKOz8u`Sbe)Ik>hT+wgYFYoIy+J5O+f!{*UOcCYnGEl z9=o0XELzp$U@esj;dKqRdg3R~3<-e_19`f_xyoBm2T&!}_2(<(UIH7ybGV=pLpR z^^-{W=+JQ~;yEAUM1Qfm<})!+r<-p61J#fon=lVoCa1LUq|4V~d9)3h(rigjEsJ3z zdZ=WVi|>wWP@}c>Nkg~DxNntVNmAcpO)0VUTsNx={868P^V~T%@v#Of(Cm(6#H)^e zp=c4O+AI&(Jk7_Mw21y;A>D;1wfTj(f*H+Xn1Yfzf6K*F^Pt=Q$^j|;tHlZJ(s?&q zsEoD%!{v6$8nKU`8{EC$u#*3X)*j*XyN?Rg`HTl|7*37a#CBkWE`lZxl$6H2wVP*l zd@sGXeFWd0I!MgGUfEOSU@MU0jx#K>HQgdEI$=1A z?Z-57id=^ea#BV{;6BXIa+EbaR}=`)7H&^e(z%*9(8A~WWgHdKI9sl*q`cb^>T$gA zcy>uH4dvnY+q9k>8ItZxqj~l=faPq)mYY}hrWBls&H#ptq1!ndN0q6YcVju zcBq?9R#`B{xaA4#YYwSe8O=CTxV9b#KCh@Ng>qxaG_n>XRCK(?gg0kQ7BQF_1>lQX z;qV;7`uKQ~X(a(ekY8qN;Of}P#n9V4WsdY)ow9KnT#7SA1^D}~tgT>llky01G=A9m z$!D-Ub4zm_|CI%2QTN)&rSqn1haZ=MRjwor2a2YMT+aX(nGOyQhTza;%u;Y?Mxm8F z@Ft;qBeUjNL)VNvxpfx~Z_+JfQ4F+oG78r=Hj3y^;$(cK+1Oz+D*$s)pwUNB&{tsg zvP~Orx$}WFT0NO0e6joyIeLO(&Z1>j7Uu$m_K}}vZbb5gRt*|h_P;8LCSavEaDa**pOY_ zGX~Q$`5px?=w4qt&`}0Lu!Xb>ODltHV0N7Omrh(|b2i|oQNF5tCFhi~Q>R;;0b5W} z>(&Olid(%-F1W>xci1N2PjybdQP8MV2d$gJhu!!=UYnVzsj@*X&K~z;$SoPd?1-IK zPFHy7i?kT%oLEq_MFUPEMTWeg1LJ$*2MjBvOZB$%JM@WqMOn+&}gYqxINB0A=;>|}Fy*XA(> zm`mr*qYYF0j`a*$2wpfAogsHs><;3B`G{OO$mux+r$g>X5R%bRP7s}7Vqj%nnqs4V zM^^_qm{%N$i!qS}VPy2Z?QNdAn zgI&EPEjcA<@+fsu^kuIjd`fw$YuPhu(S2ZW@fCt z#>7Ia(5_6gJLZ<^k~bRLwq_seu^4%$*AEpjm{EO@1N~T7Ups&`@OB`QCDdYbCwR&? zk@uL1`N;dLPiC`&9ahgV^TmnNnqiAV>{h|T(D;U_XU|_%Wy$38u7GBlL zDkgHb|A{32T(J-LTqE6^YxnQv@60V=>8z4j^H71Fo`-}G zsH{W?6wASUU)PM;X{Fz4#5gKg^Z?D+N85(dS3)iHdOkKI+iuk!w;5Sn<4k^4`}|_= z$6)J`J8L@TBjNeX&ytFC5kf+#Y7xQI^c5XK=vY;88u0XiqKtzSPhve<9xA2pR}a-g zX1nKjf-TG;NAI~+cYG42VSz$*SxS@!K&R$K#V{sP)dt?pVO7U^tVRw@$&@7Od+&pk z)YjsdX=Vq6%4LLZ7jiJ$NW7}`P-=a-F9+)4QQZmFFMc*`W$tz;PmJAF&wJRyyt5Sw z#Z2TvFT3gKnOxH^9(RZdUgl(`@^&*~4OKhB{HiO3TfuBRA((WIf)NW~j{`JMG;3<# zhJ~HJaZ)=q_?S#~Fj0y~(lk$MTaH|NytTE~WbR0wOVPY6M|NfHv3~L700+d>99wc` ziIIqHnd$UQU2UNs|I`g}TF6kF@EMj4sIE_Wvb5pdGYpp?=jpD6$VDl?N|ZF>QZ`Oe z<}~E0QVJ~-E2tK8hF_`=3F*9l0uG|Gi_cEC+w*P@TO_^gst8^0Vv^)p5o@-{BrU!` z8tzM$5KRvWNk1_(rVF6W7NE_JNLvVl5?g~~0d!L+{K+9fryY;;2U93*udqcv6cDmv z(`+B^43oSq&r3I*th<=50WaqX(>P_u>enMl+^rC5`>T?4kZ$~0II3$MbGZAEEw6Bh zqo+o6B=OI!8BIx0#>hR&7-22*sm*Ly4P24Sn?iwe*Z2c30YsGu@e+x;_w=Cdg1z_K zqbslNS&Pi=6`OHlmtl|0^T#{Hl8&)Go3=C9>JuFDgfg=73|tD&M;CJ@A!KakqB^{> z#~$E5Nr3w#0q$c1xQ`9szNh9xnb+&|_))QMn=;HfxX#^i)!hl3?r`aUerjt{jz-TI z4?nx+{VnDD4xHJ1bIJ_v7Nd`PmRT%(^Fn9{LemlL#B_Jl+Vv2` zf@pR$(_QWKr{)FRYC}4@@N)hz<=71Kf@8Pj6Ye`mDt?49o`X*=SrsfeCDt8Iix~;B zTA`6F^bl8Xv_;<6{4jG8UieN&POPs>okW;jo@6<2#QF{@cGGn4w2eQ*7nG?EKUHGo zCWZKT6m=yy#Fgh+LtZ)4#Xan7s)qD*d3&D%GX2@*JG!>A@^9alNg5%XyTnTF*~!kR z#7g>gJ_Zh12XM%~WkjE{mz8V{$puG2fC$_-R=H1ulTFjG00ub*_qli<6w5d{<_*u#8ZDHUIMxp&8a& z=6O3FKj+z;2E7Y!*vlAs;Wm5Bg_27;1DDC!}e$($^ zkOzFH6!s$!J9g>KDCTM0qAl|Q*?$Tg@v;n-TXwfpA?IWElxxy+NCB9lUk{?oJbX=z zSO4Uo?e%lG^2O5?)ow#wJYjsU)JFY{eN^nd)sy&7 zY~?zPCPh1(%QW_I8K|Fh%=j4Xar?RBo|G9);+uPv*pJ5n7sPIvrVN^q-u&^c1Wzun z&~tZAE`PIw=XY|6T2w6=?;hoKcDJ?k+0SKEt{q0*g}vV2GkRB!znoE+Q42Eeee6l$ zLoChw^U!ugHy37Wf$-~aCkV|48~qftEz6q|!9He3`N7^a_UV#27}un9NVg9~|0{&G z57#ycEy$A38wE3-^T~z}SwJ_p7MMO#)37_1jHQ&)V&V05sXweW$)?nC*vG)JHhRH7 zCBP$g=#2m(snpZA?DB`j4vkSe!}PePmWqzkiyq*2Q^{F~i}XkkEs>_2^UgE_0j1{| zl$Ur6H)~C5D6PKIib#)fwo@|BAB^~9YN#dSuvA?jtu^4ftABw!UwuL?lmT40051IhJm0MxkI5uT70+8k7``m+pcG0K*(2xUUaAL{?&vjLL z-b25dy0!&jvXy%&QW10i<5u?T>3BBf3mS?Tmbq)u##+4@pN`6@rkj7#NYN?FzmYAX z73Gq+-A{7I$}=b4VW(IP<@{*xew}&1eb*Y$P(~#a-yEU_l~U2feazQ=T@>tJ6Rubm zN=;)J`k42lNA~y=2FJ@jr2-RYhMp}g-Xut+IO!~0b8t*4T=MI9REx-c9F;Gm)$6bt z%^s4zV6*F##uhD{wZGZ(Rzx9G)T9p}$1asbPVr}QWayD}tj ziuR`zq5$&(*s$qz4(JMpkWnqd1U5Va%0tu#e5_aK+pJj8+#Rr(Rd!g5Wjvs1pas#~ zjDI_tRjii&);V`ipjBHqO=bgQ(pt;*6r1wzrZ*ory3-~F`;y`X_?=x5tr&8rBBpm!^o3Eos+~LU z0ZSyf>6qMH{>2^JEZ_*rf~!0aY`jagX}5{?n}%;683Q{L@O}IrQ(F}t_FR6ssguZe zbn!&KD+R2JR|rG`-FXLw78XAJPkN8nSFsrc|Jh{8sw8QJ6-UlD7tdXLITq)c8>?|! zz9i0)`_wtJNA4dY4kzy}8&FnC4n;CQP^s$Wub(OOnDN4&QSf^Ty0pj;o~CW@mrXre z6%N1r`jOYXrILanee6?9+5GYIr3xb*%qc?x4CqHNA)^~7oYf#Q&R+9|O6E^DB|bj% zRxIEJby}8W$2*gTN5V0sf*zVYPfFWEn+_P23l|h|4-r;J@M;HVYpr8*Ba+vSx3%4O zJUGQ_1nLW!X>&O=O3_6LDdjcP+rr{(=~#q9zhm*;ypQ78<3rWF0jbn!=ZbgNvp0>D z*9ld&Nr=B>7BR6htxe-bnetZn@gthS(iMv8jc+Xw&7R%Ku*xmf?aifNqrV(0}40pD@muXmLC-2`lL*VZ{eCSwN@iDG8mA<}v4-aw%g`eBr zg*qgub0^&6q3qRQVMS&UndLx21HRsK5dBVl@YuPc>es>U*K;HKXR{9Q3-~0#EIc)N zP8^0_H+d7d=TULdYgA73y{kH1QSM3i?mV?T4O8D;b;uQ*aV7SZ`}XCnW4 zp7V~w^}R?0-N}y+R2$wLO`CJrR)Icl9c#(DJg5tWWRrL_Z>(K$m>(2$o zD<3|N%WE}3x886a`fwkCPg%A(k2J`D0>gQgO^Be5hPq4ef=7kn&9WDQOuZ7xhzXx1)_iFVVjIl$qy|Aqwi6kI<@Oe+|ha*U4E(z zWN+ry=V(u0D0tDxen|%JbCqfD9lrz;-|S19quiE^K42Y-#F(gRE=zj>L!E}f3{lB< zEWi)$Q5GJ&9(?BNDCg0V&?eOoyG=CIsLe-5svW(lT6qLwoc9VyYe010KTuVDLs755 z6%}~sNsRHs%v}Yj=J=^0RY!n>1*GjW%6QJBEhbdu%-nPJi?;|2G5SE_?X9jdLtWko zQ|zYi3%Syvcu;iZ{xyrSJaBNEoz+RY^W~J~Th5n;dSi6MdLPGrQt)veD^QoG+RdH= zY^Z>j#A!LRnB%0;_M1TBZLMs9(XtIG1UNG3j@ogJ#ricLJ)|it0Ehq{dw_r=2d{Q1 z+1OTTJY~*0_z-#8F*Q$$0sGlA5#eo?HAZAfC@T~&8V~O)YyD0q7w*(p9kI60rNjZvSzte zw-^I1@ow)0i+o7D-PzmBn#Z-zQS4!S>c|}&J=m-VJJMH19O}9B;zV-YzUnTOh!Lp9 z17KSDNLgT7kLnxjJi*7qBM|n~XX*FQuso^{N6eU)!dwkLjb~C8K=wX&RJD(RY!^P& zY~1O_w)ax_eUqn!hPwjvcrS(P>@om7msW4=usBgrs_>{j#6Ff%+A}yfykj)jepzfX z{=D$+;0(UE%#0b1y21R*;s&?$93KHE9T-IuT4);YtH)~)u5-YEUfLk(=?PmHQF{TC z={Zadn%F^_Ob=I^G&NIJaMz`7k5ZMJE{<3cM9}>Hl;u zH$i1}Zakyc*<}3_<4h;y?f_+r0-u`#rw3E@sT)q|Ht75QRol4EDBpyEEWL_ng-W`M=zH5{p{nmn~1UM=z>`mRM zy&|VtPTAo5&x;WCn&^GV)r7`6w{#lR78k~v!54d5&&^mD@9rEVawMSAl3ixrL`-t& zgiSt<-NM4&ey;0CG15Dms2;D2?B0xeRIFE4_sJH1?RCF3c5^9pywBOA;1JWE-0g1< zY%T?*MSC^N2=t1aI$G2LBvxKtYaZPGz6~|z8I`fcqf_I0INf_-1B^gNb%{#tdH8&F zwy|FE4PzV8$Ha-9^tkfLE{ms>nz7Sba8L2U$mtCO_c zk4ekTXiQvgxX5eDGB5KHK-KO?QMM>b{24D&6E8{N9&L}c>IG;t>D zjzw&9#TutsvQ8FrIG&bK4}EJv43^Ncu!FU^kOeeEy%;{l)h?~Zgh(zbo$?6WeFT+| z`39LL%grmtvB`s&gdwdtBDt*lX5(dxQd?eN&pb%_`dLPqgb}Fr!F;uoYMu+DQTf9e z*M5$3=fOi$L@KPW8+n9U7nwO&SMD8mF2x&NbulYp56-;yBk(JZF{p zpbDweeAVIG&~2^Nz#$n++lJ1KtZlB=jSw=CzYFYsAF%s#?_AdXPs;BQJMsXr5LZND%L7XV1TkmHI6LOko&h2~xAxy;#3s{LIN%c#ZHn+5ZwFOhV zj;e71uFEzv&)Vt%C)Q7Xv0`EdVbzJ~_EDhh=(tWN!C<-3b$H-(gjWsKb^TR6D3Mkc??n@Fa5suS#@B zg?IF^G%(YepJ8Gfb!Ey@$IYm{`6(MbUgy~{!2<`!^%AJFjHGKk#uYP}0pffTTV9u+bWL5cxGul!TB(Z25y#dJ zfE}E;@;v%>Ef|8sg$aXP;lw_sm+=bxBqCnx4C+&9#O6J3^qvY+`b4ke06gR1UI^ zv~~Wir6bQ^5}k@hoR+D)^RU1IXYG`r!Krc%S(-61!fvv{b}vnU3|b9p-P}G%e3C3p z_^)Pj>Y*B3c<42#cV;6B6sk3-QNjS1gTCq7o;GSzwY}hHTH_)Q zBn-k+b(m~IW6E*tcIt0Su8D#?#)%T=;u-m$#u&NAgZi#poz$K+x#a>2a@aX}<_dW6 z%(q9G)iv)etL~_kdcG2FWi8%$KEIS2NX?&#KHYEWSWVCRN=z)0vO+PxLOo zq+1D-T+MOwI8`efoI2!b7-W4h3Xx@Aee-6cOnptX8>0AQNR#>7?EgdCB3Q4w>e@*e$ ztW=cHsCH@#4vS_rCuSxwcb|LEmM@KP`(lnEhL9mjQSjsRoU`;5c+Pd68@042m(mEf zX+z7^hTf$T5{2|(6!=1>G_1HDzfwy@0|#$?%e2ER?aCr08g0z6TSoUyx?kBMZgB4d zpAF0TSi!tYe5{zdlW?{Fth_mBwD>A7H6CW}IMs9!2=42gzHX=icx4{{Zek^^*l2g$vz*g_$}jkn9^3sh_g zYXv0UlxDyiLJV6bk;Ij012ILDbJ(2fpfh(;f0T?d>o3|6DAU!Sm4|P_$E<|njX%sg z)&6|*-Ku%|@}NmlbtzlgarBhNf6-ugYrR}51K!9SEST5QdCKxKPL{YMb`PVnUi1wH zi^7Z4;Cdn!2Z(PLY7FxNoKjf1tp;8th#WD8%&T4HTd%Pr<2+0uqR7*{c_k+n9WfP; zN}(5LfxcRL5JA86!Q99?QMuqe>a!@4tRBUvj11uwYj<=p5MHfILH5-;Y>FmF~$E8r1!k zAmb87x&lDaGiUDk*NLX%b8&vn+$J?|Sc@O6*NLZpvLh_=JC%txqWkVykwe2<6t_yK zAZ8y$e4Fg^dcYngd$eQWHzS@6SBE&ywuKM;yiujLm)!Aap1@Io0-TOV0SIJA|2q&! zj7v)p>QBO?h?S6L7ZRLx|DJng1+mKC1Cj|d@+@(j949ohVdn&qHnLc5hcQpiq(y#` zs|S*v`7&%Xk?rAePgDuu`&Ufi(<#!BvReWQ4UHR3d@)VZr^?KE{T9Gz_e`=M(Qsa_fv0kf%4w4`<@kufjotptYbA+s722lprzk;^t zCMS!C&IHRGWkg*Cc4w9jm3y>+|9{jkuOqDWyUxDMx2H;#c*WOFWRn{?Ci@Y6Hj`tf zONP>PaP5(ZPH;&N-9K>0>Z31EnMJyNvB$_H!6i)gZKUTCxE>}l@mkEcJldx1z0^s~ zD|@cbp)OH62MjC56fkK<#`O3BERPu+ytht>n%f+|p?p=VM{Kv_c!s{ADW(sOt#BaT ziZ*9d%f7v&xU(ZP)^%imF5WoF-LW{bTK{f=yJf+A$37NGDiNjq3)lpVflUBOUdQI6 z37`QYTCo8USH3kx9}sG)RQ+n?%h}V!h^D@+=R7glvvTF%&nhTnS8p7# zj@G;Qd*8Rg=BFcyx-07#dm>p&VCRD3edZP~Ce zJJl-LusE6Bu!yG~+lvWi9%=afHUb#^P-5|~5`c(_XuzrZwzG&W>k$V4_g9=E3>0+1 z#>w#)V_gh@=jyJ-(Y7t?nq*v!Pa{rZ5G(O7lW>sFLt^VwJG9+}dPcIun>7?Q6@t z`i$$B8H>xT7U@^U$<0IJ2gYexJ8>!A#!=!s5;PQ9EAuBbur>H*3Pe+k6ur z?Yre-lU-*9NMBdK3~7U|xBYuQTS7{E>n!G$4dWFRgCb0JO_V$lqZk&izmxhaQYBu~Ku zb60}?kihaRB~-rt5TWdmqRia9qD+(DP`u)uxim*fe3ecQQMKF;jztuk@>my}p(>-& zCO#RCJHXD@UEkMITv&XrT@TO4$5Xa--j$Vg?_C*gxk1j5dyU`bphVFn>Sd!#B+Lqv zp->OUp(>_reSLz38#^KFi>ZU>`7v-;OsSR!O)oeIfq47I+khXY)R!(Z2M@C7*KAO3 zuy?FZtC{ekV&57Q;IuR=n+{Lk0N*%AE_#Ds+p54JAaqwWCs7$W$}oshrkh>REKeIj z1VpJUOI~>G9EJ}#uYGy4Uzi0=^mPzbe~*0;6dOUBYIu^;dp>&XTG2I{`@Lu~id%v@ zt@B%dX%Kyy>~dp8FU-`@JC)0Vq0Fumk7B5+e+)NseU-1>));=^006<2m18C7VTWs3 zub4(DT5OV@;tMyw2OW=I(=Amabe6h4GsDVGoK@661|3zAC2bYbNYLP_m73@KZm(Gr z4rYLQZ+z_~&??Z7Z+`U$2*L1<`u|t(o45dIE!^2(u)n~W!2*6)#olemyb;;!HB``aF-HJT^5s;64SwPj+ zN5IiDoM=8Gx#jEDAl#Z`?{#grP4Jjg)gODlP5q-r*Vj`dSIj}3=0TOY{u%nyn5P!Z zn0{wxPL(HaXIEpCWViYVH_iF`eMAe>qiUA^VZ@7MY!$<~UXFA>G^9e&($>B2BYO#l z|H!#Nuhblg&xEUSI+Grx_%vh*jkLbN^vRF(LJb7-pH?shk9c>jL9g}93R;fU*n-Y-SjkvJ#zSTny2TYLGc z#dz@C;Tvm%gW$U}#&e-_WhQ@6a@YGdZw))uxxTFC2rIKU8YF^l7mZ_Uh8?AeU$y#{foR~<13wmTQ}ww5ZPN#SOD3QaU;Gu=eEuF&1i zL)~nLLI~T492L*^)@|>Pr?Qvvoxg+W+g6i;*|ZzF*y7y_HRbzXv`ZDnf>o}}h7*~9 zHlwx}#&Yy_3$WzKwe6f?s&-hUKEYMsm6jW059t!YK1XC=nGHu#WvUjWj^K1n;SH3l zU9pwqn#EpQbV2{&CDh{v-r2t2z|6VVM)(Z%8Yp#Xof#lQ9EBaJAGO91*$O`SX!+y3 ziCrh(_gGNbM!MdYIt0qrg8GkxcUM)}#uVKGGF>8Fca>%$m%!(F5{W-1EkbZ&Uc1C6 z^!A@IsF`goBo#AA+pm?F74~+w)JlIL^+N?1P*B0yM;Sf&bzZJ?Uv@y5O5nIFN5k~5 z(mUytD$M$-Fyb#4Cz9axRF#=czJBhnFBWP35v6T($cW>Pe+nR@Fi#OyhwWs3p_tRf z{?$$?l8TnfUVr#B9=nd!pI74(H43V{k)%~+;faF}AKAczgWy3?*i&^+Dj%?YRwzs_ z7myq60DYiU#%W%q7OC=9JhCP;>7dBA(a5$4cTlExw5HvMu)ajS49!NU+SVF+n1PVRUsi(g(Vbe333Om39SGa_E zWYG&9KsWu_H-wSKd}9fdKzLbrq!g9W-eQAHA_;Wq8T*)7h;ff5rxn6PO=!5Uk|zBT ze6w^y3MJ9ZffcX2BB=rGR7BK-fstVZBvqUMF!#z`# zjny@$kBYcX&8rHi_8yW?y}C{x2-wq#R~RSNsl0{Mis&IDzk6m_`cG)}5h7-Omw?_{ z3t@hHUkvJ6P;HNEUiS=@u@79Mv0fRdS+0bZpy`4bI1b+>52>=CA|vTRPd)ooK%1U% zHQ7s?aQRC{P@V^yshdWKK`a$z!$HAnM|lP%eq~#76aR&kamp-oqL0o1)(1pe$J_MeIE8{&d4M&}D>X3$L{J z>*eYW4W#LC;oH>JO_gD1%p&!z0O zTyC7Lk0C~-guO1y{U+5!8ZZM-GOHDIs*FSY@|~{UW|-_jkIOEysvVrf>rbWqRS<~F ze(%^mYFbD$%VD8_<1T9F1;sbnHK?RpR=NAQVH=!PP8$`d+A$}wI3P#t%e2x4J{uPI z%(=0?*BytM@a)a*DNGQCdv^3pFO1)+qSdW`vhuaywDzMi6#LSpfs7H8|9P@uhj-j9WIJoLHHT5#lIXn96KA|BCSc%`;l$I%RXC)46En00zJ~Hy_G#H8gIm`n=Y7 zV&TjxP|+}>R@=bg$i`N9c1DJyU;70xTjW`@x}G=84L0WFH;qZazKlEeJ8y&AhEdBe zeKmcQ1HvFQeUy?W-x5dI(o)8-tZ9LQm2Df|$R8YlVQoERXy{+FwhnQw#l8$LGjZJM zI*GnNv$_pvN(0z*4RhK=rfI6_a4uWQ07U{a#1R4NTeEr)E&(%Un^svDSyEHe+{qCn zCsoyn#YkjCO(c41BQr`ncF?N7uOG)`Mmw0nxD2RS+xvS4&wtJ!13beK;K@Bb`RXx< z?UeGC;nZ=gSBG3@56On^j0gPy%^uW#$X(+~&!d%~)kO2L=~_kV~$f2r!FI zo)4+w4MV1CFPCewg`*vgU#BC-hBZNVa!W?;vfs6MX6LH|HAalEtj^_p&r$d$N}jAu z2n8vz(JAG7UB7T3byZd7Zoa{(!;h!qq+{W5rHl%I`topr{*|o|!%E2j_A;yt2C0QY z<4nNM=_oE?3Cxe@ES(9w;r+&b;OC~?K|L}|`ls&bi)#vEZd$L zZ*F#ZZ*>PSrFF$PKJ;4AeUbAc?br`(%^{VQhxnv*`5U(?VrS77wt`zk-gh@t>=nsK zJp;Fae^_xxfz~_RJL(qWXi`e9ayRPNI$orRjVG!xv68lVyZ@{&eYJD`3)$`__2Jki zKW+teZ5R=%zrDvioVN;sOz0C;AY=>NdG&L8?eB`}O!4&qy%~%NNol;5965d(7FQ@T z5keu#RbK8p2lK7<>@|8_zIV;JC(1a|FqY$&;EwP4X5?2|E~WBCrI%qdiG>=!_YQaJ zXuxt1i@N{W+bksRMLRqzm<6L zdB&R9)O>#1zT}VQjafW>7X#Wc4WjbaME!T1uHo?awW?1)etpM?hV2O>vJFm{0khrk z&mIDsTqR%VitJE9QJDlg$0Ud8%r!YjsO(S2-(FUtiFZn#v@?icMl&bjy`ywgI#Iw| zQz|{NiI|zXp8rm~-7a~Lv5(XenIZPOsB4*mIVzteDy!{dWu!Y!{QDfQ6(dOP! z$16kZLB}>SOEb68&vWEdFC>PJJP~ck@G)=sI+)$C$P9{MY<5e2Fiq^>vc%PpB;O)) zc-!|DJ#*?4vL_V^kLgv>f|aixQtO7!kw>vR%cDbjOP%;`ndNDSxXlRUI|2Snr}j=+ z6=-jv$Qm{^B`+>}W?@(1ndmHfeO~>O2#p4aIiT>rc-=7M+D2 za>z}n!D_8WyOUzPne{gwytr8Jv9gz(sj@{yUCtCU9um^Dp4XTqV#K|K(;lIB<{qJf zqlGg{>PcZJ!MveKT*T!&&-`mW-q%flip=HFChjzvOouet0H#Td6M|EMKBi24j40W| zOKM)+EMM_!(^tua;F}j7SBHkd!nJwIZRxp3hli4Q8{r<#W5op4M%pQ|OU5X*Omx#Y z3;s*f7}i0FP+6$Rm7*z9!d+9*{|zSUUtmTHf9rDD-1y5qlATo)}A(AN{qsFT|;_j7s_D`+=} z6jK8mmxo4PQ}u^>#neFcw3CluvYZ-@8Y(HL(x013;&Q&&%$SC_b9*LztPeB zHuGqren6dN167=nZ#7zAt|XtDx_)#pe39hsJvQOZFM#pR{tNMjB{Rn>LRS9wV|=Q{ z-M<#e-sjh?M5~n4ZH@>PTPN#6ZfC< zI3l$p;mya1ycx!gmC^8^V&vU9_q=HzD{NA|zJKFvoQoT(TSIT06X$(!Zy%`p2_7mN zre&_8;L-GL9@}SUFVupN+OPzfUI&%7qYz+_UaIuyKw-bMKkXSNdk>kJ!+8a)GHWbW z_zP3X@%`zTOZrFDid!9o|@kDA$} zM>PW~li0SWI8$*+3B!`9pg8>R1yG0oqKG9g+8BWkwMVGgNa5u=WaiYist2b6OwQvB zS0(W!CGK3z11gmo5JTi$v`6UM{G-yn+0`NEELrkI3<`gkSsV%e&UDU_KRg95ZLzeP z_~l`j845_OJNf`Rm2`b^!H&ozn8%PZ*`P#%Y>=6l2QN?k!;RVnWifH4g4k`M-ZaSn zY6`mlQAgW~{~+@GC@SFMC-1Ji2(TdxyaSJp_no>67eAVu2Ngg7L={L)vg~#{>_26b zhc13yO*_~;}p>#6kvs&7r^jME**)ThD)~ttG z3TJ)N-a^>nbdc|7^30kPj!VV4+J7CTwHFU`RQ$>?p3u)aOJ9n3OW*Jw8FBd$ofe;y zUhNSb?uCwIFm_@re8K$Up9`fkIYI+NnPpGj!S?o^HtR zB0a_5ukU5Oz221Tv+^)an_YLz%X%a>sgqPGJ@im!gDVO!htYNWEwo|Gj;Dk*lO)=s z=)Z1Yi)>A4t9ne%kz(aNEVVm|oBjSBpW8g`pDqzMn37k(UTUGU^t)FO1HR`otH8^U24jKW|}cas;`8@{`CSXUYJWbxZs-+b{Yj}(+w9x?obGFRxjMG z;_dT-^c!=9F2z_IA-Ee0q?=&ZwV|D5(Psb)$HX>?$)m}sPz5hw zpSdwWWyP}FlTC*0CmG5AmcS&DO#Lb|MxiGIW->-$AR|gSc4s^y&Ve|Lg}g(S&WJ%B zc0gvMV!y{a6gnZ|$CPFaF~)v7V6RAP+`U3vv@XxFJiu#q>}k=OAyW2!8i3ptiyM99 zB^Cc&=_wr`PZR?&0gxw)30DBPGODXkk@f_Qm{Cpo_hgF~BKOAPH+=@oYUM<@;X6!j zjO^+9Fv$#F{7sfz2*zA#jJ29^Nf1X9fE)J%Ny)cY_%r%n>}uaXu&WJxV26XH%+dp5 zSCZoFC7RosklrZWQ?o$b$_o2rJSXYLq%xb4X2$Wg$*jl)m}}*%Wk5LXSR~T8K*)Yb zkNu&uo#>W2SS=s`R%0?etG6Dv#7vD8(qfL0Uq~6gp*5}5l^PO;i01)$KQ;PQc`)AV9DYtU>xF09=u|h~{Zizpk`npBu~+93oy4>VlkL1!g>}{2f4NOhdhsGy8-!3^OiW z2Y|=z82s+z!ap0$)c%PbKNnOXc?iqY=OaC49|$=>y2-1QXx+H9=@Lt3S*XwF;kP(+ z(93X&Rfw_T&jaK_jW*Ye388pME*;vrj&y0EIri2Yt*U<;omYd&wNl&^2r7j@|+%k+J5@1xj)P{`)h4 zXC2C44?f|C2S4|iDRbtaOB4b-{x&e;5Z2@096fv>Ca$r{G6#VQd*S;C1&&bS*z&D~ z_r5QlpcMkE)QSg3y{3qPA1Fl;8Ur1=00#Wn0+bvI`?WYn!}u+W zc7%>g26KSkrS}{!0bX%#T8H{AD01O&iuNJYKh)8(dDIsP2XL=7D zzGmPh2q?P#5B31^qRs!(!UX#X&!_iY{n^K5DdNK}P#<=2%Et#(A!Gr`TWtEdSCfqZ z{qtIb`|an$%8j)!*Z)%E1NKLG@Dh|-iKJCM@R{QyMrBU|`FjEZS~=Vk#Pf>>!Vmn7 z#v&))uOCW)(0PpfcOeF#J}TD>A5o>@VB{a__PhU0on0SrODYtQJ7A>5kF@%rHoE!& zkDeWmnE26MN@D|1@m}P{JK!Wfd*L2F|6pVvFg$&Q14?=adbxrAVPb@6c5R@d6Z;@Q z-niLj?SK+=KKQuA4qr4L-h)p6B@77aqr3*7zJv6t6W|l%YK-NXMj=3#@c!uAdN1|l z=av^?`&DxUbZ-<>(?P@cCo-U<3lFhkJpEAq|CyUZIKp>57~`Z5Nu!v6*BR4^6L7Fc z5UhOm<#X_>N0K}D4pQ`Ydg)Qlk9w${wi6Wf z^e!Zo%{Oj{oE?^=eGR2k3i|uAOWBH~=Sr``nHA>ix~^;$|4#M1JywcS_!Qna0=}wK z*>`^g{Nr(lJ9g=Qb|2J&>R$U~gGP-n`jYK<8Qn@CdSP=TJB+BBT(}*toSNj7Gg3e9 zV`y2jf6=D2k_aZz>O2(=dk4i^UpsxO&uF~yZWsN&Ht&!LIvDo$XYDPVlvq2e*C6q^ z(5aD6E4q#5wY;AQvcn-iu^y6A120Y*_1)Fw+U5FumXaDIw@-I3riu1dJGjGw z$nkOu&HIU>V>l8_XI$%Ye12+`GpRXk^~~w3bL9!i%tvZ?0 zXG65akWpf@-hP&Ewg0~4Px>#FT!!oKtBE!!QH#PyTYa$aH}XDTtsyQ}=AA%^b%!w< z?$I0W{ZeS5N)aTU{F~}K9Y(giVHEL`Ntix@#-?!cchN#fj77`CG^B^UBb-~~S9rh8 zQ(2=dm^l={%|?7?M@qFUrL!#sIhgigR{@zq9S1Km`Z6-SD0x4e60YUV5jQ^REffd3 zTw&V(+efJ_PeIJA=EnKAWWL;m^yX}oH9=-RL62m-U?)9&d$~^bHU7GHi00iCef&=0 z8@a!v#2&DUhtsPG*0zGumX+y@2^J1yv5LQ5_Yde|EU9VJsbftPf+m&1)my#I^VuZY z=JN0AHz{V{u-R|gJ-!-SKQomFoiiN$(2%$gw(5c`nwa7n5_Cy%zAjwHXq3YhsN6m; zXi4Jtx>z)CdX!l!(|7*dh5eOE$kE^plh%nt1%rzf+V1c+3VNYRK&`pqC+o>PYqhR& z5%4i~-+6Wpn%0R70ES>Jt8}^XQWFEC7;8`$jCL0wUJEX7ycXcj z;qu8zy{FuxF@&_QIvd|(j-Xvrxu%^pu=0JDi%_k)Z@0T|$4h!z!L%bt60(~Z2+31x zBW8^vd%-+Yoxf8QD#z8in!eEOz2 zg+I9CopU%6!xiR!&EN~Xl3$a2o}W7JO$;xIBv_boHo(fSTs5Vb!fk2P=)HqNTw+%R zs(@0juf43MZLz2b6roTEkl{N!h^@QEDxC+b)c z1>lmE@KFwpyajYw*2gp*H?r-kmZ_rISYrDtzEtC)>y^wCqfP$G39>;Ys|JBpuEX%? zR-`jN+<`eA;hU9cxv4wC^u4b4`^)3u-t=^#_Z$BIOw}`t5CBfqLlmh%-UFEv6{axd zhv|(73g#3KH7%49ZD|t?rdxTvM?X));@I$^G;+-EC*m=w+%reZJ>Oh#5`rDg#CLR_ z>Sb#WXDNYoal$DeE%AR#U$Od<m3?b)pG8L^XrCW^7N}(cHH0D_V0T5*wjWG! z2lidDIZco8?=-z>^^a+KARG4*&-gU$e%)0Zas$PUOP(dg z_2-dTzG(QRr&`5N>s*MW%?dg>3H)$s9!!2ghr{C3b|CxtETqy~prk+i%kmZzZ|*A` znG1TLtfws8?S=$%AFOw*0i&i-HUFav(l*PbzQhx4@7jxIg%d;U$xpBFinpfBP5ekDx$9OKzSB#t0ZWvNpuue% z_v66a-(!*&V1>wW{aDrSp#S5mmeggdZC1pTT<4hu%tym%$rB`A)Clfv5W-6DS0x9k!TsY5KC+kH1DUJnN=- z71sCgxT|io?QmE8uqD)~=Zf#<{e*iioA7)-^i3NvIC;4v<92LI>$*3Qqt^=!W9UWC);mQA zzZW*1s7i`4u2|YO0qz`iVsxT~q4xM!<0Ph#LHgQ^Wxwmi7p?IdKWoh>o7ICUp5>bU zV0=d?8mInXMXGLO^BA8*B3`G11W~CVeQ??^L>``>pof=Hv3R56-Uub5`cAy>$0R!Z ztkoSLicieZ^QuHp3illd9x01f_zgR&y=@+DR1G~hj+z#%QSMjH;u+4nv8Y@M(ObuE zVu{PQlH#H8&7z6py{%4;vUkp;i)aX>ixv1o&SQ=ODeBSX(wUN$CrFr@EWJC=L+m5w zL9-b`pb{FWS^gLVW~c;v0_X&9*X0X|!@(BAv)@ulUI)dTqF73dq=Vd-}E(;GoVH$Tg}&hvWEK3&g#trowpe z1`F}sFM+!tl9CZ>T|#WE$v4i}O{lEv+n#Ad(^g|EHX+Lg^vpUQMBsSBaCoZFF?NFybUo>I}w$}bxuk~J;y z#BHcGjXPG5$ zp)3;7Y$VVEDQN^;T7WDia*A1K-$X&VBZBYP3_m~OLb$RJLzs4HLFD84Do_g?%0mxn zBF5YMGX4`0j+}z&zea5QC!!QN#q{5Zd;dG45uPt2wZNi0v@g`n1nw0bIRzWEK3>=7 zAzNQNKLR~pL_=E(WPh$Zq&&4;2v;Fr#2H5v!=Nyf_+yA&Y=H>{=pkGPapJykplJaF z6+it6q?5z4R)plNNGbSW1X|G{ZrKI2|4EZhMsA+qdolrpI!+qIW~3(spJO1sg@{gO_c1EAm$Ec?Dd zag8dsc5kNFKAo`nbt#qYIR@VHcG8Ev9p#b{!MY>q{3dYf%|8_0sb1`pd)}za+&bpN zHl--X7NtA*R>~hRs(aVs#U@`^LPAS>IMLqnYUrXyQ#EH*%HMdwo#lFN3v{uzElvZC ztoo3rhzypjyhRHu$oeC%X-&-mnDaYYX>r~3{s*Qt@FKk`eiH_5((|jEZdN#P_6Aa4 zYK3}g7m>2I%4CBXbS;j~(Dk)|@5_8?N6aZ4ea1o?-_SzHZ%@f&bj6>v+zH2xV`3$P zS|Ze+5i=5Pe7C2$gjNd?$4(e{_BTOcvJFnb)X%~t67`f3>J8pUh%w!R1&If_M@f?& znIZgX7W}JTR!Yo^>Ha?^`7(dpbMV87R50# zd%C>eho*?ujyQgnP37tGat{0fkQ}CavX(_W+oG!w4fqyg>EQn@%*D^@pkX!SrA$D6 zknByt9~Oe4;OKyc#W%E(@cGFZ_>|u25TsK z_Z&=r?>XW$KkhjK)~QduD__3s&Cv)DQnN1proPovuJd#rK`i}|wlpTK{O%5wW2ibL zS&JMD8hAd^*{DoM8A68MamGZD6vxK0q$F=U1-mbr5}x zUzO%On2RsOsl<}oIz~9hr0*6TGmnYKG-k=4e$8gR@`jG%OXArol29@!+oHo1xdnI3 z0@FO7d?YT&rA$I}&NExD`Jpv!6Nwc+#T6@OPlE6xq^iX9n?fXs5aixt(XYevxKF%& zSQtAdm)|d>=oz=Kzmk#$u#7SD3In$hc$j++6@-UTAI`mNC$k%%-`S~kI4fN>#%xun zs$6}MBGRPq&H?wDLIbaSysDSc=O!>o1U%*2KEzISprTXfpoHu_K(-0Bxw%A;vy zKnEblC7I~%KTI}~ZXSixpHR?FU-?cr`3VjNQ)8r5GYEjQ@1SE1ss}xxg$G*6AkEh3{r|aG2aqCRa>&x!- z<|x_mr<$|r3hQ<6oOicszT>w^>-9GGt8G5|3cl86ulL8p#aup%u?){^IwQ}FD_-Cr zq%ls32jQUiyOT*a-S^W);KrV`>Xzhci}ALMNG&Nbr{S34%YjN+v9Vbqu8sx zC3@vU5#=Ks@NrxD{e=shB*(~89p*=~F=9=jRfv0wq30Wmv}UDx1DWCUw@2dL#=-Z; z>*c6Y*}X#%u9-aWIew|hJu9o@da;J4@QEZ@)nj6Bnm zO)2+&bdY{uS(^!%++2^h&&#^!TU!hMjiHDptYqsFsc_7qeEp~aGt7!H%>!`vw5XgP z!Fa!XGCK)B>ukUXI?beWigLE5YkMDdu4oQg1uxleT7SQJj5_pQ-75)tRXxLM^L#xY z*L|%x6Ig$J!+^WaeY<&?O{hFKe&v9SYSQ`yiGL)H}6;IXun=Ojb^sLM)rM|8q&X7_1ZvrA8iJHQ(@)p zcD>m!-u`yi_&o01en|{Z>e=+Bg2dgiJE%6l6 zVD`GO*5Cg2%7?$=(eg%b&8|?9@8RwKJZwF$)2DcQ6!P=|U^ZoD_7vV5vCHe&&e!&43 z$LCD^WA%bymyXp{NOo6f+JN?8 z2upT7`~rF=NakK#j&9%4XWo{3Gln~D6&^o#zFDFiu0nK!b>eiD65`3I2ISjM3+Yy z>5Z%AZiRr{LcOMwBzjYegceIR)q=R{9c-W}QazqZQli^T7-uLwZQ+fp zY2(j*$zhJ=mRja3ZPd}8#6-t-2+83qxUne(N(>zhl?cV8M91+|$>B8(4fM}_Q+C>H z1@3BZEWWRm{KGxjS{eliLsQk~3SCXLI88ylzqA~Ri7RVqN=|5L?b|TsreYK95F{mc zu)P~SuVTFrM)-8$w^_<7xC>+E+YZL3zi7FFkp@u9=CKY8p-@2mYt<6fYTbHm<4--# zVK6;ZJ)SG$SIYhFK7#MKTeL=;)wpR` z-6kN@9z41qu9C6qnB~=gx(ixzPh8RIva9~~=JBlOqmsecr|YU>46T~M2&V2jgz3F& zTC36e^~>0hy@{G@6OXpc*ros3Pz}_%0dod0F?wK{Taba&<8kn4?XAHn))7#AR;z4* zY=5;nTGcD+nw*}{aXrIU$)G%MxkB|;_GBm&pq54Q==8lFx~@`l1*(%kE*HT2>iJ|n zKE$U4KWCQn{hJEPu>zszF8w^rHa?pvOBJOm%AsF%DrQrBWjPt^YWEgD9k!Nqyz-q2 z3P)yR>W}=DZZk08pfN1A-G-@Ow79H@RfgfRrAKgtRfZ6PG+5gx!zOiZB@665OU#JF zr-xTE>=_fJb0ElJeJF(JIym2HS~{ZD$iGs_(EMXKT763k{Rk#e(zy?_WlNXdq=7v- zC=PLP+##k8G)81QgaDTQi!i#*kKj@u>0*h=k8>^;+vwHxtkr#3 zxkToF85dP~Qp5-?jdvEElOZsd@rx$)rB}NMrny|%H%iYJMVEtuRM&)67xDd7njjWJ zO&X1Ecq(C-j{s9$uPvb#Q+JGq4rMn2E`_n~Ph9M;@)5yVjELR4qYfUdsS;y2uc z3>@HGl(RJq`Nz(L=GMgK00ye+L@FE}cuPYbD}I$BE@H`(Xm_BM2ar24Xk3I7SA5ir zi((*WfO4-1s>J*tFyEEmlK7klsUC!^e(2|0>Y0SBVu<^<6EFvtRuAD-+wr2Pm&UvE zqkpratG6%jZXr~GuGQkm{7eUQ ztq&{~dy*EEXt{l`7Goc|s$*cZ79$v8QuyWIN5Vz`t{qNmf+U~~aBaD>CCkCT(_zc{ zYXNQ02(*FShYcG4WrG1ntGEwt8~<{PYsVt~Q9Hb9e7s59>++fIv{t|);Q+ALqN$-yIFZu^Xo>zfMw zLLiBmIidMj0kUKw5_lMqRC90q-XLxCB%^JD*|5nidtL&vezyemx={i$Vz$KRDsdw= zwN@c+C;nSZ2<4gn-B)Yw%)ufp)Ox?bPmEnkil!j>sYCXJjzjWW;mFsk*sxwJ`ZES; z^4o^;SanL92UrK+ibZ(mqQ)u)=ao4o_LQI%TA|z3V03BCTOSPO^JB%bQRSji6^_gQ-<0f&&+P;^_1%P(q+*7%tLPYtqv31phiQ~ptde-pl{=zc ze{Vf&KZ!w?6k}qj++q=FC?kQC7h@)=s+7zwLpp}Gk|!Wfr%-(RMv!mXT}Pc$G5oyg zAc3H9kWt8-2U3R}+Fdy-_oJswF)|U+H_L$N({K)kBkwUSk_xkynn0r4N@utO;+#I< zB*jjFlRQZYPH&24u)9AX(Ls{R71bZ|YM6ww2&uqoI){30JwJgl9$N9<d=A+;a2lR z6zK#PD8(cRM&dLQJ`f12ofC|pXhQxhDZn};C>61qO>!#HIVwv8X0Kq=+b!lV-kT6B zCV;uISPV>kIj5v+z3!jXEpA6N;`wGvDy5T9VEkhmg7LABk%{3J>sT5_1l6`P$_$V` z!KDO!Ya=X(YQ-#i#L<)5mLo3Z6{>|PAp-GNX84;h^mPyBjKKxf$hoMeI~ zb1Rh)!#4}P?8K4Hk2%QrkX;qY&=sw%1vHI6%h@I;x?X=UqkC&jh@;n?p$Y(bY??oh=#p32BwunB1 zBaQN{baMYR>gA}3!B zTiN+4Xf9DeOllVrdKgnJCWao+<^DjIcL5!*r&8kR@46R`r)=!+IeHfQi;EcJ6A_$^ zaqVAg%&<6S1yusA&7Yh*o)wA>z0E_@H~FTSoI8CBfk@9 z5BOR7kW}ehx1&n!LV;=B)&1V6V>oJO-1jW2tD_W2V(((CdSG34eycXU5Hi3u2qau? z*-KQ1Ghf+pr0I@iFwHBl3G5|vlD1qW`3ZP}{_C*8m7d`T zT4-!EuNTA=!{YA=q7KijstoFIiVQfezOe+M?_1lcjH6mP%;gZhj0%x08xc>0+E{aD zRODJCIr$rOSY`Xv5o17aAu>DHqJ1W?J+%9iab_QR|IHUHB67e_be*60+>)W36&p7N zD*gEEXHi67cJF=+(>QOG4h#>_C=pW!o!y1I=`KZ~v4x_<3J8!9t$v~zKeHH&^i2R? zW=ss-qSh|l^A709(M?DO#at=0aqU;LoY}fev?S`*Hy-E(i5XkU?}=F=h#~B~O>B9w zXPE*_W^xdj&49=08563(8Hjn-48H$li%x<8O$4Rn2h2973OGw3f*eoamuNq#V6Jsm z%zZtk>eq-!TK}=#oGQ~qP7@2HK)C#Gc}acIz>blt6bS4X5mS@DcjPCalO<=^A{R^g zK-F0aq~Ic^e_=9Lpqc0SB$>-?bmaHWiO`ngGe0)ViNk` z`%)OhWO6f3xp8nGN>mnqE-^*+B-_M*ds_CSZM;;CctX6~((0%JR0M5CZ1zq302H|{ zO%Wot(E}s`{v-uYv;-bx#A!yX1E~c-nOK%dC4v$~Xxkx6aJ!?0^fB(r&n)!JZY#9! z*9z%wcJ*3Eu{?9P_x>XAId`4$I~6nDHggJBIH6&1E13$Q-Aw9LJDpOC#Y`R=yN(?{ z!t7O)zoK0>`n9KuSVhoz!Nwmu} zp(40P`3;78CfIR*PY!rc_-zTL98Z7Hy(3JCkZ}8Hf+BUZU6YnSm*#lwZ7x`f>0QJe ztx{iiXk`+|A%m&+{}J{TP;oWOx;O;a06_!6JrLX>1b26L4KTPvaMz$AxVt+92<|X= z@ZiB6-iG}5-1F`|Z@snHv%3bXs{Ts5cTZS|T4a&gmfK%=)FB+-UH`(TqsI7@q`jDcHoxJiFH%`qDaNAU|%i= z7$aMpRUTlB1cEu{U!G7KAR?FSlS?--vk0zvSR^**^5);hstnS>xZwq=;8FBAt!x0Ew0 zvM9QkHOLyULUzCk31)8Htj}|qplQAQ`h2Tc&^zd1{f8kpnGQetTMz4?&aoPAgnp8* zoWSTB|4m@M*~ZW}qstyuBVm@q3gKt-g|lNuIXg#q@@dFya0kS1@Jy1Rgtj46 zzh06Fv2Qa5@8egW{2-?W|Hd;lKSyC-_<|o+H4hNfqYn~wfa9>XW*J7#Gcb+$@|6O| zD2HwM&!5;xoHrl3B76^U6wyv1_OhPFI!Y?)Hu`bi9Pn&FA4qJ%f zu$bEos97y2)pQ4Vo**b9pTDW5GOx6lt-T45mxZNHZ zZ>!m~=(()sf{lb65w@b$++FTvMdHn(yZ$HK$b)9vLtBAOCRE3p&(<%%8*l@^`T)nn;M)F<;@(Cc1 ztbLP}sh%~%{hH3CBqZoLUSEc?GR|L@i>lu|(t_ab3l}Z;&^C$KW*}Q^zSM}6J`wUP zDl=@kQ7?{)v0UDcRn;h@w>+L5SbvP4Tb!-NdfbmDd3-z|xa~OFn5xO{9Zg~#TfBll z;b_B^qOE_72eA|Lmp|p|D-YBxtL=AyxClllFM_J>8`~eXNQh*bc9Rq;o>J0ns3~&y zZ!3W8sOpiNOUuo?T&nd^L>I3m!L;=0jUJvxIEY zyS*2f_pJ7K(gbV7%o=#A(zCDrV(l}|xBZ?C*{Mo?-XqcR+dtuy2N|Vkkpos`Xaxs0 z`#swTo)BXKcW1brjbHVp@6C$M; zGT*kXB=cLbc{b{n9v|TtpwvlJoj=b7tCqA~7*v#@<&7znqtS?Kkd*IDobGfqZLQpn zlQ7ovBTMJrSpT|3XO6AM2`)pMXvmo=jhqcW@g-^CFWvU5=FiR0_&H{&WMxjfJ;3(F z**c0^#qTs+pqy}WCA8=%3Cz_vOICRUsu#z1Gk%6t!g4gN;Q|p0exlqPCyCzK;7QNH zp8kvM1Q$BDgp0S|`bwYp3)>?zC_|svFB7uw@4nr#U;2HOJ)^2(5x|++3N-W*PntR% z*G_iz3Tch>q8U*qVQ-Io0AIXiHcqRl7|}DiNh=Qq8>gm@6%8GvesJDr73~;Q#ei@w z!AovdE#cckedC-ruB@2skG)r(uOzgr%@hrMdI-xN+~gE*6sa@hngviVI8Wd<1CkaJ zpj|smmu>qA>nxnZDsZF{`8P)?Cvx|FD`!y2!%G7Q=Qiix(-+enQxN$~Z!nxW7!+sH z-ELG=B~_A@BbpV92YXnZIZkJSBr{W+#rZ7vikV^xO2&QsJO||!)x7-fJKq)GD9J28 zS8RK6f_2aCC!g^Y>L!mZpgEE$Mj)>FXN=qQ7Sjh3LkUYu{sKlUm)YsEF?5B7Fo;5} z-p1)V%|iv390fH^Y6@o>@$4g71)S-Ti_^k=G~689UrHkz2#UD&MZoka;CjLHjVy#T z1GD#O*^-!gI`7aJ-8pCeZQ=g4W|0x{-a@--SXB`~%xMM7>Ws~CqmYU&zt-E&Kd(cb zoNLZCoK9?4CFWODYu^$X$dPYYo|9BdyB+oL)_&6Z-MmA-rTX;x))n$>t6>#w7ZA$k zMX0p@5^D7BMX2Lefuv@j_MhH5#v(C%dKRjDM|b9Pa0j#67W8zPq4u6;*=1qNOd;Ke z(zs^qTzQv^8pOSAcem+_;BW;F`MT{`$RZ?j&Bd^u!j=cbay`*y*Uso1+Ye~idy`@x zLYgNIfOU4|N+&LY={l84Y$GL?($sdIDYY(Hm5HqHxj$~vjBc^S(_Z6PkMdSHZwa6G z#vv-GebEB~Mzip}W6`EU;bOUeUP+lN(}Vl`*#@`s+#v-`gV-{PQpdL32WJ-@S@oip zY^sAn5l0=vz1K14p4UvkF@1 zUgxw;)v&GP(1Dny=`$uL-w*YC+8cC3q_c zO0H?2m6>xp;gcLD08FtH^kRx^L)b`44IlMeXkhCJXexCSS@tCT7|=+H==40kKhG>< zWnTD(zI+2`xsr>QGHv2_#pG939ATC0AAzpJH%7h&dE(T4Jf()xY9ptV136c%1 zfm1kNTj{Ju@~C`#3i^s^uvg#cz>!DbLcZK6MJuMW+qbnw?z}~ylE91Tyg1Y7RF^?8 z%@DOetwWM1nO8V%Lc0|Cy;~+$N0z!!YK$Qvc$>R#nxW)Cp2MuBaA=T|&)M(oS)s@1 zt2ZUKN@jz2SGe1^$QaHg2)@lK5mGuOGsMngANC|S%5oWDX{L23a{QZ{bcvlG)(odn zN*e)r_MpU;fUeM9X3n(9d$99X`tjyQH5c)pjY6#v=%D8F2rAKKa}dHF@VOR|Cd+v+ zj%6(lh5PC*O0iK-pNqqUbe5W1EUJ#Shlf_3^PF8IdJE~wT6jHk%dscvo}nq_vTNyK z{eMlA1c)QdnB#v ziLshI$J|g(xqx;=v!5MDG`YA=XWgPIq1bXiwewd~)jV6?U;PRVserZZ;>-QxS3KJZ zhIXW0Q92W4F$LiyC#vt?@~;-r!T};IT;AAfdbV?&3G3{hy#OzZ=^1!l?UKYn&C<7b zH{>|Z@g?Uk>(Wu&-`scP?Ou5e!Sww8k@}^Uu~8+k zsL@npA(TqPK_hXXw^0QO_y6Fjny-VB?@&$gvu9EDo|%8%2;=TPE0Eo<{`8-A z!i;N;x4R|lZd~!2WvcaSRXKT8Hdf54MqonTI6>NVCV?inB$|M%%R(9ZqwgN=|Hxet_vF?+HH`Os*o9ih&$@MX0B^CajgmXIx z4%$JaoaMk+OUA{aG_<;K4vMfOpB}NsKD}i7@eoYXaJtPtGwNxg(=IAVSa9Qae~6c; zrSRXTqrh2S5O7J2OFbM$^{T(B)qmtGDP}22$reIr<@bu4_!%ocWkNNt+yp7VH6HwW zhQ88tx2`HSQ-&hEs63YNU^Bw2=uML7MCrvgSFt<9qLAyl+nE`(r#p{}dCRZg(cOlH zq5o)sBp66a^hz6~GZF<}QAStk$kKk39+OB2p5=yBE~mA#v7?ooZUp+M0!A4|(vh=q z+%AHTE)GT86+TQkeuR48T9$d;+%g}xg_*{e-GR&Y0QdK(#cw31>}u;`xeBgc%gyfg zyxiYBf>IinY61E6Tw3e}91e`+Jso5TS3F-GA61$8T-`jT_mLAk4*f>@;Ui+lpbhx%y6^w>S- z8;xPvk-=9a>f{GD{hBLBKCY`iWiRx;YAiuwJ-p(++ukR5fOR2v1m{oLlnPJh91v7F zyuL~*=@;ct;~Q*`Y(AXpz;fs3*yA~yxXE63+VDOj)ckbm>*_tC5-sXd7m!(^LL zhUd}`_g)7SMVE3`J>=9TT?|Tb4ATm==M}G|S{Hv?E$slVvufSg@-7M-tqSouQs8L~ zIp$awb{I%c-c1a%kOvfA9KspZW*a?_Ho=}N_lH% zUujg3YRQLTj$BA?P$p<^#_r?jlQzsE>GV@Ntn^|E^U?ky^11Y(%LNU{%C8U+|K9O+ zRm-6HrK7`Y<|l~LFb9(W?&R5Ty}*6k&E0mnFRBq-f#mO+g;H3_PLs%wV$1M9YMs#- zXSeltiQ0;eM1fAWxyivhTV%CszV;ezxUUael6S(F@FjSD-G)qHfl{?W2` zf|DOm<2qMfLwWnWqDO~;vw=GNUopcEE54By=@h_bj7AfZM9n3 za=>kchMU|W@;UG#*njGa`judu&y~GAb9UG4!3VdlGn47-q6&Nxe12_fl~%e_3h*4t zfyw#LpBh0fe*Jc|sGCIkr&bK;TSU!T0h9)(rC59J=h8tT;~5b-X~U6F%JLX zJzDr5-q{uY@-Fr--pf4+!mj|{TaBVPB3&*t)>m0e@IqWvlskD!9&Y(Q-p=41=kg72 zWvm{5UoyPV?#MBDgC67JD^gJ>nBejogpeA@axBaBtn~S)V#`0H?28H!BRu`q4Z3MA z%p623bt#ASH7@jLvZ;r_T8+!3b$<`l%79uD&DVq-riB^M4VnBE)lckj7rMbdghUr< zy9S1=wDe!>eITx)UqpOX%EX%cfqziv^W+oEPs<&$x^@1b;)!Ru+;<(?&^HtC_@6}; zO|z}cn1#Bj^$NC@e1}@mIGj7C$;=GDEnmBm?pVb?hEiB&BPBhCP|~sTqdp#gfK&Q( z+hLaZc?ss2(3wzW=2u2pR1RL6%Lbt$350sZ2v15H>apgu!=fTlL*iZ|1a{tMn zP?u8^14+stm&2n*PmDqW2;;Ec7910!z(Jnv=*6UpGkUjAX%LEvT|AgS|51272#vuAKYnI^Czewj&B-vVmo+Pk8z(8uvye6?$opP>pGt578Yn0?wuu(b*We35Wp)6?M25Ayzu@@vy03LlB(iZcXxISx1g(5Tmi{pKDi!2G1B8sUJb3vghY2cB*EP zYgehfMF1C*{=<7%PMI>H##mZmhS?J#eq(#zB*1)m#S8Oes_&l?Q0tXYpJ!v``!m~V z4bN-?1ShVw%+w^L)}(UwcG>bltz>lSL9UyXL{KMX50mTlIV-t~fOfH4F^*P?8=Vfs zUO*yQ7lc-o2q{jkpH2U;7LZ^WE;@0Uz%E7&YXN9dfUy2ao+x!EUHO4u-i;URJK@;X zmnFH_dsMark8F*-`Gl>JMGm8dF2mQdh8r#Y#g{K2q3J?zxXbnj)Kn=A@GRm#1EF-i5F zRLZqs1vNouYlBTg7G^nBIu$R!PhcJOgM@_60zhIxhg4 zlW2yR{zUQ7zsis<^F|J~h>m@mYd%px?X|$iBfzA6BiX3_nFNuzzmq@)OhOb!`sTL1 zSg$wMho5>?CuZ}Y*kw^ZXsG%jJ{}knH`I-F-n5L-nch5h(Qzx4-qz$|!A~5fnaStfnagnzXFW zHPnw+#UkeSmyryv!&@s7H-6njSI-BpMgM+)h$+Cca%KlX%~}Nk zs-E^IeAs=Bs+OHq&B5iBa>Y~X(8Vj!xl`z-~^Yd5C4ppc@4V=rP_Tf?_LJ+@Dl z%(MZF*8|W!>T7Tq477D`&V3Onj`gs1wbC#}6Dm;Wb&9QHg3QaQA?mAFh{3=%H|x@b zJBUS=!MLU1bcL!aQIyjzP~j+se;J}srz-4?eo4tz8JJgN05vi32jA#xh+&wVr^rKJ zLumQLh&pH?npT2a+4?@rp8f~97t9m{ep!S_JEY0RBe0Gt2wc~${2(I*;5{==XP0JP zLhc1D?vl@7DauwprPjBaOUT`IxAiL%XYN$x9n3;h1lHXscs?q`?T^2poZ29GI}A#n zZvW7aVTZM=PqGQEl4yf+!0Tr=R*A$k;8=EMxP&YJ%gZ>|@m9L2#t~UkgnFd=F~r10 z zqS~a5uX4+i60A;h1zB(O?p+famy;oU=$p-eLkH(5^#6i{mJS1&b*8s*@ZP6&Vl#cD z19Bq^QZU4gxRDzvm^eq@=n;kJA2jm{_t^N3utx)EX7A?}c3=dj=I24zzdrj}&K3=L zLgVMCG(yhn36sVa4Kze6A&(Gk0_uy1cf+xvZM;s{1gfZfN)O0+Oi2c^YGoFHzKrsC zpcrgabKZ;_W^FR~nlVz_9PWsWt0gIf|b=dfi+!mLsIuU8U8AjyUEFAh~i{jLM zU!Dn0T#$_8)R*Pew=cv8z-B0FQO-$PXu%B)mEv>JPR}vmb z1sSFV7-!6QKjiOfkQN^Qfv55S(y#+`o>#O_;?NP+pqyL3bL@7MJ0=H)kA0QTi7%Mz z3+A3IG^jp1(9jwn;w~0i1DbX_%X{UknNTQrET}aUS-=t^uh2*gs8A??ZVE`xlzLa@ zqXbZQ95m+UsxeTstQU;fb&O@Pfl+{zUH?-mCWyL=aqhLoeD?RaB2k&_bnhF3j6ZiC z>ho`>27-wi1P++hB=kPQR+fxm_LPVD>8kD zk&yEHJy@O{#c}}TyHKF0y1>3A-wYcDz|a7~xQ+c--vx1sTd`EUZm1C?p=aVR|fw$*=232+@)<}z>DnCXxb@VYz}9BXUj2f53l138^XLkE;?MI1Cr z^k9cBiHbL}m&5jP0v45v&Rj*lL^QJCY?u~pEn|~lN!fhNk;G*$E7_Rc&7P<<^2?N+ z+=}l|V4!|50P2TIpnd=Y^@AOC=0V_XIV8xtgB2V}b)g0-lzxZ8Tw85LjUJ>U68m2m zI0P03c9d+GWriLFsoi6Vm8C;P*RiS*y z0+3PLVt4iGeU|5fL&gu{_$&Y!g3rh}EXE4~kRkY7xe@iUev@DQFg|+hBE}==2WXn{ zP!L{H%8&Z+%^u#=QNjkL`Hs1~`7p}D{2T1BDhq&^wK@Y3A=2_1Ww3qv+d&?jiA1kC z)dy-`&+i#aDh0-h=2s@f2`kvy2{f+{8xix=bf`VHg$J_O769L?JRW6CeIWmR*_;W| zJa|t&A5&&wxd9#as~rDfqmf}WzQQdn?Ki+dqyP>=6mSsVo*hKg`VCd#@f-7zQz-KQG%NsUumI3d3!q`)xtgTTOz^)g_j^Xe0%SEd zPyvI!G34b5CV)_!BP?779k6O018LZ{;SQ}05PQMT#D1L{yyH~1PB^oP9->mN=4o$S z*n}*ilIyi-i)97TltqO9&Y%On%I3=sfRcxs_>!~Qi9eUS^G64NpBBT?Z?3sFf9QP# z9#qMUu$OKh4c7`L3!L7pSC^i=F7Uw{v;si)DD7M`%B^p6HC$#@mITSg-F9h! zgpRH&lg8zg3OJ}^18CjoCH`#cLCvd>%y|cYT^y+C0@zN4{o|hS3q=F1^s{Odf-BWLcbb#7%tX83<{Q zas_9nBY9>ftE@QwiNHT}8C-1$fd4A@D7DoTU>eQk`h|9|Kqn)M&n#ZoN}c$pPe_Fk z`ofF?|6xKZS2@=nvDukqctAg|-Ggw!ZtfAetTLfE&v@6ABB^*w5}C+ChSL(vAt5{( z0l_6sFX+z;Lc3~o)3^^)xASFMM8X58%rc31J$8Qq;cGzx9t|zaoT|Z+_Um3&S8SMh zEh`1D2>lvNzf5geTHa(=1C`jRooiE?hGe+)nVkNoPIRZFw;wpM20(s!4OWCM8z(nG;l za{ssWi@Sos%nS3F#Lw0*?)oq5e>Ik!@aG^e(CpdzDR^J3zoZDTet30PwuP^+GqbVh ze;;R%GzPseP0xF$$gDeQ`}^5{RsVVRUxh)z0LRPf-!G&nnRfWi;gNIXcx+kcjey?` zLo`>*qR7|5fu1M_#%6VT9XYPAiT7II7H%F!ZPR^&g5h9tiOkn5XwdU?M2L(QGJrnK zAt4f4WYdXMzRg-TUK%JW$n0;pt+lH9Lnw(fCZy?_q#W`RZsls@(>?(E$_^n=qQ!WW zdRPd04M=d+tKV=_P`3&U#c;*%mn!D&pin6#-0!V6Rb20keeH5*P}cw4(E~BO$rLGC;}S<1dv*+# z0KP?eZoJ(A|HaeUlQS`T{s%eFzwaB-)gR>I;GIrh-kW%_7MmAj1V1BV$Qf!Hru3BY zutU3EznTJ#Bb2iWxoXj_W18UjF*>f`*wj*NBm20 zaNKa+GF!0n?$Te2G@n~v<4PdT3^@M->^eNm4Gs=ATR@5aaeJaTkUNfwegc5`Bd^Hr zHx~2$kGui2>s-tja)8sdo!iRw2fbT22*x~=$3QD-m1?OHjR##ZtP5?&%keO>ap{x& zKTtvTU#KvL4{PJRr*J~fJN=1%d@`-1^k65 zkMfTm+T%%E`sdgX?)nlNkYrF(Ld**PV{8Zs{#R@u1M~{ShLHcES5ZK(Ky1JOoLsG= zDDS^wL&%Oiz<}ZpU{7RiJQ*=D|AcIqYr->jF`lvegEay58M{AN3&}E}u}*+o@ersX zY0W>85re2FP;pKw2U}_hq}VK6R>_Es`EP1BgyW$p*YS%BeL)u*h6^ez=!ef^pbgCv zMzs!j;J>ZFaRSH;?epc!oq$?i1CjvHlHI~=Sm>U48T5lnfZ|5 zV8F)6h@X)v_ya&H_6c%c0Dx576XfEMolemgq@Do*q?Q~5jVHl8ILuXjOJ^bSC2_$( zdr4ff2OzOdkpE-if_3uWiOUZWXsAh4>=PhGoP16Z51(7jps0}GzNK#&4C^nxAmm@Z z0ON#E5;$-3AjqTYe=0PkZ0GC~?LOt)?oI=66k7TW&&AQ_sl4|;7!&<~+`QiszT2-! z`IIUW6y5Ti%V^UAxeU>sqCujI1xJ$kO?=!UyE&Q(HOO!}Pe2x-2v_PvFq_?d&pTd~1VaIZ9~L!uRA= z1Dl=zyV_JV2o3=mW%!!C*Vy7)kfG45-Pl^{_vX>Z(^;@-#M$y~Qr@G^0u5>iFU+tY z96patpTV$G@~yqc0{5IJXW3QJ1s)0qeiGHGs1_SxvOMo+42X*8Iq}N-n|KwygtffC ziI>fS$;j`2txR^fJmjpldtGhz`{?TWxVt<&o=w$!@&Ti}tvHipW%7-EHA@~8YE}k1 z(4fh@?jEWIiR7@jqI@DnjIHG1$X!JsWnXYe9;Ed8mted9OaD79%C1~jf;`4}UJDLX zy^xMY*8dUUJBt4eaH*i@DDqqJe*iog@fqNYdBV>CPab@6ZOZ0X7X?`r6#{zg5BHbz zPcP?LKs+C6AsW^7e5Qt|55*>Q=|@re7Np5|c)17vnf%4xW{pYgu8Ibg;s&>#cdXk& zn1%TUcx!!1is2O8XO2RJHLkQJ%|E)ou9LV>-U;F|z0Jpf+uNQx-1a49IWJKiC2@(i zH&O8}osPGYc)jq}X}GytyZYWnya0LLERM4M=Q@TTg`#3bY<%zV_w}4nFBNNs!KMdB z&+4WAOz~xc|8(YtT}ttMCNu;@A}Ry~79fDDHItLMiH*tMSC;3~Hip#(Y!{i)+i-si zAT)F6t`j-sd$M0o#_gLzug8n>p_1&Ntd8TV`Mlp= zR(d;?&h*fwv3f;~cFMeUGWm4jcxJKfp@>0@ndI1fPEvGU!6@L}NQ#s=9^uZMH3X}1 z8>-m*eJ&mn8OtpRH=(D28W&&T5AC`x^-t&@BkFeGV>x$xiKb(RI3ci&a8cZ&3C<;J z09ads51qMcM#zGIUDCoCbGVoWe2Y-KfH#na>^#=}iZ!R$> zIplMB)Qp0dtz#9WFWmd@ibqBL{$lTZ7qqdGjzo)ZVqhuy+hMBjkp9?ro6-18)usNa z{9I!pEwpX=%L6+PvR4T=FT!SqJV%d$QfQkVg@ZX{@7GC*oO*1h5lwVJIBXYJ=Fgd9 zWs1c>?3hl-a`d71PV{YL$@cONcn|)>Kg94a=Now0%-osBgBPetLoNH(w3RnVQ{Vp{ zs3i=9nO>VfHDpT&^Ub`&#+)@|3_U}|oU;4_^J;0nq%y^&GG+HqqH zqlCIiN=!`BjD<_O56+TOT_#5y_qh{o@znTu%IJ!)l?@sEN@wFCc7z9-l+S1WFC`*^ zVRi`U&k!2z%3X16Kmq-Ol)Bb$8v!7Re%M;PB8f{NewVN+RXv#e))Kig!w;qCe_ z*Wvvz3FP3p{S0VvYTv|b z{bUiBuBtJP443uwmYn4pEZYc%*wQk08^exLmrZX$GAo8NYzo1NRkp1j1AY73iE~2P zAW&#>gLk-QO^S#NtLu>Q8UWS#T$bagPA=zg=M-EykAek zcWBz}EwE>ee*5Q{G#2F(J_)4uyR5jU3+(oLTY4|v=6@dB_bQRv5Fa?u&wva90_Cqc zJ36^pn>aoj@`0vSbPhYVcg6IRuj?4p*BBIqpO&onxry~Ed0!>HoIBsmz6pt7m8#$K zIj-{ir7ceSwnnMQ?G@f#`tedUO1zwgXr0=yV%(2%TQ6p3lzwl_7}woBpLW-_*z!EW zUdZnf5jtMsN)J=#b9$6CtBUun-6>XrWU@M5y*KXGctsuE7?J|-tO$GJnGG=3?T3=Y znoaRwi`20da_mw?$c5j{IwEfTv=e?Oe6VP`d=_sW$*F-Zd96A*S@)B~N2BkR2oj<^ ztCg=OL(P}c3X@V}vQN?1qCdFrto}4Ajo__;Fp;}*5niVEIeL@2IT?+~=DWb*On(1-}*pCw0&xMH@RiouKBw z7`^te&%v2vTKoVbg&fLqWyE#deLx|iRbt1X7eko<1J!$~fTAE_;9xi`?;GZ71GN|P zDf?&B26$9ZkO7~F?|01N#^?oFqY4`LmT6i*6D>g~boyH7Ot9i6ut~wYHL4CAnCyi0 z=iy^FlsViWCRwWhNvbS0Dwiu1`B38Z&Vc6i$8Ij{;oWzn=3jq=gkdU_%c}`vK|c7G zoZ(F0RWA^3@rp3dZ%o(|eWU4O(~c$YK=#zzbb&5-i*CVSQJNLi+6I5ml=CyBT2UF) z%Jmy{$`A816^=LOlfM*^YzOw&;Ip*8trn+(R8e(f(VrFk`R5wO-5uS1S{L7J_h ztsy>sx6ocKzpIC&sDJgEWXhir#G0#Ea@hnO1UTa8Fd(@g@5%E)bVA{1s}{mlu2BO| zT(;$FRqdd+gs!8`D!Z_1ScbKUX~}|i(jh!(uzu^!I7Le9`@$7ond^+pkw^M&QaONx zw5s+;xFK?qIq!(B#gBxtXf*mTMl&qA{cJ3}OUf|CynSmzA4<{2SmG^Mk@h2}SvozM zdtlc(SZlqzzDBUcz8;le_&ih;_<57xrUwgQDII}3!O_(!#VG_fYW(PRHOJJE{Aly^ zyU}dfq#!!O{3O+2z{IT61W}KlFWUuIG{f2({RvxtMhG8HG0|orNfoXH3@}s%h5Wd3^-V z8onOEX^CRTs~NKW79O*!TlG}-dd(($HT2pX$kRzlevUQtH6u5TlTW)hvNX7vW!R8`2Lr2*qYIDHn?pl-CpBv7S zY<^ga3k2TL>(xTAqGrFTJb6g%mV&;XV~=ROU6ree9=#vfzY^QFo+jYcZ`lFYxQ!9> zj&3`SvD|HM2n=39aCoAS3IONr!&x!Q(s;6VA{rq58JkHdq2u84bQ6WFR5_6KG54-# zsM+C5QMF?h%~>(O*1zIi+#3rHn2$f4M+DssR=`R3RG%KB!MJ)1O9aw{N@*p&R{Yc@ zZto$6kW(9|;6?EM0rx+pL63vzv>%Fb1)B)p0l^|JHU*Wav1GP+|EZynxy{0BG9^s~Nl(b9>%;P+-SToZ zxg&T2!?s(NooS~zw&1bHi;E$Zvz~w{jr48YZ9qA4;wwJPx)gS5dE}r_6@}_69?cXsywKU^=7!4ZKTd7!G zZE|>jH`5<}SHd&fy?eNI8};VN`KF&DF@qsWwt>Qc?iG&&XIvmpoV^<6kwmu_Ka1n+ zNY8Hi#pHlGRYt_c#DF?(hV;SO<*7NPY%JL^_KkS#G4-jAkoWB!9XpzA-*(pkn3oej z4W7#A?3b}Mae9OfHI>oaz(D4B)92~}|56-yvdG-TFO!l+7I|H@)@;F46}W`5vOiBY z0}172e`0I}5-Q44*N;+8xrFAdyqb4%mtxP-{YizLyPk5L;9tf`%U`5F)aT6W^+AVz zbyAAx$4>Qi2EF&tHm{h%Ccuz7st;*66>{ELd;mEuFSk~DdbKCBw_7cz9&u*+aM9it z6IFk(GAEbTX!K~I6E6Wt*8Ok{{*ME0I2Hmo^cp(+AIRB4!{sLEKvRjO#{!)-7r0px zMzKqqq!U)LM7>vxS}-5G;mmk-mGsr#?(4tZrWxg+r@q=Br=7fG&Nv}t&Ui)B`6@3K z;Z>)Gq!GsNWBPgX*Adr_lx|+2N?y;83TTR>g*i8ASnX^litX&c#R**8z{Pu_$e!;# zKcihPP})A}ZD-Tuyfm_vTGlRm#9v{%4CU}}ays>J7^K(8lD2yr$1tv5Z|G)eHMA_9 zJ#yUPacyvM^1012ebfBX((`h^asKhvSWBLe^CJ}vrEJy1JCCLN3zIq!(wYFVmsk1* zzvuObH2UNL^QLoC@TZjQ8aKx_+ZCU7bsxg|?JJ{oPUcRI?xR>PXm(ecQGsz1XF z#+EKYZbg+Y!EQ}$m6xv6%-q%AhL(9-mMk)B93EBAP|}a47+~a&gkfxtRwH1UYXoW} z&_ke{t-6Cb5tzX+Htd`9p-%CNOZzn^o?S^y1@s1ya%jyt_*z&a(YlcueI#dzP#sw# zRPiRr&4IGDo{peS+Y)%sf$ljO&$kZlzrLT11~a;<{Prh!n-M1B-LR9fp2PF&YLD~R z(n3fB`&ukzw@y|C88`yBtVyc1hrsBnE3`66zeWoB7%``@y-mx@hLNM8y!7nx=r&1q zFNcJ&ed)edyQz5ePJmeH(6dfsnZd__19r`n+2g~EGT;NeU3cv`Q@iHVLi4$G$^_Ee z6o{VMG_>2FM4Y|zxHGe4UY{AsJlw4bD~;e<>P6=lTV8G_&aAAJRPF8I+6|_Yv~lqW zC<+)X$Wa9a&%eR6Pdo>BzLDNKf1HWGt8!DDkwW6lUm1Pe(CQicwviKOS2Z zpJcmdIKvR`6)O<|jm;o9W!xW75_GEKnpL8cVISgT>F=CAFMp!HcQTC3#gY=pP`}&# zQRTc2=60~o;H-}Yz8df1*)zKjnjs)L1$=kQlA6S;QA0u1!afW5-V?Md+Fb*A!YAg+xOZ>>iAGms2#}Rkam)aDRVlfE zhuyz=Mmv!6reA;_$FMPMi@c&*Xd|n5Z!~dujidv()vjet0k`xulHb5Ba4qW|xLL1} zVC;`3Dz9Zx05{$>67Ky`x#GE-qNDp-R7_~YLx>0s(vqCg5BjsS4zq6rt@g#OPzvju zOY7jkngljS_(G0wav`6&cszA)KfN8vxx7GAa}l`lS&V)NJF%>ZWAKX9(~}d%LiyDr zfa2;?rSW0$3Asc`&$hWeIFTmBt?>GGXu#NeoY(Fi3RKhlaOQrty7**Nq1m`o5F*~H)(nY*;7={;xq|iPTdv6s-6g+Z8DAjGUQT6!i$7Jee|xmn7ze5Bh7(4kJXCH)9*uFfW5d{AtqTnJVf(;$I z4ZMDBnQtwT@1*Ji`q~Yi?^JmlZ;R&PC{=^x?ZKDLF-<6<=l6tLAUO|dC29$t39%P~ z^APS=ZON~fxBRDUA!J(+Wr1%Hsn~PBx0ggK58AN#eK31^Ie7@7mbE0on{aPvg8 zr;m$F3t=*7xhs?LTq(Fm;V}f7VA{6^)6i=%2^juKZ|CRt_R{2SZ*A&mZtkG*JjEgF zq$A8O%i}?#xV8L9CwzN`xI4z>GnNduJC^(&xZrl1u(UB;w%OwOof2Z2WOPFHAa(^< zTjI`(IC{jQ@?1F`BM`-|lHHeB;sw)OG{p?XZ)Uk@lVP~ze6IMp z@OJrW*JW1&JI7$3@-m&0hN6@S4*{h67)iL9E)$0sl&$*WOp!a^aUJ0+qGpWo({5Qw=?AqwkFL%#K?okL1Tj>7=GSTJ9PAtj?F1p(Mb{?} z5Z4+6{(|qDvc!l;&*P6@k*3$t2u4J>y$xKDUA*Ij-DF+Bi)lq~>E44BVtfq~BT1`i z%!ZQ&{ecPM&-l@|Ox#f`x31U$lFLrFuAcUKk?}KOyy~`3*U_ilEtC^HS8fE z6}J=HhIG$uO^1Pr^Zi8YF9W?r(cf-whrhH%KJ(P5$cuNT^8+l2XhcC3QI^n|K}vqG z7J<$!`5MvV-P_!9mX^;?G48DNM1qUfSLnI7-wDs@abW*(RpT#!FxaWva?en!e)=4^jBg|=tD$uq|{{CcNvW{cC8xZah5 zvFg{-efNtT2kn~x<-XLaUs_-Q;w~EJE*kwL33aYOrTAFJudoB7$>1o=_s3Y11pqhy zm+jH~e{AoJ^Z#pmg)xu5|J(K?g3hsIZ$m%ch6)3(?nf|co3ALnepA0a!xFxo{$Q#W z$A4jpx0`Jvc1t=#1M3dl%3S}k`e%2L#~|kZ=e;=Et^c_Lr8{x|+t(zlyG8|w3{+mW zfpNqiDq@NM4|{JN701)93nvg9f&_Q>;O+zl4IZ4}?(Pyi0S0#un&9pdAh=6#cZcB4 z*OOQ7`ObOYyUtnb-aqbIzco-()q6j?cRf|rRePqU`%|DaGiVTPFb|GD?jjCxkLEuO zJiCO8!Y7vy`Yq9L1d^fdC11tyQs3yXd+)iIWu22E7mK{_RtmptgF=&4S8T__@w-)u zKd)+1$Iw`yH&zc_i2Rf%CNGV{j^P^|;zIix7b>*_YzvggeVWdG`4u&@=NrK;bb&n{ zj~?|zwuIg%vE4Xqx~`r$ZcVx=m{u8`G4lBkb3Th|AL+R%q~MChav62^@ozHfV}?zz zPBCSopgsIN@{cBP!Y5A|=55qT{OTCvd-qJ3M22cU%^+q=XSq`HCesx0h&+(b zIH$*FXE`nL8AkR65obAK@{e&`6IkFo?LgQdA@`;n+icY2GLu#B6sbVOkI;ngvTCI8 zxH8N7Wxg`(sx}2+k8_Go?xh~dHWld7I&b-^Hf3(9zbMWFaV0m+s#3CWWpniK#SA5~ z>!fihroR59$VJlqrfJanJ`=vRI41o9S}DVl(h{9O+^Yz06|DT?H};#Cm7;r}EMaTF z%FsaRRpl3pfZ^Ht5IN{Kw?8}hhQxWkNP*3yK7X9VK>Wmdu^gHD^GyyZT+w+k`wdC5(QyFG14b7?O!8#I%}}sH}37Z)MOlP3!z)-<_dNica*1 zf0B4C6@`9BB50~ zoVq?YNYOe_7Nfhwj9rOt4hxZcRpXE2ARM`(`Bz8vt(HV$_G~;)ug0t?WOg@j-@Mso zMaW_%v{5%=)2DQn11EHBeor69WP*cE7!n1~5<>4gOAu3KIjLj5L(0U@O}hZ6-P{wc zD>Z-9miNUQHI?j5o^7@CcIUAhOM3OVLqf2AWAtVO#1Zv5=Qne+#i|X~ZwBwyjy-2r zSLcWooh&T@T}HjOOgWMICdU=NO{JxKTmtu zr^ykv$ifH^+vtenViZ`yH1T)rSjsl~<7EfVpp;Q-2I4j`!*-fKe3cfoW@%)Js|6VY zud*>!a7amAI|l7q4~b@f^@$6vCT&qf31$M>AULZ(`@keaf2pCepueEOEw zlp}T+Jp}{Er0<;)r!kdT2;*i6nN_*C8cF!7eiS)_q-i2m)x?;`&xjKH%Kg3xg(?_h z)#YT7Xim0h&WRXKwwMG$x~kZBV$)KfL@On+e`T%xZ`QK@i?!J0Tz@CEEkXQOn*6X; zuFl4d3I3HMGLe{?(qG9KN@Zu4&`LqOOK6~kn1mcQnpKx&agjIzf0 zU(Y||X|5UmilJ)#2t!eP=86?i@)26InXhVb;D?BsV_u&OB8sNP$Ij^BX>!beFo^{E z6`hcdR}~F>IZ#Mdb*J$PPJyn<(b!azoB<_6a;Ogxr#O;vFM}UfGr{c`&G-nfZ+HAk@BH&i9AhR+w3 z9D~KAMx;5BmdsK`Z)Zr}H_shiTTU@pii~VbB^g$dHx`{RO@*v!{`Or=aLz!Vj1pdz z;s+GX{uDAKUaLMCg24*dVbLq+-0xrwrq`$03Z5(g;|wO$LnoPtq82l6C&V_;*S(56*T-qMw5I7~lPFOk2zH`G!vz3-&RS-$tnbEQb_ zL$`lIO99TIgFbMC%ImOfi&MGUjmc2g2;_yCmRH>35DDDst;z?d{=R=eukocvsaiw% zBPnuss%n!Rc)oQqMMI_dn)h26XRGgtwrZtX=_>!pP2ZOlF}SJIYX0`n>Eaur@9Tx; zuS7~BqI!njOY5p2-j-RU&xEL*b*tCoT#vP@54yEuQ?@4Yu>JV9UGK`f^1b#_t2X<@ zyS6a8O%==PSE}#pp-QgoqO2v}>3x^S$f-*e4k%K!SxF<)f>%~D7Au_KO0JqZ=C<|r zAM-24$IV%ZY!#+c*V@fLPNwjui>Q2eiVcTp&vvNSxK)Fk_;^`*=RfiJx$bBbtKab} z?UG-dLs77UUX&_=&? zXv}xN%cF&v@nN0Exnj20B{ZqZ7pq(kZ?v)Gwka(_8yP?`OP!>N-^h~hl^BakOd)PHiXbdQ%5YD40w39};74^n@tq$d$wf`{`Jnh!_mu~USkjk!}@ zgo6pYoX|N#S(h6g-#>i73Kq+$xBKRjlI65L@?Dv@E%9|Q9vRbXUlfNG<9^U?)D2(9 za@!{PY`8G%#6ptJD=%<(He(~MI3kXyrX%a;_*oxAvz5#3;f_H?5+ zGH)|Kj@{=lWJc>j1rkh2NQW*8#4w@ z2cu)lLAV=?XbruaZp z;SdqNWy+DE-6nSy*)iPX3<^Kp*9C`r1%=;Uj>d-{dob;+XKFRa3=!dMAbndh4z@*S z`XBj|#O1}*QwcS?&U3aB^Y2@4Eywr8BDbRBc*poUIUhr0BRtVqqlPES8hMM7`o_A@ znxQWP`&N$E@^E8AxuX)Bn@+?@uxlJv6R05>=uj!)jY=%|BOvoC$oQLu``6=drs4B) z{vl-i3H-n!+pdh*+>Ixi)J z1CJ6+)R($^i;H&~>MGx!*K$9)m#HU$n+n_1a(5~1@|8C73ao0WqEa9FRjS*-kuKBt zb%XmgWx5O{sKqh&7PiCqh5|nlWYC`8r}C~Fz=)d9GA7sL8Lp$!rl6n}`-*gJACF}q z4Ya4O?-W)EM_l==P36S={nq{SV zjpoAN4A@O-Da~pV^01EJIIRmx6E{oiVjFTEqeJ-5@jN8ilAf1yV9Nd|I=N6fxg-qz zQ51g6juN&U6%H{g8yV6e>eu;55-J-DVj@)R6saEVY?1^={ zWNeNuG1l2<-PCz`S8vcI8-450@A6T`W1~nsW5$)uL^922G6e$ z{?*syZ+HP07@aHk1|6stfiv>;mB={k4){BxqR56T7PljxU`tb!wcOmCW#=M^D z_I`IZ=v`!&(K5?NKTVv=@L(fyq*7ZEvS1GJR7UR%p}O*H4FMEi=^*T~zOm+E+3PRi zNm}c?rfR?5SsP&Y+x6HdJ6x8iNE8{rH@Q?cN_l^^wxD3{Dp$?DRSvzFp+W?Uw8c`B zEkC1^l+`@R)AQ+s?x6%iK|fWjK5vecV4v#IU=TooPeL zFycdh^uS?W55{}fr(>v8u}OinvxS#So!`q^gB_2qvu&evlAhfP4L%c(_WJ?7p!W|2 z9%3<`(Z%x#kY2#4y+iYej_`gawfp?|Up})`D4_h`UJd{4#h?&QC2UJah7@u!Q2pD*fSc^;e)k_EVfZ(z!hU3m z7$p+iNB?(cl}H>KH%*yWcG(()F1BGo*x1HAbHX1B3&sx{=X43XJ43 z&hVWjRG_N=^@^CwFZ@Xv_Qi``j2ACx{?-xfflX7+CXOm5&d!kCQ_TOV%*teFVH;-f z*??A`*09gG&xqDw%%soY+l#OU)=g+lUXiMFG7PCiC=;mFB4j*VTta_xYLV2KV9~YL z&{1g5&#c<0bgSL5v15&s*c05K!IV>UQ>!#JL{XTVqDxmZs=hN zjq->%DtjX%V>xYyWHEVJ_nfPHKW?KW?F?TmT-AR)y!zm)PV;rM>{Av@ly2K1b6NIW zt918sT{-dw^mM?;74r<^azmxYVT_A*=AfdkL4VHEPgSpp?rm;KL1LIh0UqWZ zXM=@3%^B=7#8PIDt2(k7FC~Jk%>9|DW@f2{r&tw@+|*1jop-s?cUw_A+CtWvjf_vV z_g&D1wj_=`6Q^c^%}M&GG ze)4x$Nv_spym+r!kx)>(zjU``Y_V2fRPTKmRbV2)9Bz#MI$tjsZIX0oz4RHWtWdXA zT7S;m;QlUNU!q2N=AI!uPuujkUz?@<^6lt}AG2S&rppIou@2_JZz1O|A@MCEqAXk(W6nQfFcOVjH? zGd=SCT{G3BN}}!~^>;lY7S^J5Q#|#eh>(GT!pSoxOYc|<^>e}BH@^ZidfgZkr`(OI z1Y&(uow~BllAZ*^nPKrNmT|20Y*;G&ii88nQx+O(<^J4=Gz zO18)pIjP)b3{IZ=HCKAm7T@r{eZK9W87X#azS>&SHU53Dr+$=z9hII!9&Z#WYg=jf z+dz|zD)Qtq{i41eRrh%7_!`M{3;wt{oABFa?bUizbOUK7cT1)~`N*EU$>Y8I<-`<4 z%fQt+y*m=IF%wRUj``V|F(~9xNOfBW?m94y$>mB9X=)9{5P9kC1FLlL<}6``in^MQ z*XeO^TgSN`wvS4DIWO!~y_yHJtMl`*8#z;U{r>TAewr_n)N|gq6UT8M!Rpa8zt~bF zhKy19mD{ly8U3&0OL)hfi~KVSgV&=`?KPJm3bV?djupQ{WEZi3fd|hk`Gq9qHfMv} zXD7QdsIsS%CW4O)MiIh3(oT09WT%$L#hFVewenEC7(%1$<@~>T42{Mdh1QxEYJ&$? zZn@*RELLc3bqGiJMzx%-4trS{1{+`stza?btfskVl?l$Oe%PKk?pbCM4el&9_;~op zY3hBLzC5gT6BaLDw)Oh>{=V&`xj5D2ImKMS5e;;~XPiLP+b>5p`>J%FF!E! zT*`dsnkl&NA|t{d!`$(dd3W`Z9`8Of<>oDa1C7B>K^p#>SsFOHYg?9LyYc>#wA1I_ z$)xz<;6wedgfjTW zHygcfWXt9mdA>BaK9Ovy%*!33?b<@Ee7(#1AVw5Edj9HnYCCd=mtKTPYOPUm*cTcx zb7n0X&%b*fORwElTDzA^&Py!9HEzE?DEEfHWi#tm6`EesDnpCe%58RSvcn7YTcIQ- zQ?hXVMPI%-V+y5X8A>oC3`W-)NYB9JdS2c?P!RUA15Y&fUb#$|zOL5}Bbq*MW{<;4 zS>Q@{|9(8klcD*TnOG8#HI3re{3esFnObYKt&itm{`(6gx|uG^Hi`8KY0I@C3BA{B zC5mYM`+9ZS20g^n)unF|1*J6A&Z=hZw$$?d#z#%kGbkOcPO$xwvs$v%MJRJUM8~S` z5vWimrYj{%wZk!mc2*otGqx|7s9a90)Ti+Z2LyI*GqW;xFY>5=?75!!WDaC;qk^Os z1TDCA$)D}TQZlIymV#QF65WnQhZUF1Q_K|K8n!>j6~hdg&l8~dj{^~;KRPxPFz5Uq znU>i9nwI{Wmj0TS{+gElnwI{Wmi})|OH#5_FtY!nXo&+dEgdFm@=W<)_C8N)^r$6@ z;^kJpv8*z|t1>H!p)?w9Ge!MEw(waEY#d!$$^12yi`ppuV~k9oD6ZAq1bH|Aa`^Rn zs~2;V=Z=o|sK*HJ==J*fL*|N8`b#rXOnA5le|=IYMQA90bG2S5cmq{`MnP1b3XWLL z$|th}(ibm!N+PKl0(oBig#W?ZV#V+h8A{}bfF1nL@Px*f_e7-naI$U{bx-dm$lNYMHzpCJRw)@SeckOr~GMd}!(*d>%OJJn= z%yt#>t-rRGwJkz>+qqLDJ_OS|ot@)xVxDxjC@XPGTk>@V_4ia2M1(uJSZVTNPS2nx zW9b&}K-wG0G`hU-6$25yNq4B{BIzPugvTp6q{g2tx|9WVrp%uu=y~U+O({1cY=w0) zRU^mm-l7M<4Niam6#S!jSXt(AYL(L1_uF9c-T-ecQa$-S`d43p#DwqAz43$D? zQydy@3}FRx_IZ`niWi~|!fcKbms9*Xqq~A>#!^&u(=F{J+q`JvT1*<y>05d=@iIyZR>!2(Ew6ptp z@TElc8lCdqSe$CBo3uf#aAp_6m{~<(-MSU`KJgNEm+m8$pn(Vq19NSKpzML>0L*VXRy|ou)gzQJiiGIdv>9j zC3H$RA7JOB@V$llf<`RU?0Z4u@6Wu!7DSQoz3Cgfg6?P5Ew`hcMX0F&~cB%fr z6S`GycRwZc6oH7{MC#1Vj9q{B1fH<9kG6MO1}V9vfqw3I-#LG2GNHpFcKgQO8cV<+ z!>DFj*Cg^`aeVn~seOOw_2sLhB>FWy(Th()wRZ34P#nLZU@Y({&1tBXa7C~$&QNEI z*Vq&>i4|Wz>@ROWG%a_!Z@>%Z>ExOo>wiTrdK}3w*8zDw$hTg?wwljtU|C4a4NMd( z=QO=aOoEC0d3QclFbqmf+Y(l&!-XnF;=dFI{q8qhRwCl^JK1kT3Vx_853?Df{_)S( zDG7r0$`$MC(Sl&)7{Pln#DWILvZzm1&8HQ&1ax)zT+C~{W{x$+fkR2QU+RF3O7!ZC!U{_${^tfB$L2vUV<+w(rZqD_;X8 z+ZwF-|_+?tiq1J3jwhgb626csqOmE<7z>cEk0 zk=C*)qO1J#8A?+}pT_RmwyG1+>#GB!H~PTqCJX%r>Hkca#Q9g4^jDblSD5rynDkee z^jDble=AHn(;jVA{2zr$Tz?Of1TZ~;Fv-ZV)ad(H6J#R-s)$2bB_jkAivh0whh$eC|`6;PGQq%7cu)K8Ae1h7`+9#cP^T0gt)^p8HQRLU-3&>U|wh`L`C zoSP{~Kz-VcRi4374?+ItQV<~qp{K+2ENTJJ2abK^;aa^m#zh-xamag#C^MQ_&2Iw#npmv2E0!0 zUVLy_@baQdeeZG|y5w1E;%3?@eo;~X_5@W+*#wW*=gV8yis0(XZI}Emj^o6p4eW|2 zsFW&|w?_WZi4gG1MAos%4Um!-TYC`$zol1(YgA%tr~uJm~u|cQgSuD%fI(2oHmS;_18|+M+D)>yM_-UYTN2tccEoS4{S`|l8X;z*A+cun?o=bMjMsCy zB}G*`sGeM6P6po=BD(qrlq8KWcnkzA*R6wiYd?NtclCK|$bsT6V+cREG*tYyzWp(? zSYWC_kbx;P5M;JA`f}P3dW|7JC%Q||HGYEsy~I*uVUm>C(Nq^DQ=N!McSwB5c^q($ zmn?jy%|&m)b-hHtF&#gf!jq3BreiIUpj*dKcW|l$te60*XGWRq9x;ku&Cwbf();CK5$c(?)VeijH4bObB|o$ z=ha>Oe)8DAMz;7m!%GbGqU16dlIy;hM7L~Ga3rG|$!!h~?@FT5*`+$lXl?O$p(ZY+ zGndMZcrn_ z?^P^9-K4^E;K${6LSD6{GO~H!Ox3sZU%ZXbc8T_=Exa;BJL4j;v3XBgRw3@w$i#q@~=t$C0*MPw>9mS4#JK=AsHPp@jZy^l5KB{ zjxlw_hAPH6Q?+P8C#JCa_#wvK4GgXX$!I@UjfU9`(fs)5>og1gq2)+H%y0SF?7S&( zp*CL`K7f$ACM+f_d03uTIm9ch1s^<>EX>71zNr3t?hToZ3UPG4Z1?*qK^Y<&Vq#30 z>13IrB(Npwm)V&#@|jl6U?OfQ$wnCBsS^5%C`{L(fj29(foRHtHaqNQq*P(YQY9%D zvl_61Ye(;h8wFV!y|Z7IbDk~Cv@~~42ZmV`Y$ClB3LA5(9W|XgB!f|`MR%bb5PfXT zonzN-gljD5ZjH`yL#D~KQ6n<<${2>Xt6}(HmX8vjyXrqzWBS1$T;I*|warkHL@I(? z!>{Zb-;20(7}vr6>aI0eV-lGH%thgpfLt(!Gy?pj5#M(dgKt}C+q(A*v!IoYQYW>5 z;0UP&tE+OvmWmP$nnT6yZ|=xDV$B4d5iYvd1)c6Td5M*)ES0L0?z1h0inSv=8u!SH z592rtxhM}y8*f&D*T0RG{^yet_g|CJUz5^blhR+4(qEI(Uz5`Rok>Zm@$2sp3E-o> z>X$FjfSnM)-CT_ftc}FX4J>RSn@_znmdZ@(D>F`@H;IDUMl03aiv6JO3H2{Ctxm8+ z-1?#6>m03rB%(4>NG%IR@D%YB39)foe!C(y8>WxFZ07NMwtK#}^Lsq@dwht}dp^6? zdpbS7VqR&#Ki<)My15p9+)DC$?rMJiy+ZQ5HQ0RO`?#af{;*fr{`8oX^?Z8#{P1wl z>~}x&{E+4Q+?(}u*K6nZw8z};&24(KH6z?|e=hudOY(f_)_#8(<@a=JC;WKF?Drg% z<%j2Yo8|Z1yW)GdbF_C{0wzld31R=KX$tfE&m-#>4O^~e@MP0<*6`{+=}`jHGxX$L%zo@efv6` z+3`7M(U0<)r2o-N;P)lNjpt*NsDJrP`Rc*tl^`wwhdr0MzReivoM@mq97+`tN88UM zueNUBzvt+F*lY2ISnv02ucZC;O@pX^eXnH2)eZazF$q~Tj=(9*s8`2^?r9B7JegqY^F-Zh??J?&Bn(Z;y1S#z?_t#^qgI=*9{;T-PqfLZhRIw7LLA0-F*66R`H627AR%*P9jAW;t(q^H)AOrH}>iZ#d;lA z;v82dMQuL8m8AnpfB)kmNUVDHUwjss`}21!9CNR*`ShmoS^Q5n?L1`BkNi5T?~%sw zIc3q0`Z}xs(d-{t?p~_K=l93LarexdPe_f=?~dD}|5w&p9&kB$(U0m{um4fq@i_sK zt;u3`7S!GKZ1G;gEzYPVzbBY6(x?S@!>OPDu({}1a#%Uc5nb2~Y<67bx?5!;X#fkkTOuz?kO%}Hb7!gr){Vm{ zwEF`Jg?kYFNe_scg|Iz=&zR>Tx0>k~*Io86d;nz*1819ys`U$^ix9wn4)2!wz)uv& zzZA-!5yAg4hMy>re<_teBa8oI9zW6ddz>;VJ`=YlTQ@#;wIrt4815$CiM=du&$juYpp6X%^1=erYRlw)MlV`TPYWQpUfhH$*uMZBj)Jjx|J znI$~?CA`EXyp|=r^(8#`Wjv;3zt!m_ja{(6DX!N_@($Q#8FvS4vz)vQHd)5q27g>m z-U6#G<8FcF3Id&1G&aGa%d;C`-ervqFzfQ{I+$)*V;xLZzzu-cz*x(;YhaY+Y5ruG0<(4aMiu-m`dwAa?Ci4hTh*KuWWbIfq?0{9#q7lAVfcwzzbW_7vS6 zTa+^7uSLbWmG*#4_N}EF7aAHdS>NjMO zoohb93LCVJBu_E9eS%RX3<7KfeG~`lF)qQVyU_hUH*t~V*K28fK=rc@fSP-oiUpe; zQCeq)OFm$=wV+a7qvP;|ElNhL(K;#=ZiRj8ft5Ji07zM<1zh{wPY61uXmi4BESz)% ziCaML)##vS@P+lti8n>A`@d1D&UN1ue`QO{_ZBB3k-^ZHL~2g*>4#Fh&n7t`XiieM zODSG3BN55ERid)L3|Zqu#(iCF zg({9nLE!C?L;_*^k%0@sDyudR~85ICZS}t0qG7;GN992X$|PS-U|N0K1Unvv{{1Obp)5W z!BeNS%KO@=>(dTT7!I|(VJ?sfMS;%Tz~n-nmPqdi>6rig#@%531sCG91YtX**fj%j zpf$ulePfjqI7jbsr})!6VAHr0IFF?K5+F9-fn+oN403SwG5dH25CQF65d**j86rs5 z+%Op|r=(aTqFLa8F)V}WLkQ}^prVuz}(Ed z6p|D@(-d^ZG*Q?{rjjL)I!}gClvKJxkLC-jiYlo9y6|T+WDt9b4O-+p4`sa1Pj;c` zswnp!pfP^31AW_qrP|vL+Jdbb57Is#SRn1g`4f^=Lk3Nz$YDZs1go8lP!8`rV7Gk? zVJ&hHr5!bDe&JM^s|z_)aNj+s>-oy_aanV8l`+M#1!^3!Z=Sbpzq)OxgdLddA=zd` zN<-Do^S)*tneZM54TK^e9qD~X&KiB&6&SR3u9S6i0U9Wb!m9K0#1kS>4T0M`y@>L@ zBj1{YE4(jE0yIqAqhBjL|0rZu7V>#t^&iwo{s!%`e7<1w7AitURVKpx@5NY5VgUQ;Dz(bRimo*(?6D)y4 z8Xm;v#cLxd;u_s&&U3eHdK0G?;4fd2YlotFhN26MQj+_W67euX@wkdv34__X95^Mm zYx)eT@o`=YSgRQ|a0G{LSVj;AwC%IEOpj^pR2EEI-3qg3ay_lY3XxM(De5* z)i&?2k?)4bb}s-KudzpSSt|FcusV7ImcKXHe}qDZP5?|ftg&>Na!LqIsCVWVgbZ6o zz?Ti#3lLC9YAr+k-Sn8I>1;_)aF@3ANDsXJpf=%X&$nGHVlD>fwI5yE))9)$rw~Nc zkw7$;Okpo49?URXm#G|+j$e3ReG*;;wVoXkK!O$9K&90*YuE3fh$fLW1E+UPgzmHH z(J|(90)#WhA2N|pHR7TcI{ib3QzPP|%R@n3$OI>>``cS@BbSXRiw3myGulkFxkvl^ zd~cESTDQuRxY_j|ORwyc#2#2I*t>eXA{LiY4NmPZh;xTqT41L4lGhrjDRMPTf20z! z6OQ(q8!)q5kMsv09FRF?nZTCxcXW+gN_u&xygYCQ>P(ZH(l+$Th0m0ytlzv9P_@49 zM-1`nV*=HpYEp{R7@2ERP;aLGCYcmiJT$I+&)(TZ|+G&2f^%i-3 z{PyHr(lkTcc{|z2^~IA>*$;lk^x;RhS}&knv#j*q`7wQ@pBB^<~HQoPQ7XYsxo7GadLM$NrtzjW0rZF6}+#oGao^0)mAIeh%t< zmT%R#62^5Qdzmh9+8)O7t4(&cf=I{K+=gZBB0=u`XRh=-tC&0cvie;)?yql^Nk%TQ z<&cCPYL;^}ms55;wEDvk>#P@7++vC;)y(oK=U398JRT^^@I#q`A*RUuBlh-B&0!UhVm9ZL$W z2k0n2_8JZV8|cn~jEqdpc*?SL6ZZE#9~D`$JuTp*UsB|VOdyqPl0%2QhcuOB1NW#) z0PVA%-54co9cd^U9Bs-29j3O>4v~hk6~e=Yor*lKnhIApX6$lgKBk)7G32;eW-m!G ztz9oU;sKQ%LDG*K#jSVp2D`x8B5_xruqZO-pla zVa8@MMlEt<#ew#%&sU8Qw)oU!HE;n4Rrpk9TXDRx5@pgsqkNULv|SNpFWVV4Nh{p~ zQT2ElRDVJ9T5{O(heNLJ7$aiOnE@6*BJ;=v`b6jc^LV50lz#QSI!^_(o#q?QDj0j| zkqj1n54_hyYt2JW+4Idt!Ap(X^7*`FJWLIfo(q&Jrz5>%*mf-l)~F}V2rQ?IlWYq& z9=KlgZ8pesJ;YGq#a!^}#5drF06$rPqWrXglh|TAS1w6!x-ZJpTKJG~a1MAj3VYKw zg13GseF$9-J>#-4J*zW%1syuZ6;UzoTS;%vdhnoM_UOVM-5t?ez*D`0Tx{3!5={75 z@_CE)NF`1Cfr;I?9Wuv0oEs| zS;K&>i$xwFTRy48Z&k~xzD7Db=B$BaV^m2FMb`ixMl`Em!h->V{S#K$MypK%g=y?U5d^I zAT=@yJIARMay5#mZf^$yEclrgNb1)LNokfH2y)Zg!Eb>ei_4X_e2U44`|h){dWX#g zI!xmqbmsZ>M*y8&IoPW(ds=s}e#W`b)UarAK{VaH1ru8Tu|1cbN6PM_j;?*$^=Cw_ zjwi`>PsE_z|M?tP^EKU-Cm=(PvQRF&-I7YwHrf^jP z5Ck}1oUJ<&NENa&Gr3{nC>skAb(>)BkxM$DkNb>-589A^{N2*92x%r-$cj?;9nh5H z=R33mnJ?vab!?&W7`M8&fS#6X0%^;dMBcC}v)N>vqy>?XY!8P$zSWKa8nAB@zU$c+G#y1L(SFURUdcn%9F`qqv8m?vSBk+2^!*y&PY*SWlQzHD5HXM;& zACbl=ilh8Mv&C-=O?uKk6u1a`#xyL@2Skk?TkgL8op7;U%Q&fe*%kgREP?Zw4V z4U;Z!W~*o9`oJ2v!%a8Xcju_fZCS~CN3O?h+0A>Ww9g}&pt!|=H?0mBIOod8)@f({ z@q%_SZRb^|4^Y9w-Qm3_ElZx1FYZuQC=#i^n7y`J8cD=A3owf;iS~DnCJ5F}w91T# zv#WSq$uV!Wt;WwoV94WDCmV*tp4cpkralPfSSgP#$OPv}b<(ZMuzoT65$Ef^gKM7` z)^1dw9FddPsPdy)c{}pus7&&G^_{@RNL8auNP3t9k>9NTjz=@~(Aq&*1)+wNlRnw- zPT4}MBk=AY%mG&x-uTZff9*fB+n-tOb4tjBrMCDQzu+S>ar>HZRp=KsaL?Xe1fVEq zsk;tWN<+EYf&)-6Dx8RLtfN0=5LD|2zB*hKgCU^Q->For5QTC*4u;6T=KTU?|D@)xhxm+mmB-!q2F7b5?I8l9 z`C6(Y^D0ds4w7e*?Z~{K*6RVVo^f$10G2LI2V&tZJ;cHdHeey_GZJ9ILjz*La2JB= zaDkxAO7#^y<8XFnDP3CWWOX5^69xdai3UNPVM0)i(GXNiIRqtd2A~S&9U&>BA0$0& zH;S9OEGQCz6na`AN~%GSR4xDl^Mr=Du1Wz(IVT}Ti*zv|sU_y2s9ljOE(e{Q6@38D zSvGsE6W>`jt4k1&XI51v^cYLjv63Wq&Tk5*KuwL6J?RU~{E+XkDJqLd1qfp-`9j{y zOvb#!1$6QdqbX4Nly^7#0wbp?ASq@Q?^!lQtqdd$4vQ4nm6Fqfq*U|}^R*P8WEDhA<+HdJzgd`JvFkzZ_LTyUh6eGV5ypGG=k7)v<=l~^nkR< z8U}TSDdwWTTjI4tfmf(kH{>XJ5kXh;HH9ez+w;grRY7q=Ym#(WNRNXllQcX}uSMio3&{@ZC>KQk}};*H&`W1E&YsUiJ!pcw~9 z9V!0|L<~sJPX7Yw<;UVczo!n(`KSFj6(z_hDz%4Tu~XeD_VPJVh_rt+Vfx zIHexN@$-C7k(KL_=HibPK3p|M-x&zO#(L#P42op_kinkpq+{0!Ij@c1c}v@p=vV`* z>^e>7PGh1?GzlIi0wcJYNc&(ms7+6@u4?kic4e=vmzCrhWy6}_5d~7^m3%e&QC;;Z z(qH@Q1BvtZ#btZ~^=Ax(q<6Q%n*GDk;x<6j*0bpsGpD2}u%LM_2ho3TTj;+!K0K2oGHGp6UC&4={u}g7 z@w!n7GW{>sSw{N3=!W9C6;T0l;)-Y=JGl^F`(D8F!?wYFJj<)86%7@jBSJ_^cIA4sDV@vpg%=n>z=@nbqys5{?ZxGu@=G5b`h61nlg z@E_|JW+%p}8OIOMd@0n0ExfnZ>yRI|u24aTA;=Rde;?;Zr^)p#x?l*&LZ&*pU=`6~ z04VVw(k;)o$>B4b3$rmvj+WN3oKjgd#w$OFkg7{j%4rw} zqcMpJa=5xRyRTLLAb|Xu&yOfSur9i$M?h)3#)#Am)Enuaj&+1D!CImMl)ghsE_?t0a}NT@22}9n=jA{) zTv0jfg(4$irG(JD44#h2n%3l!ZZoR4%h^Bx@f2E5#^AM)_cC*4I^B7a8VN_gO&DhD~96AP}iOg;L8vz zsA=3E>6v7gjZT*lm}YM+2@a=ZI$-x!Uol%RtEft;7zJ~H6s1(mf;qZ@H>+TdBrUS; z!43r1cvlxPxh*W9J>KXjZtBY01I@(S0RuYTdc`ku-wd>etGlSu)%*rPw^b4jrb)Sv zuA+}L7;1izD{?}OnQ}n4J(-SnK=-R3pjLE=1!!nxB7=V%&o2f$To^U}3U0IyBgA4yr*xnvlyo`hqS3zMe)8W(F5Xs_ZQ+W?0!><|t=0RlDAK^Dh=3_!rK1tFIjA|QeY==xZrtJC$n zz6EVy_Gwb#K?Icm>mhh;g9ukjtD5o^2Ai+=VFU&dT#?-q-yGteGSavkEXPg^()bMj zq#0l3?z6b!Mb(8Kvi06YcA}>;aiY%uO}DcUL)IF3XvNv~p{LMou1B)}^Pv^LkhFyH z49HtOqOT2S{f(jcJ4r;;&xZ%6Zy&>SrFOS@+g^t7Vtq*7jGNdwJm76R?B;dI91~TF z9hv4`dXv9P7|5=Oz}IE1^Jdg#RiWz>w~6TasG>I_BI3IQ-_rYK4iJ23}a4>x{ z2m4kPMHlRSR7)*|5o)zd}@^%bq|6nHqpzzW=)Q*L4a>5BH zT@uR)%BAbLmM!qwR`S<>d}rxt)$ZU#pXK4J)$#NGuW6!LxAH7Li{AQ&Y^Tov*;aoK ziV4iv1iS!B66+XTsh+kM_?ik@pg+1Y29!_Gjb23xJUa6h3g&!8*P$VTgJsED{)Y@1 zjxnV%!~aXnKpFF&Lhm*7Y63*~eIF1raWGihNRvERNJ&b8UIUO8W_Xn@z9wK^1-yYi ziz!XA$?l8MIgq#B0ZiM|9^lBLQexh!!+P!=1k7YyFL8mX&i7nOV5&2%E9>US#(z@f0#9cszM<>8kmKBd9s=`=%AQCgPVO9h5ltp^E=cobURz!2L!7O>J2 zR0qbJ8r3mR)T;3KlCnZ(ZO|DMqH&$IyUu=l;_^Zm%}XcaF{~B#$UN~G7*7QCL4im$ zRZx)T^+WFB!Fzx%Z1!JUTK8ctAOR@J-=6)ML%AbJNQ)RxWZ!I;WyK)y7PPgnC8>4@jWec!{#mHAeWjovF2kjaNc|zMLuNlkZl&_WgQxc97@2<5 z0iUD$mkf_0(Yvj_Ew?(pI`<}E-Y~tFf64>pTQO2NfMQy{%#K-oNIdFYCY`DT$uEWi zBeKXeRRLoupdzq>>rSr&sK{3K^+3Ens4?{e7+tLeeYPNS zZr5Y)J2s%tr_}=rBjK5nj_c8p9{NoC`LzVE3(T(z zg#ReGbGIFmZ+~OKwJBi1&LfNm2IjvgQfNgr6c+PZcyWN)Ib{K@mk_GsxY{-~itrZm z;kAH8gwVu3>yJJuneSiCDTAAA0|UT=X<)_*t2Sxjjmm#lVGUNv*MHJ&Y|~TVf;}E` zoy6-c;P3C^8?77W8m+RXDw%JR_alj7D8p1?uu=NMN@KY;vbOkoH*Xu{?-?znsRV6& zc=%o%MfjJkW&wO_%?!cZs>QJ+J6VH<0{%^y>&{*ApZi^SU;PR9KF<4#dOU@{o+C%g zQVCPaKj2+?cCc$AkS#0UveueW+z>6mphgR=Uof}crO)iaXy9Ajuc=>H3)yu@4Nb|& zY82L|$Z%X_l(x&?ZCA)&2>ht0>uQI>@i_9!QgU&t+--KzLZfVa3O?*@vfHO8Voqx3 z)gmix&`=GQV@iXxf9T2( zc!y@^*TyTu1JlFfO*p!Exm!S-98sFcCPYARXZO7T(+truXho$K!;1>?_>e_xz+jb0 zpZ{dxdl25t3%7v%5Xut{P4|gKcM85&US~Af*sUs}4Tfg@w+Ode-wVK-&1oA3c2s^a zB?-D(fOo>1DpTE&5bnels97Q2{*H@IQF!We_D)NvN+b}h`LDC}O;dL-0_b-(%zoE~{<8X>0Ow~#yqOaB*uXS8+U%yqqh2idJzCPRW$%w0 zg;7;)9wIKiP*En@hLwHfI}aP7%<1ET1?HHT=fIIhvc25Zlbk-MVu`QFBffd`xxe*; zfTd0FXLV%~igQ<$~!ox?Z5)^yuMFZQ|$lGPzN#s;TI-r`rk zk4(nY%!pjKhSNAC#c3Rk__XY&bZvUc{%~bZsr> zWI2ILq728vX#3Q$52zu{jE+?(sN1m=-o1q6c?#U(u_4}FiyJ$yB3C6HG8jZf)MwCo zYH-2z;Ho;5PM2`(U3_dlcDL@i2WX=#>e-R8CfVY`Zm@uT#Dx%AA5qG9Q6#h!cYnO~ z8<_$n`6x5q-AqHVC3pXQQ(1xU#ZCSWp>Jl0Qr;I)pm~Gm9!8$Utrqw4F{AJ22%J)c9;q!CwDB?}bDg$eNaiVmpCrf^DvUF-HOa9!8SduAqizH>; zxgzQJ6Oys$eBK3KhO0|Yw@w_uPx3$C=Y(JqX9#R$CIx_5r&@qK3X3*hW|7x6%1B4% zwuh94&}3I_AiFd47g?Mn@AUAn*z@p^hU}3b!ST@-9uAXR_x3kNbm7;PWgLgF!gnCY zGwK$hKCG4tWEh4>?@U_aG<{)6G8SmQy}+MYSg`uCPA-wXapB{VSaF(y@ac)KIEkR` zbPfyLNIB>E)bGvgs%AgK1(fDH3y&$PcJj1P5Z87Zg3*ykH#Bm1@iVNu4 z-Czy?q%@4UfDc*b4d1(j4_$jM2H2fI?r(@?Cme^l&abV0VScrx`AONFWYl{?Iu)5EpQTnh zHJ3gAlPtZ;9b(|0wCPn`L~kdh;vPR|%>nwyHfRX(oLphsp>~4|xHnoB%KLcg+ok&I z176DvQf8*fb>Sz=vl25pvuM$l&!zhT4I6w!34kvdB-+v~=?FaJ9e7g6e5`aVjOpfY zzF7f`STjiCXpXbXxVr&M@4BfMP~^59(A{Odx{4X3i~L3Pbt}8VXv%#K zfY}83E#dAKrEAkdYZ=TZxb;{ZQ>laQv!ai23mMs?pJ?F*N3~Hes0lLwjkz)mw0ok- z^}vRk_zWl|a`Ts1=|6?^JXXyC#y8=l>q_~68`*VD(jfrwC9$F>3J?Wtll72iEx7|P z!yvP!nL)bh0IK})L4Y{vkEy0o2L`@t=7g_DF`yo^&7EuRtjN_Ul%^C@6}?%O6&b@s zTe2EZ#Pn(7(Y8T&q`lmFlqb^i4OZgezPB@2J@4?b*F;dhDly2tPlctv9&H_|M2ni( z%1ws$(U_FYWBFXJmUiXjQ%lLI`Q7rEyF^gFNl5-D1$q@7%wj=Yv&;HyPiDpOIBF7;s zkw3Lxu^IWnrw+yyKTm6}h~WCTXZ87jdIc*f06}A;zlb$0Vk4N;filLNcX!MD%t znZ4<<)rZAp%Au39Z6c#dpCzkzYTo>UggxTC?p+hMc~Wiii(9pe%c5wdxJDU1OIuZH z-f{w|GTtwC)8{=^gx3TO;seVYL!#|?m$%+r*IPw0dKAS}9gRG+ZsV7GE*|$z0MCHH z`wqXiH!W)BM#wN$s~tw>iPB4^uJ4ZzC3h(UclUh2M|2Yx-pj_z-NCv|VqP@;Iywr54ws;qz~}hAEqADS=a0zzupR`F{BM$ z_!%y+7Pv`2E9u~w4?!zIcMTeoc`vouI!pIM-8sgy##@ff!vZ#+9ni&kF+oB?AQsn@ouW>}znuP+t(4E2fi+E*C_4a<2GX}Ps{FOaw}&=KwxIo?adL7|tR{RnbY zHp1I0y(i%(5>H^4j2!C~Jx_c3ctY3W;%+~8M%L~sHHz_oV{uX zCv9KY_*UsMDXo*!n=F**G$&8HB|4RivaWV+`?xN@zUUw$f{Lc4H93w>lR*F2lGD@)PPjWN%9#R4n+H3!`1UZDJtVere)oh#(* z!l=3QphOAxA^k|eU9{=Fx>H25Ziabsa8`K+jwe{XC!f6YGWb&!!QJ)<`yI8$ zT~az`C{26nw}Nd+ENSU@u3v2aLWYMR3{ z4k(#xQ%@vk?+M?j9Y^K70zP=A5gXy1M4#e&2RTLyMRri|M-h6#kT5@@C)*hTk7NuQ zjXjWcHB~<|bJnU0fp-TA#yKtbh?SPY5#+)={Zf7+&P)#?)bOHYxlR~3qk4vWq-mUk z`48gYgUrrMYE=@Kqn@tq6SYU6RhHhf%+Eyg72ZpIk2DOQ<~=tOGJ7kMxA1sk@A1~l zWA{Xjn)ewzSu1cB!6IeLdrAuZEG-Ld7Y|dbG}fCi`!|~-%!SRw`yeM@B>Ssp;4#Ts zt7)lh@#fk;OlkC7@ILvKrF^?`Y+ZCBpJX>ucgg~fddnH||*#*BKDtP!McC!{wZl&$%zkLjp@d&(>NU zSp)Bj;prK@owS_g7z)dhAhq^e4^2PkT2zzB>+G{twWRE9k|;|!vY8^QrZQkL|V)z+h-k=N!1&8LRw#qv}=l>Q7!SVC;1M) z$QxVU0^f=~$v%Y+B^fE5Oo^T7d3<$jx9?lz!mIxz|I7(GjUcm4^@SPr(oI7Ww9*4F zLoMI6zK68T6Do3~$@h4LVRFv)>em40UfYmC)Ecd^h`tM`1_%ZeoWpmv^X$cXq0ZR1 zAZ`QP74UE*DwH%f^l>i7b7hKbS;ppPXQf8_4@sFK(B9HC=n#-JWYW{25_LI)gCBw= zNK=Xw!B`}OpV>}?%t?ZM=){pT1o|~j(v6-V$t=FFAaEr|n@5j|Z{a#gTy+0xm)61M zKD+H}8a3m@-ymh$6I7vFyYC@qw>dumJ`+{vE7j{Ui&9cL~=nD$G zyoJQfP$Qi7@~URv>I+ za=(XzOui^ui=imPE=Q}M`@R+RByRVil2q_l*oH8|{vLK7|7wc4&4hHIejfe1Y`V$U zWh7uzN|)xqKltS1sU5D16GN*Go+){_sCsGX=~&AEX~fr(ni5SLD2)O$U1!f3$UWniW7 z-VOzSo!ms5Ub9qNounmC>Y2baGV0L!(X_FKe3U>7PTkJ8R=b!MJ0nySVC!8&0d`kr zKif!>gS%PwcoD5Hj|uPHU{IBt+1xN|#n@At>K08qB_ErUg1P;e?xwM{QACG zpx&m6So)x1 zEy=H4#-ZzbT4FZS;%vkGXa-uMr`D(!qtPZiyIz*=hq^0UMdZYD_V3IU&MRXT4}G7N z80CJn3tAB_ekv@Wml?ky>Tk3y$d78bS}-^2)CznN+pDkr4?h&lkF7!@e#F6H!J}ij zk!$U>UW!UtMCkdfEa^m>n#3Ur5H{+uE9cir5}k;2b#0L@AJx~25@SGGQv_k7+OW;3 zxS;^-VIzxC)3-m=JWC&r_3ip3oRf!bc%Akv6lQjYOKD{hiS+uHGUhN6%bYl`LwHGT zRLzRNpFC80ApJl|dTFD#>NFiaqQJVI5${OpF|hCbCc$wLCiayT5oZ`TI!`U4`4bzs z_rB2qkTgHytZK`T&OumgR99xH$)9W~Bs2dw+THm2VDpro@LU0vkD)SpEKr*1DE93V zJ)wvuGhys-tdc9RJ&Ugpus*n=oyF>ZT z;+4@noS$RAK1eYKT4f#nUQ+d71>PtreRzlE`-bvUrfVFn!9bRX{6k@f@r-@ql(ZiE zGkBTg+35f^#ItSXRC~Pb)mV+M8e~$=`|{avYN2%)r$+n?iSIz@$=IKd@5_4*?>!Ldo*0vkOyCV#i@+XKR9gMI+Q-~uF^2AOy}t| z1)tthO)1|7!=$kSfT+TA#~!%`FQ4TS^g&_?cMXxsevX=QC1uAuvnB;-xpVjro>;&( zv{u-kS?L?<>@ZPJLdWhT)CZF*Nrh{GBO7*Gm_6w;F(th-Irc3|_fpPzJfvOrV#%_| zrQ_Onc!vhI^E{I}wKzUJL-dQ9*(w$-d_Xw9uiCRLw{AOvVR|RsNvpsL$DusIR-RK) zM;r7pRB$378HH=pt7v$TqEAWf`kbvJ?P?ffU38OViu?=P^f>!{n% zTnvl&ep@2jeRC@kSflhUrk&^cp`kS*-Z zWtkA*SuV*xj0Sv8)OEn;B(@htvywrod1lYN4Hb3Z1nNl8?|ZcHZg+ezJ@Ek}B1IkY z`o`rKRc9=Y9kIvJIMWw>c$;iP>IZhK$PFXfr_Jq|ZM}=9-Meh~_Ezk>50AskGeiq_ z0tF3qQIx#Prq(t@?=(k#Pj1Ftwwi-&Jb`h>h!&QAIhkrSIfF%T#!#Y7AUbqgsd;B} z@oG@bhY0`!Ihir2y}QZA#C18cK7oxuXmk^xvz+VIvM}p6NleJ zhV+3~KzeEN19HDf{htzcf)~$^RYxT?j_7c}W*-?fj!tHelOr@|V7Q=JD(<7-IbnUxF$(xV*=JU3AKX#D2%21d zt;#+Vh3%5+29 zu?n3mZClWyRxY)Bkc!unel)J(55+r`i(DmZN?PLVHs)SHffD#lLcG^^+q$Qgj!gx^ z1)UZSTo)y#A>MWOeB(^W62R$gIPJUvX&^e`SGb(1|jXoJq;~i@e-{zhDN?ZWuHt{4+wN2uQ1(5yGRWF0`jr;8#2X<7aYTZ zoB4e5S56Pf^Q2Szs$#O^)?I%v+rHgziw-|PsWUs{C=J*Q?BV1&m#hsYA#BtQGMD<1 z!1acV8WzxD+D&?wr&Ju%j$`|j5GZz? z9BQwQEV5lY{aNLL)>xO$g>RsFC>WzS)|4cL=62gCg-H{Bi5DcDz;b>##=}QuGE>Jw zwb$qCe$qtt{`S88Ox`-0>#gZq)g7xvI?5Hd`|*$WzSqs@m(3>j>>~RwV8P{Lkk!A{ z&18NAxi(<MTetO+SMc*R~L>YZi zS%c?t8`VlGYJA|bVhRzTt?s@tDTFIi3_k#w^%Dvb#5+zbxiq~Q(W<<12qp1fdhmfG z8VfzwyfI)B4=ky%ZjD-9u5%F^f1p}RkIMAdO?w9J(;Q>5s;pc7)=nk^s1~XtJox@U5Q3PrgouK<_(RyulWk) z%k>MoM~9JB^{=4zjt{Geor#5{Tp!9j4@T9tXYJUYyh_`I9{^e4i`r=TN-xPHOwv}-C*fqB}%%Oc}-X? zAB(G7^_LXQBkxtXSp0Kc0gpkkgRS`eJA(XAsh^p$seg-oF_|4MNnwdwHK+Sh|JxO+ zjnYqO+2TkM6B4{conIyuceXY}Yc=7)OB{L$(Zr~&Z!mcgbji?3&h|Pf<+t}kg}Vcf z`a|~lDQ}mof#z3OyQ}zv$1h?`CL30%+>EF`Abao0dBlz+H1*^gukYhm(|*H1MXIKS zBq~wIp=0GaKY5ec^f8}GGyyLBLZ-jF9=zYD6H_bg3$#ZZE$Mx>^d$IXZ*kQ^Y&}qe z^IYdsP)2Tx{=Tu{JGCS+b<$?SJ9v;MpHSYx?R0?cN-lRj84f>Yk8GEFbV+VR%du|p zmy%n~Y^)w!ZXO&X)nZBc#x95i*`aJ9hvZA+V7|AQ@8sCbc;ciF#3wEp?HHa8l=~r! zn1;sYqMO1HDLfY~IwFcGWrg=I`*VF(xbp^p)m#_#=e()Pupw;@Gm*SczyqJcF>}5Y zs;ovjKV#_KMPA)+cp^AI&!vy6vl{)CvbtI-Ix6JFueQxbi$D-e$5IYDquyA}nl|EP zbltGaP?ui0+Lt-Z0+9Q3@4 z>eOAU^7DxqTYtuGXoJq_!dd=+#$n`Eyf1>mgHC1%X-T?(AR~`f|MelK#=fMuonGoY zZ1-4Z`YaCu%`doncOVCo!^I821_fE# zF^jelANo9U!S!2S7!u~x$1(g$J$SEUtzwJR_$jHRT>3ziuQ9YvvPfE6TSzX@C7Jbo z#Q+I*z)x1E=lJT+G{*)Or7t0v_|J6dC%|gYP-ZE6{O#W)WjmTx9v|^&*8A(fep<7;N)2^(QZ^O8b_#ZR(BEZG=efUyg&FC^cyP@9GF`swf;#%@GF3?emHa%ot}a z44&nd1<)ZKG-58~$!f;%=_;(F>(%&@--F(o-CzEs!oVlN7fUL80JF4Z+Sahu*j5)? zd+)#b!GEXPKf4Aqc5{lBgMY!|c+OL}wqZ=xj1Kc)PGOkI|2u~_uJ7OyiO*z?UM=!L zqi66BblES+hL!X0)reUT?u?2-bu)hg|BPF?{EK6{T!GViXlz9=K(`<){^U{|)kzTL4k_*O4$mil34XZ`-G_+aTNY9=|B zvW$1uucJoZN$g`2avY06NbB*dh|i>uJicJnHKs?AGr?2NG2MNmK0nF@_87Yu(lVB7 z!VpmBqi4$^O7jZ(tObYDhhIOik_TdSYF^#JHq+?mW$ETY?fiNnC0#o!&nG0)>-zfr z)K4LE&(;E!1o&fLZTs702ajuO8ezflSa)oGTp28jOpPk68=BkT9^Nxj-#v`T(&%|h zZ!A7rVCwz!R-}gLCXbC^2$7WKR^CB5jwSHl)utvQ;qxQ`K_aS8D22zhislEt*-UJ9 zI;^xxWrcD=-n4yuf3@025PT90<|c}9pLff7mlGrH$kStchI|sGd@2+b%EHiq$I#pS zJRV8Bdvo{ycU#Zf!xb^>F_Ta3z2RS(!K-8EsJ2I0}8 zR59Aku`e>+&BI>kp3@1ZrsBl1zWq7e<#Hs&SjpLR2Vp=W-2&fw{4SXn{mD~_iTI#6 zCkkarWY58_o?@={Xr8dZwok7240l;#^&w+leWZw}D=cx$(dLABTV*R~k;3vZ)Ndmt z7l`mbdFdafQm8}~9qI$?k1bVw;%eO0eJt0i$WtTzBtiIYyOOE0cOilGmr)Y>(%z<+ z!SU%$EDyQ%sSb?T(?e*-iO4|{aTf;1sonrC2Jjad_s5P6v z>2P0cLA-#OFp+fKrLZ8C+Uw++`FR*R#eHqs`weHi3!9NEB-?m%a2HkvKbGD3oDale zyQV(w2$ARJrM-MV)CLt}z?HZGkQd-J!d@9#a0LgHE0-3&Ij;3aosF&fFN9VI`(GA$TxCeK9x!Q>gHQUL_!1_ES(CM4N#w{EPNJz>sa@~X;q?aoYOrc z)ccVQGA3^TLF*At#c{VDT ztXzXkC~8fN^7{zFFoRmSbEH`ykKc@Ks)Vj^+1drha@5P|cXhEgG=Ft=di?R@)r}D( z6VbY44S^`CVLXAlV?G%KzV2aNLMeI~N&r z2X#IN(X2AHIU_wC@Yx^~r8R8HK;g=!Re(j&dHUc4(wuDh{!4gn(kJ1cNlw0TDsGR+ zn*u5|OQ|{uq>vzQq1szi_wTJOlA(@s-_a{3Mp)pHs6>2@kDP#8p}5IU7^mN&bdRfo zPY6#5>1su?&r5b%BdB{L*lbu=FGk)t44hy+MN!2dU&N#$>gS#TwZCJ|MbX@)dHgZ8 z3KavE6O0M37J@y$SaC6CJ>QZn#ZFIfKA&7cGc-RYS7P+cWxTR&})R>$pqMJB;+ zyE9#qqdo9eD4T&O-4UhVQfp>C+KswDnWYxzt=pi#X=~tV8B5w?K;`3?pWZw@xh!W2 z?Yoqymbko{t$T4S6xxDbWH6AopFH?B(Mg+$Nm1I7IU5#|V#wjxKTpIuucH+H{BMz6<1Q+rw*ZZM41{{b|GQE?v$y|` zPX5&o)8Rv~DK7l3orE)7jqMn}(6=$4Fk|Jkk!@u4w%_v7>qJpc5`oVId=i`WsB@vi zDqib0V)G}T?YiP))>fI)c`e!#(%-j!b)$|^UeTvn+n)C2_jIHV(q7eu+;%!f?(%_2 z_%Rgg5L+OOsjTP+X4nZzQ`X3J+QL#R6AB(-7N~*0YtY_*1WuRA)$>6PGh9E{!lSsA zA|qa68)CaAB)a@Fbv3-!d$r=DHi^*Ph!VndjT(clr-L;-C6a3e&*(xYNW%*H{J*3w z-#H4Kkcf-aKze9JMXF6kH+NrZTyi?60B%JT&pSBSqHfu}OY3T#v*n$K_9VU0t1wk7 zjHHx(3wJ_K8_lIjGdI8MQ|sfaGZsB|@SgQEX2bTY4Bvic2YdrI>qEUs5ocK)chgxX zu(4qT{3VqnUat6gLN4QuKOw||efW^vuExkHeR;k)Aw=_?Y3N5>~)G{ z*bmQbz;CY#RM2)lm~LnZWn8I5v`Lx8a|CgIexW{HkRwr<#yhP0oRWr}LR{?48wBe1 zLJv;h)h=SfrpoTP+sdZl!gj9YgA%0e{E7HoMIB9?##zMl)EuFyji6@4xang}kKl_B zt9iq|vahz)2+%)Q(w^4!8N%F;{iH7_Z|Wfb_s3uI{O9<~{~Uk$pW`q8bNuChj=%iR z@t6Paj=w}gW(R>mXdnz=QbG@szE!bX3C!Epf%rB=e@#>VOg)vc142>TIvZ(w*qb>S zTuJ!`6T*mY5*Wb!_av zEG_Q)zk<5|-XIDc z;XJp2xkG9z=r1z1;;V(LwyMdRCfpUHG6a|4k@TZ3gi|Z$O~TcfX?~up{4uB5)H*nWIL!Nel?2!~8o6%G8Z0 zf;XX5NEOBOSOYRr`CUfoFHvsdMd&7!h1|q1bU`3cVdw8CsS`J%2;YQKsB!Vq&k{Is zmJ$m@{tvC&eRAt2Ubwk#g5h0f&Lvd?fv7K$euF9OK)n&>M(uSKa%H#=ScCg)pxtr1k6GL?(YU^#^@J}vxS)r5OU)B ze&g4^*TIEoGhzjUF2y_SdNd)GD#TdX85cIzQ!cWzA literal 417859 zcmeFXWmuGN*Y-`PbVx{-bV&-*J#;D{As}5M-Q68ShYZ~fN;ilgsdNZRgOv1h&hWqP z%lo~rXWQQG{rEl)A3V0OI5#C``3iVAI3r9r zI085{1brz7dlz$i7b7hXNAq`v9PW0u)CEWgPxIgqfcO93pZ|j$_?+6UvcZKLdMJO5 zolsrkG>U*(!i?%Fgn++?Na8iG_uh7tSN!@M^hm2*+e%v<-3XuI{N`SOfcb7PE$WN* zc>Dy)O1QcxA(1;p^jW>^jZX_@Rs@EE#|ML>iExIzmaH2=5-~P923mdGPPX`GNxlK35o1j8?D98td*FkBaB?Y{IZsB%mdtH0 zT|Qk4E?c`kDf?T3FyGCSs^wk#%XjoPd2N~z_F9AOqajJ0G-Fg!;JHj0R|;iH^(E$A zu@-?pKgXV)*fqS3@91RvL^r5T^F$1DO^_paqYyWCN>b35sK-eMZP0_}$p;f=YRHYc z+{&2}Lo5#U$=PoG5Rd*B{6Yxg;zdM;OtVlkOF%0VHe-D|;!Sybh!ksa^{W@R7b3wa z2aJ9yHg3$)Kg7YtZvJtnGrBmmm=d&@r}DUhvzzTHgldXr|9w2wLOldyrm>xX?TTBcIsHV7I&OO zmkgZ%@+6d4G(F(efbz>_(?3=4Gm@J7m7z7w0(m=0{m)Hu5URC1qZ(Trjf~EZZ)& zN@LpL6#w+Vx-cqZ(_TjBd^&o~(#ES5@`GE+@@`(YbBwOCoF$~oBTzFnspCol<7{;G zV&%Xsy0enROVgj4^J+&nys~&#<`WGm$HBMMA2szBBE1MjH`<&{S*wNLaB1tb1h9H% zctP*pkFOr<3x4xdeuH1v@>!naoIa~i&;Q0$s<}UbJ<1_}l*^B``PJt-cC`vi#eO;E zGM1NnqMx>+H?%P3LY=;PeVTGRG=V4lPU8K3 z&;r;tJIRgZ&9{>E119ZOtTZoLsR7P<8u?0LT@lA+rtev@nWfkVbI%x}e0EseKl=2f zM{AX_Fmv=h%@3saX++d)qI-+^X%Sl~qo-;+!$NKbRasb75JY|M%YrsuOASAYTsSXr zRb8Y#Mqx`rU(3UApPWokLLpDXg(~~R%Uv5(^X(~v>b3PMdnb|c+V4XW4eg0fdZD&y z#gBF@FHwn%MrZ0CRyui$ZKI!>Ps)c#PZ1n{%yb`Qz17x5d}?<~s1N+Th2AT!d@F-$<+sKdFXe zjNyVzc6b(XEwV<;Db3UFdhK{C(C_Z`*Wra{I>BFXL;jQ4~4k z><0|q&oW(bIgSRj@7CFnt zkE5o?`EswNp9UXU`pPWOgdhlpoU#AygOZO9*03oeB&)Eq4<>3n8K>C;*JVVd$gvIe-}MYR3qK8>j5RwRsYa+y zjNVn{zpi@Ssa*3kUugv8<+!MjY}ky2Q@fGiboa~ZlcN07owfaYgfFY*Obh~nANpgu zR;@&+R>FOrj2Y#8(C@x;C%J0gxZR$DU3=Rz*7yu6k<=~ z!jh5&Up5fd*-hc#{{ACjJ8U^Ech}JaaYZyq4EZ|1Md$s~QSSV+#l_O}S0=rRXq9wu z9~(j?NN1bY{4gvnj3{bCA$xe1YWh03PQ4BL{whfh#oVFyL zlj*C8J9>epgfC%DtCd=EFX3_roO<^Cu$n}tqR(HB?7cWS!zrHC?WnT*{Ym4Vc}@Zx}Yi;ZUkOlHkK$Tp%Zm7b5Pb_(7M z_?=yTf6;LJAI~HTXEUcv88|pa4+J<8px6F6lipdHo4dT@ge~0A!zn9yA$A`6XwG^@ zLAyf0L_?2@r$fX#o#LskEowkMNJH$DHNRC@cDP*o4lcsFpCb@tI_`b{*}doYHk2#{(lZ1t-SfgJ8sMQ!b8$)puYjI00p-8(0>ALtqFdt{|UO`&b$CZG~Gouiml0SdFl ztL(&8Ed_R^4Mb8mp_R1GE=-1@m5LrukL^b- z*HxL=JEYsU2>cCctDdCicLg(btByTQEUL9Ua=AUW1Sk^0N7mc2znI=K`Mf(M{qAc5 zd0F4qbil1;9OlBhxqQ{(?+#}$W-Ytl;*Rt=;r-n%S9*8hz3Zz3c$cH6E?#2c_KTK& z+ONA6olC}E&33w*u(-#Vip5%Ni$wc>KlDv19*;g`L0qU&#F>}pt`hg#^EdC`Ot->F z!fL(3#Zpjv8ANL!+P%+;k)-hDOO9}3zc~5yb;%d1w$&Ru0pa`UTuAry=B)Ygil89R zW7MWN%(c$76#o_+xaVjPUlP;^yPj05`n9HWUDDNU>F)DrvpXHxN#3sWXsaU~S>b2< z80ptmBy2_7?yk*-y$A7ku;v2#=l;GTdnJydIpJ{S@z6b2Ib77K?-?w>O9M^Au9~<|(KOf9ptNyuApV`?FCYI`lxm%xk_~Pc~uDJ8| zdV%UL@Okdi%|(Ov_0oyh{rJX0Zl~8Z-4l26xa%Ju4oyWlO=YOWFx|%O^M1Vjb{nT^ zFLre+_Tuu_#mc4>j2 zJO;=5-z%|VimpRMOd)dKEOFmP@CqHa)O`q8ul{@wyokIQQ4iHUy`y+?B6@c@=djX# zds3h2=FoZn=X>wXjmaz5l1)_qweL*hltw=1dqy3%3oG|W2*SUv!{PQ!_>APozMX&Z ztp9q>H12!ddm(mrxql&08Za8YFLFI5c1!GfceJ73biXBLB-U|rnmKON9!lr?=T78! zP2^Zg+o@zPpFcT!6YZyvn$ba9;5N>*M8S%XQ}>$Wd^)*626#-K4MQh7ZZQ;~Sa5 zsZo*HUiBi8_H7U3+$fxGbHlyUAfn z{CTmsf(}bv6R{O`Q1j+pJ_&$`M57; zUM@vnKD^<2N+0CgiXL(KCxJ~99M&Ac{dq7Fd+WQ~QLnm%X->8`4HMnTMYM<1*}GPC zdC$GXa2Xl=&HVUhbM*aK3X_Wr!^YHf%!>^Q82pKnVe~-~A%#K-gkm)d_JoNAA1T*G z-^idU>>2K_J>^a4Q|X9Lnkpyq!ts4Jy&}%+te!6&@boD=pQ4jgL4%7r56O^P22rvF zx#Bxih9C)K2tz)h7_Fke)^(JiuK<<=vyMw%-|HQ!SRMk!y&srDLiv5Ki>R>91k@r8 zw4SO{V<_6hXe`D*tu#!2gu;_dj11`yot%^yHdd3cQhwSW7miOoBa7~P8Ve)2++Foj zeZ!GUM`v*T9g>x$W?JnN7kWkhREC2k`6(_kq*9jIUOu^rLlFg$RIxm8(pt)DKhKP- zB(H%Xd0kE#J>L3*ix>t(?`r`5b-=A-a=Mx+lhM#HIs+v(_h0h%ALO~gs6MxP$68Plfx<65wc#W*m`}_sx*y^b&tny0?g+Oi?6B_Ykk2zHGR|vh$IvXjA zK1>7?KEIY6SCOyPEtgZmd{jE9Yoz7W-ZF!|yEG@>kA*(%L-kY&M@uB1@Asg=;!-g) z}6AF(9*yamAfiQv@U9TWoz60k>=dNe+aaLltiA5|U zNX_EtJjw~Jyoyhn$xKWmX(_wb`-lmc)iis>WS%RFpA~?J-(jc`a0S=SoT3{-X!t;6 z>EZl6{RtY@Qjx6Gr>8&iT2M@_Bx$unGFNq&zZOMc;5d~BXc>9dfaMdck+TZ284Eqv z7^8%kG~`-d_(UB|nILI(G?x6zp?8=IfeB$V~2IF=`uOi7!rwakc@ zQDHU1AUQCI2@@0|MD_xr`iljt)MV|bG&W3Cg!;9jo&0gUpr|NKf6#g=BfW<9A9VW^ ze4h+?H9(a7S?@X^NTU)?t6?fwi}S{e`=>NZSby<@95#;FKuc1>F1iiKbSPn5%+wTK zX;;t&3`2qeU_vtF9Um|oFpT&E=8-uJGx#seix)HSza!*^luEIfDd~!fnF<5{Y<+wI z!gec;lGdYxm_#Dg+i$O>$ae^6$JQtHQj#dq}BertObTr~+MV?+QoVsJT;<|WUA*CpXZ zMY;RW6qE>JCieFQI5)c5Sv<)vo?7C`06+vyBZ3<6h-8apGEY3#9$&0^5SP6nOR@rTg(3tl@)-1TRk`ClU(>+PM)i5V0_}PD+uK>Zo`nUBlL0GtG z$b8Fbz^hlQo!V4A+LH)kx00%=B~JTOlhQUdU~xMgbxdi~uF3)V*^WMA?i3vIDfOsx zGSoOyHQvRNcUm^7!ri;Y5DA*u_l{cVor*{A%w&2h0$oDfy5Y;ya>-BldLiI z*b?`<29F=LWA`*PqjYh*8TAjnCn?95J_l*QN0h;!>b&kL#Cz|^c6Kn)Zrc<7_8n<~dHPZwqa2EX4mwgbt#IFykaWCd~{f)Qt z@o@>gIDY2vQj^pX2IUIw9Wbkkf?~UEp5|nXazm!i|2PVT0^LXT0=Iio*5)YN-P`r{ zn5GS6`IbGngX0bN`wzofmRgzfdS*`|-{#H6ch{sflvRA~V)%LNu3F0vDvtQ@SXFoI zeTIhho0#2ar>A`x;`^TITPOF|R5N*>S|IM0v{S)NAc89%0m-;k` z2aOAN2C12>y259s&y*Iqln;$-{`;A{1nM@K551WWl2~mJVZ8CHLOzi`OcVrv79dJ-8mZH=9UWMf3h_8Pyf@Q)5%>=vx zI(@X5NIm8w+6$BPnREU-vek@4n{2CpRF50|O&|88IGI40R^_YDro^S?TA039=Be*w z#tfn$gJ3PpU+LDiMvK;+w&T*3U6m;Ep+Xst+QlWT%`;`6f26h(mY@5D|8ADyh~T+A z;4dTh+%_KX9KB-c7@d=HU`~z*zV0h_W%)R*7+*k=Z0DGC6qMq_-UH1h#f%IpX%~UJxVtdZZN8Tq0CYPlSlw5~!kMKH)gGAm4(+(Vx;1E=APlWqBPF z#(*_0b0pq`0LY~{$YlmeV(^i~F)SUuJ)f$dXc-=R?a+GHxqYF=@!R;1{n8kdKIDbh9P$@{C=d?P&ley3* z(LvQb<{}nWL98f;@%P?dTgUqv*1Zvf&A?I1M7h%R>}$9~JzO*XT8=_6c{7>d8Qmf= z9jQuX^o6@B7Pr0VkX`LYA2Vv}Pr9MXqPFqgf<-;ebgcxrR^WJJqTDPhX3BC;UYL|d zWFp%NtypMsqjfrH&8FbG*nn{q^SpNC+L%PAVVJPCwW~xojj6>nlUnP)B9GclO~d3 zM~%Q`O|c!(Z4-wm3MLhyJ*>GjM~$fkC$@gDLj7)wfExwQHx;H3v^kb8kNV5)$DW=& z5rgfpqyijLRlQa26lqtKyz25GRF^QGV3{Ga%HGUbeK%6u4haX!tm2&B}s-b)tU(T^<{`oY>jgB%}m)_i6?n|sE6%0>-XL| zoW}kOb{CEDa6qxq{vT;4(5?kY9r(?L*1B){~r!rx9 zPIZU$y>g{Be3n4WWojxZc5=8wmdyV^`HqYLe{yVch>{VTtx*v7mi1*`N%D(h;g<`HXtnQlQji?=X)>Q8De2SbU10=3Sp7HOnMax>t@Gsm8P*Sg-0w8% zy=(i-M%1Nkkyd)YN5M$UW+nm8K@5y5Jp(r28KI^xbF*4chkCie(-3}9r>lS!^QjW% zDG{QQE?P~-C}v)5(cwCi@BQn>x~|#=xY$uuABabV$vS*hwf1Z7R(CZ;J7cF~|D2re zbviaSyN1`ayV@wGZ<#v-9v4up>TEF7Ra5DGCN$=IOfLRL*;w>g=}(5lZzUbPBZAI1 zXSqGSW=P(2%*IZn`N{KL>pTdeqCx#~272?B0ov6jwQ&+ zI>x##;x5%$Tya46YHLRM&bM)yUp;k*b|bx!%(?j+K_(W$>8uxxR5I#-)=;7y;R>xu4DN5ldPDF)U7X-oN zn-ST|-qYAd%C%0%_7BPPL+hTXqM`}?a@8+0EaSDuMX*I7CAFAepF5Txr!3ArXOnfV z%Seio)3h^tulw<%Mc;iQBb+V8e*h0R6;@Mou5S=pSZ$KdIx2=7)C1B<;CN|FE@4-|&NSVfkpqH-3TFYsJt| zv@<(SkAi_Z9zc`;$c|Km*12L|C~CH2$b>sFX(lUDB*U7nT!6H-zc8tyLb?l5 zup4Sx?U9%Rv2JDh49z45R0p-nmHX$LhHsd$GptJ z@ZE|*642$XV}u5yK%N7Xx&tpW!w)DGFR|nwH1z=%A?k3T0DJqT$VXsH4y~K|Ln3qv zlS|=WolhzLfLpY#nMp%rvxwBQV!cP-NFERrF_T!jIT;l2J27WPU7w@Ft!9$4 z>!m%`)4U8BqC1964?K?Ro0=jp62W({D(HWV)6ZJ_C#7%Qsk~cPjM#x&^JvBZf$&C_ zl`fK1ama-8i9_wq57w}aIs91N`VUPe$Ll~fMN!>V3=+X_8@DzuO5rmM>BC>^gk1NTdiH{;AN$$u7S#QfB>o26IZkLilpT@yuLwa1!sUiUCs@@&kN3+`lb5= zurTKw-naN}tN}2@=&;@GZBj1E>$--o2+_!U-|@qkjOk4~8&MA&Zo}LALGWPWx-evY zzY|q~%awn=)GONV_LT67(q=Livc%ENM0F{(akTF(IM>rWHWslqQnd3wE)f+KMI4Ya zPUU~)U)v(8|Lq7V8tI_fb=7wl^#GRO(Csuhy#ig2(-mj}B(}kWHEUjD+;TOMZ#Ap8 zI;e*Nl%F^u{9W!xIXOA-1l%<$gk*y}V)kz1R7_df0@xPV%s9X0z{Wd_oNDb$5csj5 zNEQ`&G_J*Tlx3P?TH3SM-?hat@a({s@?euMa>eRuf zzuWnwk1k&UTk}n9;}+dl0tz;r>^Ny+idE|qy8JIKO<0-~HAU<1T6ciMD-KDQ0{Hxv zfNS!+7uVGtCAM}vgv-E}TeXciB1i@;lQ+y(+70-SYV*d(t>zS&>5;89&OMIo63wX# zD&UpLOSf;>OEesd-(1_Sxt8Emu!T}nhr|!IlVqQwEG0X>i?$1Z@ z!uIF96f+;*fNJN&6t9Vh`&+9I3M86T#@ZcQ%|BG8Q5O?~_kGT~&6t=#npA<@oYbe& zKr$g*Es9!HlW)E2)n)+Fl|LU*Ps* zTGQ340*N~H`MH6Nmr(%M_hIxYLNq<28NyCXQRE)e83o`O1*o4FIO9tPjwUrwzup!E zb!bY+z(*AH4UAw&45JAs(0CUiCm0Xi)M1>o;er7zDLacxIS@@2o%WO-4OXu}|MIcm zQvALbpunyS3=@MuVCMF;AW5i>2RotnOv)y46-jhucQ6tF3Krj!vb93yDoHqt3s`jB zp=z>~mDWDA1zpi^RWBn+gjfC9@0`Asbn}CpTFQUYX4rd(w-Az>Y~Y!A`Ub{??E;U$ zCf6Cg=Zz@j5$L_%vFSddaO@(!m#^`u?BK#CpgOQV zHfh_eUDL1)jzJCEzC`DzY^`s|_s-U3@wwwrbMb89xe8g1#qBk@<#g%AfIlL7T@=g~ zTDnrGI()Y6bzSm7ZjmqQai7iD3gkG>v}kK3v=qZS@q{Q}6#ZoS;ch!V8TvbgB_8;OD>gX3c)|4%>G?%_mI))x_GTB? z*r<=4%)u^)^Bl;Tu$s@S^^e@$>zM@dBHhIqUJB)Akt~DAn4x2L9#Jux!62Vh{`sNy zRR<@|hGs#0_0Ul*Zv(L+TOOT1Est3oIHQ3Jo-3tuAa5iJ#|gl;hIX};^-zV!Ztw5< zTt?|eA>Yu*aoDF$2yAH&-hu~;u@(@+_9cR1kkZz8h`wE|nJb0KAD-v+oEr!4=c6w0 zy`zypeNxjehHs0*V%w_~{n7J9;kFJ^I+hjU&%UJf8>Lc86Xlv?llD{a`J+g?ZyZmW zqJV1h2Bl-zhRWA7#7Vk0MPV%Tqb)!Hni8S-KeWeKP1hz07=T$@1B3BtrXSvJ1Pz^B z9!34Q9US*nsX4~$NaYu_&GkF}-aAUbw>T|MCpBaO4?=FZqjpZpC$b!7x$FtO{usZe zPSM9ktlf$I8_oF_qBz^j;v2Gds-m~X%E(+DksDIXP4ENbof9Vn#s=dx4c+iwms_Lb zFT~(`m62;AtVvtGqwUshuN|QknS&oy!YSz}bUFGx<`OAG{l=$6+(nlCJ#39?SQx9u zWWHPUEA}7LNF2aIk~!>OmuMuaX6_A8*v8vjA170t{b}P5WIctJXqrY+ zT%?BGIt#OUy~m%jINY_BMQ^Gm304cHRMl@jH0cI8f{PqgpM^x&U;tE_Il^C;=#o{; zdh@HezE_92x5vkQI0Ae}B{^Koo(P%JRok17oUX41CF&Gu!>&Kptf`BBuF}9?&vFn@ zZyXRyd{1WF>w-jBJzlL|MVD+!XKWys_miosCDzy~2+`H!Wb85LN>(t$4vV{t1{4|E zwUuB)>k0{tA4`me1ag>d*HD`4mZCasHA}y|p(8Ib0lwF6VVdvmYYft`?TfZSJ-rDg zox^6cbNu}JlkYL`Sy7jd%3(P_KsF^vK^^;Bu(R@na5+`sSEh^Ile8n}emp{X| z^W?tHPiVMr7Tl;hE=LzGR=lq_n(q&bJD>Eb#%?U^dQlnDnT#_mS^Rd|AzMj(?taG- zp*g`Yu|XB~o@~39KI+<2qu6RaQHGg6@e2c{r!Q@`5;3q33U%LHYJ@QdU9Pr;vqfcA zt}yy^_n7TDkJN=3l3A#-(dSxy;rj(PglP7q|H8L8j_Vc1syE^37foPhNr}unFL`7noJSic} zM^^S4nhCPxcAo+<%c;K(Xk%!y+Rc~I-?{82^WCpb4voVv+D;5uB-`8`HNIrEw1ND7 zn-tSvw{r-eq`+k7gdun%;qUk4w&;f1f30`Jk}gnYbr`#}l+|)061g1C>f?rHBKVcn zln%pb@oP<|_R0-x5LNq(GLSw0K3~@)Xc`fCY?w>{_pY& zO8|>Oy{~lbzgVS&TnFHZ0rSZEMS1c$W1!>WidrlYM_FQqx zg+0G<%XndY+d6Q#Y-F6m83FWJ_a>{1sf&8u>2pGISQk;q^fb|DCxrlLHW`7?Z1Pzw zcX3n#Mlf2wn^tkMe%nj=yxk*dL(#+kuC2kiuFUjcg4npMqbG}nqsthI`5e}@`GE0( zVGx3#7#eO%8+?@j>qk&bH8%{yB4uL-#e9KbaLJ5+1DL93t9lvSiikSz2jqe$)kb1E zX@V!kS>->YL%JscUGZcM?=gU?p#ZwxPLP41x@z+qUz=pMGW|e_(k6Nrwg@+MNwnqC z4xcJW3b8lQ4rzV)3k$M1@T7W`XA@(mA@g~@fZnUM&!QckhSi=p`Xji{vnCFtUe%+7 zj;vb*@$ruvYFhpJo<8uco3EGpBLj;0#uHUm3NutlySnRU{DI~8ryp8EYo%5>reTdm zV?j$xuIsJY+>pU+UyTgmggDI~CWVam@J&`GWGyGXj!c1rY)Ck^BX^BoSm72m5%~@- zB#&wuCcD~m_z!1n_KSamAlQqxYxeQNAlIs&;?MI6h3qKzns8?`xetFCu$qK@fj_~N zo$lgKsd1u3EyUEK9b}V^)v$Ldk^C`4gxeE5WMT!8&}%3BQa(42`!RilyyZLXXKDxV zUSTj_S`Yji_TaOvOfcKI){DIf{;gBgQ?TMUL6bMMJp*jPF&g&tAT;t;1W7P1KU?K9 zwDPnbkF!_gh60)jhywb-r1V%x*~v9q8iK|ZAvMb^f=T^3ku_4|;3=w!H!LO_eUIGD zOMSq&yo#*}Tr?IxFwjgSKLhHhD_&##oUySpUINKHTC~Npz~u(HYV>3%t@+my_js1C zc8OnmU*xnrCo&21<}Mb?8`SC1}XKuXoH^e-0%mVnVX0ZnFG&)01Qgz7sW|ek7 zc~)ZeW|n>m$YeLg`W-r~qGf332|GIs4V0lby3^+4PQTTezm}Dwio3Kf2Br2LK zupdoyV%JIyK`UcUW@=*4hNSZzB{?J{?h-#fOWT=JkqbArCTd}xbcO%P2z2U^| z3$_3XL(~T;2oWB!&%eZL`R;GK&8g&M@FmGa^UqhkqT1Me4H;(3nCj~#npg;W#qnN_ zj`7Z?lLh=Lo(Sa2ILlm&dBH|%+(u(OYYAq7K*mWrXJkH0)9hq95*2&*rzeM%D|bge zI&H5vftgi?&cKzk ztYk!~VF3;KET8NL##1Xv{+ee~zpbFo@&>guY>53<^PqLAXtZO(nC`p^yyR@QfNXJ{ZIr2Kn&-$;pdN*DuL~ zK>{BjPa9-Mp%4rhMBQY#Kr%}U3Ms=4FRMY*hC#|CtMVAxj}-3K9tW5}0*S4(bp1U7 zGIs4%Fo}pA>t!+|^tfJ*$ZIBt4AZlN4DGtjG-T#!P}sKP=A48XfHTlqoZ7mJcG@2p zAIc^0tq6)4j|y)i8!1hZ{CD8F_~IqWh>(cQv%~tS(e#9a<%9@j;LIQ^H&e=Y7YF;- zIETKUto}4qF&guf((X?ntvXNn^BEGNZAimc?A*vuO9w!?;RsM}bn(lAg_x(PDagjI z)FIExFxf_EaiSz1*SMfDDdV9qCh>5+hX79`L{?$X;LrL%*TZeF~~ zKYrlnwqG#bY9~jI>^27F}l{KjWszK16WynyaQWKP7pRPXA86*WydWq=!Q9K17N#@5=diSecGS z7u;s?$R;vjN&FUxxV0Eoz@VYRrLp^g@e7f*$3N9#H9$~$LQ1-~HIrqs zAuBvZ5qh4CQQLvp%&YX2B5TZLTp(C5zZ+^PJ@DEZxZ{%eYs#jGFrg>~f=OUzB{D)u zuL{+z5G{B#yvb7dbOKD`*32HE@OHL?~C+|*Xz-yZfg^hrD|54?_ z?a2WVmHDnRm0ZR`=-H+$51eg^86-ruRz)&E8piXqApopm#B{b?VjkAxg)zn>sSgGL zJ#N>v$vEj^^@ftk&RCntN^<_`rtD;JLjr4FVMKTLKbp3lYRG?>94M@^V_c3KXEiz(`Br5ByiT|58Kx|5QU= zc>MjAis_$J>T&;HrNRbHr7XS)s%JrdgUF!B0G6Qoh_L~wr^eEF-UEa@4I9dPOc zb`KG$0d|`}tCh`x&IoUP-4FxaTeM?&ct8ghGLv=NPNHp9$v%t@w5AHYzSg8?lLJ;r zN|kuQ`rA{Fl&}|zzKK?Zva!JB%CdB&ee6mq z0l_bFyZYO!B}-@E&&j*ZedFe?VShvYPG`TINod#B7-jL7ZL??nATlJ)^OH{t zk)%Gez_Kk(!&i*oW5n=Jlz7K7Z-qX7&$SWAl(%!t9~tA9x9gwXu^=zHsm|SDdmlhL zICf{?S2x%nlIA(&)k5@27YfLK{}toNB8>XfONsZ!qVw`*Mj%b>?(oF^C&m0eqvvCT zGUtz2p1QS7ZA+=#*E99mXN+8k_7^5CSB`N}UpUUXPP&W|DT_3!79E~g5#o5=ImSL~ z3rdhZvPea_{^Z{i=X-z4M0LAC;H^)PL1;%yK;v?rL*o%nK>8K$`gm-ERS{`#BAmL7 z&?QtdSR##OR!7=^&-_t?uXp93*zc5Il*R^x?@Qmtpf^jBvTUlhYcFY6|CA&v;QK+& zVKmN8*Y|zbW2b2R57s^CEG@Czd(*W0#+3J;+5g$ZdUxs2u%P^mtVLtfmHb(T>8{5| zwvRo|WB@^0|UoW-#i&!lQ_bcqia<^QVO}3qZ$?vinRQB4$RVg$V zvXf@J`=2b+-Z`BHo%htllEcSnXD>_2Q$ZF-;wD~LVx?0Zzw4UDJ|X_59LGr_7RUL_ zH~bFIe&Gsr?{Ls5vXMwE)#LR+9PgbzvJQ^#@^81&o+=0m{sAu zbkXN)Ba-F?UZU)SD72P-&{?96_2(@S2zVGw+bbV4dZTt5^N4)%e!N&>J$JZrduo*H zjdb5XancYQ#cZNYB}P|N2shk{2`Y8v)*O%#nLSm?2KTrHFwbyUjI>Z~*jz=(gVsKF zC0jq{HD9dm;=6UHDLOJVR&0#QsEZ-D4bWEC>8l#mIy5bs<{V#*y1$~-dws{Q;`)0j zEO+JpwAs(^y4T3@XMN^ z&_qRZau<<1`%5m89anU3QVY!$$=NeP|BL zvsM^xl{iz3?RM=^=^9@8#mtin_LB>q+SduoO)nzPMg$!`Dmk#aN>rCDyHfqMt7VyG1?Y0M zum5$+FQT)h|1Ve0?X#Nu%PgzIp&7_{ZNgrHnHS-Mn9G{m$)TYvB2Syn)GKrcJQkiq zv-?Ffv#=a<(xgYUOSEmb`$4Zd`lQKi5)d)L`mcNbO7F0+ndoDlu9kzBz?TJ6?F!w( z=E^wJcAhT_%L@NUI`{qWNx)u$0Sjm4fcEfM@FG>f1rXEnJ-7e3k`R3Lbe47F(|&t2 zeK-);ntly-lV0_Zyrd7|Zi>_L`DdoQtvz-ILM4_;1$YoiHE-S6-91h+JfO*u=H&YEX^lkZE20 z90T+fxQa^gHqyOWxsg}1!A+l}T<{Cwnw{qUXTq_C9?MpzqHwnbt>?TlUd?1+<5I_&JS~L3oEv zfFbEXCAQwjMljPR;_iF^GjDvddySh0rd_s^@*(6k&uSiH&BoW1rl*;HD8?sRMsAr; z3!zs}tubC+OkQyPOd+t*?5k2Laf21>Qwt@xjOW7DQwyMLGj)yVio#p$N`U{&iS}w9 z8-0hT39Ek*&@&#ljHa;Of~w%>Jdy&zx*e7fk#YFH>;Fj_?Jwk9JTL`<%AZo zj}Y30CCp|F@VU)n^%HYNKr^cW+Y%Zg!}+fes%Xl8g&+-z_;&~q2-{yFem-IND@0-P zLkO5RIgRmP+IG8tteKksThB7@L$GN=p4Rm7g{_EM>%WW8%X`?5={M_&poI7OUPyW}t(nftCgetm6EazIPq; zf91t{^_THkX0rbdFk(czagu}mnE85&w)ugKQmyOJ_Z+*nStl| zh6qa&BTjj^WVDC58g1g4H5drC&5a|=5)%w~a+_0H%_O!G6ATIULHlG=tUPIKLk2u` zQP85#zBFa#eim-{_`hC;0R<{+HG|juh_Xa2#F(%0L~0k91KjAaFhYy~37IdA&DeU5 zTJr}ODP1X*%y#GVf4Eo(ja%C7S`9QIQN$Y@SPG{mlxa%DW*q4cTYY2M&Ya_Ae5;um zaOh;g5{2%lL3#jBV*9U4z-T#a0bRPVO9%WF{R_~;p z9EHx^|D1-W{)2J<+y+6(Ty`~p$#i9MEDQN~tmKzS#y!!yn59j& zKL}RG6HD2mteED;n_ud}O<%M8(GGO7gP+*1hYLT~h9kUYfphjD>QXALMxdV7mUyyw zSl*>%`b7S)9=bFfz!vId#&sHMZ`#_9_E6HrDw|=+b)zTRa{X&i5~IQA4g+ zjuJ^wjj!0C%kzhY_+dG|g#L1HqLnS2ZpE9(T_IX(#G4pcdYfU36a===r5F(R(a3dR ze4-x+c>V$tSR{C03p_Jy>864$Ya|?)>qlrt$glA?ej()o%ZEK!{>k5bpj3?J(ZHwL z*U)_UjA56Tcc4lLd0>|d^2ZUFB9yd{M2Xqd2T!zD>761n(qX?NOz|cbR4`co6!-!& zi=M*?TPzJ({pT@Mx{B~mC?jii>}^0=pI~~%I09#cde|}4h#htg%ui&a_)I^3Ltm=+ zZo=MbIRblYX%h6UuVc(3rYKuEy31?XoFZwUX>GW?faxiH2a`WF-NJTc%@(Em=H6FaVwmpTn*gxIy3d=5_18Qc9nzQUZc1eRhUbwg~4MS}M)=FsIV%V7k_UKw!b0 zk4T&m+zL}rO<>$@XhNVDr-0tCKp1Y(@%QLZiKULPI1Rk8IFV`4INaGIZ@PD8^mKsC z2ZHHV7yygkV8lZmw*fT+3hA9$~- z>$=KoD}Y#M)@(KgWqos~fRlC9u&@k*uvBZNQL$Vmh1CbODC!$)5E8(_60s=B`#VARuDQcAs+| zeGoCj3qnN|Zn4L@={F&(E=p@NK8^lgzsOk7mDUyv#(nyK^^eh6&7wgT_N3BU*~qUJ zbSlQFpZ*{ImsdM&-81F|`>V$N`R(iJ{?mh(H=lm=#FvlR6(296@+)uwf+#PEU-^lz zNWkoaFG@p*58wd=&Qjl!mTC{qS6GfuGx}N*(WRr=qm0=QCkn6}N`7TqK=8naw3j#z zm$5vpl(QhnmUME3AEsO{YA*&(eG`Q5XP+S;_b75@Y9>^W_fVLMSS(CErAQsP>-&+| zC$Z+=Qb(gei#ORo6(+Q7sJGd46~GPMw-q~U{^=(Zw}tUGSkYr|v5JFL@)dHD4n9hQ z$A3G}r4Av683PXlguNH!e;Vk*!tg%OC4MDph4`O=E+}_MJ;iI9_UeZeN*YIEYBzRr z7o6gt+hAO!M{TYrY)gp_=#?gTOnr9~-4oY`W^7A=SHBv`ck`LaC#7{tT~wxtHZ-Ql z$oWGX(Uuz(r_tRW*`DqVJ!))@@%#j1CLiMfBue=EaP|C*Wu991%0U_sus+aGGD?j))oi&9#vvV2Dn!ljx-L zriYWo0_{0Rv`I_j^F^Ast!_(0^HN^ZC-`P%_eW-#^kc}?E^inSzgYYUNz^oFs>Ia; zO=KL~7Yg@I&A$UjjG1z@!IY~SV)(Pma6cn6+&OU-`xa+Cv|4ac zfjvNa`{Ylo@w4w)^%cVT!cWi(;6%B%w|`Aw(TQG_bO?TfQ-Z&rqKR`(BnK^{scJHe z)K;`~{q{l%qdb}xlBp+ox%hgAv=`|vuiD7sxn(X+5Mgk=AjP7vzO~fEcz3tKNYv@; z_V?si;I;Va(QB@{)%NZA;+W&1t9V82Zny0@`uT1fc)IX4y6f%mHTlg!K+E}U#g^a8 z>+$f7;ckO}{f$PW^38d%N}ublqSXiY1B{4pm8>B z`#0@ynZ3;k@%bo!q?#Y-eYv>{<869s?=@+o>lb_W+MCbA#m(zX*^|fH!^069Ki^Gy zhv zo83#yyeNIo^VirZ?T9#KU8nW#+^4pz-0N%g5)#!a+yKw6>bI}orfUfLr2)n zj&)@XU@Z=+JFdC`w1P`IsKKjFw`mi@TCL{Y9U&HsN#ZsamRLve0 zDwg-7{FFLmc*ex$iJ`r~=Pr)gj|HoAru~xUs^!dDm{763cjZSk2g2JY4o>~2wq5*J z&@ZTQbYf52$k9bjXHoC?OgC!ttLICj2Wd=pyv1#!BM4h%TK9f{r3BPMF757}w(6h> z839Oh?!3<@G1be+waa5}c6{V}u=QqVe!BKRNa8>kll|-*Wf3w1T;@W*bc2y<9p}_a z3%YJhYElY!c`>OB z9OUzHa-D=ayA%OiWqn_5h2cpIB~7lnYocwPSJ+W{p4)8oO2QS{T5;lA7O3l#aFDn~ z8^e=aOq$$X*TfTW1QQRrB>{U9$N^zVDKy)Jp!3Y~SHEknTfN(KVs<=&$^Fc~S&4#m z^Ge3_erH*qMr9@apqB$`8*JNr1Uk;@zCcM>S%2>gZ4KEQ%x{SS zLEiQ-rfpvLr-cdZ5yxp}g2kr|G^qq1ng&_p<77w3qD4Qe4F;*)go3WhL59kg3eY9G z2szuaQCmH+{e))Op6AIUCK zH!oy7?srD`37%foudP#micJ`=HJ2%vcvP5g#?~IM}k>0V)y<^$Ng#a$} z$lkR|4E`DiWenfgc6j>5W?`+U{-)dPT!;a9M<5D7ZUuSqCE_d#uiCS%Aly`|@Rpd@ z2+DA8-c^fbaoviomtp}1ZypAii*-%19M8=neOqK}IvCWnm6ge_UGNS+V`1?Y^}1Pr z!fCFR6};<~>)0S%Hbx<3bBx!6f-Kww@V~rzLovvDbk!;Y$+oG$nB=qD{)0T`_uVP5 zHg%3eVC07&`?6!k1l zFPd6h($iA~S4JuWON(6{Se_D*iD0ds7QE|FuqAvRKFrFr><@8RLA~?hRLxAW%Sjw$ zpDi)jT?F#miU+}MVn7r$AdP7oYDbm*Ux()3z;G&nk? zBaIya(u>O_z8&tP=`e?i3 zvb|UU(x3c5hAk?PC)ZSrx!_L5T2EFy+3?>NiE>R1>(C4pt>&nrZFnU*H)dI=t}}KBe{XZai{|;b0~5SwAIt5 z0*M%u-5RrEeD%>rXA+tR&l{+7n+oK(hA6yaaHqRfO(H=si**{!^cKXm#vBwE09;RS z*s4nfN?gN_4-GpS2Lm-6R&HRu2XN71xu9QLG6S+^ZyX6^Z51fFw*A3RplFJ$8a>Nn z)-$JYG=|^u(R5S#Bh`Q@wl_`$rWmgrLQ+sp57LsAgKIxO2i*n0{UH|053#@=oHgG_ zoV5!Zlswtu77+o7n|q=T?zZT3$7 z8feRj*RUCNB26DP2VAUyQyu=@3LA;#K#TF+Mx==r=6hzO!F#vILU`}?kl?M*c4f%W z=_Oh$K`3H&XM&yPu5R2nHrDm{On?L96&GmUCi+)Tv2WWgQ-6$`Xon*+BUgc+cTB$_&1q!WE2y444O1uutznJhsu8#Ph`K_|yB@u7U&DNbrvlosc)1 z!C`POI)77ZruW>eRS|RE0s{Jir8YI~fU$F8;lJZWMq$~EOjW4?1md;o3E7`mV}!t? z_nd0k1GUWw)V3$cke=YM!KPN2fi)C|ix%KQXnjQz37f*-cqF#Mc~jFN2WVnE5Yy9* zj^4A3U^8@Wh*X4~UNYJ)jAN_l5GnS%v{(k6&lsm)bammr1z= zk;NyY+28tKxY?9B00?JLW{-PUvsE>vslg;90LG}O*p|u+t?{u@5?w}btV=VEY89m|^iD1H9mkCn)D_X?q!7If9T;^tA zq=%g$meVS{{GPPaDx$b=bQF(c3>afB{Gf}|8}$L)8qmb&!vy)m1ohpd4QN6;Z{XDr zPWx@P3ZCyzU}O-`#$^=~XydYqE$%xJ<>?dy7XEI7&hwMj={qujrZ-q?(cYFbm3GPA z73YPI=WJF8uAPYwhv@I{?-RHepp%#nCnO(E$ljeiImduO0>8j!uE_{#9H0_e6$HWm z%-LqJXVJ*p=4XENbSnFHH;G$8BFNJkpF?{SX5HU!i1af@C3DNHO0?KxVDo(HZwXUD zx1(v#V$>Pk0bIvceq_dbJiIwsKw8{H`R+$0=rQ+yQNVar<0xy*4lX%nwV`x}@WD3x&9UVnn z3mSen?6vErTkBQ;bxaD(U=o(=-DUJlTUSTd>Ut-p7o?DVJt_vnSU@zS7>mZ1v5@~O zArU;Bq(7t>Q{(2-cDBtIJqTSPd3@^~V7Pw9T(M(`o0{@DUC=`gV9EwusK8wRc0J#a zcNMN8ricO<0ht}HO_AJ_cA%q}+=w@32Bj|1$lMs45 zF+I@Vfu>AOm&A}Zn963dp4cwnQQFN(IlV|VZqtm6TsH-hKqkzjN_0pW?1hgz2`whT zV@fTf+X-_`H@AqGJPM!;TynBD0l1_S9r@%&zA^Rtl6p@SLAK7y#YL*A|GgV9<*;y@fB&+?@8-Gxp+wFSwd4^j)s24< zhnOrmS>dj(nk;95WYHuDvLO&uEAaz!^P{6p3a>hqiQPEf@SA7pYC0;IFa^ z_w0S7Lkt}g5U42i8cJ2 z52yY;1x$Vi8p$XU+$L(>nI?k+%pq>_ukz?5!aP3dL`0KMIc5}yyJ=+*N8CyW(MeGGNep|Kv<#D&h@p)~3sR*OsDcZL=USr( zKkR2=4@)ucmT1wS(#Sa!Lfr_Nqm2oN#ig;#E`%70CMM934olXf3M-PAQ3Z4;6njRZNlrmEBs=!>ICRZQr6 zG0@lRa2c|whxKD1I1C>V$N}{W=s>+Yy&A&Q^xt^fDg^MPAJoGz4XAuEgj%QplGSn^ zb|AU?K=|Z*IVFvspb+N8Jy@VL%Sws+X2h=rolP2GNIL*?J)l8Z$RO7VM}Eum76>&( z%?&;dUqNbAwS@+YtPc#Wk1IY4wJM+LO5t|=4kwMEM}Kr!7$uh zk1B|QUv>h_wFtOs09itXxSzDW;GCs%mDX4uW{z2u@?S{YL;x5}n#kN2V5UKa;VX?m zAWB4`RlC%oGX{t&LBw1V%9w^zfSzIqwEhO%!!(T`ArVK{BoRFLV06)N=wlKZvL9)v zKt289QB061#Se^-!~=!cja6d~1zAaehDPzzcHc=?CKZ$viF}w-?dt?n?3XBI2#k;b zn*EJUWCfb_f0%h8ED`#{piC=X<`>c2V*2F?NJD-yVOxeFK8UWU6M|SQ65#X$nSC@K zc7YT1i}|ih%#K-C4T1ryTsB8+JS7ey6ksBTMA{92?FEI%Ng@s`!^5nGI~ODu7LJ*Z z4lRjMUV_4nY6OLWEPtw47Xn#SXVrn^d=ga(Mkw=BZKnZIB-K# zeF}fP=QKZ(!?f2talR5Six5GGaW#fIqyEB#=-jEr#?dIqwNb%{=@=tqo{t41{kc2< zMaLi=?GLcqG@#)&7t?`UvCVRQo6?0iP}q$h-O=RN;1s!@Dv92WhriJ6ybi=98gsq! zKp{{mgCogb7QYu7GTFr-eQgZZ#TUGI0$KE#J78DcQ!g$YAVzN7h($U;_scVuh9osH zSOL<4qej-dQLH~?2Lf8MFAv49q`7RH^_`oYK1~PoM-=tkkC<9(GQS*S)fO0Fefn9D zXizmp(kn(9iVWB|duYFF;2=eL2?lo^02T@sz!81_#0H`|+AMr%4N>yFHrJzxTa4ax z3Qo~Uwlp9p!VZ`*(AY%%(DQBpK_BQ2YGcKQe`P@tjzE6|@tDRy1vnu9g`(kvVB3!3 z=l!Qc$f0v&)S{lG^JANhsq~^hh^N5#*pw-(e+xUNhyIs5JJGvD^!~J1?)V|?Hkv3KV7XIzU)$h zYA%oMSbWu~@6`22SW5khYA_@F1CAJkL=dC|i#4dcalK0W%YZoAqYI~>ErfwNYrK-V z9WGUJ621g#$jN3MOpTO(2?!Vp7^fh3G}`bGnSw}@pslsJzpJgydiIx>5EMFkGBz4C z2C`j2#js7HIapV4x64>AUcNA+WK9-7%DyRDt+g5l5f{cagXjGgV@d(MI`HY$4M~*1 zVc5_)VUb}KYnL)=3VCZMaWB^v)c#tH!%6LUa}k_2y*&#- z&@(Cnw4acJs*5BvnxsAwbGCM{=)0@(9iG-Kc94ue{NP`%Y5=;*T$e4 zAf;DsQYBB?&o(R3UX=2HMOnVi?NQ;F<@My?`}T7A=P3mH?SEgt5RFuV>t#X_t*$!( zwF<<@EdV`qMMiaw$C$BMvikd|P4dWb&fK>c{CQfE3%mKM^T-b>^F<2<4qRVO;FDE` z^{ewY4kGhQwEYIbqKnkVV)%eD=DCV?Z|e{{V>Nvm@=N5nz~3yQVa|o<%+WHJw(VIY zvH%6tlJs~<`QM7B){b7BAkx%jQBFsb*lSdz$wU1$8epBu zaj5YnXN54n&j`Lh7=c8k$!@rACxK706}^I)Ak2uJdGm`#`y6+R!LryR`203X6En~N1U7lOFBd1satG*m*JZ%u@O&DJj%+S6L+EV zuRXcFx9V9&U!(XpPiT?0fxA(mW$u>@g6pMKR+E>^xrk3tEI97sjoDh}XIgqXZU~uH z=`QrU^G4a5sxaKkh80M;-_NyNU(w~!4xR<%S33M`nBcM}pwXkN=DMh=4ak?~_Vnkw z+zn}%;_syre(!NgPt`oh5%RNimLgd7(X5%14K#y2)FCEgP9V#w95`JZfq#;He@H?^ z*5)lGe5Q0110nDs3EhB_yOJ~B*}2S+#q8{dL%N8}rr!hQoK(4eLMQe(ue4Pl#NJ3C z_7L}1Y;r|cOKyKO3Jn%WNN$HYTM@Yk;_T5PNr@=`%$mOb(9#KDh@_la@yq`#>(LZT zG_I2Is^JJo*h26Cj^iwRgZ_`pb?x4kw&YC>yLTWD$e4P>2OurAWkHUu(5 zNA*0c#t2Zt8;#3YRZspt_j^VxZ{C27Cn@EjAy|VUQjQTlHC@lzBRU(Ohrh*bZ3_F0 z0v*psqsZs4miHGs2D~`@oxTsZWX}uR_TEg-*RZda?o92E&wppyIFeoO1Rmo8{}63& z?UoM-Jl{R64QaUA_8eU>&RlMmGk$5&m)GS`Kq|@)1hwE7{>%71prFy+%Z5?E;NNbb>zMXtjOP8+79(?s04UGu0*P#YkwMbe13_ z)#BcnS)daKJA88igK&k+&F0Sb+{XX)Bq^-KPb!ttaDKXkNM)on6t&Ir^99S2%x zP&XV`kl$8u)QaxohmWZln|C1b$P+v$a9_KL?}oAkUT#oq&eAoqZNGGQK0UrlK>xnW z7GQ1@FqZ}Ec)&Au-71&S5g$#=@gx_ylRkN2;A zZEwx!46g!T6VcB4q}umtSI_!ZI#&P0>o};afn?tO-AP*Go^3q0$>enpSY|te9T<~K zSzyxHU6}%^Hz@~QXY4t0ad<#h(^z#Fwmo>5syn7|R+ZJN3)?Ez!Q?7-O zu(+L2_zcjk)kT3ntJD=!(r*Ww5|8MN1CI+@x=;cg5s&31ye6y#*nZ0) zb2~D;r!jr7{+iJ>ePDaM9xei$QRr;9O7W7korsN^Yk7{!y+Y;EOxfY<~N$J5; zY&Iur9y=cF3pYa9zrIRaZ};i_z8u|Ee~B7Squxr!`?h?W!$@9#9$eGS&G8GNq_5u# z3@ShxKdFFvp)E>0yRH@7Pw)$67PVI0PkhRb9pr!gskX~Sm{vO^RX%T|H$+SJSG-1R zf%^MwLZ_&=_RTnKEAFDgH|~=KsK0aOWkZJ}5i^NW9^}Q%5i`v%!=2+cJXQU0v)g5& zM~6*XrERD#`epfpFP6@;2ZlY|tCD=0#jVRmnTt-)$IY5VE8)&fXiI%YYtHcj>|`%9 zstcGETHCDCoL;P^=dAl~R#?Z3!fOmu+@k8N+E3lT@@|YYCoj0S!C)NVF)EGUK5H{d z*CPRItHO-n$!N-BKEL6sm8g{Y8DoFw{P%`Wm53{iMB4T8$lMZ^`gSA0dyuY_MUPtu zE5EU7Yfu~}vJ4G`Fs%9vB+n6O7>OMNf4(@;B~^b*cJisxe*4TU5|58gI|L6mk6q`U zPsX{SkiGUWa$ZGOTj8{@;c3nid1~1?K9Bur_m*wWS zP4pN=YuxMFg(=2O!*kVO|=807il zOT2p{f!ar>ecR3Au1CE4!|Hn|LYq9o5*0mbEjg=JaA#e0h10L>R4KQpC3+mxia#~# z-{~&-pc}$s&=trw!#S*T8^jTc>bT&kF%A4|xuF=@F&eg@mrkxA5VOCB8rTPB$fHGU z_*oe~MIdIs56pr<%>EykA&-EVbN&N!j{ZFO%{0R7JLYlw+cUSwl`A#ppu2PZlJ2 z7q~z7?Eu(~H1cdxEh=##uxiN^@#ZaZ09GqLX8zoK2lyrKJ>-mwPGd5tB^oz^9W3C^ zU*q(t9d#>8>^=WBv~Ej}k+VN)cRX6p&m!Mz(__yeziOYV&++(HB5^23&zDv;R!{)e zrnni(_iyW#Wg2d4C%UCNmD^2^qE!S!%TM4ID{gSD2}l7tS{dK)DA5g3-$>QZ(17== zup2ibSJRmiAxf|fSJ{IGwUS}{1nS$AC^6*&Iy2AhfYGgX^b!y{?FV#IAoQ^h=*&C< zhxqkkBZX8;*Rl$zO$#^89e`~Y>oR?FM?F!S>A-uZHAi;!lfjLug)XTRpW!A;)Hb5m z(@#csXB$=9nFu}UVj16B>Kf;Z#5?|YqGGRv-x_(YE&yulqkj!3P^@#_1UiM-&Ob&p zBK=ACe&L(|`~bTmRp)2(5`ic+yY#M1fF?v9;=~dVDDd6DA6nGorp$ff3_4roI+cN6 zEhNKe^3DxSYAi*gLo{v%Avawa?2s4ilB1mUBiPehinwJHIK}8?6dNh}CLHH?$}kzV zP&JRV&?6$~u)dEKA|bX=XGR-tV-$<3xK$<7?yf);>4=<|m~fXM8HsJr*L239+TC6yZP6jkq75sE%+d!Cw?|S?b9a4ZwJi*nj6d{?Kv-JL0bxc`1wT5Z&rK2x z^yG;IlEWBAwU2Bgc;lCNFWl@?B)>bvawe#`+&(;^MGQdJS+e}m&`t@NF3GtX?`)6l zMNvd1d`3YA1kD_(KW)2lz+#oe8O$-gum|aXq#W5sNZMJTW$BkY19q= zBIuPC8-Y`iM6ZiN5u3af`ZfUPXY_#Ay5AiYJp9g`(gr{Pw=b33VtV^Z#gV{G~Tno!egZIc&? zs_tF!%Gf#4*MyoTgjg#rnx^A z7Nk7`K8&l7cddV{(tSz{#jK)!DRcy3*7B8oGrg=)M%8T{G7d=$3P4kL8*#oZ4#G4M znf}tO3-I)3P+GgPruRvB#RT106i$aexU8gK8Wc)CJ~!G$nyfrH-()twY(tIt0chf+ zRRhrj4I!=E|#EdgE>b7^lIc8c|L zXk8kw$7GS#emwr>BgAWkC4+2j-{F2z$qBcja>}G~C8`J~UnJYuVRA96K|Q{-MyhWK zVR%b($g;+FY9XanKLc6&K?+Y8Pci%nwA8FP5J&}w@$%7Tn_?$weH02FBD2#o#5f<`i zcuy6^0Vy7w9_7r~WH9@4mHBQcVKVKyUMKgPvE9Z#UzL0DIJgsKt_ploagKYQKjQ7uOH-tmISnsIP?>NF4BH)MPikqj9Um7Y=)gJz|L#4^Hk}6x2La`+OhZmm5&A-rt?N{C}V^UyP22 zf5BjsW_WLy;_wG;c(cPZYJon4tRi0$bi?E58FD8nFWc9?G*Qw`Y^Nf~J6aQ6w+Kc9 zkSDQmf7OCNe>-37VVKNLo4mthgp+Ib_r%h0hyj(WaTrA&@S41>(&x zIssT#SgCcuK4AQZ4iX*4(bRJ~soeBkPJ18Rh#LMylY{*!s%!6B(3J1p927lN70yD+MH-eb9C$iIb^hgf02s8EI1)yZu3_W3(RBO}#lf0BmP1f2 zjqD}o@BcX|Eavewh#_0G0Des;iyrcj09~`F-;8ukFDlY0*JYHGN^&2dVbuJBpn&rh>t4$Q7l zkVQGWkuI)qjiHedp(kGV8|x0&7ibI(xMU@T_A4a)(@&*@G@x=WqTyP3g-dV5;F_fs zU@kiqH-7=thzmc3$Q;~|YTmV=zVC81Sa7YtW?B&+$&CC0%bPs&_;e#Rdkhwu0O5kMk{-gwbH9m@=p zMAoNwO>@~xdUF*3j;(lpJTV+H;EZc><_qZ)c%#m$%QmSjUt7=k(tK>ymPEG}B8|-B zgIWB{ta=68Yugz*m4qF2WHjT(WO=1SzHfauD!r_#RA$_x4Sgzc~QDW8F zranY_TBACr{#-1anNW&)TqF`{R#^FgP-u8SKsXBGms8D6JasTZgJVvq;Tc+1)J{KUk*;#p&k zA>GT=sy-lsz{IfXxJz}Ty!MgpM@vOcbmS%LfO-+fUEx{6d;E- zB|@^yi;a;kTE8xiR{2zTj)vFS`qoTf_EDQ;&KCP3gF@$9OzPDlf68)Rq#OuNEBI;G|sz?MeOtZMG)E?R}DuPpHyw3jf}ory!~E#&F0Zj=fWgg%>tCs zf}xsnhsqv#%$g$yM(IZoC41!oGLy;RNe$xtNx9d>u!B=n+?~I*aFz$p*&QEYV-ZC<7zS(*swFd(UQY*hu3B%gPGh%u$oAN zxX#Vv)6Xe0$-3kDGxnDGdw0@T%^Vd{SOuPvIJ;SEft0}fj0-~yl^E>@5Fny2ukHaU zAsef&9e2$|F+M z0>wiC6b}W5G7Ne&3hYmyc$oIF3<(W;$C|?8MwLj$4q&PogHkEN4suZ_u5(c-B9vif zRwR3Qw}K7W7D&PsQSS!{z@}^?57Y(I0M^9w>{ao4mb(GUUY=M= zIJY4Kj-fCbcOsK9M;6m)N&-mF;QefRhT@4@Z~aMmkk%?q5H1feZi*neloDJr*>zcR zS(^eB3PKVz({bSLz@Q!E9s$d`K_SgB6wH)Q*4~L?`rdAYQ`{M-0EdVlH0%LsV8#t{ z&wyoJh2Z~0F8i!Y*DD*OlnWuBqP;aGnc^}(C5sTuH1OTR@aF(|0@Gc6uE!u=*~9UM zdDSVY?D}&A06AzR+MfdHq9VW60lK%sgaDFzx-RN>NM8g%nTJ*xB!j6~ZnhI%Dn&8d z2X7Zz=n0EkZNw{kUDKGRPnD8}J({X{@mQ>Rlb<8ty+oJ>1`mK6lp#g>FJ3knN8sew zubE8A5lkdk`Ttggw4Z@7im8Ketp@B&T{W7ieL0Hhi6n_^3O~Rw&oqL`oi&lEC001a zEl4tj{Y!aJixmomA6Qt-r8Vge7(gos`FR$~y0VRLtqEQH6!0wfe7rj=5VV!^+pg=WM2eHQ!PZ5Rew?;Sop5ARq z{V%QXQv$VO^aRw3`qPJ2aBcpr71-YqDwAWpu=4L($$|)ZuN?F>ROl3o1K=4q!4#n^ zV=*Dd-#xLDkk9TZN@sZ81E|y&6n_yoG)i~sGmL-ZeUVdHdL+#(Gg4r?B^Vi-`>JSD zhMsuBp(|XC-J?w=TfSdJL}U0v7XUnR@0A50Q;t>a*X#@5AYO%{QiK+%_C}hn6suVEXA0yUf{WA7=!11+9-|7z z*xX9N;Cz)l%-1axPhoaWsKyF1AF&1!(nweyWS(*)N*>wwpZ1sc5()yI)%jNm@rCeV zmj$_xNg}-OFG}d|^)o_LCYDm$fHO)eJK8CoGEga;BK3is1M&GNIOBn(f{xGpjrMYZGQ>y!DunAVygDt;Jv#jVBZc!-|8pYG0dv`|WL&3== z8nG;04aRD-Y!J)7b~fOe@Uv|!!$=c5d_NqIK&vWbrecsDY~YkE{q7F`Ra`&lfGM)p zpsMI|O@#Ar>8QL;0{1eBWGJGCCCi@nnM8wC7qMN1SWo&1|K9A#RZEhUPbqJgi4$8l zeQU>0O|Am>k<(fmhNx7lek~h23b}Bj-S_Kx-Y{6Ehf9&LZ+x35f4VrD!pxu_&#( zFtWFu0|D*fcX6H#MZ&W7=pSUkAHBw7O{FszcONg!y)zfsYpQuSP^<|L68G^)ks^5i zC|0Zm>*L{u)F+6rh6ZT+tPS& zlgun`vaz2d>;4d`PHK^^PO@LYOw@OW%Pn?C!tjs-Aiq7rb5td+SI4TG?YIZ$$ZVft ze!~)e*GOl_(MUiJ?J;Xj`K9~#0FJZA92!DlXMNLx#SfCzn63^Na$JX>>FxNIw$;*U zxvfLa9@bw!fz=pz%&8#yE9Gj?FT@1u-cSF*k(LAOJPO)Ydo<=6Bpj+Ka6pJZpU(Z} zfEY~GPYe=aIGGyrCBO~wI1rh%B;Q35Jg?@C_l*ysxu$VIf=#DqAh~W`RQXM^q40}~ z?We}*%!fqwQLN7noqHUSfV^ZmQO%zTSKm~K5^|tOay0%e67lMXFv<*GO!8#DpS{vqD`P?sO^vViDc?u} zprAUocts5gGfMshSpDWl-w@m8`cx}THkuJG{!UYI) z-0=7rMF)*k*b(8vVMAgvOm_e)S)_- z-NWl>twz)^=(o0OvRYxd%Vx@x+NmO|rYzaLQEi3~8)*Gw`_$s~6EVb{KPtxv!l386 zte6=rU$|PEkPNy-xY~l0Yymn?gD+l*=@;-V7BDjTY8M7Frr+0PpIIFYqo*w;0QrQE zDA(Fj-`JKPA}$q!^~LzfKEBTaIhYux+)=QtexAEzTX318we--zRb1K< z**#;U(VGb5A!4Pf>}GTV89+xdh=kc$`YR?%2&0XpsL=THEICXmlV1)nw{8l8Wvw znJiDb85RQmHX-eH_{RT0ZNd{Hf~DgqEV?^%rabcjCW5ttrZif2G5>lw_NgRaU6yLkH)SHVUYo{E@S!>O8GbmUfaDD~LZ zo?GXm{k>(V`82Vu=RUm!HAUBP%}Fv})mgD0tX+TdM1)7Nq^UaGp)Db?N2G1>FUt>P z18&fvY!rm8q5?4{E0`5q)60$8atM!Uy$?crM>A? zZ2)J;a*3LBHr8vpEwSQ(c2X~|5KsE90nQ;DN55)f^GBh}t4TDyGXv(7VAN3ppnO{l z!Lmnl^5(t=)(}Pdy5ecA3RE(_-8A{3bR<_ilY5H&Z2arqM70qB5+eE;pOHz8N7m8gX8Mm4B5< zIzQG-u(gD{X?(90?~3}+l!7D5CZgeLR-y~0LO5eW3Qu*8h=Z8hD<{mCb)c0lhS0X1 z3rkJ%tmIt}a&pb<{}rVoF8yn(78Xqula-RpR2;Yv=bIkmo!+FHctX}TT*c_rcmh^8 zo*!~pUy#qbA`HK=WBS*tv53@qAZ>ouMF5(X9A9hs)UTLa7r*?zW)0SP`bK`u%K2?< zfG)rpyTs}E=#A<=M-5i(jeF9xuo&z!()fPK3Si~VD1>6G!ZTsURv!Cqr(sY78Ja-Y zuXibFl%|~{n#j>juIc-``oxKH35*1q>YRzS7l*UTNEdwQgIKhJsy8!-sYmj5HAvSq zNdMcp<7Dv7ApNMbfAY$znV1$by-=ZtwmwWcvc)!0NL$Tn$u!*B%wSPDC;il4h8cDWl5md4UPuGfgprztjFI-)`mI2EUIg(!Fh7!1;gN&;=t#`) zG3O2iNimG7us+45?5I&GVwl-VsTtH9x-Y|Vmi6GVgPr)i$-#Cu5c7x#RtRKZF&S2{ z(@hWLq91g9AmLmqgaon`0x$T?gC?C}V5qau+~3xqbkDyLL46$Bn@A6lC=36en?(Sp zO*jw9>t)CrO*pS$n{Zyhy7GM6@EwD7I_z$M&=w=!5(z9p(LzK>2q&3~B@LcT$Rcsh zgQ`!-ejC{Xkxn3)pFnw)D}gq-1W(?qA}KfNQ;F>P`F+Fp*-V4w^+?<~o~#bEIWA7$ zHDBoZ0@S(O0-QOXhjm};L5M{qWGlV<@38d+1aqzw;eh-m29qi{Twv7%oTb3hJqVdH@ZFDxDT0zj{pQ&o2#~K! z+ZftA3v*>YT>qyL0?xi$A*)r&ITOICtsl zwI^ioCdK^MfLYRY?J6kr`kwyAt3zio*ra_GxYehzQ{?snLm#-e1^m^mJ+k!U`X5(~ zwcnm25lNj9pBEp6DTi9bmyXq8ax~PuFNHIi>1YQnEM8EoR!$vx{RaxgD!TgnZSI(B zvXD5rSw0MnnRBCFvHA`Kj-*?)+|onA9g~+L=fkl3f=+F3Z~@~y?lsW98>Vs!;+;-u7;Ep)B++ly)6yjMtpIfnd=hZ8?;k!kPOsRkapnzL#l@Hym_f*?N&B^Zkn~qrRW<*A`EKdyX0v5AExO30D{W_V`JXZ+Cv1 z!5MJF^@vcyC*?7;z89`4d#d&2G1gG4U!RRYd{f+^)LDS7QU43jq~BUyg)Uq<^8)|n zWa$-dG+>?El9Q9FNE5H`hpNus4N_mM(RZH3)+AFlsB150Q*qS8GP^ag^LChToyE!L zQ3Hq8rOSRhzTI760qb#_jV_jDFnt`Y(|%$z=<^3U32qyl03*%EwCEQER}V8U2#C(t zmEP0+ZzTBE038B41QLrEIVwB`u3ktG_;XIfs{sCGT|XCO zn91K{rYW4BbLr#NN*ug5VVwR?12D-(2JXCB*wnLVCQ8yh%j_3H`e6-v8aV)(woK$T2~1%ej8 z_pKL=Q`r*qaH4TBfqkt*aq_TXDDpc8(^@ES#*|MEI`pvOdkr8=IK1B}MSZ*SDtS}= zqRLOno>yPE>z*|fzhd~J@rnUv_7y{qJ%9ny;RVBn59z-kpmouoy%m#T@Efl4)Yu{A zTHrHCJ<%dYI)!w2wPr@jAA>@I)D|5?84ui8);w}1srWYxj=2Wh2dhKGABK03g@&kW zSL87SlU~9jK>L*jw@TV4j=EPlD2HC;pz3ITl_QF>yV^79D`AC!W=0UHRefUs;Ed)< z@+4jQreoR{XZ&e51DsKDPl^;$!)JW-*(f&XoR+Y5aD`;HCr+wkjZ0n$3LV3;V}dzV zlnDa!Hn^AzNjV~=1J?Yf4aC-W4RwnFkx#lG-a0_aXgxp0z1K;%U<7o>H?fmM-(v>nto2(kd1ZWu%`S&k4p2oZ zPa^%r*07cj->?=(XRCe1(@6gZ3B+dmb64QocE#$%8Jm1)gpFeLep&ZT! zr1O;(75!3^~~p3J~h zo=#`(cV4P#?B?IuiAvrcr9nAlHNWZkitQO~=Y$(fD)Sbrk59$LTvD>2mUZ}?Qz@l{ zT+*hIMO;MW)wsn-M>qUz7>HV4T`}H9DKrm{Fr=oVkYss3_8Z!y)=iKTD*+X@mm00g znbMK-qsaj`TB*4Pvm6foN1?Dc%Ni<$Ss&kGLN7m1!O8dSAj=gCMA?XFnx<>JDnT2p zfdg%Z^&}chfKnvPCWmpDHMi9n!BZ3P<M7$pgiD*u&(!IzO!kqQW$fbwadVYP(Tw)OLyDtD9a_$&Rii=QFz;0| z<0gwb5IBD(bhZT*_12J>d?xff+(rc7Y$Q37bM>m_uO6W+nR<4x}CM|Mn6X zi;%_2Hb6Dl{CB=QB`TBj`6g6!Tza-?9=K&13A`le3 z^u^&%KJ8PfYe+P0@C@lJ!h$OD@_&=H2J%C?Gue}y92#-Da@Ho~Q55QQNoRyo|1{Qu zs=+9w&cTCTk^GGF)9|$3n`K%oZY(^Ca&ieGfhImcrh3hK-lb&|q!G+X(;5h7kq?Cc zk(3>#HKMH`nrxfN&|dgJuLx^Vzl3_XyZpouMv_`ZV=c?d+2}^|PZ9ef z#8hH@dBrbCQ`hi+hQ~gvxGSkwR5jc8P5*O#-PiMnzMQ}K`t|(etCQ6y7mo&hIf8*9pAs@~fzAqAhfQW|&#fCD< zhyGg0{W8gJN8YMkd~=wWeEy<^-oLdtA7W2ZuV`vznRV`ZO}k{RP2&EpOlMXeRnCAD zppxQ~VnCi;WvQL^Y34xMjf74bi~IrtQ=QI0C5;XF#gi&RDVu%Y9As;FQy@*;wGMl; z2@-1HT>*j-V}+DkKMM`|6UNfj;eN{h^bq_RB!RDdz3nc>>kTNAqhO8gS45Jl%SW&>GmO^pf!cud|?%Ea|{H z4!$N8NB*2x8WTH&E0ZMJBpK+)6kbU3uLwf7^9zo&<$Kbk=!(ecAzY0^$sO}L@ucWp zEr6`}Y5}8H3yA$E3jo2;`%f@b{SyqK+h2&p<6-GeG0|jR3!@eHIE{*`Ui;tVz@$mQ zfkyv0fE;iD+OS3oUMpTnos@EUxgq(8isfV&=G)dP3&du{wMZ39JA4?>MevU)qTq%c zEuh5_EN*6L{D`oU)P@9l$%Ggy!gWbSqP`6ZGcUw_orHlANd8=e6sJhV4iMRG*n>{PRFboH880^alB{9+kTp{?DclrcC{NTvmK z(_hWLC*H*wSKeob-F~E>>qvlmnF~3@)__tlGzOGE9@;M@7~Txf)}1g3!L>I@AF+(a zK~(^2;U(VK?9EVUHzdK*-C#DezjD9oK2cs?WnuN($r9jxRi{BbUBbg*85iKbxenmI z9k01gY7*d{e#Fsol9}FbKg`K;EYc5@uN}V0+(uyCr?_C~|uw z_83LnUa+E_J!fOM!5n&}0&3N(N*kKB$jNx#IV!JC15ad6hk2;u}2b*$uAut2@y^1Vw>FngAn(DAfT* zQfsX`bnl^J&QD5qj;&h1{?^M|`gVR?B5%(_ui<9cu#C$G zObO#(psL&Brf*;+*~*y1(=+KDctNG+0XHhij_uHz6&u5;T`c)viH3#~{kGeiY@%bY z);76fI!P=W_@$1Sk}N*%1RP4+#h&$XuEx!yWdY`A7-Ci)0tdaDMI9XDvS{XGIb%HQD|%;kSN(u>W52+ut>$jGUCU!9A6zkC{gm9u;`}=)&pVXyOMQTt=zF4% z4=oxM!8dGYb)p=plZfzPe-FP1G}QZqs3s9bb!{yOn_%-9eZf=_#er5;pfI$=4IrPu zGDT7m!pW;){Dty^ap--fry+%)XBQb8h&24+M`Fm$7Ur5{M{o|d_`U*F+{tDMHq5>T zmC}hJ9bqi6f%be*CE8mck|TNVlcVrOtXx#|Wv4kf$F(=#I7hN6xT-b;JNYm3R)|nS z!NcSXLYDrZ|MX^&8@WJmVryN1NTrQ56+ga?XQ-+gqaG`~Q^tcE-3~R^h?Q#8Rc@%j)zgk)O{1oAM_H;2S;O$j; zrI=fIc17pe)b@Onvygm(?hDDlx}te;ZuF_S?2_(qxXXIaJAM}&! zA^9d-^fk+hci&ehg^@RFacF+|a%sWgkHdIwAa0(Gowq%Pa$ZrdEVUP(VLnifs(mjn&vm+XidX4IU5PjGg()@CaXV<>0D^3-Idy& zTi%;mAqV~STS;*zK@-qc&KCNyda5eVrB+x&f4wWISNfW!XuhagHn-ZYDEPHG3!2Dq zr?_B2HR|0pKNqQ3+N1|V^vO7)R8DXi3@ScqJ@h9dRa!1m9m}<8f1edr@B1myBAjp_s>si(AZv)onJ-ZQ zNA-bxbkHfLs9RudOqu#_KsAG4~_6X6w zO<#Ogn82j{~Y7)BU9U)0Cp~$E>3BPnRlc_RX{}f_lj%XtC8GjE-!hOFwcFA{G@1){Uy7lpHiD$4hY!Sq|j zhYMj@(w-XoA^}_BeKZ0tb-F*>1ub`6o;TFMdJ zT1Hzg3(uxU7TZR6%Z=UcBUzX~O{S(K@n)A6V91|4XP5QOFt#pJIxy*;x_u}(H9)x~ zmbXa#v6>@We2E>BU+O`xIxFqAF`GgE8z25-axHz~;3+h^sc^NaaR|0#X0tvy@^TQI z%D&?J+@(nxO+hy;!xHV7zGQA$!;N4KzTdvgkIQF%m?W9Tt874(&e~ z+KFT801mwX4o$dV^>Z50N6GQH@Xzm{XlY5g#2RK+2!rJaOE3z=rcv$nzadu(=~5DF zRc8#6v1?OoRY{e^E`=eY8FHv1Q9hT|!cK^oek#u`%m>xu_sUffKIrAR$9jU-ij7E% zVm{@F?1YP@tFEBFD@On7N@x$&E|U6NhDw!On0YRQY9NYHu<}7a9kH6;qJ+8hfh@q> zp)vC0g00=0t+54CZ#Q$M>bNtKg_D0W6)%}Ld$Altz8R9gDZN~O>23D?pkvprZc?}Z zTZxwAP9iX`EyYIVdCTC}ENgfDubzuhi8J^hRp<>ubj)6b#8=xG)itwev=?!ZMUSth5Ld3ia+uoeS{?DZRSjZ?L(s2mZs^R8bOf z4SBqy=0q?dlFilJ_zAt@0?!Z6{Xg<8C4wR2E!>$|_J^+G*75;0J~x-N(FqoFV38&4 zq=hp}>o6iHmHh6bDxgi5fk*@nRRRuGa`8cxg{Ccb{?4lqzo|!9-kW6HsDz5Vk*EQ@ zG9BYguMNAp_pdm!Oc{!QQkZLHo1<5OJ|uj`LMOQ!1wFP@zs2+Mu^@AfU-D3f+AfIg zYWegr9X3yTr<#jC+obsI1MmfRSB<$a&j$F1b-Kv1gT_*@mn+&WUH;`^rVha(TvS6tB zu%~POAbCVD`?`}p(GXarimiffcs7iH_8cF<$}nL;DEfR z?Jatrkihv)(6OM~O7EzuUNQ&SaMDcIj_p=7-~Ap^LX=MpR{0yEcB;P1BS?wosVk$K z(L{OH&^IMVeJI~c7lw0vfWUfhR?&pr()G7m^813$d+6rsrc8atAV}SLy#pjBzv2+$ zX(UHj3x>yG5x+V62soMzp#enN-XGsdS4y!q{Tf%Om_jg&z9^uc)FqEp@^OVAF76Qn zqHRb3qN%+Vp5W9*5)SyLjJ?@^{6-!F{bRu4^lW=5T1m}N3*@?K5Kb0sPr%iZ?@1mn zc)YkxGG~c^iibIb3X3+{$H7O4?m=va1cH}NUl zk}jLmrpr=Ce=QB_ACCV~rW0iLbcnCVV5p2u-^eR6_vyE+CL zefuObjNifIra536ACp-xEG z6Vw{0Y1cy_!;NVe?qgDg27cxSC8I*EJdti5xdkSW{iI=OOlT-#M_b7{7`=o$zj8*H zB3bz?4;on1hg$iZY~sA4SK`iRV&1ZJIs~y`g8=S~5IVb_C`d^EH6b<_0z%iD} zz76v17(Xy)rCr^vX-=<7)4E&R>M>mJRjmtJGZl+3oTuMy9idk$HGd168}NP($|Y98 zCE>t#b&uUCOBsd)F-~M^`8GI|zXk1{cP;|Tlv}X?e_4*Z!XTfkWQUV`TXW&OpFkbi z+Qtb%V*hK=P0ws4s%%hZ<@AcjpAU4+N!O04$Jzc90e{4^s^|5hmkfg&l6gWJE^LEZ zmuCWjhg}zM3hfsDqXuBG_b6nv*E#N%1F>GOCl-uc5bOLkJ-}KyZhWMjg!V?Q0hSH| zc{lxB)E8cPilAz4o-0>4PFB+px3qDMo6+$|)48D#Z~WAOroYpwYX!6N#PZ*$!BQU8 zzdAXIcYc-Z+b~H!m)VefaHfur-v=xl3i^t=airtp>J9`%0}v34O>h1Yp@zP9(ZyP9 zWu#v4opj>nyAKRt7)1Eq4u&*8I z5CYO1*CxspCN$Kj_AG8osn9Tpuz5SLFaXt9Y{Rwqn!D-$r9vfZ(W(d&Yw{a_G(ZEG zmCygD25l^JS@o+jD;zM|PAlf2>qp2gj_X^93}&XhfBkm0kGr0X7`4u}yjn`1l@2ED z-ZbOfb-;sMrXCXa{W?-r;TgA&^t~_E`>?nz8Tk|#aQOwd&x{XgR7d~!!TXuJbn4vd*=m0;Y`+lvbSLvr8V5q!F9bA zS>J9ed9EX-JUQqdNbfv9qo}u9`V|?)+o7b!h7K|s?x8F*Ls}`*fZ;b3t2r_4vjx%r z{ne5Py;2@js(Gy{$JJh*u3&ZFtjLvBzNkQVU&6uHF=I{T>?wxltNw@LLurnXJGBgp^bJ>kvX=ee5zbvBmfL#{qDq&UEM$h$AGE+V1EK`6Y&Y+>M-Y-Wzm_JPwY8{C!*zq|ouY9Zm)FRR+L06o2i$v^+y{syy(f z9|&k^W?H8J%QlA6qjNZjFdLePv943p%er=lnRfpUGwDVLRI*Wfk3OR`8lbId&~4F} z2B$wAVBFmd*B4NU7YJ-10vi@RtcJ@$M&0VQs3~9@VdnKgiVuC}>=5WPa#R!^s_0p8 ze>gs%x0gglz+qj^rGQzHQ%`#lezUHd&UB=5O!?v9Y6JhK<$cwZT1kp+GNL6F#gav* zM}(*J8`r>8Y;8ot?nfz|7(CtWJA(>) z-3MSi&@~S3zEsEB)3jTjVBXWDWz7g&a60j6J$lspzOTXi=JKE?7-Y|1mWV=INUMt# z_)&Tp^E9J!wmB$?KtvB-=F5v8l~Jx9W!wOhN>`l{nb z)DCqE`x*8k_{jQAWsOr^qWXpm#ey1PSSjM;2Z6_lWb{i-9qTilZuI-2=cD?^2c~-B zg{v#i=P4us3%;YLxu5IYYAXF|w1L#c#v2irPoEo+T!I!BE{aNGr~WAN3|)^e4}T)o zpS=^Z2?^y)nD^mVY-Fpyg;=IMe<^zZhT1rqANn`3IiDr>*KbH=59s4s{=s_vXkKHC zOzf8N%w6^RyM9!28hAyP}uow{ehqXMC^roM+#^m=8Hgec} z|H`G!eIqxuq4E~h9M6(O*CzVX9d^Z=hVjQvR%2XGyvFDOf&Oon7%c*SAa2DKMTJH8 zEmAYwHoFcd{4UuZM}mv3D&7j#m^BsSS{Mh!?yMYDy}*2c(M`Gd+7%Et2bC7x4z57B zoT%5u+B=CyN0#zl#1s%UHrJ)9KC}*_@Y)oF#lPez?|bWkcbi|*KJ~S=Sk1v?Q4oJF zoJWr;7k?am0v>u@maeaad#~E``w^CFilWte@4_b}z!o;(Wl~~||LVUcW zKkBN+x73Y%(f$Y_>kW+DtqxQtTd+IFjEM$D*OswHA$ZXdxUUUai}Xps&E4K(f%i z%4kxW%Z4(Q+eg7AzWc}Do9AM}$Nplc?7#YpNOfsB77h!k5|v@hRXb7&DoWaaowQTx zQt7j_hFjt`6c@PLOq{M4TeA$+l5CPWl-qT~FxHd!cOtZ>!3izV4C_nZDLyW*S5Jy_ z@a`ieXIc=*G=m)H_x+m=9nX?80sl`NG4j^^McBVe&P-znSi20BnGv+TySN@*^}4AJ zi0N^+EP=>fcAVbNWnjlprQIS|0P(Pwb8paNWgc8Lizh-9T3XQ@>u&r0IaYmR#aT+~ z-|}5u$+%fLS74G-vg^^rTz}}}w>hQ9hyC$Y0q=)I$@8_Vj^|rgwfjR_9xH_?Zo2De z?+XnEarX!Br<;asZ(y<8tmkLD=W)WsIIOy@$>GYZ4)5napsvML{mkz6KKl7_)hi~! zcu{WX{4`P5jcQuw(P`_%qM!88vQ`-Q{b{yx3FVE>(^-+g(_ew-4UGG?(UQ?G^4}5` zQ3Lf>ov&QVYaRolI>wHy$J~m@F`+p}Z=kp(nHn=4yB2dR>}fj=G4uD1U9=A#ZE}6>d*YC?r;2GfIIR*3ZOO>q z5liZiK2F;dqJI~L=c+=~i#*k9C_^n~UZx(;-baTL@)rA*%o57>?z8TL^Qt|Gvw@P; zeXQdY#N@`=Z%AcbmBA9j8_&nnt(sW^uj~&us$+lizn}0shHhXtCw1`*ds816J$>iX)}7k>B?A8g%cCPuWzsyb}geO zLM^*SOPx%)cVj$5>xMs>iT0SvFSK`ld)AR4m7imIFoX-GJG9RT;8d*Tc_R3%iZyLE z&1e37J_WVeTn0OdEu%+fAZ;~CH8?qjUH^}UYm?&418h9I_nGE}_SwhQo3h(_FJG)| z_Ekp`k9h7R_KpYK?V3R!oHL2|&Il^Yr`+nDaC+LUzlt?G=`;APk~0q_ektSB`U5O} zZy0Ms{nyDWV;HtI#DGP&>uUQQi}C{jfUale9xnjbO=xQP{jmOuRdfz3!!j0qGF8Ev z4m`DAFlH>m*Aup1tuNzg4cKbe`q@1k8F$a0veh0gf4mq*x!y;44Ma!l%~pFM!U*lX zFg)YqmbRM1JOOSe0tgY>H3v9S`k1!9EN1p6t5l4EmcuFOpl2z(U$O%d;|ny$f=@xo zt-{R-FFkE|M)S!1&r%4io_?nrHHcpGJ5sBjY0_^Z*2IqZFkRht*0x(=8J!e$-!blf za^>DVMYBh#H<@1Vd+C6}=q0t_k(1B`X<>HveI+^Ej(@i~iNXU3ZR9~Hyoj*N@2Myg z?JGO)iR1Gg)CLukV-+y$e{Eb(Pei_@s&s*h2^BkoKOiaIUE(Kb3XUe_fE*ahY{vd_ z4!`dgrTWE|dLW;@ke8hP*Cm{)a#Qa{5Mz`-{o-Wm(+%}l=(wp7NjW%>JoJpF1R@6ZeviPz&QwS znCG@ICISgc2iBCpQkJqV(po9|=rDNM#QvTA;qR;p&&5c)a79W=rCYmofg^#P;p>`+>tl_zge^8 zdak;g)OxKbka`Q#J4~*>yy0kdLhB6TS1dnR6!S$}s2&&Aqh}8eG7|*HKH#WAGp83d z-G3x|XCTsmX$T&q%}3x>i|r~fh@VM0PN)Tj^WSqkInww>Vxi8-7K{oS>a`ui4_QznmV4?p#&adj{zAe+Pyk_$=7{omFc{r|Cf%Ed*Yjs(PoX)2~A7)qk)V zTv#DnWg&J_;J-a6mGPD1g8EX6Kex1pJ!b!Ptf4nnt|H_qjSY@}$40k-a#7$y%^4{~dNHKvJFBTCIxc;hBdzJ?emR7vvw+we+xL93A!zN7WnFO>-yhqS$qEsB(7wD(!_PVF*c5oiTB!d)r7f;4l#fx^9C$_5UH@=BLVo@s$DE)s zOYrGWQCyk$x85*S{nJ*x*=!50D&+cmTpq3j9%hh70}g|yl-9;2+SuO0V|Lk`@ZLzl z1b<`&0TGs%KLvey;Kp`qJq#jbbUU=u*A08V(J_01D+qnHgod88d+_GWWP-8EDa$I0Sl3-DJzA3`SWhc-TD zFNbUwPX}CiJBuVG3;nXUtlN}FX*-fss9V8_?a9{eqhq8nz5QU6q60n+>Iy$6ZmP#?LfbZj%>r$oV9}mEXvmTT(x` zwiL1Fg%|4^(7PzZG)r=qZRlW>t%|0?GOr@4WgoqxJ#mKa8PJPh-i^GW2j&j!38asn zl64JE#&K<^Zx1|sPX%z~tDZ|(akH&sDM-ame)y{`dH#S+77gBi`t!|SdszE(o4)7W zmHzYdiTBfRk^J1iRn7AaBwY<0uOc3Y)7LTJ)v;b%d8Up$@>3CVhi;8HnTP1? z#*?in?~rbwY^c>GVN)?k4Uj;#9(Rx$<*8D2=8L zge7M&g;$V128soCqIA*k5EbR-8oDdsBA=!Mq#(-!_~9Js;RjY=i^m@t-GZlvT7`FM zzn#RW&#RlcFSSc3nds;2D&D`vNpuSgQr^KhP<`}q1P*H0-1%freGgwAwK%H8jU_sF z`f~v$;(qubr{EX^{aEgZ^-i9AX%v3_2`K)8nLfKIfUygd#lvX!ATdW56pPqm2vX2+ zsgKcwGS6>+5>4#Z+#|sh=P7!B3}y4`e-04%ouq*)07-ul-=rR7qe1#iv-JR zLQ6F~Ee3rXGCOlGI{`S=!ZRj;i;T@N>0M=`$fc7tuQuTyftr7&S^X zf4W$6sJ_cX6q6S7KR-IQYWXvt&@wuh*0uY^{FHl92h3lTV#`k{<3GyHvF`Di1Jz@s z3U1e72G%z_YEiQ+8um7WMRM1Hkd4T5#A4+xL&E)KWA!cr_6Rb&W}$(9m*jq6w``|; zv=W<&gAkZ z_^4!;c+~j*Rvo9p1!sm8OcB8ov3ZcnB=M3D~&vQ z|MSh{XvagIw=TMv=yJi{B$U&v8rp$g`MB|X-tho#;qjiJG!Ah`x%cnY8xG`L+p^UT z&-?pIxjzEW=d&G8=d2wa?puxJi7t(Giop@Z?!U|?8ZDxEkx6rpOLD{A8&$>Q`@XPo z2S!kod$1gnd|^X{3~COJpeV%Rcj8}u9Lzz7{c*oGfbi&e+Bh7FRG&e22@O|%oHh{f zoA`i1Q&x)=#$@d*$!4e@cmXAS6V1->O$r<$gz~itf#S7_TLW!Mv%Cp$*Hk8>$jFa- z+#kH9tWJy=%kl}H3^YTT%@?b_%{6Qa*Un3WN-oUnKX_#zoruzHr!wWB4){6Nf4H|P z;|pX;E^87gy5QvJ9mD>XIMDm8ec)Al9owvapVUlLi~PgA4pe+kav##Hev#CClHNcU z`4`oxa);hYz>HAg+G17d+W$)VK<~)fN@%`+%5$R}>IZLn-Beo$TFI}#q-Lyf$vJo;s(Qp{Y2g<5HghusJ^NaMC`uX<6G{)+AS1dW*IeO ztFX>~I!&!%)H!XF!Q6X=>8?TLfw<`*N;s>5IC7ZxzKELDvW(qLQq-RW4Pd`gm_zhj z#8L9#xGCLMaeQJVfzXaOuEG&DAZJyx>@QmfDBBB z2<2?mjjF+c`tEQJ*#FA|dT=E5HSrWRFo}uk1VRbUiX8-ZIKCnQp?#zc;XcMs44!T$ z2L~ULL1_QhhG+q;*kjB{K-H%;KwW)z6ErCGlrcbFkcYFXYe3a7!9$-5U5fPStk#q< z2&W>6&@qFvLXEtn_ceKp=(Nuv2a5suj}n>!Y*mI1Jdqf$j3e>ffTCgEF-+ilL_tOo z30HO?`xuDoD>g}tqLCdF`|j{p#3>XeK`02SJ|hSOm84fk22naPVhJ&vHwaf&9tdak zt91@LofOP`kvn4#b)}YywO?T^XYly@!f_m&AdfZ|7oF-MZ7nvx6mh%FJ4bEn`E(zn0ZU$i5mk%HN^K_F2^3bh~O9oy&9H8Tc5 zK%PO#L$Q1uIdt7Cv* zD0P!Dxc;qO(R~-vsdkYB1P1aut2!Vsgzl+*%da>fO0A3`c+b=zc)|ZOgntdA{1@R; zO#tDyjsGV6Q1?Fw|5MXEc~+Nl|0#qDM$McX!o76qB!OM(q%&ygn)fur0 z{}0Ny4*x}Yyr6+*CY)9Ao>y)}C+7BNgWD6}8{BtREoBR68qDkO=wu*$3DRw$lH{Nu zcsYRm^i!yM__w~>|ARLFHrs3RKgGE|yD*fqskkdd_;DeSUY2B5-_f;MNIsQ4yLo*0p z{oYya_q>JBt_U28`g`iB;5#!`piJq|Hg!)7w6KgBxlY89jVKUJR$;^Be?8Yn@VL6u zGhTGa?t(I!D0#_0)EECb?LSsclQZavCO5jGcEP5Qlaz1tSlM7IiZ*HHn^ACv*DLu3 zKI@x2&;=`IN7^2y_A!6kAj79!DC7=rPnZB#SU3?yU@1zAFp`QYk%mkDS&l>rMRZE$ zS&{&1161lI37|G04ZQ#HY9vhRPd<{{xj){=-UR*dk#t0y-tTHH^$);wX!8p*5XH3% z`8X?Y=O*~^f3f$LVO6$G+b~K>cXxw?lyoEEltiWq z5!vJSb<Qd^zd{+MFAM|8s&_1pdE(zGAvltl8%DBq^@5SLHXN)NpcgeZS84D}rE zzQK?auE&HIG~>CFM5=1JU+Q>_A#5S3(-U{Ub5V0OeHT?ZBti~ z>a^S5+$ppQh~5&fYL^K_Nu6MA=m-oHey|pAQOHxP@>=-NL*-mt?ITf;cII$oNlXkP z?&B;=e7W(gFd^ODYuF0v=Lv$JajciOJYXhAJV^ials&Gh z9NsLUO~g3nnbvyys{I`C>H}WwVG;wc!G_E1<2uMY&qVu%3&fELETS`Bb8sgNl1bX$ zPiccOdGmp6?YYjjNTl&Jl8HBMznDNDR?gO}^eEy1dkWqCgUQu)MDm0^9;LGK8&6Eq_UlbgCNygnQA8?&&$LStV zD(-nUks0?TCa~Qh>{S7s8?^7vA(^|BBA(=h2wFmN0)lIVDCOsF974JSgLLClP&m-+dJq?z^ z58*B!b9N>0rKdtb&r)+y_+rIx+|zB-W=fEkk8|h)D>#ccF}H&R1Do)cGi%N23KCa1WDL9tk->X}mwIr7z#*$}03p{5ee1*vR`VoL-$FHkd&p$1 zF}NQVP#>F5T6hyadF%p3*dbkk9cT1amiyzt!`=yWG4^HE1V&cxrnL3R$e4mB5m{C5 zCla3sSF@tp3UL?BMFkjgFTK@ZkAot7e6=~Sn=u78soVS3q=u+llXeZQ@f0djOaYT7 zAN^&LIgPmG-l}n-r2JWLKer*X>1xyhYH6(h9Ry@D*MP6SjhEtqVQ*TwJi70)#U;|| zc262V(Dd{-u9JBt;)}|4NJu>r3GK(=D)n)#$zyG*f0?_j4kInaMx?}zRErXQZ z%sGEv>rosiq)1k?o3)2NcQqw$*IEY!k}Qegp+n&UV`y7{4PXDA&&x-nI^p6Fni_`7>O5 zb5dM|dGCn5ce}h~*;?EGRQ4)gqdwBgRjVN_dOY}Uf>-uMy3!70Va$ri$oiOve$4@- zmYf{ z1{#d+N6;k4naz~NRVqO8U*;Y=d+AzlG31?ZtPO4r@iGywPI?LW*6fB7B(G}DJWJkk zz;9TlMqXowP$yZrq9b(bZ1>{UTA8!1xN+yFCHPfabzxB3n{B_w*Q??NW-(St?IX~=!bQC1i`xQHO&wMhF#Q_f2j{bLevkAy{ zHG>H~{j4_*?i!>FVs5%rlnjEcY92I%YZeW2i-}?2Gu#^-Pw;{zypu#vgMbc8KdOiB zD0M`}mpOG&-@L1s4YPVzZCBCI1!hSh?E3o5z!R1^eXESV=J|y=?wh(Q;8T*rD2va? zVX7Hfpi%6(4-M*tgBFBMHIJ=oR1sMTUa)knqk7Hs&`gT@3u8mV5XYdF8q}hthi9Fl z@&zx4R^j{DbCyye7LgB~M1mOiup>BpuY{g~sK9NC+kV6)Xl;3Xn zi=7jg7O%@=7~(0H4Pjp4L#Oxz4iA1rQCA$CueJQ=WPGw>7Zug>i)8+D6U`gXbqiM) z7S)D-Np}SfX8Aw|v+xE2_C||jP+M^p1!ObofniOpJfSC9`lvh33eEK=+ivxw z=R)-SbCneaqUTZ>5?fM_V2GuBV+}tVFM4D?7tii-6c({3?t^xH2GG%mV}Q2#-rh4@ zB!juEpc_G9l&{x_`gjZ{gYcz60)ov%;N*lZR^# zNaP6z=jXtUNBBs@LVY_4I`zn{zf4+-tx0GSeGe2CHx*Ev4Ow{ZIHSB2pj{`2xsvZs zfIwM(=Xj-B=j^a24|P>hUA)jdpZ4e*nNEJbI5M#X)}b@2aN`NtMrE`@izwVV79=*Y z$VTX92fn8pIIuF@)NzlT703WvzJP6^{}PKxc082fmPPed+c2VHJi(U9YRnQGS?!O0 zkE~YFS`&33$u3?hiYOC%pCl)VuVMw{Ia z?U%Dlz3q8WD9I!Tu|XH8$J0GDi)7wcfp-v4$V@5#vx*qsg57rU^x4b~KlIt$bk#hE zKOC{j3^Sg{?$9z|76OW9!OM?p3wJuNvU|Ec+pOz=ibDL@6%Hj299pOTpO`m0h}NaT zEf>Yh*)+vtU8*$vtQ+%#E@qQ2QHiLR+@{CWHxzNQ_8IH^T@a{jHmvfi=A!~G>QSsg zJ|hyD0erTBiXNE&1pKyoAWB***RF$)N8<_Rs0-d-F$JnCl{@T?glVQM)*} z%a_W!X`*!&6wlFkGC#dcw7@#;^_?>5zd$_&uo)(Ux(>V(giN;k$<6@Dqw%o|98m{L z)cxT2x*UjZX9Bir7_>C6z<5egI3lOM%yPqFvLNMx2|}KQxNa40%`h&QNSLTp(f26B zWaB_zA^}T+C_O{wD+_~W?HBNEeYgzQSGI`B(B{^bcyo{~i1CP8-pDe&)_zZXWRqnJ zmR#ZD%~zu~P(`TQ--!F6vYOVE_=Zc<33wwfhj(N7%FZdftkfgLYkT<*3H!)Kl6fQZ z8$Q-5-3a%gQ!_&*vg$H?pI9JCcvsp>dWdY?Zv#wA8D3#Nly?4TQNm&yiXWNw8GO;A z@`K`Lzz!m(79E^#+Z%51B4JJQLg%*o?3razx}%s;)YBm9AICSoFKq{h7Ny^m4qTb{ zo6l;9wq;_Hi1=Bzt-w=I@6hq>&q>G@0isjMsk>1{{D@iT7&Yy>(lPTn{E&fPP^!vL zP=uNS1#ct#i>RH{#}j9-;j|9^_fMsn(_MjX(JnVVXy_U4gX)?$-CNx#!_Ua|SPv72 zno)d*fUb_{ZC85hncAHw^IT_aGQHAhg>+H4I7~6?yW%&zy^8V8l(p{2>B0#Acxbgj){moH}ZKroV+=Vj2UfT@R_zWv_89tH5=dLDWcO}h!2|mCLOH?z9?1-^^)mGhGN})r-hp)8{ zTfO$KiX6&zc)goZc}{bLHd4iqi7c>~y8TWF930VGsDRFm$JEE|z_k%g5?A zoUFPr5My0LN+J}@t5)dzpZDZjNwY##L7KALK`ch9&}l|IxEndP=-Kx+>d3#9>W`iq zFpKn~9IOvAiLwx%ouoiVkuLdnoG{l>r9(svo+p_UK0`@9JT4@(v?nT&!`_<9) zmc#LmdataeG4eLlr|`@+B~(NtHBSX&@DFrqU+CJQ7q--hA_Ub`wfx zkL7D#AB5{EtG_?WH(AN*1CQ|vZw|An?L`;h|Aajq)V(~;vZDP!OkNtyy-zDWGKJHl0G%|f)vGvL#7waT_Yld;}3^%BD>cVSRjE( z7*1OtQ2?VxuDD`^5HD23H+rX}cJv-1tU%3PFOLEup(CTGR}ds|qi|3KVb*ze!K4k@ z!7;riJYph@c)l8y&qo;X0md-ePY8N6 zVHq1IJu2t!$XB?X8#o2wF`$P!1(>CKL6!{~3X zu9t%pisx1jReOec&9WTc@@y!x7Y3)*Bp(jTRXfBI9w~*`L!)_i79qWlr&!wc@BFf0 zO^s!!ct8{hUq*y}6o9cR&e4?-GRty$n)7)o0NekGM%-0 zIZ`jrV9%XknHqdCPsD~&k*_fysdcb5CSMNAaaVbJZml@(+J483k;$bE3{?D=@mt1eU?y%7x3}?CHs)Ui%VuGIEOABR!T2|7h6t} z7s#pikjOoQ*aLRX)Jp2ib9aJ#Y=wZz#?-=1YW8MP?`R!j^IgIK6(QZetP1s;pfKIW z>%;x6cZAIE?=In(+=aErlu{`Sr*Y>;G}N*UC+qaEbAFm3(~QsY5DQV|wMLdRRufPE z`>qA1jp#ApV@(^tUnY4;A|6Bs7*&QHG_;d(rT z_7*yUdibSk_#ukaIDBuoQH~CK(>gD!O2yawKqE%ggo2}ocm0Ik5i%Vs`51o80RF}b z!HEj=5w~+T*A_TT(EuZIJgC5K^>-8Hl@yIiJ-V6NXmJmT9>ZjO4WzUHW6TDF7|p;Y6@WKd^s2uavH-;k29LPf~Gf!}-)0{Zx! zXC?&(3+%o`?GPb*hte zi1}i|h;@WTDpLDW!=j^CYP=XyP@>eA(lhed{dObH+F9Z`mD7QWi@YZMBeeav->*ZdjDeJvQ8c zNPn<53jeuXVVs5sN;ec~z^U97)m3%QB1Ldw_*nV*W#-EVQ3kqh#YD`P2G`s0S56og zM-KymkD3^DAr5iAcG&bk0%)mb+4ofuUFtNauHoT~S56WV?>fBSZ$*{Mf zc>ANLN()El`=h}3+aK8LVugoY1!Gt9IMTdV>k7&wu4gN(&SLi4xy=VHwuj?iiuXTE z9n-%#icyVdemZpj$0vDVJaAR!vt>-WgvAPQpvEs;>n^CW8mY9h(IAv&P=$e=ww#%blVgkxD{VlklghNh+;_S zb4FlJ@+n0-qKte!8@Ai6epiHE`5F6mUppXTWOR_pH7>o#^b@kqQMdHv=-X>xO4&XpNPbRnUQ zRGx|{0_Q@|GApSIYB?Hl9u@qXRD`czu0|zJJt3v_@6;GjAkUe|F}?QtXgggSea<_URN9rqOLb zcDO#mzu75V&=p8|XIcNL;+nZ}&!7v-vQ(RB&QP<`bDzF7P+fZ}3&cA5+?fzxX`NY%0 z({+N$Yv=1|&X?Dr%PVM6 zTt<$@mAq2@dbsEJ(hv7Oc}Jjs3AuiO|3CdWlZL*WD>(N~;5vC7^`FK4yvwViPk00? zGuo+3L-;S^ekif_3uUQL(nYR(y207_xs%qe_k{4J?#k}Ld)^G^4A>0G44Mp+44e%0 z49<)bNP3pgbL_(7y{|W-|GKGLE4CE_tW{Emzc9NuXx~FKcq;xM>o?|&@1bS5zxyaj z)uGhb|3Wn};NLc%J=}N?RUco$9b-u1idwH$agrb(_Fq8AV3hF3Rbb2xDUI6_p^|tK ztOnLzflH=ekncZ?O(7O+kHs>j@9n=grawg+G|8l*U*7&4d@BxEjtYJTtZSQl9yFOz z${AW3XB>pKlvdFW#}WdF$p$?WeHnzNkN=WIM0Po^y<7>q>}jqnpgA8bVf6Wrhah82 z%iF&x#dj!SkD3F^zu);y6gyx`T!(T{yrgE|tF&cy_*tEMvv{)v{J8x1{CNBX^|`pIwO6rV z5I%s&J;fBQKE59P3WR9CDeMeYzA@kd@e5!n%12-?z&(mK_6gNC#}_OIe`4ofQgjOl z$k*S|1`uBR2a^Fre%kJ=atuJjHm&ddnE=?yx1R`uU;*C(A>5b2U|g#h5AxxqwC{;{mtKB>A?{Q@&ahz=*zT0n@4_b{}B*iZ~R&U*a3bY5Y=etHz1mQmYe~w{L>aizl^|68@)U@D*(2v0Vg)b-< zfONVw1s$}Zf5mt;jo64K=r%_IJihb7caFHt;#+qbmjDrK@U$J|>p$EIfEdRQuwrRk zJBV5S1!N!(V!+!5g?Hg?ngE7@sNts@Zax0rH?D~Y`#kjQdN~Y%D0_HgVq;)qZlif) zc%yq`a-)4?e4~Hk>J9Q}SG9MBegP0UXH~}nnjqFw!Zr{KF2$wLf7_0Wmch{Bk88vN z3)Bchmc(w=xkgak0hY9}_vi=5NoWS6jnW3O=;Ir)NXRb7w_CLh<(jJC99VC$hLqwK zlYa<^pf$8v~RQzX0BV@{wWfO^+ylmp&JN z3yQrs_(?WcDGBNkdy-%Ru9rO_j6w$5J0xF0A&J_ew3?A|8zoB!9ZO0w+FZs zw+4bmDF;;pfK2;@VpG`lR+f)fUW9Ci5C;>7BnKyl=mhJ8%mvS(Y;c9B11wal7@+hN zQ5RtqU=FQYGW>(_^a+hv)PID^U-SXWFM#m00lT(DjPS?Xwavzp(0`NlFB)_VRZSm40>Q3`)V@BKfDfjt%|_O1X{9Yl!3V#$qTciJ;*+-zNVwWh9Hf@&n zPaO!4{4#jSucG}&J_0mg90nrbHE^W@mDcYS;&)^CKE{0o=i_b7?x+d;jpM&pMPN@{ zmzT9@>xVj)IP`!6%E62NiK@Xgk~q6NoAM|a3xxaMO2H-ZmM3sSTU3Eo2!zQ`oq+!D zCGpmF-&O-Gpo{v=1z^%?1BJ?G0tLo3r(gBsSJgcJeWT7Q+178{wg1zU@6G^dCkNY> z4Md|vIZ7MHTK~u;p`(uACDH#F$e?hztv}TOJ^m^ue?>H4uQAwOAf|?YuU$U_4BU!Y zfCC83*FQb_N8?c@3C5WdNSt5ye`ipjG;FJZJD`x?(FMT*&Y#-`#Tno|BNmX9|EQSY zfFA{lA!i0Ci6?=EM63O0y(|G@`+G+M3bGz{fbnEiH0mKB71N3b^7R5f> z!T-n?|7Yb8C@x^{|4T6Uf|5oBDDN4nzZK`-%NgKoJP>`!041vMM`GVb)epw_rt~@& z=pI3;e%u1u!9ODi@a6Z?Ylj2q`qAqB#%>~QRZmpGvG=3f{Tb#z9q|L1-x@k_@ZOTi zck;OH=+^#+MgS;T|3d_GftmCdOa5)nExS?wcSiz+;9olY9}obPvc+|Nb2&?LdOthg zT}wCR>`LKM;WF;5)&1%W_`~ha(JC_u=vLLWI4tCbPuKA{5tm1 zbjZ^Es@1{$yr22{%*nmz%C`Y1PpU{iv*BmF0!05k8F;=Vr*e5il5dRX%XRNZR2DT3 z(w`9oZqaU2_?uDyz;qkA&idcG!Q1ZmPv%!(H0BL;>ta_!0n4~;?fz_KfouU9%U6U~ z;kaK>uG%)3ek17L^!^4s@cuRpb#RLO)nS4-WZL>r6fmVs@XPhruz3-%K+~UP_q!W_ zDsJ96j1q9Wjt$UrJKy|tH8@(oO9O6x3#+*a{xN8Qy#A}y0xkVFrAY!w&EU`)6HtHu zqhI}tGk#1{L&N&s|4vJQ^+4lBWPh`&bz7%2)c>qmKc-DU8x07a(eDfXBINIo0(U{C zpQHWOBmZ6|K*|1f@Qdh=Ee<~g0r5M5{pD~HV@ zwLi~pzy}dO;{Nu424I`PKkM|*(+H5krT}#rfm)FN1?=Ey@@Iee53qw3+~)PIqyG!+ zAP|1^Nw@PJC|NY{R|XW39uu8 z#*YKsBe`E<*VLo^%dwY5=Wv)~uKn0mEWy9D#Voh2HJI-0fr9~X*#8#J0L$GT3;tI3 zmT`b_f7s|ub%0Ji)=LAR%Azor9#?&A1)Ivn}Iuro?*983J;a3vG`6=m&v zk^PNSf9o{>GX8FP$GNB=D2@NB<=>qEI$l09IU)mA981o+U-|zwS^ZO|1Y-YRCkY@S z-zohMdi!Ha__6$#TMAw@{S(+OZJ+hMPyM-XiviHlgNp&c8UJ)-{eQXfT%NlfSBd@` z=ot(^9dob#XNcfH=PE!)22KY4|Bkp4c1Ff_K#3CsZ~_IU*uPNym!kQbf6G9>`2b7# z>#hId5P%B*3hiHLA90Ig- zyzQ_6X_x+ucP< zoe3O|GF~{Ez0wAhgjr#(fY>9S#&5_i(sczpuHaprYdyAu{d%7fr2g^@@yPv~gK6v$ z%4wOq2w*G8OB1k6zZ$U3*QTbx;uI=l5M)=%?G2oZik)RjTPMd0J8kQ{$rdT_4=1oeS5$U?jC`W0Uy-4{bs-(7ZgKF&& zX<6QwM^h!**>>oop{uM}QE{&rV(GvSWjAwdfhQxOt0N=)ATeJ{z6?t~0d7rXl$U|< z;uqisn?zxo!7FtuX97~>c1vmD;H?lt#eq>Uv zL7q5K9MiW=n%HJ~#nb%#MtBfNWOlhh`~-7f&-J}c%50+EayNd(V+9bxGI6(VhoP+T z0@jR#8fi5il7cliY$Ss<_V$Cf(=Y@E+O(6kuy{xO#v3G2y#gFOu5vUWFh)fWqvVWQIQyO5wAGZDf@qv*%Zw&XA#v0(O(a`^Q@xQ|$D~ITj0&h(6D+c~84X3G+ z!*YX7ARb3U|KEfE4oOV8fhIsd(!4QLTN?lG;(v!hQG>!G>>||U{9ddUisWh$$5JMB zxUh*;_{GT@Z8ARX*!$k=e6~KjsV2apLzg30tx78&N9xfQA7_6P)wNo7SY$#-LJ30 z1h4H*YE#@!rf(o2AZ~6TK>wJBJq>ITLiH|YJ-icaj7Da77d>1R6`QX)&Mva~Gyh>Z zlk-JV|M@|xr7DS>s{Lz;&5{o5;Os?&JRg+Y9#{^~B%h=7T%7RwT{#_>HOo^b=3|V( z1IX%vK)^ zQ^ir_@1JeM*fGl3gga^6tTG3cF#v4!*E)D(0HC9hl}*Z z5dvrjkPwQGAfYfJU?AXt9g#uE=>(>UWkW!G+J}O`1@1VSGdoz?nAtuzGP1K}2EVW~ zIleScRGAK(et_!Ad`RLwXD}JMMM*vI_?2eOkcg(!Yc)e|>=Fj`$4rkl8yzThABJan zb5uygtR=Fs;XAuJ#31q5y!3v7KnP7HQD^iXbE~LHut9Jj1{d$qbmYVLtI%$XF!L`3 z+%!_&&b>>p4SJKt0bNwMWg~)^U!6&Ct^Ex;Qln)rSzqBb_cu*MS9aMi`^^*PO#*_l7TNXYMpS zZr?$mlc6a(jW)lQFEuB(T^%_SehYn#f&2;4e8txao7$qP>Uyca2GgpA>3-&G)ddBm zYYzBP#HjwM${~ejg*E-qf-eobJ#z=y*4qbA6rVDmWE~Hj+-nnE;HX>d`-qUP7wU4T zfHSn&2+Qbrhlusw(*en0$@!^ycKX-iC?WOg{me>J_yQS}QcHFv!AqE7wS!*{}w|PUYx6A4z?H zv>~4N?dw?4V-;HF@{fFA8{LQ;bE<#+D>3?9%`AyHBahb+AKav6+<`$3Ps+WRp`=09 zd#ax_yh-~ZDc<^(E}V|Iytlo1Yiu6__QiZ`tbPd-W$omPNy|5s4>jA1jMcGHl*LOM zUY~qDI=YBj-$`-5=%4;{V?HPF+3Y02!7{ng$>iFu@#!~?#s*Gztt}39lDT^KtLe$3 ze&!;h;xqMH7dQKx^&5d|HwXKx9>uMjtS4Kp7yZ#ht7$}Q%{mSrKE)+FWS^Z_o;03) zIk5!(ftLz>vtqS#|2g+DW00#k_Z}mGIoA;q?C0Gib4N;o0mD|chnK1k6EA$J1dM11 zoJMw|iSx+O; zIIRTKoK_FMVRYMm`Q;g`OJd_vtLIc=euTsOteio8lD^zi!gCA1*B>hF0+|F=H*Cue zt_#y%FJ7O1J*fO7xWi#ttjqVAS8GP_MJxeZPe@5-z2%8~1&*`3+x7IjVv>a7GZf?Z~muZotaCUv-8#qPLer<8s-LhSHHm>?#%iy%zgSuBX zvvsv@7Z?5G_6HMvm3t)am#sH(cnz;3F!d_8Diu<+jaQ!c333)Q>&{)iI=G%)?XRso zSqfh7_u!@-)`%phk3_$DAxBDv*LJKcr7Z31ssJOVb-ARlMBasU#q>~mDR|DHspbK zjgOux?(d+hZr501?D&RlaObJ~Mn?N%w=Wl^K_#wsW_ueu^Y6!-E|ynX%#xIx<28_` zvX}FP?_;YBZmQWe;M=_&J-uKmg3&=;+vB~ks>J7F5hE#rx!#N)CzVAif+<~;eQ53q zsf&cUHpR4KS^M$C2jR^_;EUq>Fl1lW^DK^qcaT!A z{hn+2u31ilWu(b|1KHR3MBCIxsDjbW1n3jlr!8#FO*3qav^jgSK^yUW{09OEhqCgB z!+y!#g8a+zEn}%Bkw_+`&%P4uCwKFli`yL%Tf8zt88PCQTC7brD;y&B-mhFTaTgS! zv1Q79DoHXji&Rsh5Qk_9ci`wE8b@7?R*Tt>>QvSW#YtXwt+YX~DgkxCVsIRRjP{r- zZ4g^$W9&q3pJFbu%&jfH^pGORxcjP$d{I(QZ(A}3fHA`8kRmzxERgCPjmCFFRB$OJ zd5_}Ri=nVCU$)5)M@Z3bhDyg2K?NjqE}ss(wQ^Gm-?}rVb-`uzokegolLztcQEcB+ zzJfC%-jbvpr4-c9@Mk+k?z!8 ztdya*{F*l09rAo$Ycechv{jM!UgRAgpc1AgTRgq6g^CB zK=g zVXW`Y=3baHjM}As@Zf|R_U))+l-GtF5YM=<8*(6U>H`39-Yv|e@+vW!yf;E%j3zcx zKBj$FAW7#sd+^qYHl;;Ekt~wsJpO>5U81xa_!cA#3MHK^0SW!OoAM6e4ivw6a$jPxoC#poia-uQ_&|dma8~o+?Sk-|2$X6 zymuEbs*@;m@vOu&=bh6;TZMc%+sjAx%L@-BKc;=MEG4Y=ukgIWg{7&Lg8m|~c-O!1 z{SdeKJi-&&zRJhEwB}Dnx7mDR31|s*^>4&#nYoy?EMFqoJZOJd{|Z4IRrDCTka;_` zDLz1Jrx9!1X|fc$h^LU*{MCoz@K5Kdd`g=}y~vGjshg$R{%Q*A*c-SntygG2$4!GEqmdA-7iXo^~+)#iYoiqz;^sF14Pz4%qQPeC8*w zPLDD=Fz}1^*tTj*JKv>;#qt(^a7gUvtyfQ+HLII(ZHEfql;229-}AA{Ig_WKHl0q0 z`PN_~CbJw>JuvYZe!1@Xvx{f~F|)dPH>|b=d=y@e-97FQ_32`(qV$e@Bn=_uoIM}! zoM_hKJ>ie(9lbF`ZdbW`-o9p+vQNCVYDhAo-+6;Iz7$EEHLVMNmH6O};VWb?vb-h@ zQ8ELQ0J0a}gb^dBhA)aZDp~+{ex_Z48OGn?gokFS>S#^A>*6B6JT5_&n4i1%A|G{V z%+!TU&?KwR%tf&8!3ch-XT7EMFba7@Zw6D>Rbu9GcNSUUx$>84a9;wBWM1bFFCM2#+#S z+2Pg&cl?%lQsPai^~+Hx=TChx%&wRiY}zy? zDe9Q1HK5Xqtwqn++QVuUQ(}mhOZ6P@y-|*q(^LziK{lp^q;l2%N(MD z)-etS6$rc~zdO{L5}eQRLdl=uRn(hGOMFV|D{D3F1ysgZcS(GRxzqiWQ1(WD7f**$ zF{mRA=S@HqAmX#Dw{1Wp;dh+_%}sdq=|)`_J_AaYp1Hi^Bcs?Bcx+kDwc#FR&m}sn z05`uik~%gR*k%;9NYKCAr2=6mUmDz=YQz=jZS?s#n<7s)KQL6|iG&M$Ww1p`h#tzY zC_FB#a?CT@7U^?R{3mR(f<<_=@&l}f?@!PMjLH$Ckzo>KdOwsRCi2|Z@|8izkQeI> zXXnpajA2pMs>(23l%MVAu)+wck`&4IvEHphOOGOOkAq+}f=G&DFyQ{N%aAy*yUuhUvK)s#VH=Bnbv_X!Z-J(NH+TA*NM!l$4z zN-u@a3ODyTEPY-uKI#_mUFL6nr<-M^jcjqKt4*Y+qe~nTiMldbP5kDkdr)(sSQjBE zWVOgAynGjE(S7x%-^tJHEc$;WYs-NX)%bwM;7E?+N{XX?=r}0}Qbz`;6IIkSN$gFv zeDXYx9qMAmgMv|9RI%DvCF(gGc!Q|MJshA!^AqiaEpF^4jPTgirBSqdb!%!fY=<@A~i zQ~i4vVE}DZcZqSBoUEl6_`s7E2m9Q4U%2Ymc;Z6=U8JrN@Y0MY^5rYB8J?xw7FM<3 zQ7xF2ya+F|`axw_7Q+;0S^)tQBzlDqTdYE|q447MZCVbTMPFxw+K@&^CipuzZN8zs z%d=;Dqn)*DvH7t#_NLeMPB+I!RW+Ca$rcx*orY>Fq=JWn*BR9&MeCPat&NyvNCGZ& z(2>Lf3%-+bGl3-aFJqO{O!Y7O5UeUlAGxi_t!TcuO6e^?5A+< z-0ZLHgr)GkBxc|G^bDdC`0oWQb#!R5Ax~5IF0M~EI%x)%P<7cu3@#Bn=^8rWy4@UI z&R0$sw+~Aqifl8mbvJiVZeD$9D{*%;oG58BTFG^z;`M!<@mgooZ?seX!GZhzu@~am zxmv7j{#fSQ-2zwFi^JP*zX*Rcbn|C^Pg!=-zyGyjST*tT^l);o%z)zU!=BXk&YPmT zp~=>rM#0%DLC(d_&WX=Ox(#d&=WE0n3@6BlI1Fh6ZugYuG??5juQ!`@EzJ5m-Qs8z zNCd9-0ys@S?Cj~qS5JN-|T*;WzSzc?Sv3@i2e=_^3wWZJxGkHN0%uqJvdmoD{*A}yn{50jZZ@OmVK zA%ct*j%#Cz4kkEkv}y2!YDmXWA9b*C>{}I+zY_Es?&ubpwuEo6g7KI^iI&ciG(-pz zCwBCzQ5;k|Ynj?{^lLnedo?pnP^Q+Kp*OSnJE++*1kf63*OP1=)D}qbr|-rVGck9} z7jhXiV9=uDJL0sdj?XrfA7HP#v{))X%W#0z@4*hT@*%Lm&k%y>VM+^~fzdS#@2;3U zLciCiOBvEmuvpe5fXwK>`lw~Y`;;JiS?h_v{@&*T+5(Iwb#nZRwUowg-DvA|hC<83 zGyePX#!%DIvsOXE{Z)mEM2(8<{4WC`g z2*nV14A6PZv^>RIm9&$Eck9o(iE-Z2$vjj}<>aG4+fZHVJVi(t`YdEQVPlZ$ z@US(BaVVc!Pb-y^t?!%1oUk?Q-FmOfXeNFA)DsK^^_Qt9H}8sh`*UVoQ!6`KbA^g+ z*jI%tNgbM~edO#QqDzN_ik}a%jR-L-`SOYK3ng zwN!AAi*c^5}9^k^=VXDHus9q|wwsu$J?LDoRFNMPu~IwzHU=pwH{&L?Ef zG__K%gnj4{A}7fP#~pgO!}E3(m^7)>PZ+sEJ5!8)&x9i{>4yjybkR$Nm|wSQr#j>Y z2O+$8DW_;g;Hh~G)7A5Z85MC!LIR#Tk($6~G z4?6o17GJP+EJ0Srl$x?<85w-6~du zW-UgKnph`NG5tWE0L~Xd3TXDOulFNJeZL{_It8hBwUiIP!)noPC#t6~whS28es&** zyJHoqkL-}iXQ=-W&U>4t?-`{1%iFui^(S z^SX59!u(k*@<>mjo^n`{eA~j5Q+R?KsnciY7f%2i7TLqw_rZZMGR7g!`juZMPH7!C zhR~cOWRh})3T9C@XNuxeIm_vU&>5aJf6PdE9l3d;2l7Fgiw&%t{&SBPcj$pJ2uons zVPIi-H1L9G0MQ~(kh)HMQQ73ro(H-Q(bYB$03gxyNAvSensUFnLPLl+lgr0<2?EGfS9MXj6{uC~vj zj$*WJ6aFAF-~2r%Z}?Mjt8PKea%g6tQ?L zn$bWJZU@eCDW@UoHKCCex%Uy}OGy~gI8eP5n|DWXqw*z3NF3nl!w+-L zA7VXp%8{zkE5Ve;Xziyk^&*6jzGzoThxE+k_YfKJyCYpYNPdPDi5$ax4=vThA(MH7Xp>dX#k)QuyxdT5?HjRl z5U;fYFt0Q`*+}%vM94Zs6j8}KG=EaIP$?@EQ0$BiFDT$@=s-mIXp`|6FGqL;p$dhF zJ1!wX#~H^7G`h_aUGH&I7H$i5RtHM)3}H4Ti;P_M)To|greN@w+)T-a35~e5%-|;{ z9w0{QNK@ADH}U_9zO}4v{hN;%8Q9X2*_z>YGQO9k#Ci9_?If1+qvyHk}^@F9f)D$P_5|S&dDEXD;qM-}(O2au+!O6>^$_0dADKZX*kWL&* zl5)6Rnn-c8$9s|DmuA?PxFj=Ag(K`rMRwAS60xO4uP{$2v7#Q>^2u z=*W9x_yJY15sz#b=>uNT3BbsKNB+~HSH19*TQq%zi{0FVq?;ebMs}+xBabCHSD@SF z6DeOjV7AARngU2L6Cgn;9x72c&9E^nDISVF6-pw%d?1hUvdK5c3XqC`pDe;MKi!qa z*d&a6_=WebG)?f`0;>eMK99`qcPbR7?YuOROmH!hBhc9_)aqfGg4>uXq?-yyz_-31 z%178W>(fP2`@WMLvBHC3%0?$brQAZ{r>EQ+d~mT^?9Kp+!~8T#L%C*2HgQ;x7BEV?UgVi*^gsa*E3 zO2)*nia&A=j#4huR%$AD2aYo70sMy+%1Gk!0Pb-1*HJGh3mwy)aEJ_|ysj1=$c4hsm3#F*a+k<1k3 z;g|o9wYLhYD{Qt!gS)%CySuvt2=49#cMT3ff;+(_xCeK4hv4p-h5K2Mf1kZ?-Scwl z-lqwx3cAPW(cN=?-K%EoHDyczmnV5eX%lH^Un`%goT3hQd{#-sN#KH#-Vkl&M?s{m z%v>Y0(mKe1A^t(1C3=7k4AS#nY(3uh5$dFoHDZ2;!U)07&VPY%NpJFqTzEZ?T!C(9_DC4ek{_jO; zxj_aMQt&r67h&dMUY*41+rpn4I&y*^SfQ}CKV*~5u0Dm5SOG$L$j`bZ3E~BZ$c}>e zHx@uYyFVg`JfmC|6gRjPLAc?5!ZOpqP2Q-ZJph$oi!H2=EEZ3J4s{i99g z@TaQQRQBVj(a{3I6PjTQhXvF_9G_TG8C=g0sA2|MWbop))wk6N+IAdC`xG~+%Nz|7 zYwq(y&kATB=`$hXW=-4!deLKH6|fQ=zvr1Yk>B@`JUcmG8hp)atZ>b{D-P2hCW&pt z7#LGI8P0Q$aG77{BtUhcIMpBq+SY$21~|s6E(Uzpy+RL^k%==nKO-0Un+_ZPxhZu@ zg@qHR3e@zVAT^?P*rO(VViPqhVf&VQC5j%lC)WOit_NF zGDc{d0>^3*(J0%bHdYa_b}qAgfK4LIg4lVC00KtN)2weUZbrMxs$RWeL|a8SgxG|b zJ@+0Gv6zuPe=@dVc-2OiW1UdeX_(R>AHEFvA)a0UerU>fl1kdJP65`E-VNK_TK5d5 zvuJ5HQU|qVo$2fP5VFfOS#KswtBVl&GvN6naufa8_>ur^(1alNoHa@~AEq%GsU8~?Zko$8t)`v<*bN2DB^wHBN#km&7l$>Qz#W`ECh2Ug4s_K|0R z30LtI$0_W~+}m39LQPQtHT_#$8)Se*a8^{;jt2)cKUu#icvgDL);#bhcxYV=4>C|M zaKTz?lO9PsE7Ce*2LSI4v@XkJL>F8h2C~OHNBr+ZhpfO1p2)u*JPJb;`?n*w#YCzI zOFn2v;TAf#Di|Vla4sT60b7K?G{Su5&CYtm2fa{*$0tme-25Klw%$_T zQnx8_#=pknJowRFHaKgbdkxd*LO0vtjIfSZx92#@s&02rFdFGg|K@7cX zAB0gfh*9~$E+N@9iANxZ&kAKvN#b9#n2Fx!o15)Ty zNiJC=uo;G+q4~drptOu9qlI(v*m#0PX$VE5F zsOk^@P;BIvcg2!i?#VY`uW{#M0>_)ied~_Ux(mj;r-%VeW(<;)!gP@=q8H@g`jrEJ zie$ll??;gd;aU!{gDR?<>ZT?n1uv3bYQ{~&=c8~Zn_kyCw8wDZhy;%@qGytbZtB;6g2)HbkNRx&}en} zKT{}J>s#0!MN=Cq#VERs3&^V`6;5o?14U^PjmZGwZp#uev627Ie!QZ=b_kL;4e z97DcO-HygI1qaXiwGO=o5>PzKg`4N!wRR9EElzf63L^EPJ`DU1^@+j^avJoa#8Hwu z%-5{g1Y7AZ@U}_rH=0DgUF* zNjDWO?Sr=Af3!J$(AI!25{wV3(U0#q;Xrhssx=3lNyNmVY>Lvv(;Fwe*^)yx7AUp( zkG44=ZNi)1Vcq^qbElU5nf_gD5TI0Kmx<^hdqVMxK%S<6JmFUXQ@0>Bs!K(Mt1TV) z6G*^lprdLpKPZvL?(|h5^1Ufq8bmVK5~VB7o2XsyaOoc+t931P?yjW zR%y*rtHdS+oH?|Q{InDtD=4UG%3pmL3=J-nRoLRoR?mY$O@Y#-)KRy9;=kI7jwqW#S5C zgW1)io=TJ0{I_ML2i%upJga=nfbu>8u35dhT;(-m9WS3YvvLiNhCIDxK~0u`a>q|~ znRuy19NIl^5QRGCFN`>PzzfhIHmmjD5rr6q5e5Z!)GJuK&}f;~2z^4e|7qb+74OxF zoU`$?Uxwu-CiDcVs6g~~mgm5Ra2@$@TQMGw4-FwInCs%=$2VSUwtCBjG6x{%UtPJk z&iX>UbVB&KZ-|0YRYFm9H#IeuT_4L(jE%Uoy#^l9A z$`I1dQ=JB1?!2UX5v=>ibDcY<%2p)>!)ilfNGotG!Iu!y%H8U20RWCcCK37ah8hfTJEl`e6&0}NVc_s_JT%7rajx$KYSDLySA&D1Y^P>l}o;x z8$LHrjT=6$H)mWL<2sSyQo7VX^(h+y!3W7XvOQH38yj#?P8wq#XIV-`A0Sz z5!*t(TAx!RbAkP75$zjF3uwv0J77!?cz2`%r{K5Z7dGmzxyl+=dGUSoAG5KHZg~wW z#v`?KInN}@+aGLTz>5VG8?xL0Op0)NceosJow?EZ~PNLN<1nP=NBD^k?{_O(8s1ogL&+Tkun?gF3aAT+QI!x zK8|#H){FyN>X9HFmJhUrXEH#L?v%g+5_p+FG$)3GWP?#9WLq6qMJBd^3=uC|~q z!49R(DSAA99d1i<3sYDUGp-EbfCKWAyR0~7<<_eLOrnHa%faJ%PlX+G|E@aMyi<|( z?wI+0Oo4P+sLbxrCDEJ*Ov7G7M~4`Z)z*TS69U#+z7UU*;= zLrw%U^Do;e)-(>N9VRZhs^1qt3eT}fMHD95&PNd<5ANruFUpdEXEtluR&YBJc1F4| zV~)VXFBgONc2MMDQNJE@|y@}E5Y5P7MN{77z1Iul`Eng+}zoaR4_p4VCP z09hSUeKM*)e-h^y>2W2pi}^vi>taw?;y3{`X=R;LGWQ}nHaMKN=$ob?I9NsKYVbZt zK6#Z-+s7DZuQDydc{ex4{*Dm<>&)m6?IU_XzQzRZbDE<3mvHev%X1&13Zx}Rj6aaDkV=L!Z8VKRZp}~Q3e9X9R)`; z2#YUiPF-~A0eZvu%G-y?ZiMI?FBq4=6duX{&whbJ*~)FJz_ohh-VQDX28(UoVSZsMeaw)ev* zZLhpl)A?lLz20>Fi7cfba8iCg+Q($!-oo?^4fuo(PRttujN=7al-8O%ie$-ChPgz1 zhx*^mSM74$trb+NWOca-8y6zwj<}Gr#>x9feJ#F;OVahbcWU>%fz+Ot`7lkX9={fq zKV`I?mwjdOyZQA*yCU~t_Dpa3>xHbj_lMc9Ocr-7OpUMq2dhxy5&PEB=VIk?M}krG z&#w{hNcpSg?IwF%H;O%dt7d$M0FUd+nNk#6Pq8QyJ*Xx$+JTB?-W?&tH*%g~t$ zw_1c$BHSh9Fe^+Wu->C7|JMl^O{Y#IG~rKqz_W;gC&8Z7d0#d7_0lDyx;(Y8uaQl3 z178XiN-GyK7Y_x=-O1nuz9&jq z8{-Gis((Nif&3oJ?z?^fZDV`~detKTNsSrHtC*q@lC`zySckO1#(KX}+-?z>5>YZ(FZe_26P=Xno*nnQ}oth*#H z1~ZtYYp7Q`%cjX+SHk;mFWy#K=5c*#owyDQ@1()WPXBvRO0(u`Ra~-7^$ku4 ziwv+{g5*T|>horJvG&xsPuK47?fK?m=qm5P%@J`SLEW5Tb8 zij2eD&orqMS72Wn7EF^#;8ncTEez1u01p4XfiG`+ z)L7d-KT>w9UO!k}iR6&^RDABp^F-C`2>z)_Ujrj@nhv@m9q zLk#VQLHOo8;4GyvC~c<8CLL0LlpUDDK<^;;PuCGmaZ_P(&cB3w0EAxPD&c+6=d_7~ zRd+A(YAGP7&s_NfA_G}$r^4}WPI~0bzaVJzuB1nvg)jDKgDrEy5-O``0TGh5CuC*p z(p!p8DJ%v9IQ42G7)wOepG~~fE(-qGa!F*ixN{>`>5>2Bnt^kzP!|+XP~9;(c63*& z6(uwgkaH!#OfYVu0eKzF4A-TlQfr4_ZH=qa30IPIDJ4_?00-FI$!x*huQ2cmRb#l z{nLVZ5prAE&IF3w+a7Yp4SDuXpV$tH{2LPRXLF8g;x=!^@;k1mI7o?cUC3%l)n4slr#hdjQM$|em(=P zl<~!WfBxU_o@~;W4Mykw!CQWZN1G-_ak!gni)|cF-~!g{JDWXp=1vLE;Pe!#v?7A7 z_a{I^jlZ#zve|cYE1l5!NuPKrQsgT#nFSPWV~jHvaFOe4K+!GohOk}d%H)d3{pvKL z=_uk2lopO|Sd}yJV z!@j@}2AMj2vsJ=SJg<^*0zzC2N?pAJb>t%+_C+Q$f#O!dZd3WU=-lAO>=55NdT{&K zIiKLyzY!@gt(~6m(pL;dSN|bg`3PWIFZtoFksYv<3cHI~VO7b^|#3mr@QG-3o)n`6v-iA4G#@#$x3v34=KKWAYeZAK?7AR=p*lbLKm|fT=ttdJy@(%dYc;Dw`A6rj z%*E%?=4gW0-3}b-6%qM!?|>%YFM{E5I!JRy_L;3sgui;%g;i{zz?xqezx5LNodZ|& z8mr#tre}sltFNK^w_N`nyweh=Rn zG3DKdLY+Po%6lLEt{8%6$aHN!Z0U3N2fEiwU;-))`~Ig5P~35`H+RMj`+l^Y=E|HwM~y6qQdJ5CLq58j@L^)1Uefpm4fZ_LKe@-dLAan%ek^Bl~otne# z5f*J8rAqwkEhVM|WA*_KnvEini#@k34#o@!4w^N0Y^fXBR5T3;E|~RNfh{;7*eOMx z+8t_Kk~|T?s0TS7W-mHGjX$@I1jdXlmNPh2=@!&cj2OlYn0(N$a;##p4?Do7lM@2m zcjO2Th;mAqq~5vv5t_p~@*x)Bx+Ar{rJy?*+XzrB$flBMbwMOUQLG6$2{>lJWPk?4 z*<(!ma*mi0Jwy!zNJ7pwf)`ZgA?Yc`Isya;&5{oU7%I#<0tATsoMIYEj5cJ!{c{@G zzv5g|l`B^H96)3CygrSrDy#K=$cYy?-rMf^db}3Ye%rxuU@%TIxZqz=hIFys`FeKx zxR141yZBtDC)nBYcJ(b=x3jgy&+OOj+e}52a!Y<95|EtMIGTUt6n>B+nvGz!@AQ6l5oVG78O&WowocZ^4jaa3oN(VcKUifAbne4QuE|Q4le{t$Gf8a zVh_f^g?kI#;e%}_7)VoWyqw97uxIkyi012Kba>I@PiWPw%$xfQ>tqzbp01vXR>56P z2pGo-RZIdFYBx`uaLTVqxv**`l=n| z3`lC&qsc?RIjV;((3!T&EH}KJuZ|m$-jpY6{LV%l5W_mc{l1w{{Dm0O!k@f0H|U#?%3^tn|3a=o%YU=4?x^34Hy~^^JFe3L>qHn+jR=?Iq z2hW?w`N#|d#tk2j2S6|05ySSx=&9y@S#3ZjeG1pbI_6-!T&^lL4pm7&_3{8Ri219vBw zFkm?jjWMuE4WE|^G{-{h(_z~4*{RS08<@dRD4ZpFC$4B2|Ko9+@~G6ME&30qww zC&r$x0nbuDQ2#6*Pp41NjIc(ZhJ3}FxJP)(FA!UvHXy?0&!5-^VM$!cP*A4|kx_91 zNeZR}{bQkluZ5!slO-+?))1CX1lQ=;9IZ(pAqQNei=tjI4aUpmUkLHWUi{pYBP-}m zi85ge7JsOPmXS>omZpgZ3BEq9jf%~(3f|R(7Ij+4l#>3z9~28-CMrFk>kK{Y4imgP z&PPnXXWm7`9E`p$xx_CeeUBNzNMdx!C+Q|Et-lN}8o@@6qHNQtfI||(@FS$KC+Xqo zWo2{IQ2M*~uKq9sJt#x3z(^WS?URm+IfHJ_B@Zb4)Ub#lxC`Q(gJJLj3v|>WHvSiK zd5=%ng##m?`4(VZhd7=Lx?Pa|aR)LWWW`JphJBt1UDD?~0#d@rIWr$8ieUL^Zn=b0 zdcV#(R{g@($O7V4zYRVJFvqX_NQDNdg1RVxO9~-?1#S0Z1eEM)Wn7pf-}_wl^IyK#;sCW{ zs&-i(%vxEVhpVzgvdMDgK(z{G^9kp�%82#5YN!B;^f!K}4Oxo|RunT^ck#a1tpx zg;A(|Y9n$PT7}#2!)m2?`h`7iJ2hqKg7THh)*GyvrhZ9I=@NMjTZ5;HV1iFndv)X2 z@b_OQ697x+ArXQZSCqcLSBZRobkIJ2eLssiud`TY@fCKLZ+vnpqjrnAUUI6UKDZOq zv5PYy9YSND;^9a);Fg2@0_~bkUyoNT_uGfml{GJ$U)B8n0egb0tK$nk(^m7#!WY`? zOXzCv#NouNwbv)WFTwr*vyB&|1HyQb*UM{h^aYk_=5pY->F_yuNpOdX*^tv*$roBh zP+DTpzUmc(_di~QbZh$NO-XWNEwIH~e)XWcVG-xXG>}Bue{P!oemFRuxYB8c-~2{= zU)Iw{Y_G4!m7^8Z$<-73P?Ns_D$ww31~!zB#+| z(YK@=dLKe!vzG=AA@SuY^6kZNaezi|06fTWREb4C& zwlpWiwQn0Gh->nb!ehVWz@rPq?h~!?L#!b}7Rxvb- z-KoSqVv~9$Iv?(jTA+UIpbCzOKwOiHb2(I4cltz=`HW2<+~XdHsP~fuM6AO7a55DC zk?kVAMD90{19d^X`=KA=s0hZyPnSbL-v|$H?cvn>nrf3+_7VIjh(Pbm`DpvoAAypgMerCAvxU$5b$9SD zD)idLo)qkvm?57~0?onHTTFxfS;Glu?K2%N67vugSpHQD(qsY1k$yY9-e~MxnrR2N z(YwB^^-pc%Tm7TEPyP z!_I8a_8d3?-P4T?M-2lyY+T9+pes(2%r6PiX*Oo-AnISpj}QR(jG&al zau~!F>Q#+5N%0$RvYkL&BRzy$e%*^D_&h$O5wqna=C8VLWe`V98-BAvCQL#n@@lB( zM3-CTEL=h{RC=IW`N~?bbNuF0gc?Gf*1_lCW+{RtgIsH*)C~Eo#ZVCIlQVc}qk4#L#Wx zFCA>eQu5xx6I;($Iol)IwJHs6^yVYV93T4j={!?N&}awAE4`;QHPBagF*i`m7mJbGQOr$H*~cc@2@KupkWJi9`jP9dE)~}(4c%T?22N*`07dXg>wt0_QS#*V9 z;5~;(sy)g#c)iVCWx6)(y3V)jzk6jY#s|j4QG;3J;0x15vnr>&VNEtSxfnz_dC*sX%B=*#m zSemtNPAt|~8c3M=EA?jfE<5rZ4;$eJp(9zw;4m8nVNs>LnGqW|h_)_qHJI@cg(RqT zGfJp+_a`8zGyM$1yFC}`p&M|_!aF|;<=Oj2f!tcR69UwIN`~m-kw`rO@!@TFg*O{v z^{)gQg?f>TButCn!f&qZ(k_q@^^kWNunG;Zw>)khMh7njhcY5zJQFUL><%(XPb79- zKcfN8W5+IRnCv?1OkdUMc-cl$7|hRN6N`xKU$9B+nWBZ3#%lja26wIkpgmPeq}EHb zZu=V+1$HY+1Ka+Caa~<0t`UgQT-4mZt1q;zIf09pZUk^oM zf4-A=W8_zB4u$U*5tkw)a5;h7L2e!g#MtJ!z`o0o4F-u_&QGLFi|I zQanH-4%nqY@#Gqz>OgwvXYqSDz0hz|6u!xZa*tW-($ACl-UEJ<hSUgMJsr%AtuJz)jt7W(^2O;$m?U2%YAJ zr|2{Ri6G@v;Qcdr;FACy>tnVeuHMd%-xuf4#8n{i+}7g;wUABOIF;ajg1>KwQ@=LR zI;=HuPKhC^hkwCaa}}MTqZ9n?8u*@qx>TI9Rc%N|Nqh=b<^6PvFbY*sH&?vfM@hMG znfg{CSXF3M8-CB1-1;O=EENbc(Dd%#leCyBp(?HPVY&#f8_*m~<2UQnBZ-NNRTmIt ztRDX^#GsrTWGJNR5R&-O-e?-kqm3-;-(9ws!q&Q%^2ntZqL1r{^#3)VuNv=RFX99b zU3(8*;BxLp9!HOj3I1G zAV+5SiElk(gFVlC>Fp+w4@Yn#cv8sBoQUtPQOmHd#VX~`@F~OtLB*vckej?jwPljy zv~*h^j% z{YQ6t29nS|w#o$@0)d;lrz}ls(!{GR>tb6)^vtVehw|F;MZ%}Dw5WVw-(Jdv1~>^r z`?qNN4k4mU?j&r32a=x;d1)QwLyh4?p$|-s`{*aXM}z)Fm>;F{yS(Lt}wg zUsWM~S*BDEIx?;xQE0_Q`L%L|5Zj_s2R9%8s!38R(oi7e^%Hs?uTW?`?0S%(SZHB8 zNoo8jrp7PSS^-#3VwrCvqAJ$U>X|yc|8DJM47cw~1avL;3G1XhX}XZzlmwL*rM>rYD=?uFumHRrQJQ^~KP zZyp{`+pQP+zLo+FCt;t zI^bbIiUrTh6H=sl4c;Aaw2IHpU8zavVHob&Z_%z@Sa%LsGzn3+@-;r{`A$$RFChE}NdRHg|?NF|pNs)YTnmk&hw%5hp6EUvhzcF;alE7(WY9 zYzFJHkV5qKxMT2oTkN!@@#Sk{LJLaI=e&h%N4_HF=SrXcfm?t|2O1@>qCTodbhH!w zh1ie1AI|hPe@E1Uoas$o+N>RZn4N-#ZE6&RL~BG3OML=(3~PLnhaYo?NtS4Aw07wP z_g}6F*#%A3*V0xg-DI@TXsL{I)^sYon6#YVByZv}H}AC09PN}}^y_HveAs7L-`bCi zsOclex;hydH`HT!@X(`yO>pfm8){L8>upgkuvo-6-gtBkp~K7(y6R%OcnE0D!x3Ff zG7QzPIBKb-NA(yx7FNNY}x?ha6^IIM5)(TX`6neM$|jFf`BpJ3=;` zgWBRc$1h+YcBIxloN}W()+uOwamTs~% zc-r^#inY$}UPD+|ZF?o-4ULqJ=}7CHI*rnTWHFrCjfRHE5`u_U@uXQIXyTq9XtWtU zequw^^Iit3u)FxiQM~cK?&p-S3vXDTEmMZp)NGO&4zm6QS-c zlwFob%o*|D{E{0S={-C#?+KyjL2mHK6^J(>^bWzHj&`vIic2nMqj%g0oQo%UWsOHG zmFqmSmIH3J;L*RGP?yguK2(MSJGAbW@0=aor{j$MEaqY6-QWo27MT=%s{LYi>58~wke2?s0mmm zKgVP}&Osq6hlHN&SJ&8iFwG|Pwi!(%yHhG`yV$@39ci>B1=_u zJBPO8^<~UQ-z*Xgj7kd1C}$7Elhei{oI{PSu50DV3d-2Qwj=j0Z_x_Ed%xQTvAe`+ zwY{X|np>Z9e$}Ki_|BavEQw$`M55^x)xP;OBYTvTlhA8{HYGF72Jw>u{eX42HbIB{ zOk?!R;cOWf=0-!d;gkqxnmx&9i&09t3fCX1JlW;c)Q5kHi+sO9=FGxt?Ek^TXlKZy zbFldC>a|+ZowA>CBO+By+e%Hpt-xv7{gYEzZ`Fz<`!ci`JH%l-%b|GofK>^^-AU+1 z)y&i6l?SRx1;Ll)GIIiC(h8b?yy3W6R)R?N8eJS*5YJ3$>q$en23F8pA=i5Eq$>>1 zBL|Z8-T_tZ6k_8{O|}X=8($>NUlBHk`kolK&b>UEzm+~!bkjsgWV236G|Ap5ZPr`v z7i|U2y|78{8af0BQDQ5Y`uQZX54R5FW-qD#Wa(+ydXWW;yXR%e7Aj=6+ho#LuhYCT zXu+i%2%qIouHD5DR_gvpV^|wrZjZWF?XK8riFzSyp_4ht0tZX zI{z8$pYy?ag!lB_Oh|$p9zB~0Rc6PK9;X9EK0W<`UIAP<^<$ zLU4yRdxvRiuzXgOY1&bJoLtO61!+<<~3>ziF}Sn=~m|Eq=+wTQXE}{E%=DouKPEg-4T7xDL2W!wQ;xLeSM>&Yk3PFkvGRd zQs{r2{swfKYLl!4^26y`kq@WWJ{jZyoqmA)aJmQN-Dx(&Us##WN)c77kAM0((C&vd z7O7w97dKBSE

m!In^PF@uv_bv4EjQ=1ZMzFA7#lt49q%iA;-S|}!gmAMtEv+~_i z6W0*Wn$;5t$j}s{ixP9|l+XTY34)$SW!|gqXABz=ZBVxZC97(IfZecYiX)^AT(cl) zQkNj{O76D(LhQXtLb$Y8%{Y+1cIE6}?=2`o{-CPlED|OSsL9EZ2(L#;A~5&@9p0yV z3sgv4>X-t8skkvG-%a2T>pw^@Zz#)?Y|B!Kw-kx_nQn0XQ(2aa77Z7FX~!GmC~Zv} z4kC6x1uSGeQo$0&Ic0~2laJk+tAt4(G@Tu-IoKN{+6}{mtL`uaO0#viWHbLfQ$abx zH+v+VxYp;M{Rw=&j4U_;vB72VTDVT+)RWwDs@*#0Z}#L8A(;9XEBf3W6%+@`b5*W()M<{mR=!FQ2zXHyx?-U_yY zbLKi>m35x^Bo&T+KLI3`6lSM+X^v!OKJ&muM^3na7i-*Zp7Lb;Q3~v=Cbj$gkQP$#j9^r7g zHlf6gab1AbS$Zs}2$GeQ1ts09TlG-chk^7bh1dn|#)2T3?W`5dBQyc-vYz-cTHf8L z9M__xXn}CJq&I;$AnI^c2!QNuui=&c$SzJ!BEglxE8dch`IC_uCY+sIl1Y(IynvBo z`4q?_JP+=13NdP3zK&}R7s-r2QG4U!H&?@C>t2De zpLxTf<2XrWcarb?rNlh37q=vd- z#XV*oy#OdD8sd;?9Ezs(q2lf1ODY`OewEBsE+*0*(IAaiDlq}Wi3^t1OHzjX?od*3uPx3i zS2W>{;zGJ22QPg%H+4>`oUPPupg-BnIdh5_Y+b)7LO%Ix;)P5cHqrWI7CNpJ1g}_I z-0cFyuD%5{E>$)9H43@JDW1>sPEWsKsrWo@g1Kx(u}bFX4_iaa;uWhoN*v^_b^Rd< zjZO5eG$*VE@r;(&ja^Sw+K z&qWz)sLB`uiOyOtKVs20o4v6(Z*gPG@D8GzjZpfX08V17^ILdE>1xUIJ10(H8fdff zBhel31G@0B}1p(bt4Z$`gkbOQVb;pPWPSj%$n!*Lww3!Xc zNVTfXmR@59dH-X&Fy~Ba)H)o`kzRo0^v99_C3iKsK?QDefTSlvnX_uh=Z*t?Wjsh9UI~J* zGkXRMdPO&sG)x5g3mJ1e-CnbT9DuU5PDaL-=S~%xO0F}rZ@Tt}65krkwC#C=QpeU8 zGG=VFWwnV^g52iosiPP0PE^mw4BNjO=+;zpJ5}~hC6`qUo_rqeNo!g^PqfDbC=$y- zTU;5!)Q~3_`BNBlLALKf{;o}4yF~a(J;|4IRTf3lVn455-IzBlWuw*b1%p|8t7vUG zzrXE39cQB$^yx*dNGkjO%HZvF(qJah4JpZ@_iK_Pf8_E5tJjVi<-&0lYkIGWQ9}*8 zc(B@lTEXm%IuE~GL9Q7S5qVf~a+R(bdDtK>bXnByWw8FGnajPY@bL~u*;sH+KrV*U z0BJAnjcVbcgZsFbeR;Y^G5X#I!_BuiR*1#97=@fzrLN%t!)+o3X{ zCf__eDP*?wHkZjWt@Eo5>q(KXj+u32?TEuNCMIGA^OZfu>V4~9OuTWo>ol}@5+S51 zcpHMCJ`-E7P?m)OZQt_w#6nm`L>msXVH=bMyQJEBAKV_JiURt1K$0dMjogB8m$r-+ zY&-Jf_ayzG2DD=s%HSylOq}WkGg=CU?q$LGU1Ha*_~iV=T8`!Vy4Y;C_(C)dsSH*gv;_AV3d6`tF$ ztrQwFl(Y3}4@Uph%*Zl|YN$~svf&Ub3ykd59-jhe2RG=LS#I6$)u^-9TR+H_C&4q= z5F1vQT88LD*9^#3buYt|Kq`<1r%OPVyUJ+E$W{MV%;S;P<8G%gDRkr2%s{J=H5i(X z?ooMS?$aKcd~rY`fpe=HCPqJvM4rqN0i14D0Za`XbW!d5i_zqYS3IX zvOTM&j;>yKN7c1#4*6qYFdp$MF{r`J@q&b+b!1>eW)@U=1B^4y!tD@0h7DUx@qa)) z{!dVMlqX|O5sU0Gbfgs|cHi>zsb zw$ECAHl0YjU>>U6udQhj+VEp?w}w-o7u&|9LU6%aT@L~)tRY?PpaI&Zainx5q`W1_ zbpAtmTCVTP8!m-wk6odxxK8&y+bxyh{=UlAJmlX%0)wa>*zj^ffuxM3X#?YOw8;Ck zoXM~8DEh;$GgG$s>o2t<2jBAcG@~;FBU@!g&5RbouH}M1z1pSdHNW*_acYw73d(=W zYp&q*ncn`c`fuf-ENB-ySwL#8jCE<^$vtYe?&tF$*x0-WNEzlo0b*<~*UVsQE7ycO z8LM88cgjd>XkTVfrXA^?b4q>6(cXRw@-JtAmLx`)6U z4NS&1-Ab#%MZ>dQ^UvJhb;~}GwIjVFTVV$xQ?M@y03y@Om<5#s3h)fr9?^kG^>|Zr z>lWJ37~CM!Y-oG@_{k>07|EtYxo_DG%A!xZ#lLQu)yUQYIbjKJAz44tm0)23F>(gl zrb4Be4XoVO+^{^F!nd43ChNo)x-=ISL2!^Y?*&O*zI zu)so*1-6N8`TU^vgd_NZHDy7#e}h8gEik1-&qXPBMOaB}9!7jCOhvW9Kx`<`Sg%FT zQ5$A#s@kgGkZJeucC^GLq9OfI z({=%sKmt6wZgr5y@z#%_a2VY?k&;eZ%nDF3CL`U>$60oD@WfGeWrA-$abdS}DrMcl zFaTSi_L-<$Wr^a1yW()*siLDV9=G%;2ug;ie2;ETa|Ws+U~?c|5ZjBS(MkJ=!;Zf> z9&Li;&XJL|$#Lj5D7ne;4R->V6L>mBhK~(D@DAv^XRw@1p7vCEop-Erk_o8u8t;*V z+F5O%-O(7T?))BZG~Vv_EDGFTSzaFOg@aUe~enB4R#UfzkzchXcOYV{8 z=wlvlTh;UC0RVWz@Hq6uiAIRo={;ac0e}i+z%2>I1vQOlgU`IRypN zt*8^A{GQhCk)KA9siO~E)2^K#m8T^kMWb@Qpsy`|?lpYD+F1XtRxS}M)a#MXi%*tL zLf~yF+o~$EW`&Dv;}`V#M7DsZhPa74*WCd8gn{N~^K{R+wGK_J(Y@y4L_K$%ovFC% zD+1U3ddtf2P3d0zm=|>(!jjw;T|$b%{NySZ^5MV08wjWG_N4tPQ)G7Occw7Szo#Rr z00nGTglqgrt=(XyV)JZJolW%|DAXL%pX&}oj$IC`K8!SR2WxFn|{ zRa}lJY(t{o%dbwfd5~2^O|IoY7Lc(Vsln?}`Mq7nZ>6BR00+Rt0$IDqE*Wv+&{sb3 zj-Lyq;;41HQ|3>^Qk4A`N5#=ndt=hnY9dMN=1w0-MPonzZqx{9R7dZ_DEF`br%`Qb zRh>4WWh_qhmi|L({5kE8nS|gVYXoscR8(5mAZL$?ds@ZxS*07}#(oK5N&!jIQr)BE zxyLMWAkong%k5(bd;JMB2D>uRQC|DFjn>qSlq?V^Sq0_dXnOlHgC$fbbdH|qB~%rL z*s_CLGSBpvnw!Kh29omg!y2-bN-Q_6_cnb?a@Guy{Ck`F7^o z@3w}y6rkmUuOF5-V`Sbf_x-o!*FS=ngFkwR%HA#Cn=JU>6}&imPGh!`z_Zd3dMQVc zb@u4>ZnRlD?(#*FjkGuV7>mW`CU%lf8FA)tIGGRio&0f}~ApNjVECJ?%T$lh*Ja4({$ zpC>%`kDc!jT82xed z!|=<7R2x_qx*?tU$TdD#3j6Pv{&v#q%S@_4pE)-I+Fa2A>W{fMy9{=pE~pdR8opIl zk&1BzcbG+wHNv~w3cz)+Q#qV@!B-MkY7RO~$^G z8d$S4o(x{%>v-x;q@=ck87Pa!d}mzo+feZR4lOVmr08n}!BadTbs#4@fx>V<6PsDL z5s{gIYh6VXoT)OZVTT)>X@b!AIjG|j4xc3VK$C3oVJ0)D?u5m~EoTXzOajX5Sk5bf>i6ciMZQlt@(lukiH=|;M{TWOF`KpN>yNJxWp zOG`_4ry||maMs#@;`2W5_g&|lzuzDCT8lBqyvIFqE^$lXH!UjhfOXm{8jgRtsw0=f}tbtmo5D{uog0CccT~tGmtcl#juL{ zH&aByTkrs*Rk4$a`f`E>r)wO8%&|NqbEoeHd~ukUF7B^O(wEU zg6d4(_0xe|-OtJBDSj*A#w&?B-i+C0Cm$U9Z+frmct_TMrD!ZPse6;lJB8D(&Wk;G zV6wM}uNs1`_PJjxF)Y=`$1-G;phuaLRw;Xdn!J=#eJv;qvW@0z@P@EZc86pxwvsxj z7eaX;y*?+`#j*TK>cvSkO8H)taxV=NJ1;-|>5B&e340czw47Fjov|e}J_{7GPc%k- zeJv4igF;_P0pptn8l^8Y$`Fae>Z9`fN0h!$CTLo#oB2oF#VvhRA1t(#!zt13y$%5) zpou?U`4@G#U&!+(DFYF6st-UEBuTRFkVAM4cDq}8T@k6eVVuEI5cv3P(Nykzk}BE! zPP}>1tXmq`>R;@Kef@zp`L;4N=wfRIU~6Y#^^*_gDsKx9tmlj>V8ZL z!;Bfx@ZgZ=e3|k($%@>b)eXA-tY4pc7g)Yll@{>zp;3XP`iF7SOGD=4%6sn$h{Te0 zhPU3c&1oR|8iF4D)T~j64Njm{7?YydDdp)M;zn%moF@^m9suXT0Ow`BF(C!(<54>k z_{kwM$;mGy)iPZ72ZW7*@6sT-MQx*+AuSE$9dOflL~l)!k}Nw@h8L&quB#kT)@y|A z@K~gEYg|S_`K55ic0(E3l!ga+oVw93{$C<0QquR|hghPCfP{8+0wLTow3pX7{T9B* z&Z{1>pm9D@2FlZ@k?4`1F0rYu{w}g^Z`W!pLM9ND9WuUbE;6 zOCsSrLC^Ve`h}1O1AlyJFuiTM5w`sppfjI@hW)8H8}i$q98_JLHYpEd;1>_xI&)-+ zoHV>9Axo4qa&WJ><+|`n{norB3gUbMFr$$C;829^3HR7W0TQg!9Y`<{t4`SJoTNlpeS70~icMw7v)fJe0d)ArhwKW#i@6}m zTz_~MBt(U+iD_D6_YjTA5lP4Q&l~BSx2jO$28`pA@Lfn!n(Y<2Oq_Y+=@;qnMfw`- zzXpRfPme<}dx46))X@Hnt0W9k2oybkFJlV8$@VDJ<8fBEe*B;#;lTCY0FbnYi@6?Y z3j<#`_p{mkX+A>EFFqjpQ1N?Dd2Qr?zbxm4#-DxO?Vn$sczAUqowa7_m7W}BX3CQs z*DZF3J9>D{ie|6|Z@l8NJ<8PMKipaB*wSn4WvT#XsHe&LLq_qsG7$VCvig2WLTO}{C$^R2N?JNWDX+8VRs zNHc{rUc`PM1pK6|+q6W1BfbN#cd|TBt<;=E4n+cc8p)V6@riQ-d00J64N@MxZBO%Q z{_M{&*Y}g&yz#xjPGm3c+jg2kQG6Yf06D_a?}*}S?;oU06;0tg-rIgKO)sK`f@*8R zx#VWw{$}xd>9V-Z^QqQfE`5@m`)!ZtU0Nq2*b4kQy!>K}I$8bNeZJjI zYrli4RrpL-0=HCKBH6Q5|IN87rZW)RHFuL}Sv1cm*VB1etv@`aJu+y{>Abt28?SM; zaloWLn-z1yBKpJqW3NGUkE`?cO8v1S_hDY}kt(z0VEd9uRmjhs;~ZLESNSs!rDs|1 zTI1=mzv?}3<;vbQkXbn_e3-pyFxA=+U#R98ztz#0^HdMlvwGFI{q&O$_J&1@l{dl} zXR;M;X`)rKXS6F~TOK5L$3hFM>2`a~Y-5yBtR>r2zfQ`d+-9S9)!Z{vQ`_Y+Cbisn z9o@=H2c^tiXU^Wcp{_VR-MhZH&lr)ianp$#J8Ej;1r@^jrObx4&xq>;?%S5udC{;O||2{cYWH-$G2gT#(%t;{ftzwi++Ur z(VPwt^HX(B{zy;GCm6*s-^ffMsnsBg{;bwS()a4FaH|7o*(Zxe?fo% znY&iP#h>~K8SCxjTtV{~wxApn>A3RgV@B2HD0MgIG6o4gIBwRamXjwYc9s5;2{xi; z(Mh3MoNZqTWg=sYqKs}5$ZYv|PwN2xwCK&#En(yI>;xX4tXcQPSeo6Jc?)ZwA~d^4 zXE*l0_QRu7svO+9dp_@aK7)2994aOhx=GfK_@Rw}{Y%k9H>O_+O%brPx?1iSF`zmQFZC%Itlq>?>%891iI^>t|42J6z)AdD(hu z6%Ijw>`-PMl=aIAf9`hfcDp}O;f2w4baG(+G1!j>o|y1<9h=fraZERwXl8RtqKa}{ygPprNvGq4~5a2 zKPw8A=HGJHMjA2L6Xx0w@=PqI=iGpC+~u^yPYRr`Jk^;Rt z7q(}bTRxI=yLV;e%H)#xcq6FKQ8vjm8$JCgW1Q{~)&0igP?;8;%iNUEVPx~k6P~_S zb<#3FdG;NK3e(LUT%5Q9+WJ!Z+c;qjl9AI znQHk)=948U{IoFM_4J`F_J-BhnUz?3s^Bz21Yy=wL zig76_m;u276(i8Tr$#*A*1wYYc{x6~5Qx@J;JX~2rKz6~C))8Z`&+FI zv8PeQy^%;`w(e|xWHs;PME|B!_1WuA(}*4Vd8YNrN5o91gRchNtk_Z6=H-*iWgZV~ zB7IckRR~(zKpp<|xb4X=4E*#DPWE3>J6|q%RTk#;wheXD*2Jn37Ci`g%d>N@t9x9( z$H!dh)02pXG%Vf@(}23{WmQ}_GvcAe;+LXIMxt}<{iZo3_$CV<*3#g~F86#|H!XT}&miag{v`3e ziX%j$_YCVjDIMsiztr4|-<0h;MLTp!3r)hJIz7%?8GdUVy23d8*L`C&qWX3H|H;XuGb{FjDQQ_SFBO=fYrcgj7@G) zHi=XxswWlJML_qychJs#ob8(zs7d{p&`(p8j7Y_t-;7<)mOqaKxW%Z22)Ny;unfJW z;(M>;0hTER!*GZzMu{$}X$#SC2!CD*dN6fqVsOls$_`YT%8fd}5XID}KvOih7DD7s z&3{{EtE&zIJXeBKDL^Q(CMuYfw|+0<()RF5#e~`awqWb7w%?FL+6fIYxF-Otjmp>l zf7m0@u-EoZq(vt^JWnl*??Igg|~84Kh--|@u52}^<<|F z*~0Z?nc!@zuS-L4{vFwd*6o=_BL7Ezbm~-f_W20EZ*Dd%l!@|vi~Lcxte3M-C0^iJupS*oW!HJ(N>yiAh>+Al+qH|jX|5LG~>tCFbB5V@<8RVCIzhPTa-w#cOHbtIP1n%0uy1O$OAU9G9P_6GrWU;};B6|J*cV)Y^l3ncWWgw59&;;e%On$JotXDs|UR ztoUN69F^Oq5}=k|l@HjV9@qgn@JFc%UcC%2@61qdroV>CBT?=(z8w+%T)7G9h?U;{HF964OVDY6 zucAyE9EasPpVP8GSt(|GrZTA>0WZ7}WL^-X5Y;{C zM)2^4aj8dWSd~Zh?(fDt>EyfT^eX|@#pzvBK`#7T)Eg%|nzTe&9FBR9P$ABPZkxNn zEvBn|UX9xQ_bRw6GQ2u7xomF8fsVyyrCSSZDn*)3oCbafO+!{C03YCj7;11qXZ6HV zOe}U{y6>b2R`J~QK4&^R8_Ha@rTy^o){(-rfql*D~Cf1DzCf4a^c{o}D_kAz~ z6r+fM^-pDh@g8{KfO@zg-;+>*hVf>-nN4SImd3b4@L-^#1;I-Lr>GA{YiPk2b?z0i zlOpdcqMITn2qJthjF4XXAaG?7lB3po#bN|($P=bls3VAAqDU>@gZ;@WxxM@B$UZ{2pUeE2MERQulA#ZRefAA%)El`?<5UIJv?NMcing3Xfklqr?@$x7V2F1R6uD)ZI^JIybvQ#c}5MGyG<&AvTGb* z=Yx>M;co|QzAl2aNiJIX)Hs%nq~>U6V{`G)J|_30U8ARhe^FD#lKa|waxxtIXE4NGpOOBu+fXM{lYl{Tr zs~TMY9b8}kedts^IJX}qu!yfZaWFb~5?RnuPG#b|0`}tQ#$j+yO+S$akz*Bl5Ab`y zay`!g|ulUD9;%wBsqsJX- z{2sybOCi8UB5D9oWnxXDIw53Y&3zUAZ_>ORy=XW5luZPVp5ZStTc_ts4uN(G)PZ&m z3Pl>$rZJCWLqQ0N5$O0MU9%D&P=dKi;O%Iu>Zx=@&2lc8hsNs zVrI=sQ)Dq6aD|TAq^P4sREKFoCB}z2qeZpilBuX@?A@%WttGX*f*Dvko{5d^zj^C; z^@!2@QIi(=N*xmhDbeGSCIDx{pkk!=yJ2j^Z6cnPY;CRm_toJwbk=0~dFeK`{$!t4 znN9O+F*OSM1`QRR;pUsMkC^F0%MtKlUAT)F5SIEux#!$i!Lzv31hC9{qM`cl?y+ z1?&qds#)&t&Hf09Ef)B;1p5_r5Fye~%R>o~I17~yRm+3d`Ijf0)k4eT2vh!@ z;>)9pv<<~Qg~y9~Pi=Bj5{D@Nvp8wtH5qu9V*fyKEwG6sRzI9y;&{edS2}}Q%`&<> zo4^8;Cz9R){Le>uzI1hHi_*ZBL~4|E2%^cN{Fpzak`W0qCyYIK$6EvXIz zEuSK<(N(QI%L#WiPl4y|ynUbyi2zHYsB9)D;2Iy}4A3YqB4LxFj4uScT%1h zmt4WK2X~;AyVTO7hG6^6P;sAloFRz#haD6#J@o)!rI;xHH$xwz3Fk4Jzk9HYpv5I-HU$&I@trpZJvevq4btizez z`hYv}4oeA+u>e6oY}nsdQ^2Pq{pxbi4U2>&i74{TgHN@O)JhnLy-+j-Flzm&fafrY zM3GWAA5&gl1{Z4z+<6DA#J&B(R^`?UX=EkaWqs0#d1jIm zC`u*)6^)AkM3)?t_#y)w)iF@@lYj>vBkA*cw232M2OJy@P5ZgOgJ1#kmhxr!0Og|K z3hz)p?-o@5{77SjeMb84H_lb&b0}`!6La1VF9Ypyc(-Ccp3gDzVzO zj=rdXwP~2BTJ`nH|0!625#wm@J7Q+zD~yE70%$0r!`Xd64ERBkp2!XB+NBbrK5m@$ z23tWu9`LgaGYh450nSEmghJ3w;Dvs_jKBBgr7m^k8$hiEsJ3y0JkhJl8(;3f468&e zKgTl1+MD`Oq5#E-x31d(It{=M5Cxj?jH7X-l)W(-;1sy0{wKydQxE}&e}?{@5u7sI}UH;{be*@|E1t|>iMiXG;W}3FX+F{I$*)0V5}>{q4ZpF0(kG5 zdq6>cM*I?x%b#e(|D$`LVRYZ=zI_>xHsAj>gf4wlFVn7-DI;d=4P=cr-#<6J42?p- z$Lf5AZ!%@tUjiX^fp5AWq$ei&pOIvb8U+fzXFYvw42?A~DleA&Bjzq8UrvD$DFyxW z-{SH&L%2JC2l=!A@X;m_!;E}dr2BuSmH^*hKKc(q;5!+t#)5G(OBQlJpTT@@|DIQh z`Z%`rc$HY0|Bn4Tt|fEp>GiI>OrBA7;Fl(>Y7!C#ASMO4sJx8CEcAmE_{J*!C}W0x zs6+z51^uYDqpUWr9zEH`jfZy+25|$+sJ6#&6Fa|u2_~U-QR9vw!OSYT-v~|7`8c_? z9kI2=j^>Wxj_!`>j`oi6j{c7MPChS5lN5%P$(7nc3Sb=qY7(`8H>MdqPlIBb_hz@Y zxu8=v}A*d zmmh$3{1Juj1Zwel6V^Bm*zj-0fE%U?{*CrZ^xwAu@n7T17!9s^9SV>sO7AVbdF4p42~?0 z^p4DqjE<~F!wKL%Y-1PZKow|b$y`Tt;lcT%g!8@t6u`w7`Y(;TSO7RNz2RA_cIPGQ zQ2L>Ayk>r=KNE65g%`xdT-n>i-Utl@FitK5Ml4XoKZ$D2^vca(oIrmJ`1ddWj6j|B z4-a$n+xY%wrSK{=u2Tzj7<`=hm+M%sN6{6%mmVy+PX3jmi=e2;aQ5$m25l*3LIqC3 z+a&lT!6dRIgQQ1E3Q4REaNOV0n>E`MbhGPORo9{t#d*7>HT8`q-; znk9VxHoicn^(7SqBvI)X{2Q%MNKL$cQP3nlWw|>sfiQu?iOGr0iN%Rig;|ANg;j;) zywdH0GcScvsFvQK$ocLvC4Uzi5AS@5-wDY0kC=w$J4nobk+?<~P!gOC>9;}u%Hl8m z)1Z8bKh#1E`XA#2Os}Y`puZyjH?`UvMUl`9r9`%ogZ*d4x-<-5xt*g`y96;Dus8ar zl}_wcalIrL^u$VPD=%lOw*H@Nx^VMfJF$RTR!gN8)&v$N7it%J7FrfY78(}@7CIIt z7IeJ!#)bvJ8j1##Mj5cGUS!?%M61XE4Kf0@1oQhU{Si=gVy`OYMe_7rh4polFH1kK zpAirS6|WqCY8HK29scqmz%NjV&49+yaoI2a6NwqX9Mqn0vn=Bmm%Ze#dXGv3#M8x2 zK0O#o6!=TOd(JgEdqa9NutZV<5y%AXNnEV|>@R<0T77e=9fLF6hA2>>G%NMk5yXpOq8g#c`lI0!(7Cr;+>769ErV>G74?7mb4&ovL2>NMX!S z06#NLqH6L6!T=K$yuj3>7ibt32Le!+KJ6*60=f9=>2Dpa+Wy{~-?b$a+^Oc4KePgo z$k7P=;cuS~EQYosPzfmBMC`|=hEx!l3xt?FvnCGk{9m@S2ew-EI66Pw)QI7Ed)mC4 zK3H?!daix4UE_MVo94>pde}V0vQ@u+X61Z5GtYgtTeGj>a(FVUA*Oa3r(<}wmDW{r zeAvZ((lrDW3O)KbZRk#5u>frb@j}S}NF4o`M1ZEV`%Y3LcY>^q1&H=5%b~uzvK0#H z*%2YVJo4kebpV7ylLTBg6Wkb6GPB?Xt;fG@W^d%B_M?YFxFCVouM8iIlfB#k9y_vs z?U%riG7cci4`5$9>l60I%%n#7JB}{X7YNJMD_B>3?@vv>jP5I;QSGCowbDTT-_zco zk_A-`#P9QuE<*kTuon#xh|cTn^&eY)@nhQ+oX`MDU(%mB=ueaaL+BM1*E=vU@?Nhf zS6h}uo~0kR0YeZ|JM1dB1*}VRw7PJ=t=`{j66c{|Ym(I|xcZa{y2xq0=f8V zegitr_3`kE4Pf*OEUy7-7*In1dVhii^iPEV>gL#+9bTX$?f}d}a}g*Wzv+V>D3EPp z!76gyOu%_S)?Syq=tn>u!4u?uBA_DX+J8!NeWtpork6G6zhKk8R+FH|f`5^_wDEcz zr3%hk%^cM_2>~Yvz^9_nT6mqgD@OoEumyl+?yVnc`SUyfWxy$&Sr9Z$`dEH$jrOP0 zLnoWxt_O$dQ%$Z*J4?Nk|1bt^OIPg}=qIMlJ;*@+>m#sng|)j&}kRiTKcoaI!gGZx9DTnl- zuBG1*a;)vn*&F)`#L&-# zL8<+CiN8;07Xv2L4bbBkCZ3I?zZ{ZxKGAPl|9}FE(nUP#0te1hsr{)*VDQgB^ZGk* zp&?EWq^B+JX%H|K0D=+Vq<7)_YZ(P-77K)qdDi`$;JkRT^5Qgc-3ymF1waD5J_2p2 zm&yA(vA`b!^Z2sCE+Noifg(x!djJ9>=wigZHclrctvRG;!f$}X#Gh#lY@HXq{tq3% zY&e;5y|@2yWe-;qbgC`_Pfh<`gTgTZXA`UA*z}*Kg+fm%e|7_hcW7E&oD>BFC(!={ z%;iW54Mt!Ic&GtV@;eaefN?cdGKd#7=by)VucOPNeXUF(7hlaUf3o1>?E#bp@C<%E zyML#^WgY=j*YDDP^_JuB30V(EP|5#exd9G9s046C{*&f^bX}b608fJh(0`6^Q06aY zZ2%OI*%yuPUzq0{ZGQH@6rES#JB@`uRsYhb*J9sR27IY;xzj%r9wg-Iy$2|g|K-M* zBI=*P?fQZAqM`~qnfFWWU!CDD&a&XEBj_4vGrv3lurI}dgYrej{QY7Ac!_k;6E69- z04dnz26OEi@M{w@5HE$$7eoKh0|r6vRk?$(+8Fe)wLaXx@G=nvd^z7{~k3i>c#I2 zhEDTfAO0QV<(F+8THpTwu$B28(TumGOT`Qnr74g7as{cRtb&S|$Kc&hxnu3t1b z@ZH-O@V@IZIsYzDP-H-r`Kt(@uf{50y{m-w-9PmIuKfQr?=R~A9+Lo2NfeXXz#02@ zE4g6gs`dVJoc*g_{XNux8f32j{CBPSTkdKi_>I~S}{-r})RH9w?!yte` zaHuT#=L`TuQJPJ!3U9<;<YNyiUaSwlreOmGxfDIIY&RRJN^=}U)cmuQ?_2UX;-UP zfDa|1eg4|P6~tkiZhA3ggFB}m=MvZh$L(cTA#n3aZC!eS%Es?kV1dJHDG+hKn|u4q zFFE7SPup_2Pqz=-xXbiZpRNmrjUB2A7#spMP0n`=6)=Ggwm0P2DqzMwslEHqLG$gS{v%E5 zLd4`xU-4VQCSI2NEE59Xs+tAgt@}ub^$n->lL~ih^dWcBg6H6^>SO3FL0I6L<|*O9 z%FRX69Pap7=sHPK1G^yepGS;kBY1$iGbUqOc<{$_SQE8Jyg?(kdc{>;PiQX`IJK=k zo@m$=tcL16)k<5qKS-e4N&{8Ea-qOl_(Fj~@P+;dx={ToM}RD?t^tVe6wMqeqfyxo z)z@YVUFuRxS?<2;Ck5TJMj`~dUIF1^ufolh`v8=4*=JBF+~xs*E%o1_wz%GlfXWiQ z(1Y$JNP7V#f!7j#es`U)0MX-Susur88LCV#RIHUBwED=0a0@gx_+k_c|-`jzU4EEzE5H2=%R`p@JS z0g%#ipaGk|Ai3c z(fpz!9V4UW-rkQXDR`oy&mj<7D(Y3m|NFuJNQs{Ca|p?*BBV%13CODdyZQgb!R!$w zwbEA}dm=;y1mwEuyFa3+R0%o4K0NhED|r23LlGkfC9bXRVVyfD#L%`Yr(F8_gFRVa z-G{f{b`067U%h~v-isSG=*>?+rJ4Fyo)h*cTiS76;G^W?WAEaFg>Fc}=vMv1pF=H0 z9zXEG56_Da?~4!Lix2;@YLPL_9F!V~ROfs9;77p4N9@H%b~^y3?e&KP8wP6quU^1M zHuPhwqAiO1WNV*R!=>tcbBN%4>l_9K=KSIh)4=t+ZZA+8G-ik4zcUb_NFoq2Ah^X% zx5@?X>?sZ zs1697_?~3p1Ud4=_2pbulKYiR&P?^Pr6cLKAX^!tr9}(p&8mzy2472Z6sYC32CdOP zjtq9FARY$OyucIoC@(eX4*OpFa)HpHRblRi-iGgRB06z`m^&E;i#(5`c0DOg>*mmc zh|?MlU&|WQ1X!3?qOfoeU~a=80QZD2tgZ<=tXVKHWz}#nn7|WzQ(8LW-7~KPB+8qM_Nu808v5gH_tsV)m)L{v2g+y&W-nwNW1yV=rRUr}g zbcO08hZP`eZ1d)wKYu*of2}$CTJ90~ec}gs(O*J_KHWS$IAe-V_@*cw!IvKWaH0L4 zqoT`6-ZRQ7MwKR0n0v((-Gif~&BNW)p$#5iw3uULMMSlK$XVnWF%hT03%?H~kJc2n z4^Z}0ovKgx;ww`kZB46Wrh?W1myc32vemR>8ZyaC<}E-En`M zd4ngsk~aAn&essck%L&>(D&`(qVsRnF%~5I)rj-*-|{6P=-1{R71kJ*k+WG3>pe7- zf4CqM;|jbc;ju5Q z?eB}vGVMcZlh5~*&u&?7Jl=7f@Z&n{IZJg9k<+DJNkXf!H!9u0O3{ke?Nf?@F|a#I z{1}flWlD`(Pcwm&`6~~0_YEv0V*VlH15zAqq#H;tUy-~(jeGxV4gEvQ6Ecgy?9obt z<$>q2%gD|gpo(%4e&U};5WCbz@>Onv>a!BqA6UZ3RT*-7BQSeilG$kGJuRJ8;Axuc~` z$Bl!lV!=#e8K77KM1;2 zqA47lDjIRwFShREpP%+^OLCnZr^P#+_{!xd%`UCzxLEQ^vdnM&!s09of-l{fmd1B7 zC*UYWUR!bJ-JRB1DB5vy4v9;Xe*GY2#&7ZKkfKQdPHuh=c9)wnBzCYYz%_HSSHj3=FPvts=TdDV@^dh7`V$XL7H?f6p?U?$>w0(RH(Mp@FxfQ#<8PDx< zy!WG`aA3@9Jw8s&B2JZd43T`6xqYHgvMUZxJ?8XmEZ*g?&wy@tDh&%!Qmlpbi*DA~ zy}`nAHT~A9kbAGfZ&&o>jCF*n7!BQAJ(^fvS0HfS-#A@nMV@lzqplp$W zw&i$&$?++#Y-4%5^ONOzKUoomb<8yLPis7^@-^pU$K2U8V<}UWPMe4Gsb2eD8zDf9L<8A%AgnSioQ*^Byc*XC&*@>c96LJIgVcUq2k$A$Li3$nSapm z3s{02NbiGQAh zonpEnsv#2kDq3HqTQzKxe2~{T>rF%JG#14UOX-ks@4bxjSTfJUNj>Bkwq~p2=}xX^ z?M`C%KaqLu##NJ;?2R}&o}YQ`yE;0ajZK~GEDaqiaMv83?IHs~cytz_F@+Pc<;Be} zgZ+Gv=4N9f!`X_tkFAM?vnk>jRxz0%e#?iZ&EhV+$Lz=0O ztV2C9kRM??xBI0OLKBVb5V+ zs{KaZ&(UTI&AhrQJ1Bu7M4p;?6jaVC5g_+$+xea1r$^` zGdOzwiq#A?8cSaS$i9+{NGYaf3^g!xa{A5g8Yj^g;%i1drB_rJRLqfOgczMY$M~e* zSYF5QWyIDdFUAbD&2YTVve#7GK?eD@rh`nLn6p&+C;~*>s;8jN5?@+}S~0bjQM$>} zI5$+6%BmDcv6E3a&y-+%1m4TX!6L76O~-+=&N2}xP~)|5iY}E!hZ`?MTx$e#id^TY z*vw^+D|4A8XBwg__&#b*9lib8Ayp)6X7=q4eHi_mhIbC=@5`h+G)ZARG$&;>1(?Tj z?nf3WXi7wj(^)Ln!U&loMrP37l~=h@Xhfqduh|I%#;tZHdx2I>iB+4Bd-`j( zuMLs z@7au4YAZA0VIP-0)l97>S6qc_Pc1W4de4TOk&i*w2YAq(t$0Y7A+l@?iEcjXiDt=# z0~=U1C--VA@!n(E(n`S0$%@=ARC1{SyhjImPfU|V_DD&sbOQhJh?Hh(*$^C~1Q+7m zgmLc6LY#Mi^E4;E-hm;Ew0jsS)lrfO3;b51roaqFWT-xR`>`V(Ovv#~{UtxQ z0rhXD(SDGJk=sGoCN~(7;({3>W!}a5=BPnOC9Xu)v$gXnaL$6cQrhEYNLTV>!k)eL<)bQm7G z^`~@6K%m37j{yJjpoyA}tb;U?b_wvC`U5%{jR#pY|1U_|udO6_@4&`=Cptg!o!YYIlg~UEtKOt}BSfc#c_%XbBg7l+$RrjX6F@q*cUBPJj@nJmywc5N9 z9epj#mvUI7_gGmYMX_G`%lhK5vFgA`!Zp?2XB3h_5y_FhabNe=_aFBe4L{fOTH)1s zm~S(|r0Gw4c1{ z6EOC*zTd`zEAy#ue)zWTm)pZt`WX1`vz_XU?Z~AAF>%=t%Dj8w<%)Ya9fmVC&HA6% z6bM`bw*}tFOLuhbiuzboFijeIGhX#2dK{KvYbtC!N8WNm>TxfQ!tlu~Z~_=v8A4&w<;Jn4an6rm!^ ziDFBILmi+o~}M1RWM?o&>?0Bk;d;PjP!rd zE3U0D)o+vs%H+^bRwi8$CA=-l?8iOKQg(4ceK(z21(fvzA$Ho0O6!*mDi-qR% zOlN9}*t8s0g={BoR`j%!;KI&z3NZTTju}XF$%{U`;VGgZn3YfkGfaN8=c>Ynt? z!ZCG$JMLvQRaDz)??yhju*KH57Y%8ytB3!r2fO^aQ5RE+dUBG$o9GpH*G&TE= zCd>P6i_by_QNM2=kL3!?C%+_Sr$mBeHp01Uy)iTGqnJ=ldd`G&)BTObtB(>gh01AZ zFO>;Clg{3xr}&C4OL|tYx!Q6!`Wo&1v`pS$jCRX+XAFZPmo%sO_>b+ zV;YW_2=x^GP3=Y^8G<{VH_cu}vCPv}ciam->Jjp{Y`cZ~P`2b=ESxc4T1t;_H&KaZv{fb zUU8%@G*5_zN4SDSBDPB=iNsBt%FwT34GBxdAVw=R27=k4cW*7{<8bv~=_0ElJM%5A zbPL9ia+#?$r%|)K5Kp$^suM^zvf4tWc`G{sQ$f;s3wM@ykeA>+_WMAgE(OttIRfyB zH%Ofcq>QcS^K}RkkXkcV;sRfMV#u~4U<%euNexWD`-68B5NI{=XjIME6yb798q-}k zS%UfS)yIt(4Q*cEQ$r`leS)v~*gJED`0Jy=$$R=kf?vB?qY}`L<}R>Vg4o&tY~%r| zcsC7(#&U-U9^5qOuqa|XM8JumVP9={A;qQ5xPzLGdf>g|RGd@yqZf{EwmOiU zxm;&5Kd}4uY@S`0;Aiou!7}7g!93|cLD>%*BkO>`Y$KPpb50YYQ$sZGyzW9wAWT3^ zeT$u&NV+{A^U2+rSH2qv{cpH#GDQl$rp>CtYR?JGyJ6j>=ZQg}WpkgAykNfGi;Kuc ze}Py6UAZ*J3Moe|y5;3h%FvH3o`b?aNW^T-h$rM=S1`B`1GiAe5&~ZYd=pHb&n#}4 z@@$2&m(~nr4{Pg+y`sQN_K0Vp>>YUX2Pp8^hXa3=lF=iq<cwoBc6oiNi zaBbi>6wZt$QkyTK8sS>++39)`#ch@>Yg+D6bJgj&_R(Q_PRym=mx${+@b2?i$(E~Q z!6_i?&6vVAiAWnHGgBFRtPy6;0TCUps=PmUJ<{(vv_E1hE|(kIYknNJ<+o_Ok(J6`K@XmtvmIr$2j~d znqtNx+83UK%C~^P7B-DmQq$8LMgxU3lDAM-m*0MfnMX@pC@ev=iKUrI*kK5fz5wK(8vb{6<88>LX46cZx@Y(*$3OIS= za*r=4T(nbwK&7YX@Rv=IcRA9X!mP}gqN8k6cPJAq?+k2=NjH#u{%Cgx(>qf2=6>Di zr`nZrxCmbfeZxbNm+Xsh=4DE?XYW#DdhXcc8ICaS@iqsuKeNV7yCbhUl;BokH$)U` zh0CHS^(l1bwM&xuyDIbdhzFWAo4e;nR`Xe$A^|l*UGmG663F4BE{XlG4iTITc?gQM zw~)#l3AWy$MK>vBh*@HIR)1y)`*BBt`xy#e!cyGCg~h zXEa;#lqj-jEd8pUd|(YXFLgosN@c^4bhpzz#(OgsZy6D{ukiR&MOXFF(q7wS6<*?T z$B(X3S_3BfSkY*L7+dv-jh)4Uqx~8j9@WgR$trwXDfdP>Qj8qRscIh*CE6Viw2jSY zMzFG;Q$G~U?NnQMEz>mJ_J~y@YmMu83twz4p1bn=Xs(TRFuun5AUBYbZ@BtJ{)TvU z&H3gJiyDr~4;8#2^g}ktyt@Qi^XEFZ&giOsF1Q5R!ecB*M?EX~^(h^;Egw(FM%?;w zIajhj#l07f@UIJ7kB7L!{p8wJMTj?#j#*!$`@bEEuceBvErUPJ?-|Af>Sc~_NyjTx_{ z#^Am9l7R1cA0)nv<$Cmflc}9SANmkf%*;Faby&1{F=0cXmSy(*oO)T5ZV0-jGU*;QXMb6*cRN$zH4Hfm8E zZV81OY%i|a4wA|tEb2Y|~+~p4V)%OwEnG&Ka||)NfVAlC9b( z_P$24q|H8fyCcK=Z8E>HP6r~x?$D)auQpi-OtCoxVY>o4ryf`&6(iB^kBE;)h zqivSHEpMCZ1}%NZv%=pFDM~C(Wfm*w1ifoZYs`}+_{yKwXc>0$LMHK3 z@kSBm{^+Qjd%qfsOCpIk+P0D96 zg{Lmn&0L(t7&tn!6fK0^v=l9c?U;o~!H-*tj=w*c zH%q~xDP1Ug0I2z3UzP&dgQ)20IzC}K|Jl;Y*hVc-S~&hQx?9;CwJ~ZI@}jJGJkgU~ z-JD{36}62zHO{b%Bx`pM^Ub}juJM{|6PO3Vm3%|GGEMJSuMtoi|PWvNU1k)ONgM5r*SI_m3{r9?AS z*)@3Q>qLyWrqL9S6BQ3|-&Ag+{^otuMlGsLX0hV)#6_C6G|#+vyiRh(Qq%>PrZhQJ zYoY@wk-xBwIv$ctF-<94fMpvs9Ym($K@^&2z?TRW)1+}rM9Se=$VttXQgl7K$qy8{VqgKo($)O(mNDh@vw&imyDZ$D6V2 zl}-@McM7KNURwWGNB4k&PxXdW3(bi9IjujOaPmtL#1tAICXr{I$?<&3bCPVgEJ6*& zJAl86dR@;MpcgNleH>=2CPO)xP5zKOKa7(5K7|~+(DOuDI{m`1yHjI9(r^5t!zlkB z%DyrvuCVDc2^w5Oa7%Ct?gUS87$CR>cbMRo;4Xo|-QC^YVUXbNF2S9>w9bYSl*R$zaik#B zK{KDF{Id4%b!b#vK9%~)6uiG;l;ViGlLi&iqFe>q|#Q* zgZfv+LSrVcKe>-_>@JB;Jykkv^mBJgVZv|7sEI_R;wnl^Up>*ucfY1?gvkIrA5^Q@Ody#hQwAo(8lkor+Ptju7A>%SwAHfDJNm(VEM%>sc^u?AZ5cy z<*>hzQZdfTRo+t}ku1m-6D^Pll2j;c^o>`_S*DXxi7XPjit|&lb1P}iR8|U{!j$U4 zUK#XL`YVGr-(IBb67FgGHbH4FNZOMJM3?xzG(e=_?89GzF9o*B9xKQ>bj-bwNLt*k zR^bBUn}A&9@e(?j0{?G?mU7WEs3DkAM(2$|Kf;yfnyu%P0n9Oq2=vY?%1_@*O*JUN zz5m$+{C0q5Ng0k$lpE}-bLYahvew5fp&4Lm^=>DC3xg=!sNc%hmUZniDd1wk-{#$` zknDXN9`^t=jK(D2aUBYf!T@`Ii`2(&g`3M9olcG43X9ABy#MgZ-jj2$3?5<2ct}M< zJwtg7LZ{%EtK0#hBl{?|RjMrf7F75Ip#z2#aw-$%j*Yj~e3XQ@Jfv!lK!sMa1!{Gf z$`9R2g%8}>%CtGdfl9(vCbYP%b>ung?>J~x#%Lr92*QGCRGJhyaw@~@V~}teat3W= zK!qiF$`|><1%?Lfv{Q~^1!Cm6$||U@bKdOzRH6<0sRWtJr&R%XN0E+pT!9X>ju}(P z1YA;37p#Q4sgd@P&}&hLzKjNfW8mPc^tT)Rfx_zHUmRlSpyTL_nx++Cb;lAZWKyr};dPhJlY7Xm165)bDN2wMSj1YLk}g;lG8LS83)W&f8aDIS>36Sn{BbP&!aA&%juz+*E@e z#;aqd_cBn`BsvuqItLy|n;wQ0e;z9y%J#mf9OUHfuv9RJgZaJKQRhpHv3XjAjqQU0Md$`#9ioQK5x-nWu14~gkLEUg`#QwNz;Jm`}7eatP08zQ^!#>Li0 zkc>ok0xtAO107k&^)%ww))8Pq=Mc^CL<*Z3>BQVpz`3>I$^l~48R&h<4|8I#FH!gHD9d)?i zjOcL;i#4wjJMO`LTbaF23*8U2^>v*i60`;gFP@x=PAEM&n9koL1SG4ana-o~V~QSJ zxF%4R#5;8Nom(Zv*yHsK-p zvBha}uu{%_?{A|uW#GmNj@!x|0%c?$<+hGp#NUDop9IQ)n#ijRnmBpkAJEr&^Y~p1 z$sD)slgw>pB0^0&KnnmQiR=qwL>;^FKc|m~kCIia5@uIxRFIoTsv_KBf0#F5R z+xub8z?1Qm+osQnQ>)4!!|@g4vEZg@FUz|-652v!8V%%BrZ8;jBGI@Z6Nua@31Nw# zoNq2fdB3qx^MDHJc&QLMphCET3VE6bE4!{Mzi<-wKTZPu?XI&20`XEIdH<=9lf&Yw^&AuBQ zNms$X1qJ6-CQ`9cDrhc*uA0Y=&aDNq`$5h~WYI?586_{Xe}B3Ujj{+euTjgYu!;7S zN?eM?Cq*J(klk1fQr>#*n7l4OMDo{?BDV_Cka6QrApiA;uYeilNfc!l#|jQVP==8Y z$PWK+M%#!)n6QC_`-<X!1&vVU^0=ATVv;Vhy&b9TCQ zWuO;I26`bopchI8dZ89MhrO8>t^xsERSMD$p9XYc`$ZS>09^n9x&Q)nf#*dR>;PS` zebI$vKo_=ObO8kD0+hlH(1jhB!3?37Mkw#45$Y^(rb4jNlY{K+2E<14KvL>A#{oZh zwq0qG>EyA>ekCJGPF=Uy7QQr~37}7hlX#4;|74dWuaPE#v}@04w9wEWr|=&6{Xye3 zA0pYAm-a1e?&b{l7MIgn_9T-)xL3!_<6lu(J{{LF02e8mIviN|XH5Bnv`aXrwglU; zH;)gv#ZoNB1Ou{4aq|jsc*IgDnkeNU>y-&i=}HNqv+0h3uADL*=caS3%I|MH&MP|# zYRyrw-rRPQFie$!6pKAdl_(`C9*Q!m2@*i#z%Ybe;U5F$DB*p3I;T$&!!!ddJpZUj zV|qvV+ha>xQ6i|qx(85;EkG^$3reZDaoOEsLFBOij{uAml=A-<6O~FNOX2(uW+qHD@7znxJxmAMOBPy9d-;90dlIaq&XT^aj96kJ%unb$~QUwDUB-DeBDR)(pI zH7*vYT)GrlD9&t^pgC>5GMqyklT_SmGV2 zE&>h)3hfmCsbczwV)o%Y*q&U?WysMmJURcBy6~PlJ!8HM#8GGLT;D)p+|&@hgf2+Q z$J@ERZDI@$Lc?R4keT@F*Vg!+aE?q8>7N)E8Sk;iKnee`KPD*@)vNQaslO>>2#>Tt zkPphi6;dCiX*S4DQ<24K=~;nn~xt=XhwKv6xY79nl&SR zMDBTg^SpI!_fQKpdD<2I8`^Pt0sfkXC}Qjz4&N&PjdPct?MrQ&Rb>{n?xwi>atc zC4Yy2Wy>0O(y+2bO`YVM1#>Y&y$+nYiE3=36(e%c)^VL$LX)1jvAX&bfmZqN<8S5_ zmA}^#T5E7(L~nUpMN|2uMoX)z5ccLYZ|Cmc&gZdKgEcnSa;n%F%}BGsQw#-bCPgEI zxs}yi1n(*<9nYM52780%H)M{&l#dikuRJRq6X>i|Ipt;q2WNCtuqrB(&E0TyPo$V_ z+XoYQ7D%J2TM}v>Va*n(&uYI1+cm@k)azxX4h5;H$21DKlmtTt4$5sP9*S?5^*=0Ws8ja1sah37Mn1U6 zV;i`ZSTc>cS*s)g|GV07Fc=zv3zoIJ9yHYB4+R$HYAVT=`103Hta*gw8w~d8_wl=Z zd`}eGcd=502d~*}8-52u!lGOAumFEbs!#M>E;Q8X|28q6$JbQa?K>S->Cjtz@IuH_ z27>VTF9FQu4>Oh zDuLXxpK`-b0al~C(}_+G-UY3i+=S>GrO2GF#vxc3E%4$#P^#g_QsR?aGC4<$9_h_% zoz4@f&rNT8e?wKXWOa@u=^4D6TaBY3es~kL%}dIkf2pn>k4aMeMs*w938FMm?NuL* z>eSQZpqF0XMl-GzSDhY0K}T&jASgybBUSE-Qd9qmik_Pa`D*RFpFkyNZ%^(K*?D-X z&|F?gCcqz<0Ld|4=tQR9IOdujG?W`a%XPEoVmr|&F5XPAuBa3az7gLF42ZHXE{^&r zSj4F|CzE=^PM)hirr6-GQ<2;jZtyOL7FnuB$uSIgQbx)5$`RI>QDcKEy69JiZ$qO~zX)e8-E z4raoh4OplY%LG@vWPMI#fD#gYh<(40NJDHuZvH|?GR+I*5+sEfs_!1+_{b97+Ru=Dv`MCUYQFPVu@1c?UK-m?PBGQ)Hh$6*Ev<_SCQ@$$9ccjn)j( z>Q4?>fDMc|Q<`^IH4;Xsp#bry3uQcD8O7+5scPrNAk+xbZ)nKyi^r&t1pmgUZuXfQ zrAMFlGrk!gT@mhbuS##;Co)Gp9=A#-Kk13G7_F}Q8=oow3~OK(W_SF{KB6GUs?z7 zjX;{zZW*NJH`Hfqyto+Rxg6_)LQhDY-Y0laQz?PuYAfXj5$D;Bo+(sQPxd8=0YI)C z^AXWEQY3ISm(-z0J|Ba|kOM_3hJFRGjPgZ6mLJ5gVOP-)sC`yfA|LaT;;1k|2zhaF zTDYfw+k4gN0ZDXEm+rxR-wS}>d3G!)#2v{GT=}9fYs*>xJq$qRLN8t@J~!KBPZ9WB zv}e%o3Ff9LRg;_-q>;}jd{oL+x7j8^l_#yT1zjx9qN)9<)@t+hH9tL;xEv z12j0`xMX1DBX$`wsEkgzr>0K%%|q3yyfVS^(o96AsUlB4utwSu13mKDw2yfNWI)-h41x-p5ygG1sVw|$TEdV=d{PXdg_xEUL)u8@9ogxl zS*@y{H$byR#vGZCpOzYf>FMihQ}X}{3G+D9z@?8iu%rbd5Og@;W?$_UGeCk>Fw&7?f$`7Friwmh8|R}vV350SfRmHGcGpM-uV)r346(s>*m>{S_jvIxrE|0(l~6rloj2tU8$(Py347D&ph(rP9GZu(crs z2^U=fHc|PFIYO2{L}<*p)z8Zdg=;^qVyJeRZLwr!AL+#A$_t?U<@$S0yMwABF9;oV zlOHA2;)2M7FA}aR)S9A}pKq($+$-)(Z!PW=e?OUQno;cGgd8b-KrDabU0ry$G@7Mn zA!zdlu9&JuQEH~3B2^ysy{UjpD#D?6o1>zC@AWE^wfdz=$EAVY`TqCm8&^zP)w1zZZ4-bRqW3(^ zPJ1Wkhk%|FtKRL-g?_hMB+Jj~Xi<_*X%dkQbf1U!z5b08f>B1=?TA~kZ;0l0}R9${Rv z2z-jI>&tihRsP!o9k~!anxMwhDfNOlX^E7&phnnvnwHe%IBOrRc*f)SZ?^Ot=tzX> zHO{VMi3F90Be$$j++o}SjiOh9nwRqCsXu{X5lB#@>x9E)sIJBOl$MU-oLV{G%OYce=XN6h!}qc9=0lnm~8Mzh}tsQ$`qsjP9^6 zqy&*TOWeQpgL&J_R!V4@z>$<{mnksKR*H(R-It1qj?tZJw{#WCiF&Kw%b^B+pJJi6 z{uP`(f^YSx8)#yi`d3WduFgSqv1BBeeu4*TTD5Ktz6!MlecRfa5<<6b@ZI45zViyU z718O9cWP;^ioKR9k+XysqW2L6)HGZ;CYPQ6yWp?_PMFCi8;YP6qUN8}3YYgHKa%X6 z7D@;bHW#>!m=;{2Uw-*2b`3OMg|7WV%+GM{T@{1v2jG&VP@qb+v!$ZQgFdoAO@%Tr za4h*Za@X+HtM>4z=f4YV^g8#-9^!urOCb+J~=s6 zJGj#y3}dN5hs( zoaKQ4Wlm!#K`MV1ELMT=bXzWuWj=u%Jv4RP@1yAL6e}#cXb79!aMe$?d3hSxZG33G zm9xaOrE71{l^V33Bh`-3O#&r5L|~)#2;b@o+7)V1p86^Hq)6a9&PLx$Zo$oXK|IS3 zbSJ3?nF9_=D@RSwhk{<*d9eTI&Kantz2~*u=B>GFuN)Z}#fbQui5F)IdS9IJdHv5B zqVgAKaNA|Y$OyS=J;W2^v0ZwN74)=~HfAn#!eq{@lC8q6T1>KkfO7)oi?)iU%$#V^ zP_hrEsw4>HG$pP=1=(4Qvam?8)cpz z*H1fX$0Rz>KjlYNpS5aNT3yeU+EN9Y-7Zhzt4E*f{hcB5<-O2ahv2*t*}uRvPM;}= z-wcct=@?pJ{WGLHp})Ec_MRC^cGH5*_SpcN^(Xqb1>PLY*omtk6-JfjR{|U)stNZqR` z!t_jbV!MAG{ESTGJ%Nv%a3c1ciA6%!3Ye>cNOYG{+B5_wIubVz?R)9}7G!P-vKw-^ z;Id%8w0-r!gZdR;7gbM66pI7jihc$&_t0;>$3cv+Cf@&p)7Z2Yzm->#>UIo~vxEGL z#VA-~*9sV~IV&Sh_22Ysd*nZ2B9=j`ZH^Kgiw$|7vp4`c_O*4(E8ERRL~eo`=*+@c zp8F-Ual%RVcg92LSh zSMFCi?%63ak7XZtCrDl_^X=mcch7D?$?*R~Vg?<#%9KI7TL@##L+V_La?AtA3wsMY zoAjaHvpo3EAbcSGb$aK%IXZT7u!N8jQN7JIpNwH`6OThIlcfJHRNWb;laJ5L?B|jM zfuPn=A&a!q0p;RJW|YcL+o}Mnut3aIr!g^E%H{?yi96iRq$U&fs-V-Q29ofu5Mt7Z z51;^Bj6CPd`~g!;xVcL??eZ1>6%@+8T;XbC^uS~`0@mdk*_*nR0 zJYNJev(LkbPWM7IgNP?K&!@ihLOW^ySsV`k7Je;-7=tK-yz_u;Uy>}@8+$KyHzh1% z*=Ucb(+Z`AliGKo2`olUzG!V#eoEu(pOW>w z4#Z!xCWR5lUwgDdNdRpTTEqM}NgmbzXBWi%pIv&Zl4Q-{-Ai+7tJ<-nAtNH?Uv);02pp(jpjh5&} zglgJk=3<6li;2&$M0)z!9-3O@goOmv(K`_e5dBm_dtzKtZ1WdRR_C2I_rvWxAI(w0 z^qs`e_(aLiu@J)A>9R`@a`BRFR_S{wz^Y=h4l?%@U9$yrOdX)bf3xNwwl~^aeN1Jo z!Q>KLd>h6o>ASG94}HN;;Raar?`J#z$((}7DU_j;S+$AoJ@v@<2I3F(PvM(aN(Qb3 z?p+PS1NfU(-1D{eaabTsBfIxg?45r{quzB!V~AqqlYQ1kUel6+Sv6qw=8 zdaqhAg+%YWV^>4xZQBU$3C3S5nA3^D99^;@U-Xw0j8msF3;tKLD4ooAh;8pFn$bqx zVLK0Ihf~5v7CpvVHl`mWlCV3E>`2DHB68t8#rjE-Cv!R`BKCz5hnx;gm4*w#`by{C z!UKq&qwZ*vKBAT>vvmUWF6KOsKL~mU7-_eW?{{h$LU?4lD8h|5`T0f;9f2&_=M%Pn z0Uv=0PRLiKQ+ic3a{h>-|BmRO?b=ukhIQ9N>JS4xqEkj7+ZPtZwnNGX`@mD){!@Td zPRf_&-ghl^6WdO4E%v@Qe+hjo#eWNZuN?MTeZ_Z7&zkuur`k^b-sYq*ddo?fZ4H!8 zml;XQW~C9tyrmqBH8T?$d3EJUz^SZvomGq!L}8kUI|c-ZD?onwf)(`l8hY`2aDM+G z*AhYcO5!^KWT-8Hh$jEP&=1-=U>=v2L)29N^-)W zyxzn_l<(OLj7vd{T`<~PJh3HY$QyaP#;GRvgC!|HEcW}JB1V8)Pn57EPvOJ|7#Ez2 zH=1HpdT2NZ`pjC<9Xzw*znCHR61*Han0LRg0?#%-ilbir@N#vVLd_AG8)(IU?)=E{ z3cXGL;wZ3*&M{n4bE6a%+Ticg6si09fs2r`^y5k^{UqWi2~<-PUpGJw71M3l=0_t)Vy znSw=HQN2OHND>Z_bcE;=8A|x^Ud=GcvG8)jXKn=|_lpe$?(&dGQrIp<5CQ2UFHtzo zh-4cfMx6CI!@&>3m4{s?Y`eo%NqGU*)45WE^>o9wB~|Zrt*-ILyN}F1#X^fJYDDOH z5R=U&F`}`?L8B|m4d>J;QjY{zxLZ!OV-_FukOyJQ#hcubM>Fq@^7zn)7SwR;J)E-= zpy;VL7go8aUOA0Z{WFd~{Mh?P|4Q){)n_>-KP`^wqtE0Ti2;3>XFg;+=29@X4)H{^ z1e;DUTN7b+xMxin_W28oCM#(NQ9RAF-zx0+;gRCV;%r(Q=yAe{ysITV-!mcbo?)j2 zOio8eoxIs@uNCnWG6>&E5NSnDh#sJ^^nxdSck2`1@Yl-veiC*>|C6^nAv^U1&*lQ` z)O>QJjnB3+%saOP!hhCTh947x`&UY@sBD2uTzTOBfp$o-iO>Q569a#CaLS{^-hTo= zmZKR&x9KFht56sAARd9DR~MWCqj^1o&_K4bC>a;YER-2}6rlej9TZ90J^qWIas_T8 zLuS@f==Y0Ro@lcSEAIE3|3Qsm>86*A-|_n9qacF>V9cHvZ-6_Y3{Wb!obhrTdKKe8 z7zEI6eQbFfCws}g>gJPv@+uIK3859hG$Gy!D-d(!{CeOm4#z<~Yx?D|mkB|-T^i&4 zV@2szA_-rv*)#pCMAGvuuq0dZ;4TSRlp~A^cPs2p+|PEV{gZeQ_Vy8xFTrHXq&1`* z%=_cQ!Ion9jTeRiS8I%cSK@m<28o|G-w(xj5!?yC=Z#?A3_+ICzcH#=#t=&<_2)^` zUNuqI#hLYBqmlV6gxloIo>1B3VD#Lm1~ZIuk!`ji6Y*Ho#7sI8s!l!`m)mcAN!*?) z!Evx@wy5|R8C@<9;Lr88%Vpy?SmLBnB}J1~4AqI*+fTA^%k?THFtZUNGJa?{c`nW2r|y16@2C#&cD;C%fjS`=jkD=K$f zAbgYDKXDH;Pt0-{G>xm1h>pWWX{Y3c39%BVN1F7D4Z`_0|Lkn~F`b z2sZTl{disNTdCA@cWv`DC6k1r&qDu4p*2sKoxcD4`j1~#rc7(zqqFMYi%q}gQb-I5 z$;)N`;u`L;CAcS0vZ>q{RYk*ie>%I93)+K+9_z1VlHl9Yshl!6NjHUI2}lc6Pb6js z{H;FcY@>`N*C4?vO$R zvwKnrL@--MY5sNm;qyuFA8+wTm=;2nkj5j@-SQt9;N;_?a*gs!-^}i*Mt`53NC)%_ zbA3a`U7SONj2bfNtW!k|4ff$Viy=WFx||mic8T7K|HQvW@iWmC!dlG`ORJ+-;*AD_ zM7hm|g*b132cd4!2>v}2d|vpewxus4p52Elgip27?+u%@O0K8|-{Bz4Mr>GiFm-xj zm`Tf;>FFNPAavB~Erzs#)@qd%&zn|I>zBHq#jb|0T2$H@V-72HDXa?&fP=Tl>sb3$ z^Ynxe8~xrH9yaA`#=O09d9N|+q+iE+Iat_?+?4Vq-0hwv$#_`# zv|-uGm#M6@`zM0@2YRGAowoz6evev8L_g~SbVYfu9Cdq^?d#a>r4LIixSi2(-RONR zr7;fAZ8dnllP(+^;ora5mS?8+u`aUUTe%Ie9phEStS-8U&5W}PMM>0K9>swsW;txv ze^&1Pvr_b*mAz~E?~1Jsfr+2)C$bwyV)&I({mD7l74P*|_javc%R|aZVORcz6)g8V zv%{0?<{bmwsQi`ep%b?J@!CuzTI?k-OrYsHUC>Z(y{`rnTa*3tst;FK!uWMe#p)4(?A=zg5Z$B2i!m}D`@H%gI-M$SW{Mhc-`0F}DYugiNRit2k z2alT2{Z-PZ>u6ty!t#zM#;QTW@MFWPZ}9W+_rhL;mZ>KRWctU_yihzTkRHT5O_sOb@&h2KM@5E8164n|faWi&x6B z?Mcz$cP4o41B*9gcntkm&pOt-h>o3M!e@BYC<3d~&OT3OaQ)3QVI}&w zZwm`e2h z-Z`NdkBkkL`z<3Rr+XzM(pi*k`4|s{WfL!jEByqPXRWzD7}>nJ$O`JT+fHWa^>8H1 zE#5?{741<|LufU6Qq;gn&Wl}VZf1a8(JRs~b}=6Tc2Pfz%-7{iv>uHEsde>h&ERZj zLNGs0_DO7BQk#~l?N$R~IOIE6CI28XFNsGdbS}$gyxfi)1-V+HF(a)eqJECN8uw$g zA~Z|mo?8eVNc(c1j^J^IU`84{u$d-(@0^amk3KJmALeuGlpTp0?Uiw~5IYaxWqMzZ zpYWiwK%H|>)i!fAx6gmuQVYG%JD(S15&)kuS9@p{9xYgxStr+`qu@mg&0Gn$Se{YO z3+_vOx~-{=Kp{Stuklb2WqW3iqne){Mz;}DU2w{(_E6xGd&)RMCPn~8F9hu>Qy%Ej zsG26@t_Mh~J;qu!uAwy^{A0tL*GjD>tOR|VD^c2Hk!fr)=ZSgUB-rIZgy!v z9X{wRniQRHUat#I`efl<+wHkTKi6Yi3%gJp^L6epP#?o|-EN+IvtJjy;YoOyulL%_ zE8UDH9qfHiCCYa@p3XliQTRQEY^p52tu7|y-g?!qAGk$KeT2=B+z9zGGI79wO}EFo z;fgnl5Mbc>W?ySx<>458ZyWQP^Ig5$2p zu9Z|yk7Uf0(4UulyA5lUPqw5kSGum?^KeOf5MDw! zqW_beH@*1_9vioh*CY0da4c<0^;q^Q0Y#%DPym}&uUiDpS*!3BskQ`M;K+|q?i;9s ze6};*7vDRlT0!2Y`JvY`cn@!WA@98ZL_sH%Yr9}0`1Ej_mgaSPMUPZ6!fN9LQzx>T zR<^3zt8iG$As0VXpd#|TL@o}TR{=Yf6^Pps+1tz-*23WU))M*79A6LR;7t3qmf;dC zZS5-8plim-*zlh5c(?E#qb>5G$-&ha(w#CNx7ttYUXKqsR!4e^N(>~<7@ev5pHNve z+et}@1#dU3?n7r;yDi22<0TPBG0q>RhAw6iM&rkieoWAOySSPxYX!~>orIRUc4C_~ z@zig9G=0{#GUqpD{P{PHwC!$ksxKf{*y`D(h*Q%4-hJ;p&a0&}^?~D{Z+-oF=kLxp zQm@6r=dB@yl=XEx)^z@>jR%Rgr=5W3R@c)qgudrpu5$6R*D)0vO*2R~cZ4;#nqF1G zr*7I6E;N7VAEX{DWJuHrOIMyBtR7A0OV+DY^f(FMj1-R!Pvl8)*f(h1w|UbOG)uoOpA6s~Ri=*cH zeVmuG64?$|crMqa346vQa_vzbE5lmT< zea5|Xe?pXUoOkH{6e(GGX!+e`kIP%(EvoNpId9WlT$y6&&zT&I-nTPEh83d|J(!8Rvh zg`>p_=gHAHzvd<`zp2wx%_yrv#C7JcMo1?nDy1wMb0qz`r{-6w$@{j6k%7ebk}hT@ z<+o063rdS8ANBD}RK0G*$6S0o4m(g-aJ^Z2Uk6rT6DvbtQ^eYr#aWD&XW7`mhi*o@ zp^*R+oCy$-xbzC>G0TJwKZ>a=2X5x`MNna9I zL*bUc|PN4tt)E6$IDzHqI*=xH`^f zF*0?SAN0`?u#-Mb?V8iyzgQ5-kl`Vc;$-;lvY!JiSmTgv5cZoZAc4$ z`8dX8*xEQ;_4c%#KWTAwkKyXu$ad{w?27(YF;+CAD)Pej>lK-whNs=ys)_VLW;M|H z0LRMl!N=t;uw);2mG?@-xz)M|fo`KtGv1X>CBk?6cS1aR2mkBQEk0h3y zmswuR*TvltF7P*Dy;Ad)h`#1F%Rc!M+hCuaH7PI_S-Lfz&PgF2ZzA{3iA*W?i9@H$X+P1BN-~&4 z{sj@#!Q}IL&_JDd0`dUKmH_w3Cbx|buw7T8$R~wLVvSi$k`xrOwhSp} z+gP9U)z#+kh3kbvEjtnv-sh`5rcjv%8Zzy7i-;T8!6VHikhl>rtP5}!|r*OHB9ZCFVG6LM5TWTqbq28ae z;PZ54FbTfftVq_}a*i7`OO>iAF66q|;^5OJe>f5L$;T5H9Db^IQRg2#hXr5|oRi%} zLldif24*{DxXVmNBdNyvaCgSLdAzW}JuWs_qdt z?y`-mM@Not$p}89V4beKsb1p|myssqinqF8^c`&~qB}+O9m}0^B9fcPFSN@8E`n4O z)6}Eqii)|&g4jrSsRJ$%-$?gJc7Q(^_o6W&g7b(t_r5sfm-j65h7soUBj`%qEc4N1 z1tvM7-;Q6tyIDd@$~OxqEE1d$sJ0e~-M|<)uJqlc`BF(J79P#=^}sPeiil>;3d_Ii zf~AGuJ^P^JcbDFooMiN-rKel-Y_B_!(1gI%X75JkHfN!tA|dJpx7wQu6@R#r%TGir zoAq68Uyd>;IT~(HhmYKd=6Xto0`@u3+({jo_FS(RN9)T}JT{)u!)G_9wzZlB%NBynO4+=F`7L$MxK#Tos2+S*8{ zX5is~cYo^tL5yq^O)`nWk^;l2%l#txci}Ydf|t1Z4BdrEfcH-A}d*50y>0 zQA=B5jtGb)B9(6sk7LDpIbqQ@Gy#!^(6}!qN0Fn zCI9aTWJR&d@w)ZC%A3gI$NStogSN5cJ#hRcx}!>y1%GNF9wp!+X25dkZS<1Pwit({ zu~_BpcSyGL4t;{qx1fVA1gNg(^EkBI@W~VxfI|Kk^2vyyE^wIN=44`D{`=m_UW^CK zc6DMRF~>_Tb_e_(-HW1o*KHX>r?1QuU`0$1cI>K86>fHe>W#uOGG0} zZfJ7sB+=}4X>zg`w2~eRQV2CZpP)+m+v^o9-)9%w#n_8>DDc;h>d}}tVF?2L)duq>wwt6zbR0$`yvaAq_Jz?dn&-yS5!KSzO$8$2pBwxnJfera)h!K(7dZ zK~^M8@$)WvgMf+*{X9N``;3VAb=8@ar#{%r>2mT!$h8%L4t-x1iCMQ29W~>xRY)3W zfWK?`46Ui+AsZJM%iLk*akt*9XPvesda%<`YK{QAKk@+*(YJH@NgFYFG6IxT^5Hj; zU|Q?lSq~n^jzYx-(Zk<;TZOmG{iWMP4)}0yE{ZmYOy;>IT`_qAf&; zt@F79;AilYMXkOi`{X2o`?WUl_8Ux+*@`!sB9&3QWbNdvaJWtQMTd9_L-@E6Qk~m) zz(s2V7YFD??L1@emXYLEPq(|i?T5cDMM`F4;NKDBic7{G{b4vfal-GGt^`KYY273u z5b*)u@IaE;4jFe8S~Mgu{~>|TXMOqhcYqIcmb{0Lr_bcD{4xssz!MELnp(YROwHGB zqeXpQ4;Mo-HfgQSe=ChitTt~XabNEi9uhaojfk(EAyNED*vP5Y_)a}D*{?YNGk#D7 ze{v-;w-{IRT%i9w1H0DW_l9?4OyX4QGNj8eXf-qok}ejDSVD0(`63p(UeBMsaZi(4 z>bf&4v}`qd9N70pS9v}Bg8#;ZZ3}3t%rb`-g~E7@^!t`37?jhiE`B3t$tER^rS2Lz z)R!Jy98{-*&lms`VKmQmW@E&#ybz(hw;9ttk2q6JEP3|5}DJ zlUMPqkR;zndxVXNXL_ba#$r*YbwkB!SnZm1PuyD8HOfbxnWBeJeI^gD;xfp=!xa-K z5*=TlNE*G|uh!4=I98M@zH2;SA_{+eN8XgEJ!ORRXRIt-F~w{{X;0ixk&faCr|R{a z7Va$>Z6__tjjvNOJ&_nS>BQd65)_9;K#8Q#+|lfD&KP@{@A$tPbL)!AAc`-)7NoTx z%3oBdSeY{u%|8mhE>~tFNkE<{*h#HeEDwL6Qt7ejuUp5(vw13=j0xm4GE-MylMu+%AveY|* zt5~nuu#e~6u56*I47G#X>Yp$z5JW-Sq9IY3WKScYiF^=_5N(~ z8^@k)!*}94Tm{vwSNcPVP8T^iSf|i%mu9=H)bY4}0WAq&Sy-RpJD(U&83%`q(4Rk~ zabbjO(T@l>F-EU4j)#R&x9<9Rp_g-Yy^|TJKeFx3SxgggT=#VX?RI$ttNG|iGI5Yi zn*HoHa4{7tj44XVl(YMUd&LI@e~;%A^`&QKC8(2qxctIMxtDsJksUSEwG4LlZ$Tbp z_>HyoclQ{r*s#i3EDugYi7GV?D=w}Z=gf)4vB8HnnLUh^k_&dZpgWxjV%XDVS+3$0 z_))unAhxVAK)O@PeDwVRs|&xiEJ=h9bOR^^{Gpw{Kr3D0PJ%w^cPdcaSG{uXHoMWr z|Mbvf5-nQR_-ljV3IC`1$G^L^92N;fwEeqne9K7NVfD%p6yQsdOeP~6#LTAAI%|Jx(_tAMckFH#FlF?P~D2FX?5-R+)35lVjh z{bdgEVNPAr@j63kr8yhGJ0-rOOk#h$N(|TeS=#)3i~vb!!E0`DySicax@9NIu-!o| zefqYbbV4Q;(4sXS1TXK+nD!%53zqO^*Xj9Edy){WJ7<;^u`a&C^)2!$D2;bz#+hP5 zHS^THRfI|^7Jb=Mu-U_^YU?^lcI^3pwDsw!ukHHcV#)SHzsl3@V~M6dY3TgfV^8)} zON&e_lBIF8&kX~vQZx3rM=X+N8pe`ILAmy+Zjx*Fm3p8c&p_xRQ8?>H+Ur8);9%<} zkqhT!^|AztM!qqb%Y2awPpSmg%Rn6x^XUUy4ecqhu-!@UNW1v7EH@huv$%~QJTEZ~ zqqr;bqPOscXJE3ZA#jifF%bjoco)9Om{aULVV!c|@g%%^?{`(0yV7D@YRnDx;%y5z zJ>TW+b{aSimQE|hrR92adbnPJIkeIM-@vA3@3Jj&i@Lb4+&@Q9ZqD8!01pZ7x4tm7 zf*o=4+#OuuOS6t9#S{Iox;8-jt)^al5(-bspZInkiMdKxv(yfrrr@OCV~^PS^1ezGznW z*sGnGnn{h{ex=(twSQ3WTQ&rXx01NJ?t{)0yPk5oFrtwv}gLssa?3E=cNv}xBkYEFgdPHR=BaD4s|-fw$20N zWiYL?6}axVkz-IpwQ#Z&?brSI?lm4J|H}`5X6~DX_Bd;LzcS)EnDzaGYVWd1q}J8! z@3WYXr8<4yPB|6uPe z*9c#_rgS!eN$sOC0?mdr&jqjxX)Kd(@Sq%h3Y=`{00PJ>- zoH>&ol8Da=^}a0z)-667F7 z86~!fv8oMoqM*82BpV$5(61&-m;-pBNrxX%YaN&f# z3E*d0J_Yr2_lPS#>(ccAAKLgpKeX|Qm{Ylz81)>E3Jv!4bq<$L!EQYXmH*8O8Yd$I zk?|rinsHqrSvNms|D)HfXsc}m(Sq7=-%b1$7IP)wjD>z##qPs%Qr@hQh){W~EFJ<; z8ETjUqQW`-IT409WSJkh{iMYQOHWM{lqY{{|{3OW%9<<}rB5xeVV$gzJWjyELM+@Cq{ zw_w8(c_qAGrX@plBq|1DOl_Te>xdX#Nv;8BTvogK!q{l?%k-qpnbmWs4X00e5vb~4 z!hRnh0X{8Lgg2cbraFRsmf=YseGzhh5(YLAi?OWXp!UptGf_k$nFo)mtsx27xa4Pf z-the-jCc4&cQKgn`zZq45JrF7Q-(DzxlErA9v+K2e#Pllxx>mH4cr#p8PFU98h}LR z6i+K6v7lEk>RLIwl0dNSjAZPYCQ~i#gDzZndI)2Def8cz$ux#M1L#77MBZCF0TwiX z77WBaneX^Qdp>k8(V7{lOmK-Ewwt2RXXhITKl9#tA^=~R2@0Q`0E8cv#RR;u`>I){ z)k}~VCFVo$5?O9T_#>>bmGA^i;*JB50|>^;makkEUF8RSUk_d6z;;`|5OJ_d+Qnkc${!`N5* zv8NjGqI23O`Ap~{%LN(;pGEU@lVeILkIlGWew3z(uo&xodNutJbyvLxalx&!3wu)T z37jwn5+i?F%K~z>!AbEoaey;^MJe#nj8bz|vUC_yjni4|#@bLgyd#>V)M@IV2ycJJ ztHr_-h6R37+LQV3=kwAqrkZ^?)9!o4nrDU(O_ zh{(%d(-uxz8)926cB{>QO@6+S8DBUJ`drY2)?eKFLQx9sJ=^y*s;(OCX~lXuf=)g= zVG^VWt)5E{8uI0mIF!x-f*Vp##0d&<&oWf+I@Mqni68sc0W&3#`0y)U=0keZU|Eca za87Tt7Hp*Yoc0>3V@iMZc9QEH2lgVXMa_sW9XFPh-t_|Ig^0^`m0<#k``#LcvnoHa zB$0HaDhx1*XTPqc7L_A!shet^BQ9#?@NtH-4}Q4`2L7ON$?3M?eAa1J<-(gG^ESB3 z3cuo3zd^f8eakyH*+@J8Hs?*;Pg!T9kO;U=RzsMy4{r@LpTeeH8VGBKr>cd@J_8R3zAPH>m=v0*{jBo9QcnK+8VuiPYZ z?CvEHn4A`E-ACAX_ugst$#Z>6%BZ+5>{Ph|7;UPS$K)&`I<{Zfh*+tHs1i0^##war z+lK0XlpPdVG;y9~a?*ANM*DJTjPvj9q`~&L8BN-mOo?o7TW}3_VMOp>kP9s!z@T)p ziX&n6O~F2PS`mYoenxskDJU{oi`02>06Pg|kP<}+kqEI9@=GI14Y%uq_=)2@wKc1k zr4EBBh=;uBz!8}vTON_RxAh{_?$HOIh&Fy}9C?_^9bl*EbNb#%`?9FuNf5;J9%`B| z{IcUy-zFUEwxZ?31iyiH{E~8V^dCfeoiz}37}f-raW{e>oUTnDD^Jq^85O6mXa3C=hun64XQ{~;R+QJO(37Ao-{t3H>(>@RRUUm&E zV^p2?ymUkV+0#zijDQ<43X3#`5G;2%p7f0oi*HJ<8&*J|f_q+lX5c}`mW~sS6BUhv zzV>Mw1|fn;gw80O2kTX;-28)^L{Rf;*+zw8o&Xe*L7B;4<} z$`gn^QddqIS`6FWTAku>T|#gT#Egm)C|!i3H*VIpHb>yr#L;)#=ksukac}i? z)_SF9@>T6FRo@mp;u#rvWEeJD(DIU*X?N4>OORS_I_xh6T=~pf)8X=# z=WodU=?bSK(d51)ap$L7IH>2oigcDKo=E++16w6}bv?B3>kY5es==i7cY58Am?+XM z`R}KDN;)r8O_rJeJfu6;`kshNZ$lED2eL*K&`;9Dw^eo%^FRN zUcs<-zdAY?jAsHrOv^{BdKKw3%AEzfD7hXRE>gPKTE&@E}&8++k0`usKB{9~TJl&_-`p0DIQ3s!fRw24Cl%(XvM zQ%_WFbKCar1!=yAZ?!$|2z(w+*Srn6_w|7P(&gF{4#vt6wn6hN2CS|6|nHPmF4P(~sAX<IM9=|?Fn_~;SkC47RA4RMDRxK#U zZ;iUmQOHk63w)b}o6()=cuvH}!=85%T+up~#KAZ&l`!^5oy$C8Y&o5?n_$XL5qow3 z@}zK`OM?3C;N`yNo^p~pmxOW{g{^PCdTRW45^~M115^`SNSgs6ks&^wxeI!Xv+G9> zcA1chWkmFh04af58Q?hsq#q*=5R>}|_gs*Ol`b(L&k&~4$77X0A0ur)m9Tr4`sO-T zxlSgBl(?CJR>({ck`;SeGG}~C?FtJCTwX7+Z)L!L67K}r#+2yEdNS;38Y|Zc*U`?P z-0J_Vp8@RxGb-~4f)E+&e!}?{(~Nf)Vv=Gq4hh7oCyX#u%;1a=qZt$Q>SM^0?qu+~ z;*(fv+%<@`Q*~A3%ZSF|3cG6ihDkmYSQy}tu;fi2@x5=R%Q6B@d)MEH!@tPk-grx)!vPlC%g5O-sgMQ3k!yq zHo$k{qcsxV<%x|M+6*f{^~ETns8^JGUG~g^qb04I*=3O3xEqjvFh3LwR;FuZb`27B z9Df5Rp&S!w#$yu8P|?aCqny&5uP1C0TNJt_fvDQs{{`?3f=#ijWMX)3WD8m|Dp_|3 zku)UmGo&2TXs(4p=j)nCkdyh3uS#+exLgHdUB;K*pL7W@O|kx56Kar|=~5_nk^tlTNTB)A$OCehDu7Gq@|aTfD%T}(@?N@LK3zp~7Ck{S7VWj`Vxg2w^)%=8grOBpYN zOZW6+wX+ci&Rp<+^|heSbGtlY{NWNC$o*Dw#4W-;iKDlNqu1Q?kPNF%AHPh#iSiq= zli~uWjKw<+8A|U+<;Ofn6cWU|foHK?sKgu@-NLOjMiQ_&K{{;PShZuuli?N*A`FxB ziD^60&^8z(zT*X164SoFLdl4pR)ipY8Uk4GNC{*?lJe_9Mj+ZFL=O;>l*KZOWA}|? zu{ZlLAQC7sjoC!X8m_O>*djVYbFpPJwh-F`Bnf82pQ}oQ-WMytBkl-Ax;#;p*mQ5Q zHfGQ2mx}-l?oDZb&1(?5h@g*vIYm&+ADyN@SJ0;6!Y=a=HDFC3V^}ZU&0R9oP$ZXe zpMjZrv1qh1Y@cD0OQO~}!rlrJ=%7p#Ay&nhp`>Z`--2v3NE{fEpu9r4WX_r4qY9Uy z;oY4@7a_)jD^V&x9`OUNN)%(u+fS!hP;}^nGN*4AJE}Qzpz`8HKjaxB2T#UgZUJ$} zL=tCj;E#MPx}sl@ANg6H^cm-EV~Z6@Y0FgFb@EAu~H^F8k zH0zfnamvV%yk(V?u-p6$wcGqtJrHQlXWW`t5{&P~%jW{_0{w)9nSP%EpXB460^o^> zAAM9Vdp!)2TvgNvrzwNwP~=F8f1iAHDMFcoU&74{68PTl&hX)XhPuYa17b3ZFSM4T z+#N#v>}Cmq;3-YQdqsm^r^B{P#a?wNu_@ciFj2{q(XQbNOMVh*sPYsa2kC=y*@Kx@ zhFE>AyMU|lTmQ*%24}Uix7|M29S>Iph-sgeI>4=w1G{A10ONUWcgzeqPPaA@bn~w> zHq8ul=%fYN5xC_pMtw2L+Vgv$__?z<@p2}ptZhkbw=kG|u&zpGmpQmsat|rPXf;5Y z0b39#=j0LZOxJ>-F~@v$kX^ehjl z>t&UL0e-LJ!-#uBrkxB-Y;~{j$>Ml2rZiP0YLy0k{CkLP(fQyqfw%{xz|Q&@#71*9 zAKy1tUk641oeKFUm+qW-K-oA%_w@l~OOPPfij4Syn|rpM6EQ+F2@SeAKN$4UtiOYP zObKSU!R=jk?7Sz-yVC0*z!j-j!3V|eT{D9W(){C8ZoRKn;5^-LqVh#y4ta& zp1`MDySyUocq5q4RpC`pzA+}1*-=YoN2yXB@b*mid@Fl4?N||4Xco`@5p9&pTfLM~ zv-inn#@qXe2OO@jN+EEUs|sY1!vn{CL9M>}bEz$v#i8Zx8@5hjB?$!N;gA+W#&0GM zFksMx1^wT5+8QazE}Y51!LT%t^{Tw>vkw`GKx6T-G%ZPc_pVrfNlf%OnXh>t-)|$! zlal2eXfl;DYc5FqHmumh@CAud35a;GGNR0T4796LR_IBkgyp3o)y1-PfANGy+Pii4 zU@m7i1w+iet^^2BMA{4HhR3BvuBDzloXqvhTx0A~Y@udr7R6OfT_X)Xq@WA*eu?cf z;*0lVR-eXKC3aLW7WmIy`#CUoEvuIn#w{cz;#yWofx(&bDCgF^>Mn?7i_U? zn}+tp4YwGk7d`jty24Op&lnhEv_!{N-lnTpO*DJ-6RnhE|=U~&)uL{7@JngZABV-p# zNZFMLdB6Ol9L9)(fe7za^(LICAw4M*uYBBF^$`LIsdu|_0{XVODpjpYunrul+>TC& zkaxJr57F>yG!1OIIy|}=AH%~KJsrqOEJ^^B|f`P0Wb^S33MSuRM}k99B|>%JELmPAf^205I1f7DP(=)@0sZ-urv}9 z1}~8!o|(l)JVbzSFwtqi>hFYx+4*o_gfD&Vhhr!7<=~Gx+KO8d<9L`HYR4A{A!1xW zflzk_l9u@3_-SkNdRh}f0UA8yh;vBR!v0}b=KFB;!5|c1<986Ch(7?ZMz-G(3h;p? z2+%({?>VG}ntfHWUp6U&xK}`bQP28>O1d=9aud}kpdm9aaS0V2!okM%!Kqo}X=C?> ziVu!Ig&zS-=chCzB*ugTiDX*i!t!_usXIcJlzYe;^A4Z_{%s%RM=C)Sr*GpgHx zXJ6xs0x|~%LX$}??~1-k&aOTEO4~px$b3r^6+)9wJ>Y=;Lccl04nt!C)(B^cDnk}l zVyps*874w7$r%Zvsw`lNPT^A;UAc|k#@t*JE#}3AdZMb7D|?~PjEw4JEdtkhO4Tj= zn%7U_W4LT{v(0{Ls~bzIC+hyh)$Vnb40ipTZMMSI2e-i6=3AW$wK78#ap6APnLfVn z8%7(jJc1h)-eK|CuC$+0A|P_tD4{LQUVeF`X3h9Aqh1sG&nQXDdfz9rJTeUL94#`b zXO+IzZWRksTybNe9A?k55zb@2#`q#L5bxocnSUU{fY`mFc|JB;%AN?^D<%Urf=SOTSDqB9E|5Kg&(MP^j!xr{4>TgQWw3~(@-+xo;L)cpDw)S|z2?Fz1-t1_Oqn71UG=0un3O*ZIA zO}^bl??$e(28c*3Iyr!$(H-)Oo`wyp*V=mJNq2%}Jyv4PB~0DgdvzE8IWkTaFWxa3 zDjKG*c|?513~zZsXn9{-bVWPm*57`>>qZ8F1YDvC#pELM;9gqY|$h+nncOO5WwCsegpF zHpUC=?(VU1rNL;N)p3mpJvqW(78JUOoW|Wwp00>UYzV$5pEj5D{oiZcA?yYa z#sGhd6KzNSbV8*Oixc=(!`4_7`=w2AnlIff3Gp6{$8yXTlC}=YIhALrW-6KZX(Y@ z3<3hfy1K;9qX`N&x*xN{V!`On#tih`&GYmog5HnoOKdzY(l{w}2{}IxYDz3=nCv7{ zU~*RF4Z1t55`bi##5UzHpQ)jPhZz&SOVh*2-)UU)IDV815|}++U+VuO6pAh|v_c zLLj~%rq!p3j*%`*PobufDJ(4z?-a8b08?d56HFC5@4}Nu!Wn)QqxWB%8JVCGUsg_Z zp_vz!euO0!wPaltpr$b^tc67*7DX|sD@7>eAxcFeb|^jh@R7gNx9WU4tgywpu~!P~ zlaFQ(6Agu+XhZi4VwuC zufWaWxA7*-oZc6A{PpKKn90MA#QTUVp5=-VQ zraRQS?kZrez3Vu>az!x1yyUW@LpoJTWTaBNH#0N==USiJAizI#g#w_rYoL__9F<-$` z${FJR6fAGsf1`jfnJh~)PbTmz;+nA~iU?QRNC1w*Z&9%?;hxWeU10&l-LGLDh4MI~m@hy=0}_ZXTWT<>>@&mt1f@pcFd``c5^ z_(UTXu@jEOuTU!S+OdC{0vZ22Bqm&V3Dpk*jOr!k_j_-Ve9fG9dn zUME0+KuE0=K@n9*OsHCV3J!2#X#q{ASSC}OEVaZ~E+Vr?1UZR%6h!sy)*5&IK&fi` zRI#$4j#LKVx^`p|&~*^ej9v^#`$1S)PBe{*$>xloL|pigctov)Qy+IesT5~%p#;Is zT1bqATKaQ8h;oKZLpP4Nxmr*EeZ(#9ecdj zQP2HI6=bGnR9#vn7NMPi`U1PXn>$}=Fa(DuUtbM|E`6Ha`(9S^! zM_jJ8!slryPjSab10Up1MN)OPQ7OkAdW9^J*7zSsDSzHVF!6!#lmFz90wT@Q{&BEXQ^ed(pdO8(nJQtF5}Qi9&wZSz=tNiqmLj!XmFhy*JbP-2 z%>n$7pX`rU5FSfC$oG_d{^Z_j0dF`UXK)Ky19tMPi)+A8G@e=6fMJkg8VMIba!~sHSsS>2=#o1nW*Zyaa0m&xhib-?MkTX zoaG@Ls=0pGuFOEu0*7Pyi|Y?!1u}7yPePRDacGot#qt2JrlURra!iZ>%rP+nFvsxo zp*iMjQF5<+idyL;go7ZL;-g3yWj3i@;BeNPvy=lidOV8W*#PhFbYC@ze4Ys|d5l`LwkcY-T4p?2 z+Dx)*ZQJKw>d{AcXOUWfWTNsW$)D>Acq@Ze$PPu(Jvp0|7yjY7AYIheh+7<3w?XEt z!VrKG1zHdQSfJp_h8T!Kd6K?FpKu`1Sxt8l|Ggq>R8)7QfR@9}LBD7Bb?vsgh@}{o zkHR|BR|TDM2|U4oPf`~OudveTt6)EEh!z{v;UqSo9q;jdyFK0NnaS}k`u?$RE+9wG z05^9Eud0B)u`xF3>Z%+L#%5MT|Csh3Y&;GGy^VvhoeBX#RY!*b4rxvW0Xz8wL%|VK zT-jwUo24V&_~ZJo9j)cfVMKlvJ{|~+emCobKn(5*0hz^vcS;ezSd8v!Lm9w^=Q&=TmGuiip5(!(hZ~jdj+L5Zq_yZTgjy&s0gfK|z_v zgkIVKlcYh9C=A+s@McVn)=VntW!ljra<|7A)_QjusQjgwnNx4$KK@?N{`KqCm zZ@+JqY`=N|Z=QGU<5{gF-+py#%jIhew^TWqc}iBQeFr>(eOV)deLXE+oa2$stkWhV z?J)6e#E0cbp4-vgLcpJih8?_du`SV`&jFs_6W9;el9@mAvs}E+ZNU__>+im=tJ6AeRMwU!b0GL!39Kesl+FOm@;EDJ0}mCl#d zROpYmjd7_(oj;p{;o+`_&KIYZzU!mFqQ)hR52% zQ8R2_~^e*^+7>!M$)=i>GN;C!hRf-`l;n9hFc@ohcfi}by4|-H_mdWh%nsq3ZhT;ys~a-#pUCW$UR1zw%&)t+mQ)Yg6w3yr~z@ z(Vu6~I$_{+Vte4Dl5K>D`Tp3d4Sbf`H`csBEKhPmK179#Fn@p87ak!9;0bFl~qCTt?&mIjU@N4L^_a2#_2ce4xs&jbKXb1*J^eDUTlx!(AT15-VriEdU&gR-4 zVKu$Ey)LFS<~_YFcXk$dNBSM-4S^`u;zzph3!|NfX`5S3T5Uv)1ja3=fepoik1Y0+ltQ{IMZ%sX-B#XDUamYUGcVq}pZV;enC6PJlE%tuj()+jy*KFk zIxB{z^w(S0nH)!kSL7FFo9>j0#^2qC zOA`c7sx+Q_r3~kD#q+qdyflf(n-_Asv`N2qyEJVY+Zf$GT(}uDk@41v>RiOw+0|;& z`5YBbPZ8->oH=*c-o_!RPWd5c!Rzs>+Gn50Bl+B|E-yC|=Cr0Rk%VbKR++nekqM~C ze=7B*7ZdeM?@jL8%6vytE5oCl87?~S#dt$9(J!c2GupUWqkv(Kr+{I4>NlGi>RHzu z1x$X9mQG04LYnIH!TXW3`s$mlRpPw#Uu42(trKTf8s|c0QWY@gzq+{9c}yHPH_ zR{!=rS@6Wks)oF_feU%N_4)v#UcfA~e(H6qptibou+_{0*7LZN+}%f}p4-*3$3OF1 z@gDETRcNUj#y%agNolTaK>azFRufQ7^)P;cIn>%$0PpgeerZ>+X_+{;%BSb}yIL^?q|nMAU_DI3q~_ag%trroNStzdwJ(%j$qL zQb&-!O}^#5U}b={AmQ;Q>M}^$iblbnG(m>#P2tULNc0nP z(dk3pyt{1LIV3tCxH=kV#3>^B;W8%bn4}8b{rLq?A?e%#VfG6#8*==Idui2gv#gli>Z=~JUIABB zc8IeCE1&b(LjuQ_7`AXZ4+gQ@}j+HvfCu+CKm*{Uw!=CQmm=-K>NYDklQYxuho_iPcr*G^LE( z#J_j2+HaztuI%6&J<tNaX&JD`SH?lRIXaRc$_yK#$V=X+5L#FY?ftouEVUr2MbMy3e@wj!JIl^-z zH#x};ZtEhS?JS^pxk6xF*G!KR=5CT>xsAYK=JaYz)PAJvdp!c=jeCw^ zZUOC2#0)8@|1s6*0+QSCzQ0pS^ighB$Dil(=3zrG^4y2~$1eF5^eN(s{#>80l81^z zcznVwx=ObTr9T6c01E2&0y&2W57u&ed9hR)w;%husfGSy)v+v}_A9mcHPJdpa(ect zY56~_YEQAiiB3q(?|34`TC@zmHv2|0Ho@VNJQ}*0aJFvRPd{jyroxENTY_O+=aA{A z$xH$K0=x_5J8L~t(if6yGqHFqVyJ+D1U;NL4V=rHR^-tp&Rm+X`(=T2d=9fAvk^MX zl};p995BzHJLCpEbfTwYE4>5^Hk$l@t<8<-23Rt7!Yd>u-Yi_5h5y++67RzoCTkxv)BnEqPc=WdKcmkk!enm@O8=%MtTq5lC96*yA33jnOB0%jbU z9`t%FqB)~@w$w|7Q5}gl;k?&IEyK4i1mI4&1kKoM+f5f*cZv?u>e@_%bN7UCq&2y?`C`!V(UY_NE&J-ALU-`Vd_06r!Mef-}Xsdh<) z@d6r&S}Y`~aqz-?02QptAb@fUiqc*IBbZ?o>O(Mid^tfg;?(Pa-C03!nJEsGpl|=R zUe2X06g~8_-Th5*eK!-sS`lU7~F>E87^jKq8dy6vXp;!w;}F zW9fL0moqrXC>9tDfH4DR#l)Bt^}T>#7@vQJ7h%vCIcoV>Bx5 zMxp;N3vUQC_D2k5|3>XM`AZat<~2?!&47dO0Ivh?Q5h`7l9b}>64FKrOaaKY>x9>my}0+0ht_*+~4Go!(aetYQO@p1i$PYqN;wcQ*NYYLE( zVgNE~8Gr{+O@YpErx5?|^8s}xZ|RPW1Hjz>jAGr8BF`+;*nmqQyvk78K+6tDNe{pi zCV%N{3XBelAdWlTvDil3uoe=i>a&6WU<8!;z0dz=wcL4~9W zPW`JS0ZmX_;aedI_NYVYGq8wmdh`4a18E|=Ouq}|&X)#DV?(pY$5-e4u>VnyKvSBi zp=LY*O2Az(jIg2~GO<%uUiX6l!^#=Wz2SGw3z{H>A>ZHg{Xmo0iFs4Pyht#62j0?>jo4Tc!BpD zIsjl9sRN*j7fD?%n0Q91K`20v&X^5|0B{h>AI+s2ESKpV1Cp^E1JWFqm~T9yAVG3` zm3x7ip+<=l5rEBNsbbq5d4O|Z+)mB)W1rWIdeu}$wS?S`*Iy08u$&Sg%g7aI!DMQ*@# z-%h&`q6BamrXq?(1%RZ7f(Cstd`E;!Zn>RN5vl%KaPbJ-qjS;K6x}UwQKi%%s}!YO zsQ=z5f!!R4H{r;wW>g4c6mWhsDsain@byb$=m`hPzdQnnWy2U?6Y|=z%J;j)4Hekp zelMNlMUwrmlb2OD-aO#-6F_|f_x5kLvWmRWfsDDoz1=Q^5m3?EfyMN97=QX30ySwu z2$2Tr**0**A9jJ0i+Yh%*|mcG@u~SD5WYKS0nrxt+fiJmK;Zu&(Uv3Ux}7eE&7r(4<7gfnf}{OFsesDuFX6qcL2EZ zk7{05>7{!KIUjF)i4zY)+T> zfz~J@DEWJiZ?ru)C(ucfQLmEeGEuKy$+ZnwTKWV3`%TbH5GG%6d@sXYmwwmA1|?5U z00c3jv?k?ehc?JyX9+?VGklZ1v<9W$Fwn^R@_h>a-98^dvM$L;iu_x>=8cDtfqvMO zTV>dbBBP?UMV2;`0CNc1V%K19C1L^kQLYG=E-CgxOfldSN&~h#?ePTAb|-LQZ~^Iy zdz4%M2PN-P&FFOL6~KW9po^mIDS%Mll>wlM1Djj|F;sbJW>mMIc+}?WrB|-m#tAHrJ`mYki z4J0$vjK6_^atqchsKVTx+RQ2g%PUk5q3RD6E?BUO1*?_jQtt1)0#riUQ6)ib02w_p zeJ2y(9yAaTg9v@-p_%FvnIJ&evr?eR^`EB^fZhf4!j@1@d@opHYle{A0Fh&d8}YiU z30c5xKSi zUf!kFRAb=_PNo5gq1_EoWWZ0iekULJDGnIvyWRtueV0JfcHs2C&<(0tceejM zqwt7rytf(QisJ2cU$OV)&}8cE^1{R^_k#CX6IMK>_pdJR>n89~yW=D8>tFHvO%*jw zHy1hkH#hP7-U;7mMa`o|WUKj2$f#KDIb^^WT0HE)mk@ao0kA|ac7M5V82FP5T3l>eW((-+I0_4h zcu<$}`Y_Frij41Kq=lU#DiL_V<=QvER#14rZA|9!`s9z0HW#*^Vm`A(-0kq0hq0!u zav5>svSlu9pdLu})e7D9(wRq}m3eIwRrYFl9)1;L@wuUgY&0)iHSUan z1t#y}Y5*s~L~{pM{`l(X6|jnc)G9cw^K5sLr~vyixUj&NCGb#{)jD)RvU(^C)$s}R zX}l3A_#9K{OrKVd!6`fk!mcA8jVkwWCbz1V3ao zboXU|PArUtx>+{zF50!r0EnlPMlYwosI#CJb(K{Rc|m>IVAKko;w=)?&h`C5;u?xR z0GX@+@cZdtV1J!J18chln&Eu)4IBBV4X(b3NW=j^S2WXLf~QmbPx2@yE)KlwDnMHo&Puu*wi7|RR&`E1RZZT zRLTM@U$g$#1mFl@wlgvib+|_)=!UyXWbFk%0L%59XuR`?q^+fpwI3>dFli*c#|J$u z*!5033VQf%*zfo28t=ACADof>arM96e=-6d(|R}S@aLre>mtC~z}5e;=>Pj7cUJ?8 z{sZgZ)BgW@qHMd=c+#i`SVJd@ww^-PS@6S-JInVIjsH9Gzq%x=hC&u#A;3p~nPJ)GAMO`Y|QU7=1e|Jg#cB$H=Q6Atcov5rj3Rx$?4_odm<0l&bcjA9_$?8(LWtka# zd2pr#J88B#e0ezVLJNEm1-wWGU%Uri%z!WASK5dst-m2V%hv^kujx+$j~AF>0&lYK z-qb_iboK#*+`b{7@^8AcCHXff)a?PMi{BUBe&(Cn&fIQ(;%UbUc?%vv$pDX7wwYl9 zgGo4`gP%u02NNG1bT}Dt`vI4~xjRAw9lYHG9bCtWr6*+7ceNSseS5L4S1f$ z5(eh>76#lHN9mxpil7G+m#x4&N4pK_vh z-?JNV6b=2fSqjmP(xPw3F_YL)xpsUP)N$4($sA1o(Vwq`DOJc?Wb*R^q`cr0+J!`q zF$Z=Q3h9s8oM;&tj~+eL4`cJ>mwB{%l(*As9|8CIxeF9H9E_4I96UY@A`CL{o*HK7 z4g01_Gz^RpGdv6gIO6)6&BX@z#bz@T6GsO&=M10TWl6yl+Tj!|Xq`A>`kCR%C3 zSkYaYOtSOVsK-ZL+r~jptfaKwNmLbx&}V-eJzNg%5X~FGZbE9kvP}`$2-n_YV&Of680w6TjM2AZ6?%o}!%5cXM+$ND?y@ zFAz$jMrI;a3iyUMOQF0WXYY7A{AFP1wdo1$_@y}cN8za!@2#9sD(BJ@<*%Xs@A$~3 zV2N6rmN2P^Ve}<^gk?t`B+GXNEX4Y$(<3w`!4f}vlK`JM*C-GcUDM`EZYzC?JV-aP z-$Of5A2v0*#Oh|3Gyu7}?q!<2ryL2=( z-w6EF{pru|o{t(XPl6}+H*P6(KFND~E8dn1Bn44^i8d+z#{2fBZRV14D7*TMjWSioib7{#2F}jyS)Iq}#rOBi<>kUx z2Ytnh5yE$^%^w_3obM>6q6zeKb zUc25Nj&EO53Zvrc+I&qjby;}gakJa?{p$^%j#McDJqxdHv`?;}^6Q?fH~wrqAjNDQue|j(C$;yMoR4b6T+Opo&nDsJ zRaRVXm&9UjH&Wi}7ZcVOx*nAx?SXpM0+FdNI{UJh%klDRWJcnkS3wzbK35kv=S|nE z?Ll?Kb_PwJrz5i|c>6xL2NXLi%c?&j&Idr|i*?5e*G{wPD^AYuhc~h8@{32c1lwEP zm6-SO-g#DrwA>-|*Ji;97ryn(|8^A1A@4uQ42WOFEa?x~q@>%(n7 z`PjL%FfA_Ts<)z*{o~M4br~})9idE!O>r5~MnAWaIwGiL+!#K7@dm+hbrizRpJ^B0 zfsR^aSwH^$IpMDc?YxN5i`>jZd!)gO_F*?=CDKMldPg7g2)q+1bAH(211^skfD1bW za69r(%_2Jg!A1XgGdy;Yn}4`Rcrxt+)D$Z&S04aJ2;y3Z;4~6_L6$&&b(51yhOm=hDNp|2n8qYV~WE zL<5=_n3^^V>#sAe_;}#XwYf)=n?*9DB)MQiOnTnw4ZBh>m@Ff*Qc6G#~qT8g6mG33`D6*#aH2Bg+bu|rdp}M$!IaZURUR|^~)gey3eq16){3~#w=iv9EZYZHt{Jbi9;n8(qcPFOA>Ul!9mAd+&v|!S; zaIxoiVkIaf{ybLNF!M;!^gART4+*R(_JhAzgm1>U&0azj_=8RS{JEyLn0QD(luvQ9 zCD)-nOBgXumbD}p+Q__O4K zeoeB*dh}7-hLxZYgSbQz{aX`%K|AC1FY)((4&B>M_n|E&n^So`>PEp|cFzZTu^Y}K z7EXajWa{GZMeA^M2UetP*c*oFV=|esHlUn=Qfp2xaAH0bTX;^ayv*|K-cGk(09U@0 z*UTPtqnFWN)VI@`SH(9;m;T9%CJus#o<3o`!D%Z^a)0(5?bWdi7J~iyM2*}snTm(5 z!D_av&B)uu1cHeZ8Bl!GOl~(bdc(S3i6?Q5P*7n(K;_)Qphl_V5PeO+l!oCLbVOQ} zV2)S)l zD)ykDY>Mn_DTI^1o&CI_^9O&wqA_SSSf#AdbZv(eh1$8#hZKr!EA!vJ<)h2<;OitQ z&G?%Xs%dMNuX0$Koi1nA&QE?S6GPCnS+L&TA6ojkK6FhWi$?vBtkL7#e-{6q=Ws$t zMwXMNr@#6WJr9E&*aZ_)@yAG7CK^JZ71yXi(9MYd z2mL*x{^QnWmh(tPu|TucgYOq4sf0-1=fzw~)NTUj(-X96cJ-%uh+A}20ZH}XtG=yV zN@2TBvVQya)HD2QkEOr!{b4;#Hn9r$tq{Z0wAliJP1)W9avZ zD;K!1E$4EhSpgb3=6uf_B;Th6$&Zt$In)ZYwm>B_@SHCeO$xGLL#j$ID7s8AOwSul zwi7z|7px8|olk{z)CMUl9gR1~V@`|s`#G03#Eqfj9k?vFLQKZOk6;v@=l=SAu80-* z?}?e(^4#uMEGdG!FN+x#yV2xq0M}h6rnd3qVT%V~k|pr3r-B<{&xS|s8uvaN;0MJ2 z_L2X_YKF0xu3zT##Hr;YJ z2rIF%W&XA-Nus=>=s+e!^*d~pW>PTB(!cW~MHSINo)K$3Cr+Mb&ksvLQuuTyt`Y4a zQ@jZyzXQK<@rjsxN`!WXqh_}`xN#6UgDMCRq|stpm`rqPJC+#3wZg12)@U?$H14N? zV=hy=&#NQaUoN~|R)4#z*Zuq64N1WSliHL><3-O03l?v)9&KZeq{*M*vZ!(H#RA`9 zx{C{^G4RIE&nDkDy7_ad5-_S7U!RmW+ev6$#cEhM$em}K4|1re&!yp1fl z=v%VT?f6W+o?j1|)Q$!Ors5X%-HJtJw4^MRj-(+@tAW_Lr^zvsphVG_BROfEB^>oQ z(jS2&IXJC2{KGUak*X01U@8&t974!;N36MqD~`1ZC%VAM_v>V?cMSyJV%+02kDtO^ zI%3l?udz)S(@_d1v_+JAv`1G>=ZdUZwmiy5gKRtGJkt9K{hyf#DkDIj@rQEy_BBXz zSgW0Ko%~or)kyG1DAMe(`=wpKO&XTZ5#C;@iv6DR?6jn1k684q{mSJWl(oxP0vLAunr=n~3yqr3|KQeL@W`v)kFz2knO1teJS zNtF0{yiMG5NHeX2_9@Mzt4*5*N!8+1J}Mh6bg9+`;FT9`ny(kJpO4Sja$bGToI_2k zF(Wly(NeUtWp?tt2&Q_OjazbpO+j6EJ!of(bcmvUaIg}WUVEHR1t0bNFW;}HsB$ee zuDyI5SZqP^)6L=H)QEvHKo2@C;PkI(wyghxri}iG_Ppu=&A^?*hStzjW#Cn1y7X#4 zUnspKQx&f2NI9-^VNx~I7nsCyY_sDbGs zCBIyIKXatA1)*cBqiJIK5|+_?K_?sJzdu%un10qsjMG`E{N~xxnM_rS>0UtDh1@5s z6#xELF2+pr&%^!Y75+XMI(fx^Cd-H&64Tn#{#?D3ohhJwZnV;B%I_x*9{xm{uTi-`KL z?7fZ5`&rL$pNtKX0`7*ptx4eBh12YfwT?6Cb4~YaSHRN=i*IurFdXG ziOOlPh%cG*6nf$@@~>9&Q~K{89HA0_m*$$TUK58Q>pL(XZmn7sS?8Z!^{n&zlvKDj zIAt%-xS!Qmy2hNHKb1q6Ih&2+doqv%+Jl`9QXcH zvMIh-tq=8q>9cH_mcMTp^9 z#`K7dTs{zrtZ&D)LL}C`onPBT6Ve_h`P`)y+s(W4V*Kc;aUvVPP_+;5uZ=017r_eJ`>i3#uyjm)tb z{^~$ct>RB!KMcfmc*I0c_)xKJU~}Iri`W~jgVzj;w*1~(sY5G>^3kicT3kn*#%b>^#!k67)&CIRn2)-i6F5^BH+ zBs8AIJg;oa52UoSeEn>q7Z`QBzQ5vF@J&VJl-RIoxQIcTKXWHvVHUGp4L$exQ|6gu z6^ZBd1sUDbWA1srn3m^- z@{73~omkJkfV-1nmLw`=0m-G-P-4)+GlKw0OV{Xyi{O#3PniWST$3o-ciDRPSv$|W zT|u6$-!JVaUuJ=3K!d#)!OD=tD; zWKK7JIU70DdNstX2H-n!Ex9+{9TWRQCMz`?yHn%h4@-)-qlA=W>#pe}*jU3A_hy9G zqFP_M3W{80AGicPMZm@ZMtpY#a=S>n2B5lTAU0#%_Ckv881(C!N349}Kr0KA<-{6- zvk`)O>0!0Ak_{y;lCgTaxZh%!Ude^7L|KA~*V_9rLy8!5?4;{gXV{3NY`?C)1L0Jd z-8md0_<*u@uZwANkF+qKY?MAv%WG0nAH4;I*bW-TcLm*oq#{F`LWx}>nu@Lvs+x+< z5xNaeQz*Z0mok}g+=A4<;rM`P;J2U;c0Gpeb%UR?HeFR|C=Rs{ZQ2ZTWeP5f6F>bn z{P1-A24q}l;{zJ2o?j^a?9Sp7FF2s<6K@7S*24Uwd&i_0{E6f=XRUO21at%P5b80E zFYo|<9Y4_eFgtX|GzeZ5t6Sm^Jkbh~ABseS^z>tXEX9kvE2=-u!wb=Bz5lH>O?T+A zK{NomDh@>#2F?aEj5jO41r=&t6nA%YWWDhL&3Rw8ArOD|)bPk)0j?t4JQhOf<-z(g z!!|bh5%kaRn7qF~^ZDyJeyG*QR<04!Dfmh2s+h)Ru{4x*qg1Icuc=%A<|En|Qr^o0 zt#*r_O`+*mes@gL46CJCwX%enN>8m65zT!pR-vN@*#9Y@ge;5ezBBEkmRmtIGn0#C88yz z0E+=t*pES7a=%eJ=N6P}^SLRMV8)RfuxsQ@tETVyU6JR(!oJj*maHPY=|GDUKgY-i z^i%J2dz8#lOabRbs!ndZItA^O*Ysla4d|omqO0?f7An4)YS&#+&T?|=b@5HnmifS4 z5lqVxwZ5s_CV46C26Pyg<4vovBCr%Vxk5Hz%ebAMYiloYRldN;76au=WeyH#0(!3s z|8HHZ2Mao_TbSwyH>AtmZ&rR*MJ)L?YMBeE*}B?8r}06eZ)(>v^2gI(R|qUPJk=1y z4km5~Mx9?4W8GrOt{w8e>b#70qaRSO5P-~tWW9u0)~qH3N?Awf-5Q)cf$L5+TQd5A za#(#q){>C;WM#-I8|IlWA?qdrJaptEq*8=L`-K!E1Vmhf0>&dOLWPO2qkt_sU%_>G z;8@Cp5ZO1Qm?&(bkaiS4I3QPF!c!MtfOlWem>ec-23&#+?tSJ9(2fXGdV&UL>Qg{2 z9!{ous=!p}2l}IoTpUY=Q2e_O1zb3S2DYt0fiKMlNi0yO@;@1oQ9OXK`Vw+WlA?i! zZ2vB%Lezfh>AU@S1tEMZBT9{2{J=CaGY~+N-0*IX+?Dg@N1}Z} zBCoBQEx*S_pn$=*I>bkgdb8M*L-{{d5n&=^XkcwSe`u#K;TTy=n<#t=!YDVQTY+4ICLecBxd(L|QALYTI~F6f2Wy+bBT@EwCYkdQY`;&G5BruvbMPvRZX$ zzMxb&WM+>obPpI#CIP$%8-!FGg!LB*oKB2X{L|#Qw#`2zKgb(st2q?Y8UpHtATV$3 zA}~uDAr!+Ro@>|qc#jTCq(xv}_=Th${}KlRN{>=kg-LY2rtli&pXgqH%peOJ+#L zqZY`_)jCMPdIx%x?3wn1q7lHoC>A8zvUQ*!MJ02g8dW=!oz zEjKf5{>nRO?k)xLF%GQUfbmik?vRq_Mh_uW{euN3m85>It#jH(3*RE*pHI!>i#Km; z#U9=~m@zh>A!{UNt=b}V*hfY5f7LG%vor%LY)dM>c`H+@(l>rRpqXhm5d|!a z3zO17)h;vE^!r-^sI(ak+>V0=&zgGze@=h~@1A1ti=XaxZVnX$jz5lM_67ZEK>+8z zuz-Mc@e!ES6>(uowxrteGYHzRZRy}jX?%d_Ui*T?+K~}Xu;!rfOPHEf?g?5dyMm;_}G~X0g8&^{! zp}G4?Oalcx8^vv-qH#P{VFU@_wX1Q((KhPS6BI#UhUKxLG^+>vLvc#TVAvJk*9VHr zfE5&g;;(NWDV~0tqVsl@g=(zw^gR&0yf$BF)Wt86VGj!pzM$jjxAhY*vV7-;XmHAnm>hJhq3@|YuN;7W97@19_4XU+zUD@f|xLOMaNW!4|#nHG1&^OoCpAf*rBY79!(Hgo1SyL@pn*McbNSRRI zi`biFgx?ZE*d9%+&PT=>U*Q|QvS(Z1|4bddt&`i6-n%4RZtWc;mP8)t62yWmw)ek1 z2z`;B$M(?&Y#z;9S-WMm4F6%U;mnEff0Rdv0UzgK!HwGskcz`7;KoQ~+JxLBK>iYL zR(eO$%w&~~0=8uyM`T{ZXvPvKK>)u-N7jxv%kcwQC?miWUh~44YJjBTfDDQMmDJ4S zJOvC75)ipm1b(*Do2O0O#>hQp>O=ViU6m1O@aWnC&h(r6jEaR7sC#Hz|qM} z&7p+ZSTMH#ZAx*Yf}uW)?BX>dk&1r&fAMV&A+#Bbrba6MzaG~y8O0evoORH_-}E8Q z$?Rt~-FRy@&1p{U4JJT`I6)tT4hb;a!AI)7_|rI1S0v+co#IuYih*v;s{yXLv80Uo z+mqAzV#Pv<_UCda=}`OXN&3-h*rq2oGE6{*iPoowdHeglMPzW`E&VaZrA9>w z1?iOKsr{H64pk;8OI`A3;%_EurCIWwRUVhf;2C&1Lb@~648l?WK(eVsY_T$t>r}-q`AOe z%Fivsu29FUq9t`Qt+p7YoYkrWLcKnJP(e7q=Y5|*)z86}LY7gINj#8mnWg%$slT2v z)Rb3!!kaeYS=Ujqs7>Qt7YOZ)e&Jmw_XMvCr%9g{CGl{Xx6GB0YumG->Rfy3w6^Q+1CjRsV(rs2 z9L^OV&M_VtB)_1k(1eQmu>9g6zSroMF#933zpJ#LroLZ02F;zgrlb3FEwl};bfsa4 zNz&g-3+Cdg*lNI+EE%IPi2CBFC)C}ri_bR5&8A&>b>2f4u+!bgyfm~-{n=iR~ zco#yV`m@(*4kSG-;BlF5P}%-xJ`RZ=7D7a6E6m8<49>%Q)nDB0aFa3g8cLhhP&gj= zU$En-ET(LV*YXH?G@jAB$S_{W=wJ0RwJ+co-g9)lJkY-ZLldhq)b^c>f187UG^pTE z01Yr=&Od#7(M$0_dD4eP_j}XtvB{MKFr623KS23BA~7dowIhsA3{{LTd#_d($%Co} zU|_0rxstP_ze>Mp2Y4yxHwi+_g&in+IX%rHxDHj6aWi!4-qpkPPLg=vv>!VWW+X8Y zWmF=@I+`SSi5T8q`qO_3>D}=-bV4&XH6skC{~X>63q6#1N5x%XdV_%{XC^n~Mmo^d zTR^Hhi^|2_(*ce3?RA=UYeGZiDkg|@RectnRP=Ixf}6|gTO=hSr*AK5o95}-%Ae&0_SVL) zDBkgL;a9HUJBRc#{awMgKuwAm{pxBZ{JFQNeLAG&OU$H#@?{_dDM?ftPRGT)-FangJ0;Q*t@=7LXdvH@Z$FTZ_gj;6K@-L<3VY&w5=ms>E|~U(K=0y^~-~DW|dgS zJPy2E#eWm!)2*U)^1DT*)lidow|a$nd82jeh5?Rc%=&bXMf6dV3N4Ry$Pkj+dAy=} zVIId$9^blp*#uN&UL@%du7^<3au=_NJR|7pg$atceu+s^b58Hz=Hl+|uS4$xq_IQ`t}9aV+Ws{1(sVp8GoaU>u&m)*-}Pm#M|YM$PE;Eeh7ysLWiwl19F0mpq3 zuC}dX2R8{bZ7%~14wK8vi8`#L%I$#xFyd7b*EVqUzr6}Ue-wXKk{PZCsS)5`tlPjn z9D)%+(}dzde9DO4UpQV*4O>gfpNRHEybAA4j^A*f<>u0e-}r~-+>J+?+czF*Ufp=4 znIPvMn*YxKL$lh|ztN06@<_AN2)+e&(rMTT{uc_a?YMkbvSBH+Tcp!SY2e*oN~0rP zf4gAd918amNwYMrQ)_ub(=i6k{n1egvt9MmR@-Muz};hN@k|24NkFeN&^5#_4D z8XMWvr{S(M7Jc@?)GQwMsN3YzN8NtBebnuw$D?lb_9=L1xhp<3JdmnY@(-z-9*?9> zoj#I!c=Zpd4c>bRr2wg(4d!2?UkLpKb}KNF77wfhMX0!04B1f<%e=jI^aFaQPI12{ zJCCI1?)*b)<<92iRM%V03f0lqT*admsyT$FeCk7Uo4+x*iW8#f(SQh~1?`f3#xy;H zv?K$Pu^zZa2g1=tHHX!7tkhN&$D<3TF+XRc0C3DaBmBh16kKetN~=X%p&JifsXxFNASYE?&0^QdnvTI-21YQCSJIqKgKT z0U)|>y-|K6a9PDQWz?PSSLYY{>`!uVwOyUh2nY7U?;2k2#Y}oehL}kq)u+4=F7Ddd zz3u5V=b!G&PDu;fYxMA}6289am6uW<9!?rCs-3gF@fm0(S7ffk#Kc67xA-_H8qn0F z;K{8ZCB|3I-Oi+fw1fVWpYH}(x&4}e*@lV|CM*V_SZdBHb2~+}m)!{{!aIHg`SB*y zFU{-h&l|0J*`0es+w}YOiVo4)3A{RT-F%xvS$~C(cIJX_%EHQC@RdsKL|?Mxov<3c z3FUkq6=X-dlHWYXP#R5PQSTW5vyc?OUZKqJIr|efAP!w*Bli+CjR4l%dw$fhOO5@) z8&jwfa6dCTPyd)*=COZw(r$Ps;Kg(QH}m5;UbxG)=lyZr^$m|R+e>;@C;wa~@9=in z=A;2;$06+AKV37cpGC=aIkG%XcvvT>DGbNHz7-RkQ$AY?ay=hfabu;ty>o4fXck4B#hW2NO`#OMV13QK3BkX4&^r0*v887T9a)&F{wQvC>@Iw_jCI^o#@hw9?`Mv!V77Y!V-|X& z+EM-y*}8^vVJ5I_UHrN)?$0!?5|#@1_V#V0D^G6-j!4$RU8qHeSF&r}1MEz(&+1V< zpD%4k+WIuV5YbX;RnQT|)M!5sRG}zW`Yjrd-e*n8a|b+3IM{po1&w)-QXaO3^m->1 zeRi5=dSn#k%=$v4Ik|a8*o6Y33=tGbM`t=oW4aT}?wF>DX{$Z{Zm<8_Dx{YEIpAzH zQi11u{m5Q;uOiF(k&lPFTxj#0)+JeD`H6xB!I$V-DfXtHW`Lc{u1X#IR!Qg78 zb2)6WP|~sOQBTlg`S7Q~WF0Y~Jg#lo{W}s{R$`uvJOAUI#pLXaYky!20$9`h8SWo( zEMZRB$vNf@$z!ssHdb<_@MlRpc+=Gd%JV+g5E2jg>D)i}Y?xMA3~y?)yRh|xGK{QeuHys@ee(z3k!o94b z;b)@0|Zj~y{8V8_73&-PPgI*Up7m31n* z&^qe_XWWvuZ`2HRf^Eo*OIsEqa0Iv3kDDLvEb;~RBWt^_YW!F^`jJI67@Ls#zu2sb z1jqe7hDcC|;8lI1u--jxrWc)9Z>jR8fRxoP2mf7ghpZaMtxJkiF7r71)K`c2utR1k zAMa}~>hZpWQlceRO>!)`aS@BwC26VK$U?ijFn)|w6}01HlCAso{|q*P9XG4=OoTC# zi(ydq;I8|{e|xrdzmgwarLy|GmDlk>ZO7l!k~!h19qzv7OtPm7A_tP7<#VYVSUNiL z(Skc1pwK)6U2N1W1HJCb-4`_`k{0}B-H#BFW#Ef9!2!=-x~fc52?npGc1!$6tyN+Q zimaG3y1m2t{@E896&JR=fZ6U%=9e*uYfm{ZVAHdOmmcOtK)@X*=_!u%RkK7&2-3Z(i;piqdp`CHaggtV=);}-GcSu8%!t;}gS zQm9MT@1_+IZSm z0uWHJg4x25{|46vks03or2U(pPj?An>Kf5sw)c@C`$+Y&z$6sxTV1en071R*5~N0` zjWt>SqTvj{iu`$i#X5?sP8NB9jWl|M4f14sfc;ibexp9r_L}J*SZusU*!#qBQ9Zv} zncR<&qBfW<)3Y}lzg+K#lt_NX0T(aJU20pVWj>tA*1 zG_OmLmjQ0Eg~Md(Bx z3&4_l@L8iKx^z95ZxQ6+21mMi<^L4HZmXjo1Rne(Uwf)Gr!X(D8`=z|D%SH`)ISNw zW#%A{snb!B2S24s8h32NQ=I*S^^+`C2%A}f6Uzd%j1Fj~1Mi8!xizZF?2MkD&nJfD z<=`q`LY|vX23>5ULdv8AY+gPSsC}-99c_=uA`i$cO{}O0rJg(QKcM2$r|LmgzZ^%5 zlwk0qmjkqm@eWMDkw$K-^j4fqQ4wR^nK|n1M$=%;VeFvPudYfpG5+(Y%Hw3E&?=<2 z;2IE5=QF_BAKfx;G@O1c@cdz}<8n3)`U4C`%uo~SX&&T-<3x?noSQOH(~b36eEg<9 zTo1C}&#KYuwfvL$GYsGu)gJAW*zTb%1Y+Vz{;@h{B!=*JPP~YWrG1x<(P3GI8}Tb2 zo>({`3MX?v{e!t%(_@b$Lr|~zXr^2NTt>1wE+gY0MzTlTa_S%`bMyQYReuD8Zx0os z%ouaMMTBm4bh<4@Q-qna`8Mxmh%LYQi{(yv`ya9ew{|gW)%{3~gi+;Ln(nEGN$1IJ zv=2lNPqbpi&IqLcpo+Wuq2qV;lyP51PKF6&B%{}i^~8o*;KAe&tU4|=qo5G1N9Y2o z2a`qQ{>^0m3QN?vlo0SI&fV^C#9<3I?T^}$sfcr^Lw!k2@=I}JRIk(K|7^a0^F+p< z8i4kef)v1fNARVZo&{5#S))q!CKDF0w;!sQGQUH-dSDygD5d`kQfHVomqsVDKY37U zf&m(ccw5b{nJn5!5qqSl0Rpd` zQWZvyVC2Uq+WwbiRa|`Iw~*;Op7wlEvMNj*HNa$LNHDO^!{B{v2`8tA(!F(s|ee*|1XTc7BSkZg+@p_RCPb5JUerTL_s%46Lfvwc8t zMBaQV-k_XVW|d6cM4#NU{R{P2Fz8wOR-WD*LnBlqOZX#U1hd4VnnzR4d432tl#w>e(jkq$wRE1G?GXu|gB# zE>mi_UUiZ|-9uX1`9OInMDct(YgZLN?#z0EfrFv1!9>na(n4^Ctlcvt27|gK+-P&6 zuAfQBesdD%?ZCAKUW^5ewRQk`N*-qd@K}>6GRkB(qyC#ng{Sm3gn}aE=~9*=%c4<2 zy$HO0(Lb_YWJc;y!K4BT00TiePC@9}vh;GIu3tvQ8qTWcqYtbnm^c&wP_Un*rJ#r| zsvMm^3U^?k$%7|<7n*aw6Q#@(l_?5=8xhJOOkHLyp+i0-M(ReSMu-|!0Xhn$(IxLx zXc$=BIv|+PyDQ>A9^;X&3N`zkTupVI!6D{V{88%4b-fm)kx7VpyN0Y{E`!c&cM`4! z=}iU-Mv+X$9Nc)Ya5OP6&BAp%=Ze()Nt3VJvQx0nMyExx&UIS zOsLh+={|8CdqV}&CQ#3;goxL>cLW+nDE0Vf1?OpVdp3*wzTJ^`_s{TkC%o!av$yfVEK_d3p}CpQ zv#P6A%70s%z3KfnLNWY07;a?e(uxvMw$t}EX<~%^i-QuL*(TgOG*1WUIFp78pQ~a)7OMHr#ulW7II#%Z;hu>#t zP%l!DVb9_a3kMtBEA4|K?;U*$qBMfg_P3eZd?SeJ48icjD!2y2$MDlC4h@DUk9kiz zMoKbubo%p^29~TFmJ!jYUUEQ^lqAn2OEM!tJ^CbzCRzYct-le;6{dpKKCGN6kV+TO zT47YtOn|jV&W-&xGrBEXXTe#Sy5+O$xyim##l|Z&7PIH=w(P(DFrx$RQ8cgk)MwOV2IEH})mhAF+8q*~L@PWJiO={*Bu%^DrY zCN3VY8VgBWq+*bn83hekJb3NmM&g%p-~gWNMe2iPi^m59>Z`!TLq|o_ci=wrg=<@d zfA&blerh)OjG=Agcg;6j;83Jwfok)%KtFq1KqNTfj({vVIQm&%X>;_GL$yfd==&QI z?e|t4gd|c^FvtRpI%@zl60_86i7w@i8a&z56akC2F8e(IZ4-O2#MXS7n_k#389_8R07jOl1HO?NE4nt*MHWyvrM`@g`OQM^V4|S zCkOvB|JrLVr@Bq(iZ>ZW>ciT39WZYcEgkGz8b5LQ>G*Q%B7eEs)d#y83%0}^f?&W> z=ALE#XDZ>N4cT)ILiTT?Pr#bA`2#dVISxyMM4y*e1&lCwx;qiW=+$r494@IsyWi-B z>bnp9)(7T&L)aPFz$2758$EB<&z(cg-n<^VGsef?jq-7~9SaY8F%wb(dx@^^%I|Z1 zc5$<|8Q198U$37ynrl|$Lw8TEb@k+=czm7l-a4=1*h6ayX&U-qK!}lW zbgQrIXyQ|IW`SX4X<1`mTNgFHT-tkww! z2cK?Ggz{BirwwLz4Tutz-X4pmcn+(-=*j?%mgpyBSc4Jw9Dlh!l?ob-Qv;H7>#;dtI>*mSj3I)C#oOO#7}+uusP zYp+k+2E=_X{;n+gI1DaL)^}l`(6aZ;7Q5P|)Qb!Z|5}>v?8?T)Bfbs`3T2H5V(jb+ zQZU(W)iYVOEB$x7rBMSn4dwVZMT+tA?}u+aBWvir6Z*+p-Nsu}aOg6+4k;3h7E|co zF3b9UzASTOWw|av?`dqCzcwOkq;=BF$@tyTt(r0##=ojwhuM>5TKj&*!mGBOMfD&-mqR-_PDR43?L}?(w(E z3m6nA>=jJ`GRXLLA)J-tI*{)%JRw2sKZPt-Vo_kX@R?|Nf{%+5m_ z-@0xU(CZa9R?`f4W=73x{lS6CdnK|r(CNzGT9o6ktBa<68Z{9EqU8>$)1OID?B!{q z0F6v@>dC~U*w%4gYs`_?e$M@z*k)5ca&=b$R?4~8aZZ%R3yukqO2J^bzKSvQZGF9~n^U|`vmYLz64)%vJ+6BlS(tX> z=QqVgPmzA&Jlw6Qifl>m6$@R-nQv9h_{ZF@V$Zj}dh4a0EGjCi9OZn&*15#Q583%j zQI&N?E4NyDgc+@$j?CM9qImDMo^x-Ic4C^H_EjvrOrqgl$KX=-c@+L(!pF3ee8toT zh9*DW43khQSG@F-L|TTT$di<{zd1)!a$3SdNK9~f;q+04BSy{@<#yl-^f@UeS& z#e?Amnw1uhEc7V;OtBIWy!P?s)o;Zs-K3vuWkr-%ep=(gTZE7xv0~DCJpX`^&<1Vz zK;6=yD_Q1(*8+-daq|z{{bft7ms+2t$>)l9ti^DSGR5C5t59C~RIt@xYN`BMB}!GA zToPIryM2DkbBl!*tctESo<=KQ9eFqMD#$R7(mQ2<6E~p_J<7ZHOZ;-%P}HTj6iU4k zfv^_EEvCh-&scwHXXMPseZvoBTGs|BLz~>($@a#`!@UaJ!6r6fvgSV#2gZie+RZv- zclayI>lSyVS1}?#Objpv3Bs(wTH=2PjEHrX2Q#|#f;Jeh_(BRd<)=O(TUt=SHX-<1 zaA}Flhz7T~Bv4wv#ayzT^jWsif}M+gejTkdWxoDIQqbMS&3p2zd425(_f9*4ea{&m z*O2W_itGZ)+GWJS-y%blj8ACp>Zp5E@x`Q$_TSgDcL)#2HIVLQQ!w7?6UG+&M$_P}vBy~#aROcW^)rDx^5i-ye^Dz4 z=eF&YPoHeImgF`dblayYVKO${!Tq7N>naJ%&8Okd&s4NxcW<(tMfL63_8zO!%faHjU@Xb zWT%!nQ6AwZb}0&!Z+9Y1Xd7z0z9>*SU&YML-5KR{QY3%ACEaxVnVjow{O8WcF!bb# zdXx6{$?6*`!DR(XpW1#c$4JL3UOl(HX{7Xge(z!_3o(+-TLaW-aXF8SSev{Be$TuP zW?HW-kckqd1u144jZK9kRbajANWgXP!p-OAI`8m&4~%u!vsSgS*vkn#8EeDl{)!bQ zmC0%dZVLnM*QgPSfb)yN_vCYw?EdHSf#>p+z_)<&2@`@jY1a#V{NqKh9082|sJ4T2 zz_j}Lx&wo7SBfwX-gS`a7Ir}(EL{Hp(K^ZTQ zn~$qe+8z1ly6?`^Rh?oD&Q}K`PNb7I^OMGX$*dpG*S?SNdzUH$hE3d>kxh%Ex$H20 z%wMQx$ww@~*$I)2K!%!rSg{K&?Hl_>f;X><45hOcgE#G?yA%ac-HjOtbWb%?T>H8H zZKhz6sx#V~eEN~sPgDg;Fp=F^g0VAyf3SIb%mE7;<13IqEvKWrpRw6po7S`mJRYt* zbWVPYyK3^<|FEFjuB4A3%Ksqfd22*rKew6{-U29W@tWFy-&oT%+|%S!@zdJkK)jjy zzBYISzB_iR)kOcseG&ZjPHMtC3eLLl9%H&pmEAgMK4}DQbKT#1mP{Ud?oOunHm3y) zN3NThN>$uJ<-RqUILjAKX1riMEj;Xor%enASj$(*8su$E?(~KlUE7mZaX&jYx-O%v zDx{D)X=wNqS7{`ChMZAkB&_Z4f?riZJ!skLl6uBqEnjNztSUqN{$lgmXyVBan~BJ+ z*VdilK}L0!+}7VpB1%V0Ehi|LsjcNffxBj*=&e;u5cB2m!ZB_|E4*nCwvnFhVy8@f z+ua)rQrdZv87BYTqQy2oyJHUP&h=LWW|tPKC*F*oN{p^0{1?kFmjmFp!T;XQs0TY$ zTF=^&vy0j|oYAwyHoU-?r>ayp1p~^rbmqv-kQZeY9ooVW=2v@$cw|EUbZpud zXOCk|Ay_>A>3oeO+o1fc=pa--@LB`oy#Hp;?b79mEw@zD_%XY0Or2b*-*X%#Qju4s z@-*OUQjDi0jVMx9$5;x{FB=hx8gcK-<}Vx>uluC#ll#{34k5dmYHKTa>1=(SQce5! zAFn$H_xUqY7^zOyzciUQwFwpO<7RIK+;#Vfe7Rn8vgFH?Yw+H%Q`D1HimM%**P3m+ zQLO8m#+K8;xveB7nW4A|#r>#!Y(tNi#?dA;iO8?oSVME-<92y6oo_UV_rvB_)Yj`k zz_ZkimfXJp&zb|Cm7rv%4hB5CZx$+#fUUbM?! zFDj?T$Y0M>&++(Q%C&c1_Onu=d1$68lzkUG+&NY7v_$qg9(>Z~l|6#ugPHu^}36*;WG@lkBmK z%CqXpZ=|PJl1;0&gyL#jNM44#{*JlIRm9=tBuiH8(QwgbLbAc+wP_U!A)`R&^6Yos zr(&b7P0;gcRm#diVS!V|%IX#oSH>X`?7+qP-4?ewC%gLhbYR-6_s=**i@6I@FeyW} zoR15+=Prx)L~Tw<#+S!NI)3j7T!Ni#DQTd^%hJ&OGdvUFsx-QfDHC_`*D7tt!r@z) zl_Bexs%;7er#3iIw;e+%w`TUxK7)}@ZtrwJ;+GA1xtEZcGpMr7JxTSgfd)5f(>M>W zxATncr8@g3{uS(3$}vADKP2;9mrW0rhsL~e8G`-~^4>D8s;z4urUYqG1ZfE==?*E8 zk`4ib?(W`%ARt{zcY`3^umO>dE!|zx-Sw`$(Q`cabMEK=_5J;x56rz-bIlRgxW<@c z?Mx+pUf~#1i62t>2%KP_jYF7E8BbTgE-osw0h(uKV+at&=8qg;+m~ zIxOw%Kf-_Ryvd3-zlS^IirDoXbQjp=pF0b#mkU@!WKJdT7QL0S8$GqMnwS+$ubAII*^SSfTn!mN%g+DoQg5-m)>EN>BPD2;^5|Y)MNm0VRa@`P9wQD;h-&KLObqrElK((s z@8v7o$u&VS(YSvVn>e<_K^5SRf4TD3ZDF>>;#u)4<+HP}Mviv06+h-M<{gidI-|s! zv!4&aXYv>HZ~PK@BaQ^@2giMrf3*W$`Pm##-U5tPs}Py%dyn4;o!p$2&A> zJ^RMgHr4c>#gZ2z6 z--$Ygn)nt>vJvwLj20Ek^(x8e6`#FstBCR|z03W#R9m>02zE0(4zDibiN}+*CZ2ov z$vzsN{Dse8n_kOXbpCKv!st+2o zjjCzFDk?A|b3?TH?eP1uJY1?ThNWAlEWW=Z>ev>?Vd4y?OjM2)=P61MfdmCpPLT>L zC1y=o+a+x z@oQGBGfWT=ugM;M(APlGsHBO0Y@QIhfQMM|n4s5Ac>dLEd?)K|Y1gD%QCzzf_*gcy z4@tUO92OK9_=nV&C}hT)j4Y@i`a0 zg3f4tz5zYOwe8n!1EIsM2N7GkO?Fo7*19w%+4wH4@$PT24QEF>cP8n3QT8@ZEXJ>K zARe>PaR?*z`y*jrcAwGdky){?kI|H94{uI()v`Y;d*;49+-g@9-@s(bOq|@I!a#>T z+HA)V16URQ2F>7&Xe#igg*T&uE(MVv!@}#SI(?s%k|v%Ui6gEa-0jQKxpei|(1dKM zYw(bbizD%*FgGMa@aO9dg&;oT5WD>gmzM`3JQr8bDm_1x%|i6D=O8^VLx5*yNXVvC zHazNkaOC0^ARpW-(#9cCC<)EH8fe|bYnORDV9?p1mgjYM46_Mq^g4X)1Y{7}85x9* zLEu?cUAoGKu*u33Qc!CO7|IEG+D%q{5uHFUZC=tnLGP4~d~SK9Bq{{Mb!kli_kr zvgYWeLVHT@G`%(`z7}2ZZBm>&gq=sG*6N`Qx zC`ZEsnl^X`ra<&U{u_=3q+hWG zPH5mRj_(&+F(bOk5;k_}(F)^gTM33WR+1rBlFjvF-h02rezwJMslx-9q}@K7_CVV| zB@L<4W6)Ao+!N&2C9m}U&`Rj4yb*M>EA4WXEe${BEouSDE0Cttr7BPYM?2kqQ@l+JQFk2>i!(;lZCj?lYin zDv^#5dMgrYx0_(U-%@tCW3Inr*#EF;MvVibxI0YmrtNEEyu^n7TMa_U3Z!w9#C7|u z&BG0K3gnAEa0Uc0N(P=D7fRex%wD*D?g-+s<>NfV&q=%031K?5}N8n?LhA1t0&sCTFA%og%wQ4M)DehttjSs>Ba1#TzS0@zF0}jx3VUj@hSxS#_bKs+jMZbrurx0bJm4 zr}*Ru6LE8&e;l#y+KUvS?rXHs0dqr17;X_`EQWAXSFS~oyDBhx6Ak~MYF@|_-_gvfIcX|#a8$vR>=Nk$=t}Y22?`n@kg536K z&ES(U?8br(s1^>0Fnzpb(>hm#3wzT7?8v|kS8F$}ZW)h-@igG~t>e9VCFmOC1$qn) zvMS08nKEK7>`{M8nBue0Ecdo%e&UWv15*pgtzW3ww-7R0xxOS+{ST+oPs_ki6*)`q5TvMvt(7W~ayy zRrj5iRPD4G`IyOp1&?pvIJCa<0WVZ8zBny#z#NKmRrQcST#t!@=qG4sM4>Z@T-6?y z4T|Mz$p{ZhRR;+M#IY}Nr+DKP+13B3A`^bPN}WaXe3~ZhRhG4Fw!CO}?D25M=LKh6q!nM^^OcV4kKbL7IT+VZpxlkQ zKY=x$dZ5}EJK$KGIEd#s#n@qjzBn|5zf}JD*r#zgV$cxfBYN{;on*7L)jw2|*~i?ODedN1C>iBh*!ZMMK@(J|7l5Toc+% zX4elcD;HAFRsCtV)Gv;zMukaGElbUjj?P6vl5_5X2?T`~szTmASVPRzHAzfHHCs8@ z1(I5ri@3Qd5zDF*VItGmySW*c-)gnoRL%rSr+OHQ;Zoi-60XS?H6}2C{Z*@W!QEiq zq=co))L{unk{J;3ASX#WN??jTxo3$6p4!Yy8gv!Towu6@OZ~Cg6EZ~fI*uYb$LUPm z4I<2;RJ}8WMRpb!;BYcLr;pOIZ@*X7i(U3v;;5NT74SX7rnGp<7}(qS2yCLHp2{C6 zz=)U;0_lwnU2&>I#>eWNoF0tDCG(qCBomvI6F4N4$8RtXW=~jhcsH5utQWb{CkaL$ z<-LCT4LjBO0rQWx1Qe>-&tE=h;aKK?NEhOr+0PJCCqssBG_vpgSem+1s8hdY;W(Nb z%zdS?XY@{Hk2-%lOwa1GRxjO*z3S<(`l76-gBCsSOpn@el=K7{^1T4YQ+xi_gv%Gb z`-(g39$V8t2(}maTnbi6thz9qdh=@$EC$U2`6tZ+>%?ko_)K#<4TUJVzm}7MAe7up znA+CAB`jGVoYi9$SZ+A%ICIxTR|l*_Dke51y7b54d) z&Sd)g-3!BHsx~xNGbe`=XZ^lj6s}J<=XL1U; zIc2_Rv;tpz?b~Y7@kA3F&mDRGJpr_r{z31WW5Du7eI6L$O|1-=>>9cGNUXVzsLIj4 zJS91PSIN9@B25x$QS!Xt$)iQ3{rR{&gQW~lL!=BfLBW|Oh!DohzKZ*+Ts+~TCtL}cm5FLHs)s;mKCy-0olglrjtr#8`^hn_dyV* z(-Bj6H?N@MEg8?7lU_r7lXOe&Q*opCIija1A81d7y2cvdPt;bNX14+xFIegKr!`j{ zsZLcho;Pl@e%Uv80O}^QR!0Lj6LM@*ax{-lrE2bmpe4PG}C!)zOBX>+k16Ix?8HP<)v8 za|hw5PbtDCdJs|!l{Yw>o%Ua=rZ&-xYh=$&X3C)y>g;a0zZ%ZP0AE3h0PZ()=WjPx zovgj;r91Vz;bDj_YU?dei}cw!oV%Cg^JvaaV|Tdb+()$dB%o&QE%wo@4&D~go!Q(; zOmKf3^=aGUmD%oA{$Z?@V~ify#8SfBij#h92pe1>Bce!g5F(CrM@+|g@Q#+9k83kG zy}fr)L&f4;_vNWKg!+_JiodF->V%*UXl?G)F+_F>mCa3pb}W6Yoax(pMvvo>XT{>S zXrjhF#0}j{gdTw+#*>j*n(^bd4Dl}2Jq&c~NXI(;_kVQB8=nh%SVoTfjIf*@gY7or z0q?LEVBV1&zMBAhhjGDoAdW`$f z*rr57bsyg~XD^qRb#|8wAJnbV!m$90-sQby`@teTuv6Kb+p71D#+6KjJKMX1klN`v zq9haVqHM*W23$}6&zifv+qTWzGZ(w>R}#2yc6!fd_alqnwqa?SkAQ-Fcg4y!?|ps* z%D~Y%#sD9CAZ7WXo&4b`X{0yA?~Ig}V+?tA22}#^bTH)Q?q^TK<|9x;m6 zq!}Ryf9skjZko(!^O_dQQb*5Bc#MPAZESY*#LQ1`icrB(dY=w67cjB_nwlNIlQeq- zax)^AN@=e0G#((pe_%d{9L6GG2>QZ%2k_K?g>Cpp9T8}7)B78T3xnXJ(L1wMWpfuJ zzytNE_=R{6_qwBxm3?+VLA)O-SmU>wy<2w=3dMc-r;WghCR)}^FEPOVA5)v=%yuLQ z48DQ%!sK=U-osMupT+JsPh6F$Wa}++$5y_|0H>+L8-I-mf&*wVz%dsT}SrnP< zYLt_$>K`vAmXPI?lVO0z!lI!3ys+tEu%38j+CY6O7g{?I6=?U>G0wYa{0=2F`;ye2 zxFgSAH><+cGAZ&|d0tWsmi1$tdI`{Roin4wRKRU5i~z`DGrUtdz|W-S5NS3`biWvUo5?{%QgnS!*-= zC1UJc5Q&l@9!~^Ah2{egO?w0?E>Dm-l$-8S1B3tv;&ca$cDKj`9ot%QL4(w}EDdtI zAw;SBOC)&RDxz-Or`h9od|&SZ-%852a>0TQ#%4MdjGZI;v!s|3QlC1$0;)w__nlde zD$3?6!iU@TLZ{+cxIo?9HG$R5+Bq{z1?E$6Um#*tj*md-k2a{)J`Q-qN{i_+9&9D8 zsCrvH>nudlIy1rpCD_gWBkPhYdJ}s*d<4w0uGDvr5TC6x=zcxZg~TV_;VR5p`N9>^ z<5aj;&!e-PS*XwLI6JYMS)EEMpH;>y^Ni9m^IQu50DsEBV5`cFFL7eU{N^6b@V1FWQ=Rr)Y!yRrB#1-yqgLY8c zj9fb4aqp6+K>+gy8}q}m;;_*uIZn$#4V&v7(NW6S)C#zplB#JatjxFGsqjtn1v~ zvMfDwWNS>3sWL>%TXbuw6mx6&#`92Vj7W6?`#G9h%K#jn(ipK}&iiSdyfb>q-YWmS z+)5J4i82R0?vI$*Cg|(a_@-82>U_Gr11`-d0AfeJ6O&J}k1_K4xL7N=!n-`x=^2s` z^3KFdY;TApZEldtk@6@nXoxejiD(DT3?0g{EPHX49I;zJr87-nmc&ip;~v9QglexN zhiS*s$$5Wu52l^_#ja#Ipgqf4uj&N`wkZ0#hUAf>SY}2K9NjyG@cc=NT9nj00nz+2 z*5`$onfqi|N+y2&AJ%l=%fG+LWsfO&f=VH>E~#4YGsM9tm_(^c?m*587I50UzxVdj zA~=rtglMTc=GZ6vd8iv<({nVbZA-%IO|K!)!^{F9IbzCm zt=V4dU=c>c$IUb?bvsFAtuT^w7?>WO5YG4f9&6wA)--unbKCPETK6kE)a{x+ETuvH zReMb}-yvW7)nibRboiT3HT7{l%S8H2FvTmjP{n!Oj)WZ=a=mIIrpfg^lwikT+Kkh- zY-Vii6EvvLY_Xg&MFrECOtg~2xGO`z7oonyvfJTcKC*l~4AG62dq4Cnq-N>{S*b_c zH~O&ymCvw!ok1Gi9g|Fuj&CGdwtH^Q>DO|4S100k4 zmiC57a#?7~?W-Yib|=>8g}Z5-hcxRX1~krH<$K%kKeNU4(&~qSSW6*KgxNI zR->17^*A$}KN`6>e1V1|>YLwY2}j30rFs2yqa^?HFGg3$Qe?WM;xrE|u-Ej{b$GKu zax(oxEtCAov{gCEmNO>EHb2idb#n#T(pF~O6s(;Ec$zNQT7&Gq=I=R-H+XZGuazT$ zohWHE1{w&a%B0$@*=wt4B?9`>1an+m)8dnMoU)4&8;KIMX&Y=hwz41POVBJGM`2i5 zi}+5(>&Kc~!L%HSbR)EOH?=k_1n;Q1qCT+6LgLSCV(<2jmc?^zvNf z^uBSm{){`$EEs%dA=68uKo_&oMja|;g^_Q$9_wl^JS$re*Cj&bL(*0alL-z za<0^_D1SNl;d)&ITQB%mHZObMdi{JwgF?nb-}>G(UclaVP4uE6&U@XN{)dYqy~3j$ zuXVgU;jF7ixtDNZe54QageOr`n0h(5mJomnEL_nW^?pc3!J@0TrlM1LfXJI(>l-zq z)Jp}2S3+yL*WPsnmost=3{*qO9>gz*e!LNRMU9<=kt0F=A z_#}J6)c{}m<;;qb`LP?jz|EF(V6Tf}pzNa@;L~1QK(KSeb)%4rt>{7Z9D`%PaeNWt z@UwQqjpZ@(mo7CGyj%lBKKTiH8Kfi%M|S3xHX`rySH_HKuNPF^kYCZXix*<%o&y)r zrN*z0QK6_Suy$sj=D`n-(u~tK%jQ&Hy%E{Exjck03tcV82wh+1Fh5jb>NITRR#qU9 zFXd%^S&F)-qCno6T~3DdFwz_-Y$~T9lk5`mPHIjqlzeo57AJWf)q(Cpem@r#G)1B2 z%4?CH>8RKX3D(&KZ-iHNxOU9l;#&kNNeo04T&e3uZvZ*VTSTG-Y8< zA#V=eChx!iu2y->T(DrjVFLAp`JQzLT0VLJm()#%6nIrEfJ-M4jh<@a)3HzL^K@Cl zCT}#O^;i>g9yvCs%P!d=Xyr~G%5;0nBZd=_0P(idBG>!jU)`v8zI~^VnjgnSn2(qr zY4X6r+RKF9;#M)FTnei=RX1ODPZ=@4NWNk`JC7@YU){Qqdysp0PZR+Xq+|hXU@DRo zbXzDQzA6bEUUwe$y<`PqZh9N@QSq!F{HaRo-G#js5i^ferdtr~;LqM{dl&^?y-R>; zuHnjy@p;i%5x|vNk>+{zjz}X7z}gIkwf--x&C6t?EV!Jsr#!5(Q~5kjCtVavVQlNX zWt%y`w$$gPA#r|1sy79qE=n(V^zkMfv;-Yv7akm#C#c6xkESZ@16EYRtS~1!`dOcM z-rh6~4R>#4zd{oCtIo;*E*^!7aV~@X9{}@=CSlB*zGYs{r1_wILT}dO=7}L%{^A26<==Px1!H#oSFa;t%ZmT_f{!}Vdb8m zaaC2P3cotA;7~zPc`{2qF$XueGWn@fG{=ix&apbP50tPFwZi^+bigRT2vRkkea4m0 zT{Ujii>uszV9^(}4@F(MqY6Ns)fWVy-io_#(Zd0{w46DPllm$aYL9s_Ux@c#(K%QrZ%SRxy#O}{Jrr58D zl;MCx1;tFk+xWxJQYi3_j+f-u00UBB1{~1Y##sgBc?h;LGSSKmgU~RCn^ih0b(>w( zDs@>_m#yIr5a|N7Z`gl5OWFQ+?aNfo)WpLvl_$$f$22bdf(vkx)zlIq0&UsP{-HdC-`l7vCp{x%RbWSD`&!Q zx}lBZ0)#NHWce&KrR9_7!X?H)zQvlgNtN2A~qv4<`#p4|I>K2*D+5VGHTkD3( zOA7-l0-w>|T!egag2t+hPKnw7W27vOg|L}Vo(GrjR|OVMNH#6hEPXWNEXt3^s~bEg z{PIzBeN1t`pvnfIlEG=~jGee#d$v>2d1Fhzlu*5Je0YwE_*1|D`IPHZfTxeViXmag zxpbkH{FTS0`_#>dn?zpkRrvYd$!v$$x$(=48`G{9uAL_VQ{FEm=w`^>fcHLFWe&A^ ziL#>=W$@3lO|+c&`>E1R6~{@RLuG^(_-cG_Fzmh3VkZ5`Ex>SP;w zy$|u+%tC4~b& ztle{XP$h|3c8Zo7sk{2DK4FN%g~UOEAld&!6g!zUZ`c20Uu;fEo%t!UOuRqsaymvx z!X>=BC$oiBxU~8Nw&F{S)X|i)=PA3vJDP@spsVF~UIff*priAYlvz)g^PNR*ZBwV> zP^Gl5Qq(f>?#@*)CXbW9W33=A!)^3xa&%D)C0JsWvSt*=d#`Yq=plUi#*jdOowhT` zc9^Z7jr_v<;Jpl{NW-OOkR5^UGcN9qK5pZ?U$fiEy%@Vjs!g!P$7dcF6$887qkXh3 zI8^OZ zw*5w|T>>*3NWD^W`Zro796~A0;C7{J}iDraC0b?rTvU{N~7o1{^{fmm$$l}Zrf#I}ZM^6^voPLd4SjZ4!w&kX81_QWb!UKznb+NeQ?v}~Q$US4uyb_ z*5;x-PbO3JaVNS0%CNuN15%77rU{(;bJZURR&nU4D}Az9{k)`UijgX=)NZ)=K+7w; z^H0SFbxJNvp-7oo&i{-;gx z&I80z84&pt;0M^y@H_jr(qE*r$UTvebY|R=5M^c4+`3DSJ3B?e&ur4F5G?y4??{Oj z?4Hq5j3&k(wy?LAkm0ZMuvg?+-_{dSBltxdf_&^zV(HB(!l~yv_rjPl9-}1`H1e$G zn=Y2rAn574L0&$y^o?R-BCP{H;BLHNv*t)kD&zs)eS2ibOeo}`Dr2sc-VzoMd7zod zyy%(Zu`RX`YJ0cVYD+Am;OsM@tPKvwidYUR8%E4`V?BhnTp`89UxjVv`0N+^dXKvk%z`XEY zmgm!?%*xp+Abu;Sym7di6R7cN_Nf6SWaIdB`C!qi{c$%MQyXfES!BvRA}Sx@eBcPi6z2piTlW)6>fgmix0DjhlPZ zJ(zkt@V3P6O}NjRBTLO37oDb;Nd~9a+F%_oAXQeIkZ6@f;}fk@!ok=#wkRP?rNd+4 z^mlbVOA^lZl;3B$oFpHz95ney51k(|kC1r^@!A<%z4)349!ZfYo%&gx##SyB(;_7* zP(kuOzuklh*8t~pO<1cEL%^AAJm-WG@p!_bXBtj;byZd3Y)mUdRqcHCGtIkip6jei z+0Z^qPia+rj!raTiPtM92hS`0u;%!=B3^UUMRmK-DrC=# zDddyZH@8_PXQk-l8NoZ)%0IiNi?sM2-**np`tjKzfhb16$&JH}>8WGss_o$WOsnpE8llF@Dv3?~$?XFet_2ieM5E}nSm z{mb;WSZO^DZ#TaCbz{h^X2?I50&}-A_r;eOv<~BrxI9K!eu@2S?w3BIh>A1R|IcZ_C2k6%v-H^-r@hht)m@LwDKS%%|3wA`mecCm;KhR%rHRB?6tCs5P$C#; z{Cy;&v3aMaDX{R{Y)X=dvEJ_spNZ>1vdv zf}V9BTYPO2my;DcZEblz>O+mWwO4S-+6v#MnkBRhF#lhzoQZ4^p@JIo=Kwf2DMri` zya)muW;}zs{(JcPkT->S!P@FS{DS=pIJX7E1nN>WbZx}%VKgui0vJ-YWPPu5^*;tt ztP{uo9h0|!S4(#P91h6+>j0Gh8zzmgxjq07<4)VJfP39F(Acf=0nv#D95{Igg?^O} z3h^j3M$l=H;JaT!`&NPZXi%R6R55gUiXF)>*Z-d@llA{43@1T6?;f>73B)L{1pu&S z0*$>qKQCa9`~^TW`9IM5jT;cY+jUU%|22Hu|0NDOP(amFL=T<4fBrMK&M#qeJl&o1 zsZW66apW>I9=5jCszC03pC|nAJ8^9TK`HU95?$o-Y4pnohW09zK>f3yZ}YMC z-s$u5yd$1?jfEw_2pu9AQ2a9_qr-R-vG{>Ga8_Gd5_A#c>rksa+)i7NbQUlR&RXxO z6N~m~X$5BItcN0j0hqMr0mOc6S+gz?i*^%#lIYW-n0Xfk5K56adV9$}j{l&dAk-=; zV6`Guck?_gY=*AVr-dLQXv>Tzv2WJ;Y!WEHxRb!-z#!Bp5Nr?xT<+42fC#wX3R{IL z{XK{;fxvz(CNaG3+hY5?Jj8zvK($H2gBFctXn~$AoE;SIXBQ)*J(ui97b_CiclUS$ z3xI7wi%AY8V>=&lg+A{H)G~E{cA)N3VCCdD%wA3db@_Km{G*WFiY_DGuqG-`2G-n? z52#vysV$p|Vt|#Kf0kPlSdDm zP{96~b$~&DzP!!lNX|Hx&;y`imj9!`0LcIXe{4zm_hgWJbvOF-S+JfvR{tV${{t}y zu6ycFN-<{K2EvG=n$TT!J)ow1`{8JS@aL8h)lzYbj$N9-A9ert4nSthlZ0K_1{5B2 zQGTG@V7>Wc&mps|wt)E$^;%lK4j{;%z*+oVU0|SDLu)TEj0O_-0cAI2!}=cTKhtl? zx)9iAKekx>7IRn*NY2awb~6AfQLHLPXyTqgPyXvRCI0W_Y84uYf5+v_&i*7aggv|iCYF3Sx5fwnB1=VV{@MR;5Re6AVcOmGz?|v9oRhctMH7j}vbV+iFQ{%&V*1R)A$UUdPf`In z0N^Y38NEv7c|iqnx&-h`jE6G)D1m}XhtK=J;Ji-pkCaAFK31viREKV%|H2=CZ;2gl zSeKysGCi8%gk%}kFaT`=`e#wq(?BAyanSwM)ZOYmEOE38=nR`3Ue3Hcvtq2#qtO!DIiJ>mrn+W2RKDE=GupAo-F{|7uUQvoZ1TgFY9TW-KO z0wq{wuAC@wyTI0EbQd4yCT+L7#IIu@YXmQ&2?73n1VDqi0`0n?2D?tcQbxR6VCy&Z zJVt^r5(xf&wBq9f3J)|9Va+NOqrc)NiiN-asK9vw>OPEqA7HSiMpF>ONPlaS7!RcG z7VlK(eF-#2BY!b|9(Fw}#eWg>2@oJ?5(ceve77lpyaue4#}!aMe4ieM+n{i0`hx4* z-{kr$&0q}u_e5YPgHfamw912S-FHip#;j6+1JK$C<-%e4uUOlz{LWw0RS$;O!2JiT zGW@~k-+B4FssJVbw>3bGhH>>*$$(Wi5}$|A4GVAw8noY~X2x{Mx`hvOGMx|8hWO+* zyBt3)gERg+IKL4Gi00=&*arhA7((Zo`5*Te^$-YbE^&Db8Yftj+@1_A3;XlIK+ECR zlBCEvF95WL;4CGo6g`qqiZfzjU;rI59@WDbbOtnsKz#NXKmVEnwl|;^<_F5&y>^>u zx0xp?i*M5GQzeHybdlktUi!9IZiv3^gSRW7U3L;aG*@`K1$KUQ-#{w? z>!yK?F^p%5cZl_LbavH-*r>)x1?Z+f*a6Ru01Y#2>mw%a`}od$mbVYBTcA_P9Mu%^XEf;3fv9^i6$^u!Mp{!aX>fpsT6A-;4WQDC1<_|D9i#%hcEu@ zr-8e!vfG(X+a+j||GS6z-5CLFHG5Lh z^i700JXS@RPu=lrD*%N$@C059nK_l|Nnn1^IaR%f568a#Rp>?O<0ySw0>wx0=)x2t zP1DK_hEamEhb#3nZ`$Yv9f)&MD!&+cOn>oQ&2fVjhr+>BSpmE07Lz38tzq_2fy5D$ zADRLOg91|kp%Q?9vXg7J=gZ}Mj@RQhNaZ#-jEj=b)=0ON+O?Z!SKs954Dw-440(Q8 zyPdmEf?Y)Hs!?bibZiaGM`e4g=;lofJx%;2W)_eK$T5!rK)#jTa*%R-#5V?ccLFRB zaXY#-gXfS>@Bq4NKuxqNUlU1~F&*T$a4nJzn>d{RVb6IW=Eg%8u{)UUKvoxM*>qOx3zuMCiF%%DjzjztM=B$G7W}T z39c)({``f5#Tw9>2^<5~Lp&#JZWTb@&E7_|@u29sWpM(WE7t;rX)T0Hz!N zPQ{vHf*^7HS3|HdbP<;c;D#Fy0Ct1x%K1MdEmCQg8zl|IB~W`?nM0fPH_^5T>I{1Be#D zSr`Pwt|TdEzY~Fb;t(KW#aa?q!)UgI#ksX{ZTy+ETlH1lnbB5Gqmbv>!AX10tjF0= z_ZO?W*~XKLc6p)8%h{H}Re5<&`^o9Ui|eB>&#N;Cw`aq-W8Ej@YPr+|6gQI`n*(j; z2Co{I;LQ0@A@9ej>n3kbEyxg4RhX)Xdc! zsO|$+sz7Z)bA3d>OvpIQ%td;ry0amFF~9@CXF5<1Anbq?PI#!4F)paFl24(d!ei*z zgd35w-^Hei@)Z&gC6c4&4aMY%Cv&M{YV$Ew15Ey~;`9Q1M->P{`z1xpCn+ zqutj(!v0Hp3R_tB9ct}EPpDBj*BF6bgxzu>1}W(j=4il)?{}c8ao=e}&D*$vf|6IV zY1hjij{r!rd}IVYfAJLt*0BLpU=8{sG2sw{oVHR(QV~?fYONyd{ADE6l&`w_0E!%@ z3|wm45p<6@@e(Fypg>w|lj;EzRz`Kl9=!t$i24KlgUZ_96ulRFGGHd}<=)W!jbSUfDm@>$P zwC0uY2(&K@sV64GPC!a{IPr4YpeG1}2JN6%tnorm+%5rh01JL!@#m6N=z`xu|L2lh z9e-c(hm`+coD>Opl3Rkr8J*g8e@NY%P+CC`)s*4?+{wrx^+-Z#B|Rxq2C0xIc_mbw z(V1=k_fCq1WaXCNasoeht2Cq@NGPqSM`z0Lf9|BMr$j`Sgx9c)8R?%e*XO~ZED@(6w zgK9V?6uu~GNQ)1-UQX$KO=AYqAmyAxB!x`7*Qit%3kjkojg?>Qj?m5d;o`zDO>p{R5T&J>+Ovg+}jeiV^iB(sFdAkNpNihIXjg@#dP4Fx0P z==x|$RCzG^hd|^N;i9iWc{t{b1*Ha`n-9Z^4wk7s_t%)S8Ji~YOWSZ)_1XO> z7vTn^mW7BR6Z$e19#h>d1TgZfx?G9G&^|oWU_>|tX+$JkIAplHfCJ=ky~-qc_2zJJ z1d51okAO4I=FCo3wq|z51_t(a%&-S;CT9!tM3qjg19Gv?nYu(`Hv*!jQeH@YIL#yKL-pKNr2d*(Bw2Tpg^9kddsFGiAmql; zyEHuQC`ze{x`P^=8X435B5IlQ5wmp%|<(kGKz1#{>$ zTj`BbP?#%zoH!z*fMg(T$l_}%x+1Ce;(-|J-24R$OI))jLzR^Mk8{PY3?W49#Zr!_ zNtx#*7SuAG$aIzOtljoAslv@2s=j>Ae*4~?EGoEkE_W|#!HMq^@YPZDQhnuY`K9D+ z5=kpnTg({-FUC6#D{q2~BN+yEzfU8B6|%^pJ}ptIoj>QgdOU7UW#_o|s=M3!GU&q0 zo7JYu`Tpwm@%p(umzfaFiEEi^;lp}AH~7OFWsvxY@mLS@P`ntLbLxkAB+jD7bHacn`O- z!kGFfIko#HddWEMY{Tr#UojXF`coi=wc9Us)v%X4c#BE=jcq#zVyc~UG}j}lqO9-1K=CP-Rq+Wp=l zcP672wAr<)w|TItBN&#W`8H=kgLu29U1!q>}sing=`ibR?{+x1M#=CQY-Z@n~A$Zb6A zN5IZ*m7t}neS*I-sleSLjD-8^$_f065b-GjKEa&s;H%Zb$ta|smQGVBi`70B}Ur_XM55SpI#^pb>|KFcUFr9wkip%Mg&s4BD*?9JTCQJOV74Ot!6KgZ(LoE^ba6TyJ1&Ry-quxZYSN4lOoNVkBstMH|$&BtL?Ru zo1O75vtYL)bsIqp7I2)wb9ruX0;V? zT1tl$jySKpGng<-;+J1dbr5`##E2o~=)`B5wVKJXO5*^T-jCvQ!LO5X1bz!gjbK%K zd69^ZwQ;5Vxl}~n2pUW$VQQ?qA&7)@OEnhNRhT(A=82W^ z@(1rpn`Oeh{OLj`Jg-l;i^#Mt&*X(XPp7bL1L zszt?JO};KNuIehHRS#&SXnD@9s4DXG%2Io2&tI2L#-WYur6FP>MRKQfLdrNvXTA{b zxyf7>VTx~q4et^_AgxofS zh%7VmRA#REC6Zqp$THph?xXC3!u8;$YBsxs`ttX~B%RT4h$$uTZH{HbO|b@uaC!;v zMXsJUeYAX{J?7^&X-)X(1!8awW^fHku&}Ww$N<0Kh4yAo7j>7Pmk!@-eji6+!r4Jw zePuIL)MG@lQjs>xvcZnAE@a_0;7c3M)xvS6Uv?B@o>b0rummC#OmeYR3g~}$1^oJy zc=7!Roso2IMXnDRgTR+~QR~N|E&`(9NB$D!Q8wB!)(MCb{1;JmTx^a4`c3FlXdQP| zDcE|5I%Gd#lDF7{UnQXu7`8c67g@}POI9KgoQ7kvVI}y8w`p?0v0)Jq3^jTO|5SbM z2aDi)MUIZKs)&*uazt^9JNigZaR^pq*8%^+Vg7x!B+Yo!t6LiE6elLsQyhluCwbi zAF$ZXo+-z0|MbSU|Gsq}G?&43T0Qm76hv%*IJd~Q2tc(ParqLC?#*^k^k9cJVKDLJ zBVI?=Ql;1kT^HOtY&$sI%D7lM-w(mV4XBic*Ur)QiKi!jwMsO&*b;* z4`;E}K7Sj6BJOfao(c}HVSXb=Nl6EHKQVWaQnGGWod%CzQ6bpttCQEUSP2Y`PSHnHl4A-k2lerfjSR(w$;A3f?pFisRinGTZEc9xKsF=Y> z0Twm#eG+4dht8k+d+(L^KQ?*6=N+UGUhqINS%qrcFEYv=gNjSDpzcA?*vAsvCgf-8 z)o@grO?n72AAdXz-Zv*Cr4DUCe*J(-Y?HGlJ}&bkI20oXS&DKU=iR2aeiF}GX8LC? zrT9#}$0a37(@Da*8ChNML>Jog2;t5pVW=$R2-z%MZwGf-Y`$}J#6PB^$nG4*h@>#& zV@o8Y3W1ZfEq)v06 zT)-Y29jHAx5r91lxh!37P9d!FY-1shF-TqRJEAO>LOtZySl z*2G$6qBxQzFfs@S;FH9`;ZkIywSZVKu^*tk@+k<2q{xkb*Go%I;=I-?J$iufr8#Kj zLKb*7R_>icWOHw)xGDfNHCJVR9lJ~*frN{;mUVQinvQeB<4&a9d+;Nv22h}jsnIL& z6DhuRaX(dh7YMM+*_6%Xg%l7lHq?^3hqfj9se{xfQ!71cO7$*0(?0uj7rf ze;%9Z+#G<@jr=mFTr`ew5`7`V~OlrG!AhsE!ou#V9Q zT1Gs3c+aLLPUbO}alW`p)Eb4w92JeSaHTPfyP{@g;#mEk@ z&W$w{Y|Ay#4Nztw9*cd%WPtB`2j4ercz=GpNmfLe6M4=$oU7|?a8zPXQ%Tz7#q(7T zwsNj7ndphuPc`NWK0SMiSb5yLY$*6t+pKODhz4=pMwIQ+l*ajO;VEtJCuyw^a_-LT3v?c8e6b@Wc#~j1a7V8CGn4fQ>OvpeM}B;Q(WFfI zs4iol>Q3j-Lx|&3NnY*Q81?E8HjWSHgwZlO(=g-nS>Yt82B@V!i`m$+vCBoszWoV& z*|dGeHGFe(gxs61yMVOKK6=CvWXC9b5;iBi)}MVFG!Cwk^;k=%tDY4b1do)?oh4%?i;0;%v_=9fBSpvyf&%c-MPttodGx2uKLY5ats zo0_{Hj@NUtOM-OtbTr+M2Ca&0ud&q5vuM(pJsv1d*QEsY?lj`d<2Mi2O+rYMr+qIr z>+m>RF78GnOw_^Qb?u%MtL_MYooH?vS$T!<)tuS+`o~l?@Rg<2gcaQU6yZssX$>=q zx}%PGrM2+Hu9NH>BXxHl53}N>WYVrrQOSv#7UB?~ZEQaL9{C`hv0Hh($J1iq=sP4} zi4+qRh4?Dcn(*AgRElYDhnc8E=;^1S*#D2RzmAHdiMmH&2*Eu#1PKrb?l!o)JA(uZ z?(UG_1lOR!-Q5X;6Wl!z+=9E@hUb0ncfWOi|J=1$GgCd?yUwnC&Z+6sbhW5kyz{y< zonL5F+($U4pe{IKgM&`5!}*))sYB#0DMk9+7?TUDQ8X={M-f%G%OykPhk>ngri$)! zndym6;Tj53hW%ziuE}1o0+(GSRc5&d$*E)>7l%UoM}i7kp@TgOyl&^J6930&C0JX; zk+AHp3$vYuHk3rc?LU_Jei$xu6$gg~A?F_)Z>v{26(+0eOIJE)S1gV!Yu_iph&Q<{ zTycEQ0tb4}|2Db@0iNN{vD%@4>;2YeNI&9XIcH0to*m9E4LSN_vtl%=V-`u;rT~GX zBp9u^mVnZ&C6mf3Mst84^k=tqQ-8`Xj<-2sFe8$CQ-GgyK+lC$FW3uLF zN4wia%Im#q(c=)P?_HzZe5nZNfyi;GmjuGR@m_Dm4L`(tc|Jv<34FQux<*zO_2Ihe z^v5b@nJv(b2i?pjW0qv(GCb0$>#Z5yagG9H1;w2^&NT8ZCVTuFl?D_h>3;Khs?gnI zF$iY_kR)VJwVKER|Cn}-^^efUiT;5W64GUVTjppa6~p1S7@iliX^Hj$#iUWq+}(EK zWVv8{VVrr<(L7~@40Y;~z5HvN2xJ0UaxH&7)i*wPFkcR0-IKlEEDp&@%QjpZ$u}(B z9ItA7Gi5(KM}<1ZPbeTk*tb5B;PRXOH=345!8$^Cw@AVI#RGAM6r@PCqFNMzUGmFG zqgwtt#R@C!UZdt6k0oK!Sgr&FM%pGdxSch=DiuxOQUhXdv_Q!I{mVPlCFfE~;#|Wt z+x%7vR6Cn5O^#hjZ8i4Ls9qdY=UZQJi#3>ss#+-tyPbA&=E$rj>>cTkz<3PT6r-Bv z?n^oAHfh0)!NC(rq7Z91iXwB zUBU(#G}K`_X4FP+o5_;~Nl0>Ru!B3hFmT7z7x*&1Df<_VrtATY6!HwGfhCS6C+($% zipzqTuu!K)mP##N_=rF#((^6m={AiBk2M^ER8cggk|o%}f^E)>;-V(1Ex1ypH}7{oQ-tF#phb?IAf0!(oK zKdmPJ;C9g9QSTSJN&f)L>k?=U2v`9ct%eE}Z?AK3Mh*hw@f(M5wb9&ttzf-9+punH zoH2qkeo%|p|TvA-8q)*4_>&+N>_vcPviB7{?vQzEDQe#ef|!on#B zfvWF+*8>0zm*L_wkD>x7N)DW9{54a;SOwr=sIix%e0`U6% z!i&#)_mug#JV=lGJ;{i+gBf#lQ=%D3)Xz`!CL{`DYZGC7-$5VIOBs018ipWk3}Fg* zzYK49EJ*;b>x00|2&IO!Tl#IU+ZI2&W`JcPrPJ4?wxi|;W92Uf<&7S zuLEAk2Y4MH;u#Y9i`TjF>rUC7F*hf8aN7ze@_AdAhlq1QAPs555RJigLl4;P^`uI9 zl5JwTfoPW+eZJHFe} z@8&x2jnLOmw{P0?OM;=C8LyFQsL=89^#^BuLtqTticXkq`=&#a++L^w0rkJs+JJz1 zrIs851k`_W@fXE~FoF4i{6GTa2NEDZpab~<9mo%7%y!x{9{6r^-AGs=l1>`SL}JAd zh(#->Ya`+y)YHwtARPbm1})DA0v46Cs>K8fyV3*0)s!COqyxix*>KR0WGgutwEcPSMn9n-mlZ)GiA=sz%eTp^aM_D|;=tgalRhxz!|92z@ ziIxa_zkB0_XE)b#>{**rJ=}l3sq2O`5vfw>tVR`wqoU_BgoG@hoH6Sup3@G{@x3Ru zztAJ8*yHj@(H-J@&y_7h(qVa8wfn_=-qp!to|cD?zOsvN`K*2r(q^W9T$|UhHj`GolW`4N(wFZSuPvgmHG|GxDnVPCU^=MM(bo%U zLx^{3b6WdL#Vjcq~HDW2)Xuj-g(Q&8{jrC@XxI|zswlQv=8e`H- zCUL8-9>aOxM-P3*U*<|K=P20wx3|>`R_%yHmhxw55qDCuU42s*NA1ybObD_^11-6>Y zmomrUsjZe186_=F!^ea!ZiynG!*w>7ddalnh>cbWad7KHg|Z))hCi1|z)s>H4t`rU zmr5jbA)?ZgAyz(&0yX5Dn2_2eg|zm7!)1}S&!Wur24RviVZ~So>=_}ViE8cy6LsXf@B75$C6Og2<$gzYg+LeG<})GW0IaW_K(0lDx`QeSQnEdl!#k z%w{WUVUGAob`);X`@>{O^ZWasVPxC-N(ah|Scy&fz z!>Y8$Hiet14m9xL&7fbJgg0rGfAH?I=L&+e9e>I!<;uzz%}gRgVf03Y7SHC4y!RQyZ>$m zhvDb3PTQ{%q|5Z}gasvjHSj_iIdUl~7l?9gyZ-m(vHH-Q0!|cX;Iq(F0v-!+!oNh) zIG5edYLXKF7gSd!3TLPv;u$nB&HLNiNU~|$qMmYHZM4)?0prD z8NF@|+9hpVW6a`Dy0~>Lvzm`(qE6DRKFehdX!0HT{=yTEf*a2rjv|V+p9plVu<99P zgVAtul7a^FOv76AQ`483#WIl8Wpl1d<9{io71{VWw$(^Zk06;YOuV~Pie$y##j01$ zU%qORpKcd1g|eaCuTdcg{87}dV!BTpwpgx?#wpg-#iT)%kIj5inkYO7hqAvl^fNtl zu~-wXdNn|Gte^&#tJ{LAZmCEsv*qJ(tBXw1gdDjgxF$W%SjB;}V-R#66MyP@AE=QxoS#+*Vqx&AlV zZ?PjBHr0Pp)3zK=RUbkZnars2#io7v**&*QrH+4n@CtU8U8_m+ocT2(%v^lyJpP2v!z zt|L>3VED$4$j&s8ItbsZ(Z{m|<&=RN|NbX>->Qv;V8xRIOH`z!__MV&VSXRp(8-h6 zZDOm-zQBaso1F4{xk(nX#TLbt41aUk!z>!~LxKf*-M3;)HfCIQu4m^ahDFe6IW$l# zzUe6W<<{4m`fxer@a;^_3KY4X1F<|k5y@O9!}o5T9e&r)gRSn`g#tFzf=CUumlo2X zU_5YEK`WbnxR(D#7s>W8F7A5oFv+|P7w@fdjX#2aj5(5fSQe$I1s0QdqK+eXC2ItF zT;%tX-Uz(4WcR)Po4MlLg+WkiMtQFEBum>oh;Sw2RHZFW3SF*Yh#0IDh{rV4xn$#d zrfLF>3H4zD`{bRVSnwp3ez;}orhQ+;49|aHUlQE+LI~#uuh)tzeHOf*DTyHwBiC~) z1WZ>#_*((|B(XseCmXOtZYO=T@1A0Zpha?M{sgf-NiX)up3YSNKcS9d-1j8;W^a4? z6?`|0&1$27@*NZBftH(D+x$1W1o*4>T)2$g5k%+Q)~@7(_?XZblOFxNqr6lAN6wKO z4@d65z5D4B5;GgUUVCxwd!6p(z`eo|;H?kBre;p0uV~lGZiNWi!c3C^8*MZV_KfD?=p!s zF6YTnvxg`Rg2PG6{Mm}7Mqm30KAgfqtK}{2aoWVz7ix4V_@b_eSOHd_{#(R#8g^vD z`9?%R>${chqkhFqYBwy6mr7#_VHx{s#P~3y#_Ym}m3|7PSdBw8pd4%1dmIB48F9R< zLmYo{1FI9rR&8|P=-IeBiemqPViNa^aP9}^0kDEj-5oS#^LkVF&M=t#g|RFgS{7|s z*~xlkWlm>@0-00zRW*&&V^n(>8rIj~m5eH*Xj~;UY)RxQXGD!QuAIl-FHEi$-9mOQ z!+VBft?Zwy%Qfe@f^b?LoU&}mj7|TT$bC!fyT|Zc=p6z%Z20iWqE#FH?E$c(gO39}GN@+-v2H*1C|bJJN`1 zdAuD>6u52~kD)O31Ba4D8(en0UQroV@5(U#{;GrnATTXwIB*iDc6c1`*rnlLZI7tZ zrs{Uh46Luh;J^M83`O(48x=j<K`(oZYW`%yV=(>WH!)(_z>uHsr`HA zvCRXgbbpM|-^LbR@?J*sOd5FWC{E;LvR+<1XY|@gl$kg9Q7y1B-M^MjFjA?%QLVA6 zSm#}Ji~~VYBpmK$nJpx9z1jT;iUqS{86;nGIszBU8$ zn?jl;;4Gj~l3&mam;4j97lH;Gzb9<`OnRxv=D^XcHe0@-S*e}5I_R;UkP``yT%g*+ zSF!%B;YOV|&+uW(e?-N2{T)D|^vJLxc3m3^l4uK^XWzw1mhaJ`1Mtk}{*?2-hMmO& zhFugsf+lp><713+>j5dTiOOeI5NSAdO5Zb2%>k$J;(yxAk4UJ9u*!q}W~pI)77w&q z+7bMC&8lVX{K^rfB=VO>{}@8uMf6XeGOTKGHbh2FBY>iPH6}puj}b+~B6Pf3Z@0Mp zDS3leii33zuKrJ#0aqr`hLIE-N2Xu-|JAO)S*}k;EVz#S;x5CgdqpvSMG<~Q`PKlG zbcecMP`&~vu5#nJ3f)TbU5woz4jbTiYd^(!q9=WO93;$}9ml z)18mie1tbbJd3!J^W!ZZQ48RnP4naB#|rk<+2AdIc@x8R@+SA}B}g4l$~Z&9NHLXv zMCeMx!FHS%0i*a~12E7iB|);(?n_K7z|ge6lJa~dHStO+w-LBB5@-B^GO+|{<4M_N z!2VYRpdhR@l)Am5kl1De)pIrEWCf^310j1Y>aP)B-sxJu1&Y+b&^ER3cAK`;tmAG8 z2P6k5GRV>N@({oK2ENiqxrS1W4qI1%UwP|}DZE@v&}+I@`4v7PQ|Z5$QLcC23v?(v zzRo~9=y8~k>yC*03;2@0^?S{i6#FyctP9RjyD8M5P3jnWn*?hxBdP`Qgj}Rql`Sc4 zdDxxCs5xlV!bFWhAM|Uvm}rE*3~L17$HbWm@N=)8&;@1?BT=Ry7@|?rb@Dd%(`6Vr z0jf-1y?v^#2!vgQkx*MlroZ{2ySSjj*jHnm3vK1Ds}$t$Mkw3nQ*7g+)_eP$UEKO) zF}-4cba58F&T0|+B%jY%lvnm-xS;jLwA?KFT;jb5n8bA(U%a}c7g)E2*M*`r#D%=o zoNB#S0=O&yOdB=8wG{pEKgh76Zl4%unOIa7?SIzz{%9XRhNdFLTFh971#<#$=E>!1 zDh{`BTX*>gN3V8qxc}hIUTOAfxpBxCXH1oLug+e1nbc5^_K&~g5&0;S%wHlSC!Y)- z_PU}o-=@qTqu9-Z8oV&7^%_)u$vQHf%1$^M)VeatR=Wi8N0{J<*IxYSSzo}wfv`?-ivaoy9w~FR;e%3b&y;1)V6td>$$?q zkh{B4(Q&k48&oQynYF#lhk!}W-K|cI3a3p9?yuUNylNNh=Hk{f>}`n7t4=cSg!^ig z_cga&6jcZBKNqY&;yrFVUwi>47?TwDPIeLNxVA9SV)zV#UTp>!x$9DQ0e=43+8^+9 zC}Wtm7G9V>IQK+&S2w^WsK2o8(aiTLQ2)Hg<)QE~|74^=uL3`q3 zdt&Z8wt?483W0!4UGoTbaZ%8H67DW;aNi?OEYanzkdg7A`yx(A4DVPlS8t2bpqR_7YN{l0yv?sI2f-u!LK-|r?lvYXdEv%$fqQRPb?o+Z&kRU zKZ}LB*#^4F5gnKZgu_rc`PFYL->t%I5dT)BR%MCV%(15JfaWYdH}yG zzoVW3LHpS{1_;`&d9up0pWHS9`LY`Yk%8OjDnq+bGx^7aWOUAC2AkO9jh=Q zCoSMDwY}A2(8%j^8+4Cjk*n#8jYguwS$*48Yt?BEJ4WNy-0pk2v3+-CmzLG(^?WmR zkY&*6<^8y{v_YXIs&`@)pm-KiIl0ouQoizWcqF82y_sJm`aw$MdP5p6aaI20+{OZA z0PD`xbE#bDCd_x!PxbYpIDa{%!@2z}oOYjYRj;rW2nQbP=7vYHiD z2Q!wYe~8a~s|B&*K$vb_70hf>xz=_jaU`K#e8BJP`na{WoCW1QJjTX%J5symeZ;l) zR%(_M7c|qx?+6y~bcxu9S7;eMcVxl0leg##g)cPG08L8A*_D%S#yy^ox)H6Ls|tnY5u z4BBq)cl@4IQyMz%w?@z_{k$J89~A}LpJ(c0rR%$Y4`JNBEBIBwz`NADUbd>6zI7(w z3$N5kupqe>=@$-2z6|HUQ zLu|gNr*xJdkv~hBtTVk5htYt>P(QAvKBZ@g>aDTKx-}GGfs{d8Kx0|1Nc@Q@OA8;y z?Gc+4e*oBQ(|qu8qBNzTO4B%1#Dhg%*~%wXq&c;~opR&1C|Bn8$16Q)2uRXhUqSVj zoKa+P3R^@}K{b=(sl3a4#{%gx-GcT};f$Tbev;q|>IM__s#QosXJ73X{b!8rXl@Yy zVu1jO&EFAr3-Gng#1*LdeezjM{a&~2DD^3s&C-g;N|yQ3alIv;H7C4m^28Mvqs>^? zc<OW zRYJFeNluXZIA{H=1<@9)jjC0l=50FUGlw}*Ic}YNd4?5EU1a<6oYv_wj?KB07}Yjd z&2PIA*;Phbc2R=iJX1?|)dO|Q0P1^Ep3Ruf?C-irPc$1mc&to`PX#}Z>_Byo^1@4N zd{^dackXqOTvK^AD~;ky2YG6GL+5CP$Z6#9J>TkVoJ^eka%|F0f9h39tJCY@Ph3uV zuQLYZh-ad7?!4ukTcZrd`!PD5dkkd2eSK?su_{DTL3oq88RGP zxU2M#jhBw*ei*DI_Ra^1R{Yy~$UIuk?ka=60rmN*3W)+pZ(go}l4R2*ZK&WLt8%G_ za_eh3s_}X^S-9c>FPVMpNS~c{!0ct=w?B5$2L_G6t!a)H?_qzfBIPC2b*RQ-vnsWH zGCm*Ac|VdNc>uG6c2kYLLA$m9R}R5K2*Bzzpvx3_IJ&kHR|}KZLfdl@u9*{#Y4tpn!37jrYR>sG2Sv2qbR0TN9X*`g{HE^t z{rd)3kP;}_teNIyBBNhKmi=0N+CCW2enk=}gm{8;KY^~Hs7AgBzjf!84^ZswYHe4`e$Ky2i~?nYAD zuXb1~${zS-~lg5{JG8!Q) zhj5?wtz10c9AW(CF0E7*wWkrBd& zs9YJih290{1=W_=itRdnX{u9?NRLlOrg?0E?9Pc_Y>^>mv@F4XY(SgfA>@r7g(nGb zm69wBA4jgAl_uDNO@0X;OxIufsN|9!n9kX=qxDF*{rZvlJVQ7kK}L5pClYpm%Ss4NVX9vr^bl;`u-7uOWOXOOD}Ghm>X zpltlE1KX=Prp^wO=c5{Pr5wlU(kLixO-ydX?n+|OZ%xB*^* zSHM_BQKZUaSlv;W#842qZ83vV` zk7BNDgcpWW(*rHu|SEOM*QrM&)RH__QRmjEW0tC9~PPZrE7RDP|i*8EndtRKT! z?^>ZA!+B*1{Noai1t0~R_Htbhhlqufzuakf?hIr+CQ~ z-@I{e0y3v)P|!|Ao#6Av`u1r4A>C&)hu!zI`&4f~kcuTAsqLmdPFWo)W)9@pF{U-O z;FnT;_f+7>W{;IAPFQ(>I9HT}-p)04K3vl^rYaGZxmI7|(DY_Vl;Qr8v|xePn|Pnl zy1gW2!@qM|{3~cl;6OfchvJ6yT+vbbw?OlV@f9Two1(4N6-KSX{`x47H0_u4<=M92 z6dM(Ew+d;MOp6}9=MGFR$|nS;@Aje(A9nC;<~{C?nqf~xX*pyGNIpDe)(v@lgeD)M zqj>*m8>db$LtTk>8~ZGe#A)o#Q$X5H>4*G~Z+Wvx#+xfTP(b`BUFM-SE|)YPXY%}0 zV~b!r)chOQt*`u;--C8WKe`$CUY;~_C3hA6`@_hlqpZvYJ3qm7!bxhvTi+bmSE zL`+CfAa;C)uZK)yD%1<+!G5Xb&P+1v3?Dk@hx4SKP8+P|iqFQhs2r$yBn=}@4R|kK z09wT%t#s*mMw5d!t5jBTXL<3GZwhc7L^qum)VP!bogAOIOKF|KU*l}msxz@N>yb@^f>;z*_EekQ78D=f-ckpJle$EAIZNjU z$%wFYn08n{qSoWmZxfihwjW{UaNBG>TPv|8LU=mxtJk<({r!O_WYMLH$P`|Rn7DZ2 zRpylQ6Oj!_<=Z6s#k}8OZ5jRjd5l3Yk~uYnpa-Yq{M$HYZQw<@faZLMXCL#m<_|7Q zPMz9*P*A;QNtJ6&P`xxCx7U2P&Pvu7bg)*bZk6Qsnv>;)zf<=icw@^RFe<#%!stas zX&66sRnv~9x5Hz@b?hq0hU>N8Pd&u6Zm(Hd5~X8}Pd7Vt-)_|nGO!SBaz@L? ztNn%oM1ly+GV3s|QG0#ea{`|eeqB*TPo9fUAkbUB{73YnRFx&3ZK&X8i5`(F#`v~{ z_eq{gZI2+-m)*QAdnbpdX9NQTTZtug4T<7E#%Fn>J=z9N_ATF#?voyM+FBJ%>HC-_ z8z3fh#=xBBW@B1*tk`BnXPk(91*|QdIo#T4AmHn8oiE#_gv%TDMr(4~27!+;94EW;ANHNQc08g8{7)B!FdTMyys|U)Fj(cQG)+(gq4Y3uH8O`6|T5i67mWo~@oFaZ$u+do%K9|<8 zw4O4B@@A}Ir^==KgJhmIU9sp6nTHX7l{-z~RQJbACD zA>_ng5g=|u5UvAbjK3H>o!542-uF{Xf_+Z#x#Ul0M^|EPdo4H}*~`2u;h>v;mKhro z?D2TI4NWXz@P3enCgtnGwJHW%cE*%_i6q8*R4@2sMJ#MCg`DrPaC~nSf<7bsFtR;SCrOd>0bf7y;szChYes@c&xGlhoXw5>yR6T%Bk?#XK;g;17Vfe4*@aauDC2SvM-6Yw1jkVQ zWVyKnLsM7e+!@o3ji=s-Er~xQim)?f91;EP1^YTOY)Us;Hz$ zLkrM3UXONm{p5fxk{BLoMzjtxhK;R47X1^ zKB5{QTJABmxko%cij{t^T=0eXS2)4t*bF7J_=k4Xt(8Q{cwrM^xhc1xOsw{s6cW6_ zt3|-T_-rW5K!iDwe$1+;!*+20!1Dj)G&&C9Ii}M%1Iu7wlN_q zvWb~~!F>Fz4xDr=C}_nrc;`H^M>lB+_3HVste|}4bQe@OZ(w!u4)$|-`1;u|ody&? z?I}1KdQ^+6w2Bu!6J2{hXw3c1A)mBxaV+D=mr-x$J89v{I0xKrzlED~?mOQdykVn1 zg`D=Bj1O-jdYrmRX0#W25(#oxovP!BWExHA$hB>@YU*hdB1V=E+x^c5Zu_1zV%$9p zcQ%Ki+;@7%cd)Y!nZN0yk6@yhWqX_n^q2kNa}gXs37IYrG;^^(u)gNp1DX9`Qz3!UMh21xc-bkyN?$SC^@Q!3u%Q zkyR@0!js>2a7pPABO|NF+v5<|2CnvKAuB#NF7EY*io}z$sIv4UTxz`?6uu>X1!Mmc zYc8JLxbE`-?L-$}S1zs{j074^uEG=B&woEyx;a^r2)}RFbZ-D>`tS7ern82T+-lo7 ze05_K1dbj*I6cqN8!c`f;R*Yu_4pf$d(r$OUunkZ!m;zD%V<~a%04?B!kB9%8!ZhV zdOH5xA2YXTC$tYgjG~>8hAoItmDAF(v`Z_v!fi&~MF}>5E{HN%xd=|n+(5s0@y1+B zu`WE__3IXRT-%E4N-q@eM!}B7JEg2274fea9mIo}kLwl4gm{xBMYAU-&wFa4;o!3sua>@E2 zD}OIX!fvD2ArbnW8{9vd6|m%oNy5m?+>qJbiQ z+Jv-bg@hnKhoR$%?5wYEP`5X0385xIWzk)gr0|Jj65IFYy7sunne~_VoMDU0C()5y zN={pNxGsk?D8^bfKCnFT&l(p=vI)Z`3&Qz&ant>}RDPeLCI4pMdf&WjV0ECh4pRWonwCqLQLVL&TuEWi3kiUh**XZ!*L1x0Sin?<`9&xR6GSE#xVSDuI^e!WjdURJiqk7lfm?|X^ zH(UjiFAI0TAd+uGc^60JIZ3Hjz4sPE?)j^I8d3e)^4-1+fpwSkS>jS=?psNND({oT z)`8E)FyTrOD4ZH9fgpQx#UQ1XqY?&dIh#wSYIEo+hdx5SKUbVMUdxCGw}Ii33rz-s zXvqu+iHeFM$#1Yqv$Q=(;uMP*__LHG`#LGr+M=k`0AeIa9N8+WvTJ;O`ySE`1MJy3 zkA&GdN?5cU>KfY{S~=(&Ta2Ofw*oQTr)zDjI|ndp{H_1 z^Su;mo)6(l@I{{|19hHbK9WCH#u0)^tK=4Yk#HU>vGz|S>DI?X6E%ux102DWN*gYt zTG_aW3D!cGma#&EGQgox>%|x)tp+VY858BSwcgrwQ1jfw7@42FvJ&|9#fsdq4=m9btv0w;>f3iq$~X`-5|cm;B#>O z{bS9Gel=D#Dn47JGKQC$MXmdD1Kp;`BI1|wP&h7Xf^61=^LQ3}w}Bwmr;phiF6@A2 zL0w8kh>58>cd1Isof1X=QNRD6#_!4p?@Fm8Z_?W}xgzh!Wm^P}H2N%OuOQm=F!NK5 zqN2V)!sqhF-apt3FS<#po~*Ho|6{188R@@tA!RX5})OuqY=?daY2=GWRqx!A*xZ|!()oTB~u%1P|zp|1SN-ZOrodgHr5$mPy&0eCa z&JT#H7Um<;m`#$=s-T4Da+za4zy-4%Tl{KNK2B#-`erGiGl=kG2ZrxU6-_HY{;sm{ zR|0zqWJi7XlP+>61_-EqV8*r-$uCIipi-Nz#H4)OP|uw|dMlWU*(Z2AG8E}dFG zOk3A@Puhs!jFS1&1%_M76`iiZW>5ar3LXo;sJrJT+=4n+MV!mzKPC5^e?-GU_)=fydIYpKvs(z0nf@g{KS zl4?*UQ7NQE%3FlL0pU^$gSLbsTSfAc4N?FtV)OsSuL6gz!%YUSW1mL?hvvqPf|Y6q z&!ig>)w#bxRRE|g*?oR^filqsnEO)daa3ym9#X`LoL%L})jkziVwP}QNW7!HGoV&m zDU~jw!x4}#Ik5m^3w*pK%f<~-d`Sk%H$6Zyz{3@Qj$6*PXi&PSQ!Dc*!Ev&-ITmv-nbThu~{!B%nB}q81>&eje8V}I#ds3 z1?=X=jLBqp7W-f`Z%FF>YNV&kl;*?q^bJUGdA#Z^?0mY4P>6kWxy|x>UQf4_oR(n1EsgM0W>bZ)hu$0z4OyCTMzaeY_1ky@6A8{(g+ zW4C0LM(?kjZH761*f7a^$eTqrh`9A?>{2v{Wa+OJvn>~-@XqhcHI^i09xAwX1WEsS zg7qAhb9HiHyHEyaMH|jBkRjUC65ZY9)8N+y;(C~~{waKxQzvXp z+!shJ6H&36!@hTTaHzg!guN}uy5p%mW-sDR7Fp(*ZX5(fL#uauIk#~z8*UNNs-#?GP z(^+<)%yz(<%;e%gI@)K<^UmtmHm^JsU0i)WO&wS1So^aYcx;;0<%m9j2@Y4N{D)20 zfW3t#lWnM|Y^#o7GnSczj7L4dzT?H4GhP?8t7S_oqv@Xz6X?3Celhe&`Z6qTMpEX> z>D4>(ks_@vyc7m?4!D5nYz=r$ZB%s(q2q3!++p9n=jy%;sE&3kr%^R5TUa9 zqK*SS7dWq#M@CA7_g{nimJu3?jz|PzePG|X=U5tHkSj<1DA(uopeq^M_I8%P9N8S< zKU>Ma3IKoY9jfM`Kb_#g*)IR8x|6{;B3@o_?Haw|6A3J@^&xy=>I?2Q*rPb~iC#}{`B*&kAei4#Qr z-f7FdxhOq9T3FVpM-oxRcB6+htHGBBQr0kPjQ_KAs|k@sk~Z4q zQgi2NAjb+@oBlC9D0pDw6|!dF1rnsAyOcb>nyFo;o=?Uuj@{2%C*@M|LcS2UIjdwG zAG|4ycVPaV;Xikn@=wEn&pT7s3~CU>;ATg9o8&txB1&fe;tCiDn`lVcE1!uO8W(+C zzU;~$nB!3dx5B#*T8Qd`CO4>< zz=meQ4Nq2oVOeuII4Egzuc&qSY(2q{PLeo52D`jTDPTySl^(N|S*tFba0%lAUZd88 z>?OJm%$wCe)HPDWlsGzBNT{NWCl3nI?x_O7#X~UgsMZPko7x%JXY$g?j=Lkq;*7~p zFgkh`;G?WDOaJcntrJk*hnxJAWPQ~s2Ia-?*Xbo+{eI9td|3Bgs*!((9GuEv#*2Rf z<5Eal*R;))%|ZZ0ncd#Dr@1Qett zQ$G+4{D-;ANTPUv19M@@8WTSK68H*mj)LkhRz_13k0H>Jyj#pP77#Yqj1OR>gdx0f z$v#qqLyL?H$j_=Bk3mV-U!wuEf60SVaIg6a@RNvs*B6O?pychdytrt5z_Ow`AW@g7 zh%svwkVp(N{y)H}ZEwa&{*OQhFWK)^pddgSK1#qhy;i3`y;6<~P}|ws2g1_i&;0+} zg92w?C^v`EL#UO~_`zG#?O;(or^jEkz(dN$b(y4?>Y;1Z#tRQv4S8vm~0T%|^(O1$IF{jrfY@T$+` z&(c3ee0J1BtVhYX!A1$+d%fFdy4=Zw1KlLAqJ6rGCs_lOw@}gsc&o$tH)F*=hfbCF zrS8r<{bU;@JJO+jESl3Pdl$y+I$Q0rIj&ER+;%#PH`DqhEV?Ggv~|;aUFmf@!DGAh zVK_iyI{Uy`wT{DjYu_VrpQ4w7o{x!heoq~=b`VSiP?Z_Q@>(Gc zn>4Fu7jrQ_JkNz(udO}q^h%e;M{#OzFV^%Vp-Z5#aq+8P_SX9;#da9c$?KCgUv)<1 zdy@P5csQX6M7LMej~ERQnd|Hz z!jo4DoF?UDqiqzi>R8acS6sp+0riu-{nWlI^V+2~syb?`Wwj&9^ZssVxxv-_sp2i< zZ1J0MEG*A~TqjrQbMw+B zJ#SBX;T&BJ_*i;kENJiiS|;b*6f+)ZO@a9jl08q+JD;sUgN=O3Z?m@qV}ruViGlR@ zo2w6QkN?U3+FLoLoxLec#A)iCu0>fVL4%Ka(BKJ_HKklId}aHsY~sAUOd`B$2Fm$C z+QNzH&1L1<(c0nNlMOccdjrN@>F&MN54im8z9ZKPX{49~;=?30$2Z7{JIH6Gz84$E zcN)Gf%5L8%8>A&(dT>szov<-bUty6Q5Eb+b&*S}qn7q2gOgd{P5H6_YU@>u3lOy-{ z&iiKlxKwio(xIFOr0-00%(zVbH9FqBJX7?D!zljl(q&8D71JWxR#V!Jxy+-nOF#XB zjb;_m7QbXGsSu@ueA~m}1COu`S(nzQUmi4DrqV`ksy?FDPcu#vdq(t3Myo}ewJt~7 zOj!&DQKXE%z7jraoB{t{+$LI4!JCVJMu6Y_O*Emvn|DHEOy%MJc@GzD7!|_;9gUjH zJt3OEdqU;}c_UTgo=kuFX4J&q1LoZ?2%mtjsuULBA0)=g!^cK5Q%t_Ni~vij-J>`9 zwR~!pK3f#)Y_>pTOdVeT*HBrqi=X5_67M=}Ot3rYMI@G7+Slo+t(QeaweoP@@8|dY zckKD@K=A3xhf&T+WxHTTC)JF%(yU^}kFL}AHfz4E=}K3-;*cnaQC4t=hm_@P@3Or` zJWBT}#wB9y4hW1T{$g4AMmGcf=_C3u+qliGm5%$Gw|Fbt^gLWzcP0Bt3&`_Qjct{C zK<~~=M{Oq6W2gobM+NHQF9*#Xtt4wYw|2PeHAb?gKYi5H+Fo)uQeJEDLL;}PcRXC@ zyr}X_3^=!u6W$cO3gpIfzCUtHMssuKl5wyN$Cjka1C#B!w6`9|kLlkPStjx*kQ~qA z!c5}bm+~ld^7eaJXb(Fu5+m@y@}!*;*B4hS$JO2pOikmD(Qaow0D-7#d?@_RIKk;X zH%H$e3h*+MK>HKj;n$vyVktT8QTf;{%CI12v-ZdTI*|Epp|Gtj1-#zco-mGjGaN;< z&%tIH*6whi5QW5V2O@N zVIza0+(toYQ2M-TPSXKgF!kKVe0Poz<`LKf>@(_ODFnRiGhnB1>7X9}CCp2al=@9U z`QJV~cp}hYz)R!H!OhjtrJw%?)X4`UCdG*c?d8Q5Iq`Rh1f9OD;MUIj@$#$tpsaMa zz+*&y3{T1nvE63>H|G)uIHC^(kNT}6Z{%NW`mc)z26U<4w_smn*zHK)Q?%2Nl>fiJ z{ZQY$b9w?Eh8f_IyCx^f{`^0EpG%^VvFz9(3mK7srH_a{G25AJh3s?IK^tDm^^|g6114i+XD5^s{;_!34t&k{`X`oFW;Cc zpu|y@r5X$Wfd;gyQ^EcIr(=T|x_tqPf z2EDB}*OPo@(BXHl;Kqrwy+qIhNf7xlJsE#?wZ(=I?X5%o-)8(@?7ekZl;77bj#7$* z(v3(+gLJpj-6`GO9nvBoAl=>FjnbXcAyPxffCvbjX9hpvdB5-Poa?=Qf1ZD4&&+=I zUiZ4!z1H5(49q6qs)_>uTW9^>_C%HCx_EF38pxtG1OZ$V+vJA8{tMWD>Cyh(4IP!d zR!nRI1@~o17A-_Ic@e;}lLQbp$x;xqD7=;gxJw4O%jXE#@PPPx2Dk)VVyg+ISNz_` zf8$S4^>-&jI1HuLk$G~$R&NMiadNv*#BV+u@*q`f9!!E zw5afCEQ$`%x_a!$!$+uTZUd1-QyN4p&{1PRpi)5pBIhr`wC=9uLwtJ43pT6nhGKx| z4GL5D+)jxMt>FwKQA~^iDwe5T_ZqB0yPRUCy>DZQau}5fmUkr zbh^$pbs|PH#UIir{F%D}zUi_#;ARR5F{FJJ5(1RBW4pla)~z)sTX8brx#g@s z7cU_IhL@1^z8?S+PK^&d*J?optjZIG8#w@` zWNql`!jey1Ty*0kibNww0cuk6A~0|#2>?9F0$2v<0o!qFErXIEdH{x;K_-Th^p`6I zjs&lwBL8JD>bE~?d`mJ=xd18Bz|Dj|#`?7R<(VKTdK@Eb`yq|MHpe}+#4_>!Tb`5< zALidHqY8C4>njl{q}<(?2td4(L53Z-7if1^=izd;{IjOtkD9&r->muz++NSF`rK|$ z$=&^2eCKsFaJNF}`|||c@oRNiuH*LSRLAu0@=>#HL6z^XjRZ#in`$6;hO1D4fd3I# z6*SkW{x13(xUC5ziGx2h4K5Cm8fzE;Dvee%LmKjPKJd?wKh(0!dTJ*nu$E*yPqypaXZuuFRvb`?{_w^5 zU&@CT8~_D0yVdx#|C|vhIQL5u`IZXW%cEtJ;2a1+f3H)2(FS6!LP-yW+ols~y0#<_AKbA8f{?Jih07D|Qzt<7y8V4-O#UVV<5c@-l z#Xr@c4&V+bBq30kOptN+lC6rn=LYaRFV{PuZWahGZ!(?tD3H^CDJ$LGiUQ!RVOrhx zbE*anO>;O`jdFagDP#&m6!&^`@CZq8Q(JV12%r7P!GsaSs%2>n5HEpG3p;DTPb!;X zK^A!`J9@~Re=V+kG>cYwroiugSSn97i}V=30uB^|?i(PM>8^(Xz>q$pCXvVAE&^>H zFF*Ttc79zc+_eo!t_3z*z={ZcxM%mtIyQ6_Lw&8-^Y2=(YGF*v2hd}wj8i9aDf>^x zrV>Z8iOxerTCOlLidskU$1vr5LN@5`i+JNL~RCg#OdU z6rhy8>Og=mz=enXP|hO;51grB3;x>lOg7*H;e=FvL;B`ymBd8?cg|@%4CrbE%`yN_ z&*+>aB-`R0lIA`FGUK11aQ$f&@-tef{X3!>LO*2;U{`!XTC&zOUN zUdUz!fS|RL#3BX!$rT9ytGW6$bu0ofVF{1$MIiAbK6H;4XWD{!AzHh*tZrMsjY3qM zh5!IA2ZoDG&@kE7LJk5W+GBnCw-ct2lgnP0bhau$p8U}j)AdIE{rw~F2i3Z3E1`q*@`R}+uq5!3F z1Bh7`K&|lK0f)pNKsp?YVUY!Fv46*nf4hp&d-NW0-k7^Hkxh}|_&exyPQc-0;={kY zfE$f+&4MgT^Vht;^>7ai6Iv7ip#N2gfE&E? z>DU?nD2adjUa429Q(eHpL{1UAtfe=fG93Sllr~x3{zoZ6e4~Qy=YbgBJMmk=P*J>x zZs-Bve<%r}!{BV_Z4}_kA0h#2!0!nm#}M9=3VjbqFsKe7?rj8W4g={Y@-=V~5)gBn zC~tEcsB*3Hn%a`{fHR~t?^Sb;2%<|MU9=*g>YD{lby|@7$qyayOXSu4K#DExfAsMf z*a!pCf}C0h-1}`qh}NSmYHKDb2M!H{m|RA0CUcSl`Hz!jy%ZjUS01&4hzG*kzZ3L- z4+wA31|rh5`S_DSQr7E*pSg{ zoPXS>PD2Kcz)S)vU>)@EM+gUyV<|Dq-YpP7&es%y-km}U6=aROCueI76{;T0vD9(; ztUu~d4~qaRa2VwejKpf;<{pr(k(l@xA!ILZ zs|jo?db^0^fg|&NZ?U1h&}}vJUL4vf1gYiVM-q_DbT^>}4QUY{uv}}#drH`}TQpu*WC11(zB1i#?lDFl6IwW()$k0cK^kH=2`bWg1 zyv5=%+H3O%j#Lwf;%Vx9G?~YK_57WLNH3aTE3O$c9jJOXuUF*V?r!}rj&S60C9f#W zbFg$nePNum1of#FHxa=)VXG8JXpM}zB1Jw4m=`@MB4M#D!RVwYdE8AnIE}zdrIO$; zmu((7S6Ph;%Y;bm6{T$nV9E3MU=jPCCN9j;`bI}>v_kGh23H4;D>(c5&ARoFU5alZ z-_h;BI%`(pT21HW(=L_7@3opnvh3=6*yiyi&rRj+W$HOFS3Y@vlbMHCmbLF``?@9n zz2e;kqBglV1l)m%)(V9;Om3F4>Ed@2Q|MGB@ob-Vt+cf3tWbk$=nwg4PGQia$c0zWtCd6AwD8wa23kbw=l&|u|w2yo0vbN+o7f-jw zMb3%Gx*X1p$;!qTPie-^Nrp3yo-YE^9?kF`+l)L!5;1Rx=^SD}Yu&H*8_dE~lk?DA zJBURTY=FlMHmD%~bsOdTb94JnB5nqC=sY0)xIS&3Wu?C6z+f+B<;2=_5qaToSl53k z(#q4|GjY<*{Bq>*?U^+;d9(f{-A-@caXeHD+bL{^Hs2bd4P71EJ14=py-pPa?(*FT zpm|T-_N-A-TI{kF(iHTUKFh_>*F`KxpE4)4g#(&-END~p7}`+!KpRz8OE~kIdWfM~ z=Q#pM6a5w1giJ!4oH4x5udIK8xtV}}V_B?ieU>Q6n=d1>@<^J3cnX2Y7A_w>%G~z@ z1e7`Bd$xDA0o@Q#3(0E`Pzwn6jl(x6#EY_Lxxn`wKnGGM6s>*@WFYn2`I~PvuYw9! z9%)nLcTVC9NfNiA0#C)qAQ&(++{x_X5+`XPh?NwLBA##ZKpayVU5Cs{$a%9SOaKW)vG>ddBhvH)Wf zLh_Ft&N_~VN@3pI%>X84gA7?zEiyZn_>~d$E2ob$IRFYGO(=atPw$&v2($@E_q&Pg zZzgo!-1rcb2He5h&<6g#(KUfU^58JsnM$IIdIwN4Hvna(vLD)%_W_M4&>eM{3NoR) znSl6tCZ-k!U?b6?XvUMuu$a|Sbh(G3{Ba2aC9V(3AC@Jwi9>}n02GK7r972AJ_vBW zzR4CmsiSnmo#hXCu47dYXCZHx(6s>u4!Iz%d0Y@e-|&pg1339>$o&4PzV;q!<(!Uf?FKu&;XB=ilwKITR|=o=|j$Tq#qjlVB< zqzeGv06_g~$nPtF%hT^C9Q$L)|F?zTL+&yB0q8%y_;cnz!2GAn|1W3#|KTzqsBZuS z%O8xLSmOWRi~ku110(8`9EM4NCLLJf|KE%M83*$t>Lvh*fD(aH^#5M`&p1eNwMEtN zx!YUyz1nGLA@R9hi@HPm`(!7h2qB~|Oiy1|pl`v)b1ouJMlwj8T_<}uIzF(KJaKa&%%>;` zyiHrOLCthSs$UIv5~;MPA*gcKX86*G z);efhvh(9fDvK$@=&v=p#tY#%lWGR}jgbBvwrGly3wYprf1c#$as=85i9^ZQAYnES zb+2Dc0us*Ch>{VA$aM_kpA${6;gSgpI~NjA%GPpYB=umUEJ#3a6tuZNeiI@LUKi9; z&56{{KV18$((`Cpd=g1BB~nx&5(PAiI0K?hd44hexHQt5<%J@vV3lENQaIV`^yf8w z-t<^2_J!Akd5LbO@EN%618foCjsbF91;wGkpPhtG$*b`KDESX4VW$?ajwOqM3T6la>VL!%w_-3u#7 zqj_}Q?HZAO%SJAJ+JHf;OG75(Q-Rh4*p^bNgo1~ki+@C#)(hb7J;Da-b;cp9cGveP z)zXYJCwqr|8HaC5B>9l;l+ky4@xiKna|hR`FWh++)*CJgmsMWm ztss|^6sjSiamIupK4b&BpEUccxmvCqndLF6jhiO)mvXAfuuEOja_e*%qV~b%1!JdY zNiIQezEPC1D5?jHV~C#Bw&QA7>VKQ7>Z2oMfG498Ws%D-MR`84OZWiT?ZryhK;-+RlhPi@C{?-#FEKwR%Klhw>w8mwof;w?HKcDQvw>J zOQxnrAT0{;5(%|XxB_N*;`YvVkBOOi|9^w45%3l53SQkt&ruWb(B zyB)N#DZP#X{FL&-blcZscD8KluG$QFrx)T|dEH>fQ)8pxirvz4{5Vg`2uTve(wv#}S>f^ASA30cZ+Kh9)KMfl)77!LCF`jkf6Kj*496$2}E^vKlBw!cjo zF@L6&BaVHe6BAsfhk)o(7C-%KX7Fa2jNVCa-gT5Ub)){Y@?E4ETLy<#{?>T6ilgF- zCeALO>xqn-Vvs;=&`*nY_?_frTZs`N#jI{E-~fU2;@3)Ghi$=;z2~vXdl0Rg3sQVa z9`k0)NSOX*hs`$Drp&flG}|Rfpy=4+MVolCEZ!ElbmB=%+a$Jt&xc4c;nBXlpO`L! zp*AKFUYc%;v&3bp;<2Lc&A00BBs1okyZyXq{5#Ps*hB7X_Ktg#W9GK=M~SiXAVlvq z)=Uh^u?FBuh8=g^u(msP`NO>3riJvzqFPcuwc&<$c<0*m+($p#;*yrgtRvC`V$Aqf zt$#?5WrdY&=e|}QbA945su7pYq55|0;h8kPzffWHjmM zy(aXQ69p7F3D$W#<|^fp?m{(|x!sgdyloMFkUtrGru}La$zlUY%M2w|K5==sQR2Vyt=jdo)j`hqfn{bpz zFWU|oiQeI2wLed-?ccrB7aHR#nFROl?p;31we;{I=R=eT!X{}-p9K;{W^5=8maif} z+M}G27xbjyL7KdW4`}aFUt+9asD_H$Nr_Fz+Ijh@z4%wGi?WS3I%<2dJocW(v=>2* zZx)4AYU@cj)T9>y5)X2vR2QS3EC3|d10*h12sY;*sO262A={)aKY++%>IWc?Me|P* z%Oi1!j+?C6_>${U-Vp)}7Qd31>l3ki0+SaAnv!Vj#n++6BGhQ(cr4a)-yc0WDZ=-4 zy;>rFds;W*JaMtmS;+HriAXQATZ{31^iH$hnaT}5oMo{OO0jMbriYgfTiUWbn;_|; zH5p%Dk@dhb4(oynm}EF^DpZ(>Z%nbgzEjmy+jVm_Vj=E_?ihn%`2gPiPR-(a`sh z*hrFvs^-Brr}9sQh7092c`-zFI@?k~FdhN-Zt2MxHZMxE=_mWXULdxrfR$2P3>b0# zjBDn}+)al++S+BSnu1r$w)x5IBONcS(b(sqE@8Jo$pc(6 z=b@A-Nll)qU0ycKu-Lu#hZXA2Wd6NBBlrH~%DhZ(nQlBJ$c{8`kxi3ynf@_PXWR&f z->dDRo^@!_z=yJ{&+>KO{1&UovvL-dPRAL|WdYtW^KbyY#!Pzom8<6FbZ!3Oq3X3V zi~7MzbaToQb%eW;t5vKE;a=WUsEN4ukyV2!DbD!~@6J@%Hq*;AL5khP_C3sEBgQKm zY!=~%ZS*w^5y=SS`wiQcDMcmV4*qX z>RRJnoK)&^B)%$xS~rZp8vjaT`dQD%-IaOEF=mEh&r#E~H9Jf>ob zVJy(Uc&)9}1$3gvM4Q+rQPk2|#_3EAp~S&7s|*RSalI&E!kcBbU!sv7br$tiMxv3b zw(}vaQ?HJ^J>Rf0*HAB}70X?sbq{U3o5E~j)ozGhdAEv_)Y_OP_*mzVLVDhg1^mkj!$_)mMXX zA1~9LJ7unB9>@sqJtcyhv5)x9yw@qpkf5{6XY5!M*6_?jC!3h<9b#B%SFW?U4G86n zHdh2F3SpX2Q;fIVsm zh3!`I)=08~7J}e)x-*RBDtD%Y8BsRuD)*KYW`joGhoZL(EtQd?rnIz_el}kX#A3;+ zQPa-66(}P!>}RcI$*ywre}>OQ8|&0Yf^!2*eb~L(jUQu2P8P#va}!CYaU6G*3h@K! zP@)`aY0$?2b#k`WZl-d9*>C%z6juHEZy%#k1qYQ+mPU2e078|T6N$&dh>8+Sh-4!B zxuq8pxAJ>XW7*@8Dj&rZerNc0Ay&H1yR)uAm_D;(n2lOiYLdnuzmLnq$}0XSGfE!k zJO17rBE&%xpKtZ`$bvU~doVNY&VsSy+@gs7&bhFS%yqmCWQ{5==0x9d8Gc7E6reN7 z+$PyMkrfs$SdAPZkp`msLyk;PkmB0itAyq7*YCreu_HoEq-h$P>d9 z&%jh?jiTGjc29jNzz6)E7S!0w8|m-9v6qsRaa2Yh z&;`o}23&FnT;c^>a^IKNHX%OfwvE%FY3Dp2f*UVOc4y^!0cHxbN=`8$o})A@)ly+- z(-nxIisQGaG-KAdeI3gs7ehdEDqn@~&7D|iNSPD66hkD_t1f*MXt(pN2pc?qcRNqW z)j!MbIATAG-7D$$&4kYnT`R=E=m_oItIGF$?|VxhIxeZm7VQNR=>rRn{G`iKKe}{e zN^h&iJ4bnfT@DI+OY4+N^}&bB{JeK(Q`d6IoOz#6*nV!@9@evF3!5i+&Q}s zQ%tE#uq`rUsV-{If3cW84j(%_I=cOJdgv2-^y{ac$I0=dSz>SxFP$!RUFc10!d*$@ z@`CvrX+EUSOv_K#6AA=YeQn<0lq8sqA@xSVReC`%+@`_Y<`^NCA;@w0giY!L0ykmgV?Y;+7?La+ZEc11Kc+Yh8 z-XW(cwueK;iKS0ILvSkio3sPpq$-Kbx^yTvwgc;^XtiPgL?sQW-#oD{B8$YjsqEc` zWlGZ*X^SU}8*l}_et85A@1_Lay?Vrjh#3(?7?`BYmFI%)^Q3=eOEoB|)>DkMuTy$3 z@Ys4aNW<@Y78>|#O^D9QbJ>@^_3CAjA-N@aAC(CjNhR!Eg=5U|f^rw^jKz`W#6)7S zYdn4i={F}?!s5krs}Lx(R(*9f0zB6fiNOouB$xRb)^IB%;4Gf);v;Tg^paer@dfT% zL%&CokKYJS`iGEjPdM~*@hXZZAIn+y(~!$V9kS}ZeL-He{XuwASOSGPRUazW0TsO=O@s8P-lKxE-xN}G`%LIGVDG4<@@--I< zW9&ZeCTpVNqf9Ah%c zc+C~~QH3kd{;5UmvT{QvPKgf@AO0G`hl%G^A<-Ihim$t>2h(*D*d1wCj9wSGv`ZNp z_2rGwYA3JZ*_(?UPNs?t*?{J>7xtTKbKG3q&c^eI<^zPJz`A7iW(Cirmg`=mH;r|= z8&Af7C5$h|{H=p*%+$nkE<(AtyjVTtssq6Dy8+z7Fgo0MPt`a{93Qa&h;1th+kVkH z@P8(i*4tsI3J^(r_e$O1ZI;>a<#XYRL28{RSzy0?`l<@a+s0)cb%Uu#vEWx~#BWSK zb7qw7dDZt`%JZyVGF7j8)zhX%0Z94PmM%G?;?u@d9Qn1zF15|K$q+=wD%Is)B?X*M zhvrFcuM>sS(`NLrR9(Vin!?P8aBO(7a>f)Ij*114QSfk+pp@b~q&jkb8wyOwg^@DM zWXwWC#eDZZRnCqQTfKSoB_{?gF6_2rME0xg0GNK70%e(p0uSdM`LTY^9TIVoz;uC&zZ4|v~B42CUuO>m47tHc-wI~b!^m;e|F(A^z%3i zT`F2EmjgfSW_~XCM3x$7yT(n_-II8q+DW7j!O5I78h$M=Or`5!byJP^&w@FSu}jC>+2yJyK$?0NdEiPtMfjw?^S2FRQwdP&#gSBgp@pymk}& z8GfO`+tI;?=7ir&dX$p|tPWs)d~W*riEEG{hp?Z7VZjsUpo>@A7qPO09EcTVrQeyK!?6pqAPK!b{<^uNGHUxQX6N=H; z^|Ydy45jjmX4Y3QqQQ zNva};xoZlfhT~e!1?CnB4~iP=2q7SpfYS-U+|;5rDNX zwN-B3cgAVcyIT)b|K*w~iR_5wIGSz8yWH@|u?^%s>KJM;G{$6gPKuNr=}zJuDqNj& zF%d!)2-D28?F|821Zugua#u`I=I|LBRnQ~A`6_wc+zU&Q&tD!_Gl=!n5G7T90Ve?- zw!ta!VNe|Rpq!F?oab`jl6;%@M#!)`68_CrNGcdJoJVk{ow%7_hh4q5zG<&HduFP4 zF+g^sz*bl*|CufM^B*g)TWVF+7s!?E)f8nf#mMk`5<$J_ll{c(r{b^~U9rUGr*=QE zd>TWm5sfyk6B+_+K;F_h`(fN$v8;o-)j4vLRGy@M3>hA83oX53!fWKT+6m2$d`-!C zDp04}y_vdRlOm~Z#>ThTRmrq$Ru`_z-I(5eSu`Z-q7Nu71z5Yy5)tST) z=iW203V#t|m~OYI?N~rquucCM=dQ^5(P1w@lV z&>1}Z(UibE1^inPAw}OLOfR(8)d)kmwLuIemNt*^Bfd!bc2!M~SKCa+OL#l6MmRf4 zAQ15}lgvqP!g?h$Xqtvvp!{F_u%D zB%}|`l9b1I;AX(jtBKHz%SF*obG}k5R?1i`40RUFCo&2rED2&3;*S zm!BI)Y2u0a0^DY|Oi@`4pdQ*3D9j1Nq(#wovmK5G=*yX}C#_XZy<~miibGbl(?amM zS2Nn(Ca;3FmE%rt&yboV^mY?)QD zuvSInNt054HA&A)4gRgTM|lu%V9CRV@OtC|9owUj{V4O&6t&6mgOKRUO5Fi5ip0*EPqh<}+v;q;+nmi))*F zVM8#w+HvQC<)qXWquamq)VZJ5{D&6ssffgSeGm+{uUe=jFu_v#j}#&in*zp3QC;d@ zn<-PP7ZsQ}4R|F-aV`l|Z^4p0?`(4_g%2>I-Sa%&F6WlTT|KhF-`k2qe&=b#U#fOW zy0qgD0EDrJ0A&8SpO-BH)c$XcQ~h8y5t9Bie71@W(k3O?gE#{!R|~qfN#=OZZjU&% zU9Shoy%r}ZhrE7=L=|6Kr~GVy{HH(x#qWQM%a>|1q@a+`5T)rZXwG9i6u8SspsWc| z<7h$JwJEcr7TV8j3x8#&q#xc;CJB4-TJ{yvNZE!1b%Z|6{AtugM!#f^Wz9|BQ2(YOfRLK#;Cga5h`+)0L73b@_3q+VkSda z#Dj(sbwdUrBLoC%Y4G@Pr?MWg0=6|m+E`;wYPg9Vap+#;EdPpmD6K-@u%L)Gh36|+ z@a{0hIGc_nTFG!HIg_4VY_P)SW+{sg5^RdgaHiUF4^vIIMHYSHXY3#&6Zu{G*zQSW z%{pVNZ%IP%Z4QrLurO7sC5Mik< zEwO*>~Gu*g&?(N*}xVFu6Fk^o|gChp>kNn#xy>z1BEtq5rn-lyh4@+#H< zRTVq}HxqdQWbIs7kq^V2-x$q_lkpPeV56wQ*#kz|X$G6j5VjxO9Eh$Npj?sdCgPcm zXBaV>WXgFWJ$6b97uGgLFnNiEz;3P{bhBpbI-C9RyK6wPauy!kVo~0Dkl9BURq`LU zA#)v+RjjZJ6we&?*!Pz+LrIeS{qH7tSy{$`Tl2x}k<1#~kf>_FRMA%R`d4jNeA71& z*Em@K*91v;FwsHppFmE$a-!0`CNz6un;R}=0`gG=S!s$ zbSkOGCVBoiC^X+bNIgyRr#_K{gv(39O;n>6&x!rL{3t{nwdQJTXqQVrWJOX!xlIu8 z7s%)B?-t--8T`1e-g>wd<1HC~s}J_;>KQ3FNGXiC@nN@XiH1oscp})`B1WzOdn1tT zC4Kj7QS^)C`AaK|jtZN1lhuo2gB8)zjAmykr+e%L&#?3d(G0p5MFe#fZ*JW67{*cZ zY*>eb3Jr@Z^ciA^RNf-Okos}C>K0lmuUesQ>dSbFU~NAX(7A~EB!BKHZa6Zy0{5}D z@?o>^W#TT`Xi#9Bhm4rarMGiz{*`yGJ>K5qcIjISFgOH<(d?(h#R%|mZ6ww5(f;Gl z0d%{!?wy#PCq%j^`OkL~4=tI3jKr2_3(|vNwx%7k$|t;Q$UcRzSwB)?h5v=@EZ|rB zLTU8?@uTVhe&dbhr>GtNY-(}!qB$pF^qrOLf^6!!1K5VQy_%qQf2Hw2WlPQoQ0U~% z=$ogZO@-In)OGdS8JEj@ik6~8linjfwDSrV=SfLkEs?$Z%vOJ_*$v`T(pE}VRb zhIy&jygGm5kEk(y111l?;CXKfxzjF-Eafuo?fqTpk)Es<_AdT1ho^wMx@(HJ z%#*G$`3qP~BIa{vfw>>irT&LYQCm&W}$8N%Vk)FxeJ~cT0iK>Id7+69JJCGz;Dr zN^ijdG*K~Zipzu zlt8Qdbwgi<&&}=iTVIE3HywUQ(1r8WcgKlm{ii>FBxJOB3uWLOu)HI{bum?XLV{Ab z?{63Lz0d3*@7UNuB$}S&7~{v`g}~jYw*T&7Qy=>?gC)9-IwjS8$(1G z?z7sA@eq__0DN{-mADY$?i2+Cu&`@vyb5lUAiC&C{oTXJ7&bdP^QM$dLsBfq9r9Aj zYPBNBlGP?jbW%s-Kt~xZo3lz7E|D8GJf1})_6~6eA3q*N)UvPdkN}^SC6V|8xTpQW zm38zYawuyp*y!Mb*Ro?)!!tV)FL`u9%7v8`WexoyXi5&iFfN_+g|}G^z%UPB7=I@T z97oGho2i;*gn~?8R%Tr96E*LFuB!QrJ~sOB^|3=ejIcye94=n6#MdbhhX_m2RWzPr z@K#)(fzgMVXUhJeh(EHXIWDrq+|UWu#ClDG#iV%W1TDk^2TtivtYzA|~j z+aJIu_v?u5)UVJmI6oROh6n}tPs~6Viv#z!p(WK745!akG8P>{Lh?QgB@|eWi@7BG zp^{nWWim{AgjOZGICEN>Yl90k*TDjI7UL8&TEbVaL5c+N!Sv{&l%~%gv7(J^Aj9b! zm46y&${S4{kx@S=#nbVqz2&a9o8ze0cCD~#38+xPuzu- zH^TGd!@?SUpx_^SEr~1`;dCP2$s^;c$s3i8V<>-#=2Q{7Qm8ZVhk|an+^wSFtp=e87laUJUd+!(KmLScoIn+yLyfT6r?0er_i+aRZFUC{aZMVkdfO~P5>(!<_YlKS--Y<7kC_J z`1ly3WB7QBqRWs3K0Y{svXtb6+;r@CG~g$vU3Z@l8Gk6ZksI`*?=|!85I_UJsJm5y zw_orpN|eBcc)_uibslqPM%k#)c9kY1OCkEACQunImh!SLg(%I@0M?u0$`lFer}sq! z%%-)vS^CkYwpf|f7LIvAh%CIN8QsXXEkQ8-9< z6W7ce!;HkbrtC0C{rD}ELrajyf>LseWe_7d9uKnnA2>aIx%@>YSc5>9r(i>@wJT7V zxyv#WqrhcKC{tDu)>Mt6PCs~7z(O=<1$nGfRyyV0bGw(r$CaW_Sz4E4)~d3FCyysF zE>Pqgejp$5swco!c-f7s<3NMn3=O*TvxlHSU(#}BUYxxcBn%?XIf_DQxcVvo7AH## zJQHg-=O+SJ-4pt6NR!ssy2F*yLC>Ev7WtdH5rP$aqT-Vg&V<3^kcJuR`t%bP-e0BE zEUhK(IAzNrpalbPjKcuCF_&v8sj%L(^@ zJW_K}E3- zKo7@h6y3BONmd!RR_~`p7mYU+pYceEfFP2o+Xec3z-Y!}^Ewt15_*Ix1^Z4$-P zMR~(1YwCJ@Z{L&{P2WsIeDCnB2MZPdz3}v_p(%OH0bM#d)5AbG{BXt45`*+7Z;~QY zV8wEzZ~H_)yK%dH>aMSBn-t0gQNFan(ny2L1S1vAprZhMxT1 zOx{HHg6O8n_-*gO7>)Gayj;__;#8vjpLn;thX6GU@u0D9c2-d%M#una*fh6#Z^Rg1 zpyV$65JeVHV*GZtQhv#Zf0q*Fok()#XCgmI1FgzdRMDVUi17*W-RLBCewbB?f4Xyf>NS#Kj z9anTtN=ojCD5_B7l@Q~m4(@~uITJK_A>*eo>|VZ&9xejbV1Bo&#xKw8yJ}DAK&xF? z-$Txmd|or?t!>wF(P^+_4G;0W3b{RxSjsE5!CbUmBGPJov&@AZA!EBs#)+n>ORLhw ztA`~#lF>2WZbF52C?Gf-EV9P0aQ+mTnSPZ{+icRQjmyqza>JJiv(*YQ?b94K&}4Kc z!ZN1l`jQLojKfG$Rh?Bo%=(1yrW-HvsTeLgfen|Ux@pT8<&F6OLk+0~<02xp41V6H z4c+7FXR_1+_NzmvWO1n5LNr1g8^&ykVZfcFDp?%4=SelC{ZN(SR$BW*1MY`}k45O| zY+bS>9VJKX3eoEwhH}Xjf68W@1~_ghz1}i?~G>x5NdfJsAOyHu^)_NOFq>| z_osm`a)X+0G^5#05uF{gXAA{bctt|fjK9NrClyzXKk8C77 z1D7`)kpOP_BbJ%fQ-!`#LBjxY&#H%MG+5{$R}fHT;eB4me?opnq45j9&E1*f;(axp ze*j!f{kvYm?!;QSxNn)TB|{IvHcl|Yl?kodXcSn$4D3y^}s$bjB{p+1-ux_H0ds261XGQEfw6R4}!b$u79eg;U7Mo)R00Zwma+-rd#ye4jqEqtF8X7wh06iQJ5`V(4l<#;{`lvLN$>0k{Zk|L3umD0}V&OmJg z?!;(8WX@YXjA=w;0m=S0{Yb19!G(sZnF=fbi~juOjO62DWJvaLSdEoQ?hRZfUp=o) zV3T_1?-uaXg%H_e=depNm5PDvQDw^dIE;jEg+LLn`dp6%C}!}4>`D}mRyfS2Q?PL7 zKA1b=14RSgdv3V(r*YZ3`*XT+6b=92N}zHfu?D`b4!{~tpjlaZ{P?Vo2Wk*E-o1m% z0eNWOSLaD-W`Mqg)f3fm>V+?fu(XK^;wJDYT|kAPeTo}D-C6T6QojgYR8^0OjuowT zRi(W0%bS8{))OYgaS~qp(z54uS&;u#(U_B>5Nf;do|(VIKuE@Tt00Oujvo z-0Irue?Z}gOeK-~^W5#R{ENi%@XzR(8;LX4=<*I$e(0anll@^njh8tS)RXVRN&?Fh z)A-ZakjXcRLSOSD>w$Y(GD(x*(?`SKctMdlKb?Z#xB|W*vo?!Vr_L5 z+vnG=!+j&sIXqjq%hBRhcyw7ja5d}!y@a9xwRW+fNJA0V%x=XV_~rncvPC8qP!12k zARexhm^s;S=I$iMa3G;%OK%v7IcJgOh|hUObBM zV1Y#`b)&Kl#8cMsc!zgZh0W3>0B2&C{(?v>lAF_F2^R8+z&bHG@QFZ#=Tmf0lq+yh z8;hOe8u)yx-*L?`^@&{W9CEzF+B=Pu&x%!%hMG+S+CQr{zbF_KeSd)?+c0CDh==(& z+Z8tUNrAiB5yBjlzL$wY0(ks2aL#%N+Y-_w?wUUfF(BW@!loqx-^L<48EA^@wXY}? zTJG!ZndCQ^)5e(QSH-0y$>xruqLO63%*{&~mL}0M!KaAlW?-HI9Lt{< zihEuS8=I8xZsy`=9Y~~XjNcGoEfCbIBTXt2bA6+4H;!VBwS&p5(6=vG@R7o^3N}p` z8$D6Z9dnn4$Ih{Tu@-Ltc;pO86|W+q+x!S$0~|I^cnTbdX@q(?=g?18HEka)k`ENI zVbm+G4dz`X$)vXHs~*6TJ{s?rynyrEd707>KCnfbZk3LH z`@QANNXerF_(Md-BcET_U3(3_0kk+NzA`Pgx_s9^?hbYDPIu4IioS08j$O0D+0AWm zohhN1OcG>ph!R)hcKOm?>VI=?3g@AIH_Cytt3`n&Feb2C z>F>f_M(=c~>jC_3<~KZ~v>_i?k0eBXKIf?-UN{-$nIiP66QqHS(aCTMDVT0`i}U>+ z=M@6E&?-yO4>z6fUxNJ&;CrTXH~Jcvj67%!vCa*GHKlu5=cGnmA1zgbjEVO*-5V0N z1KO6HJe!`ibu$axUS8tdjj5~-jo4y^juaT4GLGGDZr^UEl-k*@ipIhVJCmUGY$-9W zZD<=Zt-9BYiQ}pqWug$Ch*@~4d3V3e!r@eS4igQqO`XyGgd{M zVYvA;dXxp9d9~$$e;QKswMOYY#5@h|m6WBfx|n8Pv4Eew`=L`6HeXN6QixV~dWu*F zcH3e?(d)OpEMASmrstqNM^&}W0t!49oJlCIICVx&*%sp zK3rvThc5(6oB&aA=s7VzsWfw+c9U+ zPOMtEhduiC^2v6^qycNoRJ~nr@aHd=w0GVZ+n|!sUMcH|ndROPjvr=gyjU8SU-0a? z>#m)iOVWq!plC?yX`Tc*Mw4rD<|OwAu@qjouKxOUwHS_4y1?I_oZ;=IV|Tm5_VumC zSOD$b3%W>ywCdMcfgnNVd^UlieN>&E(-CAh( z-oMyy-Tb1DS{U?MmBLP{hURn0iR1%N`Wsg@icVuy3ODC9T@#gu+G#3}$483cDtb%M zGs9IR@WPtMI}r<<#iDiO7mMMJOjIcjC=Y*Ks8M7-_EPzN9(>DbX{Hq?$YZJ^JhQAy z0o(lPi>w9Opt368TYAx*3h7U`#g4`0Zj1$^{Ff`o+G%}zZ_KN(^mrFCV#Ka7%38KI zCY*4$b^FlPnLrA-+c1k4kJnonmYsmJ=+t0W8`t%Ih0RLymwYD-^4wKg}z)@3)flP_`+u69xw zN5>X~0e*)v-W)3r62e>|BvGzBP?{;x63^ChMfwN9@>SmjF%(~p5 zII!2-at1mm`_$LcI`w{M%GZm0Rb;JQ0cL&f=fz{a*7kL$BK^;5alDD06ODQUQ4gfo zNsCb6m{6h^r{f+IIvQ2Bu5DM!fBt+Pb3K6n;ztZ;TTOs0qKlaQ&M!Um`bWd-xG#d5 ze$sq=rmp^2KRHZV_Kr$FDe7kg<{1~Vu`j&bnu$yCN6JJYHUr6UJwy{Z1yOn~NoqHj zE)71U<7vC#F$32)Axw@tA@E00hq}y;DrBO?G~?E#dCg!17h60=#*_JF<8O{&++UX) zw+?t13oOB_T*jX@9LnF_nRpJn$+Zk1&#JU{O0I2?J-6~V39~k-=$QF*z#<~@vO9~} zo_9DDv4-@p;zUA|`BQy{bX05O#V*$3Htfu*_W{-t<6?ylVE_r}z0xBW?aPydi!i5O zzlNNOqVLpT#qfWYBnRJ0`FwD~Kb5w2$esGChGf4PZ21(_KImWm<<362;}oqQqY49r zzK5<&%C=+OQjeOAQ?K(ZvBi$}NoSARvk#H5g#}C_-J_PzC_PL?g478>r|Rb%)TS7q z%qxxqMFT{W6eI@EBkRs(6en0V&l_*avz2zLG{F!dlm!I+g zoA#%mOzOqvz+l--men7`_Ijf;n~JH|?|tQix7?{mu^5h=QTs{=wlN#7g%i^6iWr@G zUc%W&X4raWaQ2}!$|PKwjeYG*q9EQrn~=IHYJgUr;KL z&h$3%s@{x95Nv18@gK+nWOxE(*rPVK*q5g-d!F8sbKAcCB%9jx$_|i*SlH*zj<+vI z*KYRN0S83*TNJ`x71SurzY9vOLw;>38K0qYYs2XD+UWJR9m`4-!FFZ%Z6pOKc&-Y0 zosiX7D_$X$B_o*xARrz>z(Q}+S+|sZxn0v@{ITeb_mKZZ)7dY%l}6E6)bE4>omcz- z33_P^=kskP{vu(#qdQ%mF(m7${I#Oi4yi2tU=OEi7BAU00oH(RpREJnTj2Ab#Fn^5 zE9n;oOW>ZTee)5vmir2RJeV5peqDxM(hgXwpyzL`zXvyHDrd3pzTrp>s+*waGvR3D z<2bTA<_h1Xh}OAwZQOm${_WsR{ev`z)ow^^1Z?BhuXz7D4wPa4t)I=|TrJqi4c84>HK*3;kvqDk?7mQ*v zC(h%}35%5hPl51{)CXK^r*OrlLuG!fM(YiQUmjg{INHZAzYONr1U2w;234*>6N2a4uefp+mP zk4>$4)0r^RCJQ;xw;YRM=QnL+Zu2Ltll?juD?6P59A~s{#32QIZp)h=sB4il?e3~x zTDK`N`pXg8x8V}AX~GhTM@&D_r7o9)wD=#_Qr3XUq zHlJ_+ORAW+j67X=?VYc2@o2%~f?(+R`7W}BaVxGy*c+sw#@u~>=A{?Q$i+-^y}ry# zTfWSxi3fg4KLG&Hn|^@Cp!}XnFXwkNePeW6o|n8Z;j~_FCT)6+>2z`A;&TAY_~F9a zLHZ&ucvR~SCQq+za#!f0j$?V-fz^#X0=H>NyKedIQQdO>y@yH@8ohRe)gqZ&3we&} z`YL}b?#bwu;>I8qnlswjx8_gpF5U*CwZ$``F$)iU>k@J^xwzUnj^{k*acb$nLfulr z_!fnz2C~M~1qGMuB*b1a_7K1pY*UawRlW#&9IfO>pC{9~Z$6XSE$KhjI{cpR6+CE; zrpY+A$mcced(7;j(xErH<~pMs%)-!`%)((CVMwxeZ*Wp)IGFX&#-(l05(0f-vmFXu zpW?&>wmlIS)`!kjKW;^reaoUFb32>OuZJWosdz>SpXLCM_5qooj-?E&9+S~cXE`rgscK7Iun z>wZj_SM}-jedYt^l6Rt5KlL9GF zUAAzqH2Ni7%ON_mXob2TsE(X4z@Z;mQ@An@-xsu^MP8=9z2M^qTCsXVC94u>HraqC zK88UtEq`BS{PfEs@=vk1-Q;ESAN@enrEJynXhG$nQt4k4Uj9N8FHAzq74Wks0Fa_c zJ7y7n6zd1VdWITR*oYE!f*=@J;bswtwJIBjnm){*f##fTLpzyH6kO!${N`5+T5fL| z$O9qjDqq7<=yBzwlV+gIlPFC-;BTk(7L)92G~KAdONdIe(AEd3VT-VSPVL#W*!cBi z1!~K&%`J9P3QJNx3o9}OUcMkE{i~?o+q^iPELO%t+0gg0PQ>{MHp%(fF{+NE6U7NO z{K_0zRmUsEN*p35raz1Gf>zo!b6`K$<9c?~z{-BEWG!`SRW7JE)}ar^jZcfPQ1fuX z#^(-U6qRLw{+3!JFQKGd%w#LxO2A?x;c{#&mz+ZPhSLj83id zOWWsSZj7)Y*9-k`__vCoUuTqvH!CS4zTR%YcxRq`>UBrEWZZszdq!BVCDP-6P~EcqP=jMj6g&wB5KE+opb&mU79}#W z7{25eQcwO0FLCG6`AhS6dem>QZUce~&CE+@_JTB*paOEoK zcQK}Ad)@JK{akay$VcfDTd|*72quVK-IkWLq_gVXqygDf&f>nvzHlB4NL&q`R)DFubYL#e?sCV6Ke!5$oXK zqu?8hi(1Gphp)E?h$J2>_-4GDbk;n6#!WPz1fTbe>j!pqrcRc9gXK)YEj#mT>6AxB zOV^qjro3stWVbq;7CT9t7vHtsNF(7~ zoo*0X6UwRP6`w0;3I4`vG$vK_@~7&Y04c@28baG$Z58L;7yDlqh8?0sit5#SarUO4 zqv5w+;N9==nE}5FK96H9CC6p^o^HTc&KmjVSmW~j$_t6{8#cRN!%~_scg|^YNE;K+ zHz#s86|XKdCm8v0dr2BX-3NVKQ#cr`Q}O20;RWRFgG^=BbwDV{qerTle&8__9w|#DYQ;KcQ{GIjAlzq09AG*RiEU8cM3cJv zzG`I_d1twF4j3o){p|UoL;La|Z{aD5XYI%#dPPqHL)b2gV&^l`mT4(k>Dl-CQFxbu zcK)P#tFImn9JV-0yk>HvS4%Y?c{o9F+JEs z+YyL~G*aesPusD!cu1iM6(_`gH5R(OBZ$QyfV;M;$X~q-d>>}FEEQQ!NIE=4Ng9PJ z;Zratwj^jwT`On6L#v)x^D3PrrYLMlkb+cp&_^-izhla>qs;q@!1L>Wo~T4fc*Eh;8QGT((JEqMPhyYKjx$o;|rRN-e zMK|R9nqDgQl_L2atV(Upcg#FVo2(H#(aM+B{31Nv@X|#ux157tKKVtrlNI1%>{s6X z!Kqbc2R<3r++d9Hsn*!QiYh*r^_M8qfk!+?8`;JBhOC*L4kD$RM>yB|me$!neK!g7 zdUhkLKPwpQW)F8Y`0Xtz+IuYsrO?L6ZR}`d71`n(kXR;*xU8mZ*9x&?8{u&wyG)-a ziMV$~B*PkV4y2dD59mnKpa?3iF&OY^cT>gFC2#1zZFqT@Bx2H$ED}YftXN^JH6TRl zC^68=8*UU1=S&~c@PR6+LwiVNXyJ`L&i8LgA}$jNtOal6JQDwyif$+izb*bYq%FFf zi-9+UjkrK!@j2Fjkf%}IFnqG#E7dF>C`0S4xfXTvn6vQX>THDRd<@VY&8y@>4zZ0k-`Xo(lK z*Q5Gm-J_M%$Aw~nSdu=X#vnmmKub)C+<3TbO!{S)F*8u(BSWhpWvOx>4Q|LTrLYRa zN|;OOR5T6u&$4-u=D8;2c7N5$aUF7(84a@(87W;+oa4q0ou+1GyP3Bib=TT;(m3UJ zCS{m#TsZwq$QW^4c>Q+#23%wEi$5@|B=R%kTp+N-NMZLVq^FlEn-$*|cBD6)&W4D% z^D^RG?@s7^q>|b(ZB)+O#a0*`k6Ex`6v?Vp_VUwc^#AqsbGOjwaH+BpdSpj#BOaq3 zdJ}0-hYokGvY9634;^&Nv5=0q?e35c2i#kmYaMh#6LqB!zm42l<)o>_mXHn`%Tnb% zW}M`j11=>=2Ar#nq1&sT4x#d81sLPfA-jw8m`FcquLnze!Iq-3U`eeH*G*qR^1z^lZwUz5L69i|$11Oln%|X#z}Tv}eww8C#6M z#x_F>E7O^7VsMyGuGM~E1=Ep6Ta0h}WzX-O4>OlD^eg8&m7D1U{MYD4 z8F`gPV?@dnN@~(pMiJr_jw%%}Wt^pLr|IO%6{XiE5~c*^n~!sYM1Fn-edwf}*bPSJ zT@Yoj#ew=cChOQQ;xjqc-8QFIUYVgyXwhg?QIiT|E%@XGEmporMhl!2lFKmKJO^$V z=5bxA(OizX#vWi_U?P{cFkoM8EyTX9Y>0jJDu8{5bucYQ3@>OC;}5uB+q`7n^E+_IP=YNSr59YYY-P!(1(%)zHS81d znM%^10z5T&WvJds=BoWm{;ME?@TMtvW*g?kAho%v45 z@%8Nkz3K)uNXzG{?2oH$hvo)OQgHzc=W+=^A^rxAIL}IrlE~VpL;MA|8hm9QM~^#m zr`xZrppVqZ>|i}%xodj6OC+S2BSG0Nl9BC@y_YZY#+tWUIx@kDzbBa$_er{AoHiz) z3-Rlz^wEx=;q$L7@0!0>fWG=rJA+eBzVR!&(O09~kLIKq+T|LLPqVuUs>{}Mne-NhiwWw<+C$peAoB02sb=rsl(vlxnu8lNiro-LmU zOoP#!zB4L$y?hqtO1f-09}vnUCHBEW%uH&WusM9w;VC#hnS@B%{mVvI3-RMbI9C4Q z{ZGX-?WdB}Ta%blXTFMr#_bFsL4qfB09riGVVLukIALtZb%#qzwJoNp`v{L^6;3L(1rvg!<7NPcZK;bRvXiojdBa9m@NCV7@$q1~P%+h^ zkZn|;(vA|ky>2B}AYqtNr0J&GY3XqSUUF9c$gDN%d6^4KZsy(|F$=EGD2=EV!+8e& z-F4!Hc$ieFY`H3X88HEQ;(~ckrDFT)JFSA5#JJuHc7?vW@l8Y4t#rST zIywT6V<(e#2i;p&-5<;8TT04{qw1?d+kJs6qy|=@gsUm3XWVy)#V-YP#J`S6UwSS% zGS{#A-M$~^y;y$bVELh=PgTI4<5Ob%V3oW%r$r@OlKFb?&o9FaH4`pc3ND4twFVCm2TN`P|eeNDrUe~lf0X1D*BL~&=G7FnN_w#OyA0vvX>BA%S{UE5OZ*$cgA&^|Ir>cjpm?Xce?5J|psFvMtY3td>2HwiUp zwJc@KHP^`&bvxSLO^(zOz~wX|W#uFNw4n0YYRN2XS>koRyP2I$e7X{P=k@%Y`|dfL zi+RfKqr!3!H~q^fn{kj|%yu>*bW@!f`Ktd9bh&VNHTFY~i)F;;>ul;PslM`6B9CWK zO>@!Qgnz6E5k60`f+hPYHt#TxitVd;y@ zHv~r=(y;036*Ka2b?40xxn(i(&7OW@jjlTQ1t%Pu$;hW7-rkK#NHW73{f!wWYqcT;59j)cW*6BWhHAAQrhA+FU(1M=yl0^%5QjjwL0Ip(J zF9L;c*W#m&GP=nyP7BE}Ah$))f^g5tqRqovC}vCViJR2S)bs8Jy+$11r!Ru+)BsqC=@woI+Z>k zK7m#j%vw3L9-1$iuQoZOc1tjbh1>lc(74NugMC0|%5YIsFT8~sXnjB!#GAeUa9nH` zyjsK;q|%u40abCpg_w2SIigZrUe>F@Mm36~3+K_8clnJHb=Gg3sh7{AHko!Ja|gyW zKM%}Y#ufb47aA#;DZ(}D4O&Ss7yRXNLoLTT`Ue5tKq6AXRza#)BPbM&RX60h8t~{d zN7d>A_`*iLnij7g1FQI0VKnYijyz)FK!N}f8=`GwlQ&@B#R9s7L6bjLgZ>%%0 zg(cRv$fB!GV~gnE=SXmhIekFn3%kTDKHa%eF1uvjIa8JtoIr&5J(#38gZ*fNRf9CG z(};x!%rbtGVGza%QU!&I@M^>W*YFd4w4f_RAmaLH;^`S@f2|<#hX%(#*$3ot$D|~v zXBpjfbRm_wC7F=HojLTr3#C_(YGLFmDb`=}aTFVy5L^@vv^6qCkZTQW)GUxDpM&ku zf^MsQ0vqy)g^ylb^)|o8zhT3^Um?RFHHM4Q`0)BLw+5A>0@kkH<3->Q&d{6}0kCWu!M^eYMfrTuCRq6defhq-?zbKGS{5J*M=>ywCUIbDN%U%P7 zfUI26da631qIRe52L!1EJmd4p$~b#;or#3=1~R#4P#?0NvoYu&aRY^nroMyJR*7i2zxrN>C`o^%!Oj(}Am9CbJJ{ ztlAs&K!eJ^RyFWZW~L};)8V)KM8ZeMjuAlhgx&$F{-zCEsw?TXEDUT-J#_Zkw z1)tmpl>cHEM_5i_hA~hQ*p;XK0np^h8`xbxBly^$kv6bhEI}}H66dg+dZx#)Ld5MM z*oTl{i|{=Jd*yTFdmheiG~pi;2k9e76rvq-5WbtN1``&N$?+(`M^!v&uv37I+SNXE zVGE4eU37)-BeOA)cjOIRdhUSs<$0j+DW331n9g!gx*{4n?hL@jDpMc^+W5lJ-O3d| zMS$xDNE0sVnn3Bfehb4*a#gZ-Xs-M(xZH;R71~!Y(!o zB+@FG++8+V^q)*u>{ww8%rxovfc6F0r7#QR@!!#QkwpuNVD|wPM?>SvzF3lY1_P;b zu_)c(D)$TqT;+=C@x2hmpT+v12xi70(b5%?>AaTt63MpkxR0luO*Fs;syo zmY*I`)A>~K>^-59&c!{k1k_?)|BmRbW@wJW4W~Mf9iDZ5`|P>t-GanZ`uJLN-kA@u zp4Rq@BNp$k{RW!8tV`!=62Ll15x_2Us6H;{W>x%QnhIzX(K)Kfs}R6>f{xXLRHjZ#yMwO5oiywe{24#f0m{lCB*b1KVjR!+kF{ zi6ywn76;^VBZs=C{jc&x<%=f5i61t#cX_UvYDA}J6Q|%Ni=2^@=k1Rc4ZaU&Kur!) zJSJKQ`y|4Q$VDr05U+W+d#>DfcXwO7=zc#caCh@lvuReHW;b?P2-V|4canSNLk5&; zu@tM%6qap<6e}=56un8*v4I(}H&T+Ez$iN2QfJMT&I{+6a%gnjYP+d+?0hex zMk#Y_DR58Lq!RcccH1k(!;SX5@T9~c+1yq#|6;pvfmrvwhu^>+&!y$4{mI^=nsA&J zd#9&DIE~%*sGQ_#V@!|n9Cvucc#&eZPiBx<0t=xyXOK$N1vYsqu*o>d)C0~Q=`k+z z6fYo0=J}aSLNDJb?!vLqrNd2@p2HAL2#r_MO+wS3hi}J_Oca%yBO1lNZX9=g6nd32 zG_6i^Z(bL^_P))&0->m_Z=1m-YMV%|*fx2Pe`}6hbJAXLAG+%G!M5y{B}lTx?d&=X zVF=>-j7`R3SBBKl@qtEv*kqP3%p%eRkiYzLjAb}u6 zuTwxcQDjRCqf7luu|aezSaF7k(W}tS*RtH}i1MRR#*H*xKbIRWA%+Nl6l_x8pa@*`= zP?5XuL;pRyiMEiTWAaV)CQpI@JP`aE)bgFO4H4P(NP~FOS741sN|S+LjolVLWcBlb zJ5>;k4!uvtir5;mh~yzUt7fxA9P7R09P%$L#B)yt36%OIxXB`jJg7^!Esah|wCMQ@ z)D0;cv+jNrk5ng|R@o=oIZXDrv#5)e`!DgRKAzOJkcC9HM+CQn$=kYXpGQoR{IqB^ zWQ8qL%?a8}_;9)?#f~`r;ul=zwiSh#;pSpSxbw}%S+MXxmdH`97sxhW`IUI?CeO=3 zcuwN_@cxrri^_CqaIO=M)0`^Riu9j;6r#_trB_EiWCw?r1QwE0pJlBL3fQ%HGvBLW zMuCobv4@j zPn9M$aU#V*+>B@6Vezj%h>+G)$Vj1n)x|`BC`A(dqm;-SP>RhFqy<*`^;5lN2N8iE z4OWigW>o}(3sX97OXVAq77=trt+~?mq#O)2Q@W2`wvRt)QBe!J4P1U=2Pz_MtGJ~1 zvXFRk!85+~@%P?o3OJsx(>)5lJr>XPo3QF|8E(mXGl*XOgL!nk(0@HNDj0r2F$5ZisHwPh`-)^QLrLSz?CRq4Jp zx!(EHSGP7FpQ@eQ^h$YYBaHd9>J-e97gJ_s!$imJh5%pqurPi(bug59y*IS5Q=`g( z#WroyI@#Q|muvU-4jP3Q)k3mae70-_UxD03wz{N)694-M9z98q))C06LydF)0MuS+ zGT+ckiU0QLw!Q7osLZ=Oj?%R#vq9=)_xXl4N^;Wnx*k3Z4DETomP=V>cdlPiD8XWn zeuhu>AM-_<_ER1fBzlX!zzCyywGO*YJq)sev6;{G)tJE8UPB~6oahmv#4Z|TC`O9w zRGw6-L@pqCuRPyFCPmU?^-lMcDMF6{Og82+f_pg&^1On$`$(XQIyzCYqgWBIMMWYM z*&38ktvhlt8RX`xEG$Q%tUFUpCWx(A6AMz}2Z>^&96y>QClI%IU5EPYq%6)V8Iv8O z*IrfR8GH$QXRz3d&-%}-J3@JQ@iTXM9Q4I2Txb|sF?^TN?jT`?~3{Ieb zD{e>WqP=_IZnki~wn%EJ-S{*woS@GsS(lS3 zf^VaAWG}t4SQYuA)7*d1H5IJ{Z-OygQC#J@E{uEV8Gro!uWA8*vF%ZvseJM#AO8$j zU;lO%4V08W7~3#T%GCY#G*C3U(sw&4HA=Z?bR`N!%QzG}LN8FFe=z@L#A8lkPmM}v zs`39+i9uTty{x-wql~q805ZZ`;_0I#M^{_#(|SJ14M`{OucY+@&LlmRYf(;WVnZO& z^r-gr2B;GBFe-3wG@?>@TQh)25VXp}NYVoZWYQtX|J#@yaiW-aVz_$OTGab$)gpNp z<@$k6O7UBTBKc!b>X2P>u$bJ{yQX(PZf!{4AqYM@`0o{SP#wEAY$K5LfcPHbdI*VY zpcus4C9t;?(I}~aw^4d5K~yz5kE(cuF|6|+nf<{RT^z`#?J?nKFupM0#{_US;Ra!3 z!~??73@+k4Zd_E+D8V3rI_m3uQNJdFKp3;rfmD>};=qgqO^7aT1Jh~`M-i=8IAdS7 z;lv&~_?VHp2kL95GOIY;Cvk83?Cm-2Xz={8^T%5%z*`GhHt{OMPhi@7252MmP4u-S z21c5lc3vRW%v`5k@Qf zoM>>d=(m?3W%w@I1~sWohZwZP!<-YX_B5ADN#vQ};8S&)?GT~2gha6^h!)A;s7iqm zE>NNj(wm?4Jn8=S=6!SlFcM07&sZhnB$6e$@hO;j=l4*5#~!ucD?w~8{9(UWhL}Cl zHe>(trQlYvO-O=N2|u_i*S1loYI|+7Bzg&3CC8T|76kwYbuhoz0Mp(eb&b6aX1hc1 zHcH*l4_-6T!K5qsqBl>-wgTZ^Puw?asx8QA(3m1lIzLNXO0=}^zFeE-+`yxLza*d4 zi)BV;QHT7?;WIj?Lb%-g7%Iz#^xnwcvq+J2`K{E?cgu2n^JgGA&^$xL%b!S-$*GHX zy7(3DTuVfb)Ivo!xZ{sVE#8UTTPT%pECPQQ6+>EqDJef4KmSfPxyiE0eC%TnqucSW zM+CMFk1V1EN351pFL{odz$Pb=jWEo#C2j7fdh(mK*!SK7k&8Fv7gC5XH(y*nX_spL zICn;9Ex*b+E)}<^W)pAHEI$0q{#|Vcj%t-yw9uA;bHyg7nw__Y>%|k?#ff!UgZx}RgbQZy5<3%=IF zu&v~oPs;FMSdZ($Oh?greya4PY>ehW^Xx883_sy8Fw)N7H8B^vsw1{KGIu1(ZBpSK znRKKz-OvFPgM!Kc#h2ZkD!l|@!l*O-GDYSr#6jEdhVaPItcimekl>-FIeJXX?6&$# zY1|9>H@AH_lg5@v8oPy0?Nc#>mJ~lB_*V<7&jN!8ReDhmTsqAY81(G&xPwfkXoOep zw>R@`&G$095-OqMsvD-U6x{N)6DV(2(|4uaTvuhT9Oz%n+i02wNC;Qut^de)Ntd_- zZJbpU^7Zqp4p=&)iY0lqREm&RXIk?VI!lq|i33HuaZ8co&Fb`mX*kbm$?I`i`Z-U5 zEn$J0@e?1x=7XR0LbVTOT?$-`ZZJLgDj2(j;l8 zEc<|g&ufZU?e>W6{1mvpt^w>^e0Hp3pjZ%0l^Ksd%+vrd}@vdHbS=d30` z#*qjW$rWvE$)NL6%nzy~}ZPlQYX0^2J-VM>S#j zG_J2zYqu|Rc+R+)S_Ly;Q$|$}YF|`K4smHndv~Ve-K6srEdf6_-?ePMvwdqfu6iGa zp?-p=3p$q>{a^bc!xA@ zH)Wgg5t=$hxJQ~o?j;a_;aCsY;qlO`Hz9@u@jTqZkTiGaq0yQLNhM6TpwFKOAYvnyl-Xl z_o&w+ud9FE5jYUdeU59W($|MJR+zqA`#^{FXqd3CmoHK!t!1B8!q=B@2bN3C996ZY4OU|%-E%0z3dHoeGznhmM90YhrgZ8vzT*WW(LJlBm{OEg@}wn5z4m*=ai-`DlN8ED zA|*-Xw^Xe>1Jie^nGE|eilp{DSbslM3(?|U*Asu-%T4nkBxW_)CNX1xtHp-VdsX#u zZzTeF<9Y>dkQR4Nqe)a*gS?CJSkNP|RLDUe5O9z~5KvROv>ppmePw^uPC6UqA)OAt zVD4hym{e(5l2S;ML{AXtC+Ess!+IY_%#S-dv}0sfpZ(64_Td`6wd8 zaMhh|NDlbXYQ^?@>))pVyOqFkVwvj$3@k|kECTdA2n0+`#IxA*UDn|>sRArv{D*&` z5Mw&QhT;Q;{&uerwimnt%+442aU_jrVF0+L40atNnPnFIw0yqZ%9aKNcUHDMnU%;` z8!Q^V6Ra7Gg-H~_@$Z9x4lWGszQ5%|qJ`Mj5ApoBqTkRfYZyQ81t9(MF9(3ELk5(n zF-FHRLxOR|9Yn%J<)Sz23MBh5X2`3u4V6HM`>lT&`M3MttFdw5P<;50P(b{dYqxs) zpH4tR0ruy2eEt51`2Meie%___|G=YNGZmfyNg6OdK@Xq-02krpvI4=!`JF@mzzoPA zPS&{*#I_EHvCpQFe}eEAHWoTHS(yGIyR^L=>A&;lZ}f^Qewk?k$W4V;Bndyo#o#a7 z;179KvJoT#u#G_&5=Q-hh4D8+m~Dj+Ov7s7RQ@AzyjKB7ATrBK5EOtM-v#IR4}e3N zumGbVTz<&fxmK%hR5Pogp=04CNg_`f{v&gIQ!=9UX?hXcva+{HVd60Tb8 z<|3CXZ+z?W|~PyYrt)c!MRyuBZP%FIKTe&|X-K0>O73E&M-;rjkvHrlNwAt?uz z2-FlX!heeSI0eTnpcGR6{@wc?>iECRh0Fzi^+Dj|8USwW-)-e@Z)#Mj7@O_E)Z<>G za=`2p!AUvGU50DJ*sz2K-RFLDg30VPxUCb%`KKx!Bau_mO zf&IELdJ800V(pj{pJqfQ&_Rje0wIAbfV2uA0hEC;WSoL~Ejj#_X`2c(fb?(N^VIwbNT(H*FL|0+j& z$(BI*F~H)7q3l(Tpb=yQxJdHL{n{hU`b=ab~DF0J~{Rib`ytYH`CxC%~1B0v^+CU!sF#sR($PYl# z@argx9ZwEH&`~lMvxCMT; z$xD~1&(FcRvDboqo<@#+2{GGxDBffRw0RV$! zKGh_HaVEnb$T|YF`#EXM({?qC0(yZkrNiU=*V*bHvcY-AUIHmXZqh#BB)bB8{ogsO z4UP{PFe|LfT>=KTn*Fv-yXpaCV#U7#2!3|~5e=^IDWhZ+W8e&QlWzN01Rf&c3z>Mq zFk)y|na=&j2uO=RSUunf_yZa2A!#)L_8tNi_{D#O4j=}^8~D&sT|eDF;q%hF0E7Nr z_4SJz;sL%K?F~EWHzr~p;1DWr|NFg5v@Qvdk}PZgJCh$G5B3q@#BX0ACf8gaRcv2KAT3MgMI^ z+4zO5NgGUF#w0aCc1=G{(ulre%7d9+9FrW>I2j z)pn|vJdE`~ESDv@4 z=PBx)i@pWF&YSOUdSyKCFWMqJgIWg{Zq`@Ny7mR`M?LxP4vxGm*uXh&^7M zo?dsXH2jv{16#wqA7fofc4clFc$vG#wH91E)0r@r3>T>Mf$mXw(dYa^+DCgg3Qm<- zd2<^QSy@T7izaV5N?DaQe%7M(6a~JRZqoFl*Vn9-t3t~yI{9FpYjRRgA76w+F&^uY z&lqbhs^nD3LC>oxqHnkkb!gJtkvs}>oR{Mf%agUcg9Lof#iml9Tuwc=S%#;+HJ>qF zpedmvus9vBw4A7^+h$_GN3ZoZY}M zSfNHkc7!h-Lg4tw0@>N!R^x(Z!wlJ(#JvoW^#&bs;$6fd#D?)@b^e1jWs5Y$T8M;T zV+hu173Gj6(vyc}XJJ140#R>&qHe99YW6Ek0JZlM5a{0|i$T12PYhW$a>sq3eYXCh z1-!G>0AdDhIRG920g?=4`Hl0})<@1Rn`5xrBH;g;0k9RMAFR@9gII-4=EiR|&_0}~ zi{A$Pwr0c(&aM~!#H&ptT!t%nRq}vMNkO_(bvxjggln&tK#beyFAdeEEQH8QRD@t! zA~*(-m&giU3R{NjqwwOXQ#;u*=uRARUnS;cpgDO z?WBM>YPJHw7;uzzC*S(Z5}=iHU-D#4xiis`+QpXPXFo3{_+gUzegYUXh*>fr5VN{; zA#g627(hf35d$7T4ng#NQdDmSfO+9^UK$EMI1ju8OmQTI$oMVlfAPQ_V(wq30DJ!0 z`tJw7#eo$(IQZ9z|Ip*k@Cn%CZ2RW|81SpVRC3|>gLB{|(ZikJmw!J1#DNe0b?Wb} z|MB4erJmoX{%z9#wE9c&|I(`e>EQpL&s=R8$^m`<_ws)Nf--=?A)HEfcADH5PHb+!V z>w&aquweBtQ19NtJjQ~8gF*nzA&2^WRUWx!3=LJSfDDBP+;K8vcC@rHwKdY$x3gu2 zT)3H>%*~Qwr6Oin(ERsfuSgjd#aG7m6`E49oM73u zxQKd1y1K%&Jxs*sZ)jj;NHtnwIu|@Y<)TZ9Gt&QrnkHs%W)!exi!Wo_G{5E425r#Y zFpbYC5&dsyV~E{hJ{b z?xqn$U8Sq%uxA47P9Kp8S&F8M$u~_AS$fcOxRW-|kCDmW#xQ=5L+P2UzuxDhXM4f6 zlGMHB08{w%(YmnSdj*HFpn|->Zh^b2NoLKv%ez@mkLy!X&&$hu6pzcTj)RV+Nl&-y z(c)!IPrUg?yqnXMWlhI>j--a+`$jysbAjf&g?1PcfZqF#*K|BLV3#?pGfpzqnRRP7H|=oPoM&guWs;$N4C5reKzl>4|p-M{SShBb1tqM zBaNbb@d`1(azs6DU}qcm{_y8hpGCL()c{h@tD{@X5$*=UE_vreXI4#f58gn}_WLIU zE|!Lgi+5+9_r>?1m5-Gao_FG*Rb#IN8XGN7YCJ(T;_@~@w^Y-rvc{u~6%4Y90X8k^0RA#XTo`St!FbWUa~F3zsUNjG#V@s})05r!EuFM5hYn{InwVrgh_y0rLR|m!MZrjEo1Shxz86bFo z02wqmgS$(B0fGm22<|p`aCaMAC&AragF6I=U~eGjy?f8S^~3U@G(Q2#)MLUWx6~gD9ETo`P()0QHRTkMR1XYJQ>U6CSLy&d%BmXNdwPEDepbiZcNk&Z-Fpq~8*$7eps!UM! zwAf<3K&q^o$|jtUvm&}aC8U0Fbh(__ogkLmx%wyAvpY!HTcvc))ERXpwYzbS60m1| zA~ss-gS4Hxp>mrO$Gr**ivD)O)g$UEKO0*k!S&xnUs+d`l=1aX+qIW@XfcNr>Q+73 z6&U*R4jTLvTkKSiYg^>XSSvDQX=tKeU_i2%Zuz34p8WH930*;Bc}W1$Ks|Y~Nb@5H zE#{G9487l7C3M@n@p-&KtXTTaoG-+V>&dm*x=!l#E~Yh9p6!@u$(4`{rj^hgopMZI z`&RVUdqp4!7{+dm*6TePjC^yY*Pe;d(k0_Ykt&oof$h`xQVksn01J10i$EdM5U}^z zeF;Rj2CQabRFuRo7-|hC^zR@!Qk=2(GODY5|LI`(*_ zs`=(-a`MDAW?$rdO-NLqA{;@~yPT5MZiNDk>MBqK!b~)?%nxL3_qKBNM%Zy1EJYjf zJ!xcni-d|c^XiM!m!b`dUq7dgJ|z>k3as>aZ{d;lbK{i~fWIM#GNQfM2}0=I{fVzg z5<-ScRL!spJyBDvrnQ@t!D!5Xmm#B|xCv`!A4My_Z(T7#3#i4O!8o ze_jd1YPEU4yGX`Q(ne~Px#i7A#CQ_EK)qxq6mQWPJ~7k+dq~ZE)>5@O)lB- z<#RCNTHkAojzbjkB93MmAEgCVbdl%&hJ=Eblt;p0iTDWO`#D&w7S+$wd5lp!_-~uqQ;;l2mEuz z;*q<$5t8rr8It=Thu5gtV_>x0tBPD8;M+k|5IWg<8sPsDAk9Obgt||kn9ubl@ZGeG zP&~Xwa4>ojXvjlW2!&KFT~iSY8~J_Yevk>cJZ8jL*t$d%ay0rAeuKEry^4e$RD_tz zhyhm-V(<70z9Mg)1CZ>IpcU}>m~{?vB*w^@EeH8H zkYFsJXsfX+IPhZXLQ@0Y;kTwUkVmsB2;p^d1e7gY@M0)Cc_U_e3HqEp(Ij`x-k?BV zqLc8kvqwg0DiDefdpsiPb6CKi6ZmU@vgMN&hHjlRx3{>@GBlsQA|oUW z0iwI9joEOK0HG<4BalxJ;>(18Y?gkA{!EswKEoC{0%B2)8a}vIWFhWGqSP!tU6|ebpJ0Ll%OSG8Q>U?!&tGb55 z8G?jL46oy@UsWmLAN@-ih$p6*!6)@2x^RDDCGIGEk&x4>!bl9K0QG?aPB;Z=t=nK< zG<@ezpI2fzbV@-wzX@b>ycw2C{m+9#p6L{V z)KAq+c7up5_(Ssp1oALUDgD))@!9nFvxrmjFeJ!@b0fXpjuhsVQ$J^(Yl`-q()CU+ z_!T5xJgz6bNEeHo9Xkh9n8dTw?>E$9sJ2FnvRE`JH>CPK7LRpc8>0vG?%Hbi>JdE< z&lB)@H;Rrf7#iBvnii8k4B|$XPZyEqMrIKXbzjysYLd@Pb&R+5As7UZC=V8l#W&8& zQt-2W0i}!3??Wv@gZ)J5s4Sv;s62igMI)G6XKm*JO&RdiSt|8D_Ye7{GYE3|ogowB zakAL5L{N4z>R;ik#pXHf>7&|2?;B#;68YJtS; zcm*smd1K_ANh2!s_}287wqjxIWXx!1lc8=~0ajqDSE)oz;I{YlOpd*ezY+oIs*n z)pWgiXT;unEY{IS$R6E)uwaJ&6-($nmXTICmim}KSnBldvCLq@vC#g(q6Ej15Oj}a z<`0(j2P{B)I2I5bOLsYwFmu>0wI~xmGfMBOD(a(EJUyQTzcNJT)hRJqWc381z4ax2*>{8Z?6^pZ*xIS3 z?og2vO@_eTt=I2z!R!+3z9o|JF1%UfRvDy?G1sPD!fKMtmB4Wq>V^01K zlL^bmUc0er)JX*XWa2|W5wq^2KoHCe3GCrP5nuaMCz`KX0@jeukHH~9OM@B3VGtL8 z(OGZ~?LU~w8rfB!Np|Z&SJZOsr!RPQ3}S1;VKbPIv&>6jX8nxihM6pmAeR6d>oQ)s zR1vI`CJyJ+E&+eYm4to(+KSW{8YiSGPk;}{#H*k2fGtZK*|FX>)J8DiOiay!5qBaw z7aBGd?tW79<{SB~Bma}TkdD7u#w7s;SJJGBIT-G1|EiMhOK0!wOUq_gN>xA&AV@IF6u5Z0_RZ{6 zXf#r>SejGy2~m>;?sU$b(sXyuXlliqKlbR99~cRzFKmFYD8 zf{SvN5PL7gc6b22&_3vd1=cb-fO8mi6!E#4^XVo%kpP*_!iN*T_UBKA~W(rFyDxI*3ZbBZW5l#T>h zKj%wryKmRUqmV<2C99pphrFmXc!q5O!qv{!L`{;_Y7E!&Wq!i{7=^)T|M=4j!x z9ySKU@o_?lQz>WjmLkmk(L@S3^C&#?<^Z$SWpkb*@IQ}}&pI~;nH|%xH^`+>&Vs8` z%__nwpr?#|l(WMUtOi;zYbB5n>*qX%&$0coJ&)xmqRdk;qfMdXSW=?$;6m!o;a+gz zdaiJ_qV!2RrzNGv$T!d6SJNXMCOP7WD#GDsjO5Tg;(LRDt`SiDV@*j^a}+Rdv!fOf z<_-;b-YJI;BbtT;S>0^E(V>WUMlv&@!6~7b?N)<^5}@95@{CJdc#Ud0)_aXHj&WL~ z7-xFoSP7gcQ$BroL_bYcaRW}YBf5t{JzJ*YS1d*FqeQ{*1w$3cOO%5;a8O=zJGcX4BH!L`M6uPw4!)HflY z5|jT$2Wa%)=`i_!bO=^2_+Eku*_X?!q$#F?9x5c?VY{oE2%U{(dYy*9?%!o);;s&s z7?*leaI6f?p2>jAYK~I%sevVy=EQv;Ezb9B`61&}Mx{~WsaO0@!!+0>lOV6Gzn)y9 z$dh)Yw+qKKZTHLNM-ekqB;I#XN|KtL)ec6}>?R+~W|zD%%+|4D63sMFV`uH^%?PX1 z%`^s8%FW@WzB5o^me_YzVLo9sHPP@c)x6WNr~VwVY$-f}zt>#;<9N9_kkkZR-LK$f z-CymTu_YE{e!BX>Il+AVx^gPEC!1Gsqu5NMU7Yocm97ST0cP=c^m&{l3i<-5o*ukF zmVUwqf(iy)rSg9qJFA=I`7b29 zc(4B;Y4H4aBt}F30|~WZ4`;QnmTw=jx?bV7N zr|{}9(8za30#B?>wz=p91oz`RHle@6v6$vE^6}MBmV9Q0RP*J&-e1PQs`=-7f4rFY z#Wd?xjfiTkQdS(s{RQANL4b!;C{k^Alj_C!r9-*L_7*)s_V)((oR;sEows^q&V1Xz zU#@7mfapY|F$lU~L$j}CyT8K;odV_cTmMwxwn`PvH6-AKztCF4P?=sIG_MRq6z96_ ziwl8r>o^~E)l2#}JBsEu7~0)1G-m}Bp^Z<|>fkWgA+#k=!0wI&7v8v>(3(TF2ZgJ1 z2fPMl3T3~apX<0^9>oo&dU&@upm{jEH{Xq658hm~er-E6T~^US@hhlDmGW7%a=QZ^ zl!p*3nx!rZU&g^siNUtFq}y6eE)mkVYnCu~<3Ycq;@@xg2)0*s+<)J8z8M;sWhvF` zP7OON`+&c|JS(^=+LC%*@pI2}Dc8udOXX}i9CnxP;{1}&bweh3Qdwe4dNc(K<4c@% z4a#@XBZfy|7`ne+=nFP{txk78H}Uo`<9WtJMKW=zhSlB`o{#*qpSUy5JM;aWkaMgo z^)&%YF)u?O>CdhaghCc!IzAUYr5x8Qg=r^*%fmR+{Hbyz=E0jvn#)j=I!LJQ+^!4ox%E%<% zSdbBcO}18Q&`~)rolo0G@w3#)>~45F-4u8Vb4qOF*46H=)_T!&njG<(Zd+TkddpvO zb%tvXjcnSP8Uvnq7)SetX3OE6GlT|7+Zac)5lB#Q2h_ax^8O$}VH0sSf`|;1pwQ1V zGJY0&G}GGBsL8x;CCeeWM^^jZ>rE+-EJJ7kM`fId{bNjPp-;x|`-00GA&d^074L(P zTO~4=jI;?rVIWoQA0v5F-&up%=d$JS_2NXVr#eR7F5J%7t!r>y6I$Ljz88;`Er=B{ zfK$K_T5oL55NZa0O+JAxs2auOLIgfb8ykbgp;q@L6DOhx>HkMhjuYXa?IziR>|(@% zakmU4DCoPZTcZedVMxQ>ugns!9quU*;bCZN-4kYL<1%|E&(PDks`moJbY?i*?&$B&!xHjety{eSudJnJR_^_1TfM#q1S&3Bo-Ey#^VIu_AK< z+*2wN6fj@MA-RViBat-%M(P17g9Q>4jOoo?cjTZgQI{BpsGL{JlU;#25bM_PvqR1g z?x9H+O6DK0Y1z%LF$pcMX$8%$A!MN!*d7#tI@6Dw`NMR&F~yaxX)AmXrTt-x66;Q7E6d;$=!LJ+ zzP+PuCi90Dm*L2Z=cVEM!p=(9+gnE@s=oD&4pX19XlFC!>D<>C585GtI_`1jd9M!X zs?OK!$v`y+g(Bv=J09b|>Ko%&0}cQLS_`73{qJoLC6o#i)yn(GW46~w-^N_DYb|)Y zVZ*K&5BNpfnP9yxBas(&IlV5YMVK%==i08jx9<6?rSG-SVI9)f5CBz}&O=_3|9|pw zU8a2Pr6aYB%Z^&s=WTippA9d@`7UUJm9F(Z4-EaoGm7a8yUdQq`tu(?`Gh_Vy3a@G z)7@XMVP%xDn_|~3N3@aJ*f3{;Lj>h?k?VVNHGC|Wj}5b?xYg@!V}fCLjQL)~aK39e zEG)(FU>U!Ys8lS`rC&?iIJ8M?(I82FW9V>RjM8z7EYBN zN|@Ci79y7)O8C8BR=ExZxEnm(d=7M{lz6LjSlEZToppiDvj6R{@H(QPg zh3IzVUPozj6DA~o;bLts<}3AnGanJ`{V4kKr0S_+0F|{OM;~V8vQe`&dbIfUaua5Y z7+fq(n4CLog?)>3WLsj_obZ2mT0{VIbeIUf4quLwl0ue#c4)fY#sunKxxg;-1&s_H+Adn54@qBKYvSbJ4!X@Q*Fo?7CjgCAi$elDXpyN7z~I8h!

%rZ_0Yn-R=!Ef6r?XbXENq>+HJNB^88yLVXji~KNdPaa_5VuG1{#3+`wBN3Zq%%t+_M&}WD%w8hkRUxKEuhr5xLI? zV0g+BfXXzeQ@bb@%`UI8=T33?{`xw!`9@>}|D=P-5{AKTb$4kB&Pfl}DL58=ztqVD zdh-^cyfMliI1m@Y0@uflNDDCUV(owfa$iEzmRZiqp*oGdhr+j_hrLvfpHq8Xoc6$N z_PXV;a8)SH)cRKUUnR7o6y&*otb(t%5{GQuRth0LI%$11~6ZRATPCHAb zy);_-rv(C*Md@TMwxmBw$JuB@kH*)HQZP4f2S8%|vT&UOzDOMBaeZM!D;gr|yHWaK zDqM$6_eVcpkshB1MGx?9D5>@htOMSUF0!5T+k$_s#ATsH_f|GWu_zt&WlFY}vN+{s zF00fzii$3)G`pv+H0P%%t>9V;xkcW|T|+@1e*}`cH`y=80bpOQX@MB*@Ly731t4_mW}B!hng7h#q;WqIdcjfpIe7w(}@LL{7{jJ@j3Ck{E7(ep!hq|?E1T4g{(MV`dzTT ze{O`Yd8?4901o%Wz0X9%upp|F?Sx`M7mz#7OdG_NzDC4^bVkI`CqyVIpp$~TfzQ`U zl6dB(tjgX%O~Skgp#@WDYH|Z)z3{w1so;5u$R-$RvpExt1tSZEGO}nCfVyceA#yna z$_d?jhPf=bUGe%V5^mcZL{pi7Px-Mde?8BQF}$4cDz)B9JG)XX7Nuw{4)N+ zr%12WkG_1#uZX41j~;&nQH^qt;_@pN6tG6oWA3JX#EK2=pVzSE{;%g*C2+L zVaOVi5JPvHch4kds3nxphyHVJPH*vd7WnjcZ~o-w<{>vt9zxW(-}R5*VCbkkUR=B} zx)=#mZ;iH^dE{2&jrP0##Po9=ERl^~+kH!kNn-z1C)Ac%`sPTY z^lRO>A4uz)gvt1XgI<>@1nVpTB?U~unOW{xIy@JIO(M~Kky+pQi?b}+1U6Z8FQO#K zY&bfL%M3k)j3xb~v{|^e$_&+OhN9xlclEp%uo7Ji|I)_G>@%Ag_2(xILfo|AZM@9S zO$*+}C(25LH&@I2LbZfkwN$xAr`yfhoG37+I z*I&`p{g7JOti0O(9zEwlD}f}fT7mo1zbaxR!!S$ZonT@dCx5J#VrrZ%(d!KnrnxOj zA_0Fk*tmqOJerXm<|e&KY21fM9^FvR2G=}P)z)u&dp{2vB*KjZ0|=yLP-|#J_wv#c zXY48$O?sEk);@Erf3{mkXWh3^=VAA$T39FALg?)W9$6i3(9Q#s&WL_^Sqv_nZ){$( zRx`dbnnpF%_6}2-N~5TVLN(3Vd*RDQ;rsToZ9N758*Al1EGe-U&F4{fs-Can>C1$X zH_;dA%Aj&_`?BqJlW_uzmMoy;&5T8-4r_SM=0HEP^dIgJG?V^Zw(*|=Mbo)ehL&Mz zC~rDPE;>eM63&Q{s}`=qvVQuoxjc4PeU-pyB2r&ws9~G;5{j(kV%xQr@xh;Me*^?d2iZfPDFlL5vkrU`KN6EfoP*Uv@~FnN&|kfLXCgu_ZYx8v*Nc1f@rvx0KVdB`V5PScSTMN+~DoTvWd^j z7$P5Zi>Es%fN{r|(9%dz;%73ZO~u?TrQa5~IyeF>n8MTKQznuON%)K41oTt91*z^B zZ#?G9@L@CCh@1xbvXRnXR2ycaQ>Ok0bFLz^`xU>5N}|8}Qx0yqxxS{pV#_p73{^r@N~ zc+&c<>Cv4r1E4z(f2-x2`DQv**NfNP(wpQuoTx!Isw*iZOX$Ci`z^OIqEANE6P|Gf z|E`SPNXMSY^S_tPn(-ca>S~!GYiPY%YuUQpSw#MEi#n+J>&C~@I)4^#8Pm`+5?!Ie znko_RaPGXrN@Z)wHtHlxQ-~$x^~J1uH%4IOu;tP4rIEAx&eqXGN_LOnDe-3;ZFrhG zL7%LvFU)@4_m|aX-93>|9=+W2>q@_HdHB6kMwwsh;`9Nh7yh*mVR4qIbQ8l%_{QBxk>&$9) zLL~YGRrR3gyJbV37gckcf?@j0Qs{7<6!Ut?!u@4Z)Zx)-n~&OZ)7L*LxrD1k#VZdG&j8$0xQdL9~zt(vaIiMfF{ z{Mp>az+yfxRlefOCcZy)bct{sfH_fiDQZYfJRvE8hGZ&&BzF|p&%^rO=<`3UyP2sr z$icz`_s^MsxW9o9!K$t9Z|ogUl9nW{YpKLBC*NVoXWhB0YAlx8AEzjaMXumfT8(|m z;5`V=fZdq!h)ub&-wdl2T{EP`q2~|2L*9g57QVC`RRgNBemC&m8#GgT+FX%uLxa1F zP?w&N#MqS|O%P8<*a0x+Cq`PcN}Og1e%o*JIX60tOvRGAb$HwGd!Oje%K=l8L!`!w zrx(V0-IG82(Uj=?`xE%kO*4h-{8cN%4> z%FQY!4kkiw!BQZd6bw&cgZxAt6%4zO6fv~sbXLkIey0*UmZjm#`MT#-lXZ~xhoE#7 zK2fI6Ya57M__kDAH>ye|xvXCikgU84J$_aF3|M_9 zwZ}+`$6a3cw}qYTNkTh`_)UwKSi7;ZS#iU3_7Y{SzS>**f}GwR_ELJw;?8>@lwb#( zH9tz*cXFv*!sSw>zy@)(XU?ZsZ9=J=Y*p~r8E+IV!kqV{Fbk;~$LTZ!V9vye-CLVV z*?8YI)#RhXYqz0t+M6*7?JaW1O~32(_Yf$ z)!8bpp~=mDO{tN+V+2IiS^ZY|!?Hzt1-`9v?dl|LJ}UFIrH#0}IGm^EhCsbU9h(#g z6!Ci7h&GV-(3DPvX6O9a)UsNhZRrq>YOoZG6-W##u$+g}!5e zh0mDgGrs$2MJz;lY0}16LOc1w)N$dKv?OKnaZ5{?nQNYUj1JGSW!Z5Y^84P&1(p+T zQU)D=RsVsrzqROC9ZN-j-eJ2z#6G2?a6-dExL za^hgI($&e7qEN>~g&7e61T3Y;^g-tC{RxCU)NDBy?|0looIktoIz{j)@lbia0H)PzPr!iv>Ss+Tu+LUYZmk5j8%sT&GA1t*Gkc z`03e_^t1hqD}(A6ZpGrBQf=LRLh;j_;@vlUZh{90X48zy>+3&aN>l$bEZsAaz%?9G zhgH5N#Wv^7^a%pl*o0`2b#X( z&T?CV#IebILEV(P_j8n^>hY#jj~RS>w;8nt1%t)w-l=GQXgmM5Eu~&jknP;xlpdE? zsq;G%xsN7Y6-__*WBC9p+616m1Nx7svBzX1zo^|)67yJzzT(y zvpI1t_+(MX+rCCf=EX-$E&x7DfUTT<O$WWBK?quGXa#45!lroROZPXx|80AW&xozQqo7<{EOaPx~9^&5s|7O5=bkD$x4DgGmhzP{Y z%?EdHAqIRveWCZA3*DYz z0f!Z2i*ssq)facZZ5{)tdlm}c$(1ua+R1d7=xlE%1!;ONb+&+~CyX`ww|gr!NTZza zsG`bysq&0`F(wL7(PwBY7D&(1Vc6JJ9(T(QFnuiC)KIwT?feWuL8(7_>>D6~Pe8>q z7I0&^1tJ7NPbszT)pO3}%=|MVtLafHz~5fv38(;*iiSj$He8|35=)baW0Gb|W1D(ZEPP^y_*n!Lr64HT!|Fok9bR=R2 zQqYQf-(H_Z-V_2TXY59m0R$$u2( zzx$EBAn@c}A!1-_F!70~%WgEcvv zhUeMe@<#EHRR->Jn_vl5ecLhWbmLM zN&&cnbOX`I>C$@+FM^k7E9duRtbi&W1<*(Bv9x>a z@M%EBJD(P9+u}>iuZ)@`P{tSz-Oa2$DoB;?xtKJ=ToLg3TZ6VQOW8!Z4wPy(xx z?4%elXQ&XQJ%GVDReCq%8AOqd-`VQJ%!C6LesS-&Wdf#?+mOG-e{nt{#*LW-heU6(=Re*Ayh7bF4UC^$~o=1irT zxO}~300^|>wRa?kUjvtz4CIIhyRVG|YuRrAd>h#afDT$teF$YlmbfE7L=r)aD5_{W z2E3;dMh6122}5WoI;gw9?JSo9;9Hp?PW~?QmzfkyE{|`;txb#o5m~gmAd$J!S^i?z zTF|}GE-(R}dNRu8fuMa9v|F8fEHA_4sk*t*7$B>ARE1BKA%J51+WZKBg@2@$RutH> zJgkXBM75~(?}G@yQn842yq!~leu8GCR}3@QZugfEMAej$QvgyM-Y8Z|(H-qQ0szf` znj3T%k#n32n^6z1{6r0m%f8+A(}6s=E;(5^R2fzX!)Mth+o`*0EhE4S3dA6mep$Us zy=Tf0hX=`RC)uvUUDrzb-gUQb1Rh-X#32@KBOL@y;!~HW`RGKV4(LwARYoWRfYcwj zDXQ(h=f;7K+r=`ZY}s$`Z+9p3poP3;!vZ>s991j$BeY0>^4t`>>yUI*LrPfvZpJFASk zlbw?V$MLr3sW9dE9Cz6SvZhKrR__<+o$31Sym|k^I|};NzssyO$$^8mHPGG$f8cfR z7x)II^)?nFE^cP(*rfnzLus>inq|6#V@)#Ds^yR|Ocvd;*SY2V_VSZ`fg0doksV)3 zGYG>BvG;|{O4BTOqhf22-GQU$jIqrFfW}0#yKbsb)MLCGLwrJOlk=v7@tKkqYRxio zCW_7P7~nkfdz;ukGH!^vb?oKmB4CBLvdNWfGPDSY|IKp;$wto{HPORI;|UU8v8_)P z@b7M%a4b>RmHBi7LfkPfZ8xL&K2SO$U_Y`nxPPdTf8!=#@}4vgMYH z<=cPi$6wH#x@pRhEf}2%18yp{D~T5uReQCW!JPWsr2!C(q0Sk)V9j*X%W!W zJnYV1VeiEp?bAUex(oM;-Sfm!TB`_yfrdDHYeU^jy&VU2uG<$)JxN>s%yW3FYsSe} zMlbSprD1-#Tz-bqFb~5K+CHb8AZo5WL+O&`e0TMPiqGRY`1*40--7YIh{5w(I*-ueZ^X40rbhHgpADh_7=ibhch~iHyV}@25d> ztD?-{YD*CJ{tBEO=PpYun%dDFP%j((G*E%fV=SR=*`IIfyxmdtJxP!Y=m|{E%dN^c z8!GHeKs88UtwPCH_k zF8j8|gT%3CaBJ=h%;vFo)RU&)!$|H+s+G%sAf=tBQOUT`GS{2y?SY(&)zN5uNqG96 zc+?N5c1se)RGDI>OMHd$;rsYwvjmwL{SkfXTJ&?CjrlHV=}*#mC&qgk1ouTFsAeH) zNwfVrZR}mH&fX}oAZxD9epDrrO-lZGK8b2GI`hf*A!JPso??B6#qjC7aa{5TZLtj@ z?zsI&7~5|9woQY?6ITx~PT?KKHks_K+?`20fwO#Bv`s~RBLR|{u5rxTNI1toEF)`H zV>)WUr-y-)yw{SN79PXbEwqC*TsMOlHgVQ%=@Ii2wx`x;sec z+S6F=Uy${ru~xr`$@3e)x0JQ?Bu)n7*01K#P1-(BULaJQg^6rradg?o>mQ&j|1MFh z*WHTE=8D}{Q!lSH-15v8jZIN?HZ*P>nGnNCMmTzrY+^Z-fBvFsWPWI?iT})+KUZgj zh95h5ff&&4l3~+9Qi*uOAAFptV1zF4DNK5=ERukj(q9vLTt7JAN-tO z?QQ~GhA2g~>T>8dPr}k?ZrM0P^}9mZnrn#tUL;$am+pT%_|iJUAmKniUs0)N+&}VE zA{_qm`;)#AzwF{jdLSAYk8|8FUBMF1B)cJUl+bT?O+Z?G#Fz(bfdycOpUt}y2@V3GC%o#Nhw(3eZ7G@hQ@I@L`@>iTe>=$ z(D>y-ayc9+E;R95iL6H!KyrH+AG2d@?UIe`~J8@tZ5D)w3F*UtCa>7da^ za?QujZHwjM4u=0oX~G=upkd8v8o1(>Ci7por-1J@i}Ya*PvA&rqjEmcs`yGYjl?3F z<~*AO2mL(MwsV9>f-ZJ~o~P`jYXnPTkltK%hM+r40d;knYdob%;b7V{yCGDe(P&Vc zapkr8M{^=^_lm4@`OXuL#+9FVd!9+X_@g8}^Rii*cDCD+E{J_HAKr4%e2*kx0FuGO z|LwyP7U4hO0U=(dhAriP1>=7TL~LH_u7JPR9=4>rKJ@KOI@wretp_TTaJH)4+z6=v z5678UpGA-GjLATG@c9)fje13I1kF62+~m}JmzHMVvl@#rtrw8CoQZlXC_PJgEdy1^ z=KEqdNk3m^+dD!maZX>Xs$OyOeS|_nhMuRQQrFlNAUII*)ak6lxzOlf%;ijd%VPB; zg~z2XVw5Q@mNbFznCop*+%iu$P=7|lFQ=!)M0DU9nW629*(jf! zi!`UyMnXCufk)J|)&ThQ`%Mw)Ao;3f*a&BPTRPibGUsSYPs~~j%U*Y}s}luv;@KBm z!GWnt|F=Br^rg<1zppGeLBDAb8Q#1Ey1X)51#dyJ;T7(iv{0!s3;RZBqty~Q8vEOg zytdvn)L`UStT2Ua>J9`#b~C&VVlRL*p|cEc`&6( zvug`iRzj9Cmtzlfn6jG0B~Qnz@QQB!I$hl)KapdPp+8?S(ijb6D_$W*HXN8M>C)Pt z)0xCWN@$}T^{po50ynTTDZZyHr%A!1S$XikP&|}*7k=W|FM7YEa^q5=D&~z4g_<=CtSek%1$|zk}VwT-&=W>rdN}zmDSub(hA$>fj_tZ>anp&2uHig#)At9 z=eux^?b_mTIkP6q<$K5PMGI^)mI*osz;k4YpVC~#4dk@R;d!>cI;PE$KOFfGe;3dW zaT1+RYCvsNJD;39*CjGO=~W_8#Aw2qVhKHdjIqo^Hj0c(6)_@5o5UmsvZYYFwj^C> zRboSWDyd8NdI^D-K8$ni5v=TcWIgxCm^_gI{84R7&*UUmG2DmNuzKQeJAPK$ZEWt8 zl9V%cfc0ZstHSoLZ2@jdqbW_S52h43>T-797Cb7wo+;fI!0Q9h0RABSnfNY)O!z>O z5t=6uSY;$*V!PVM;}Sq^EloVh)+Q5WGf|-efAz(dHh_vchouOf38z0fH~N!vs1ce2 z^J)nE6qfrVWkIA(N5!PZCu(Y!vk%)nY+7Ww=erMabGx`JLH6Fcry`c@f6FF}wNR_q z-%82GmN1PaQFR7y1!fz?veTP~g1enadlwR_caxoZwdv+VlNO*xOt{w0y(#yB_x=gI zcY&pHmtin$Aj#k%@KJbESnXqY2t0Y|PvFr19=O3lpW2_m4gM9l!9(EiQ{aI!{0SVY zLYOzBm&?&pO~xnz7djHK$soM&Zouv(-}-w$UYN`?6^H&26p0%8`EuLAk)Uig2{d{h z=tTJ3{|JlIv`sQNI-ase9>zsfxH)z$Sf}dztJ1k-5GlKId8N2E0zo z{l6zA&1_P!aaym3@w8z9bBSC8uipcWh+VRS0+RNH^{n-1TRG1LlJw!050L|&-Omve z)LegTvfTeI+$_sgG6;Z1L@rgHCe~2>(wfm~V8XrMA55)m!{7!PHJb8hoxw$O@vki` zg~cC zo|-~NGs3p(T0(Gdw{^yiY|bB>nU3>DvP#pJwRH0lXF=gA>fJe!$6fqNDDG5)}AtFCQsG{m^>Zd1mntC<`O3}h-Z#A1l0aMFpEn| zkal?&&!-l<^H-b4w+%}qy*``Nxx3hIUuKe!w7(wYJJiX&tNTzlba%eI*?D)|$#-{n z-YWyUHV<*MI`P1z_P9A@;=6%4q~2Z}j+WNK-z3AR^H`scXG`_KmrDd@lm=5qm z$}QfZBo}~tE?#nce;IoQs}Y5K9rU|AJGqnj{Xou6em{^`V~~l5bGoo>g6c!_)+qRm z%+oH`UNmi>;d9ql-;xEXU$lN=axt~|YKNj(a4xZKdb*tpn6={mWWLqX5c(fDe!lBD zC$cePUim9Hc%gDR8Bt;qRy7$O+WAKCOj^&U>{eBsrs`{`!wgVow{}$emF-i7Y0oU2 zNd~QLmT9WOXVZWD5ZVrKqZ3QoC87Yr2hKAl0cKGSzxaBg1*;Z-tkMZ2`>WDE(_5)>;rY)5;c)ZuqzytSftrCU-TtdwW0&7HQYpl@V@2uAjC{2P2ib? z9!c)eS)1cix?BtSK4s^dR?WF(lNZG2(>VNbBm9;E6ZUG`AbeXeVI5;^{OZ)_bTE>n zN3#BIcd^vB=FZCPuM;0vG%(`kKy&sEhp8zz8~flx^dUQr%gxmG^$+(0K+b-r2{mv* zVrwqPYoiy|sFQ^Js=Ta_wAvrZ0h?QApK~JLvs+a(XjWD9wqFpUJ~&q5wVppy;w2T@ z$yv3WUmoV9;pu!sm!thfuV~aHo_Ob?E3iBa$!_Qz%?QC`ALsoeR|N(3^YY4%GfHKY zP43#L>TlsT!?pRQ0CT zqTG7XEyf2Ns`#j@s*B#l?NKT9cXA$O85XhfYI08ez-HA?CW#EQ>xlSLq(G8~x}dIf zhKLI8HZ&np$qS@U1#&>q-y}$r37?b?#G}#H=qF1hw=8jun}zBpp9#p#MMRuQt_)EV z?u_xNIKNw7=jW~E!)KYW5)A1j8SmsACQIyeXA`+`$?oKga@RUX7$CH-`@3@y?+|sB zxs;$Z1jj8nOawU)?KrL^G&P6VHM$7sZCfMrO_Ymb-yS zAu&1PP;K*TzT?;Y6Pg}pWxB+R47GhlHKl^Rn|kGlR+W^o?+!(jzDyLBthp^^#{Y zWwBktQp>cRt7Xza-v)-c z>RGVnr=hd$baFW@v6{lPt4)@j_^J$K63&Cqj|oiLX3u`S;|)DJK<=uNF(z%$!RHez ztog`m1;f*V;{(rJ#`rx=M_$o_C@k+e+-gq&gbk zy!=4Ku6f|bXg^0q6c&EO&Mmv0y&ftY7!7G^t!@{>WQlKKiKQkS*Q%lZ#JEeM)}A6k zSJVrG*;lv=>3#o!w+OUVS>8$1H8^jTaNeFwbM3)->snwSXMO^P(S=3tzgpd+kHElq z;>7hx4cH@oAaXMH+Lu^Ne4HdKg4&RVoHQ=z$SKH)6wN9AsdZprF70MJCMgUGBJ?bB zb&MA36f0k@Dq9*P^v&A}f+LBTEC>|sGVxAl(T#juXOT$p(ZZ=mQMG9~HEkbVRkdVqQS4*hg9TTq5#0cy0b}aj#aN;-?N)9XcJ3%$}Byue0~L%F{Hzd}Pf->Byby~_%8l2oTtOQwqgPu{sd#P=O4z7!x zbo(?G{TEiq#lh|mxk}ZZpXi?NW#&U18RfTIaHp(YCHp18+%kE-I>O7UROyjb8mxA; zg~)A6ip;G+U2$#VDa{({302koTL*P8*ABV0nWspsotKPni@pv_Wi?aYH<|}lAk$q# zRsLcsBZ9h1$KZE=G?dQcCs9Go9i({FqiVT?@;0k|@B#haPm&9)>|>7m&x;-5P#5TDAS? z_*(2B7WrbYVUf=UsAAk#^?)#m_Vog?^$jg$ttv9)@|)tR$8oo6i>Fz=x%d|*RW0+7 z06qJ4R>>CfBpucyP)JpenP&qJKQ}rp9lbR;89Gw+4RT1`xXA4fe^9e3wBpj68%0d}Y9*ywUS%i^8B(vPe{t!|mR+eKY3 zq!NDRKhdH85|Mn4^JmlQ+EbF1Wg|h)PF}q$8YNz+#Uy?=LFpAhN;*JFh|cN9pY}^A z#sm?hA9--LP%w|}`j9a*ay4OTyde*@t*pLml=p7+7eu(`4TbB6?ZtRr5l<`3x1&#U z^m3jNb{K8N%A2VHqv*xymcsO{wxc3fb{H4fU;_KwM+Ggo12rJU0mW_62aH$Kb^iQIQW_GjQLhfwZKyG zY^7G%jkV`R9pbM2GBh?!Pml|1l`wbvarug7mekqH;`u=E?N(HlWCA>vjC;pR` z)$yQ`k)+SdFE<=l7Pq&~r=|xBXP!Jks^G!zOInjYw^SdPp0{drjJfEOBvlFO{Qff7 z8dWyu=`phaYfnGzvsW)hTL_6V>xbmGBsT@hx>p+2JvJ==BXns(*tG%P>hQ6y}^p@!29Dfhq5NhDr%sxwE^wSu)FSFePtQ zoVfVNed}e7=anY)!g;-PLx`0}l_O&;-2K7XE6WJ6DfGt1$|^q-OVKac1pZY&d2_uV zR=IzD`;)M{O;QF@v@-peS4+@g@4FlXKM$T@f8>6{Q}4ut0DbkHYx-&f_9+s_FWio5 zi}sEa82HSO1?@)p`K(+RtZ1wnf)Q3iQ|?W=rr6Eq>Wh zIe552U8+Q#)W*Rg1~6I`?s25N`6Z6D0P3Q$;QkBBT%1m=e^amsAdyTxG7);$pmk{&^lf!r5I z3wo#!>9*yPoVvHVB51E>keZ0uk(=q?>SB+7LO$^NXvN2d<{oMNc9i$@(2+$-lXlpq zL3}c=Am|qON<5jl**4;BhDQuBw0OISvFEC=iCBJRlhwo)A(ozN-YS+I$r}D&38?}6 zTJC?u9k(v}6!4!JuEJZ4P#gQzt;B-D%?Dr`R$`|L9)vE)3mOMhVqV(U>X|A=wB3l_ zZ&9igBgEF@+KzHB5cAj^v;szUtja^sYYLBHOGzaL0x#l6tUXER6;y89VY~xwNfuZz zX9X}p&{Mrkn8gfm{PwkXPfkwr#-tr9c<(mNJCnmQosTLhSb38W-li<}idfj8-L~0@ zM~P(enNHRAb`)EdJVQ5@YD$qEsxO*um*ioo=72U~nMk|LBFhl22qAw%v6<6b2r_M# zK1W+{c6jm8m(mzV1_)_dIG=Yk&x?Le!O7`moSY^`)SZp`MQU~iBc@Vj7(p1l4=F`D zpf{~R(_;F7Qi)_rF64HyI>kU0=%lwwY`3RlCcwxNewgRe#Ca0ZaA?E8V4I)uAh8CK zI$$pu>s`k2^SL38pO?FsPTu@{42g9j<1GZIg=yN05I1cY3INN`c($UAqOu+(IPluv zaW3?=PHCvN$35Xxom$ho3*MttYh_Nzo2@p+n8K6B)(-2Ax*%g6$YQr`(73p0=71L>%K zLsLQ|&!-~|GnS;TQyS$*d#w`MFPJqt3^(%jo$Y*U|(DMBT!<17t`nu2JF!nO+XA|8pc zN02##Z#*62J{$dJg^P;W`A|S)Yq#fE^3tpI=6hpjZ0*x}*d#9fwBhO0OwyxEQo+&S z#_By53dkpO$u#Rt>-=DLq99@-lD9>6tNGkV>1n!Kx8@&I@;uU=ymOyOo~F;kIOYyi z_TXju`|LfhURuQy)KHON|Hl_EGc1*l`J(OaA4M>j0Zb$UH$`UX-pIkEJW|Nvu3Ph~ zH(jhc$Qk5Ad6032oTer`PxE}L`qiH!^9_i?gzplCnTmR$In|!)x+r>&@#IFFQA37= zJonlm@kS2hB~gua+^me>L6te)I6)E-o7kRL`)VeSAD|icUyrA~=%wMmE=OF$!LOhx zY270Kbj*-Q=^zW)L2`ug%$yVXX@R_u7_?5O>x08JDRkUksZSs3vR}b|frTtlx6|{l zE~p?8Q={SI>vE)Cm2H_}^G|fGF58`;A_Ax0Ba<#V1<2=5B{CP}PCE}(Jw5jPU30Q+ z^obj<`eh`nOO3`$8$)O619C$Gz=!~gP9Gb67d;Yl91 zrt{W?oYdeNJytUkI*pahssh@x2OXhEcaD)$H4n0E_SZ}*Gc!~3M&EuQccD^4)`rKc zDdxP_?Lx*H_mLOJF3Ou8)ttV{OEmeE#_2}Dtz#mOe?Exf3O-H!>?)uDi7vze3Xm|C zy2n)6bId09$#X9tY(wTqHH6)Ci8#Rw@G=9aE1vA2@{%I-BGedsgjsAUM)90-8;7{V zL)eMvcxjpYsL;bF)LAbd482W?{n}q&h0{mfPFvCX=W`!KrDm@zF&sk-n`C);=~~HW zTY4YqxIG-HbYBhu zaSdMOIl-sR40V(es`v%um>_6yO{&8PtfD zv+3O9rlg18xYX@5fuIc;$sjc+mKsVJ~^clWmn7LbCdPF33J#xveXwJ4;mw^cW5KExo!0X zK06(CkF&V=>HZU8Mj|%pE$NFqG*g$f$<1v}ZJKG@p9lCAsd_kDUJdG*WMS2U#YPsRnfpVA?vd!X0mmBzGv{KANS_=R&^jGvmf~Z#^&0D6Cnl1nhlzi zr0fq~t`Y%4qHLD}Twd^I)v=vUEJ{rM8G=*C?c}Au_MXV)G-WEn9n& z+wqs6u+Oz|aDw9!pv}S&7%PwY=uel*vn1y#)Uza;Gs#Gl{IrxAvfSv5ogO+e8E1%V zkPKXp7bPB0iWemrU}-N>vD0PLWcImqiz{94Bb*DfvhrrW@-y*FOXCw){!8e?Be25@ ziH2rQ9)7@p?qCG9<}*-S(|lGIE9wa2?O~#~@eF4u%Hk6Jf2oC{xct@c&XpM-F9ii# z7i-gBEMm)@74M@W$%IZ>K70gOSR<*pFI`7=yi182rbv0e^hr*Kb+6@(dO}q=SV^yC zfcj|GB}U8B_c{c}QrWyULr8vh+gM4}@z`E!!)$CcfiP<;VLMqtD>pjIrS-07L6;zI zHuG0b{G$3UWP4M;YDu_Pm>T-lekLGi{iT*=yL9X2cs}dlT;c-aEMb@@?6pG!Z98qr zoEo7zVK0N3xY<}4Z{&6O7_s0%^=B;~49umER1Y3+S8sBqmv^RRO+>K?U$|K)~4O2t|W;)j*P101ux1GLhYU^PitR=T#gU9 z{9Ij%P+jWFFAAsIg-S%oy_{Lj^pmt5vnsgVMKX=74xhVx-f&|-; z37gDl>UNvbziy^g-=5B6 z?5E20JlC>25~|LYt7IIb3H=Y+63Bz7CB?X_ex>a^mNr?Hv!`$QsR#8OJa?;IsQCER zNL`Ej*Tj0GAHq7LwZcJaB~EmFrexVk^%cb!vX2~rQrlp^Kqa_cO1X71_tv$-Q*2r5kk> zOzaVH_EM21YEM^D39l1)RT>v3X|2vH=uWOjpH2wcKKQ6BqeLupKHf$F)DPIk*CU%!QY??pd3q>`B8u{J}6be z3la+jEONNCC++uES&EmsQv}JTntufIZ2@;In#_z`B~MZIpG|q9=3sx%XtVMUh zSgS1Ug3Q6-?XmVx)+7Zm%fxnC?b)iAdflJ0iPY-}Lu3zz>qACJ+og-ne_Q?l8O4cU z(D-R%XjPDxN?zcO2+~Dhchwc1L&pm`t11*LPN}nAnY!7V!r($eX3WRJb^~A&8dj7} zsy@l#+@R(IGhZIY$)AN2eCoN%^4KAD_G981()DUCUMe>bVU20$smD(GGek{X_6w=Dg(fnPU$g#6cphAQqUau+eoqS z6Mz&wLW=Fuayc)_{8AMW01$fNfRHFC-n?21CwNiF1hX!=a&O`SS|-W_o&wmGu?AM~ zU}ZSLOSANixd#8>SoY@~m8_pBay28obRa{>HMAEhm3ZwDEcDu80N0CJ>T6La_S=D{ zQCCtn36d8RUs;KF3H|J4ctk1o;kmX1SXPop{PAZB#Ij0=REB-Bwj2bJNq^%~&u`ac ze4osxGNh^A@S)RmO88okrn=(8hb*N9XW0hNs6O@CBvr~SFE{GoU@dB3xb1T9gos4L z+xtHY@fgDx3;>!U7Y$3cULF;pM`>{Rt7gg}A8MpWYUa`+JqBZS?YRr+1oC^h&+Ttl zPNO!Hif5O|aAfwW$b(zCTb);KmqC@)+p!t5&<%&4rU__8+71q?`LLLU33%O-IK~i} z%PhpEUl^bdwG61<)lrI!ihPBXG>*spuYH%$*$uNbl4-LbwHH}-(Y0XjhQ+3S zn!WEV2Y>t7`oM75@s%uz zAx`B$c4xdY|AUy)=xC2bK`wV85fO?Vz5kFjJF9pa@0|z2O+RJ5ygZ70Vrj*bKb$q zx(d?d?7q@Y{vk_ScZ86EFZ{Gxdet^*NTi{+&ku4qibvv$x1tZ zS3$@q>Jw7#Wr6*nXPpDGRMHyZ66`by>Lf~RC-~(bD=Jka-LEy(;bA-1b@Yxj?KiG; zKA%p#tC*{I)T8&GNH%z~e@JX5EQylmhSY(R$seA)c=c3KwFylBFt2*h-ZZuM<-A17 zs{_sAtgsUy77Oa>A9WUPI~dwhg&DG)s15~);+IDDyf0UJXD5?*d7u$U8eV0eB4R5f zPP50T)bRy}V(fD+S`CYlpYLIll~Jq}rIMx$Q}#_~i^-P)r0~wbK*ENXPPy;3G>g0k z>7V-w&E0BNRrS-AhlFXQWfx!gW75Ouf?r4-WIIRpjjJc}`fQFT<}@2etLIZi9&s$6 z5`jk?VV*D840JW=#ZR)ak6I}UAsM*+#oxrld^!DU!QlS^F2d-D`aM zXX?sg^R$$G=CTpj3m~TKZ4${#=BCO*o(q|Nvh*evvD zlMR}%d#u}@SR##GyYq~OB6G?SvykwIKT#f)NKPX7#-(n@#&Gf@6H)SmDacKBn&=%8 zYoyM%vuRZ&6($_NE18^i(yfLoAeTuxRaEX-ndqhWKfRKzvK7>1A(Io2C! z1~f~B-1W~N+T`pkQx&f+a4i)DbZYmjR*hYiT7md0cBLeOyxYTx$jk z1kzH3-@Xc`?+9IN1Ra!alEwfMd3gspt_K0g@&3ZCdh63|S3_CS9)N=7z>y~d(@Y3> z0deFz!+A3;k3`DhWO7>mp$^7m%8`^auE&$@=28@|dMf^gg?s{O^n%omK0y^cA*#Xt zJA(M`P+NjRWJ$EN^3B=k7O8<4+Hr#9Wat3bT45AhaM2~v^XCYa;JSyCQ+O9%byIQ8 zvR&{n1fWn1K)-KXI2?Si0pQ?0jE;gdamoXZ(PPO5x-Sl2ly=cd>pS{EP?Li?BoqgQ zdg?b=QVui=v%>0sE}=?(Pky!syRleqfP>|nBOZU03T`cpkUl^ljXZLeEjfB$GORtx z_JeL8gY43KWo-qaDo}`NFiQ#xjya|~+ls}+>0~mLBVEA+$#OWk=-vBQ!RE41Z}#BG z*4J!>^_F^PB$5r5|0ZJ$6E@zeC&riduvSUv{HTKpfvvAZB6x@x65+cvE zGZG@%+hYkWD2+8T1cMphBkawa<+2+Q-S3^Qr)7_E$kkATEDaFXbz_U-|i&YJnybR|iu&8AGZPqK8gPzC|Y48t4I~)cHX}&)&mTHXjZiQoRt2GG7wi;93(s zr4Srn02E-q984>^?cMnr*ISTj%D$HA z#671Cr|FASBjhF2pfuAp)HTy5YbG_9m9T5351nP2h}yIP<|aO95S$iz3;X&_g!tydf8ErRO)xQ2d|d0Se*$=WRIAs=<_(x&|Tv%t$MPO3mGz3W<0K zJ>=BUEMqSFM6tFl_JYR?53hI8P=LDHX4pwI|2j;Tiq|5DWAsBMlA<}2AqNsP6Xg~0 zVVHnds@BxF^D(92e!~~UhA$r5u$btwm{1#i;YA9Jp4Vq(jYQAz-bbAXsqN%R^(toG zchzT4s2O%jEBK~2+ZTF9OmU;`PZvN;1l5g(R8i+DgtCX&<=>|-FHVkP&|UKJ{--6G z!ju7$o8?`9!YH~#8$|ar2#qIzHHEiADv5|DWzhTI2?W{hH!LHJ+W;}7l|f9LiOsKy z160;T$d^1bG@Q`67L5G~0AsY^j7~bT^HP4{&H83Qr2#~qFnj??bGTG5!}Gy2BIzOS zB9m+&YCcQ$S66rB{pp;A?bFQ{FKk@kefP>438v&?g8KuYXdUnvhJ>lw}-cZ|$;q^xf~ znUW${8AvfH136a}6|_wJ8vzyqlq>+7{_4VU>jVnRtulaH{z*IB3dC`14t4x4@ZMSW z(SV39|D*@@7rTznMXAC9e=Z4*_~glqrN`mynE_tA33~wGm&#qZDs73;GGG0aSwWuWv)7Mn z9W*fIZwZjBhOF#wJWGbVECk@^#92)K>H;X@@d^1%a@Fu&f=-}RYa*5+o_8*1PmJ|M zE*sCv54_2qouFcC8yBrwGu3{-dVRWJ*_ei*xZvle=@17-KzF6sG6K3QVm9LT6I5fg zH6vL^P$OdM5D(={poqj(!;Cs+K=2IIX9C{`Ue|YG#PaDUUIBN2PmMDEfYeDCPKW@A zAHm1u9J$6C51XUnkt)wbD#fWAf&EVhJ(uK=cIRbfCHqB+7IzI;KfdiL)A^SdRM3F@ z!Zd|fa~@UoPeJq&4S)@0@S^tC`JBeHK7luS6j%hGC%J(PlzfgQi1M(~OI-hamS=`uBH2s#N>`OQPn47(0S~nH)>Pw}T;b;*LecYq?V6MXfg;yxGGy{CH&Bjv2hDd9}jzNXE8#UqliC z?%IM3%q8=`xFFlSpmVI?Qibtrj`Z{tFoH22o=}!CcglqK(k0&47tN`)*H+PFhG$)V ziVey%CCH`uEJ8!dlc?=+m~mQ)6B6}+hbLEp1=d(c8==NbX=b4BCzBcI%eV6;y#+r{ znCe?59v*qFQc!@5bEL?iu`iOkeN|K?}FOIHxje4kVSz57h#CQL4&>ktdG9h!*qxlEQ6vt4>p3X_c$IYA%oyIl-C%vd`toN60I+;5vpPOlFdP)9_~ zM>`ng1%8}Hn^8v~o}2ti0SCnHZ;DVhF$_x@!}VWDyAP0d|6}?v zH$d9s9nyw=CGGJJY23e(=Ku1)NW1?lY4?94jp6zZY1})c-T#%ehW0O#ruQppo_~;L z^9|C3dFB}kc|UH{@e6y;<@0`=UYw_oK#;1-=g>r;!!kf~0piiy_j(Iu9EqU;nA|{@ z)z8Fxs%yxY=1+kXGJY2xbk6Vou_l??ZKgTdHYY2PGv4%fyMpBks z;wfeEYeu%lkJBP0CV$|w9tAna+$h^Y!J1=S>OKd)T@^*I{k5gLnr z+AMlh&NcaN{UXHJVB2k#Jf0ENg8&r|PSrS)+-cCFjer}KY$M;fmbElCb0YQ$K`a=m z=JpA>Z*Ja|XzFnCYaU-*&xXj62=F+`>x%I(S<8;t`&|+Cd~8<0;LG4NLQvqr$*3ba zJ-fdA@e+?!c1ql&BS|~5Fr1;#zc~ut!QG{U$*oG&}I8dS!L6Z$4s=u zw1@Z55zxX^#N)~ZKbb4lmw8y}JPW2M(qts24G4c};Nua@3KZ<$m&Awr0QV-WG1`3J zK%b=nXSN+^f@B$-da6Ae6b{lQY;Tzy73AsPR}iZ!jD28qV2m)|r_O}A&%8WGCJt)5 zvTtk1FpOl7Oq{{V#(Ctxb84uoAA8gI zA@VX$F&&m#I%VJymfAcygT1G2BO1x+N5KE(8+tIJeWdzD6qz`G@8krqDZv0Hz#2s$ zbY#rSGPQ7?`DG)&wbv3XXiXftz&R;3wsqed80Zf_*ufcxFf7!};m}44i$Y~hILrwv z#cs^(I33985sY7v&(_^XaQN^A2`&uT7>H{=aRakGwYbc$il(#=D;2Dn^&7)9!+ClW zVS%%<)3awWYjvAzE0_0(`wz??b?3UHc-u>Oe5E^*5uzR1uCyoZKXxCcrpfo2} zd;XQTT%X@`qfOAk*{LJetNfZ?!$bG1wqWu#-c8-YqVkMFIxh#GO{Mi_Sfitjd@i=3 zrd@QRUHOru*t?Fo&X5v|94T*OIx>N!knax)AAg&|-bgHkT>1coDA!S8&~}VcK;_6F zWu{Vqs$`a=Rz-U56 z-6xDFZ8nehra6P3zB3SEg4hVnk%!AP4l+9`*`jW6$~0vlr%Gc(Yv0ZfPYtwWI?Svt z%nIm6L>Bix^l4MI1?z2HhTk2~4(iuy3hC1fd#3a`rC#r;zHG;`Q|qOh{G&4PpO^=2 z*IuW5Ea@>A4o&2{DVW9nlmqh6fahjz3LA{7J~BZ~iOLN4FAACLPx*GE>E{d0hz7d>Jy#zhIn+&m1Xrn zwvi2J&~{TmZ#7Z?^JH^!MZS6KC}wN}vgzznV*A0ed5#G)P6VkITtTj~r$)Ap&xWB= zR|;xXE8G~IqQO^^XWCq2dh=O@B8FloCrGQEKN>`~`46|O%vWA&-RP1mn$F)ggDj7J zM70mbQFCs?k(gtTDXO*)bbp3dO?ro7jGMQ)=hl8%23=u#%Tu?lIJD_$JIe&mGICOX zS-BwZv@PEjfSIh`YRG$9w7y-w9nd{!HPl%#j1hO*c(olRT0v9mn$lE!Ikhcsq%&Hs zv^?2Gcc<+inHrJHkhhOD zB3mH+Fb&$Gmc@s|ojIbJOr*J%CON=0#YG^y^X%(CB?gB(FAiQOFHIIi3JZ>QE=-fI zwgQ`wgUqTmN3_O4P*t_!P@ijeJrk+CPW>>5dIYq^sn2^8RN=mz9iUxVAtKR6f|$Ff zVyQ?v-)=4DC?wU;_Boa5ZP$oLTdafQOzygLuZd9f10Fdmv55(hVJ2>xSG8x#eT5*` zP8oixM23{brq!aaAhL%npF`(|E_ncBa#KE8i#l(*$vXA+wH0VXhYKSZiZy>hu9OPg zv)Z6%xd1Z|h47OFIV_VE$*DN@E z5V`ZFe^FFs6X%QTEN~O>dzZW=Msk2)o$$=E-h55!%3da$nU4$sCBVz;EQ!6W_IjU3MzzzF4i}#? zg-khmTe_1xSyreJy^lHE1ZrQQ*UTm{qL!Su_S=%F{m78jf+$)3SXn7{N^)K{uJ&U+ zZRLzrvEFCPD#G55CQebYoQ@{T0tqe{_LIIPpPyM0Pnmtz_tVboc*f_N`|Ag4J8zD3 zI3_yv``I>r6t%Du4A34qGBL8gC~RrUM4D|rUU|BRRgEV5SZU+&e(spf&uk)0Rk9>8k<`?rSF5hmd+zwz)@pim zO}+Y;a-WY&J(?aND@b-j_v?W>p_Vi$+Q(&?9mCA{p)e;u0SE(nm2Cda=umiU z79mshz2haNIUbQVH^-(Uo5{=X9W4<{$IN$rENDxe5%V#O8}=w4@^78x-v=k)my7{S ztPh*nEGSp~YB}?D;cGzCr@t^Mg#re;oghQqPAf(uLK9e{Ii|v)4n>q2)fwk^P*Y)6j(=pKGC+PC*YvO7X9b4TA{Ajf`iRNUoSruULFS#ry@6-I2UH;=6fh{;nS}UMy+=2zAYRO*# zFeIPvPVSt1F7f%I&8?U3#OupI^|Y_lR#VjoPngB)569_~DQBXU zG9Ny5fCvp(#&d!V$!T7twg|w*hcPBdj{*>A+nvw>;w4#58QtkJwl!PE`th?v4ukd9 z`R&F2jYT*Eg!e`Z4}WQW`EyL`RgvrJ(>A-TaB|-ugkZW zdRJUHF-NP#DxyLLxtztAA*Oa?YltwH&s_^u$D0IOF%SCX68+0O6h_zc7e3l%l#1yv z3hQKym${%;*2&x49h;Yutl}{B8cj-;QGOl8eld_T%agHiCJ)6?x9gdSzi@cLNyzyR z`dvf4;X9lwaR$a#7Ye#?ndXsN;!!gyeZOm&3QvCffOh9i|023aO=e*fG>=jlgk}^P z8EfFDWVtfpM+Fb}Gna_g2pz60*5p5|)yG^C`+ELSqjeXu}z8A?#}#&i**(rDfIc*EcWXJylL^Td6u|f z*fjQmg2}NJexP|}eNLheDSVT(*YAF7u}`gC97Ddy?BEQy&E=j}OaiSdZH zt50-C$2J}gDl`(8;%K9N)VI{@#qw3!^!?rdaBSUAX4lAO0GD<0QsZ~(oAh1Lp!G*T z(BBeyWAn&oW%(dVUw?}=Z1NLn25)9-&Xjznj8N^bFaGmMeurZW2bY3a60bIemXTVF zp2OoF8kH|R>05GQXZgy<{l?|3p{L9lJ881Xq1Zq8pMT?zcg$UQF;ZXn<=DS_Wgshm zs>j5~{_XAYFW%~JzeZz(z`gT}_ox=*R|GeAfwrEBS$q@!wVS}*Uudykto>I=O|%dO zTX!F+&XV6OX7Y&}W<-hQqs=yr^#fQ@2Kv=9h}pVWS;TsswhUsbPFohSQs)uVx1?R} zm{J)CEUmJZ8~dv8ROcwx`rJDc?j3;yN5{_8!P7g!i! z?7Qa)v*at#?w+WRtjNW>SQ$i^uV_qPzOQIp-!tFJ=)Mf!%GkbaN-%G3F(sHk_bYKF z9AoQ5(5$d$OxsC4G!0({gTGway&y@;sOk9JnV4K{&99)vSGMl&Hx7 z@lO}@S2p0K{MVg{1D@SVITFDoxg|EXQCB`nVjSSn$taI_SLYGY*X1i3)wk?h8Q$0A zTN&90_uUf8<);J-=Q>e>LAex^Xn|aLO0-BW7bRLKca#N%h5`EOc8O$jeszxa<^n6U zRUqr1BZzqcUch#AEFMPx1fvkqPpbsItRq`u;^5CgC}(|n7F1JRtQ?}hE><2!Mx31)l7VluXe(YAr%7hQd#Nn;Y zcc>^lg8gb+U=726g`VC$=2!@oZ!BM}rVxm6Mx#A_MI!;zUo@hRixMo9YeWea%RNO2 z7R*(p1dHbCu%Zn0tyoc(`tz(PJ$)utl!<;EE9!wh@WEi6$LP+Ydb&8S7y-IoE)$QV zcyn~ef7-n{3SwA6d%`K_J(%J}%l1Ik$Ek67I49$+QM}JZnz2XL=%-hsB${!~tLS~m zj*#7JdaYc*7?sZ8_5YgB{1-0VKXf!I{)y6wa_`oI*wA+gyjfHSI z$kB2X%a40l&O9;D+*pWB7;EIjmRRl>cnIalXYUUh~>H} z83eq}BdTv+V<+6q-8Ps1|C^@&LhKc;-=9UP& zLSWmYsE3{o``_NgWv%)xC5_D9RCdyUzc-78MCIf|MmH$d>=qXRpMU)}Sg0?*CYA!F zpA+U?NsCy~wIT)!_m$U-P@wd30=(U65zD$d#AuUCgz2IZXJ zDq<8-AAsrn^xW<@ZhS**|D1&^XNZ9wT9r0Jd~aT`Xt1L{(mLDz?RO`i@V9_fT|dGq zh$4WJ_ie&$O}9-FWBKjQSaOtk&Wv{@HDXFPn;0zG7gaMtjI^>(L5OzOrFqec3{ zYO2Ul7CH0YThxdd-D+a=R=a;I>}T+#D4GJiI9XjFH2I~(`Zq*$4>p;jeG$vhg_zv$ z&bse@pW|-4 zh%H?vVzfYCYK<5L>OoGnw>upItqUSX3-)E#cz_BL^ZCX{oZGgWv^Uqd0LNbSpJ&VQ zXon4m;a6d26}(#+wWlS-4e`wD>|L!6q{4HQv^CPSRxUU~%wMDX7y0%8q9xJk2Ma~K+a!J5N`kvYm zyi{R>Gx$}&t%6U?mIE9#)>hvD@kD(HMA_#Ud5bb3>UFtDzJnV4&e7N0pZWme_peeKa4X{lX+3! zTktlB{Aey)qAGO%yUQW*w*aWQAA%8#j;N0?$m_Ug0hoQrcg)CH-8N#dSl_c6ZE}=p zPOo<*4Fah0}%-z>iqfLf#&Efa1WIzn-&Xb@o z^)=Lpk)d32xV+sN5QDm-Bxvrwwi*vI6#6AD#Pb%6;>W9TAYg_!k+EUJU9AG3#^HO1 zmyq03AP=B=9`E&hZzai(;Bx!`?kC{&V1|DWtM3{vA^(^3`2RTlgIB`XBC;Q16#(;c zUIRk_;S}2@EMN`TZTPYU2ww)O7)5_M4)oR2gjfl|J1zKC_${_Lh}1K}l&&x>%uGyz z#KB9qcA13);o%Y=5ZDWZ0pN0U58)DlZ55{#>H*r4sZ#NUH9-ie>kCUHmOP?%9J%2W&af$nSp7y2dUQc^n{?7#O~s2w&0k z59_)x@==w{K7pDVR535Q$qLSf5gj}}hLLZDoVGd@7X(a!wO2I=E=+uG_g}pmRKO$s zI;nF65V4A3!h$gVfnnWMY#p55PUzhxC-v`?9Ss$=W*u6s!yvd&6Q}sqV-~+BTUiLr zH+v(xi`qVDk%OabiR3QQLOnP-ZtbEXZvfWMH_o_=M83+PP&vyG^Db(qOf`&pe+DOg ze|k;B0*;8Z4%kImVTMJF7Uf*vE(#(FXJWS8KQS)M)DDV@gIyAb$s9pIy%FP1B^)CO znD%d^h1zh0$Zxi78*+KrB=*qE|K@=G#UZ!<{s_+yY*@n_zdNxpA1qw9q=8?@QCO|+ zLr(cQ^7n0F%QLBW3Ww z^dIvASDA;`fLQs)i{*|mEVph8I#8@Fk0Tl5D=RwYh|8G}J-QU$m5hiM-2iViIzByj`i{dEc!uD2=kL*+4AFT6Xz#opApFi{2^_Z2`sc0n{!0UX zM_%cNu-5+-D)a|%-P(ZD7JFu1qPg&D{D0q({a0)aK#e=?oj2Z~y*VNAACADcV(z~m zS;NP8uuFm08aRQ0qB8RbAq-_Cn;4(CQ9|sIv|WTRUt)qFsB$)X9680;p&A**P)UP!s!iPMO=`V!@P{d`Ldv`1If%AADebxAqL+ z_+%@sdV-in<_HFwG?11#XlyzArJVyn0)1V&RwQ8lK6H&3Das~C-rJoKIHjONg1*wX zTH`^Avdhu&-tw@-Wf&$Ps8fJ}sez9Z{qJT#|1 zxZQ)u2mqJU-J)Y{KE+^9)RIa$9l|3=)mxMlcm79|9Cf*Gux5k|<&i_-?M{#A(v2fQ z^Yr!BRFR?FbC|rh=n=iT)p3K^z(VX=+%PtLiPz%z^!l#T>ws9I_D(GG@L~y6ulzHy z1lmFU$sGS5QHi<#%yWJ_yixS8NSh&Dj4;uA=k@eG(-|^#cw7D*XUy@HJlN9~d!PY# zU&-?W*r%~hsJOr9^=vX(IQmDc`a>1$rSIM4N|O%zgpN(RjCoi=7GejaaC&I*+SXt28qEY(5mNz+|aU?G6gjNO&v zX<5L5Lm9g%#{+V9*5dIJkC#3Ddw`d+Moth0;84bBeKCgMpEWu9ABucTv>g4ca?K;>`+8~a0X2BE z+8ea`0Zai)VRUaAwwb0C&`fh#82R^`Z~YIsoDf9=(f6$wyn(rk^B#Mk1AhRi+7km) z>~}@(k@^ps4pVsJqM$&J*HN6$B41&IG32VM?)ttnYYj=^g#76uB81Nad*8OY>pkftsT#TqHNvxoxiR+5G%>4z|EM-OSmJI z*hxT8T#lj+jCu}))#bjgqs(`5+6-BgkBP;#ltBR#s;axR zNl~^y(Gl*%5rCp2D_ru8btE5?hgajf&A~mBTV?LeAjlt}VJI+*vKN>|S&f@T*(Evf z9fNyyA&djqp}AH-o>HI7W9ioSdF=Qeu-MIuUj^JM{5Db=j2kKKp7b39QYla~zmEz6 z02LTi@O|Y*__?{*?g;o*z^wuRmu-6pmq4>ZJY4Q-_B`Gc!72>^E-~1a*?R<+I(WFm z4_n_0Q-neoY!3`boyQGG{Tzrg&zbT52bFNZ84Ji1VdK>}UXAbCoyV&2 zN}y$us4eya#b|Fbxe&cDC0{(Pjm95-cEdKcY+ z2C*@L>|KLirj2>ihRqva_!yy@2eaBqFwXNU_4&1|DA$e+q&)Y zhvSpGOUDOKtfNGS;`I&c$!9=E9^dXtCKB zbksO~?UdE;g~@+@f}dykFPdlB)fyWE^xNFVO&JjBvLpdI6i)#IDS;_#E4o(SnlXUu z4ws$!+jzA$K!`y=;|~0IwfgTEFozAF{U7h*iap{9%-;k~Z+~feFVOn>?~XWwq6+e( zfQFl+xG@9Ij0TXpPCLCjfZ@{E$$x+292v`NWL?^Mbhhb|IL+yr5|c)WnQ8ey;Rx27Uhk?SX%QX$jzg z{y4c|LJtUTey?T0V9gwMoK*&PjIU^4RLuxE$}(rw+npLQsT)U(7U>JCsUk;NZ<)g&OG zbK^fA(e@wptpCR&^E-}-24G&c?VTD2q9b^3e0O#g9xj3Snt5Sr%rJKB-%c8G$hg>h zm<-pm5SV%Hn#1p1$$%KvohLzG>T9SGBSX35aCy5kAO>|uNzmMVZ8f+quf0mY4Lhg9 zizQx*t9&gB`8QKm4K<(4-B*+HL0gLrFTG!5AnUU?b>Ez#9FcS8A8$IOBkK$rhaVc1 zS#$jV7Gq-~Q_JH179y-TsCK0rB<*@&3nVObMxr1;u}}B$%+H`2&VDS6o1N(%Ed(5d2wgKoi9rBtLb36ZH(WmW-Mz|EvcN8)nX-~L292u&G_$p z>Y`h({#0Qh3zr!8zFN%rS(kp8$ru|gX!<18z)zow%Sv>5B`txXr*N4mje!?%28ft9 z2w&B)3rgeul4yP_NAI;V7HVI+R7YbMChkPcz72B|&9i{4+T`HEMedcH7`(2JkFc>C zcsh{?&aMfh_va<-T6h3S2C7ijl}16E+!a3vyj1bJA-2Y!UHc(yOOzW+tYKeZV}F-T zAYRw(q-S_0VQA`X-d0Y8W_Esdk1ySRppz57HpP$4CZiXRB-4r7E8&hwUL>RK+9J-B zllg#sRxJ{t_9gQv(OfX5k~e+n!(;EFRJ*5yc)fv^X>w^fXw@iCX+DR5_HK2}Jp2?= zy(Vq4Tn8P}*<}8OUNAKHhL~XJ14)cG^50t@gywqSi(FQM+KyuS`PJW$%hRzAbF6Qo zXiJig=>gCOJQm9ONcpt2OofhtjWS_F_^B77f$r-hwSX@=-dlN#yB<-Kp_Vm!L|!Cs zZRHRAn@7lBGz}_S?T>nja39eRmEdNESUYY}h<%aJkixypE4j?6gSx1+9vfj6EGhj@ zX@!qOg)_{~r6^8m4dEGoB|ffke-Fdr_NIqDf%pN{AKS9?CULYh)b>wk|NfNv=)@9n zm7hI9TodE81Vp1$I!>t_&z(v^{bf80aa<8j_+p-rBJO5v9+kKd@NN7AdZ(W_B9|f| zn@O)IY_L%*qF34HMkJKHn$ z`4*qA`JcbNnOt{=t*^De?4Io&|E}B}-1Ey{y%XenxqMq~c|HwGu@^c%@f&@j{_S)1 zmBk6K^!uZUfL}G_p#8*i#rT-O!@U9c$|YKiVLclPoJ-?f8K~a}OCV z^(+*NtA~Y2nekH@zh{WthZT-?^iKE|m9|^-Of!O#6n>weYr6&Kpx7V1@J@J!ygl#V zo$J5en_QpmmMHwzwf(Ix2O`(>L|yQ?T1-rzeo1_LeoZlW^Fj=Ip(DZ3j@q?0#jCJ| zI~IR5CGnGC^(g5w)Oc=Q6=(&H1ybE}1Q@(sKF&%Awtc^O933VWB!jPLIM`1NE1Bl< zdl>%x_LrDqE$(kb-t#`?o8@eFe2jK2PI=vBIhvb6+r#Be2{oU^)M`b0)63O}7oNB) zo2k2^6ekR9v+fyjh4BUfJiGD$+p>c>fjs#Fx9#uDJ!t;GUjRrn6~el==ff8RLH?)f z-@Xr<-Q8&R>n&a{)7{Hx=YB62YbcWjuSZeiaOWj6WGkP_;fxjLs3Ck)E;gSKnFT z7>e|NplI+-Y?cQWZsRc2h5ZQeI;BNJwIcP!7SUN{_pN7t#TijW5qR1{m+B-i3d0GQ z1Vz1=Rm4{%qWVYqh{N4fkdQYg#TgNt*>qbPVxh9S*_xbq4fqo~(36mB{up3s7b?%T zLBPwut~-()U}5WvZmE9>5v`^i=m@ikb6g-~XT7b4jB^|q`16WwBHHkg)utP0%Z(b9 zE!@`@9p!_D$71!rNV)$vq{{ZJ-8$6D_fFy6$Dy*ur00nD33EcQ#^B-2vK?)8I=X_>yMQKg1i=vB z7orM`aqZ(1ODsa%bC2JHv-(ca{!u6*8I--t&YB8G-p?r>qZd_*WtOW65DOSN4=E_X0~waZ?T%+(!|1l}X7( zZgLipJUt+ZAhr|fOKW2*byKMfGD=U*off;_&IVeh;vkro!m7K(|c;dTOBv}FRBvp*=gAWMliGWzvX1qX7e2QpE z35P1=1XrlR#0ZLIMW=+AfS$fcS9fC!g3sz77X0Cnas7LcJ!Jh6F}y;QGUd8odaCA0 ztOIkyTd6eI60s)d<2PqWEJgVPBlY4+F{y#7wNv8Ki7qG3qq)?^8!|W>xghp~WR)P)@2=wcvl8&_6^5ok^gSi-# z;G_mAdd}1bdJ_WV(^s51P+<@*)v~^SA~2s_MWl3draBB}k-CJY7H1%!0Zx7J916~w ziCf0icSGFh>d_eo*clY|#eE|SEEiteNg}%#x}$(p3D%bgo$HwmBnS4OPaHs+>r+ET znkmO5p>|RoerjF#RC+e{*SKbdW<>gu;3+2zmElLH{H0^$PLY53^{5F{m9Pp&cA6}% zB{cPyUr^Oz!+MiW_;}js98<9JjY&)nbBM!ZtPH%1jW!7}ko|CGuI^Cs@c>$)O2OcT zj*lB7*c-YwR2Z44D_HDm-ylA~TjsR%at{uo5E3-E(!0o$f3>cWZtg&An1UUX9;{(C zwDxP#9gRg=SUQ_;=7sD(d!zues9_`4eMWk`FS0s@HWyePArmL?#{k0(C~SAw{^SZ! zfw6zcGMoVQ&Z_ddJ%j+R^JI(; zdJfJl(Z!-TEt2n*71^y`M|21>9e%irvSU%hA9}Eoih$FixDSFb{$o1BtiKA3XX5gq zg!_LDs|GjBp>7zQmUq^ISg!oCq5Z#(dAqvn6XFh7QVvyzP!4=ijjLH5q0)QD@h6OD z1LMT0i25cj<9!j^aW}ECm6pN%(mBiIH1`AIo2jsLa|6Z(1<}`-Xo%ypC_>P7As>ye z2IF`xzj|EF@(301e{fX(;RFXgWbV*~xrkheFxgdGLl<8oDCB%z<9x`A%-`_El{*fO zFvlyb8%`(zLnfkPAD;#1L&=t{=x|SwhLn) zeyp(etg5j4Z7bmA;qlZBa%cAQ@(7=mdgOV-j!gfVE@q^~`8}|M9r}J|XCT7}$=z?lYh-4gXH>8w-sN@x0j`Z*LuW;MF}$$qaA1R}*zT_Z{PG zf79pFgV8v*Yj13CLcLpbXS51kC)Y%>IET`t>0a;FZiQ~Lf``^g*FbEnZrynJ>b$KT zb+lzQvvv|Lm~6+Z&_>L2+rZac6>tfoXlUfU-NrHcA;}3H)>IxxCu>ZjRv}m ze0V*Bf+^cuozy&L1?C_>{>Km8kCdD2e~)Jpbhqx9392fvrL9J?KvK;P%}LDJIVL|k zbxA9Q`{y6MV~Gfuc}LqIqW<=7BmToyl8kr0@PAr0HrMuCFk9ULo7*Hp5w- ze-}mR<*jS=2Kj;Wt@h474x@Wf-e-?xT@QvqA1{lzr@s>vcY|@fOHKp8QIe+V8+NUr z7Ll__NQrgIyENa#mBBpOGn*dLyTdHuv+Q(I_vKMa_mZ7BPzzL|_wYPblL8u%lOT*C zj9cI4q^JjpZrn`iIKtAe6>=IRFf z*}X1|e-a{HV`_KXWIAGB8TAh%*P4?=7iOa+F&(~0aES`F4Gce%XSb;d{|Q}>6&r#q zf}jug{C#DF>5D2$eKL760yRQVoymynxGNa#Ke>bNa_CMs$UV_4`S z$`p&9!Zh6gJv$+h!(To8@DrdH4x+*@b?U$kM}_tvd<2 zekUme*@W zyVi-J4gB~5vFuUZIfz$$(=5D(yT3yJaTNN_5gBTZyj1soa_CoOc~g$>nHH&bYx;8U z^{u&;>xXuUE8oXSi=FEJx zI1LMKo{a+#yY9686id@j%hYIY_7>~O$^$ct1vh8Q1-dWn3>6*hD_3<=-5>y}fhay$ zb3a|`^vvHxi0Bf@-~9Vb1eEM9RGDD$Fb@1k zYBW<|G!b28)a>caA=iE7Ib-4R=ezK9rAE{U`%0PUT6v;otl3A@<(@|hq8y`i%?c1E z>asFm*PlOlKRFNCW1&QJO+LMBpcuZKzc93;J41=sL=M0do6j_!AHx{Cp3`0Si7OF> z$og!O2n7v1KVhCS@SdsV1)kVD*nqvvUe}c<=FQ5w^&PO@t{qkaShaL5+Nva|oACew zpB~*j!7TBCS>gk;G}s*mK-*r^UI^*loXo&>hr15f@!b1Y*WSOn2EcV)RW2ov+n4Z- zEGHbeU=W7RD_y@&5dcsKH^q0N_QZzfF7wiGJX7@NS5J4nJf&2>$HH9E!5MhLD*uIL zQ3N}gX~U>u#t(VlA(9N+Ln}u~>*;c_ZD9$i+LG->mt;#sB~t0|0CcXkcSN0~^B? z%ekhoZ)xI<^u^8%%ZFIAfkuw-1x9B|h^1d)|E4MI-!!4+$PadB)oR#I73uL>Gna=Q z?v<(jPhIz%fqO>he5iYyXGZwTu0w4TvRg(vx8VC-KAYh-7kBW&qL?uC#1fxDucNzh z*=#ItwF~~E=pgRKjV=ewALk~GI1bN7nj7hIGXUVe`D;j+BU`?BZ3_XoGyr&@{b%5A9$dyzysyUeI}g5_kC>(><<@Uf4Bnsg9q3jJm38x%yYPSth*6}qn^smmsYd2 zMj}lFkYBE=0?A3jUGz)Ha~?e4Y78O{hQ}v_&E^w&>gb_e_fhCq>Y|nCDbEbH=x%QY zD8yR;1SA&G;tBi+#0f3N|4tEu>tS8lRuHXfgBzwnKi#f2SurD+K3 zZ*Cs==bT?T$h8l4?2 z4LJz`qj8ST=y@N|3SO2LS~oUZ*km~Q0P?)fJ0U5&D9rI%XeBbkgi7`@URha*nCpdS*Qudm~zP!;{iOE_PXV zwWJGrqK~en8U-zwb{0xtXR|bK+RUDWw*j4b0bTY~V=G?S_y`6{Zhupe5?eo%Uj0{E z1Lt5xLeZ=^J?+h}$IDrdGN%?h{xvtC7ax0K>eAdcm?)KHFTPda`+^q!#3+$( zM|*DfQfw5eN&gr8V{P@F*S#pX94afFOx%hSM#Xekuj(8OImOM{%#-wMeNFo_WatIq?2|b=lAF7V+8q`a_{BFoK^wF?>n=1YDrfas>Y> z(GM?k`rDt-oYX-fGT}?~i_2YWznK<;>>&n|g=U(}V%uI-$d7h(w3Tof-N8CkpBXLY zcPJxzs&w_9$olvcm*kymiq=s$e@4lLqEsMV?%+g_QPD@86QVK5ydJd2sk98$X3~YU#tX_ zrA1Fut^*P%kG%MaY5Ea3Pzd;tNhLOpM+XYhkj-)O`NJmeVQWn)(bb*JcAQ z+r?)_n*|)oYFGg)Q1o>EDPEb(s(l0P zCxg;F{j1Oyj5?Joc;nWT!b~|+Hpk#;6eX^R*L=HK;!L%>{&uwxGcu*+-7~d>4;Xc) zzGd(A6btV9j~@N2XXw?xI;u~uRi%^Ie*%R0RB?jgT7#nKRx8S{ihuz3D0=!6 zs-E8t)3pL0U5MaEGXp$~5tUU1AkIr7+YK2i2vvB-SB!*~GW%8rN_g<2YbzD{PfR6V zu>cZIQGP{i?k>yFLITr(i|iW_;^P_EvmJPMw|XWPss8Y#IoP8!$(iY2sLIx8BL&o2 z_nP^ykGCanKIcHb_H<6(hgPB)6}f3Kdh!XhZ zVRG)z8V%YBX*Gi`jHtbVHdEian4|8T zlYCPB7si;QuI_y@mx-cYhV{<&i(O*rf3UW!XSGVykq zgy6se%L4!4QkB4PR=U)rZUq8i-!P5AM^?<7r0VYGEen{KKjCkmS#X%TB5`e2I+@ku zF(OqzpewICx34=&Gf1U_QHB%2U{yQ?@k(_bm)S%gnP0;Dc`QA7J>g!*@^`@&p>Ly| z2`;oMX>|zNdjbO)ce6LzlaP})J|qmB*kMl#5%pet?T?f#nX|#oDBKcfd_1*C+;fSP z9+|hWd7eRGP@@{4O%YTxC@jSjiknWD3sMO#{eycbj^-K`%PB}seJ))1 z3$qIRWBg0(i(&>|=M<%)qaPj+%rA_QKhiVHlsVElw;(BBh*=-=6X#~in=b+_`FH{d zkzQ=r(nJai*@u1yOy)Knyn> zxPlJL-4RRHD%QNsICX)Qwhn2yj-?)9Uspg7e()tas;Ed_v4Yo6Y^kcSA}I?Gt_#D6~Zr?O7p2n=`9H>%eh z5S0{=vyB4IF6>`+KQPZtGd%3Kd%!KkCZL{s&rU!QoE>~MIJ*{uuTPdWxJFwn6TGWX znwvDAkWT8dxe2-y z%3UF)tez=K%}Zaz)BREXP+LfP?{_F6I}fDMZw86>v@trhE7*($@uVDzmd_|6)F4GI z>IhKE=b6^%Eija-4Hg)xaAB2t*Pk&SY*M)%{mN%XZSjyg5Z%HJ5X#)a1OSn1!=W7= z@rda8HEgitFgPSHKa6e@j~tlb(jNEN-?4f%H(V}*&#NM$*N@J^u|R*Cls+sF+Tt(? zN4Ptz0n7;SieXs@U6Dybf*LkS*<;6K+Dvm7Bv19Sz_L>c!aCPv4)}RCssH3k)?h*P zs=Ky4V4Dy_+AD77>Mjzo`bqi20)^5)wAy*V9zI?!EK9~Qju29qEwpl4m^bA*t8zpl z3KDR7ARIr}10D@A*9DDusRFY`j17^N(=0vrn`G5zomF6*aYHb8!<2~*k%`+P5~vMp z5)USuOB^8{EIh2ZSjBZQ>yJbu3LOlq?y#u?|-ftkc2 zCUidh9ti;2@1oR&is1~{z^WAgeX$VAoNE-{BovU=}SN1GlTU!mi;Q~gkz z^v}yX`hhZ&P8zit;&8KFdAK#FI1$8ih)dbOU~ma)!RPOd3xCSaL zn>+Bg;SJ;Mdhm(rVAp#xTlHZzqn$mrS%zvHz%w*5hvjljxiiy7tbk>aeRkGD946p^ zZM(%;rThWTDEPU+1emtY-cT@Yfsv@IbnrH0$jG>zy~wM8{L#)}yDS@d4oF?mlX^X_ zl$BuzTH}V0F-sFgMqQrHW#7XwBj5pJnv_G;Bv?y9kv;9FW1x|Iu!Afogn#3hd^=&}B~q_q0)p2M(8@b9NPjX*vY8 zfd&n!1tmjFAP;Ll*7y6v(M@`apl`6wtv<>fgi7p>O?miL7!M5Ll_I=e({<)R_@9}I z|BVjVVh@8I3(nvbKOFZsPRe#gMsI^hN8g4}Hib%u%ocm^stH3h=0!)LjK$8h>RTf+iR< z-30F-mn+b+0#up2z+s_Aak=bGq^$1JAX@GkD+UK#32 zURQEZm@65`f@-r@9DJ${-h!%2Ky3OE8_2L<-D#NSm_I8oIsB>i{na{g21!MXxdhyV zueX6}37=rnDazftLLIu1!B}E^-+QetSlvZH&Ug2#+dNr%?1>k~UqSCX2f@VyqF)j|%X3ApZ>3d>Tt9ZUf#|vk|J#LHAu*`$4JxX0~Z zyHEeM+vZ=pFTm|CH_&WEVAglIgGh`W9SHfoz(aXQqT-bPrD?D=Dut}^UF71kTX`vo z;9E?-a?BMmHVkG7f)%+b(w2qyhZ@_xeFi__-Cn>V2XCLC{+iKAQTP2aJDycyF&B3# zdJbP&c?GEt5-_Xp-uW&7@MSyTmLu?hDNPE@*(!LyiHtrwI*Y)^xllwFT<;bY{O?^{hyTU?ywh<+^rG^!5~>+X9u6U$rWbcUwVDBVLTHiu7*t zK!XeIAP%fzMSPdiC z_2!iP@$Qp3@w$_@^t+O^SWrRsiF<%^V&Uup3&GGPSi{?}`n}sM`oVVy)3HA; z#w1o@{4p@rn(#KkPSAmcq5lu(AQg<$!|VPPj3e?7C-gs@o_{#u8lHykg<9`8;dcnv zv51#r`^|_DC);S$*5%r)Sx zOFa;2_R-KLj!UW^;#*KlGcR->oM#ezuO%{rUSMh&?k;~9j7fHj&V5!{PKyM_t|@(; zffQ%{6T_DbKg#$R5m^))uD)3kvt`6`VN@| zh7A71JmwvYH_+qRaG|2p?-@%r2D06|sP@K$IbQR7+~JBK95Dmlj?A+rUhB;anR8Dx zg>N46L1_W~FX{=<1q`T3qRhyush*DS>3)R$QTy9I_u{y5$7!6SS4nD=EP$guu3(VS z=6MgVE)tpOyQ#_J-~|0PEU{QqY)8>M;d32dtF}pT`|&=XRna42Z-0M!dVCxjt&=tl zo=1$0^5KH?*FGjN|H0w$k^YXYL|g&Dtw82svDmXmK5p0MDdFYw@cb~ld$Z2j{(P~y zxj*0D;`?^-*x+6t*(_a$>??mfNKM?1w2#y&p*+3X_qlA9a(FbwX|pNBaWIy`g*nqi z@o*JJa6LKynzquMpMC2aTv@?5lL!SI;5r^~O)#*##2v)wa3IAc923*=*6yoTLuMQo zlVmv&5ia{heNUJ^Mb1I*gEr#trR=|4_A})_lbYAMalyZI8TEk$KN|85rEd4UO=o`D zD}fk%>=r3VYml%TmZ-2(YW2!J=3~BNEw<)HSw2J<-HH|)_|Z^DF?P`m^o&*e`w=3k z45$wkmz{zvN{S2dvkYjB*zrT3X(BiSlByq`CCg6f1L)lMyVthbYL52#eM1m*mPTK3l3Gp655rJk~e=*^$AODU)KV zD+E!J+7M}5WmVm>D%FhE#D_V_HeDH~i4;UwMra==LJSR4CAXlfvEKWFzrpSSjfF_Yt~vl1Z?V5>qLTYqVmR$KN|Z{ZEpjdAuI zSaLDr+E4U|t3N$!Ia8>$z0YsNeL$UN_a^dM{^wL{>ehYW@iwn#j&w=hGyWos{~?qQLs1I{641W{Y%f z-qxXgLbwv)WsAB$wpORQC4X#BX8+j!q+i;L50@QjD104hXIh}8WVGZp=n<1lugAbo zsOPtSE~i-%=MSro3_?^O$5NTNbthVSk9iL8s+IHMTk1=yljzmuvHId>hnu!%)=7X<8~3v>=H zW6nZFxbVWJ`3e*aBS9{1JYsbZcGEb7r@Cy>K&owVs8}hamy6b;cCp-WpJ^v*^`FeU z-||QI5pb{>uTD&Le>h;!@kGfRCZt!ApQx}r3bxpIM108ODhmHIqNn^8CYh}uO!-i| zER3}Z>ODR-5y%|wmMUONA588EYOzyUbn)AAO;63$t*kR*(ETKOY3TzG!&JR^uc7|O z_2rP{UT5mD!B)E1j@;+D2)1mOIh9XvxX$!Y4Z@{;ZKbt&vMcXg`o zJjzuR*9ku%AVmjX*QMXss^Ph@uH>Qp`8fqp0xrb$b1AqGO}@3S5w&r{;%CA7d^j=o zB4p2WCFGi_7kNWRg=tzqLN}b_-n)+yjRjF{e>Gn~3A3Gfb`be(>IDQ=VTOHLK0y3H z=ZB`g!;!sU>PwQ6kb`X`U5UJ55>pOgx1LzGt^wknIyT{ zbeD?7#s-H&e)=vN{T&XRKuee?0_iClAEN_vs`@7%I=(vM9v-M-cxBD;(B`ykI9Z+k zrR!o^C=uSFVGd-PS!z=6+*&BXa1?IZasd30octbnG)`!1RPeJl_xw8sF6pTxvdGtj zhIe1U{vyF2)*Pvj5`!))yqW^+creA_Za=x=yt%~L_F$HqoAc3uOm;o;7~7SSn*LQb zEV(5-RUd-aEEw+=Z@SJ?`U90gC&Hj9*9XQI$MjRrphh!Bz(6lv>BM6jmUmNJZ3R!R zk6PTVQUa%ILj^_shj>nWZ$is{7!1GdkQbTmms_Z zE@+8HBX^V>!!y-h>E)MHI#78kq4ru#H@H@cAd6ILxu)+tg3NZtSrT;bdx6l2mFqK0 zdRh`#ThW{gHh`%+mD zJGrne>AjKFNN?*>Ok!(Qrb0G^Je5BuUlCYar4dxCq#wsw=T@#3$9ZcN$2o*;c`Ydl z*wazlj0!kbSZxLJRNGksmX~OFVog1BiZ ze!*YF8%bZ|t|K{5_+D;T0`Eza((+JZ(ft&(cUux5;`fp;K44uVEtQYa(O^3xc`C;? znfvhn&gCr}p)zfs)2)_=e1ZjbNbO@Q+%iO#Pyo_pY~HL_fBQl#K)LM(@?%7W!~$jP z+F$oxW$c*(6xKWS%xbf^E!$hTN>25u*(%oL->l=D#7XhZr>Ze%5RP+_W_H zmFQ}?4L6CqD7m0g`k$}2zAXN>?c-6~C%~Uw`W~dryWRl}`EoBLqH&E9)aVEOY_r^a zmVv2IOoXPI2dZ^IE^l7$DGEzePT&%4qH?+)}+6iOVhga}>K@sAFM9 z7`8%th>gZD?7{_iGICIP5iG{O1d}QkX$?UjI?GQv?GbvrTv`Ux_htmumpFfr?#=j` zIkTTpTCtzu0-yAy;AB3{d5+eiHGJ13YsRU%U{e>YiHvW^+OB>X&L@k5Ttl!=le{$EI#>#@gg=IhF)zDLJ|$O{i) z##eJB8px94QCP4qPq-rT0C4!_C;Gk!PpfZX6ir_KX2^H^@E7N=?MbsBVN}c?Cwjcb z`aiDI%P+!4E~#6Q7*9Um;1NExH8y0^Qn+X{i^>_XH2l@GK%M-*cd_nXQ5?c+1*o|1SDd1F#nwjQNfyFDA`$)r> zANDIhY=xt}xX9K)T1X`p_z_?rlfLpXQP}Q!fL*E=CT=;6|3n2fXLrh{nmSydfun+S zfd9t9l3(iAM6cdk8wMA}D}uG#X6XIb^2ItMcu3o{K6nK>4w)!Fs)O8JMQ6wRHv~Nd zEAeGDW$~gv->!1yd$bHx9GZiW9+F?QYeDi_3~o@W%g4X;`26|9#=;%hRjU$;4rkj=4mijkaiUL;5%9-+bOB?= zRK}if?e;ss!FDKI8T%cBgy?8bG)!9oahf>kS)6uU*#WIlBNJchzmwHe$iW{3k2BEe zHPe_h^DI9iXPUtui!ypymJhC&fYKK9P!Ke76er{2rm$X#xzc+(J#oF4z`y8!D53GV|CnENEVn{p=4v$x)XenOTi0vzaC~Yx=s&&e z>-9|Pqy?ngq`=2~4<`@v`(a(9++w22mID4IY5@S}5JL1*n+l*!ia6j?*nsDHyWjQ8 zxV>M5`3G^a@7JemqAiEb*lk%WysHsBf6tA9UE=JC^E&mFpMSuw8|f?*K27u5AQMC* z=U2z)4X+uUPh43BcJ)d9WSR00D=aFq&S)%;$JRca865uW8JxWvqq9Uie=*gU2zgCU zrcN0C%HN(p`S}ieQSd;+B*O2B-38xs#(~}YZ%n`mQQTMswD&yh6;GWmZgH}8b)Bvh zAA*U_aNZMUoGoLDTPKcll?z_nD$*)qL=%{5FE*vmSfuxI2uo+hMdXMld*ECf+0aGov;+On9 zCPW2M;x5SQg^^(Tc0aE;Aq!VM`k=5S zOtPHexBA=P#`zWerQz^*-mw3PkGV@4$)Vpzskh+ii*#W>OxV|CAv<4NcF$iaIGn8y zF|Ifei-Z%jD~RPFW4N==);+xvlULmAWkMqhEs8e?bf`qb3HR|t~`ITa%0mYL4-jQnZ^#n=>@;aKr%3JY-Iq97Kz*_uWCj ziczRmYc$9@A;%Nd79Cakao<2&Oap@ma&n{caa>4ZhK5M3^j+HN9r6KB ztWfRf9V;CAo z-kIv-RhE$1qt(8dSlOPRZ83mQp9sAqhY#tp;bRh+F;0Cp)JdD4LUg!W-6%y%2(g|h zTj-m|$kA;R6{8?UYDYx|r2}$oRmuNFnmT3w3iAyo9vrE(^gWWZ(t9KjC0cmBT;)i2B@(&frKY73QE;g?Uey?9=C*EArG(ehn0L(7cy?wQ%UJ0BSF zE~me|jGj^d**qyvx+tyZHV5@efoaG*1r&T1@~BVGP?Fm8+{uuB{@5@)ezvzq7|7bY zw}<6Ru;3BCw3?CDk0x=Boq3u}z2SNJp+GiE!go$5V*@xm?iP#r*Q+F243webp6+~f z=G;{!PQR%I+~HaV%7Z0!Vbj194cS$*dK@KakOzd+nQo1H#mTJfvlW3-!V}BVyw4j^$4aFkcn&SCcnBmRs>o_G;b>n-ftWY zxyi3ty#OC7L5;ihPk$oeTV@St0G$yAuylZ=g39$|CNui`Gb<-i zYxKTM^}IQA39588n_rGm75+uI{1@TWQ+`!$yr}*72jU;U?{Ar`q|@d5x+h*+u7H4j z<9QVV5!FH=^+~{e2W~pmWtco)fGo{g#%kn{tBT&7GkWM;K=WmHc8a zjq)+7s|xh#mcG4vpgU9MsW0_`>jmFcCGf`Cz2EuB-ZOBK<4Wld9pHq5&pwiIoPv0{ zw*jtv8+PZ1*?w;_wSm~C=f(t@eXFCh*JdAQJ$mm#u~27Z_AY?kVp>3}sOifTY+s?>I?dJ<*vj4uI*IT0ob(pEl!L*zfB- zV@M87sPE+qCB|1+VlExnu}c`sQkg^zABR=2IJC+=W{8yvb{8G#>-ogWSFif-?=)kx z0HZM2y04$^Pd9U6<|Q0;MP}=6Wi-nm$h|d&?3Dp+31@^K7B8DcKs3_A-2LvO7v?uC zd4&~FS{=g|Odtcr$VWQdw7+_v#C;%JXLdRnkzjk26Wzm=u~>gjopygyXrOu}LV~!y zxo$VT{LQLWtyyysix8z+>_#>o(vP1sl-(|A>scIflqsK#j12`_54}3zR;l!9pfQJS8X`bq72^El zgt}EzNJ@F=wvkw5Eo1l00BZ>Ka2LoXkro=|a80Q)ba;89;!^b0)j-A*WE+le*o+qm zjzj2tk+)2c-YXCMZF0R|Eer4%xp1UZswB5^{wPa`G4BS*_fCDlm15-gi)Uwj1-bY+ zl64**{0L5?>xmY**3`yCJURxiv~O=j10T;kzdMHid-F(fwErXc9Ge=knInyFp??K1 z_vz5dST9R9S)rLfK0GL;*bRMKR}hfY@*^0~o+c@tFnrsj%cN>hT7ml;i~iZiWnRLfnu<>No7?6*-QYNH(l_N zorbN^H>;BMo^05TK0NCS|K(-XlS?v@-b9-fw570NoZz7_>MWUnAG6l#fUq4*E17ZX znfOa)MC^(j#H2L3;4l%n!kL*VuGlIsU1dU6xk8I}@j{xJU}?Feq$cj9gB*`0HZqwu zGz$4=u8NU|$EMZNk($9PsRl$fZcLxf4^tnE`7r6+E)kLd?PN2MbgArFbArY{B*%%< zCEU}4k9->pi&vZ+*eC$+dO791flIfLM;gHHE5JeUbPSUc0<|6L5skN=99 z4~}@OQ-nw2$Wm4rZlhA2sVGzItr7`Pe9(_)co4X1|E2g|2)Y$#5rUd7ZIu1AdS1u81}UTJVQ?Kf0A(@kDw_wv1f6nUjJN_1CD3kflT>MW9xk7y&2{P589ZA78(wkhd zLbCI(uR9WN$HB$k9DY|7KVA8YN{?;hU4c76f)A0U)|`J3>IRz4D8&kqYsw*|?D__9 zoW9o6y=;k1LIn>k&J9W@DTX-}`iQJHAh;T!(-o6vDNEd>8BIfE)&Ko2LWK90pm@pi zp0$YKKglur$Q2eEkgH-@iR9%c|L?*~WY=4)dgp224gBtS-|cJRqRB(JkwREs_k?0Ra(z_yXC6|&P=^hQJRaZ--3hDD+ z6zERf^53)dpXfBXCGmUOyVh?M@ff6sLR{OJQ}!9367Yb1kVgM)YmL9GggPzB4RK2S=ox1 zbR2aj|FdAhr2GG3gi3W21*%b`u&^%}|4k2_j^9_TkX(#3O|cc4?_<`~CeaVYtmHhg z!mUCyslo$4prUI9RaUvGd!Q%L7qr?!Ua2c#5ym6=1%I-c?6cq`tSqKdUPy{2^B|k7 zJ(H4R8GS59p+a5zgi=*R*TRS%>X~nmim|X+**qWVTvaRZI8o96pQZp4`hU$4hltp} ziWc983cN6)Qfk%NR#y&g zuDn2u+X2Ycgk%?#@f_{`QxvSiyP^hLPd=MyE>nezE>aE1o?zkjGV~!27_Wd|f<}#7 z{yabW;*isOX+<$uZE)`rNz*$TK)e~4Y=kn9oHwTZg_>02ID`#6Dw{*5_)t%q8L%dw zs=-71@pPw7Oo=UNC#XV1iLDoIrbKZ@wkqK}cH`kBhsuS}N|0f_B6FP@d`Sz9_J-Pq zc9BWmEgcp>Fo^t~g^OmrM{m(3LauWD=5?C7z10t1&7|VuH~3%A-)h|8TH{y5KfTb0 zDl}C*b|y3oV2*c9MH&QX{zLY@4PlNGl8KYYCdbY$JOHXN&C zbUIeYwmP=eu{y5UHafO#TOFGn+qRRAoqUyk&$;*e&VTPeMyl4>shZE!Gv{7aYuDQP zsQ@&kl6z2N@Ks`Kt(G%5hULDm5$Hdj*%>8dF@D_~Zn5Z1OdEcdQ&g}}X<)S6HO`Us zuUR$iPo@Pk$eayMt(g<1fUJ#E=f#_82xo}9Gn>`o`wS*A9eJ5cDU0=+Oao5)I3rzw zO$2t*F0j1xDdUt*cf7R<1K_PsdvmOR2rHFEUU!@r3ZhYm?be2?L092fse}T>tn>Z2 zxr6~{4;~8McyadbB&oBb_kNcTxQ~e6%&hn0*+LRrs(igOUzgRR|LvfWjQ#YZE@UQ zi5Ad1=M>A9Unwk_8%G3qE3n_nF0iMRg^WlXPjDj#)H}$60VV-w>Gg`)XS&?vM*=he zH7fR_etX85U^*~>yU;O;j*3WYh#%jzmNlA^(Ca zPl>)E{RL+Pf{*|C3+@>Bb@>B)0)S?3;p;T17?z!=AzeS4JIgJQSMV8?-(S?6Ha`K( z@?GPTM6sS23r$7xjeb~inh+*veao^w2_v*4cDA|@!laspyHzQqC7^;7Tolr>SF;g| zxq+WsTmZTtn_O|SU>z2l5&%2t_qh@fD5pU=dB=U|L6xYCgcg6DPwMc^L<)#!mP0D* zY}{+cMkJttVIHOEzEC2Jrlu$pCDS4x6&jyHW*{Se{dCY6 z%d2Vl2Mj7b95HxM6+z(olkc^FAYp$=b__BFkUios;vkUAA^TJL%Fl=Kx!NSlrKrh- zAY>H~+pvl)FxkrF(GwBJWO8}3-uzx9v0&dFI_upc&^Zt)x`qIt4j%BSy71{psNj^c zpq6Be^2eUpOCXKEp#<~^(*gK09}!IR^?;AVn=%IYES-WC=0dYj8uM@8h_V24Y{1Mf z0&;e1ObCBn3Sj`XttXd5cnwB1qcRcJ(+hOhc5(>Dm7Ty#6J5=f!6#u7rhhAuSRYp_z^4+W7bgP&?&y? zMSh~j*+A}*FcX5Z09c~PD$oJXV<584>Nr!`pvIO^+cCT!!DA-0ZHbcQK0umWgqKI* zzqXKL%SIUE|D6^@4ZtzxUv9u{dCPC`h zz%PH}X+unwVnuUkPoAdp{S!FL<|F?!GcU(Lps&U|WL&)XQ!i-@6MyZC1V&A=9gT$v z{BLcn765Cb6YDqh!ekUEz(+mJ*X460FjjN$;^}k%r*VRRJ3MYITK@qjr1=fkW0$XPN2p9MmR8#*jfDQZu5!g%F!5?o>pA9y#u{W3V>+(KI0j&YG=u_$(2uQ@( z2mcn*e6J_r(<89>2ZORD+$U}Z9R4$AQNZ|pbUI)*B_?5606yk%&@sS9|6$wzj5PRB z0)KHnPx`H~Ug3XA(~VO}1^Xea1Ufxr$Wgy!B^v`wXom6Tk?S5L0^T#+J2+D;>(!C^ zyEg~b>_Lq*vBP6+-TP+PPY?{>ss#6vsNUr9wTS%p*Bz-*{N__oZH>Z={QCRrBUdBp zFku(BO7EGaM;1Ioa3FIqqx2&~%sESGJ$b){mVkg^j%7%&qibqVi^ zvF3x)VRe2L#H33EnSG5?gS1+o1X-Xa?b^X6c5R$7Ap0u!p4a)xD5cSo84fM;B6rs3 z-9((AeylAg3g-hVC1dwViA4rjhDzMzZ|{z-?{@bSa{|;pc>_lKi7hmqjKaojF)bdK zt9;sU549Ct3)Ba1_PQt?xKN%Bg-VXRp+ zfvDEp2k$cxFZIJKSQf03%#E`~A?&uPGWm4YQS(o3H6hLyNz2zXnep$K36==T;JBc<(Zc|iOsW|Yvv4pKgqf3#&k zWdzH0ncvJSa?B|9`sO3Dn~za^=w(_^?`Le)amDMOl<05r$7lz|V~OmXu#tg&X4N&D zL{sCqy)TAt4&{p9xlp%ZS`wvEiEcG$C28agsqA+Wr&T=>;_gBR#2<^!;Fp4DN(K|5pp{fYX?EP zjG24SV_^jmHs-{;zwRPdc7P zQ1hNE45CP~T%R?hMO;LdZa7AG&N{Ugxu>r=%y9%mf1BPp-#|V3OUve#!(Ta7<-Y7j z-Hr>ai*_abR33L2^KZi-xPo-KzkP6gpe0CtT@-+)JIL3P6(0Sat`x($(=KGEkU-uB zxkBC5HO?lsfiT`rX=*x>^sX5f? zNLsY5Lo}Ff_4WSqMH&|8rVpi&W5FOX51@MA93$^yYtc#Q(^wXPqw{n>duKRn*(Vn# z+(Oc_fVYfQE5vLUxEiaRTZ8*-y03!v1;OWmS^(%_G>M;fS6@30f+_AGKep`q&%N?g z%|yj`fZOKDP=oxhd*w0y-79ZKJt~a>8D#T5;fa8z6D^1Y6Hc8~wbfer*NXEXe0M04 z8Fy0Y+dW=ztTrY6lq4Y(O-D+1@6BUA2B**UbgJJ#J1^;v0NR43&o^g|coCGBzG<=4 z=GoaMe{Njw&P?6vtq#n6_~jWovK?V$#*;Bw0q5=wp#Ibej;YXXj+*;8&~2wW)1joV zZ_%c72<wZfi{=blejM`Oe!O-hMs%8KeCshicX}p6Rbdym$dBDx&4~xZ zbXr6>dgN7KD5cv9$Rb8TOx&avx_c!_NNtrjDj(*I(y?wd^68-s^vkqdyc3a)C;R(b zu>bLw>`+ns)}%fJo#=&vvtE5?-|Rs@;`fGArCMglD4xfHQ=q_>NuMW?NRz9OS{`^Z zMx~W65>Cu~gR0(ZV}IzyB#R$(es0`7pzSswKJ>y@*Ez9VU9~~b z+mJCj(qm;mA^z7^jBTlw)+=nltqhSCoj1Q{BYj~Di#K$xwCqB1)uUPS`-&Ia##pbW z1OHX_2e&%(Zf}&B!e@z?Z>1D3g{&g$l+JAg@2Dl+=am$9bskw!P%DGpLr!0&f=@HA z#vgQU#wM5t-{876ED>C)%9OuAwra5Y{X2efX2J3rH2 zXh-C-pJ2Fp+q&9)ZXYAae_b5jZq8+dr! zQ#ajlxGQ}?73$WrC2;e8!n=@5c)kd&ZX!gfsrKh{uhXi^6)=Is;?1uE5JpdY5Tk^+n)$;} zTmJ2YV;L8EuUhBQul_s9h1)tuYr2TESI*oje)`1zfm;EA#|rSmThXNRB^@5ow_)1&KBvv)vHT z!W&b+1zoUaM#e-AmQPw!1DPNO=F*Ih9eTL?zk2%* zviZv+z!-D*XXOdcb5#g0ujw{Ej|5wU%`v1_zwMHA4yBf<&(4z1D`u5ms(4PP|2&Gj zena$pDtv}MRO+?%;Z3k=e-cLU{C|U4%=N$#5eM zTY8c^3{e^qXR6-ba+%%Z2NKY8bc?!YxctV&0tAJAn*Z@?#9AP0C z4LHFN@SNpfp*$e2*l!$Wzv$1&pK|*A<@H4|^9X4kd|RTg z*(%Qp-_JRJ`;0aomvVp0#u>a>{W1goAz_ICT*n~KW7M_zm&CxoBNgr_1|&Xo_h4s3WXgDo>A>bKsA3sS&y-YdPfeZMrJapA0dU z4gm~dF8)@BjcXw<6#@!FWN(TApCA|uj}K{B{X(0Go}Zle(7UaUK+0A<`|zcRuC}26 zr#T1FP!kn31_;Pz-Tyx4VESjyp=q7QfDZlVUg8-saU-NTA4`A;LrSs2danL#jWOs) zKc+D^yYlNf4>D;*d{QwgjDP>d!zN$dV4jL0(zuklWNNs+WEYI4R2}8f2A`aQYzWfo ztd=@BDUWYa)b+&%@Pe#{4oDaX$Q`NWz)6g7*D1e!FGFqyjv2Kg*DlRQy$<`XlP%H; zHS9sO!e*8m8uWAgUbYDI>U#a6?f~X({!5>e`-;;Sk(q6LS^LH{$C&CCA${5e_#)5( z;jnF2gYq5opPmG9jF`KJf5b0G>5Kvo*c0l}$K6%}P=-(2_E+wTEQXt!BpY8h`o9|N z|Db~>`0{dME?daf;X z;@rElxz+mp!j3cRRh^ZcfR69&7x$_+$10E3*hFV#()CFaLCdPD_SIZlNAkq-Z_no| zf`tS6iMJ*%*Sj3Kr5j56eUn#e&G+H$Z*8?F_9|=CCTC6o5hYS=g;Gu{1Puj#mJ-Zn zDK#?8pP3Ajj9I83((Z*2-#Ei!`HG}EQrWGFwh5T}R)HUkSNB(2-d}I`ueWwQ?jCL2 zSvP3t*f9?*W8}_)*g7*WbUIVKU9Yn?I$h`9BpTPm<~qQBHs)5lpRm5Xnu^x>QMnsk zS03nkw6s6FG-W(SEYhtujBa##UB8VrZgi}5K0j}C0D7~|5se2{7f+MtNjzGWl>;!jAuwexwcDr(OGl;@B`vWVB4>|8D#WUa(SBlq{3aF)7T(z z)cuGtWM)KhZ}^58U+zPjX%zo80cTKX?bH~22a>eS{Qyt&DA9uJi8_Yk&Q2Zd; zR)i7WR^$}+;Q552V8kV?LK^Ha1Wt^gg^b7uhw`Nj!~fL?TMOoVIzApn9|v9Z^Jfx; zF8#g&sf68go_tH0P%LXg;&;F5G?_6HX; z;gKj8sk@lY8zIGaWvmY*9Q&b@F}P8Sxyx?W8Wrv4XEUVbMAtTmhk$*ir29!oN|!*= zzfdQRqD=O+K)T9}@feSA)!U+!NIV8CuhFia9Fk7QNm91XPiZD|37*jC{)v1}dT4=F zHZUATIy+iKqPS4Nk97dcR4iGxGzvwsl*(?Mj$3WJuiYI*MwSc%ej{*OtW~$We?)dj z;R{g%iIFfX=~*N$3aQWl2T3>?>>Ru(9O)1VqvDN-AZdq0R~4#Ye5xqbOAkNd{WXl2 zQT8rHc(_N=6yk#^x~y0`C5I5%UWDC5;?Qgb$I550Qv6porqR)=EZ6De7a3El*D{Dn)!Vehn+^ zeDbMVzIcO5jb(*=V<2#w7dTbURYt`;TV*?R(cuj9)@Nm9VqNwxdcv^i!wmZ7sO5}U zBqFuHLM_dIwy+9wipn<)Z)L`CaV`PIS(|GplPb^NRJB7q)_ejON#!ZPL(U|s2MnXp zm*%PFD_j<8U=kE+c2A(bhJW=H#1gj<@na?P&lhi0 zsj;q*ZwjPcTM!`7-M`w9A>O?_z_VW4$-ReyqxkUSoH|%&D1@b!Lo2PPX zlGr@)na1;hF}IsXIs=7cOoZc7cXoCpFc?HPHFhq1Q$K{Zvi+kHNsWS+5P#-S^+ty; z(UP+W$un%YF!dnMr>5r+%V`c~HV7)<sd| zIhV-6^7DHfk4Fitp5KK}aHL0ytUrP3SxJ@AHng*SP(i$h-?|r+jO>wb9y(iQ#7uD& zA2`j#NF}03zR<$bgE5yGmybEBFqqLKU%Lpv@I zRCpmKIzP_;06_R(Xlge+}nR0;xpA(r@SDEtA2Y?|85sfmKIj#vSe{P@hW|97t12 zAK1b8N%`zNnY@FMT5-s+Jl6dC5Yeze0F^r81yRohZNk?*3nz{Db1r7Iq2x7sp$TDN z@K~9d(DW*XOmc}Av<54&=vCQ1L@L!0?~zI2O-r!=tIR8)Xj4(|PdaBgF;(WL@K_{q zNa(f6uygei(B|QF(~%7BfTu48KB3=%KR`de?549g`=Idmu@4G&M#|fzD))#tn_4+1 zFAI@;P%@L%PY_G=lsp2+uyFL0eJ-{!*3^CEy)ObYG(qm7e^y{f#q{#qIvdws&5$BI z)_w%IF2cYWeW@W}?ZH-JoaW8bnOr!j?FG*T#0te5K*-eMo_|r_bl#AZ9fqmHJ8Bj^ z%Q59kjKNPOGI-JIy_pO!8)z=94%)XJXAL7(I;{mK0fhb)tie6U>b5SA$Nd>&r?h%5 z{VPbc!)la78VLb?c$CBm31L3j0-utpJ8ThRN1y{%Aru9-BcYdv$~7dW=s`McvH;ILirRJA#<|Mu$E5pV+i;n+F`?d zVD}KQ(8L623dNH^T9)CSO9-r#?o!kZnKsPLR*+24G%zdl!>R6<^c(Pm#rGV1Uh#|C z+`|+ZpEC;T&zNiuq!5GS0``zNzj5Uu1#!-yW|c&T2=MuIK{HhaD)u77{<3nWx%6rD z6xAd=ae-^>TwF?k&YsOil;6Jch(t%XUV{+lv)b`5Z09Q8pB&H8cfYDk#wg{sb<>F7 zk88mx4|P8*d;M$Kd+A<&e)_I1wN%#tsJSc=Mma@7no=#Qib{%wEM;xAjD;SKmO7Cz zrJ~J8lgQ8hIcKM+C|g^dP@uQtBLYXMFH(X_sg6NiCM_x%6K1K8xsn|QEClq^mV{nB z$~jJ*VhV{dxbxh*(ZC;#D{n>K9aESnfx*l9=yn57tJTR%*$(B!cTJ>@!Tb4E;qCE% zkd5Y1>0;|-XiU-!IrRiX@il+hKCq!XkGcYE9FsC)^ZD%svn(4YW^r;Fkr{LJtbWGo zs{@#**S1BQS);E{99!?bZ~>tfmS`)>P?na#cFYLN8k}uGWX&E^PiAo``vFGQt#Sgo z_n(Q$SZ0SC)o4D+7@w`=kLNSX#B^Bpfi)Fd3&s0G-B#eP3&m*-0Y)~-CetUyRy^U3 z&tkaw#m=K5IY*B|nuS8CQj3bF=WGZrZoco@r!5|^9om0LdR77@{dF0rC5DfV0)E=I z@|0GEe?qY@%$XnP*I!B@tK+g#G?`8*6hC9DS+}7 zSHsTNIg`{J4;qoY7R}V~@Fl+1g>zmhiJ+Hir``ebte@_g&~~Pt=Bka3yL>MylUVho0$MizBSZSd=w{RHBb)^N)U zR7;?z<=JPz{zJWZl)IOIJq%lR)X=J=3#9}_qf-2nA?N$K8)+RnnM#U{4rOfHh}spM z!qta?PMaToojOk0DXPe-DL1}C-0U$Jb?N`qKt_|?QyZcQ2~j39Ecks!XVBOx+z4za z)Q3*M^QYvMyK(BW%(wt~dF6^1*i&gT(~la#iZIv$yK+O7fj%maq?&2%+-V@w zF}}ChH5ouwnF1$gapTnF<+UF|+kb^Po?g9g6&A33ym59Aqw^juSl#3BOmL!Jj(+#dhfOWA?u6yOLh81Hyr(8${So@f z6)H|R>bK@l&G6Sb$%!e}(dLTOO78&01=F6xR<=}MrU=}XH$MIVu6a_yx)k>(ger(9Pqce$*|k_oo^ zoxPpV>uxyNPay%vRK&SH9N%W!CmcA}maFzTrR^}mkxaPo_f4h#Ojy*rgD)_@*h4I9co3~%u; zg~UyH86k8!;;uwb1g(@kdO6xQcOHg+f0pXLeQ|s1FIs7h3R+oO)yA|?#XR3=ZrBb> z$-T_~8l^?DvR5G?;f{1x%Bke)k$UCt+#6Zr3f`5-e?bCpm~x zR}!OcQbeMJKBA5KAlzDY84~~8BHrA3>H|-8kGvNxutyhk|2rE=DRx>4%vgxUQ2Iaz zZG7zjxh|X{QH1Pb)hOerl6XO6e9Z{jaI!gwA_$(#nX^p{>SuCnKB17fGXhqteQNYM z>l!y6<_NI?pTV&)wStMDVQBs{msOTdo&%Bs9M;D?2AGIoN?;-a92cS)af;1*TAp!@ z6ZI%=d}?pV!EBgNF@XUC(p5&j0qfN0M1#x zguQ0>9l0T+Xr}j$F;31)pjZ}#hzf{Uv*&hALWR78${j$0VD+?`|4u%eW!+lyMD!2; zv)B2}VqjhHfU%fqT~Gj0?DqUG#hjD=QmnPg z;G$yy@#G`i7k|U;tQw1M2y;L^gpHDj0pI-MXUz>-IYun9U>ddTowY*-;otxfmn%tXGv%J^d ziZ5?Rkm@E>uT|-|3H|Rr*gpC8!FB-f1|H~Gf4TD9N_bi|p@(m2!d>|sI!{BwW(G%Z z@AQ7M^{2YkwW;}y@4r`fg(E)hh=wd&ReK6*;g6n^4|?Q`gyI;7K4Z0HarvY{^u&I_ z*t_`i>$Es0X47@Yu@6+nt2#0qxQ+}Twne(-o1+Okf$0_M!7u*8KPe4GpZrD{=gQkW zErV$6*UgCJfV-i!4LL4YOnrk9vd~YKKCYHh%@?+@0*jV{C9!Wt7j*4@p)QTaJ+0&xNB5Tp_jL4b zh6-TGW;<*T)V8FAZ8({sK_G?8P5v%0gaRO~fGVElQK+&sJIhao_$xIFueRR1+Z7K7 zwBy%vW~`aqmneqYQ5p~G-b^j{TrLn;FHJuQDk>LFLj1*|yX7<<#vFLDnq44BY4)5m zur@4)4_UtsFD1?Vfr302Od zNjlg8QTzPqk4=vWrT5IQ)IZgBb*9n+`^KB@=mnttN|*)VmUAR|x};2RnXHvnRGYYI`HB|g+A^BEm=UY{=H8WDBI><QY&C zvU7Fv(Vv9x389WuJ{lEpxU^A#8G@*AUpFSg@IVdnoq~iGjdWGzCpD%NZBWlcEF(x3 z$qCklyp@?&=7Ku{N$#)ZcJ>l#M#<69iF2mT>E0NtO20DMW4Ue|s7hxhCzHq511w^p@1SakEy5z-a5@ijCj#Nqi&J&@ z5;~KGG|zm^^SfQ92ikh@ZX4Pc6-N%5%U6#IqaHhMi~%DthV|BYGFfuvtcmCN7YsG3 zq7(YcC<3lbeWAa#@yy~Lp|335>U}NBx&GP@-Bm}qMzeOD5tg*fqo&aF)HUNLCz*Bq zITnSWgc_?h_o0E4{e%U994Ducq(-kWjk;tZ8D^`M>bq0B*@C-JOfYJ+I1<+~cVQE< z%#}yIb-lS`D1|lZ%P*Vng3m}=9j%bpO}-~LnUtoLQ{M4}Hb=~uSIcZR$9uZ}V>uHH z-3Q!5fPe%Mf`B0WQ_l7dt`}d|x zwN)@bRSJulM3(&Pmfkyx;E>z0vlnO5EIP&4#vjMq>3AOF2ZY^4zIBJUwA^;jvI>KL z)^BmR<ikKHlfb zF`j0S;n}^m=tWYpp?iutaet;LE?6N30J33Dy2sfAsY+r~L`S zjb<%b7EJWZ0>mQX_ae7qf;@|XJh?x92ApHjG)$rUkeiCB7BzmmuI8az#lo$Uzqt+uIWZ~?7YoyGxk5BirP>p&=8anl~T~i z-e6&5GwG!HaP7uW+wo#^l4uIje!)X<_?_;MS;$j09B2ys@m|Xle~5=F z&wA8C&F8c~idJA9oj<+>jPWZ7=HHuW&%g@AfXHpSG{<)ORTStl5M}?6B`3N|3V#w# z4AvKMB()&^(Ybl74|&^B%qGS;5iNb^!lDHYfMY;VHT+EvzJd9;)@2GKtS*IhQbb~X z0s1~d!JJ!)UVvwf*wX7D58E6E$CvKiU4U4m8#>ziD6?~=-J&EzJjzVGy8wc6MZ>(M ztI#YL)E<$gqbDZbv;3oV~mgjD4S(k#;8TQQ+D{pvdma4bPEDv z|NW18ZtYfAOx66$ZK}myiclum)#q|bO=e}Yt2$9lS=obh5O*T9!_Lwp?36AL1o?}p zmh3E1Y|tUO?NdLe{z~=}kZ_&NQ|C>R6lhN}7YT!S&N&CL!RhjniZ6qFT}!*JY(BPq z%FEJuZX}NIe=^T)1RgF{bvv`ai=;|_I>=9K-uo`dX_wWo1q)#%3xPMx*~BW%)d!{u zaQ?KEX6j5~qHPv?FHb(wgTbgIRVKuFJiR%1Em9Po%-#j|=2xF9M3t4;tgD3e zo(_gfwEcSA_7CcXCA!CbRL??>S6A5yAH{*Y-%ZCgmhngNws^EA;0L zs;|~*#B%AeviqctH6W_63D2SJE1_%c{$yGHTCdKJ15#A$zZQQGGw|3dfwJ`0w>`@@ zY6^BNlxoJ{VHRr>g}xx5(6w+4Jb?6(B0Gi#TqRpz=7{6 zvuTFq^$TIJ^6h@+bO-RZd+RP_&vv?m^!q3xeW~qWF{`Z8;{>=MCx;5Y_H zHaC$+7N(8nT5A#a#eV7FI6)Lj7tavX3FEn#kAaUnap@Xgy37RWMbDbU#l|hu;PwFA z{chJq7P8fTZ>82$P32CKwwv3)*Fczo)#7PF7mW(#FEX&NiIzSx?4V)9zK%qUiD4bvj6^pe|MLn13@sx1sA~zmyab?M<)8WE8$&ahy1rE7! zAv~+$C3f?M91n19TCu zoZo|X4?^nS^e8g2@bQ(lF7;jA2Cljv_AakH939-aib|6@Gc$1&whU`h3FwO*zTsr0 zzx708^__A-G2*x)*HL5j!RH8!RvIBQ$3rppnj$mj0|ztQNH%Gsble)oNG8R|Wx&KE zM+WSDVv3D*%KtUY(#e6(q}W`fU4CWAxWr}1fTiq$Er@}E?NXOCKsmgiSpp=6KiHGG zwsUCVwdWQ?Q<}_PzKl`orn*q-0yjg~O$Rc~EvjW{F#`^`zgW!*C>tIk9@cBxvn2ydq?Ouxfy2C+bnscVl8dZios>TYy}ngOl5^aZaei zaO;GuBbtNTVaoMD2(yjKp*td4wjZT)vj6|;>h<7O`Y~Ac@?YbB7I1-9SiepmrEvn zj{VdKP5a>_s1wCCYDA|)jIv}apM!s9$(F}B=pPlKne%0EG|1v=l1Emc4YHvE|D3(2 z2b7Yv8>iwLGJ95KO?qaza+<;t8>V{NxSUN%Xh%!y;zhrXmi&D_bRd&1M!Q-&SaM+H ze2hp4NO!SiN$4+;L+F65>>^^@`qtNDC(ZC-3F&>;sReq?^An=Ym@Wy0IfXV*jOhL5jzfbuOn|0aPm@FkcB`0uyuAe%4L3j{D1cDkgb9ATj9 zIoL&b=!1N#W%)q@wlBS1lCfWahu_NcLq84&Bzu5|8@*Jf2J*Px6J=kc%y8eUzXxwo zC2Hyz`48|Z&t*`j^zwND2h(1@BH+N;%Qp!eV0-xl5GlSf#-^H^rk=8RpS65CD4PmpF55dLRwb9B6c$sTa$Ew3M z2(=Q!wfyC6(#+6Hwd>RazTJd*3Fp=(f!_=7wg z27>uQ2z+nEG^86fxP61ZeS`c_vHJ3f!QjzB@k}If`YVrcsL`Nb{eIA$y}(;E$NE1m z8eP|v{qrWelqhXiUP9gB>l*GKyyXZa->&f42o7z(jt=6dMe+P&)7@{6Q=mF_5Le#2 z52)9lL9YqzVSL1eMTQ&#Dp5Zy`CdaR+#t-sk0%P}NYpgty`wAeyO#r=l&o)I=GkTm zV#>s-*>dRwEy<7N7M4`&RKosq>~^2qpZjAnW>BwZv8kg{d?dyV+A7H3Mc#bUmRypoAqUz zA1^3C7LkA#-E3-btOt%;RajN6BHFx8WyIT)*Egt?$(@|gpJ?9Ox;+_O-whhKH1n;G zW>we0zo`dKgkOUX%7m@P2wh4 zo`@)p()7_M>)1LnOWQV3^}!>BN+?c~}CfP_lqmP9lcz}aS z+n1y65kj6rtRw&W>CYrQE?D`{o&rxCXgni3$YD__H#JH>6XST<1tp?V7sQdey7QBA zje?D){WBz1E-g<~%e+oW*3cFc_tqkUt z%9J4BlKj1jGF?>3*cy9N!rm*6WXU`YT_Q_42^>uO!(#B;;HUjFV|c}>Eg7f%lLXu* zG4rFCr>;2=YaWs%2)LC2oJaN~@i)b;5jP;X(r%O*fofztiz)wTj9K?>6@1zxiNSv| zi0!z+6Mt%C5SV}JK$|~Kv6zPIR0_UWuAP5aMW_sWE`-t84LV1aje@z?7P4jRfgfVx zy9IoC?zOo5$$MiqsOISps(TD=I~GNM*FB+e20S{4wyogl*o5XY?~ek^S8?y8=ZkpZ znm=MyJQ-|AwpX7|$khDgJN}u71R~QvtQ(r-8_c@sgU3)~@O2P?@RcZAta69`Yn2YaOwAeiun zx&iGt@{baBJB*Tensz2UBFC7P<2WM!d_)fS@!X826;qUalam)PDhGR{1Z-mxPqS%y z`9Tf9YX4q@{t!{Bk7<}! z_yc6|i8JEZVzDBgH2t9hcwMmbtg?}kdyFbGZ~+l!}Ie}x{V8lf`Aex70-kwy|;*d>}~HAT^`8?^wRVs#C6kXaU2WjVG+ zz(#)BJPK{`<^9o;=zDEMj6mgpU<2bhO>DI2(n3c4voc%t2u?$I0a>QVyn+5G)h%Z- z;aT~p<#!c`ibR+NgJVsZ_zw$y({M-P6k3xeHp^@lJdhj<-cWLfq@_C^6gO28&Likt zt~v2pVz%JB@625|1t8nBWMKOK)1Y(k0Gt9S;1P^I+6+WmjWt3V6xmgXzhiQU4QdSb zL^N`1At^eD!C^ZdtI$FbhJM*sOv8f0FNXf82$5AqILDe~c++B}w*bacSQs6a%0m3f z?R>P+eh0MgEK?9A$@+%SO@i9ubj|i(m3I$9M1qo)H>{?@G^ivha=*qJp~A*}CXJ+F z=8>-z$Jb94*N7*q1;&T;=Pps9e||&=$iLII{5M_4|4LW;f2Hdbm@e!asuWM8Jt^bgZ z8ldv(ax7O47ASsRh0b*hyC*Z zu=mwLb$rc&2?Td{4;DPQTX2Wq1b2505Zv9}-8DGD-Q9yb1Sjau&F}kt`*z=ZTklov z{;^eG-KsM^ZKtRE^yxYG&YXM4-J9pE@ICd3D|0MTjFF$yVXaU^6SqtPnos?E2747wV+KwUhaB_2G2 zH+15v*iXo+;W-)B`Q;;0Dr!(h-6G@0k$o*)TQ;b_1%Pfp(KOfzoLs}LkVp}a2 zlK>cts&00`qc5t`q~>IJNVx=7`@u$zX7t-!z2CUHLXgR|_C5W%c2VvC#7T$>@Z6@)PUedD3g^;N0Os zNd=r*`Op8nXm^c2I)BBJ(uf%+lGjd8y7h*a+twTn#;#ZT#wfeB!V1o3`jqnmueBNJ z64P)h8j=SDme;b+j=Ff#YPx zh5=#9Vu{z|1mWew+%C|yw+M!($Ak7X;NX9|vA_vN7*ium9&q2sTE)+SfM#J8d*eZ& zaoF0H3_xW$D%5!B34(*6u{tRYLWbDrAS_l{B<-P$G`4yII}?f_0rnu*WX!G#BxG$Y znTU#_>7e8>Y9MVrX3n6Hf{|fCF}yleX<+%zXmmh2t6@QeksA124K(5;Mcwz~oPJs< z!-AZvU>x;L{ka(O_AEHEvP&;|-|`~J+RUT>qNTXC)BPWb3xSA#V@qkz@GWmcI71+t zcKxSEmjeNhTHp!JGlQ#7I2tx5`1q9Xh{q(L1ClNNBybfXR6uZW)TuuRV}_QJ&~P#v zl9(W_~He4z~%Rp8>o2VpLs{!+ZRU1q0^Hg^>M)GqHMrG_ z>#3Eg?nhicML)DDWLK#kaBJiwNnMYJ)Be(|5IvWMnU5!Jj|!<~Ym(HVn^9fYld3Vs zIMU2hJa;tKRW_U``!0IAekfgDGWUr8xi3|_^RA*)txV-t zhRfHT-t!!A^ZTWY4dG+ur^wG2N-SW+D*a*x#)a>zr~|$(u#8&>)BN5lTM6?x&?(z( z)q#s$m%_)<{d}d_ntndJ>|UWU>C&;RB)(A^+F&lj54ER;CqFlFhHr7x;w5(UK#ltr zndT&qiCM{)wV?hywO#RnZ6S!pFKC>x(rJ}EvN4DT43p4o;2^gS3-uE zKXLbN2_Td)`6WY*Vy+#6^v$QnwGxfx`ZFbTA9F_NZ!_*tofXNo4@Gk&k9&4H$qE}( zXFfHIK3Ms8GNe!BF^(#=s<|@usOq-|?@VkMGB-{V40u{>YkC(7Z*C8Ej8QS3C4y#! zs$I>Qqi!_g24Y@s_gR&aCO7WOjjMv9+g5VOchilVF1tQO%z*c1O`k->GpA}-5Sm{} zI`W|j9TqXiIk~aboqx0c80V%er@@VMuM*PVmuSo6JyYUJ{=pxmX>r(wU4C@!^T4@g zfi+6%?p~MB*XNQjpQdC!_@AUK+V)Jr=+-{9JNn4#x8zt|+S{a5QuL597@a$$i(w|k zkJRH@;RX=neReyYWLO4|>atDAow=WFQ9K@dJVB1>I`_b%dx$S$j2X!ExIlRGN*y^a`( zDk*!^V|O?*7F1_olTGao>9yF`3|$)?dz6#DEbPNmDSF@bei8XZEqKy^ux#39>`%j< zD4xGfXb|{UueLb8In+e`wt0mkZRg$8M^v{(X~?%j0al4i&ka!GJETnqTC>Lt9X_#P z^JTBGtlOlH0{dG!U)QoMpgMYU?Cd_Bh5eS|zwS5)rQAvSM%>sangH^c4Z+_Y>tKld z<;moUZL8zo5Au$$=O0r>IshkGXuUHU>Lae*O454gaoQ2w(Xri(JpjuSwms-Q@ThOe zKLUg0Fz6drOdb(7n13GDE5aD2b@H0%)iE$oJzt!|hM_$Lcbal1@_ER9TS)uNE61Vc z8n;$7APL1nYn5DU^t`7~%TbwTyzfcH(j?P6b_7BDql;E})ea>1W=C=w6dbT6w*q76 zlI|O&|E;@J zb+$;8Md)w6X|!gM_8%aJA9MZk8bn1B_(nwzzK!=yTR>xNLj1tRx`W2L;x4Af`l1}= zz| zZBwwubW^bOLx;H5ySl-?7n^{v2Rq{pfguqnv9PdW)X-*Vg2`qzcLd;1@>*24xA->o zy`GtOb3HOgnwzTTt=~Hg^xcD*v#aN5`v3RrDHzKPvn&5m#}WDDvh$xtPo=4t=*=BM zyq2SFeN*swr~$nYlp}qjwr~@)&Foy0t3Xro#;|nrL8glXJz=p{{3rp|wnxsIVSqIX z{T`5ld-~Ss;eie)si2_@d;2Fww2!f2x>a^4e}WeZ8v3mCxh~Wm^!+tp6Tt548!=%u z&$N_Uqa<+jxrr?Fq;VY#s90UJ_BF4Xo4H+JIOQ(aSAq+DO3{^6dI^HkgRsR>;V zqb23L>W!lhT$NUqBVSKt_%n|ajPlM(s^+M;hBVD)IZ6&StcLO^yf0_VZSo8<8Ujyi zxhl#QV2^vucf3+H>jJTnYzt8R`QwZuUDX7UaoOM~=t`3B!6l7*dP<2VtDCtU_kAy` z3h#fHoFL_S>Tooe8uA?7A;dIP^S9_mx-Pb0idwGUY1(hw(73#q@|*S=$681vTF{u$ zFC&>RN~_Zisauhoi98A-q?whGyOmYEuQcV)-yHucx*jvS+xgwphX%wrszorQ^@ZF4 z#JD2If3O|3d=<5sQpU`zD)v!Tbx3Qlo`t z=7nHGdY6_#OO9nE!JENREiypSTkO_NAB)Oe%}v3nv7YCopvQ_`%|`-Bhaq-+%yg)Q zYQ?lp)(2d=GUjV{yCyF80=_v|^LjN{usppTrt%Bs)(ht4d-aNop9)rA?byD^$a>9G zDX~;DB(iJZ%iJuyK=R^#x@Htbp|kIqZzRReTJBN9&p7J&W=DSjd7HG77R2zmNsTaz zX(aD3edvd+6HngTao}e}tEhb&S-07l1t|)xj#JZKPE4zfwYAr$*Z=Sl8E&hOQe6N= z2>5xJ?5`hyU2NR?2RlP82+66dH9VUbnYM3723^+E^-I{BJAoBHy;2m zti(>*q`VKV|F8_Xk`#T1{_IhQZ}ejqcp`e2E$xw~1kV^ThIY0EEMUg~%e4BJ$1+`~ zU=7F7Dmn}uPqf|)eMc&|tgK|nK(rbLTup$&`)BMPuimAaNSKmnzP%-h5I4r5-(h%@ z<)!9UmpV}O46+U9v^$=veq6kY>Mtjeod7b0pmlOUHoYA^`x#FCIBBz(%^aYPy zZZj=B5#JSBjgDO1!u&^XRipLNqILgQJirWkYUpndnD+orE1m~D`7L_9=MIt&CD)N8 zS)h1+Bci>Mdn;-Bo&5LX!J@xVWRJl*;}>srteda^15&sOYXOn~mQSg)Uo-d`tFqO2 z5WFP(F)IfrTgRmCLc)?Xwm6Md=7cQuFo$gVZIkV8%9TV*4W*546b(|OZ#P%uOr2%w z*mtYIS2L6dAmMfy>$7DSw34z~XE^%5ol`%RgIq8~9;?flE6zKpd^+L}xIpYS+2sKr zCj5AG&A|nDxbfd_X2X&L6Z>Cs0n5L4fzKZoPzEUa?rI4UFR(qoQPv(I1-YQ$_v4XT znotzT1*eA|nX_1!ks-7vPT;UZMSP0Yzr0#cv;}}suoe#ujDpQsEA~?wSy}Utfn;^% zKcj#sLXUszM6D?N^HB8gNq#@7wDZduSgP<0Puk_m+qLeJ%Ju;J)4OczD6OPdmmp@Z41>x4&wY@`&Hqgi^39tA)HiP^|MGz?@F0w%k-d_U zqa)~v7>57toQYoF%sNyrSdU7VN`KIB(11#B(r8ex_)TaN(+;>gr$B8w395J^m=V~| zQg|F}Y5_60;w4!z9BI_FybHIDo;T&f<-{2 zA-)%|bksHdiF*C`ysd-5H^CubulN-n9>ZZTFpJ*9vj0l;>+>E$(*D@>%I)`@liSZ; zs+2i9mEW=;qO?0!87i}v+9mp48>`^A!RLL)Zy6SF77Ty6CO6fnoy0h4W{${f>kZ|; z^eTHy_wBKZ@e)EL@^CQhJL;_*sxM$(!d5W2-8PaecqrgyWgaa=wK9mWyu>Q0<)vnN zXbI&>JnTm8Yw}sDH`Bf}JobPWSrgfFO#d?BZA}^qT!OXmf6Ck&O><(nHy)D3qz;nq zYTFUP;(v*;lx2?fhN6k`7j9L%tn@b1*NM8iBNLtZN5ylZ z`TMz2T{4~cJ(D=oegEhbk-IV0uONT6YHt$(35qU^uim)0Ett*j%BH1#aQDlyJ1&`!?a{6izMUC zia&2lqh_$%p;0T}UG7gO)+Sl%p!AS2GIQnKTJx2v?4FzM^>-KLc$rJS+pQRC)?&yg{Utb&dXop87}f$n%@@>+j!@w9j_W?%<4fq0d^g@r!pFZnvVMn}{>n z+cJ5o#t&tUo*!Lrrf138hHtMvxWW+{(qpx0nO<%hiUi*9Deq}P-T9@_JKgHQ&2A#- z!>`djF-er|EaGP`IbihofHJtAkA?Smn!k3*HwRgK&ON35SPml3(U$WtnRT4YFVZsC*O5 zRorv^`UaEse4DK+4FMw?zuDv2%r>a3weZKeCNvywPX?H1Mw%dsEFjTkEaur474a@> ze^{T}ADU+pjO?#AdAfPZsOx;5zd31e;r~>%Ztd|!`my7@wJg>nQ{COZ9XUk1Y$EsU zm+9l2^zHFV*rS{y+-m!!;ni&;i`eh*5dO0l^)aUAVBV`|9Oj#nNR9Gy?RxHq-{lc7 zGRe+zb&bAc3JN9#vcsdV6$}r~nY>3%k^W|ObwN%{dygkNgegpNzT9|%=opZD5^!UEtaC+Y&MNxhGa}Ty{+PU>-g|Q z>i}^Mu%A?j5GN-iK4k_j_5gu0veAnU-B|E27dtj*R@HYE8!Dbw{S)_b*N9 z#sPE1U3nyoxM2UYc^~km*h;4l-n?}|mMhI=P#~K;^Jbr5uc1hzK{+2ktr{ zm3^6$8xQ;>mG-DO%xkrnC6hL_*Ngt=iaVE$_P+JkRk)i&anON?dHILxkikA7Yl|o~pW02!`x#SHT z^+Jz%hv?R{g!$&Es1D-Ca(U#TBb`P~y?(;^x(c*JUU7Am%i2YoU6lgwsR^U>jQ92y z=a}BfS#8;>0`K$O1Se}BVaO4t=W9eOG{eyO_BZT)W$azklRKSTsLtaQ4fE{(&dka@ zxX!2eap-*RnK_)rjwB+!!fVE^P5NppoRUd?yyoBDlIU_eF($uenqnePr{DP+R|YX+ zx{Qb5Glh(e;Ddq*2GpGY;0Eo#UzR@pt1SJiEd8r2{i`hft1SJiEd9SKOX5=G5K{lG z)eI&g9J>YL1JO;>nOUBvmx&Kbvl4eT z#Sk+nN>Y_zVIE{+B}mIy-Thw-CEC9F0nf;$QRjzk=n3e|xPrZwN|buRJm1Q|HTN=V zzb|YwW(XGjz_~PU{C+3gnqMnZIdbZO4#gL0WWMBEz>l&qMak#cpYIL5ibu*0hdCQ) zrEix=33=U?xglU`osKFpl#0NOu_)P5`Q=QRmz922zY()dYz3`lwshV73x&I6|d4lX?A-`1Pc`J@%`Sd+HW_A(Y_85}bW*#(I8p&%qkBS#h?G1Dj#?spRJ_!dY;H@U-GUDjg ziqr?is>}5sAyDTWw6*b_14gp&k$pBYn8F`zeOqaEZCF`o85x#uPgc>mV=ycMn6q*gqfj8krRkEnQX-!wR2%98Ej21{FPr`jaJ;v=lST zX$Ld)aB+8hzA7KY74u(w2)Fe_l{kvS_FAoXm(;Z8`GPwzhwYZ7n)uaDECQOIBv>^z zx0WZekh{kuGLfs`uub+oPjoLirZ>SLY8p=P+{|4zE~AGi9Gj+bKaIFT{GBk^*iQ1M zgCNazM0>*oDx^ZFseFgYjp`Hdm#I}YkF$I);jox3#E$F?nBOm7BBrfvqir45MHF1p zM0)qXJ~)Q77*S&ox)d|F$KugQ(yACYwg`M)om#(K>pU7oym@z;^kGv+@cJ8HgN^hO zf_*Up>I#>_lA3ZkTR8LT0!8+xdaF`;;j+7@qxHR~mi2DeZD{^{tvus1-5iwC=kbCn zEfJ3=+4dXAcGG1w3^UQC;psBP+?IEVNf42}4_C8=VHwfwy?>*GU}T}>#yqHc+`yr zYz&*6Q?_$*^nQ8K?8;ImxVP!xEn7X}gGBxiw;zxvzu_500MB=sF!1GBu9ng2pQS64s~gXliB8WNy2#^iuiEFB zOtA_U>)6N0EG27x0+ZelA&^59`wD}@)V<24etlU;o9uwvnmY-Rys&gep~PVkw`pPU zgf)N2;*q>LOCAy1PIR1idu;!4mCC#&yr(Mo5}~DQQ0-uIPuYP0@%GpNO&9pwXQAA~ z{oh$8vHWY9^si;ozm`e=S|#F)|xw8wxM5kO;0xIDs{ii77})9TlG!g24z)%@wEaPbBf67|!UQ z%Q)-tY_hq_DdOJWyyMSu7~jA9^_)KO>cI023K~L>_{}?T)X8^(#Hp$^kR)xi!9@x` zGKx^zB4_xOfcL>4T`_pq;g;UWOA~h}T#A9AgMAW+NzSZh`1Xe6C&in$U_2N3(r*67h z5*?Et+dyVkE4y{#r#2{KL4!sLiX_DURA#Y(Vvr#OgVP@ zj_o{`2d*GSn{`ceJwu37e4e3UF@KBm*&cB^-3Uh5eQ`_{TboGtYf$zF<+(_xke(I# zxcNlQ#3P$2Xf)-VPb&Uc!ye}kZ$3M%cz95!N;};Jt+`hixfpkUx~~3CcaEf?XoSP* z8A9h=9Z*-Z=Ty+ca+cV#jaeN9mQt%kXW#>#7(Tp}>bWp!2t%ijs?xkrCz)&*%BLYU zH17S#qfk9=I)N|jzWj-L+kqb<#=U|(Sx7czYQK`<>7qOrTpN$86)r3KG(L&`oJ6HG zZk?wsq~)5rJR`O#E3u-EE37)0m2j!KNvr%-82Hzp)Srt~9Gg6Q5srkZyssqk--ZYG z`Ra{aVzyr`m9gX%7Ig`z?0HOISi}VPtZSR)E8r)b*gk+v+Fhn3q*Nip=<>4og3>8q|KJ&rvTTO}q{sT@U*;n9H6p6tRys zpKFZ2W~~!QWXb%sTZObHUdQP-F_Ox0-OL(8a>VZEu-p=cTZ_*UxM)&AA$4_%hi>@^n zC5a24&i1^gZxnFr3ycrEiWBJu%fhAKS^dhprIRQa5@l6f(s@31bcy%YUcr@rr24_i zcdv_nyKhcR_DQdBIlHGwL1naZ83pcB7+<^d;o*qAnY02>cNGqE#n%$wC(MR zBQV9PnlAKDdsXsL4BjJYX@h)ciAs!w{BSCYVrkPuyRK3TFfDZ(5nWN{&lbfH~6fPh_GtQmrEw){hN6uR^1 zFxm!{AF?8^)jqQcF?r~jczMe8q8cRc=BW^2GcRNF*X*}dtd}bbZLQt&exYWCJ8*CL zLMI&>CX8oKNFd}JP@LWm3qH5!Eir30Lp2xnwMXZ=z*FW~sSucYWQ;-E)YE)6DL{zN z`{}b(Z~R#=OxML6(P}hFG!@3BX)e3o>pCtS!g*wD1AY6RK;tb7xe8V`0+9Ukx(-am>9>UYwHrh|%^PjGj2=MI>s(>BXyhGo9q|KH{Hc$4<}Ji`BSf4t%Kx;Zz~ z+2M6F#?blt^qv3p=I-@jbMEya>ap{y>&+O^>(k*K|LZk~b2mu!^)88D`}wi+`R?_$ zD9iidW?#i`4)^Y5t6r^^w3@5h@J_9~su$J_4;U1i>nGZPz6+d-;PMZne% zH)A^9t~Yyg?46N~Z4b`Rn-wp*lRJFv63cYMc+NPtW2QTW(;7WbIU2(H4S`SXQA_?$ z%~8VUFBaQKb%}ihecbV=_djImsJwSx%ZyhF6u-WRQxhVG%B6H{S20j|Kd&7wNL~C^ zDsUAD(s_;S?8tt)nVR<8_$SVLL`O&d<)PT{^|;{vsYH<{yQj)~;t%ewNQa?sUoK(m zEy0N^LcvoB6S|bxj42$uD5a&gfn!7qt0-2Y!FI_nmLtqt&H;PLLs`>j-x0+Ga+V`l z=u&J?!Z`U1%x@8*l!3UJY^-naSlWNmryY6W5a z;?3tmNZq`^UI1lijt7aiXywP7*@4&d?i7mcND98QLtVcEoXuPuo^^2WYs>@UVlfHR zY;{flIoo^_z8M5SMNK-q|1mP8b2t;%jS7e?U%P#BTeV8dZ%R3`n}(HXUQb z(pUs!z5C;aWqHhE@uq2n4ck1>g>8L5JDvro3ytlx2v$@)R{Z_HG2?&pq~rZVs!6eP zNsX{Zp~tSktFA^uKQAy(hR@0}cJZdZ+B!}SFYS-5J2U+hA-w!_@K%e9J80DkJyR4} zY-|#i*ITB4@hscc4;4koptb@$_5hD9`DPz2a6y*#uKg8(Q(^y5Is({>r)>kM2O#;L zehM9%wgJ%9$#g)nE!(D3>VRm#wZv7i1L}cm8Cn2LaOV9>tA%bJ!hqZ54PZ@2_jKwbT3WV;Y;Xweb`0FJt;84m9MeViJF& zOpf@v+okS`J;cHt^_j&Hz2#*n#wrr@dUxFh$jslPOnM5obI4qfW$!~YY!R6T`=5ar zgNfd(Va1C z=do!mPnie2e<}sjdEm(1XSI;H1 z0Q94=c30m5akEw5a&G4I=Q1~DjxYf~9CZ}U(SiJMI5`)^1MeCzb!GmH|amw zkX_g`rVb0p#C8kEt?c3Nx`ub70RZx@Yhd?wESAvsv7F%x>3{)Bb|HoVaE#21Rp@qn zIVCnIN`Gz4S;uBhxh4D}5F&`$UprEaIxP+zV01tyOaU<>DY$B13LP|ZDsvK+{(9OG zJ=k^4?e2-g%Sqa{8{XUT2gXMWwJpJVdJ%q<5?c{ShY59BUi_HE@CC7vL!=NO5L(Om zX(>GiKT4jBk}3^6e*5>(-o2rNyFCxjQhJK`z@d2_lahB(ftEE8-_;yZi zKEiNI{mE6UbU6`cC?_5?&cG}eO42m4gl{eDE;%Nc{E(S3qC#ohDXSFoK}38@D-_AT zwMBVRW8;`cazTV?2#~{>k=&+6EVXeFQ@y5oL1d9JkcFM~qf=P!Y%Zdy1I-Z9hUpiA zZhix%1sP(2CVb<2994`$yrnDeyne%_#cCDkut`xGlwoo6bG4+1xjJ&YrdP5x6Q$K- zbA6v^O{OaKUhkcADMC+^NFUJLHZ@~jyHs>{aOTVhB;AbhJ8&b5JK z;k}N&qu1~0z)@#|Q*Lwptzs>|%(B+>AVfROGEW9|mV(_PPN1J)!4s=^17Ge}n?Gr* zYpU}_@A($WPBpV=_lYfA55BXhwVD%-PfG*2KWT^goM*>#PYhV? zFpY@H+Ulqt)dIsY9D;@8JwGL;i!6yr99s&&+CIsPCS=96UvxCf}i015|;J)pNpxj*!ZAqY6lZ~#szgMl8m<7WWH>AfH& zGx`R7{^!U>L?$}`rHA^DEs-EwoWe1r>Hu5r8$bjTkTfSd0Fo&Ws<+OW*J%a#>54Gl zmFlKp&^QwZd{?jQUZQIoE5*=^?q0bj!#COwa8Rfo>&EjE-n2?wUkpYkl%eLG?#^Q} z>My@ygR?ch!(1;UN@L}?N|RcO;3JJzbH(%QWvl$f_OM9XC%0+qu{5Utgs$znX?2ZK z=>}?F+(E5u+Z9{b<&3eiS7=?bqVxWg)kBSX%2im7;)W=Z9kD8)#ximLsbgfs8q@Sz z|7$noF&?&YyN{kT&W2Eq6SyB6WZ-(`d9g|u6r=?qc0NzF41aM$*UGh@N_7XsW#i-& zUYiX60UIJy{c@4pqt?%NFjzFkjLO`Lin*;*={+=_eb{}#dliFD& zI;}u6zZ*D@if1)ZxQ)@+qaDs%>DSD6QWvxqw2ATB1%~BxK4=gv`2wS0?6OTggFWoZ z*lL}2EGE?;Vv!bjI@Jw$%~EA|EVoTP?(oMN8_lJ$;ClH$+OBIIt_|k)m`0m=C_4=k zxW@M}t~T{R_Of5bDC^~2tBk8`G>qWizOOyB+8wi%of}W(uAL{YM~HoQAl_5RRwrTi zF(?5Ki!fPPx*iJ_8M9<}f!GQ+w#u8WT6m^=5D}jJAUta?Jj*RC^bXO?-9daNSlGN> zcl8nB>Aj&;jHoguTR+Z!|VN1{C+PcLDY|QcL+)ZRnBJe3758=%X`X*h1E27ML zfir1|as6WhcL&T+xSa@q>`sVZYh`px=;$70o)&O z6BkHYB=!|G)A@+}>psgwrnKd}}voY6wF zf*1rr3?e0g00MhF!jH_;j%Ls&5#XbG1QC{k0KzceS397)^bYIIFik<(fIlMtmZF9J zheFTz?Run%WgqOjO?VDnwz?rvj>ZQ;IEXCsrF?c~WTj+@xAQ1@FI4WGhi4AU1~ zpF%n;Q?_=2I&X;7*pK2}#A1^l0us{w*r)||@$1EN==Y@yuyY;c#3qe1+_|8v=2MDZ zRjN$1xH+x94wmS&HE)h9)O{G;I!+vTJLU_K3IWIB?eb+Z892gWnqq3X&=_}t{UIzg z1glpI)am*dcip6{P;sd5LQcaZ;0c14nhm*SD>W&Z_h3I%gk3Gbv1gCZwd}3>|Hu%| zvjqopS+?7Re0PSQ9Ds-1dpuUdrl=g1U?*~&W#_WZZ)@?_fV#01k^@;-pstFKq>~ zB?T&ix?}>_7xj>FH3iCQsKI$pP?d|zWlvDa{xHLBG7fPWXk!~u$9WFK2QK@i^AE)} zu}uga^M${H+KM=4Bre7A5}=(<97};BpkA2+TC=i)QNPG|lVhMoUvk_N6qDp*G$xf1 z3-#l=$|fuLzyY)YUjfxIz9k^lUB)17lVu=n$$(V^)bf91bpcDnV2^Q`V+zTPv_VoC zaG-YA><=ssYDHo}dd7v)fp%*gq^*b%)B-6B==_9gKr!u@pWFyiy&M8Ev?c)r>jD={ zaQI^sXg7CbXkyk~EW9L&5V$GLh9^u(BnpmxG(PY>THU;hgNdaRB(5^>+#?oxhxH~d4AEIhDxcCVpHM}nzMsC}GkmDY=y z8`UtKdSwJfkSffLV|K>6v7@K!+TzH?Nu1V zaADb`gi^5n&AnYCH9ZZvNr?oMOG?zB_E~^-V?=MG-Za5|n*;7f76O!Dx6H*~H;iWj zIb9{&-{xo^$>iM2w9lpqUF>`qJhKun{w`>D2O5=swIk-6fgh#<<)`OAjvU#1$GZz61-e9V zeseNj0$+r{k9@J^&uzR^cRGs?9DEkt`(okBkS-K>#q5Q?n1{kA;V#kjxxvA$DTdFB zhmLdk@=-4z;a@|Cz_5!*w4-ZO6c;&68u!sg`1yyW<;ITtpimDV;3r4t2967+VL&({ z28L~UW7CD6R@B;gaHlY3?bc@B6Q$Tvp}&%$o%wHh8|o`4K1E4m*MdMn5GZXC`Wh1= zA#=h1F^8=0^~Yz+3CDPGyp+&e&Z}xz>gD~>9^8D>EM_E{=v>cno^t*_ga;}RVL1;( z$jk%?@D)yOLSmt>f?}bk>cF_=!Z>vRMk$CH$dyM>mVm?$#HaW``LUP@B*PZlhZuVD zaG+Nzw*yn7w7Co%cKM>`IDL=#yiXe3|5k%_I_hC(WV7rAzqrH{-=9o5)f{c|SVk!i zS={+lKOw2tgF3~xuS+oT{HY(;VWAqiJfs<14Zj`-(d*M=Ij`+J*|JHjG%(i&A-a)f z!0;COt*5BfP4k{hm#b6C@wA_5Ey;PgKCFhhg{oZp&m154^;C%$wLNCQe@?%Zfmcd* zmRUU^G(gw!lPq*0@6s*rIwq0}ETz4bD!xL`_-TAtZLD|9Xbr#m%Jmstz=9mzQLXCW z_S73|n6pCp3kTGgE$Zqkec-qRjYj-%*`*RgUcsZO&Zg`bXz&N%$ycdL#qm2=u@(y` z?LnkY(@vsm`4mpVvh*orA2^NY+ONnL>pt5~r7qGs7{Y-nPZONXpk#VDpXWgm~GrdE$H zV-p}UqL7?dZOSRx;E>pj50QIZmk-DW?W4&F>7 zHp&^@l8ZC$Gm0^0iwL|%9B79=X8UeSg+9T7*m75t6Dn7wGR}e6w2wYKuQ-4#x=tT) z+$SAF*cNf8Jo%dgvB~L01~{k1gf;%@Jb_Po!=p1mSgQvSB0&Tj3;a_(5JAcbAbcqT z5l8{Tc3D>1t-DGn9OZ({>2e$Tayf4jkP4@zz|Fuh{19g~!f9rB&zxc_<$m@USCJj! za`{>uh#?bTaEO^D2~L8n}y6iPOUG6K|qhJ_?y$+PIlY!o;RHB znPahtRUl_VC7I5leS!85?J$#^#Y7^URN7HJmv%ou>mE44MwDrYeufnCB zoK^EFgob5tQpu(c1e2-2Fiq9)$#vMny0b1oJAq&=hwGgmfuRS2C2I==#@-hQOcL4& zZNxd4%nS{(CIe+t^`bjx7ZB5buvORXyu%6xn6!XM0R)ken12hN&~kPG;o5zNg=qv5 zrt$#sERDdhC8q0&5xa4Ajr*+bzT<{c1iHZ=)RL`sAhzS|>W@J?f$pWFT;xPxK02c(LB0*9nAgOealzk#dN*yExApc11&;nA?bs(v6kQC>CO{$y>77*al1;wAt zzb^!eX%k_P(|NDUM&2DLh}wSXWn1nGA*#)qz`Wm9nbk#u++DsX%TVd-|if4JB)aQFAE4H?A zzsQ3eQ#5@Qnb%Kg$osmM=4e~^m1phecFkc4%N!KfQf!E)stoJLOHH4DT4LUe3&u51 zUz4W4a)H+o;g!h@w&;rXwMu|q=5it$f#O#b_^0PKDsapxb0(nP~4}|nD&~TG>3>HHFnDr7atabsL0Z6gD zHXvpZSKUVx396~wQWt?>3b&FRv;bv43J4_4W;H<1K;e=Cx>UG*C~XH$J@d4IjJ$*e zl&EU!=?UI0`(sPE1w;z`8m4hX?5%7Q+7~!@7+&T?Zth5Bi)15-6j%pQ@+&};c@X&i z4>%48imCfV3XBh5Iskzw=LKRk-2DgS+BQYog5D{A;sD`XK)5GX5GV!$WrFSE#r6Pl z8zTsJWskTMZggKL6PzTJ)&Ro<>J!K=e^7Q&^m3Zk0Zv0pLv{rRP**?M0nMX+3*U_H z$YY)zn?DpM=v>{q#=KNR121YPVv+lpzt5H z4yu89i#9IOMlNTZMWl}=Wc+>Kl_XPol+sbY9)^j#$RiiI#DNj&gMc}HpBTaBvh09A z&0~Mg^U=P?7ID%W~sRCruq|AyKPG8Szb7C(EX~pa8r{ zJ+#`UW*F*8bb&uP9U!00*#yS|p^(j~1&5x|L(!|A`UuOCpbAX0Y0=&K#|<#lKw|#` zv`gFz0js%L_D9Dws$v4gOVmwI0f-d33VX?_KgVD3{EI9j4p4A^0pYelt5svTAVG(U za;6-YDMlj9$UwKILSCg0z6f_0`04zN2;B8JPa%NXu)(BFcKd^F!qso`Hs5o)5TI8p zGrM?Y47tERT=GgAE+^rz#>|7AE&w$*1u+h2lW$#s$}1HlH_l@!^(e?}MIg!P+f^n^ zy{~&<&TonjI<@pCyT8>x{p7)$hmi)nqY8PKR9)v8E0C=J7=X2sg z^Dk66@coVZBLbS^fi6#>Kyy5iBQT_%v;PpVC~y6el>pS9 z-rkJYWJ-`55~2JF)Wz}gGjKm~-Hw;|;S^b&60_8?{Pt1s^`@r{s)**+@5zZ)VOWq1 z4em3SReOe7W_(>gS1Uok7qaxdTMg0sx~PUlq*xe&f~-aNd|~Q3y@$|cBrYiDN}yN9 zEMTh)kR>@`QbaL`^!UpR-GRz{X@TOr6UFlwcrIHK>46+dQV8S_|7dZ-M#& z7$0adpo&ZdniyO9!w9ZjII9G59%22T zgjQ}7vjG+2VeQ8%5H9Tl!0eF+0%xdc2et9A$jnBzpx;%|1v?NsTT!Qj=NtzQ0dqlQ za(EscP>R1tCZ~g&fpF0cAW-5DSl5W&KZOzpRB8~8^Do@rAjh&I2iX6H1B$>OvW1i$ zJ^>Tw|3bd1L9?O;it}iIk|r!oK@=~(Px?(w5D;L`lTDzYXhH$SSBt(`V>sr!dy~qM z0TOU-U!UQ}He%J&zq~fzT(3<*N@pRv{&Wy$Ve7cg|9m>VoswYE{ zYW16Wdkqbqtf%KEtnc;xd^2Zjy;lq|gNNzV!vVc78#X^Ote6prB;KM@#=K}M5vm{& z)xAYUd0PeLQn=-lwCLteeeFB3_%m}&T*=8y`pPlHX{S4)xyI!7cC>4A`d~0X%wIeB zm)?6)w=|t}v4Ag2?FdbVOyzx?N`7!KblgQc*~qxpt%5%`8+@Cv$REx+S)Gnf4+j(2 z<&8Idw3><;PX@d#WT{^?37T!8q|z@mdEGqr%;l1f0#?50J9_XQaGw=7+sa9$w|aE$ zjUGH74H8Toe-XHx?5zTu;tZV|<9@0{@b}m{6VP_V)Z>SGkK`$twnyavt%|Vj_V|#)bxR;1K-3}2h#0*WG7htha@dazxYjSQ4GVp68=ZB(df;_5jQ1+WJ zL)_6*h0W#hY)+=tE!_isYj^OyubqQCmqGQ*R7#>SsnJ%BCmas)NY`}($~WbqCj6VHcWR`-VB$G1f>%SA%D zU{A#03Nd^qpfdLwLWNZfWP-pGFDMHQ^(li58UzI3<_x}#xX~v{%^x<*^V5j~x*-vY z7y<1q3e!@T&@l?`S5xxZK+@iO0qjeZtCBk;l(DYd3{oyGHGIh6dPK}1^xQ^25pI!p zuF#OFiLD0DQ(%YC=*4}5obp-e-1`D<_Fn1WSD*54a{9WJq1-I=oe}dRpb!1ffXBXN z?a~D}nMqS`<+Xlj1Q)M@$Fv5aLbjnl6!e1c{|Jo#@e^MSIX4lBTuP1l6F-q;i!I`b z*bv^h&odQFFK0Coc^n7StsnHIa0rbGY|KFrsxFYwG%@`^#-iE-AQ|kd{AEN@-0ap; zRjPOx$J@ptJHCSn-$qCl-qxpdV1A)<*Kn*qFqs<5O$rzyW`;@w{y4G+>Jrl+K-&zu zSqRIt6!`DjKB`Geb)P~M4AasA0VM{A)KKclS!o~lRFTTbexVk_mP>7n>2}C4D}ip+ zmi+?yTaB5hx@gjjGoW@B57tZEwV~(B$3SMDxlxPfkY4btIWPpjzjd5|3+tZJQd6_^ zq=>Gd!?~QA=4CiaR+9EHogD1KYpiEtNNwLEts-<2In2bue5AT-t2Vv0pNI(XUkvhv z9QXOzAn1aanjf9zFiHF#oPWnbgZe!NKf0wIq9p;$DAMnA6!86ae)83}cI;JXRkT;wDQ%a=!~{p?Nq*>peSkxd6gT)KfNjwbLY zAMPJS_KNN3mLlVo4!YF#sTqDuAE0JAlXYyN?u8Nk6S@h0B5{&}mN1hXz!Jt_2dFrR ziFN=L+~php&ZrwTu%yWWiV~IYkp)wfp zG>L;yXK#=e1|A~0fAj=^?v$}Uc7M52yp}rnJVo>Of)gQUxylApfOYvYgy*WIubmf_Bv0WcbNZv9| z6aXvA372R(p8k0&a40w%eSbVXOL9%-IcwP~4n8y;;avW*Ku z7IWawkDP|Q2$%tWCf+kx&L~?;8`lAFVFcaB9d5;X5HScCMP%cGGcgkP0v+4noW2tR zgo7ULkf?7JZRAu(m@hj>ug&*DEZd+iVY7VvldNutXFfhz?+fS;{*U&~J07mC>-(b& zLJXouH$?AkbWx&4joyV2!C>^>MK39$6CniALl}hUJ$moG*NBqjImvxJPp-@3z2E!) z_Z>bnd(Q0rJ!|jTr>%8n{WN?r4yE$O`QkATPw88B8e{1K>{_j92{gZYnf*As=aeF1 z!UUn2JAMJjDbajIa#%dy+T_?@?N5rSlLn+mlY6O0#beJA4I3#~CJ0=bIor0a zqF>dzWg4<;{cr^1ZXRQ`dG(g!A`{QE*n&z>n%k>WHo|G+Bz%0hz`{!}hOwdzS-fb! zh0y{FLU|PSg8MLi<9sUkT?5CIXeio)qwY}Ya3;Gj3C?cnmP~lnI^7WLmQ-pI9I&h; z!@cMIxa+%n9i6qo$z+wK#MhtqH?^$PB?FX<_!U^Y_A z(iGv1lDty~7YlapgP>zbcr$PBg#LJ^i4PA#st5-qvS~B57Ud)lk`Ld;7!JORwwYRo za#Fk=aPHuVH0sWy=j73|W2GkyZq1_?{8fBS7(7zli)OJ!kX1vkU&|a*EKlT5^yUFU zISsoKG1oI(lGI3R(WAm7UY+p=ui$?JURf!BhEiXm6ZGZ*ocY#9>#)ScKYo{$677*Oa#0+ zZD@*c7Ks?3Mt(SpR`B*Ae&XAX6UOz5X|Y>=jGR}rjg)2xIlA^~X*De)6_!;{@xlX! zt!i^=C;{ zGzN6r2rf_0xw|i*_3be7?vf)Vcr8!cy(xcqMS#V0s}Sm)zNeQS+B1)iE(+w%#fsOz zpX>QXb_VE2p&(Xx%mgO_Cg#D@=OzF6&wI43o9BVMzVmH(>Y$){NekZob~aY6o+{Hz zRN}1={MyQgZb`eXgtKf;0UvAE z2m|reN+HiQ0<<~|O0IbOV=M4j8v&?C>PJm7#q6<*zWQnjT3o4Nl#lV!@yD|DGs*(L7e= zhPf7~n?)U&Q9_zQ?eUQ{c8r9nEfhMmd9w*_+&*WZTh|UJfBj{r620RMzth>>BnW4quZuduwf+A5^5PWeaoBi@T{ zaQGT8uVF*!DvV`d`*pJBHYW~0W@pf#qF%Y8WUkZ^DGvV@>p*1;>iq=b{3lR22RF%J z1vGM=k{^3x!U-)TNjl0A58-j31H2_DbL>k4Q6+0-LhX*y%w~-EhH8y72s0%~9e#c( zL+m#4xaAx3eSCaU>*8aHU*5Tdin~M`bt=8P7mAa`wM=i?q1zBY|NX@^LCe6kl^rt5m?jJub{5n`hngWmO0 zy6ZGlw4Q4kUBVBk1|r{P`Kowy5BnrEwTjC}(1mW}vN>jf)Zx4#-Z9gh2hK29A+KBd zNLH_iXu89Uk5-5`z=S?pZ*^;9fY?UW6r55KE#vW66wbk1^q3R8$tJr>O+-SG{V)VL z${z4~`jM=F54wOCZNQZ)oftaeo6`efVdu;|>)950*IrnaT%|e8gZqir{)h^N$suT8 z&X|{D;CX?JhYgRFf!?pt-N}HMJrYht=?nRJVzP{J4^d@eATj=40~h(FtI6EB3?2aje* zSREAuQ517Wuvj}bi(0Id`hE0^!OayccEbKF(=LL2P2=0788E!04y8^;XY_jYPh&8T zBC%2DCC83VYgdRLPB7avkZ(V9Z%{GXiRiAICEsjgtxnrUp4W+nn>p$1&V${Fcl>*d ztoDKBmE`5lhaZc{;=_#u*%%wA3D}ppXTp8lxxh}Hp)Qa+{2!n6HL*UuOE4#3z#?24 zt4^%fUxna~IC*b+s7%U;hifEW$!(7l{RV0%FL;4yyT9M|h?>HC8GX-TmB7XP1nmE< z(s!m$pa*ABxY22FY$j-YQD3-MCag3a3*M5~=I@`0pqns9`o`SCRP=(Uf_!1hb(>7sio}KR0r>kf4_*;En^M>>tJt7jr%y!UY z6#`#o@P$)Pen#7vf!rW7cTuq444}G3KG>4}P|er{UVCVkt_--QUY*nFD(XI`ql_Cvx*S z_MmWl$ssZ(N3Rr$|K5$EFHrx9^-^P>*TAD0jb(wH-mYQy?^{Eos9zY4lkLo%U|m#z zHtC%%Fe^JmeubErBs@p3p=~g74=W|>q)*r;AdP747!qgR6g(Tk&F;uguIQU;{-xOM zW>kPWS6uCihr{O1(O|w1?eJ8w84#c+#q3P5>=0!3`+$BS4BTL0q{=u+?@*KW+Bsu; z=f!8kNk@@v-83K`zV>6XnB-STJAi#!D>eu<6Nq(Fyv(7Sdp28|g6oi9-mRkeayBgF zQ|_#@CpgJVG_7QAvF2Un!W*GC5k4jjD3hNK+`71*8u}?ysCqr*m9>l=^h>rN7=yrT zDB*8=Vrsm)rwRu!w_44Q*H(sIlj#!79c5n3J7+v7wHm_cd)6iRE5c~?2{4X{PZ?`x zMJ#!jA1D(a&sGL{brTnj6{@(58A{JPBUjFEaJHx3a+@$=AIXF^!hsOybMKl3P56dr z77!v$3=%p4%D`QnoA*sc9X4}k2jR9S&8_EY3f9t(l{DJ+K383&DU=YR-DhGcBHSEg zxtXl4Ba#msP*{OOph$MUOSE^o`ZI}P%XD>3k>z65n%ztwhP0nT77x|9Un`zd^OZ9nuJ)vRZyUQovkw-#^0Tj>~g`XMHWh zZ)+$fBWilqWWCaXkosZ~p-2~&MhT&aW^|gXw0u`49k3u@=cnts!kJ*c7J=fB27R$A zqZy2^ax{4$f&Tc?H5$5d84s)h6ayHDaGk2{(XVr7x0_7j{JNXdTl-iK9Hn(X7)fcx0Z` zr<2K()7z_raopNaiO$jLL3Nt$fBO`SMiOys+79ai-LsaKCvR8>KD%iGSf&xiDMGlk zPLyjFzetp0_H>abTdMTu5uJonyJ8bnIOO!wfo^*zHs&YQ)P?tMbH#(*2-3kS&;IW_ zi`<-@_5&;i=p2-%?^8MA8^Rx_w5~CQm#D29>}}-?eOUWKHGWhxu3cMo_}+6Uwt1oQSnGl3NjaVX_LJ`Zuk9LLSpQ zDjd16z;ZWG%^v0G1j%*zbfcbx1R@!G^ixuCLeOv8Yev86eTsv(Gc4Gmoc-vj*q|+P z)!`1FJtcCLv$|$@N|>9{9tChvcIFB}qS+iOTvUZRYc?L`{7jVK@t>nZb|)&1hYH9U zW=#OmGz}7)*dx^Y<|H;<@1<;5P5L92UHXruaP}p98A`obF2!bVMNVV%V+5+~Cu%S> zd$&6>?J686H=0VYXUqsG1aiu+F0XXhB|^27V^s)*d0m$~9wa~!5eW2{Hup2q-If?# z^|`ixmgZHbaoiX0H54TUi9dk?j?4-YKOkaKLwGtE zHmG#aM{XkgnZnv*;pSfIf-4`=J}jwsUMJ!kf7fJmxAkJK!`g8&gGs-eYNp|06=Kb0 z2f1H+oA$tCWk+BcyxDg12cDwwpX(%(H9Y`DL)WcsT=sQzyPKTILQw@}cRTo6f+u`Ux_ z9VPbXX}VriHumuCw?ZOc4Cmg>VBwCYS>Y7Q1Pl0=l#1}{RS<-ZWH+T~vKK*cM=5Xo zely5f1o8DsthQj64i-4k)T6pxR8Z8sIbe1lmqaHV1E-vcUoT!fyD4b<1}=%EnoTLK zw{$Rgg7Ew}#QMEM2u4&nCcoZu@vNrT+bFmsR(Ljm`&%klZUXH#dl&V9na0QEydjXaYK z@HIR+ia?NVhU$*fzkDE(zsu2~MulCdEG!xCLXshPn|#Q4KRL%3+pQ_CKcr4OmWymH zs2+QDXCA!i+#%Y4T^Pl`*UDBjyMrVxDLpsqiQ~X2Jaw{*`y$`7=#>3(BxK?Y^%iNm zXTgu7{#S^lRX(=Rh$Hf6meY53a%qiJ!kvUulY$D&7NhEN>WNw+!;cnm?p46VI!V3x zm)0Ez367O7xYjxyLoG)!L!tOV{@xFv>DIMt@tD)Jnz_&mt&-3O0Q0qcI$UY0jf>+x<@ z_XZ(73Gbskn3{!WY!-2`*0SyzD8}TZcS$e4)LE07H!w^`o3Lecg)kJl4#5ujsG8KD zD{oNVq$@7&3v6>Vl|r(Ze%|q_94i(4l)#tef#bvjWX+6-O00vT)L4;w4TM5#CupOca{5 zsQ_a!u{8+ztI#!|?8?9y%C@J3myw9w{}{ zfx~Yxs?_Ab77VUx{|w2c6@9~8zri$Jpc(HwT*?8Su($U`a-NxkH@!aK38L;XdpXK%k31pq(}VG3n`Oc9Va#Qnp_jU zBHh?`W6`aeXDxk!H&<%U;pUTz>EX_giXTm9cpON`eXRa!D7AQCP(uEFv8$^`f%f22 z@mNnN$yr*e=tuK@k%12>We?g2su8uEi(&d}F2>R0XS%w>!s}q?J3NyMcbi#-OE31M zZ|Vu##23dpM(Ac3)wJN;z#JE@sCsG4ggLI<3-Kt36${VJyCSKLDh60Ob5yLQLQ*TnNJW`Z~R;BiGqBmj7dL%k~4^4LT z^=#^q3Q(3$Ygj3qcwY?OqX`n`YtkdB^~yD=(uS(=h4=E*J^f>QJi8KRS8FV0{gmk> zxxo5t%WIT+&n{tw`U_(6+(FCsN9f4STC&@ui%Jq z-iwWBE@M2A@k;vigIqN{NsHL6Pf46`D&NTxm$sz$`01er34PxN1@b;?u%V{A9ep_{ zAO@Nk^&iPpAp1GEvJ@C3rA#`W51yk7>@vAoe*Ka#0hWJ+LzR5r#S)?^pLakOq~^Ya zoD?9Dd|JvweaB`j=QFDjVEiy>r%lZO_^Drr~Mocp;jmRujOVZ zp7t{>m1~q>@-F)Ze9Jm)#(c3fao0Dk+95i`e*U0zd{@sK_&OpXV#8K!P?0kHq#(hk>H4y;JUu%ZGLwAk)zWA;vQXhpLzdwF`sru;#1`D z!w6iZ?x-h;!QDZ-HL;JM7OSzH8R!rgX127k;rk|%J$%!TEn}BY4az$c-Bqqxx)&)* zGVVQ_T^@o?ys$Vj&iB#Y>3x&Eg=d@>!L8%QU4}~dtiJee8JX<{6dxn*wIUkar#F4uze~7J zXSwuK6zH55*c!=;GL-9A!JH0s!kAR6w{!+aFbv#+{y5^zw2~hte;#%b zxm52>!|#chDaV|qf!&*G`v7xtsx>BUXw^GVz3wSCm(&7W}c6^`+7pPD)fq3ekrG=Iqi$_DX z)=UV?`v&=Oo+#BwX{CWv&e;YkU!vac7P2{#>VA-kP*=*N^Bh5t91!53b4lXL$Wol; z4~G$DhK%<={?2xPlRi$aJf0c0lN=p7R(h{HTP^J-o;6~rW{@#gt%a0m*Yl@w-)W7v z1N+@^z>~L=FYw;eWPoY{_sl3K!QvA;vjoUAp+MAP|G=pl6Y1q5C{cC*qFMZ&s>Mh- zw)X8nYuk_2YiGB0;eb``B*Ds&4zc{R%=OMk0zkyUN7FA}dA_WX=an)l`q@vO=9*N8 zav$Q#fyIVSzgqgeuWz0OC=g{p-@;;3<$6_J?=s%ecv4v|izuwZ$Jc8V+|KZcpUROc z%5O**LYg7;w`0{z0{X0;*r3*8dF5r!%ns3h5>l3EeWNe5@F-&%)9TgT$S< zwC8#l>S#DV(M8q+_X18^wa}FJu5v#jpwC}u4`yvpn%$zJ7pxy-$V&|f``}7hbWulF zDd=D^bWFFPt)wpCO(B*2D3?7@suWe-iG^9*C4++pQowvE7?$~r)$#UP4z;@QcbLk- z90M0VWye+xH19F$bMwqhyi@ELIf}`gqK}Es0{tf1BlO~FY@3wP_)$U(D~M?-T#RxE zyk^$FIdKX$AtPvd_Cx#yr?CQb2JREQqHG`%;a4?}Xs+VT%o7U)_ikw`KyxErC+;*e z$!hnFTK0vMTO{$|B*bB+2yn0yx@vOswAiFdTaMk|W$tGEnbrBNpkd2A>J^aeOd3Q| zwVmXKc&457HB6felkQ`96M5wpX9>}yW|}8K2}cUi90I;o-^PmAN+iZ*1AUsqkRFL#CvE=Jl#B^IJ@N#(<(r1dvaf0EC5N34f^W40l9uJ%l@3{rYu3?Q3)t z<}46U<^SzRNaCE*XKu3AJ@8!ia>MlO}m>XU_ zt{aJbozy8j$F=6ekhvpEg$yh+>O^JKh(?Wnz{5EP_R1$&KnIT!bSe}x5ZU07^mYwB zOWTZQMRULRm^(HYS4?p-dK1+?ZHT<>rGpecg=hHjq7wPtG|3c!(U69CfqDMecD(>- zG%Se1EZ>`6gqD0K;e2G6BS7P(09Jh8B7@R?(pVtD*Renyav0d%dqU6KR7H}#G#srNl|7Oypb4#rchJfsHA9_uSYEj9|Hy)+cnAjSj3 zXM*i$4=aXK^s0|9Or6Y2dLM_OOJuz*}hh7*P zvwef!H&sH}wCK+Et-)OJW5Epg<%ZA_%Heogh*q$mQRg^rUc**^CF|NDSzXCR?{bst zP0eJjY=)LyaP-A1pC7WC#jLS=!54F&9ed ze>vq!7Oi}-!#;hfoEkUl-8C4_9r+`#w>BBL7Y@@$QMV~6pS-?GS;pUC?BSb|DtnJ| zyKmoQ%M(d!f}uiK=b!6LblW5bXw(jySKN;bc1BX@k$bbgiI$8b@l&ol?iFhB)^%`F`t!17G#OB$!Z8IY2}p3=kHugbw7c z%%V^PY#*jTYD>aD)8Vg@p$r^Qp>c3AecN$G9)%304g*!#u|XibzcmAaumPlpc!<90@u2h!h2nx7G%`pw%&n2{Vd=sl#dSAQhrN=UA5)DNo2Nc9tbpch<=4K zNsjX0!}|9g{Z`kyN)htUJ{Bqhfj%}|r9Aj_E#)|Kdjud{`R`#OxS?LB#MU^BkY1`N(W zFjINgV}46$UHz8mI%`qcVqZewph6$tbhNFYe`w}v3l z>)wAgwJ~?Lvea?`RJE+HC0tb``~%6^x;hBg>Jwfa)vE%3e}K8${|5L+?(Zt_s$AY5 zVE)d(0saxsy9&H2KKBP$xchH_f28QH0Z;_j;(5s>Ze=ME<{+~d9OB7s%{-3+=h>r1VKk~D56?!$V+aG8e!Efk4vbKW#xEPYn#v|GJF4+WepA_p#rB5Y`VYR{uj>H1FHZ4 diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index 55b7242c5..702bae743 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -59,6 +59,7 @@ extern "C" extern uint8_t g_io_soft_pwm[16]; extern uint8_t g_soft_pwm_res; #define io_set_soft_pwm(pin, value) ({ g_io_soft_pwm[pin - PWM_PINS_OFFSET] = (0xFF & value); }) +#define io_get_soft_pwm(pin) g_io_soft_pwm[pin - PWM_PINS_OFFSET] void io_soft_pwm_update(void); #endif diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index fb337e761..b0eab5b8d 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -3936,8 +3936,8 @@ extern "C" #define io25_get_pwm mcu_get_pwm(PWM0) #elif ASSERT_PIN_EXTENDED(PWM0) #define io25_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io25_set_pwm(value) io_set_soft_pwm(PWM0 - PWM_PINS_OFFSET, value) -#define io25_get_pwm mcu_get_pwm(PWM0) +#define io25_set_pwm(value) io_set_soft_pwm(PWM0, value) +#define io25_get_pwm io_get_soft_pwm(PWM0) #else #define io25_config_pwm(freq) #define io25_set_pwm(value) @@ -3949,8 +3949,8 @@ extern "C" #define io26_get_pwm mcu_get_pwm(PWM1) #elif ASSERT_PIN_EXTENDED(PWM1) #define io26_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io26_set_pwm(value) io_set_soft_pwm(PWM1 - PWM_PINS_OFFSET, value) -#define io26_get_pwm mcu_get_pwm(PWM1) +#define io26_set_pwm(value) io_set_soft_pwm(PWM1, value) +#define io26_get_pwm io_get_soft_pwm(PWM1) #else #define io26_config_pwm(freq) #define io26_set_pwm(value) @@ -3962,8 +3962,8 @@ extern "C" #define io27_get_pwm mcu_get_pwm(PWM2) #elif ASSERT_PIN_EXTENDED(PWM2) #define io27_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io27_set_pwm(value) io_set_soft_pwm(PWM2 - PWM_PINS_OFFSET, value) -#define io27_get_pwm mcu_get_pwm(PWM2) +#define io27_set_pwm(value) io_set_soft_pwm(PWM2, value) +#define io27_get_pwm io_get_soft_pwm(PWM2) #else #define io27_config_pwm(freq) #define io27_set_pwm(value) @@ -3975,8 +3975,8 @@ extern "C" #define io28_get_pwm mcu_get_pwm(PWM3) #elif ASSERT_PIN_EXTENDED(PWM3) #define io28_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io28_set_pwm(value) io_set_soft_pwm(PWM3 - PWM_PINS_OFFSET, value) -#define io28_get_pwm mcu_get_pwm(PWM3) +#define io28_set_pwm(value) io_set_soft_pwm(PWM3, value) +#define io28_get_pwm io_get_soft_pwm(PWM3) #else #define io28_config_pwm(freq) #define io28_set_pwm(value) @@ -3988,8 +3988,8 @@ extern "C" #define io29_get_pwm mcu_get_pwm(PWM4) #elif ASSERT_PIN_EXTENDED(PWM4) #define io29_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io29_set_pwm(value) io_set_soft_pwm(PWM4 - PWM_PINS_OFFSET, value) -#define io29_get_pwm mcu_get_pwm(PWM4) +#define io29_set_pwm(value) io_set_soft_pwm(PWM4, value) +#define io29_get_pwm io_get_soft_pwm(PWM4) #else #define io29_config_pwm(freq) #define io29_set_pwm(value) @@ -4001,8 +4001,8 @@ extern "C" #define io30_get_pwm mcu_get_pwm(PWM5) #elif ASSERT_PIN_EXTENDED(PWM5) #define io30_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io30_set_pwm(value) io_set_soft_pwm(PWM5 - PWM_PINS_OFFSET, value) -#define io30_get_pwm mcu_get_pwm(PWM5) +#define io30_set_pwm(value) io_set_soft_pwm(PWM5, value) +#define io30_get_pwm io_get_soft_pwm(PWM5) #else #define io30_config_pwm(freq) #define io30_set_pwm(value) @@ -4014,8 +4014,8 @@ extern "C" #define io31_get_pwm mcu_get_pwm(PWM6) #elif ASSERT_PIN_EXTENDED(PWM6) #define io31_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io31_set_pwm(value) io_set_soft_pwm(PWM6 - PWM_PINS_OFFSET, value) -#define io31_get_pwm mcu_get_pwm(PWM6) +#define io31_set_pwm(value) io_set_soft_pwm(PWM6, value) +#define io31_get_pwm io_get_soft_pwm(PWM6) #else #define io31_config_pwm(freq) #define io31_set_pwm(value) @@ -4027,8 +4027,8 @@ extern "C" #define io32_get_pwm mcu_get_pwm(PWM7) #elif ASSERT_PIN_EXTENDED(PWM7) #define io32_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io32_set_pwm(value) io_set_soft_pwm(PWM7 - PWM_PINS_OFFSET, value) -#define io32_get_pwm mcu_get_pwm(PWM7) +#define io32_set_pwm(value) io_set_soft_pwm(PWM7, value) +#define io32_get_pwm io_get_soft_pwm(PWM7) #else #define io32_config_pwm(freq) #define io32_set_pwm(value) @@ -4040,8 +4040,8 @@ extern "C" #define io33_get_pwm mcu_get_pwm(PWM8) #elif ASSERT_PIN_EXTENDED(PWM8) #define io33_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io33_set_pwm(value) io_set_soft_pwm(PWM8 - PWM_PINS_OFFSET, value) -#define io33_get_pwm mcu_get_pwm(PWM8) +#define io33_set_pwm(value) io_set_soft_pwm(PWM8, value) +#define io33_get_pwm io_get_soft_pwm(PWM8) #else #define io33_config_pwm(freq) #define io33_set_pwm(value) @@ -4053,8 +4053,8 @@ extern "C" #define io34_get_pwm mcu_get_pwm(PWM9) #elif ASSERT_PIN_EXTENDED(PWM9) #define io34_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io34_set_pwm(value) io_set_soft_pwm(PWM9 - PWM_PINS_OFFSET, value) -#define io34_get_pwm mcu_get_pwm(PWM9) +#define io34_set_pwm(value) io_set_soft_pwm(PWM9, value) +#define io34_get_pwm io_get_soft_pwm(PWM9) #else #define io34_config_pwm(freq) #define io34_set_pwm(value) @@ -4066,8 +4066,8 @@ extern "C" #define io35_get_pwm mcu_get_pwm(PWM10) #elif ASSERT_PIN_EXTENDED(PWM10) #define io35_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io35_set_pwm(value) io_set_soft_pwm(PWM10 - PWM_PINS_OFFSET, value) -#define io35_get_pwm mcu_get_pwm(PWM10) +#define io35_set_pwm(value) io_set_soft_pwm(PWM10, value) +#define io35_get_pwm io_get_soft_pwm(PWM10) #else #define io35_config_pwm(freq) #define io35_set_pwm(value) @@ -4079,8 +4079,8 @@ extern "C" #define io36_get_pwm mcu_get_pwm(PWM11) #elif ASSERT_PIN_EXTENDED(PWM11) #define io36_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io36_set_pwm(value) io_set_soft_pwm(PWM11 - PWM_PINS_OFFSET, value) -#define io36_get_pwm mcu_get_pwm(PWM11) +#define io36_set_pwm(value) io_set_soft_pwm(PWM11, value) +#define io36_get_pwm io_get_soft_pwm(PWM11) #else #define io36_config_pwm(freq) #define io36_set_pwm(value) @@ -4092,8 +4092,8 @@ extern "C" #define io37_get_pwm mcu_get_pwm(PWM12) #elif ASSERT_PIN_EXTENDED(PWM12) #define io37_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io37_set_pwm(value) io_set_soft_pwm(PWM12 - PWM_PINS_OFFSET, value) -#define io37_get_pwm mcu_get_pwm(PWM12) +#define io37_set_pwm(value) io_set_soft_pwm(PWM12, value) +#define io37_get_pwm io_get_soft_pwm(PWM12) #else #define io37_config_pwm(freq) #define io37_set_pwm(value) @@ -4105,8 +4105,8 @@ extern "C" #define io38_get_pwm mcu_get_pwm(PWM13) #elif ASSERT_PIN_EXTENDED(PWM13) #define io38_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io38_set_pwm(value) io_set_soft_pwm(PWM13 - PWM_PINS_OFFSET, value) -#define io38_get_pwm mcu_get_pwm(PWM13) +#define io38_set_pwm(value) io_set_soft_pwm(PWM13, value) +#define io38_get_pwm io_get_soft_pwm(PWM13) #else #define io38_config_pwm(freq) #define io38_set_pwm(value) @@ -4118,8 +4118,8 @@ extern "C" #define io39_get_pwm mcu_get_pwm(PWM14) #elif ASSERT_PIN_EXTENDED(PWM14) #define io39_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io39_set_pwm(value) io_set_soft_pwm(PWM14 - PWM_PINS_OFFSET, value) -#define io39_get_pwm mcu_get_pwm(PWM14) +#define io39_set_pwm(value) io_set_soft_pwm(PWM14, value) +#define io39_get_pwm io_get_soft_pwm(PWM14) #else #define io39_config_pwm(freq) #define io39_set_pwm(value) @@ -4131,8 +4131,8 @@ extern "C" #define io40_get_pwm mcu_get_pwm(PWM15) #elif ASSERT_PIN_EXTENDED(PWM15) #define io40_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io40_set_pwm(value) io_set_soft_pwm(PWM15 - PWM_PINS_OFFSET, value) -#define io40_get_pwm mcu_get_pwm(PWM15) +#define io40_set_pwm(value) io_set_soft_pwm(PWM15, value) +#define io40_get_pwm io_get_soft_pwm(PWM15) #else #define io40_config_pwm(freq) #define io40_set_pwm(value) diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index d8abf2c58..900765c00 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -73,210 +73,9 @@ static IRAM_ATTR void mcu_gen_oneshot(void) } #endif -uint8_t esp8266_pwm[16]; static IRAM_ATTR void mcu_gen_pwm(void) { - static uint8_t pwm_counter = 0; - // software PWM - if (++pwm_counter < 127) - { -#if ASSERT_PIN(PWM0) - if (pwm_counter > esp8266_pwm[0]) - { - io_clear_output(PWM0); - } -#endif -#if ASSERT_PIN(PWM1) - if (pwm_counter > esp8266_pwm[1]) - { - io_clear_output(PWM1); - } -#endif -#if ASSERT_PIN(PWM2) - if (pwm_counter > esp8266_pwm[2]) - { - io_clear_output(PWM2); - } -#endif -#if ASSERT_PIN(PWM3) - if (pwm_counter > esp8266_pwm[3]) - { - io_clear_output(PWM3); - } -#endif -#if ASSERT_PIN(PWM4) - if (pwm_counter > esp8266_pwm[4]) - { - io_clear_output(PWM4); - } -#endif -#if ASSERT_PIN(PWM5) - if (pwm_counter > esp8266_pwm[5]) - { - io_clear_output(PWM5); - } -#endif -#if ASSERT_PIN(PWM6) - if (pwm_counter > esp8266_pwm[6]) - { - io_clear_output(PWM6); - } -#endif -#if ASSERT_PIN(PWM7) - if (pwm_counter > esp8266_pwm[7]) - { - io_clear_output(PWM7); - } -#endif -#if ASSERT_PIN(PWM8) - if (pwm_counter > esp8266_pwm[8]) - { - io_clear_output(PWM8); - } -#endif -#if ASSERT_PIN(PWM9) - if (pwm_counter > esp8266_pwm[9]) - { - io_clear_output(PWM9); - } -#endif -#if ASSERT_PIN(PWM10) - if (pwm_counter > esp8266_pwm[10]) - { - io_clear_output(PWM10); - } -#endif -#if ASSERT_PIN(PWM11) - if (pwm_counter > esp8266_pwm[11]) - { - io_clear_output(PWM11); - } -#endif -#if ASSERT_PIN(PWM12) - if (pwm_counter > esp8266_pwm[12]) - { - io_clear_output(PWM12); - } -#endif -#if ASSERT_PIN(PWM13) - if (pwm_counter > esp8266_pwm[13]) - { - io_clear_output(PWM13); - } -#endif -#if ASSERT_PIN(PWM14) - if (pwm_counter > esp8266_pwm[14]) - { - io_clear_output(PWM14); - } -#endif -#if ASSERT_PIN(PWM15) - if (pwm_counter > esp8266_pwm[15]) - { - io_clear_output(PWM15); - } -#endif - } - else - { - pwm_counter = 0; -#if ASSERT_PIN(PWM0) - if (esp8266_pwm[0]) - { - io_set_output(PWM0); - } -#endif -#if ASSERT_PIN(PWM1) - if (esp8266_pwm[1]) - { - io_set_output(PWM1); - } -#endif -#if ASSERT_PIN(PWM2) - if (esp8266_pwm[2]) - { - io_set_output(PWM2); - } -#endif -#if ASSERT_PIN(PWM3) - if (esp8266_pwm[3]) - { - io_set_output(PWM3); - } -#endif -#if ASSERT_PIN(PWM4) - if (esp8266_pwm[4]) - { - io_set_output(PWM4); - } -#endif -#if ASSERT_PIN(PWM5) - if (esp8266_pwm[5]) - { - io_set_output(PWM5); - } -#endif -#if ASSERT_PIN(PWM6) - if (esp8266_pwm[6]) - { - io_set_output(PWM6); - } -#endif -#if ASSERT_PIN(PWM7) - if (esp8266_pwm[7]) - { - io_set_output(PWM7); - } -#endif -#if ASSERT_PIN(PWM8) - if (esp8266_pwm[8]) - { - io_set_output(PWM8); - } -#endif -#if ASSERT_PIN(PWM9) - if (esp8266_pwm[9]) - { - io_set_output(PWM9); - } -#endif -#if ASSERT_PIN(PWM10) - if (esp8266_pwm[10]) - { - io_set_output(PWM10); - } -#endif -#if ASSERT_PIN(PWM11) - if (esp8266_pwm[11]) - { - io_set_output(PWM11); - } -#endif -#if ASSERT_PIN(PWM12) - if (esp8266_pwm[12]) - { - io_set_output(PWM12); - } -#endif -#if ASSERT_PIN(PWM13) - if (esp8266_pwm[13]) - { - io_set_output(PWM13); - } -#endif -#if ASSERT_PIN(PWM14) - if (esp8266_pwm[14]) - { - io_set_output(PWM14); - } -#endif -#if ASSERT_PIN(PWM15) - if (esp8266_pwm[15]) - { - io_set_output(PWM15); - } -#endif - } + io_soft_pwm_update(); } static uint32_t mcu_step_counter; diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 7b1db6178..b4d21fc55 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1037,9 +1037,10 @@ extern "C" #define mcu_clear_output(X) digitalWrite(__indirect__(X, BIT), 0) #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) - extern uint8_t esp8266_pwm[16]; -#define mcu_set_pwm(X, Y) (esp8266_pwm[X - PWM_PINS_OFFSET] = (0x7F & (Y >> 1))) -#define mcu_get_pwm(X) (esp8266_pwm[X - PWM_PINS_OFFSET] << 1) +#define MCU_HAS_SOFT_PWM_TIMER +#define mcu_softpwm_freq_config(freq) 1 +#define mcu_set_pwm(X, Y) io_set_soft_pwm(X,Y) +#define mcu_get_pwm(X) io_get_soft_pwm(X) #define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) #define mcu_spi_xmit(X) \ From 003170ebdccc9bb823d8b1f7bff507218bbef008 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 8 Jul 2023 19:04:59 +0100 Subject: [PATCH 012/168] new IO HAL --- docs/mcumap_gen.xlsx | Bin 463701 -> 465402 bytes uCNC/src/core/io_control.c | 200 +- .../src/hal/boards/esp32/boardmap_mks_dlc32.h | 8 +- .../hal/boards/esp32/boardmap_mks_tinybee.h | 6 +- uCNC/src/hal/io_hal.h | 3921 +++++++++-------- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 325 +- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 29 +- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 4 +- uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h | 4 +- uCNC/src/hal/mcus/mcu.c | 304 +- uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h | 4 +- uCNC/src/hal/mcus/samd21/mcumap_samd21.h | 4 +- uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h | 4 +- uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h | 4 +- uCNC/src/modules/ic74hc595.h | 171 +- 15 files changed, 2315 insertions(+), 2673 deletions(-) diff --git a/docs/mcumap_gen.xlsx b/docs/mcumap_gen.xlsx index 10826b0859a6ddecdfab34c30f667cd11ab8baf4..ef31de9d3afb1d231d0b939c65ef6e0ee1210408 100644 GIT binary patch delta 63028 zcmb5VcQ~A1xc-}jL=Z%e7STd<5;a1!=z=g9Wz>+-Yod_qon*fA=~6L|j*7?seav^*qmd*9((NdtOFcLWhHEU$9TVigoK2H1;VD z2W;(|g7awp=1&#nr{wTs0yW4prr6%UCm+K?^J63IMlCb9e;ppqI&qvpLYYCc_xstD zUb0s|*9^#J2(zr-$)9_Vh0I}3YWU!98XpsRuF8L;bkZ-e^D(@ho61AW=Si>V#+zVd z;im2n2Hd`#@%U`sG83`JJJp^@3q4i)uQssz#0rRSfxp&pa|^01?9aGptsR!+%sMI9;$P%0)G}+uF+0>~g0$L}h^gU4!tQmR_pSd89==8KRxNBGWRyaB-REwo8X-!TuD*wA+X1D8- zwa@C5p{i-30NvDU_$+cuY-Ql{vmSgY?TC%F;Y?{E&S)wyl=C{ZUV3g*;>J3^>) zzXFSk(BNlJn~wF@ly*AIN6I<=@m~wD^oIy`%Ve%Q6-uV}T*^iYTzxNIvsgC9*B$$!8e1U|fY=Iy8ax=s?LoB!n@bmWtQ z^iEa+ecc!9_T%W4Pqm-lpLszx(cs*bsrOh(@#~f6z3C-XJ3knjtHx<#I166FVRxx& zlc|3#2>U${${SQ@BU;=WTsq1U>AU<&6W>0O5@X<6>bJ$-`do#nVl$tbe_q&AVt1#j z(}FsL;IzPaQcdszg(EdaqZY1QgX?#Phjl;W&Rg(nKWWLijt4v}uWdWOR=?axnl&o^ zc#B>|(8B#Fd46B#?yqGng>H@e9eA)+l+SY%Emv#?`*d94UVHwb7v0sVmfK#Si}Uw; zLgv96dm_t>?P|8HuA0q4+`nf%HJY2^Iao$noHruwkan=YuL-Ou9w<|9rXBg^GSk;? zU)V-?5*NS1@>7DYQW0R%+#~nin zyJWTuRNCo(3N6={hq1$G`*hrXYQ%eKSNJts3jCNPqTN{8%64Y`+|%@H9dbKwua7L2 zrqS;#;`P;s7c?`$bjKDv{eF6lv-y;tDi>=zTQ0;mue|i7u6Q#bM5vP(it2ywi+Ca96IL8oBQ&Zc*H!3mCw6}^`SURlXMZ6KD;jf*B z@oJHK#p#=tfzb!bmCDovt!V=BhMp^cg*@q!{x;AuZTMYB5Z0QtrX9i?6ilsp02i$`)TU@ugjNz8{6Tr%Wj( zu9ftRwj&RNBchtpS;?4MyT_1%@iu1p7cx$5gPnmK1WYx7NojMk8oqjq%Bzb{VwL(% zmis$Xc)eqHHetb;A}ITZi?{34*V{F+T6-1eU?p3A}Y4_5^tNEc*I-}><%i%Qt# z%D42Z&6S<*Z#6{q64NP{2et=mH9}s4?Oqc>-)3wNGW1V1#Qz=)PJD!1ovqar&y6s? zg+^blY@T$V2sKT}sVF|0Q z$CS|Ew=+`km;KXHaJfp`%$&C-6pCa4erzt}>835%urj!^au(JLfm|K0PqpWKw7YQONzYF%Zcnb%F6^vP zJ9tU4zCjX>l$iXpJTry!1ybjE4qJR%?EUHQW#KAM9W_nOEP;*f-{ZNfDTsHS$Hh+b zjNeE4Jn!%X!`idcU)wbhL$5!JCvRbY{?1nl!8+bjL(d&gE~=B4>$z&(U?=BgYdsr& zf$rW{r`?iE1J?{t{k^UkQ23=Q`U>ixO zIdOD)bvc%v<_$YITp8zjQ?UTWs`YR}T^;rQ+Sr3%?G4uuRae<*vv_-*R2*KJLbkfK zor{Y0_8DRdWJ3Z~M{nH8$%Ax79#%Wi* z4F6+JMhXwX#A>qD~F=R)brYrgsS^WA1M}(XAmN2yzBEq9_&5#Kq;@^{Sr4l4k zN)csQu#CXGZexUdv=(Hm5`ghB)D0>pcqH$)f^g!hZ~~bQ;#x{z?%)pl-|LUKcPb7N zLM&Edr;b<|jb??gd%Px|8G$6vW7nzgC$>MV@~osXF}X}NeL=zZJ0~=xoss{kAn{r6 z-*4XzsG~lzJPBercpTJoq#d6h@H5;W! ziqf6hi=qlo_U~!%4eT*YSL+b_n#1tipx~%(wvEB*q>}b;mp81#zvpZthQX<>iP!AC z5|;%5Bb3I!XJaG-t%kfkZSBw@cHHdOHI3CAeHJPkL={iU|7CDV)J!max=4bU;UJU2 zY^Ph5p{zRMuUU0GUQ*oeBTG)H6%KO#FS7O>)9p(JS2@4><^FmFA$``k@2cB0GeE)j z8Q@&}4>5wYSw^rC?5qY~sgX@m-!-*(sjo#N=RP|o!M3pvxh@#620dLAf>$^mFm%O( z`>6fbxP9_P1uVHVt!`z#d@zWje=M{5_)&15Hm6K)32ktsr>^vfr(?}unb(IuZ)bT; z;AVLo`K>r}-BmaDd_|2P?7H!>=NqaAmuv<%bmtuzMldA{mKzY2HOVLq2z!S2MuiQJ zlTEf(oFSCZ{F&^!BJ%B;cSt~c+V#{85q)xPJoR^Zy5`|_Bqse4%OnL@S zbN@jF>rQz+SevoNAbYI#CV$56A<_%&%k9IDDw4nMz$w0T*~Zh?ToGPV^xyo*-A3Vj?VqrM8D>c<#3?IGglor-Q_jPw}KwX9$;9WB^UE%v*|%atfI13 zZ_8o|B&{;RSY)sM%^euFY&R+LL+G(NYbZPqlCC_aL8jF<_8pa-@9pWv>2yc7|E?^L z#*HKYTU4^jg9psA-QFE)FCYdnS!a0Cp`|(TW%r)B6aSYr_{!JZ$O7Di0^G>L0B}M9 zaNhj`j#~LktA;hTPYe0(CL5iee0Md>y$p~n3Yg2`Z{RiTuZH)(8s@6OZG;t7@EH`* zviEW(1HY4nCufl9sC{+!l47Il()c#x8;h_ZeRRu4yq!73V_w({ZAVc5RDYQ3tqdDdp?vp3 zYjg|)9@3nVt1SqK%wF$3pwCgAXZJ5K_0`?Lyj9&*kVRw_}=IFFHnE#Lc@DrlDblbZB*ElXf6j%`mQitl*C{d`9y(f3Z>0?tH^ zn-^Ds9p8Tzx|~N9-`>y8VfX=y-5exeOHQxgU6KE#Mm=BeF8a;Bn1RY|&8r761C9i2 ztrImnXyzg=dpdlxkN>`a;MdHGfcsf(jFRf6(tM$BB1A$tAIZ;%-;UXDe}hkPDuw(4 z)s=yr|M{b)tMNhWSo%)xM4p&ZzvBy=eBP#K22cST9V-`#5adYX=gmw#Y&FdDoF0%L z1%Kc2AL=6R1Wui9bX}W+6(OGX7lZ&uV=`jp`xIU_aYYP*D+y0D8vc5fJ+XMD15Qe! z>7)Qkjme-8O+)Of*Kkvy;+;NNv+3I46YIhvWPK5BfidI})Uo8cyrtD%cg&XiW87o8 z9p!>!DT8%_x?;>!f_0|g-O&OUoF68NiFMaC3O_WP5tt*C+p7(UW*8YcVoOQ5IEc&m z1q!LsVc^w5ky5Cxl|X_SrfC$s_Nlb1eYaX?QxirQ zgUU2RbIF(qP~etQ(LEw#L%_%*-p?1qHFw#3nKY-vjw<~^YTZ^wgL#XA>BneorUSWkveS2Nn%veDkq6wsR6LBv=rDIc0hb2z z`E;Z2G8Im-z6Sm6DG*vuM0~yl&F54Y^}hv2R@3U1^{2#NQb)&eqvvU(@i4CUbwlpK zA7PbtO=zVOKhG&@thudoA5Ci$grIt+DI4*mkX$-M0|?16-xe7J+bDkmtxIMqjF-`J zk{m^j%3!40W3|L{$6B-U9izetSPE?z7z1CBnFy%_srtT3Pt@oL(%HpXXq2% zZ-J{b1SRMBiu4XJp~3(B*rEYlJo#u6Z=oSG&SASN6jW&j{2 zBTfQA&HYsv_1P0hC}h;%^Ex4L8BrmSP$rO2vS9eA{OcSdLVbW+DGp+FSf`{?xd|0! zNE!!8#h`UJ=5=A5Mu-LplFI~ci_G09PXW@AE~L=ZatZ+9xUVg=~TVS=ug>rSYhzfSeh!2fo5SjwxPSuhAR22>ICY zU>hSe?%#PO>J;p>!Py^4I$`sSxzr+#q12*1MESk%!z3Mb#_xY&ZYX=AkOHx{rPN%x z!nL?}#|EG=&I;t(dT|Pjm0Hv!B9nMfYQAVD6>T{ggJtR`r70gURLW+YTi|Nr5an!x zR?er6%j2SND(GiIzbu6fg3Ar2&=rNl3q@zp$PVy~Rxe9*uhMYamh8SY*FUvbID+31Y5NF)x+q#eKAw3^2CM1d+sG}aj`P0!A+Be$|P=y zsm>D8jBGxg?FG#WQA|?8~G*vRy^H}5CgCA`SUf3Mz19edS=J%@QWDV zvmP2oo>%23(c60|dGzdAGU3)*@3X!#JBD>x*MMM2Hof2c{InO~LY^PubdlErU*8Cv zrCpfbBzg5x)vPinsv}J+up^C*l|Knr%FIMIB>X%mSS)Te$?SV88P3b!imjO#X7Si! zE$hN-Rf_**l8g@ShMO!pJKSgnhHc}F@j#3`+Zsl}fny8~jl&Vb2 z2lC)dRdoCcY&x*&MAO;=wV*V+w0l`%2%_J{3|{WlU&*cv&9w20_TP&gxB09w zUKV_RYr^O}MjdOP1Yh1@g!Rjhce?UZ_Lcc^B7mQjjJWuWH*!)>b2l3%Ch0!pLu zsQjC}e@bID@Q}kfhwGEvqwcl%$D;Lv=4Q@ua{Q+r<*4G3**`}|cIkDsvxX0@Z2hN= ze;$9T7FslVEmykh%X{$N>JYfR$RBSj>u`q+3`e(_HK*zVO2n$2(G z{BaTHIyRRw39!jPTTH!6`uXohKaU~(Kk2{`|LoLtt)a00Bjm9dZS^2bv-%L89wMr> zIPG--qgh#=X>Xi)do&f&*RN6lPp8(z2unbAbXGwevp*V=TED>-$30Ju^sWTz#Y?*ky(wKB^kC(C3agcicj$~jWsSVpCR9u~Kys_L zlmCGqA^4U3efL~KrYL51)jkp4Mels9OU4JjR3>+;saa^|2SomHG^CJOQJ!rph4cpo z`c?$6k-eY@Q5zT^PBB~s?e1s%ImpfB!(ot{gT8t*r< zpIc*WFtThVWG+FFZ}gTnJ?)Rj)v{!GBooE7<(|T~y1f$~i)I?VIi|^4IhdIW`j$7< zZI`xl(f(uh)wHz`r{+)QOq1GpLUJoN5_VOAr&6s|{IrBBXq1|RKpn597?gX5MHBnL zSE`k1KwVi&2_ z@2}du0z%)5spdb5=)@)8{Gplu<0tkg0l5o=%(hu=aD^{_+-cTvK<@o|LK9)Ys+#&L zA24i6$)>hv00yaB1Oo#)5xF_ZsZC0A#+JFMw6yG$6d5~pm`uK9?8e%FEOD2!+<^4M@1#?>HJdcmGZl>8~!RN9M+THqMn z;d=(IeA_U#e`5G4Hqy%`%FQI7bKQzmmvs`}eKxt}!PDg(;mKtHl_ZIQg=SVrdvbNY zP!De`BN85#K{fV^&nuGxb6UUn3xa<2!5p<_PcAX3C6DdC1N5S&2}CcP7V@$$dC}^N zxckYnRqrQS2u(!iZ?ubk*BJLy!x6fgXTx8nuEI9v=XFJxc8Ha;C}*J?S8vBF_C+7|@qN7^v#quUsNSw#>Wp)E(o#~ATftbj8M zq@-Mn=N8eNAZ|p!RjQfm~NHyV$x*k6gKHFN(=Eg9IWAiShX#l zPFgBQ79$rm>Rc!86%}K=)LEGi(N70^Y+Tf5PbT9L{H@*!&x`7v#FL71J&}U-MJq#N z?7G`3T+Tm>!<-=#bD}^GE!h^e7PU}`K zs=dHz3BobQQWoZPmmHXPH>_;%ql4=ud=7KUmBvbxmmD?UQ2 zG#_|w->+Hp0&r^?OY^96O?i90j76(4M z!_@8rr8#|kjDo3sEYj5ZePFRr8IKekE{g9-X| zOVEvy)d^4~GL`p7DssfP+#Dk7fVCd>(%cS>d?O$;A->#v` zjgR1m;XLe%H+VWe!R1Bk7ZVL)W%>GJGy9!J$W)9mRA^;5pHRml5qMZbThhm?)tiGg zN|g)EB&99sX(&_5N!$o0{@73vF>sqEHXKXv&GhZ>nWQ-3%K2EXH378tiMws8;@)ZO zeF9ogCD9)J(t`N&m^mLB_nT$;axl+niolo~cYgwZ;k$Q|wv1iaH*eR#*ctEKAUrqX z*q3V8kmUL9+1`L%!yX$S&X#!!{JA1+$+xtEqO22w)6?glAag#?74oVrb<(h0hgFfT zeisCZIjLY3Cg%phZOs|+KB0LprOATKy{~wtdBdteNhH+CONFmA-QIPXEC8OU!f-fa z8@Dvv@@G9p9QA#Z?XJ4#%DihZNGtE@K1;X(PVo@X0 z7>9zpq?h;O#0vmf3Q!|{Z^Xa5ngZr5OF3m5&~a=RuZWrN+F z@FoR9;n*~ISm3gVk&q;&RNWJ&heQ*Z3n=-P0YB&3rLkA?h5xGMiNzY7Q%&#Den+VD z4WjL|?&IPMg99Ppa1OU^y`zHvdj`4Ps8}L8d);146Q@Kep+r(dKUTt|BjJxZsw9A_ z4PaG))YpM{Zu=zo8SM_nTTS2Ie3#9BOjnX@WR68=za5@X1YHkwXs~HMpxrB2htCVb zatX(kbhJK-0Fk)ni8=t00Ext6RY>o9V@2Mq$O;1$`c#>rVmC6oMIQFJ!{cEvV`a!QjK+MO2%-! zvdK0vlK#{fibV(G+eumtNf_F5K(q{nIFV$R!Z9qV4va}!Rspzn(_j{t_TNK=>wf)a zaipZDrZGdnlTBFoJ1|hvzc?rsE}QAWlr_K;zuf+gn{l|W#Dx6JaIA0U$xkWD%tO{q zd;L9FJoMf!C^=cu@`^pvpIdtQRKQnHePw%5?$EooUJX`%FFkkGGN-$Xbzlg6To^pp z5KOg;ExL$^csh$1<0_AI8GY*P{hUsnRSO#%y1(J3cdyZU`%OKvW-^Qx>}bC|Ci3H0 z6lcs+fKp_QRv)APhA{Q)NHmrzZ_0DKzQ;?4;*4!UT(x;w?{2i84ND|#xC*-?FGzC9 zr>&n6#|+lYgi~q3>o`vo{WM;cHuMRfHj z{Xt)j=;&O&(Pfa!H?K;`OW3giw>sW-yyG+T8l1F>I*n2!aayULy?*aw@-NI-&bUzj z@n!SRWz5*ikBL^L5qISgXiABrAc&v1nWAOG&(>; ze4g)ID{)@j(XjGSFlXeiCy}`zo6lv*l}C(WN0L$XU6p3EQ^n6Cw_Vy$XHf3a0jhR* zRVZgq|9+C#Yq8QOqTrpyY*W8sV4Y^hdLc~srm>-%;aU%MGk%wK+?m+xXxgR<=R6%o z{e>~k&*AvKFhf_HnMKRXjDn2?OFP7K438aXbq8`Nz0;O9;at%jzS&G1ZS!f^s&XJ} zd$Z5O(Oj%kZzzC)kr6-k!-noMWxZbY_c=HHw!Ph!ow7-n0H0OSl@#LLGBZJ^SCmTY z=nd8%jox||mjXP0&`?|^x`n)Q&Xpx3LVc)-e{J@?2uTDYz{c)$e3bjxdh5k7CO$^w0)XAKF zm-|BaSl@X)V3l#A7^>9b6uo5F`sfpP%5>qlQGY!N zJ0gHR){l81*6)<$FW0YOwlG(v-v-zqPN%PZ|5K4^AJuPtr5LU;CsdC{p|?~&I?Zyu z3OpoFaMHgj7wke^a0cyjT7RK|(Rbs%2xs3r6wE(l{<(qvVUthMx_em07ZW zNH|sp6=*!E zJkGZo{;4Pj5Di;T(S{oPwL92x?AF!nz51i@%8h0f;uujfwLg_%*ewu}5^v@2ML{EKuiJy|&NR3Yxno>(2&@N zOAu-+CHF#^zd3E^BzeMbS8)956&tD&?d2s>=7A%QamRxoa)9dN+IHB(X) znw`M@enZ!!Un?m^w4c4izYAud=qW8+o;^W@*FX2rIXM-0vRx+Ht16I?f`L2)#u4Gd zG{KPJt-~qIBZt08L8(6K*asF7#H*atqQ5x#GgDk@0))HMyB%2RgVH6FQ&APn7Nj3s zsW+7z1!0%gS@OcB^`s?LWltF0ERWTbQvo}l`fdsLsumDAQRGeNRy!>0(e{D%5E>4j_wn1uHRS=PJ?Y0o)X={x>ZXn&;claA6A@8U~99 zg}}15U?&QKRC|gfwZ7^Zsg&in(LZ9p^gF|%RLl`vof9&Gac$=@DJl{LEc>CSDLG2q z`Eo-MTi>nOb6(r3IESqf+sCNnxVDiy_0N=~*ifgn>&7xH>Y5LVrU7@NeHF~T!r{>Q z=rSCZP&a;viUa7n!FK9i#y0@{wXX}ZPvkHZ{+E}EsZV$6O^2>&%r6ArLW-<3j5S5} z>DMyb%7+$b&xv-Hnx7khoY1_2AKG;EBFirOf@9vl7)@BRKCa3dYTm26ZLlwJ6z^vg z`+g*_jr`EoYU8@U?$YGrf&_Wf;=b>A8~{(sKGN?z{(14kx!JzL=F?*f6-IxHI9cDa zO^ui`t}0@}&FT9%sWirQ$%}|SScF7*kj}ABOVHbE*caS@T*r@cS?G>h%c{ z^e-Y*0@ZYxg=@H3M5eNsC18lSB^)Gkdhv>IVcZf%-w{-QA3-7dxols1NE*SkOB4&( zgtqZd5qL_~M-905!nsM;OiEJp3aG_=QQTKf!7HN zE0tr=3{AQ&p_;8eWsbga1S_2Jkvu^Yj==Mn#}-KEpQZ9Jdx{Mx5m)tO=HB7Uamh_6 za8cU_HL$s6yP)pc6pvX8ux=f+1wQ$Ii0{AB3u-!a!>TiZ3N&BbTkSOa7UUoAI!&!$ z%i)lJ)zsQXE!{W7azfikq8d)Hm3@HG+muIM%5g|7>%<`H!v9`Eo|8z%5OCv>nT?YvA|M69Oni&!c1 zrwF`BDYIPjFYEAk9Nnf^*iuV$j4w_UR{4DBq~FC%N!ry9ApUzxc9aym`t8R>sfWY{ zOE6>WVEgzE@h~8(c%Y2*=yG0gzCU>`_N5GTtP2E%FAx?)(Yv7bDbfP{-r<^=QBDv* zcIwmI>zEQ^%1|b#xgubDjaCpljwYH3TLJJ44&Yiu<1QnnxLPJMd6zjMe2o*Y^M$$1 zW6E$-O-#KM`V8NT(BzZNz#{M^Wi&m5P(V(M8k}uDWjfh905K?eRN_qko>(6^+QdA1 zo>Oz24ov1M{VS;qYz!QB9Y7pg@Tw(*Dpcdz3=Y5y$e5k>|7ym(^^-!H1pdwme|XU~ zx5cp16oMBnJ8c0^7-OoXnF~1X?!7uVO3rTuOAKUk8~2$g%m6o#uz!HbE-IC`cQsI) z6|x-kqZ@TE@f-C6CeIX%dkK_Vr0~cHJ@8EQ?z8(Zm#~dfQ487V74i=14z)xk@_F)a@ka?9iSaOsiQcdH-j>b+?s)p+5xi%6Rd>&-;1<@wD@s1 zq+G_`!bGjv#N;Z$bie^wUAwRuUX@)03c^U`scAzK2o>BCQF!@QdLegB+F(y*4NS?^ zC?nF0N6nQl9o5oFG%0xG2_x|8_7{B&Lx66 zc3WeQuz*n}5Aws%Caw40QChXe$J!JqW!t-cB6Q&h90l`T3?fhETdG&Nz^KeUWdkJn zx8jxjLbM4+Uqjof6`J`jAI7o#JSas6@f>v9#fF2=B|;^%x{W=9n_A*Kcj>PY7ms@d zG+}L9jPrJ-xEP%RZrsjnYeY_yHDYR@J+az({jN($IXorNr&>k?6n@*~x5tk#f?RHI zq7%nbE*IdQUww?dojqw3Rdgz^Q7J3pS_g_uwOStc6p%Hr@iypXfw`a^fqD~At)c9c z78~gTe0GryOKuTLL48c;?uhK7#fYq6O0{kO6Bkq5Bm->unNq~BGNYVoT9=DgF`+Ir z>^&NlnO)aX#zqWO1H2w1^cP1ka*A48@3ebSrJqNTslN}am4qI+OkJzl=wMI6cFBy~ z`Y9_XNS0;-n{h%i-MHdncJ0b$$F(aQIRdL947wJGI~$WAlMU)`WG)d}uMJ*!zcDat zF4#PNpdm!@bwajbM1`$O(M4h7DT_H5`TK(Z+mp56t$#exy7mMGM~oY7m}pJ>rzP;N z8xe3o1WXH1QBbI54!msOf`%iKl{TPSx?Ik9E;$1$VyqmS;lSrkDJmP7#%2`()P%M5 z=Z9GfyUe6XZnW+5*W6F6#`V%I;8vK)ZUA!ObfGza^e%zBHiMhk7&tMhC0O=^@?~(3 zCX&-A8zA`fR4a09fz#{;I6{{tHiLTvmY7;;*%R3G+y&icU6=g5XfzRc4`gOXQR1tf zQmU^(L5)a%L64{@xzSh!iRsvQc8L|@&Q{j%=Ua?4kp`6(4{K19J=}NNZ1;BBeq}}@ zW)X8t1$qw%$ls%;)Xc*Tst@nfEG-9`3*Olx>D1-BH{KdkX5xnmW3lM&tQfbUhNT4= zaEKI|k&Fk#lpRoXPN;oqD~eA6cJ(+WrVLtCQkXu7%u#JD`pTQSDr1p~!Yctb4$8_} zV_X1q+ja1i$~Bsxy=dxr@QjYa0Toz1?*_xR?h(JFiKz> z2<2#4#jTCe@s0^bF*#5QniW~5fK4FGnyqVE7Vzs*IU4B)cW;IhM( z%LUIhCu?0SPZEg42Z$sbh@=UKqy&hh1c<~Hh-9k`{G#UmqZ(X3Z~=G7Og1(0|Dl06 z`$oh4p=%8k+1DCiobo^>|Di$hMgv)PYUTZ*8x2oxG*Dz;YdGlHVLNLWzw|sg{p)0Pms`inWBgxLH&Kd*c{XP6El1TINcZLTj# zpDqg$-AiiDCwl~wuz}+*Ru{;@$QHN+WG(Fq@UgCfC+^wK2PbDZS<-!5SF;`ck-tO_VRyt4!C!jJNlczhig zH@R4!-fs(mRz31FqOHGQK0a?mTNs}ZYvcDDIAS&a(Bc})2VpO&p*?4_z>o3z8-IYf z`n8>|zi2y=htoWhTY(A0U-XVWs?mFv`>MY)9!cI_G^`kGU=`a~gkBgASY#a!5G1Sd z?tkdoKBQSe%b7a=Myf&|u4E$gOwYD}H)JNBU3zOjM|&7&vE9)GfPBL78uHTRYsk&J zuOVlFTfY<|ssUB#pRttSn|D)kl`d!Qg&T0`r4_HhN(#-pG5W^ZRwB@6-kV9L+Mz=I zPSwlEe*?YJn)0?>4epHN4P>@}E&mO4;^X*h(AVO_0LVtUD6c`+GyI1!+AYunq)Yel zcfH@yY6Ax4Yw@t4Yu0Vuu2~-iTnRAXTFJlOZ<=;#taFYZfXxn6z%8Hxx<&xlzwizO zDj*7|fF?o|+;(R}xVC17ACt)Mo_H`HcLF2OKI7GWk;PLhbQx5y_cLSI}d)GaaO4qgv z-4E-5jkdsD+7@`(@un7VL(16_f|}lydt}A|ifCQYj#bGVTN~Ql0U!0tF^Xc@{~QuFE^!;#8OP4YQl%rls!F1%G!5%;L3?P&loPZ$C7 zgfTErY*oMV8;?MDyAt!dl1?rIQ%#M+wxd#j?v~&oUmLf9`)8N|;|{Qk8n_3!DNTJ0 z5C+_Wk7{&kex_K5%>a9796h#5s(Z6mI z&*p!2d`PGS0s(q=8_>Irf!;k1^zLz4LE0Lice|Qyml|M)&-lAmX(qJTYSc_?7*o^` zc!i^2N(qKW3BexSA-E+<<=w51j3})V!U)>9N4a@er%Wn=gMus4wJJuzh!UE>11|5D z{zV0RtQe#h*fI%)RZT^s++){i;0g0MPX2ouH8*Kw{*%VYKWV`JBaU&Fh3h!BNVad% zn7l~?{aE z6O>#Oww|K9xnS3ga-jWD4KPZ%hWw~ZNxW4fQ==b#+ZE+nHEy(Jvb_(C4X(f>WjqE= z;7G!D&2&A>lC2RVOG5!4dqbt`HI>k9#~U0pR~hp(rv42FE$9sn?C5J8UP7lJu zd@#cFRs*#WW_+-bj0qQRK3ubIwT^>qX6Se_uTL|+uh9>isD2LPDoo^IT}QZ(V+;p$ z>k$XQsWPPRO3gVkfPC>@g)4DtYCMT^1xQ3xuO_(9{wZ5(rq*kVdRStg^qEgzBe?5; zPM#}Qt8Ykzp~AA5Uu6}>EPd{%hGPg4@|B-*ZTLneWEy z=lrw@U*PX^UNTrvpNt2emZY>Vq6Q0WtdJ(U?@;%<8~P zK8lYcyM?2?KZk#n$5mmBdt**S5yqd&uvBsCr*8LV!KUcEDLXGC9~52@bHdGDXIvyE zyzJiaKU@qJJvb5DM^Gr<|1|7phx;mlxhPWe$qZHW=R->3Le#_TN=8JRMwAwW7DUP? zZz&CuT5RTQGzMM1M6D8_7W4|L!! zFQPmotS5rVD*oqzF+sB)y}jsZEs-U~%%8m)`5kXFolCpMEX6u(lW4c9GKA`yY-Ij( z7!Gqklp)=x^7U!_fRlm_oq}BT^DMe`9!8Mqk-VL(PQ(#YVVyAIDPGJhZzHsDy6^=l zBCxBrn__uZ?UONjG^!^d7BR{g1Le_0(!Vc)1*n=FnYsjtf}+D$dnRSGUBQYzli+1x zn{7tr=A?|TfuP&jmw%1l5H0(?9BBkA!m+DkKE##zsIn;m?*$*6Ih+%sqjaB$9UwDS zqX$GZ5}hq%Ookvb&TWjbv!Mf2-O3;@hc#vYr?tkueV}>mYrOAzCve@V&)k!;;DQMx zU2i}1Q;gxzgxCRXZK|^;-Lp>&L!Wfg*hJe+NX;k*Cq6urw6Kc%UIy^~z`}Qk3Vhf3 z_#$Xs>?_e4Eg~md@rgtdNJMGX|5i?I*NfEj>~+o&;J30ofx5u#9O=(CL#3VtWR{Ae z$f;y>Zi9XWG7}|zrD&I!Q3k`@26f&4 z>%{f+U~DXX*ZVPK(NnNaeh2s^%bgy1jW^dD;LexHpjeYtE7?_@SpLWSR{tN=W@!AQ zR`psfEVX#pnIelo#-fh=P>e)W&OOd?Z=&p@Jc>WD(PB6FeU6ZRD%R1~%rqrXDJuAZ zN?~}ql^TZ+@&;5_&1;3}U#r%wH~etDExqeC&~tIzN1u4?uMP&Qy!++2oS9Q$r@vcc z^Fn)nZ^n6YD8C=TTQ0RDRiCJAQqF}f;>hF*Mz#O2cpR}h6xA9M7mJN+SPVS#UAA91 zQbdwJWdklDy{wrG-Cx1{8wT;?tDn2T_a+lT44*rd;?IwHKd;saV?W*1O=e%lPRmDc zFZKx$iAzk2m0iD(?k~6umlY8vOT(RB7vkzoaKauv9>W;6wSz@;@aYuh^I$wM_uqcZ z_LQ6Vyf~DN2Jl!)>_~}$8&d4tMI3BESp%T#GoY*?B#zXgigOeC8KG#8;8B?O{vt!& zIEqJ#ZHtT{5x$m}*kCR`qW$r5Bt=~7lZ|p=a6^uwXHeF0hZYXE7Yf_3NMz&nOXbyq zD!gp8>(tGYd~BGlI*uW(i%}lt^T9InXS8U^B>tUEp@o?dDLInUMGo3Q z?pgx5?L_#Wc6CX-d-KtRPhqX0?ZrN9IW>14I>|#0&?kxUbE> zhc?fcunFT}esu2$Q z?K~{FU4~8vasNw*sQr3avuQ3NXCUrlJr^UE_~777(LJ~D-c~6l}QzRkc zIHny;2O!nC*ghxm_aaO$DYk0U#NkP4vrHhDIx|yYaAyahv`8ZE>*WSKlcb~m#eKLK zwi6V_#iDgbWnR;iq8C@e$RiF{uu@y`SIPvQ`(xZx=~o%zcAp}Y3-`S54r9e1?_GwT zZM}4U@7@6ZU|-*~ahszaJGEVd^rTI0{ISj7{he*Ub{>fMv0tvuq^qnN(s{hXT%iSo0%`|1nx(tUH}`OU!9 z6y?_mUOruJPFI4YT>srFN3z4%92o~;TzaI`8D)Ao^5^E))ho4E=cZi^u7uZWg1$8e zwlV|b($j*mAwGrNBH^dH7?L*T-r5tBpbv?ii7lyd@$S$0aK%g{l^2|1TbWs-hr^z= zNgI4S^sR}b?45{B%$Du(5`YutCCY?Vt#)@_e<`dDS13=cp%8ucR9*LOwNB5gY6>gL zR%TVDki-`7vI)ucH}+30mG2;Z6I*uaVUY@f`;y8eh@3;{=R^i zBmY}>Ur4<($ZVK7lZ&aUi6zWgEo!@znwk0eP{d6&*HBmx8;o^M6tH)?rabYxl4M zQc^0Zlz`GH(%s!DB`w`Kz(cp7NT+nSNDk=;QiF6z#{kkp=Wj;ebKdjTxxVj@*)VXy ztovST-S>X>6Z^CF(%$v0sTXe|{x74NpefVhP)D=r}%>XD{E17XD|FHsP*BbMoTO8eCL;beXkTb z-VtL!QjH;{+-6jdo=F>DK6A?i)Tr_XJMQhRtE&+BUlRA(pm+#)O`1B4Jo$wHp2R5%)N9Ma&-5m z0pFYDfga^EWo%)r#+EGKnUCVu8p}YTs-yKn*}U1QTU3FW$F{9 zYO!-F(+4(Hm~*N^)*2kI9|o}@mtoOs?St{NzVOR#=)VxMBe@Xbdom6aFYkn1-1LYz zF;Jbiy=5(gK71^wRGxX_6E%*vt6k*3@O&386^xo;hT-721J~OKVN*I#Qy|D`G^Pau zzIu`09}A6BUL2VvESYW<)3fvRxceN*Q+Q_p9sWO616{MgM>Y;1h*W*uu$ z*6LY!jJ54ELH#DC*g1g-IiK7?iaXiHB}0v4DPbpeXO^3tbU;l$oq({-I?zi`o7?e zW4YFi6%5SH%BUzyUUPX^)5ueB|arhunM@7s!bS-o{D;s0=D61dPQS0 z$nO0^NSx@@zA8aqC0sb8!ourw_X5ewmVjxyENoCtMvZPUlh4S&oVF?ZyC_W1Li9t> zLKQY>OR2LaS8xz8ky{fn8W-tv6bfIkeR`@k`|)S~K{c2^k$UGOoGe^8$IF5~6%Q2eTfDGU zD42^0I;@g1-5+m{?Vems2r}K*dpJxP23BDsxsWNw2Jxf;11$7C*+Uz3f+METBDWbN zXp__$U2Aur4_*Hk=zql=0jB94Xz#b5rmbr`HX1eEe<-j+WD*5s+Y{Q!rDL#5`z>v| zhRoajcJeoiE#3F<< z%HCCbu(<@v>wKyE5l!r*R|Mc;&YHPmc)wyheqh8>k5MpoKg47tA$Zv>I8j#Udgl>Z z0^7#&zNwle0RypiNJjq~y4|`*A5;v+kK`jdlXYLl+-s-XF$|{Gvtp~uU^k(kvc2qk zV#$_pn*Fk~Z3{Im#!57w*WWSKl;F5D#xr}1n)C&`?=YQM$?4I&zEl@r;g!eX?Fz^Q z?QrIB5K!7dX7a_Re`M1x&T0pZ6hYJ0EvUa-xOrj-5X_IBRO+8hyi#uQ{USgZfeL@=AlipX;)kIlfI7=}bfgC!!*1nCwJ zm@^tJ4-xQiX3bD?d1+B|d09|R1t|CkimbG$V_Pu+l;@wAX!M>PBu6PM(Xh>QU~b{C zu_B=!Ct`)3CyYGDvgG|(sZ9~gnE|~Vri|GpYt&h)Em1HtzokKwH+)H#*MT|D(Id85 z-?Sq%7Ig4r&E-d<vBuHR-#h8glTRcv#pPizx+KrB@S1242xAMp>_g2npiK4MOyBhuRt(`14AJZr9S z{S$s@RyJ1P^1vH+?T{s)3t**_GmCem3*V#I*3shB(z5= z@(_&bo4gUZ5S!j&e1duSA{X^}eUCifhd|kK z&E6A)7s_@wP=cgA5raA7p4Gpj9l^RYf^`B+pj3%tB>^|oohdb0RfNFPw;xTyPkvJ@ zvaYLdvJB;UKRWG(KK1x3M-UoHZhyEr<@;cJjwg?Q=BqP38+@D6kG={#%Ng}PbKU;- z?!TcWGu`lYK4l>I%GJ%nL^}wv4CU`fq>!S`Bs?Uh!1@!Ny{HovkbKu|8A{e*Ool1y zcSY|;xu;Pag7yCB9%&<@5WLfP&_2R|@B403zEkq0O^sqJ(SsJSt1rzLV~#K}{h{Kp zw3fiD_`A!)oE(R}z9r8Nt};{(WkBk!oo}dkrJ<{!*F`Q#S}e`ynfHm+F?O#7k7?N8 zfjqv1*bCMs*Cw9z01M{3fYhHRo`R*5AcUt!P?f2LyACn+{lC$yPoU({=-G6;4~WIlkmM%+$| zUPgjl8XupoNUALVf&qqowmLh7@yGMkIKf~FfE*-9$$Yv3yqF@C(&w|_Vmi&UptUtJ zEN29%*CCo(Dp=M8WieowocU z&7b@|V;2`-xc!Z^?hgFO!f8YXV(cVQGxbdTv`7*V`jUV9_!C ztM&{mwH*T#iN=AC`FWc?5nzy5N~vWu<6q;5*1zLTILQ*~YtAU#ktSn5UOEZMoJk1; zgH6MCaJh_kjx~1ttE{Kz6h>-F&~QmoJ})!S&-{MOjf0U6W)trzIq^MBA45+O5Dc;B z_&3P`R`SW0f1#cdGm`Rnv4EnkA1WhKvz4#yx~sDTQLMU%JbDycL;zBseZUEwemKe& zN#wn8ZXn;Idf#lqD8vgE7%f>rA? zM%8P4c`wSal?Zg0U^n`F{p20?{8{>Y3xDgKiF*6Wd!V3BKgaF=UQ$}cFGZA+_skPE;lBWF0mt>ZiVEAd&ukoa&*(g*xAK> zW#RPM1~CVlzA}W?G`{Enk2wZ-?5wOc%JTm(rthG@;|672dyWH06HTGBH5}{kr1A#u z;Lesz|5nC4^`-4waNpzyX+HV3&}4uGI&38GZpPSQwP?r?Oa_M*eBFvSXTLEb`VZai zNMDZrBs61B_!;f<-IzL`h`AFnW@QMxb#h954nif{RbhuLz}&lGz@r`o^Gh>OmZ^WJ^X!^5SGI7{~D*fwf|B@&i*B05uA=v7(0o$o;~~9kZCv_Ub|I${muoO z-i?*qFOBBP?bSKmVpqX_`Nx7ubIzaT+S**W8r65vqTe6E`nP_y5y`lWD3rRxd2ph^ zi0=h%udVbF`hFXk7D!-4uVz~^RGm0Nfc_aa5mvQWvp1@q9WtbZUgQZ3drd6ru_=^n zwX79tu~JT4S!B^&Bwr!epY{Ar4Ii>^;Nc^GZ1ygkERT->yvw135!=T00tF@&j);a z`r#`Yx5O3qo0zLkocvr*uU>b5PMs`|l6(xINO=)`IBGXb3%dpcil~mw8FKhsSm@Ib6E2hPYhdgMk5dbLFX2t!5v^I$d;@ zgd-mZgD3E~`Hy65Hx+Ew?9(-CyBYA_Fsko3kP?EJV^`d-??Fm&rCfg1<3I{^*z`~X zSKhGn7R$Ap(BeefxMc9rssD1(&m(0ATRqcAkUwK4r0vQ?(sNuz>i^N>n4z5+-NYiR zRaBz(nU%LLIp&6EYH90=AxGm^G&h6YC^LXQ6`^24!LDDN{)hviwnI^u^EcaH4OTS0ZHA5r+P@ zserXj>=dR>{zW5idX9tPREHF@b$&lu^I7CdlQmhiqN!00`aMWPoyv7B!$yGzYXn`i zpg+>a#`&Z_hAp643^LmSoKQ8KaSyWx$k8nVgJBQ%6(HsExoXa|NG-Gc_uj~=dK)qo z+bzgcXini`JcYyv>I#)*iPfr;8!`INuOOTfqN6|vdWH^JKsbm(RLsQ|Rh|5dMbf3T z{^8`k&rQU$QKH0<%+acKgky^1|9F>>mMDEE4I3h7PrpGH9W<>{aSt&%?j76%AYfA& zhJ~(^>)GME)1kb8vB&X>iuR2YB5HnaX07>|lC>TO0c40|%r~#7@18Iizn|TcDcwb3 zj$A28!iEIl2CZ~r=kXyHQdfSV=kjgo2d~IF9P>BZt`jO)=rcz}oYSiNb;v|oLs%oo zqYc=Y2}u;4V5(S54yHk7t>wT`gG;4V_3k&zI5S4Sr(h9Xp{o^jp@HBj&z`N-;CZRA z=h3JQ^LX{JRG$@QLq`$;9S*GoB-w`C|(Ax6CHY zoaY;Cx}*_?`G#^wpuA|+oU-RMj{apuZ-qcNg%3%XaeW=XyP$m=p{XYMHAbh_k~~&I zhQ}yyk%0RhG6q!S;a5$#FVOA|><7RP%NK7Jbw!Nj_QEDMwVe{R1Z%p_4#k<*{o5K% z_g29~?eVI;_Q+q;y{UVzx_%KN~7bOyR9lAU0?4|svMKSqCY8lX)wEc3UKZ$Qim z5btfN*4O;oKH1`9Y=|sGX~?|3mRsMwiJ2jbes6s8-9L96(LFFK6B$nb(cA(8SH{uv z{`QeFFfns6@9V=-jW_829Wtr1OcY2vuqhI*7B<2$)C?6GcB}fQzBi=jkplizTC)S{ zI0duyIgg?d2lBE^L0X`QG~a>*#RhiP(o-E!-n4u}yz66#N|`V@DWRZxe~BleGF1EK z7tEIbyUL&?s26fAozG%-;hvE!zF7ST9rB+zrqraKTBXHr16w=^w&e&77BR?Z?EcJG zOXTwMK5%d49VCGK0V3hTHqrj2U=~>{=_f>xwX*co`K{WH$SOC|mp{uF7)npK|BWvh zC-9KIOty^?J-z>ce!`I-QM9+rk*(}$G$2>T3M!J|Ot6jdaot#LC(|T+=F__Ch-f1P zvu$jCS7{<~sX>iMTwY8hPD0*Gpf(CoidOPf?nWVO_A zKvv6wS!A_DWa4kNlyae-SU?ub|3e$4r~iNR0Q@5n|ICAWEcf8Q`we!lTcLL7jt0+CWrx+X#P^q zf#*>xDpW{|OfkqjwVHW_=$={zgRcltOTX&fM~tVxmhVS{dT`Xq;&akt$U?YyEy61*z4&UGvtoq3!UISb zhP=K9FjN)JuEa}o{#RW>Iq`zK*X3WC?w|Ml=>*z%UQVNE4;(MzGU&( zuJsQL5w+_{q)+i6lU-Mq|B%B8Lpy2dsewWng`PN}Y^4?ho;@ZZh7JMb;@pi8#)Am~ zud$_6Yo$7E3$@flvK+kZEoPlcWQdmK~AltklD+qQpg;kMmRaZflkOBcZ|CjkqJ1G-fJ(tvDxug z8MinW*+mrG?)SF~9gs@+m?`D@ngt&Pu;KjnWlvTm*~GC$6Fke+63tp;&?qhXHb1o&a zt7Cf|iV&m`do+!GT6R(g;P6G@d^rVw@$TqG_YObgb7#co&ijZL3gU%|c%e0Z?tCz5 zfSn6{bs!{n@7`0plt6NHY9Il*vjJh)S<)pH%YIi|`g2UKJS=tD?L1q-dBKgx71OD+ z!;0E>SEOnQAM2uIP<{mNdkuHd10wQ4c%N}~je;aaJ23@{Y!@6JUSEQC3rWcoThp;8 z#Dk!358x~C;_H&*;V<`y`6aBef4!Nr4keuoF8Ho1?7pX%|D|A37}#dz1f#!+m(=*c zfN3SAv9KKVVM~^@%!V%{$qa;*l|}s&tzo#s#>a_``v+y0e3{qPg1N#eUhQ)592^rO zSGQw1$EeKPy)F`lWw}`}Pt+{f-WR*SpGar@hHOG_@#BxR3z6H*K`cw%QUBWr4pRwk z@^j}vUaezJ#pM)cW}u~O1;5)$clw~!{VU8P=nk^Z6y2U&N-}I+o1(QosF<_Tuh`A~ zW>|NN3$Opq`{UHFtb-5OHt(IpB#g+Rnh1PG5%oe)s7Us?Ka zTF#jG2~aer$B`$~POW}iPL1 z_B43kq#AFRaK=%9Pc77lX^yjaUFGf|`{>vD-PIWWzSCX6PjCnL>SzVBS5K0nTJiz( zv^K_?WXc2p9m1$?4+mh-QfV)n&zq49=g~x&s{W6Mrua`~)%)M8gRMz`mX527{YEcf zUM~u9+4=zFcXfyV&91HqxXtGTv9&=C!^JJkfLHdcsaUDe2>=%Yd;9LD?&rL#S`J2x+o`}m`N+0aIN$v3VHh2PsLpfz*DMw1MOa8CK?ZSmXW!COX}VJ5`Fpu?H#*LD6jSCCEH5PozmQKC8jfWu%zPhH#z-#H+5loJ>Ugy$ zk1ELW6l!0}l;x-5$*}rlxZZBX)?qJvDE4EYGCP-pM%f2muLPM1>_McnVa;m<@z)kdousrt<(MGb7>r>7BT zh)2T(g}aKhT^;r|Hd>1B$N`e_qDMNFz}K@w_Pgue{MNI^J2G6^?S{ntGpdDK&u5lO zM7gnW4?jS6I549F+;XvTxp8R@>k^Qh@MDy@xE->&8_RIdfHt(>>1Xf3X?j)9yr_&9 zJ3u!BH_#3dYs%F0rR)=OpEY+uAXp@)>L)8q_12JU zK4%q##?71eopAM;g*h$Z8gmOD@U85NX^)5!)fhH;jG*gFw2U+VlLb4-xtBg1XZdD4 zx@4ZelJt&}?8_{9R6tu&DsSiQYfotTsXKqh_a`dHW4vE#S$0HZR`pvw8i+7{70hDe zILT(<5p{qg)ArwE0HVg8Y^p9!M60oB=qZa7$xNBTxMP+besboBjcR(L`PZ{_2hEJ` z%v9WT23Kj)l7IVXvru8zEVVJU6PBB0NmfTQYxl*RX53iw_Kr2Z+qe12Mm%)2ou|Kk zKr*B`Y01b{37+iP$eW4t&CNg0^HInl8M55T19A(mH3I_X>Z=0AUVF`622M?ZkQKGCc#n&dxDe_A4uv%q+Mqkpk(eEZFzQZpLOI;)ONV$>|p zFf7(YZfw*-w@P!A>brpDrbc&*%8W;R3~KYcTBe$I0^=iPlc%!36J3&)D>eJWVb(ZD z28-it=2|>+GL@%pl<2HSsVsRG2E?pLHzh%WXbZ9j4XE@;)nBiQ&%kW$QNuqErlptgvn_p(z9xAhQraMtmJbg=g>hAN2LY1`J z8Nd6(_a{Nmjma@3+d7$Wc%L!hNpix$hfBS}q?CT7aj(9IE^CC<7w6*l44{)1wY|cL zM+tX(iYEEU4-za(8lCc~%7YkJ@-rSf4%}fr*!1I4r}GOV8l5Phj?m@%q0isbqe!;#5rlgOX_GqgXpx7T zZGcw0;z1ljmjDO3bu3oTA8$~Ft3G?1dNj;I*eYu>XhVP_eL(b((v*Q0w$1W1T#N#T zbYrgNK@Uw=(6T~{RK;VDhd8P)aK@<6apH{>^h~|CDM>I~e^TQNFv)U|t8a9DNLuMU zu=pRUp$%Ea`lo7u|00{>d*Q|ZA{(LL|4TLq)zJSJ)zql!Jka~_kqgR4I45JgmY_lN zP4baHBwv;~x|+E9y-<3j+-n@Vjf~c?Z!}%vEB&qCDj$14e9R6g(iMr~&}FwI*3cZ* z{gsX!Lif*I(9$EMbfQDPDWXQ9d}>pE9A!zwBT2*cLgHmM=@a(nFZ)wdqqcFhU-n~$ zMsdBg%0m<6H<_mvU{ zX3x$-+|NZ$C_=3vwY$pusam^r}$03?Q{2ZX#9EwjlI-Q~3GOisT5B zsKw_;YLbZWpNu%w_`rOg-aBB#?0iF&ayD`3$9CtcK3&E7wD0L{x&rFvl$J4O2divU zz3QNs6U(_vyuYgd>HAL*i$#PRtlxIF6U&>5w%n($&T)M)TuN~5`zWA+uzi*kbeOc# z@UizZ6`+Q%Eb4a0tK8^)<<+k?%C2~uTFssYQ4os*Y;I4ChIRPHvI!hC*IeIKC{hIV zo$fbVQlfkuTJ*pDrZ#TPIBvC+2n1J^bm+N$i7~Tt1vg+y|49P3!NlT;fyj_EIC!;$y}yDjKEqema}(>u(?4d&L!K9s~bs zJ!)VBHqzkaQ)pzxr%DMQb+lXKT+;iw|1#}Ecz*NNhpK6BsA<1i_s?H0({4HMuttdd zBvXKTB4;HT^$k*r-x?9LbF7<9*05wBXDLte(^2{s!tKtFKlG$MYMeNV2_-N;8f$s8VYZzpOh!=4CZ!1VPVEunIFm}NA!*4M)J#tYh^ezw zBl&1zd6&z;&&SSEy`k!HXEkz1%cP~dOpdKU5gA!$t+dlrNwQUU%dC(7nu8&UpdBmvBTAa_xPsnVYwI1Cg*H*%mtwwC_ z1kk?5Jt1v#jlD{r*J5@}=WguWe>C<1g}FC;g@ccWP%mUPIse5H>A6h_?UWB2`hXEX zdUU$YMk-Wm>i5BYD~o%*#Hz|B(YC%eW%|hE>*C^5Ei*X0mZ3zA+iic^k~*jyb=`DR zXx4mj3v!b+gIc`4V8`wCPkDmPmrxZBP(A&v7eQM`@8Xz-A!{LP#%}pqF&B?K?UC5{ zTV}rO{4#m%weqx!JKUt$RG0N!snsv8&$%6SW36Mcx+Lh$tk^A7sxE$-o1$_x0CSn9AipvU4 zf9KGv|B+Es5&O_@-9%bf0A1!;S&5|VLXR1_zW}<UWD>TY5|D-Sc>hl3%0G87ex8_U*--D zqT;r@%3d_7yW8{r8ad|W*u_AW_=B6)71`pVwP#aTd1 z&kTIpKq0fx86$5{pmUb=Zp6I*(v>`{6dFr)`)sVo=mQMfRpW|Ji&H+1h(z)J;45v& zJsmCF8aPLv=f#H;n(nzb7Q?yCp+R3=Hy&~Cyu>|sb1e?)d_W=KAdNC&^b~Ijc;z<_ z!zUHLzbIBJnZMtea`u%}m#RHTCt~=-xqduif5dF^N1AoL3j2hBA``mF*5vZ?*r?XE zSkgz?9+J|C`->uh?5b`{8C;y_Dj3{;Y43`?lmr=(QTfR?YEmlb_8RhTl6Ve4NsO*( zTg`Py+Vd3Ka%#3&FXF0>d?7$VRQg({~AU| z#4u5JqfIjUfrI)vPGNU(3SQ0&qLAvu^Miv&?W4!G0K(f3n?eT{BaU_3QBmtr7Zanp zyaYZk4^)VNb5GTYc*w*AJ>@88Em|n2$HI#9QPn3f%Xr z+sY3-!@LO6Y44MY15`A+8rklrUxi6#%-DsZbj3uz#xy2GS>(p43*hvtj6C>CycOg- zj=y#a#Fk5!=mjUEh@YdBeLkfTKi^=B_^ltd|DBd$=~-XMyJL#;qXnx2+-vbM`#Rp% zZ|J$DOv6`guE>yFFmVed<=XA9%;dwCn0uyg1Ietu&ETO%&ES6&f~Yy=^1o;pft&gsx$E`F6LKbZGMOE zK#9+xh^S@emdY{&%U>zvIZ1cJpt^)ay)XlU~oQ zTe#;Z{c6SJdqt;i@_Lu9Z|n|}+c{Utqlf3_l!7^{uhYv1KI(Zr^Ks$y8)GPWrM+w? z4Lm<+Kq~DdX6f0CCHlA*+WY&hfNrL&Vi2|8{e5-NM`}N}l%A7{Zm-oxga^3fa@?1v z{V9(P&rk3Bp<-w-9d%jR+*>5Z7*!MafW9U6MuYQQ0pl^E2Qu$ABYI%_E?$BA3v!h6 zBW{d##wQ{B?qWSD{2#+LnD|^gt5j2fClAjPNJ@pYCZ7dXzmvIE%p^MRuM;{~P)$H+ z%Va~r>^^|w2R(c_G_fvM(fX;aiL~8@a6GN-pdpXo{0$7UN(c@k`^~Y#$YlJjiGB3LD%rGw&Ql0|+f8F82 zf?H^A^C7Mf=?-_6!-K6bW@(e6!5?WjmtPf=M+=>CHV4MYFN>67+sE!Jo4ho7s$gd- zzDPK~{w=tj&X@^5=>&a~IsMVyv2|E`9ZP(>#y1Pyw6T;Qsd}AMl8bKNl-xY{pZs=x z$<9{f^z;GZZchJ7hR}9E$56?nKH!l*t?5`GcE)GUw_aP(Uu+l&3Z7Cs+Oj_`aN2Wi z%GSPg6bcS*5Be4*vzS}W?vh8EgM72nUFbB%g1b3K1DQg075xwdX1t8<@oMwN<`kC!dG*-RXmGj# zv>{o>v0I!}ZyNBBMceN3ZqmNRe*pGtXwi7y&&}WM=I~YZ^)WTGwo>^OZ}E+)6P_wS z@A8;2%5vYlKu1@6x3DgPANSzns;LTL01m%h_w6E;$=&51TZi2F<;`yOe9CHKz9e_4 zN%5AzyawfZ>D9$u`TLzq88fdtHpH!M11aWn!h4%9(;Qvd>BAr$9{7BP7qZ0%B2hz= z42Z+0cA?5Emw^`7p?!+X@Kh5CJ>6{J=6i|PYF~$3Dw*dYq}U7EetwhoT{HNFiN%CR zm`-f`GdRw3or=h(A{C@mPsGcO$O}kA?uQ(IubsOkEnvrqu5;XX1OEc~dNfV}<~`n0c;~9AxTJmVC(7j@aXvP4vn(=j*`;ba{_0 zF9~K@bCfx{ltizgCB*+ZJM#y)JXzRgXGRCgWQzu$0oSm#gCG4e?s!qLsnd%oO1MwwG041bSm=yU3~ zuCIHa{@y^U^Li;%&A_J&^X+=6S$9(L)b_je83Sh3EsG>(RctPu>~fJNzZ$+X`!7ea z5iylQ%sk6}JkIM_)1kmzbdOH9@cFay{z3vj za9L-ZxRs$aU&rdRKJiNTL5<)h8KYy2n`4H0SS$5AR0*Y30^STKcfb4HHeDrZkLWaA zeBMtjNcYh_sJ2p{TlK^vC`JrSLx#miMI0Tft600_Q>FV2 z?%hNRW$p%6gyN{7_w`*62Tf3nMA+b1Yd~+By4<468%>?MV!?QrEhVW?@%vx`s9n9} zfe--=;^x-nW_GC}(i~V2LE4H$w(P89^uz$cmHbhabY$i$cGZMJ0v~yZH(OYrkPzID z9@v=Z%lC;JmxK#BVR3pJlQ;Ub?=|H9&iiHS1^_7wP0zdbJJI?s*mHvvJ{qYoc&i+( z9;x-CHj%*W;nir@avzHBTIT8F2k@5>%KfxfH^T-k+|kqh2+xd)lg8!oO^8(rkAw*h zZ?sJFy;l4lDl}zXa%d=hPe>P$3b2l>(4xLj%7)$#H*7BN_UQNrP&Y75c5e^F+t`H~ zfVrUg;GM@KWZ>N{=`%du@e=wQHGmR2A;jUWVu1fVd&(+e$!AHAQmB{fMN?hOKp-s0 zoS%pcOh(0@%t*Z96Jze9E0Bz_rDv?cnXTB%g-_+f1{n4AnIE*x*DC26ELfNwwDCE@ z{pP`+6ga0~s#}{*7yh$SXU8cU7wrJzARhXo*pM>)x1LE(iZ2Io7sXaTQa`{hab9PaV+O*QUamDyZAZdD2$IwOL2~84 zko;!-566YBNRH1KpuM;502rEHhuaE@m;?!Wmm#1C&1Nr{1xC^CI>BMX4^$Yww6nn0{5 zE%~&5O|x=eSo}xO)QJkU-tFe;8`p?%a|f`Pp7##wRW4|%uIh_E|LBF)wp*R&Ase$1jokZwAoaw*^0IG zhB=xajC1yNR_pb0V7}5q@ewiew9H4aKhz$&A*qdLfTqEx{T7U=4&dHZ8$n%ev!y79 zZ9IZ#P}F8_W$vphHw9-O%D%$lD7*IEjA)!mm?ogTGhYCCpl+1Y*jMOPXy{A7KB~y{ z-HkD2W0@AZ4rLGBNQ)>}n!p&9#;F{FBOG$L>cYMr;U7 z`WWl*FY$u}m5(x$mJbc1^F4_8p)=3C6*nAw@Q@~@N0^jO;9tlD{?nzR2$vEY|8=QC z!N0ilQ2vien+lL74Uq5|=I;MjlkVS12vrZ^b-_Dz!EnC`gnIojCt*R=0z_noLPy$~ zENvoAhuZrJCMPPFWhq**uukJ?0*V26f7s3EZ9TlR18*&PBQe4J@PXrM9{8x$3lC#-ofr*mAJh+(e)bbtv%$l9q`KD(YvC|j|)p^65^4?=bN(Z&iztRfy> zGg`YDS!DgM8WnBuW>fA;fDu|8_z@XB%>ECB9=5Ht4X`m9-` zIJd@;;w;phLloJ}s7BGY;=DcAq=3uio83iOaMD8cBuHbItIH*av(hu?R^zmu0&WZI zI2Lrd`NURCs8*aJ)i3F8K>8c?9129Ed)%Ky?B|O5lo^8B`g|&RV$CAO(?JKTza`B0 zSz6AcS&-xFd2t<03c>-)WBxKvG9r{EBVFdT*12Of4)bQ^(y0~RHQ#71g8hEw-mv}vC7^j(TFbqnB(>(%8@ac-j zgeDTk+-FEq3Q~n{%Uy%k+`*rwtNW!B#`1`AT@`|SeSrd@L}<8! z+P?Y}BPd9jZP|yBa+`Io)EkJ8%QxOq8Bnkf^L=X^S^^8Gq$v8RDbBfl!e3UR`y6vy zTP@bNdh7W%Ya02tTFm0L8BWaTRSNNk)pQBT_6 ze+eonyq1Vs=z1bgqei8-UgTr@d7-giJvRQblc{k*-hNzGr#Wv(dmM3n+q!3=wj+I| zt0GgluT9eGGVOMu_Hdv1=iB@WS8#C>^OH<%;U@zpMf#4tgRU3ss3(#sn%LuGcA<%5KX@1Q>eT}`Vcq0i z>YhxzX!UBSx-=MDTn(rWHX8>ih?S9n~XnQCiASJ zsx54mJx8{|udf{ETbiBW>J;s3VH{fS z>$sjLgPJi1A|lK;&dHDVB?|s*`~XsNmQI8~wO91-{)5!k#0 zBCwKPZg+rnJ*dQ~#FXgdBuEthBr>WBL)-liYfYPfSo8Y%hc)THtg*HHVXbNNv@phz z-pCzE+E(5l(qe}D^VRRv*;*Dp{Y=6dF3aB9^c|CJG#6>PPN^+h^x`iR69#|Kpj0SH zacc7^_f?bUO@jFYy76*bp5ciqI-l~5-)!l<;PDNNAA}N|7`n^6mr+Bq^V>~Jy;_1` zy!WQ$Vx=r`7NbyvKQnS@n4J&cr6Ky zhkR`*6+$Gj+R^EJ+u}9Zc5$G#UN2KE(KeKO^5oaLw1e1xj|li1(#qeE+>jwbwI6nr z$M;rB-DtJ;8Ohe)lk`ug>hn6mMKZ-u8-01%nG@zKOi?j)Bo<`kpWr+`z&xFWMbiah zjqi6;7o8a5UZ^oC@XQ|oZeLonKypAgE+l(GWxc+=hgNV{n3Cg?bt2A zu&~}C&P0>F)X{cv3;5f$hp=nn%*N}#yC)NKeN^ll-C@ntdY!U#Lprx!fO39ptl;ym zQgdC}Pupi-JU~4U;%5{Gue>o<*sUmY-L7v$(H0ikfyM5r_OO<^o&7(?-U6(ur&}0T z5l|$Rk`C#Tkdp3{mJpB*=?;M{ASulOq@+^;=?0MoX{1Y1KtQDXn~m@LyYK(I_x_*n zdCoIuX4b5kHLGT=z4zH?6-t;_@EmE(BPS_QjNLWwKB^yRs#BPE92$t($x5S{hjz}> zXwpUo(`bTv{s?m_2$O|>r$473QdQl0ASJJTi5i((h5RBWZ=OeADiFHCu#?L{*Ie1u z*u43nIs5L>#(~>QXzz5@uEe&fwyD-*71irXYN$QhYoo+ zg(?NUg?z>0yjr1saK%g&G=H(!od(ejNfe)J9dXdi46u#G;aq4{H((^CS(9yiRj9{g zYdYTVzjPSD;j-T3Ed5yJTAp=IT5Y4+#mc%NqcLSm}-!{s#muCRj~dn6IPLn*mLnNvz$x`w>2F|{To6E>6B?k_5Hucbut z34?PPL8o51!HFo|ktPWun1$nwk2%k3=!z2~W;VmZi8Tv$4ny6p#fHpLHSgEUa@i4X z5ElD-J0)RzV$kQ-5Gq|w8X3$hND58Npj%8C&Cetp_BB@6u@(?2=6FM~K}uX2CFtyl znbIS!7iJ$!R-aKME)F>(uMipzBP@B30t21Gwj5PO)jXdT3sj8V&9EF|9{;0)_&JP- zTN+YtsJYFgBjp``I;Gw&!lj{t zm*lxsz0(u@GU~M0H`f7bF0Z$1FXh9yBct}EY*L3pPR-eFU^JRtv6_TObmWV-tcJ^2 zZqr$ekyjGRcJINI*PGghgB9)GwQREquh*M&RoRo|j%cvbEDGm(3>n2EbGQEVdf~iJ zwlN8n9>GHxzm-*^ZJ8my{|%N3vf?^&#h*bPy0^L3<=-O7g_NNAF_(HJvIM4gnGy-P zUAf7PUVIaUjCl+Xj0!!iWz`Il+PGHEu=BSDWA*Vgw39c=M=cADD3S{E(G(jGr`?#> zg-u3dU4?hyWQ1?dcpOB!T4 zn{NkkC%>x#S>aBOmnH1X>u9WSnckPvh-9%uQ;2<^dk$$pubxV%;b~+P2+61BGNNP_ zgcc5tS~V+<$fQeqkALP4KTDl`&&1g6(3HVebc?ln?AA~vL!G$kMwh!y-Ac{fBos&K z!oqUygOv!}r4mJ?+9gjLp)WJ&W4SDjo!$&?GxD`dF`+~1J)|DT5^5){AyTydxm&KC zKu9m7OrU?HWad7TAe^K-jHn9F&i2dAc4vmI$0F34gh9^P63vD*I!XFtVW!Qb24AYi zcVqdaTO*Hh3*3{NY+sWkcWOTWMrR?o{@uJ_}=zxrf-dI%?6!oU3SpDDURY zgqSzQrIjLx+~2g=v=Gjyt=Vgoz=UShkf zB&`QsY<)O+U`iw4m+Q679mdB#6L6CdSI=iv#}RuBBh)Oa8NYG>=j#Z1LFowkpP`3O zW@*i{y|P+5$1)Dc%oje@V08|Q*xuT1?f7%Unme9QXlT~6>oynC14@i)B*l3N8FnGK z(H<~podm@TabdC0eg%q_&ZPJj++tL;q+0$#jlF_4+T(;6l-Mv78S!%9>1#YbLUzPN zQQSL1KKv%}{_6f~LMKtZXAJ4Gv|_Fn#aK5Km*Zx0yji(22wZbQ>{-TqX*qFve5iU^n-hhC@bgmdXCws8y36Ctt8)($iQje+@1X_LUOpVC}zQ} z*n1<1@=RDeWGnsdw=nFa z#qS+;-`RM=#bYg(&@DEc)HRbBZ~Nw=g=VZjnQcOnCMvtwSox$RIj{OS0(BjZNK z-Q#1TUZjk>%^|%c4%}STBpf&UzC=j3LR%su)k`X2Sa8dMk}Ema^hO{4(>cS#cR4mc zQA>UI+GEf})dF9FJ3>QD)hW8k9;0&Qvk?ibH};8Yq&!nF5Z#BP;%Q%SHkb8i6w4LEVeo&8E?!};7bL1`s8BbQ^bc_|NU<) z1%zBV<`F@WgNSBm-*#n)sjoI(R4}Zwe093YayxD(aU%`t+&-dH{qDVLOXevi!Rk;C930ozOgHHcTaR_tiB$hAOgr>@WmG4%ju6&clr?a4M>4Zt=sVW;&r*8iiOu z>#5J7JigQsmxKuMo5fr=ca@DjD7c2k&GVk2YyRDZ0jbf_*RHOo+K)~K(Laf=zw-DD zZ=#*w8KN%|N3|pcH@__8HnFkDGZ+F^pOazqxvneM-T1?bc92V_WS_2W%`SVQXuE!R%Td>fbl$n7cdLt+-JcfSBNg|PeZNs{I)F)W_n7GF|+GkE)4EPTaxP$1LFFn6M~ zd1S^Bc3rjD7}e#&`zvC&OX8eS_f&N6^yOZQfz_FQMGTdJ;CchK*jNLDi22w0#2$x4 zNn5rV&Nr9!u<^OTlfFsqt}*IScNJIh_zCqhbc4Wkh`~oi*iRuYP24wT+B+7#cc(8~ zd^%q^%O^l>j978|c52g4-9xL(*>c;-Dx*WSGoE`C$&!Qh=I@u*^ZZ^dF0ovkfw z`C$Jg9t`{!Ewp1&HH=OoHnPtS+4>Ft+lgUjv|8(RN1Eq|TgbMjGmwf2c)iUXohI@? zx2R%zJB%FVCaN{ae4oSue_B>ml$I+|=%>L?e@FO?5sCdJ`q%hP8>ubIw#dO3^X-3W zmaHGptjrr+y`Iv8Cey;WK(olWawsg;m9UbGMM{U6nMz5y2BMKxxE<2J&x)8Sqxa=) zkZ4#GV&6_;qz}w3etx@8hRsQ&QUn}_gP*i~JBCFpZmFij{z^zPLtEvRq_=tVqY-W( z2FMo&mP4-H?M(O_!MWZ+CHot*cQ`+liF`4K?^I+P4I-o{$b`hyhpr}a?U#~`Y!vk8VOhNGNzdok`v>1GuM$4C zjm;4BY=lHKnT=uw;2MsQ!6xE7uXJ)YH0iz-dL~;sGYl zH_YrTBR?YZ0xI=R3iR(Pc$2>4K4jC>Sx9>FMvjV!*y_DIfh^ z^VRI->tKfm^cVu7T&tLJ-b&c*$8ZCeAhW{K_LN?*%H7X#b@G98)Q5B$2v59V|Mu>0 zoSfkYCd)(gk{gB@qXft|bJLB|WN)Reqwzo11W&DqS{##FgnFuJo3V zKxY|sJJw9AL)C8Pgb-A#6zbn%Q3xlK#SV}rnRR&&?eeo-Oyr|o5Vm}_w{m<1gX=~_ z3+%9ffI!3IIz>aFw<$#>m47`bI^_?N>YQP+wpM9`-0P_5PLcJ_NqEkCKms~(+jS`wnfo$El&e~+-R6+{_a_{RQs2nr0Xb567OzBgpLU*LK1*^o@YdteQOxxy@4i>6QYA6>Ds7e=v z`YIP@GSVMR+07N_zdkQYLrlCGu7T#|5zpu_j(mn68__Ewp%=*!qe-YtDVvbyyoex{ zE@+^gDaE<_!7>dDB; zAxT23YGz8Ml0(D`r!<0>`^I4&%q)p*y}70u#PwMquBQk2BLd`)cAC+i!KcMHa~weW z$gx0{X?R-&ttUw5n)FV7IgmU04u27rFt#m`8wpTXaA5x+B!_f0_%}0Ao?0a5kH5^w z+Q(vn3JB$Lpx~fL`nXHVYwqu19TdO0=02W8<2nUD2dWCt|Md)zJ<7?7wPDgAdIV{J z)_liSq^bL;Dk0%qAt6y#=%rDpAn}Q8I%8iKPi0_>b=2`r4r8I8s&_oUoCf+^RoD`M z>AK?G4awgjQYJcjT7M8h7Y=FWT_pAStbphaRCBv_jgE+BUS+*8UofD>Zz%DP4(BzIWBzC z#L{c3M`5b7nXjqtfT^yyrkbg9Qo*yLLb9wdC1(X`mbJO`I4JmC)Fe@JYp>qpQO97w z^{+73a%X6?ayaDQAqv3bO`3 z_4CLrXe?*#G|aO&_kx^rTz>Fn{a)t0hK^#q7Y_ zl5Hxx!y0~l@T<<@dqS%2%Vz8%On-)RE|Xn|`1^}6jY(WKv@mcq$q0Dy=~AZl8t5(j zDtN_@+yxd^P4rY%m`((jL#V>;?6Kshn^+Yw6EWzImpyycKxvA{;l2F(#aBN-AP#UQq4muLSZoOs!Rx72waQW zHH<>n`=xyPnEvQlEjfyc^tgKFnIU$mGbxLF!Y9V7$N5}(z!bd+1;$6dJH5cGBsqPY zpUFs$0$eybiU#_=p|Yfg5IS%qz7VlxG|&to^p1;uA@o~ytVB}3TPc2S0zZE7cmiCk z32Fh3+=~z$p~tn_A0+y6Qj+~Ls6}M5Qa>5^L4PcNmY!ncf?xb{rsFZ8-h_xARx%-P zLiPHrM9c28$9I0d$0SITi^nW3|ESy3Jsx*TYC&#ue|n>nISfGt7GJShkYN?9Q|9 zbv?S<{F}Vy{AaLiy|a2i&MC7?d?6vQRR|bs$;IIXV~nfH{FBdI+io4IB2$t`x5{u4 zu9djKWfd6_F7Y4`@XPV7c-JvwSirUgo<0N(tG|H&vrV*Xs+{Gxirh8ns#DjbUjWkm zbKXRC8x>e>5y|ap_^>S<+I)C&I3VXXK(&y1nm6(S|I8h;F80s{u^`iTrL zF?)#XqgR(|RioV9#~yrS@+?;4gzM+Htt#5}xxZeN@9SEPf7y~A#aw<^5>fbBJuRnS z6%VNtoU&RQmGez6CC6Ad>QUl>Hff=0)mw;&#QTjE$KO(k2QfiE920!z`s@l~0_KAv zJ=~>oF6guC-=N@44$D}vn&lS1tkrl7TIqF60Gyg>Z#oY53_q|0#J8!cPqzaRAZ$v8nI$Xq=;WtqKK6{|s7d@FN-VSM z8+NMHLmDSndHUC<17l#;fY`C+HGn|$&-%{rT$El}$empTRX5L;%~zzi!TZoJbLO|K z5lsrjF}5T!SeD%XkIjUatLs15o(R4@@I-8-mN|7bs$ffJbN7Z5r-9|Ws!jD*_0LqN zE3=K5iF~%L=R&SlruB^je2S!+ebOU)te?B^(Gp8@{_SE4Q*HA4SHSH;c2^$S2&dp+uheDa<3n=+Pk@G_GK8~ zZoFXMH8s21O152#u~APzpxoJ=YOHDeTCZY(UNLPG$(hHsso2kbuaAr8R@xJ^32Rb`JdVS7_kA}ITE;Uvj3c}^UDj(Ci+%4!Tq%0{x5^5`D+l{*9KAZk3rzLrOG*s%ZC0nh#A-*NbSSM39)GLF*WZ<<(MVg^*;Tfl%L$j?NgPQaVcxN_Cazp zPfX{Na@InD8xYC-Ut@$B$$w%52LcT0E>-23@2V8wl;t1OhA$V#qb&Y)LN(V;2wH@_ z5V)rQxk7Trg|S_aj$s?*@_=9htTZjqzUFsL@BhMYrT?4X%%=5fT>m$_t>SORKJw}4 zMV9$*@d5Pj03oFQp8$bkn@E}AIg!E7hj!w=^zy`^pURzk9Ud@awCRneV#<3v5VRk| zjm^pvSk>3B@>XUXrvrWI>+o9c1sfOKnEt{&NYRB-cB}QtU`cv#c>1ijbl5A04-M9z zltM^eb!9lGxAC(q7ORKWLov8+dN2NSzjVNF{nf7x`M>(Lq3ECqq~v8%x^I<`d@ZF^ zBJI%7dM#K=;|xhT!8J_Ui>!%^<^}iN6lW96*3H}X1PLgHzENIBZwDH{(*I@XbLU%Y z8jrR!E3FJH8@9usoHsS^dhRqO_$?O4-vn-IS<8Gq#^rjm>hM|dS4@k=Cvy!gbLd)A zRNHbnHB2FP!sI1IAQY;32Zut7tXZ)wsv?%grK1OA2QE7*1C7!r%H9uR-yhMFYcpSr zt>l6TRM03-Dn4_LIv)7fLzhr9hDAX+DE>$$w@16ML0au7NBdM8pkAhd{9T|Z4eL;F_^(*B!*j4w!bhQ7d5mm@qPW0nMo zw(DnLS0w!lw{)MH?#t`8m`E-D@ShhE36V=)FO!&eq7~xG)jcA$$VS~_VjZQIkNxKp zJSgg;Evc(Fk1kxjXY3+pr)>|yevSRMYd|_88~TP5zmfkwr$eKV`8)d^c^CC>s&3Hb z;U423vZ1LT%tfF6ZtDj)Gv>15Z;HlOp=+D2XTrj0kiHhiQ80XP&t+W;V_!QduBREZ zWNr4#-%Mq@ygo3(acHO5xwlrP$dYx_sQVUd-%19 zGdLmcv(L#xsN=8It3bvumt`mb0+YF{W%tNH#cMS?3Wn9pGZI!a;~gCGPUC_V!I%Qz z!*+&7y?-33n#8s-uUx)=>k)|p2ii??sUXq6cE+R0%@+-!4bl~^7|h}0sinBT$y7xD zwXgqFvIffkVPjlcbwXDHsjNyty@po=vFTrGsyAMu^lKm=B!g9b+%VBe>vTJIezu$O!#ttT-fJiPYF6%NoH?lYrgz3 zEqt|?c6Blj9o4_QI$le=Ivgpv`g3%3ev+`8aCLA5op0qq5my(T(E0W_c=gDD@WuML z@YVUA@YUh?d?R$UJ+gDjO?!O!61wWNy9Bh9M9%x{CA72}{3wBz((E9D{T;s#2&Hr{ ztR4fe{`f4P8!K1BAAR-pWjvLJQDb5*ycX{9L6nTDNM5_I7)yU;b>e?%rZQ+=+f2!2~u1Cy3(%a3{NAuBVJ6#uU%a>0buSjdJ z;O>OeY7|mPu=eW13|O?8?g*^A(|vK2ycF}Vjx?V7D)NAr?cak0zBY$4WChb@1=C~& zQ)dNJX0_pLKMEO0G9NT=} zuc;ECvYp=-NOR=y_Dtk@`mTRtF2i$1!^7L-9)NXg92f8KsFVD7w%8K_R?y`GWc}A- z*K6=VqvnoRiDg#`+rnyxY26p*J(qi{6?wmeW6#J<-h`czcU=IkqdHyz#{13y-a`~e z!q#Em`*or(65NPiAJ`gyp0i;ds}Jw?>~wSYsAkvMImTz(;WpcxT@|b{bK4_hOFnX+ zZ0PJ=6?CoQS)^0D>g_+3x~*ZKd^AD0043bX^!n9tyIFz|?gIHNN{PKCB)||CJa&y1n=uUu4dm*f&JOx!34;}59FeKR*3;L% z^Q-^au8TV@$+ns~$m+>XAn6JNKfn7^M_>Hz<5nEqER#~5<_G5zVMrvlgl)%u7=!3p zuxRUDc8kH4bVG9tqUX#1@inz7=sw&yEHmSLV<-5>cv<86jX9jwr)Vj&(NDDUJLPZB z1)#KGklYrqP;N^XHH=K?B0c8(nTGjKk3UK~CYYoq5Y={%Yz8Niz&1tH|2?YB9vL)K zgjDT;wSD0`-GHhT1D69io%bS3L_v+`=!?z1=m?iRvG?F8#*CTXkTWJI*>Qau22HT0 zq{y9bqS$6()!`yl525NIe5ZfF$R_EKY@FX9H~`Bo(H@c!l)PQdr30fb$h3;W@Up zh##R|l2zlI=;SWpIElgm?FLI!W_5W#Y6LpXdG_bg#Kc;-$DGz$xWnAUYPjW`)@r!n z+{8+__MFyAxXRqba=7eVfwyF1NMMrh*Y@ux* zTc6PvcCPs|zm#hs>bLCiRKpJUADRdC^kK#&lQQx=Rk!^MoXl`67hf^^PXOr;dF+xH zak7Py;dv?K{v?0aX?;#8%zMyJ5FlG@2jQJ7Btl&;5<(txq%8p)5?v9DtCgrLIFFVVdR-B?*7{n1kF=*uK`AA*IVr{Jn=Wlw};w*}zgx_W) z$lc}}lPU;EFx)sk)P|zZ7(W!~ZV=BB@aE?#z={88CJr^@_=p)X#rp{1eY_(SRfcsn z3q1Pq4sf!TkIN5@kt{jNW0nEJ@JrA|9k&XqRPN$K&SuE{DhR~ zQM83okAfs$NVZGX{|WJL99nB8+H)F)N)5BtyuVSn_MpptAL&J!59OP7cTrw z8=srJO6FucEj8yP^Bn@~;nZ}q>O-Nl7lEjETi3FLcGuq_l*pN^ul6~-gbLBIhJUP+ zpX^Ka&3ovEf?i?-D<4d93!ht>sl^m;@zr~JnI=*qO}w>EH8@XS{*(|(JHbmi*GesHfK$qR*Y~$PJjB+)NydBvYT-bxoL0EhdfP__+0N^NC zvaRSG#w#A_MYb3a54Is*?}+JIua|7=2oEi-(HMvL;$x(5-5Zz;oFoe0_GnW4{@^En zud!b+EGMFVt>w;J++qI`4GZo{4eFvi-jjKe%39oMUwXcttv89&8b_iX!O?0)%1UxP z|Ebm?K)^eUa+r-FJZxxj(Z1 zi8c*fdKG3-)X=_at;_rSGaoUvoeoTDR}29e_eX~xUs^j%()?+5i3*(n%P83)V-kUiHXhpq_}F{sZAMmJhIQv z=JoN5_pm3~(tInbe^D%Z1`B=VfLhHISxMZ%d|k6e+NfC4JM5mg_rP4nflEnYVMd8J ztsKAES4<6EX_-xEZ3Xy~a0{6%i@zg@u;TD!f(I_KM68)O8^u5T{Hznb^T|W+WYfU# zE&UqWpr3y#?#g(+$QB~8VoR1#432K^@Qm12f%wPPro|5OoW4t{&O+uU73Ip_Qm3&) z^&2}*ItkH-M|n;ftm+W|xXFH7@xzw{1z34MB6I?&VOuAhClZ?S#wLo4}6?BIt0Ue=omvj!M*lhC`(>bO$In^#j0QR8)N`CXE; ztoiBl*-b!!@%KhZ3a3AFgPP?|WMRdm5q(FR6}Em0~vtcYIo`a!u-DJ}}mqMU}k&06#pO zwnB2FwRSGkvLz^O?1i%q|DLWLjCX)28L;P?hmDd;LBbambD734yb6#Y zu#)+tJKiLnpZU~!!V+u@Hq4Tzvmv|m7T z_OCqdRe-rRGX1Bn5y5s`l0(9!%q=$7FvXJ}1G5;*nyRTx z;;Q2pG@j+Ahz+|i=YArR(dO4TfaL9+>x+ zS}#4G#;a;Q@rc^5k^vM353SY3f1L&}tzf(4GBjC_C%59i=H>##(#$f3{HT3b<~(ag zI(T9NR01k1W{>vUbKYu-ldGLxt?WUtxvJmJq(WowaGlJ8EM~*rpY%)(jYdqSPTu9OAF$dRbQVLt7e)# zEk|18zk4C{{8_P6v`K8_9By>vScq-Sq!8jc>P z7y24kaoFu>Ne|{bs`e@9M6Po~AuojtIb)um+8FaE+BP2lS(41yRk7~ye8^i&dCKS^ zh zSSg&=vLCcS1(|SbYtKZfan?urjGf36D4ingqaVyox+&xw{U(SRRRL}9^ zx>IaMFELEN*eUAPeA-2?qbW7yV1e6M$8&G1-7Es}PZ z2hZm~niZ|guAV{(XIQ?k_xyQ z3#VqfO&OU63m`cRB?6pBLxi4r+_gT^WbV5TzyrVvG~R9 zzA5<=M>rxu@P?LQeS{;FPZ1ekxt@lUVKtAz5s5WC*;)svx~E1=X@3l_MMG@~G~3b0 zuwi~KL4n-qCSzW`aE$-Z4|ir&@T-ceE-z(36??-E9td})V_%9w)t-2%zPt&?A+Gc~ zfjcMt6gm5T;he_0#b%DW%m=yJBQl({|Lk$^MBi&`1&2$ju}<4Chr=TRc)llWHGQuo z%9Cg zaPPEy7l89h9Yv3hRY9r-7O?(cq<;0>sn!P+Fq>cNE6~6PS=FvOv9Y1zI6x%NN_5$@ zX)z?gm;rgz7AnZ2bRxl@y#Dkbvw*Wx`zenI3Ed2^UHr~Pz z$IfY>i&#cez^>5+r2c}Tu&5FSfvEP+`9jMe^Ea{8b5kNH@*bN-K<*aWPGD4#DH!#T zd$p*VJBrd`&T|upoIj65a#Gr+1z=W?0!(v*tBDCS+Ph@?nq&&R0+|6F@6%)VgP#)s zP1*lOMjZQXwAa`;is#VXID%))-8gK0NQgW4{pGH)ad4J}QOv~q9~QUl!TBRN;t)yy z)ExRDp`zehn*G8(u8i3k?r|6jLg}(GLuO)@t`&m z5?vv>z?G!IUBWhY?jw~6q zHmgf;=cD)U=hLV=P2Rr)XCTy_A%OaRA+^CH3K+{8%NMLUyz_#q2sOZ0$tv$jsw%idlc2a4I$iEuz@t39kviVk~c^nwM@J2 zQ5?}Z&hGilquSl{`Mo`D{kv@4W~`Gebbgh2=r!)wxI?s`netf+&&i1yYlo{39xoa3VDPbijO(JcElWSk=L zhL;PYXg346=1Zb-v%?Y=yHTD%c||WCtp0Y9)WT%W=KCDA>NLKk4}X6VOF|lN*ZrrO zs`Kxvrg$qMugX{ydA4Kfj06U90&z13vDRm`8RB1Fo-HT^15EX+6OV2_t(Iy*xjRuC zagST(OMkfbXVF`(+Zlcs_doAx(N9p^e0n4X;LwC}%oEiQ`?;Y`iAUKy54ZgU*A+7o zjbleo;tJR%V&`zb;r)`e3;lz3n9bvXf&6+nc_suN<0IAbVV@Q?+d#=vEm-?AT_eLG zGZ?w#zf=X|bAxN(@%g%7eD?t(7!NJSUe8~551!v4LQ!=* z`Bf~8cIy~Mi}r?>Q7Q#!vG?F*y3b&=WoLXq)gLJs%k<>Bydq7`2EV>Sh8KRa4NqD~ zg$v48_hGu!UFhL5{JPA6%h73NFdbA-sPY-Lv0%z@FdMuUm#sA#HMJmhBpNlmfVwRj z)w>{OvCF?|S?B4Wbf)imBp!nZT~BGU{cOf?YAhX9`X62X5$YrCCaOshxLJ%|U#tux{XBU7`xWo_h0U72) zC~}0rFKRr00*+!1dpRWv$(t>YWf&z+zOW0H?uiglyh4S93iFII9T(nfv1pTsW0M`c zBo27PABqwo%E8#WQpHV3M3+My9o(Z_OC259BT`FUI?kc6-NpLxxP{x525B*SU&}H# z-KLQ=%a9gBi5*WZFfTatZmXI=yYmnB7soFGzRv%A?{w?W``R0S2(NB=gk`=FXjdjB z-s#3uJeAL) z8(N99owRo+3Zh^mYV<**y;!L4Hi`4dE9RciuP53=xht^mIP(P zP5!`oPBRJgob_exUD!tcY{Ml9FvzV0)qWH0#as}5_C~wUYiE$y^`HfRWqykHi0$Og7#8=U6(kYq)6?zYR^~x zTyk?PQw`D)#U62ORqzgVQ$bMQ7w402P5-f&@hRK*OLyzkJF!|%+S-H?Z!I3K9rKRRMG@wfkDo4a%m5IM;L5-2pMKi)keV#d)MpT zdpIeS_l1_K%Yy=N&6~eNn^7BL0z3Mug6tG{So?at-tGb@e zBREW{BqvREu87)5jdPy+dM^5o_XyvP%&$u4zNhzJvykp>Qy&J7Z2t7;)Nlw*d7sbQ zu88iYr1BsZx09sZPL^g`^p)SF#GnY-5)FmY(EZp4d0HV1IsScqp?-tTcaee4KDgwd zi_BblR#mu!nbfk%H^E??nh-IFLM<44&r+^DDt7_RvL`<(mlus;&eQu+hoRJOqa^O- zx-;UJC}s3(?YDkZM`d@BCAZ@w81t3;JSiuUr5XCv5`GP$kVC^H$n9}iAHMi4_NWBC z6m?k1e_4`VN z@Z!n3vWF4A-{Si0(H|9C2O1*!?9tka^cg!vCN{zy(ItxX={iLQd-MpU_|Wo1`g_Cx z-t*@z>`~=qx1k8%6ug6{pyQh@q2%T>(DH^`Tw8=)+C!zr6y}okfhy>mxLw*Rg>Wks zMv&wOL(qQ`b|nVJx~i!p_ho5)V~8p@V(Jv>5B)%b#P`wNgiulm%%-vJfWG``I2@qH z83F*4rz85Z0(HU9ZmELNAGp7vPw%_f7qr{gumYO=PXu2Ms=W2{b$G?mM>$etA`5xW39U@OQTNBXB); zb!qaUR1C)(#ucShOa))!l!`@o!@92maM{d#9H1g+KkxLE1u?24M?dIZ=uGcjR(kM) zs+#n!#uNi-ONijUX$h&mGNSR&9q@Z<1zB>^Dvbcwl#OmeWojcpVsev!6ZA3dv(fkH zH=8lQrJ@4@%$WI0W0MIqg|XmHnnpj+G0a5YrT^@+@4o-NJdxk0Hv^0*TrViTvSZiz zEG!U0!Meg)kHb<7@!Jet6eq#O?tn#frjoimc@&@+Su` z^tVo~7aeQ8!M`}d*y3;|$Hl!6VO^|y$B!OHdtbD1Um9 zbKAG|5fZuWDuXxEo*|0uuIlB$+|9_9%O zQopExK8oz9+#6_?q3Kb%*x)N8DwhJyval#>aRvJ=ublZyO2rkt`?Z?bs>;jyqB5e< zuSr>eMY=#*ymEPBz)H8yfv_q&?}e6)v%+!(V-9GZ)E%!ftkEM=0--bAfn^H1RSwa_ zU~9x){NDho%2ADe*hma_9MEo;P_(gQ*ZX02iu^L~F z6oD~O74VpTG%@rniZ+G>j_)Xspz?op!FKa6G%(=0buCU3(cs8i1OGx<&`xykd}D69 zNQ(3U&yiW-Hsx;=+_$`c7I^5LK(sJ^qn!BVi;fYzw-YI{>k;k=8n-D^%1gfA5exoR z7EbZDtEr0m4rSRUl^-_MnSSsN;e$!&$mKSr#G%V^yidE(9ro_L`cf=0l81Cs(qhu< zDbA1jAMn$oiCL$P2&!N&5~lb9LdqQ!EvDDs50=@HOwAi1L-?upbzJHmRjhj(*`o)x zutmlQF(iIpueROnr7-zcg(ZgO+BAjobpA82-8*9V-2PEwNw?^;8T`bO#OR-7*Vf*% zM9YlIokC;K#}p0DawftbR@Vp8LZ$@5!+VR1`!9(G1!Orh;@+V%EVw;?-LBmD=7@gyiNBo0pY&rtb1OZWGg^e4iy0pZ zY7X3KteUC~%=CNW3UIr->4u|;E5PIaN8i7yriAVO&;C8`Kfsa~qFX+ZL4=vaI7;2 z{;*e~SkfQ1>=Us7t|!VedpT&9P}6ftMH<}UQP?I^Z6b!FHDs3cJ5^zWWr7V>8J4;8 z8vWKT@V1p!u)RjG0K**81BMy84GeR<$pw*F51@Fnc(|q|eJ_9~&#Z^lVU|x0=LIDg z)(qP(mj(bBWx;@TTwIfqFYO{|+EB`^7N*+{=xxPOu#1*ci16*wFyaUk11IMkBRlM% zL%LxH4FK61MzFh$`uZ3EfFFhdTAnLlP3H3r1<`fqSfGXz?`TNs zX?En-7r!~VkFk|ZZtD^`dDOM>uYB#aq%w2$SzWcabnXd=yd!Bd4W-THc3XHg}PG9%M4$Xg5v-Q&7 zxkdAimfK}i#d;f}*W;6;jEc5bn!)HH-ma<_>CRO8VYyxQRYbG_Jm_;=^wvc#^_ln zAlD_3Mf(2IEd4WzK4P5yT~qUX_zOHXRr?13Ol(^M7Wm^3&D(!OFk4~R>mmL%Jeq)> z$F>&qtJ?m!n|E-pn1uBH4!0e1SYPj#%*F+uq1PVoOS?X>Jsdc|3ZM!mp4fI;%i~Tk z7E+#t{K>MnIj~gSl28lk`vwTw2>nM>PenIATv0@8vfnANEUP9Q03!GufqPwKgXCz1` z5nWlBxbrxClfJi(WH5wG-NIC|3Dac6g_eHrLr3CLPU$tzqDe{VZIMiLP(xp!X;1qu z@=Kz)-$6-=uQ%SIMq05{>#J231+{c>-*J@j!s%?* zI&9YW7?n%iX0#-TBy?^iiBH}9t?&|hSBx*n!mqPm{?lxz_p4!4s(&B5kj^GA-1wCZ>ag@f`79AlS%HVAw8e6b`81R4e{ER zo~unLj>{hXcFB!db^}=k;m$XdTu8zzPE+(;c*1ek4(Mb2MDNr7@Y&!JF@rBs|D(m# z)w^$U2Y-VX9&#lF4y+S4BtV7z5iOjvb)e*?}h zV!r@ESvdOitW~I3#DgzqAQ4tHAd!s@dr&RL1XT-O=+EH5^KSy{gA*sqhRIu5e4)}d zRYk1m`|VEgou9m(y;cJ^c04-%1WRW9iA81J!hy5`t3H28XJTgiu*h|%0#)FrWr$_Z z&zav*c`sV1$po@k4rQ-yZdEFsYi-J|-7IQQI!S3l(P4U3r@X1!tzZt$v~du^Fk~}S ziX~;TWHVfeCCM>n7j%myZMfcNeL}k3t}X@+vzeP8y4yLTW|m%!u!GWZL?Qfizh;gL zx~Ku!VhxgjU?&WX8QIt973m>!dy}WRg5)q_Ny~UIlnK@CO{DKK=rm8NR8ZQE+jhd; zzA-Rr2u{EnBro*kx=zvsq;{9cr(b|wE@A!-J`7WneEaO?W+)peQpZX@ABuJF4=42Z z@kRgY{>~%0Lmcq*OPZqu;CpWd z(0u03E^yG1Ft-9I-S!QrCvi_DsysyuaNLm<#2me{F6hf)FiNluAPnj$1(^mj>MVN{ zr%?MYSPkd#gg_0_c?cNt_lvq~H<8kuFFnE+O4%I>1CwF}4XkEV!jw(P!6c4zeBeS< z#B#+Rt9Han-FJHGXGL>flxHgIRZ_eY_^W`}$RV{?B@U*OMZJ zWJn+2A?Wzq^+i20AvV?jQ`lJmwbgxV9|$C9ad#(BtU!UF4Mj?E3Wegu-3!4|yinYN zOR-`F+TvQYxJ!ZJ?oQC&^!>m0oBPe&nVU&w)^Dw6pRi8sinXBlQtK7%$w`juWr?@721dL09qfD(| zZ@XqZa*%dTY;pcp$5EBP6@o*eJ7(-Vd%f_zdtO`TARG5dP2!_BiE^kVx9W`D+1Evl z5`!um!eX6;*7nL*)+B)T027^Pwr{BM%eEsS5q}yYlgcDxR zVp)S1*1lz#6UO@%?4K2jSf07cvs&h~p_Z1?NBG}ab;|x6>E(YwVAY=Xge*c8Sy}Z;^OZg*=Zm)7T%7bJ7v(<(J+( zeFK*PF^F!RFLpgkhZsbMn=i9P|4Cs4wXvAOx<@|tK#tx?u~dIOz11Byk!%RN?T9t8 zOXi)s8s&)uU%N}0l+Nk|0|c=AEg633$(C42I)4kiVUBMb=5d~&G{>BKXpTnjZvD7~ zohrt9wx;bVeRiddckYRcyuC2L0CTVo>cgW1mZq>1Em>85IoTPFZx&{eV}*6fe@VHQ_Z!|qt>HpT z-!L;)c(ET=X@3CR1oz)$PmnHE`K=Dn4EF5g3zd)D|$4sgx=R!bXk z>ra9wXcq}nu(NHFnYx%g6y7`KkHW}PHxOOlGN0sFlHJ)cZR$HID-D9rRELuF%f5I& z5mhTSI5n~7XlgTbK^iK&8=#zA;0zTu8KXpOau+l>Qh>8Cul7c>vxc>w4K?7}eu;*r zv+xvriEgfG*RUChc^qV3M3sq=?E-i6UXq66;^#?81mrm9k7m=ig?bH2-ef|vx6t@Xc+x&!U>nYW z+r@rI`KFiuyPrw@#BGP_avB{EPi5s5v8Wp?KlG+!XpS=AsYl+Az$bu z@AFFrGO{!cmM?$*zg4njKAr}Wn8BG(=uf)O9Uk)mnw*n@q-ET!wWs|#k#CV`R{Xw6iRw$ zz}PG&&(832_}h|>YhcIKr&aKcu$7cfGX|%`=#EX?x<0`L;orDM{Y>**$=aDg_aAH< z`|7#cmq=dlWhnggjlkuf5D_4$2=#O7J=aukaKIxyc&Zl2+&k{y?{%dq#;^f}05Ou9 zHmUTKyU}8P`1S>gL@h`s0=dRMIHx}BBJReq`s!z<05jYj7&Ahc1*V!EsWCw=5vxs} zBVVhn)sBA;ozvr$(%!A4ziY~RItW@N?X<hXUQIbrfNeehJCVU^kB#R}PD z0ueqjAf8-&v`p67d+Xnt>q5bB>u#Md4)@<{;_7oRgnk9B2I*$k=ho*=;l0u@9Np#N z=Hj!#Y7I;1_QKVRYjMY?`pKR#psK$pV(0MjOK7zpp-$KKvOy>4@|8@_OZ@#3Zh~6i zrQY75gs*9Eh~vWRA1J#_k1Qd-FV4XDS_mPRaMLU{)vEB|Da0Skb;08VubMPq__mDB zzOn7HF!&MbdFSR3EPpNG!y>A;tJ*M1km93FxdD9HQW&`B_FnL=ai6tH7` z@a$=xG|+t&Sh%Rxf_4HBH%Tmh1ZZTIdsKYiWA$NU_Pxn2?>&oYNuBnVf=A{}QwdIT zqpaY~p4%>j(8hvl*59NHj)aI@q_7RXY$=&H?c~48(0WSy_{!iNP9W&8&Z8K$>7?_; zW7(EMti7|+nQ4^Nv|(vH0As*ii=b(pvgpSC{K~OvGQ(+O7PX&q`gZ<{qN3#?RKI-q zQV~8AmGq)#TFyJ7HL#Vp{;JA~P+L3Ap0kxXRGdRftC|ca8^-b6*+M*r>hI)U7R%|} zfH}58K8*_=x@w_YW0UEiR1C3@%>od5NKHCiye2UqMgD@=BOr+-(PK8 zNopdK6w;qtGJ->I**=95Ml$mF0p9Gh(LoP8-id#Clb-Z&I2wOrjXWIHw5qwuM8%E*#ZMCc&e6GZA07T2eWTbR zSyC6S-Ycy&LKr`*$el|Z;a@;O#!?;YK~5NtY9@KxB&W#z%T;ZgOQ^z8ZQY`cqmUI< z#Ujf7!jfkz1peDwdRr;@C(aT2C{Twz=S4<4f2Oh(ATF$^1*@j70sa z0uMG159JC$b1&st!3fuWGmBQ1rZRPEd=3G%YrG5eL4Un?rizB*E zPvU?T@v7E3>BOgn=@KM8&O?4-&5VsAA~Cx#Hhg{ z2VXq4*e`$Z$n-3x!_p>0ybla^+nV4W@&oIKvN|H zNM-`u-K_nZ6g&?kHEyWExI+``aq)KjD^yKR(A@h>zHF}yEQ(;_GHNw)>rHKy9L6@!Nq^HC@heDdR!f3^+cO{z`T z6XgQTX5GpzM4|_g*o$H}YO%r{3{&g;$3HMOc+F6Q65wfyfZ~n=UqM5AQ~^^r7p{V# z_cCb z=Cg;@eJx3A>!_ET9{&n4($KaI6^5Zq_kL*ld}G`u%i{uY2{e6gph;|$IPhpfk??&i z1^~ILeh2JOT-iZlXx?#m+{!VL`1uBSTnr|!wPo~V)n6Yd$brW;k{Yx!pG>VM^`VYq z5;C92uP2qT6u-BJvq#big<6p{q? zHPm!n^CCg{ob{xl0WVkbnXK7K=m6QSoKD|YXSq=Ad8JTA+|j?@_VT;Ig%P#C(yNZF zdP>v=a)^En;#y<{T|DkQqWVegwW@%qh(^`mV}~15<<`bxowrurzwwSi6@D3pe$^ znGbKG8UH|l@2uT(9$kVDcd07u4j7hB@CYZGNn&7XXoD z9gQp$1pfuBUx~sRaZ)b;@c$S6cVJ?CEU^oE0g(R{EUb|vrSyLU=NnjUv;J}aEj?07 zk_xzz+Whp&i%prljf#=~Ic!CAEtc|b6&8n_L)u;=DDP@fR)j*2dK4&f55aH@WDx6r zd5l|H`MVj@Ij?6VULB%CHX9*Fp5o^4HXWx8AyxCE6A*i3**K$2(n;5>PH{-roA0eS0cXLK zE4=}Y##zU#!>ww_YR2z3utKTO{sX^r$_L`3c^vr3HT7*CL%=A_Yi<5Po`6NKGZ4IV z;O6u7_+_x1DWAsbxP6XwfB)7_5)v65n|^wxnMFd;S14$?d*;z!K^7F7?sln}<;F9l z5n%rdOL%ZlQX2J*j#FKa@YY!4+VTxRgOoqbPvz7%^yA5J4-?L&>@<}FOYvCRe(nRN zNZ@Z!6CniISW~Y%s^03+ofy?Ti7V&s;`t2op&*&cQyS7hZovIsb_kA2A7Xr{gd(|I z3O=A5>DPjhEXnc_zMtp-fdjP=;MZh!Pkc6>CR?iOG_{=!p;o5l)YcTfU%I`r()IjI ztzgsqBvwylgo1@CJ%FH;_otwkN0Oo^KAeq1qE&#B>qOry2NWLe&|+rMn-zpru~1~@ zZGe9$=3Tnesc2Ti#fh@$gY9vfhkzfZy=V z#>T1l=ke#yWcgo4nDnn~o~`a%#fJx@hIe<^DL4ud-Rfnj-5dhYg&wZ;dXU`0MtzC5;h+$I7Bf{A}qIM|*X zidU5?jMfj6DS-U)DqV;8UOoHb0RJ$Tc0r}L<`eH(-s(!9=)_i}XJc#i`q`Wk5R4h7 z4K|)Fi5Dnt?O3cAkO|X{{%AhwJiJj#lT^VR&P$hK*cdpWWc^HZ{CkAY;H8^R_1$!w z6${-ojhmh4E-;vI_d@HTgs7i-&dnk$`=0(jO`1)rW8nC(ZAnp+m2j^zP3kkE(xO=Ws8}tpDmFrA~?x#ng5pDp6&5f{br%P5@ zKbxV$`re-&j`59|dWw{BTAQpn+BtBw*IxTc4?A|IWEI7_@=f5pLpMF>I+I_dp?GQ5 zdySI@zYk*dAwKAplJQ>(-~W@ZuwY zv$azDSJxpyCw;m&4GTX_t|!mI-7MhkMxwX< zX+%y$~ z_vOtAcCmqqffcLBEK(ar$z_TvFXe<>(vP3H^Db*nZz;Ud4_+ zR|0OZ`o&95_{cbaIoV?HH}EG*XeI-JwNL40tT_&NVyGQCdaZ|pF*3$1-294sH422% zRboaa>!3OCznRUDyFlvnkde%48El%O?BZ)KKN|WBI>y7TdY{Wz=#ktFI+Stz8#Z8N zuc^@00rwu%x-=>;#HCdFciw6Zv#9n9X6G*Nep$Qk1BjP*hVK;y2(YYAZj91^?E$Md zTbFE(xA}bl`mYR3e6Jw4%!AX#K3XduXIR!P**ebmS0y(HnlJGDvR1zC~+G(-6B9 zjMHQKJu%1y%m25X&DAA$&hwxH-ttF^6sxG~n{uD$JM2L zHNXw(>06eu?_Q??G8C#yIlAe04cqa^&0gz#DbdxT-5v%ii%q}O5dWslp9^lgIwM83J6)Hi z#fh_a8OCNy*J0j7%bS$D?2lg+=*^nGp3;CfD0h(M9hd$|bE6((&`>Sk{Vd9E_He)M z?w0qnLziTTARGVjEI)nU0M-ZFvIODRFH(snKV2AXmaq*6OufY;d@%#1+~I7NgY18> zPkKp~EJ2ZdX7qWtMPtc2FKE0p^3}{Amr~7`ca^+v#$V=P>ROtTZ#uG8VUx`pA?aqg z;E3%3-0pH6!5l3#TrS?E&u>1z-oH9@7k{Gs zo^P{>+w*t8grm-Ni77_ysxKrUsjM@R!MC~ z=ZjTsheh%PJj#N1t&7!@91LuRhp;$4Cpf#sCf_DPmI;1Hoz(^HsFLaI!;Jh{r7kH7HsttF0yzNNgQj0rR7%pX>OoXsfpzM;Wct%1*2 zDUO_DVX3zvsYA&Ku+Db)=zm%9NaGfed!{{&T9J*LyRrFWZv^Qf{j`WW&G23*l*^($ z#S)nKu5Itr(^)_CFAHKC1@_K#vXnZ1zAOmajX0{VI4Fdr29O@z@-Yuv_)z12%4kIk zP%moE>WKiWxiDsO-A1Z19IrJ0VK0S;xcFD(M7SL7d$( z?B%@)mE_O#6W>ZiuYv75Y_Ob;GTR)?*O9<_(u?-!mGXUfEy24-MdhtKkG|$ow2jR} zAQ@A5J`L~V@;CRSDnLTZ4u8m0tj#QV6p-;8nuRWNGekmHd}D**jL$E-C}OkWw||5! z`s6vWI&>yDygi(SxVXN(sw}D9gFh4!+yx9!lC14XZ$}0SHXnQ<2II6)^wOqpSplr@Ko@3X zg|s%^f4yK*z<*J5Rakh1vVh$g#Zxau=VcKLR4q4ref=7@Np|hRN z;8|ibR8$}d+BfiX%-1E~TJG6tYKzFNQb~pxwIPZFn>9Ao&aI(>7(;9=JC?({S~+;koJJ z;&fr|p>Zb#P0Fp z2NX+^~6XWd@Ww+pzM5TF(NO%whf(aG*NoSAq4*0duOhs$`&q}9oN>R zlASmUpc}KF|8*{o<)4U$OhsMgt!rGo2VGGcRJggUb<_22UgNZV&ao|~j^#_ShyPzlGr z71kW`h8gFZFMDL4oezBA_p((5F9z?H&l(@e~dk}vf8%kZ5u%ea_RoO3OnoG49@MMa=ji2%Pe<^!S94+)D4t4JV|SRjV7#&CjIRA1dpAo!pX5IydmGJe3bv_n)k zLeWevaW&jOT>smt^B^~3<*aud=6W^yilCs>s~df*WI2h}R4wC97am|EY+f`<@q0fL zy>B$=x&oY$kX>zT_oLhZd0(l<_Mz-v=38;VA1Cc^{&bk9KWq)oK1&i<%?yYSCvv?A zvY}#Ivy?143E@aYK!#(l8VG(1lPHZDjPW2^&F&5J>f@Wci2V-PL= z2bxd-xc`8TASMHnA<*$qM8}WuA5#2Fk@Npj^j~6i0Q{#m@t2r?{Y%vNDDpDI{97YO zn4$=Sw+9iA50VG?k^}!{X%Lq9AR_v_5usyAB{Vb|dki#cwEy`yqW?!nju0V0wSH@b zup$7-UOlLWmL+#{Wyff9Z3=KSYao6NQp55u)VfiT|dIqfx1U_9IIS zqCu}lR1<;N5rIUg?kQy;s)<2ti0Qwul=mOtAqMfIJ0q%yQL6W-7z0@Ox1f!YQS%=G zHwlQG?w>mtDWIYK`G$^0^gllUG=XM>0SSnO{+}NUIvQF81{xai|EItNfDq{m3T(*GA?yzm78 delta 61383 zcmbrlc|6o__dnh)m87zUQY3qeT}H~jO?Ji_i5Xi&#PF)fzJ?+DKDHq;WQin8rfg%# zF8jXk!tWZr@B8zzvc}2WCdJ*g5*7c`uZVOXUI|8!j zmF>MPBQqo!`;kR5?JwU5_OFiGKQozX)VThXX*eb$owGVZWv_jIC3J^nq=2X1nB$7V zheT$|LcF%n>8o#tW1pFR81gGRK^ z^zw&s(K1)j{SG@3>}g1unU7Jj`mA5yIea#Y^l378_nNBgB=500=QDQZx3$y;tlrfk zXiH()O*v&y-UY^X&p4`Ac5iy8p*qX8 zQJ2u?;TX+!y2zq7e6we7zcxbj#)H)R4C@*j8_{fs>-u2Zc2_?h+Xx*vX(m-`A4b_I z(wK90`kFTr-nji`@8p=Ty;bJIN5138*ffR*)wnb0(lkAz(=U!57oP8CkorGM^ud&P?(94Cm|jHve$h{fg6tS7zyPwhR|th4@a>y0#x;Vm`SoH|~1; zrK7wXR|RL%x3zUgkIfqv&#vp*PU3R7C-d_)5DCXZ^Bf@7(>MG{R#8Xwho6_7g3j>t ziY$eiWKdXk$docY{S@@@LRGTiD1%zBKg+s0v6O$Q*{tXD{jI!|dJd=YAW4=+)RPad zgbP|%9F#ZW7BlT;%s;l7`tBfp)s=P@cMm2O*)S5CGlC&XKf8j8lyn2?$$F+CePUP z)>ieR4Av&g4mH$xE01L?>(L|K@Y))F>esh7p1yIEtLZ)Z;Z7^U$mkY&l;^}Ws>#%p zF<@$o??doi7b_jkYIMf?z_$*&-=KgHgrw^G#+0uZk|ut-*J9?f+)T}y=g?ET=2IDx zYfZe&iF>q9PZX%!Dx;Ydusc=`AKBWJo3#>!UaZ?6ml%09(HG*9sX4KO-rR7YT&sPV z6K1_xD*D7&vWjDU|7f&>;jxP!Zk-;`IW2$E*6)JJp+h$fk4CgnF+jKZU2SdR-@-%V zZl0@Kh}vceTli{f8kZcVjbWctlGK{BTL@u%O?yeRcMF>{`01#65zp9p+_83syVV=@ zp2UVUof_7>h)h0(y8#M^a5tlDM2^4k(0^loUbLk*fQNWrT5YItWOfBRRr3>PeF**1 zyOTD3sfxhmoO<|2f1?xBI-Jy__d}9@&ZoTjNP*9F+>O9gikvc=Z|}l--5E0TGhV)- zk)Xm!J>b1D-&Sq?c!FP$Z@va;S6ab;QO?CrPnlyE`SR_(z~3*3OoXme6R>(N`kJ=k z+C^3V+qD~)IQZTOHFtP=KXzM3OYC{8-JsWPpZo3dXgCt_ldyMW5PCRkjv1b9GP8d_ z>h<22Cr^q$ZsD1i(2A-WP#Yb_5sPUr3lJCX6sdbR!A?+@9~v_jg9KTs;%80EA}vt&5b~Ki*Wz=@JfTof>iXrhjWkNZ~0PaWj!}(e`S4d zrFUneTB_G@Z^mxrcUDL$LjELMdrfR;b&)Dle(8 z1Acaw(*zTtW;q}X#g~<`m?fz7WnVA|#1(&Jfh-7#m&9F;U%xTtJ`zF8`PoI zm3xZ~3zzpdcZW+$p+-0pVjI1`Q}k}D1!FbPU%kctS|8oo+PrYtb8D=Bw}@>?@qu!6 zqwx=@Bota2aToepOEEWx{yoxPAqC@~K>bcH)O{xEfqlrku`pV;2x|d^o({8t1Y1+IWVLYi&0)x40xV!@k@e z*POOd!=W~XHx}J3##A^X#aZ2yG2N^id z$0>;^ofGOcoywg*B)C3pbLf&m;G z0S{7Fk3e&ShO)^R`i^*D#sVI(9dg}usk}&>2}iUWF8yU zC(*l1XP<}pIMHET1`>%+lhPl(oAC45$~-UlT|^Gqn5hwRKK&OgIi>t)>(AT|hnePY zQ8j?isL?Pmsmb$Fsg^P`g~aQ%x1t?Of6KJK-#>e+!Zxi`lDL=*S-HY6sVRF#W^(%9Z-0 zieL6JzU)+lyYc`^RPv*$TS^avqZ}izP*ESIBC))zH%_2xU3`fYtp^_q_}uzb+ze?| zKGynl^y^z6z-?%Z^R2xN2p*F>CU~qf%*U9Sm5M?_;eq&Rg2X~&mruig#S;2AEPnri1^PRf z11uCz{$N3sjtBk?Olfb3Fb~r8yx`q8f*tEIKA9Fu4{TZ5$R2ymdW7kSwZa2|v!Om- zEa_|sZ^jZ_h6V3(Aoa$@QXf@iAER0cR%a^8j!Zj-bUkI2^@qzZeK=KWp_6im~b+~QTK+m z{bX!I!>tgR3LTv^=kbzqS0~x-U48GP0Q4vf=n*^6qXAD{W`A8pcFc>Auo!#pS6|WQ z7yWIx$8Jco8y{DI{-W>8uRK9tZ=I#~*F1K@pGXrZL*%3Ir@g3ry(e`3tNhyl)$#)M zTA@<`9ii0%9i`(W&p5#n2D}Q)=PD=;z4) zAt(O!1`VI`PeuQhjK^Qz@LaV)hMbRp>89K{qTT*MHf?}1yj&+6F8^$`Lt}NC ze=56fl4Qjv8O6@aW-17=dMB1RtHI4Lw-a5@xusTJb-U`W0vBP5PJERZ4iEfDxTTG;o#PutzG+OiZS5QyK)CH>g^!EM3o_hiy<<@je;SW?yQoyro!`b zd6Fs3h1N9UXX`cnsrj7aL&hhw>q1CI?V1FZ+%|-plD0IxwW&BXB0Y&Tm{=8DXOj%3 zNa393N#!hRSanKsnEJ+X>v@>02d%@i6FD*MT8?Egt#!qMm=wzgHt~s0DALnMZgSfU z9`2uCv|7rnvNOGN>V?sJ#0oC%1U+gG)?bfJ6j)X!YaFB2UNwQp{^!}Gqp zThQ3~WU0AP$?1~&HQSp8KL0R~i1%|iF*5bdh~SV3rHQ$rq}80GSNme+H#m`w;@Qt8 z&9p<-u51?Lo}rm`&L!1*4P98H{dJ++99`b_adY%)f+^xFAH$>*K!LsvU;jihn0yfVwB%CYn=Y#k7z1`vZe>3|q$x$~F*BE}~B?IcHjKREB|yK7F1@4~mW zCQqUfg`w}?ZrX(JI6=yv;Mn6*#5QIaeiU1-j7CYi3L$o8`QKbL;@z1FqDaBoCJ>1~ zeOCoRq+}KNB{s4WiNW<5oVtg*rR!VfU!BVmj7qn>f2yNh&nJ_Ij&K( z%*$NRim&-l!K_Pr#`AeYdGZ!NzGYsueO-ZGD16=eC* zra9x4Q-MHF(?_oU!kD3kshDcFrgtQ)vhivt{&GFG$C4){ZD-;W>tX5Gr7Np49oJLTg8Y(YrZ-~f94Jo2rnGClO{63}R5oXH6aHF1rHIv`qBnMzn`ZmVD%SASE8G*W zt>I7}TkJKb&O}C9b&F=lIiytih0EV`Me$jFCCaqwSPL0o8A*IdR=KiUY?nkZO8w+UHeokK?P}>tTtWf~=DA%7(`h;DqI~yqYC3hjvaSJ7zLV?v$A{ zhiq_vz|@~#1^U_!9SH2lb>3^Ar?Ty-MS+}|&gu7ft>)Eyv}h~ru?lI;m$cou>xRIq zb9`U^W`t&+>P{8z;U~!%tjxC#WyDPP-$U4HU5Z}qU|L5NV-hto3xmNo|3Oela?itl z^?Xoa#9Hb=ZNwH2g%+Rs+p9KKA;btZoGD}YNF>e4NyQF1GuBl`8cF}2tP>;c7jlEg zFa1ohl(W@xxZ0Vxo`L$J1k~NOn07&%h)SEXn*QctZA_T0G_cK$nqOnKp2{A0^wxDG z1aJgIvK!M*SYo|bD~RMa5Xo*Jl2=DjX?#!;ox?M^g(1c2+3PEGiGRbv#9z67X0X22 zxZy)Qg@>FBd|i%pS&4O7jdfikF{meNSf-Vj6HIneV2@RW)+JkfkCk|A8dm3$w#!;> zc+Et_Kt)FF?0}asrT%a#}V}HV)zWURy`4*Idnla%&kvn!}n$CTE^~dhkc>m=M zbN7i*74tMIYux3@_MUS(yZiKN`$H|2aHhch?Xk59YU&4v3Z(j>Dpz6eHc0EfTYsnw zOOC^A)m}B#$nxeRg{g^kXYAhCRVm?&Y)`9)n!CRTbKB3gS%fVpJXy{x4~(;~LNA*5 z{N8}}ccnl9sRbW--JG3LoO5g(YD?cFTJ8b##R=KLx08EIDTbP_RMnNrP;H>bgO^L8}| z(h{?$;+FSxC~C)&N$y?Rk(w5tOdyX8lLb)*I6)e>kr*^`JrKd2(C8Vjum9;k$cMK z@6bKxF128tP{)-T-GvFH%cGjhN7{zZEN7Dm(2V_f$UJM~jEVM!>fQzP*Kyd``l^RiSt^6SVg28y0WEoz(M4w~OT)cI8|u z8X@p@tc7;?TA_qRm&OINn~BTW`INUwu&>96qb?**Jdmm=!tDw zFw(pT$!J`YW1*;6wO$*8NnpP&W$7lbv*o$i8SoZ`pu;6HrFku zV()7D6U3rQk)}w#>z{Qfxm3rNky0Ds&7U#~Wni|*ka0~I9`$j^uI2WTyGhf3O3sOE^!pc$`k6^Y|ybtMK@trwC8Q%1ziw#BjDT@G>V6kG*eH&@=6SG2Is7T8%bB)9)jR0XeDk+l4&10fQRyj$omNRohWY& z(MMZa^Jfgcf&lvVw*Xpi`-VjyHT{Nl7=jb9nNn)7;B6oeJpxhiiQK*)SaCXM-&GfB zDes#}Jv|z0H3XVu)c9yB-f1{$o($awxQHTbV$ z(0lDb3?eby2VzjH^>;DgYmA#c5CdoTEFWoD)JP6`apTj+;tn7N3+^C?~6C=2P3HDT{mb)a?d|2r26>BK5Q<3t%;A*TNJRxz7! zB7Caj6e0{^4l49zu52NlcxhN2zCM7u8EbxXeuXPvNOxZT(68iqz0Ol)=h^xf(J=YZ{iWv-%zt&ZUOA6T@zH_PLA zxYzWvjO@oSRjnjzBsp@-4k9PH&d`23)Ma6BGb`lymR3J&6XU3+Sbh`5gr=c~oo{Z- z58rqQ9h(h{{sOchq32gj&I0Mh@hT;gQT~oXUIUy&m#*mzV>Km~imCLDTY@^nJT$+F zZ*!*JMrhUAiRrKP2}SA54M{}vZZbNv%5CBoiqgA!$@3bQwdJLDlyX!-zurx=>Z#nu zxsGe2f#8O?X>JpeQKq)hSS}MzHFvrJ+Wgqm1+G{Ou81W4^hJ`u8Clse#gROVZxkh)-YMxhGA)-M>VO)hrQb6WYiW3|pWf>xbh z`!wwfM4fEJ_)Qyx?Q~*uG88=UqTVhj^dm%KygylYa&Sah|ILI;v8#E zZI^dC&U5LgVqsj4$>d0nqQr=FdyZ`aR@?k?rZzZpPxC0{HnL*1MVLfz%eV`msnzV& z11TP`szdGXtV%x4#a|qV;{1zM#Y!knAkbJ6*O@pSAZZySY^U0EM@ga9QhIZ4qL$nh zg8(Z~y6_wxf{LcKSIru1M#zP;EMCE3CihaRvEWn1|D&^M$haW?2M{X)@d_MpQp1 z7&v4-Co1PYV$6_Pge&EiC=XyVvJ8w7&OBUVUJHgrdzg&6o2i33*3&fbT*9!@GWfl3 z+dcIakp(LXH;Qt#uGBi?^~>7+Z3?9c6d>d|%*G3RR44twJWqMB_-0)L?vdrQofG61hvD zZp@JpiMnZLT$d3E+63Qn-)Sh(a-Pj=Vh;N$e;0%xggfLkhn?ovJ(RG;;(F%M+^KtZK0h1k zlGf|J@($U|ppTo**3!OQy25j)L$~-{)Lvkbehc?xyB^q6ipSuWwtelj0p)Lu* zM94eDWH!Qc2$+W_eN(e++l%%P*Pd3q$E}B;%s4oEIp`kxxJg7GmEd`)vV=Xw0u>(d zJ9(!vf0N|7Ps;VE4#ijIyEYi>Rt`qc-j~D}uxXi>+!rlv&^;OGmr8%8z;D2SZSv#K zQ#F?(oO1nXUnB0-mKy{*E!g4m>G|~77O{zs-kdv@I{&!*zUlFNI)~QM$A zpf0+9&qJ2y*yB*$lXimhr(W43C^KdIZb*yef{yr`up5>n@Hlm_RwR>oj z{?uRnSGL(kmxYh-43fb zUH1I&<11Cu&Bs#5gP&Z{Igg^@{C!|eCKvP9_koy4LkGLV1lvnr!Qk8ID2mg+&)*-z}N`#^gT4>3*OX0Oc!4QcinlI zdWc*^o#{At32M0qo>aODhqK82(ya7DS`H^#vOXTtTB@nu8$R+7JgVbD(y;2LYXb732}~3KX^XfX*LfbB}-3XVrJ+Yw3NU^NcrcyaR>o zlVq81>7Ynr%mPKytI3X2`C)Gr-8D58_JtoPU8l7Sd-e2N`mooXbNuhL`liQB|AO2! zRH;PcBXusIf#f|so2Rg+cTsgX=-5>Vq^}UX$`**^i`C}{iqaM2Qq~1fl8irPz z#%?`_asy8vfTpKE03BU?02*V_-9UN+;^OfY@N&HeYSnw>GkCbZ3X^QU2Oh2`hDmQg zt$OC77X2SHmxB)Qfte4id`V#|fo$b_>E#a{PB1EvTd$Di6+}hrLS%&3g%e-V<(hc=$hd{+7b1;PQIQjnPW1br~?@Y>TJ9uVul^BIw}*X8g*Y z*LeMi_0{b+cNSaj6}|ih%dh<)!peTQyYt17+v|^x+y>{As?=lNvkpfb(;T1+=L%}g zDHu7Elh4AD-0xnVcXkDl%%1G?)AdNICQs|VQ>4gTDTRCKXWm*gzFO-{POq znjLZEasO9)7Wyx9Cjt(5e)UWfE;94&s!F5*63P3Z#pkD}B&d!}!`;|Hbv&uqgu7^Y z4=$F^&7cA|w6g%+>*Y_`?q?-=)G)oXv+^#(*A!bYIZVFldUrct_RZulksImG+QH-j z++db2dESG$_Ok)f76Kk^1!ImWFy?S$0>hsUT^TUum;z&t_6S|ld-B9biv$`GQ}42J z!1MjzLx#^+EjU42vNZyH_pgypOd_b$doJjbV(d*V=aA(SZA2|4S8d7ZK@nB!JLGntsV8(Aq9^~6gqJ)!A-Tw6k z|NN()?z$RZd(*mQD=Y&$mnh$ovF+jN+W_S%F-XI+!ljC>Mkz*CB6g&$N3rCYR4|(C zGZl436TzNPb?-uwglaDveU*7oQ9$CM>D>9nJ9Br zU|c$hrY%BY)cPjBWTA{_74(Y5?FsubE$8qzkG!K-C(C{-eP9ZWx} zK7#4Tbo5owbXkq;-KH+A+%yG~x&Lhl(^_-(cBbVO0e)4Eu0+Zg4u2cMybo#&1h2)` zh{nLc5BsA7gPM?EqKvVjm&26*SltTMZ0ntC0{NmetIUj?WGJA)@BTs$B|wdE7bA~` ztOas`xA%CiS(Q;Pnsv{kYY+E9Pz|+6f2apec*LA!&`Ux%?tBTQ7Os z;Yh#2hM{8phe6q(sT~C)@lF^Oh8#|fCqQ?w^#hx*8eANIL=TeD)y>}nt`XLYKP*{j z^M2FR&8&L}9gT1UWq%qric06pNw@nydQ)Uqgc;zg9kHbclhYNQehx|J?$84W6!UDD zN|t|uzzjN+0750G*;iE*27to+1p&gpPL#Qza{yskhYVp9M~3jN_kSQ%Y6A%TxX}pr zK;xPBXvW{tGx$t0M?dM1Im*F99waLz5ZEx*{{$l18Vn3q&x|56ve_jsIO0G)S+#-u zg2_XlWX`rbQMppdoZ;5AKvsCWxM4Agdig?w8JI*cE}TS;A);=+PJC$XWYxw*RZr~E zv<^OifKw+!K%^Z^p3)us@NyLYlD7Y%Y59)cKGf%#|3-4YSYHV5{*bp>ts@u*Iex&H#PrQ zLdlIaqjQqMIyjFa6H64&z~VzEk&-thADJAMOp#2-UJjOTX*-V!evO3mhm%#h&5q=C zf-!QMrPM~7-PXTmlLw>8EFtc{jV7xtk<{%UKs$2-Xz6M^b@y&!33=n96AY7EFQ9@$ z_z-C|o0aQ#QMk5)SQW~df18M~J`jum!H~kvNvr>mF6ci8$eoR6ZyUN}xJFjLPrukM zqn_$+B`2JNr4KOGMx@<7a#+&8Q{g)p@23JkkxUKU%y4a>o?iWK70j*nHKKyVM9EXO z{&&-W#S=stIqw0gfW?yxg%MzxkUv=u`mbrvI(U{WTnI3XbDVqE$^=>k|62PvPVno@ zGTbGj$P(Rw&+kgUAv0HqAv#eHQ04Pk$vcR&fD6*_T%q$iZxew%Ml`IQ0DuG8u+{?m z78TZ?etkgT>abc!X2`s-tqsg1dpgBn!5)6_5$Q$$?SMu9*;}xFD?_wnVK~dkk!zK(~$zJ4A00v3{^m!q*vhAbj^M&dTCpN#Dr44&s?l1gF9%QGvgOXL=g-1BY znDdbV2Vn=ml8 zu2SZMfv5T}FrwvtbPSf#Gx;-Bm??-8jlu(B_`-3*IrFEI+z5~*9uWx7CW_WOrll?Y z?@J$!*Ff_o=~W+K=~v79c3|1zL=sqbK!at6O?J0t7cAzF5gf@zfRO9x5QF_&FsXj2yS;s^1y$v9&v!B2 z4QvBHOjs}TSM3&7-WmJrJvz9%ST|l^@42(NR@#vJYw*V)MmItHxu-N@_sRId=5K7z zmrdIMzt?3M87I5>Y#+rGFxbA_qUEbO*4iT?AS7!0nd(Gtf!K40c9Zs1#%E=9kl}ut zz0H0+kzJ!zYC=X(4EIUv!lA;!*6HwZ%3wz>m*CbLHPM~h#WyM4J}p%>pV+-QMe|dL z+B`{AWDvcz_&ZK2saNG`042{>pkCmqwU6kLe)Zgk z*t9ZPyiSUa3qDI&|m`1qQ;yP_WMPx1}2BKelQJ59h9oEU+J8L?OBT zTfEQUfiA*8t8o+TI<-DquWIrau+*{%=AIh~-ccz!XZ;u0 zlh3SmTz$Y2gk4}SKI1GNTZ_d2FmK?v<5@btd5nVKTtgD|;vHnZLI2y9k+{|Y;m+a@ z2J5bi7tl;FAWowkHcg*+IXPrQT7xy}?da^Q(~ zkOQyo5DCQx%Xq!Oa2itoKMe98_BgE$3Mll6`yB^M0c^lw|6U3hint*J3aFuolj?zY zK6BEg(p?UM^U5SFXau%^@@cd9euq-b*t8~^eX0AZj3nQiEKWX|gpka|?0!&kf5GY; z)yj?9ybCFEOmpd^BB+DlSmyw^_2pkgH&gVNsw3$8?tXA7ChDX#j^8OaVlW)kO_6OT zFO@XK(Cg1G?=}K(Aavh>#i%TPs2JL^|Vs`{O+$7gGYp1~eN z?1lX+i^!;~sGCQU9{RhX)KkyaPmm@Qc_4LAZKF{fC}-Wxjsn(f9qT17Av9Jm!0q;b z*_Qa%vP1w1RNF96ZKI!zC4y>u6I9zk7sn5DF@}Z<#rWz_l1u#@?trnKsRxXe#gQ!{3oH`&j}{3878$wInhI*%O%*G3P~#4P z8aISo<0i@E>F4hOdjull55o%S@S8)vE_t$mDLab;P>1BguYQy|&!exk65zKZinF|y zRu}W}S>Wjb!_(o*dC(|6)c!jJ5g%^lz1>!;@7Sr4Hvq z{E3*81Z<#C(x-d)c9yidb!^}^sB&v zE?*9)D1%zm?77`;v8XK(HwU$#!>wKeoBF{z%OB#kw1T)HU+vVpm%l&UI1`zgDF0Qx zg(4zymFaz?>%G|2n7fHO1|P#=@mP*)+luLN(mS1w4_Wektt6}ro>AsQB|-|{m{jqs zA|JD>E>o&?J<5YsLax8Z);{oa5xx;rmd&lxA_0E6@ zZeL8G)>3%7O`zx$ic4*pe{Fqx>gn4eH^^g+K9VFrtiZ|Ta`A{;eI#b5-&W{QP3|syw4mC*RMPdIfS}L{;>H{&`M*if6co5g3j9_KBmlE z2lstXqOLrE#Q*yM(k0Ke=txqpLT($XscDyxae=Z4aam4(0y=Zp0w=GcKT~_-v^y2o zX~~loyD{jdW!o(a=A8mS4T20;cK&2Zqt^rWpOy*5OeUm7Xt-kEEYYoRHgF&2dyfo4+r98)>U9W5h?R-k&i*lwwiS z(1Gly3-*A^G*LnbRsFI{2!{)s1QR-HRL&k+b8~Fw^$q4pBCWC-N@HTBSl8VWmXVeSD-?5 zm&%_W1Jzm~Ce|D-@Fk zguU&kbH|E>qEl^@(T6Rzw3G+JgI9JFXw)$`j=H%(E;UaH(oN?bK8sz2{)TNj_W)ZJ zz-9ulMUqavB6A0E_2Dju#Ts1~syMdD(camG(fU|GaBAMqbUU({^azO1n4(T!b-HyX z4LY}TP20D&BFEkyw*UUC1m}6)3vct>dJpi~`tS5n)Gw;8BGU(wxp(D{+pJDD0|q6S zIo#;&R1GcC@zEAzzj4|^PnYj@UX5#J9^H8r--t+((raKQ>*rtO7LGBS964!h(r(nm z_j7FFtH_B?Uk~%4|HW_lyeB6V2TEUkOt$B%z^FE!?jaM1qY5H3XzgQof?@dg&wUcE zYTxzQEc`o?r3OM=K+$Jdm#EnSse@XL98zS^_fMFy0+pKJmVGpMbQtoimy zs%8L8=(SfHpmp?A!L2-FLQ_J|zeDW5N0{T``|s%2ena<4sx~4R@+>}F+V!1bGbWS> zlD+2jm)H8YcNJu;yI135KHP6QFZ%^Jj8CF&_+bekHlj12oZI&+f-ayu-$2I5YpD`L z5_s_LEGJj)ppV9`3rG53k}ZsSr!J&C79z8Ii^+ffwkL}cnN_ZreYfgAi#>qu>Cez; zc5dHn`eOW`=|1&+eW~k7MZf2648%m(pLtE6zKXNxD)QG&|4%mQ`megk$>=ZVM-H%f z2m}sd+THz^+J6n>XDXm<>uV_glJH%-r#c1Rq>CLz@N1UJi}Nawrvo5W$>MIXETihdr|r29Im z@w~XMr@$)l>zwZO@B#~EYsIGZt_L46wkZAw-I*uEEWENiM|`Sp-MB{cP-pPKmu-j= zL4PiTYmQw-&v-FKE4M7G^X4+;^>cS~m=XCFb@C9!4E!W+dGdy}q}hRd|Fl-n zpOn5a(=e(j-0CT2u6E-RvRcWy8*elGiPuPzjN>c)zi~)hOXVec(z+}LOG6<3Z_nul zH$qt6HqReq%??`6y)XZ;6IBgXs%-+-XAoA^;<(*dGM(@yWW^?X3Dv}nREci&bO!O> zDfZyMlIPVrf$`b>ZiO9f1VKZ1X&aNDU3SsJVEFV60v4fx@lS0c3lXw9Kq8gb6N*q~ z)L#!i>=~`RpjSXWamlO1&TWuEZ%%hCY_t9lsyg4G*u-n;_b1>ORdW3I6p&>SAhHs& zh!V_H1}Oh`x$eHVGZrM4Vw1khjkDm2b0sKub&#cc={Q-cxd<}q&{*?8ckq zf_T$-J;#(6fTkaa&<+Gf zBtoA;)jKudQDr&qoZrw~T-*zvACD8bysdQixmnfjUhn==ZNlD^T{(J){fgAxq0`i& zt=U$qR4ivkhvf>rx-NI@4cmoLTk*ZFpHVN=RKDVjXcc8q<7X*OF5D($c+m-hgrZE5 zu`zxAb$#>p`wXvVKBiNqlEWEZYmbyEpr6(sonEp&o*HTx6<|3copxvZ@zgm=CS~jH zj0bY9KRXOjQ?2Js-a8Fx@+sCvdIED{&Z@NP^|iGhuAa@}F&^bK`dywjKqJ7?Q$EGV zl9ycQsKCnt{tKEDgWl#$9DGB{o*#D5TQRy^T|QIpSvx%P;m4!ePCEIblB@=(-8xXk zV5!HfP3dEaRmgzB(fEpYh6W$g+S~1(*rq@&arp(NwvTpG@yGWSpBow+YnzmS85(2_ z$m~6~ZM!=1iPaf3fq#QpQuB?lKFv3R+jF!{v8W_jt@Yf`X0GrKD*XVnvHbCS@X2)PHM62Ky@drOJvF7rJrsB%L*z^Z7UwLzn^q>stVY4 zm+FB&NwE+@k_)n(GKv2;R1vBmB#)n*iOQoMjZgl+6?;%Lu_mWeUSQvh6MsGKX}`ZR zEkMN3#pOEiVt9Y&v+UYzuj28To zN&ufS_;>^hn9n1X>6#dzW5%8lajre>QorCS6iC9hEHZH63jqa@xYfO*xvkflfQ4@@S8~T77`hXkefg8$z8~T77Ci3r9 zEd+^uGYUsn7h`@HF>ZMRH}sL+PyyUvc+cX zCVWCPO%g3iMRDz2I`pzJp%d-Vc0=QRFTt`L@0V_r?RHPj5A9wVqhk%e=>iL9?s|x^ zKH7FfD{O!HBsX>1eQ5Q#nIo~wDsbki%nCdI&Taod$`@#NsAqqB{i)>q@aE>`USNJP zM#W@z?Hu>>xL87ZLFS1U+ov)Sp_lRlAIe=-Fxeicd1lreQ2aPUF}?~VW49e^UO33m z+z`KNQ8AS%V8HN8C3UPe`pM6n)eO(<_%!PF=(WIh`u)NeDkjo`ZcoxyGu$t1eOM)F z*rZmfsHF=S*+OQpL~w(?uVshBtMaulm68THH4{|BcVYFXX4W2h+m6lW(gkK{umUr+ z?ew!kDkiO7=>k&Mr96%w=ZwGA05`EX@3k7mKiO(R?XZnP@<&x6n9j7*C!zdL>pV>j zl8LO+tD(FFYVn&Mg|9CNU6t|(e|-TsAfrH~#{Z5pG)j#2=zsqQa^e3#Zu<*z?W)j^ zh&1D@3x+$$+}o$u?!PcGAx8VA1~shj7e0r5DqV=E+ry z(=V8D{8)i!td?9_%X*bm$|lLa>>e)y?|QtrgsJ+X?mNX(d}Zo%gEvuED*-_pkNBdf%hIHm#x@by%=qihn_luh#9`o>UDQ(rdVR{`e+zmr%2jc?}j z4v|&dQFqTyPp*zxzku|7jFe2qqX~>2Z>uVeFjbqOEiJ22GUnBA_`kAh zS7{Mpt8dJ|O!07q9~qBNFUXS#aLvsuQ1Xw&RA_8Ze}$sc1*$rjMDm{d%?9y$6rSfY zW6coIxGJ01So=WZs>Qtd;^KP|mCeQ0E(I}#^vkTU-reL2zT*u9u_9oc3SN(;!K9=q z9{+mJr1n+k{NqX{EywdS3)K1mGAUX7UTLgiQnLL0*FCI&f!ny1vzW)b2tnnP z_3y*BdfU(uN%kp%!RQpB_x&nuh`5SL%5g;#(d+S5Z+q^THY;v7p<4V(QQJ8kiO4dZ zi~=>Z;`XpI&Y?D-sIj@RojzCc+PM1mRlMcbfOG*3_b2n_VO4Im-ctnnBmkF4&n-o~ z`@$->yd}kA`|(aiRSx^|4TC!o1i0^}tB7Jw67=|R_kvdJ7nNJl-xGKDNZHU;fgLTb z?{xRxbp>*L*SROgJbCenax$43H=o5m;p(`j4{ZAgP~#1t#v4G5FMt|cyv0|z&NO&y z>S-K34yf@+pX%b0j_RW*rW<@N85cYK1r#5lvxWHe9L{w!>Yp+fdieFO(xdbf0gzt! zMLAURcaJj~diF6l-)vpILE-OoiqMpN@oY=43)S}&3$E{bt6T8}^gKyllw^e~2j8Q+ zZPB*I`+>JJT3J;Q>%4EAn`|1D;o7G@I17)jnVtIZM))j+_?vE}OY*q{uJ4IiT>lSe zZygm!x2=0eAP_=u_dp=H2iIW1T^pAKX)FYXRB(d3ySqc<5`w!s1P>k{K!5Pf^r-)QABF~)n_l)dB6_zzR z-yYc>HAgANS?qmORh)c_-%W25B2gyvc0Xn@VrH@k=be?!;2zM0^Dfv1gc+q;og0K% zH9=5amA0wU1Fw-{Nyv?@=b}ii%r`!0UQ#-{Maf61xNji{sS&==Ry(eWcERM|$G#DccRCY%%)H zrHiC9yj9i8{Vj*QCK8~!%vy3u}IcRlfKeZ^XMGP z(3M~tM1B3OVzpQ?k0T4{c#G-a%zQf|%45~=HWBw#C7|nITNl6cYcTqXvt?yR@^YMR zpGs}DqMRae^*zV}>J&i#=nN@KuXC3=>nqC)G=Wh;OhSaoSge8P|a%^4gRdgc?Uf4L<DnLs6 z`dK3BD}4XBAR7k{@{Nu$@M&Jf`-OTUsX7JAgCmMP8hAzO<6tm?6p|12Q;&+ zdyL*dS|^j-OI&;h#U&vc0&hyeI?G`K&p`RLhPsPti%hD92{)W)Hpl!~kW_(_e_g2# z61V!Ep<^xD@SencqYhH1S6*qcBdd;HUMcUhN<2%_l4bufyk8Nc(~ymtGp>-j)dI13 ze>~qh9vZoYoau)N4sRAproCK%;^hSmOVXOfSo4K1ESXFOmP3LXdm>JfU>tiQgFe~) z;Y|4BaZ`K*m`3waI!F%TRP%9`q$E(48pK*OHGZ*$IL^DgoXg_qt@N4T8prWJt0EKA z(x;&F)Vvm6C`Yuo-L)pL7Daz*-6Ej?0nyX@9OEQ3~}(ygExkWsNW5ZlO!=>^t# z|7g}Rk8%7rZ$45PPZ$l8u;!m{Q+rmoqPEwvb!Y_H;ApJyMd zPLQgh&U#--32wI=!XH|@cly>KW^Mau2Gx}xpjtz&7L&)f%M{Yx^;yQJcN_v9%R}-< zNa1+);?H;sIm1E72=J|2rpzye8Pz&b+>89=; z!z)%*5Dh7*PT>r6@4Qk>zf#1h^DN4pV#s|7^B2+Fhp$OU}PHrI?o=p zOo2dplVQ!f1*g=3kZ_SWzFipg9>weNwMa(()t-Vq|L&3Cu|}@7M8?bq&@f)L`qqK7 z3F|}=MR=jojAEY#)@`WI8B3VU>c%6u8iKydvo)XH@mgK0QGcGrW(^=H_YR$8q@pg zjf3(i)wHxY7*~z$v)hDDzhemOH?ngf@u@a&TMy#)KUm8pvw%B>{S9@4Em* zCG3BWZfrm_W}h1VUPny>iAjKhXFheqgek~zkq|8My`D37B7{jot8phylVL{nh=MQc z&+vF{TAp`W^Xy{4G7&qN!k(^kDMx#O-E(Ntbgk6Q8KN9ryBKQ+dTIygsn3P-Xrfai zSK|u%z6rR*{ha;q!X_~ZD(-6!$WEGqp1K$}X^NDBW8;-1SIbdvUD$`0OS6!YwBM}% ztyDGoInooDf&y2PUU#YT0u+&VZp)g$2DDV07Kt#>Qtd!X{RUd99cZcb@*AcgwKg2Q zi7v%!b(F8H8W>hVNA(6f3=vH3JvBd7CsTCv7gt{h^u@)cKy5v5mFjqT=UiI?A+KH$qoLZQra?KILLgMIITW|5p#|1O5Zgt! zU=rA}|0;-WAc*aE5L^4?AAKOUi|^dnk2SiiB^0MWXnqB;MSy|W+9Zz3I7#|L@?K$| zA_FjSMH&qRaLaYU)(&Ee0Ry3aAiK&n9nHifIJfM!HoXJVDzV5XIA>>Qw})VsJ!iH^ z)H0-j5n~OW73^`}!5&wC#)S$4d)%Tw9s-PqCS*Ze>B&~gcP{LhFEDx=2Jb4+P;Ed% zg%e>v5TgMa>LR;nVgevlPwmZKNeOPNKu5I!9km|OyXvtP3al~%YVoxHd>R|3pyZ^_ zvNrv+-~X}S!e%PJBR^aU%ta`o#DA0m$LwATiF+xsX#Z6TWg55?fNBg}i!54f25)ei zd`<8jG>|~Z&+eZ47_y)ibbrO5d>;cH7=sT4*gvP6uMdG_*UzCu{YM?%_TTFe^_LDR z|Ej~Zj1vF~K|==$0TWlb*FojKbx^t2AudL6IrdoZl1bcs?+fG=9e+8#{oYHnPOpwq zVdrZ#Yu)bBNH7!f|1lGse`P}cuT0SWcP0QhmC$=CC;rL=-F+tL{*j3cI{weOcEncw zWQN7-PPT&fdz@yVP1vO7L3u{&TN)f-_dpDRK*at>Ak_W>BK97LtiOQ({w8AbFCvr^ z6F?xc?t#eq8wl}w!SBD^z_03@cgcI^p?jAyDbFomeLGnC(hs`mBHTsc$>4VespvXb zD(F8%R41%>Q7<8AxA-U+2iETYor}!TcVU*Y+ZqG=+d;K;3H`vdw2>Izv6(3Fxk#=V z*B;a&Q+JG)lJrJ-{^{k=qL_Y%RQ>Z-pP;a>T4az1CR_vvQN+8yC$L~(h!&GYJf9RNOE zXRq9BvH-tN4erkKS?+$rSlX_378F}=XWD>Mev8Jt11~W_7yV>{4CX&a~otfAz@)-*z!b`zOv%K&r znwR1;HzTJNf57??SHf5VLA_6 zx&5=y(-i30TE7%(e5xPu@-eYfIhxzs!>JaDPvwW!vn_5syFc{>YbY*ud1yS!)80l^ zJB~X8i7&OA)sLnaqBi21##`K8wQlIAvec$>e<)9ri8}ae0kB-mAzcOhx?n$d?oeuP z;ZxN|&mUpg>D=c2slU`0E*$SZ96!%@P3*rp*1Pw9OTUF$T0i#X<>AY|?X$I(#^{&m zNL%_#U$`VWZp}At)=38lV3L)tEN`QZ{*x_5p>7F$!eRQ3wrPJ6wK>tu@+Bqr@x!%=*Ng#i3lyZFBf0Ssj0AKfBq1Bu_oW%P%gESd@&hXL|K4-|DZN`7u=lnnBalpS! z=uX9Yn)guoa!xh98aykDT2= zypB(JU#Te#`(hQoUJ?AlTfJFP6((jklk3>#;yN-c7hjLePQ@7}qMkQTxLBuVwoqII ztvtF0`^iDG{?}3m3TM~|8kxj=>)pmd6D)vn|9m*LiF617MoF@e>j3b`rI#122w#(U z(7>+B`7k&LnTC4Ki!Qa6FBctjSrq(71Qn6qu`d?ZV+N$5+EKdKxF=F1hJcUcP4h*z zz=W`lPlk7%kL-2z*|~MDw#)hRSFr9ww^fm;Z4<;+z8(9Lc5xYYTP@u`r1$Qi;$7I4@j%SdmF{4!TEJA>8Q>a zHax7+s}n=oEx)OkJ|kUr!cQ!E+j2$$zz0F9%3F>P|A!E5(iG}^(X?Zp*9tzM8tZ=Z z-e7U^J>SJLBz*3C+5uo+4DSW|nQ1+FWWeK_AuYW|LikVsZz=w>A*J-hKJy!F51@3Q zw%I}WIAta{diB#9A=;p6{YMUX{`}A-!Sva$`nd1mIof)D;(%J{W^UO(gCwKweeYZq zv5mgCO+Mb2QuL3e06x`EL}RXG9gecZ11pe`K08NLED;U6n(+KHCMoJW~5&0={$&0VwgNX zEU$j&j+AAp*)Lmz75LEqXt1NFIzM~27kszAWIQJtm5j(URoNE0o$~Zziu`Y`Wme0C z0yvK3DQSgL(0Av2F$yb%s$=G|8CLwLu$*O)m4%>j=Ig5vrfNRv?+tbOm8YO3;O z5RIID;ZCB`Ecj}Di=5B7nEZ(I=`Zm34(&h9^e^j~%Pjh+F4{PIQiSYcR>r0N%Ey%X zg4MMrNjxw^dL`6Nh`(We{Pw3D3;X&hF*P;#YJE;2ad!R@4=bQQFC>^@XZlVrfyV^z z{DW4zvl?*H5V=;asd0iPEBrKB*QoQTs!L&-`X*Up;H7KX2}PR1IE8y5jp%JcD}r{) ztKc1WgB<0v@ZtBh-*CxvF`vmx7uRcTVw#=K5oD}jp&g3JH}ABGt>ce6ik-$py~wmO zsT12{pqD~+9Q7iodc&iCZf9da9iDI^oIR|Rjobtjd6cjO6|+s*#!Zg?)Y}FUI=Lf~ zr`PfNzoIUo+0*S#V5PLDWVs|z{`1@P2UD%WNqS=Q+E^;?UW`3KMIq1`EP+JhJ&jnB z*U}0x4g6KMjV-FQr1F?ZMNFmDu=37RQG9tVg(sd{OYh*)P&F3w6}wHMqJ$&R9lhdl zb$NAly16i7o9=mf+_};et~hd4eK=8Wy8>k0xm5}8-HzF=w7Q?H3$v69w={jayWE+} z7KRR|d7d(xd8VBR2`)f~`DA{J2i%?Sk8vB^9n5hXv?W(HCsaX4TGPUG<)oYjA_tCp zD-@+#^DG%135j;2PPXP*)OP?0^<9$3BlgPMvp-4V9m5XvIWH}TsUTuY2p7=)>tE31 zCbc>fg@M%DORCL=zProQh42~SG)MAs+qATnSpir3+dz~CkP&w$r^|zj_iey+dfV+W zZ|x77=QyO8hz1qjr-kTQm+=2N=0mR9(cIjTjqUQCi|0gWZ2jy8(3sM4d4A2k(&llw zyL)!`hrBI&W8q@vUD%QOlujDg8+E$l_M8Y!tH-}x2ERZFe*4{y1C4=A+vWOtH$Sh2(%Wvr zy5Gw68=owF`i^}!)P#OyYXi8QuEIvzZqFO8N1WS^sh(4NHs0#uReypO4zbMG3Rm^x zAQAOn{#ngW|J1SP) zF|dYlZ=%*;0egGJN6h8SZ6C=>IBJqux@cEg`Juq4cpLwQY1q-`&aKwQ@5}S8)8qwo z+fOZ?cRODEF9zr;@P0Cr=l$U4eVR_br=7R%?3iSHQnKAkr3vfYIo%-=-2Bt`EA24r zR`5|0vA#*rv13&w=7$qpy_B{<1Zy56@;nv}M9wZ!UZB%^=vt`x!jkP=PeahhU3iKz zi$5RFWQ8hKqnK(e9ENrFWVWs2(A7vWzS=@yRlM!WpDWI9smEL(8=?uZZRZhA&o`|?zyWXJ1Kh3*aYog@WT+=cy)G$xpoolTq3#qJG^p_o=4```L zsbYTSZ-H4yrV$_KHW|zp#KM&S%hjUc-L~ui??Q78=ZPN9(6_ia$2J7nffLl>aTPjz zeI1QZ)%ZBaktErHWgQ*7r`_Wp^tkifwQgT~-vAXN1K%=rb@I^r$E%K1zBbm7GzN5e z>3%Gts;FTs-e+QRXvLo%kBa?(E-Sl11T=V_M14XZ6gGIi{<^GOAU|@Z^~cBrny%|3 zYCi_W9IoDeY+9thkD9|KY~O(y!Q9m!}{ehr``8BFp#XtmUFWyZ$Rbp?j4 zud<@QGmK;__>>6Txet;%ZWb<6Wi+gsR<(*Mv;_`rhiIg2I%a%=;cPxEzMv}aaM{$p zz4f>@`mB-0-fiHj@g7+-js20fEBN@$rbUfT3o+Vozk|7!Yonl^!tk;0VShE!kqKuS z7#Rx~=Nh6v!$|aV+_sj$MB7j#K-gx9+n@VhuiYi1!mnc!qx!CgL>g&yN6jZVfVwAJ zz9@qtrbmbOY5!@ZmMbVw>?(e_6V(4 z#PkY`e^JL|Yz;LI<&dPFh7*@5U-B#Y(bY%Qetv8#hBWG=2@2yc-=E{EuSy1&8}*U&aY*XB+C!l=)qT<>HLg_ggGyqYC8rfAtQ34A zsJ&UVeg-lgFK(Nq=1SrzAt7o*o@q;XdzHjWePN)Ez%xCNG0jCssjAbH(Tc3yBf~@b zFh)_;Pw(E_e<^2LsdD&GyS=`lcb?t!fWowofLwcu@QrC7GJ-aHw^ZDi<(WR4;9?#i z6j@~@61On1S!ySc8C=2?$VjA!pzUH$QT6kYm}x4sfT!x)AgtSm92QYq9r=2g09RWU zH!RJct7@1yBKBmscmA2_kOfAS_)o-VWRcWlIt~9w?)!hut><64EraLw{J(Mw{9AJQ z{YwP@_vD@r(_5{4W`yMrKvrGe;A`_^Xmh3^SN&WQFausg(scBX&}DxFyoe7u?t_PHmcqZmXG;+eqCjddkSSaC_$@P$qOUH9LIa4x2RI51 zf1}XrXcG-jZ^M0hNk6=nekUn7_~Q*`_<75ZZSg=|$}4ZF@C_{BvQg~>da)MpjUk7~ zTQ`2?Hp7znx4j>PPOKy6Pv!?*0f4zMRtVWL_f6wR55MX4!x#Ll8Z5K^FDWbOwV~QAKw~w_PFhAqTiN!MRlwnvgi^amolzCbyZN{zDA|~J@az=ol zKH0N*V=Iu}SE!3q=i~o`{i~X)#e>|Weuo#1{mN@0Sf@)w&ps_0PnskvubTqOgtcm` zKL~%Y7D)(AhYy$c&8YK^ZmA)wv>>->p%^e(wfr`j$&HfA#8C=QQrQjDPO`c6pNq-N ziD}fUV-Y>~yj623I{NTt)!0p3O)hdEvyz#uDB^jw!vLe&YnymMJoWYn*MhZcy(=l? z;vxckjWa?@9d*nHWkm$>n&5Z4rxp+$gIZq2VofB{va(X-T6ESjWR(wGuYQz4*ZGl_ z&zbX}mMEyRVoJ#nyv-99hvA)JLiuDM3*S*_j|o$QQ&&qg&TX+HWw6x(_cV*7c=Bvsu~s129nTIB#sl^R=fx46id|Qyl&^GGY?PEJ z!S}f$F!+V6;;$>Ue+3Uc8`Oyro+_@8kH<#wjf4e~6YXJ9q0ZI5h7G>aT2CuA!F+<6 z7{J>4A}_p!pzxB!NN!z;szgYv2Bnztfv-B-eZ+;Y_@KPEy`!I`#xJO=zZSq=eS=JzYCE@Q@`>CbOrbY9WMD&Smy_Vl) zP)HpYAF@@Y>91Ux?D(`0YFx1dPP3msF^$G!GdGkmrfmi?2=i>#*Lu!`onw=O0Hq7N zGr8DE;VA%l!HG9hgrJZ8cV=Z6+t&y^U635#*N3Zoct$;e>?*1}VaCe-c674IXQ$y&vGxQ^u$3(gdgJz0QK!6Gw zafnJC?p@*J{$%KrBLrW#jH+bO^p8(te)0R=kUxczvt4o>p%~648io@-%WzN zdr@MqI8%wtFPRdV^c52?n4^XO-w0&g7i9e_$i0z9v7@i+RtTB;dtc9?!yqqyD*Pvu zsDR!3ntMJbUpr<5RDghsBxH|d1Q8*x3o>?(-9i$wM>8B67>52rBzr8LEL1;;^B$4h z4iJ&&Q!HPSb(?8<`Ue`RBeYl0cbg?lS*9AL$z)6E5g8d& zyBknU^!jq(~zda!*B;TF&9AG*w)N$+wx zEAYxC4T4^8oO-jwsf8Ggmv(f%@>dt8wsZ>(GCKJ5Jn42fj^z`e`(CTz`6ZHLo94&{ z(WUB8g&0V*f26(-NHhTl>fA9%w6WIur*acQrw|>g*M1y~8dm0P%$>U&;;10Y{vgYp zVD+J%E)ogS&mdnXEnPoql4M3TB`};ZXFxL{Xk4+{6$v-WCt>Pfm8uZMeNE8qt`(9! z#41%Kx($3FoaUq=^{)-&x*D$;lb!003SyJ%=W_Yo%eupPZ{8!8nr{VTtOvrEb#tA6 zXt1;ov-Fx+bZ>2{wV&AakVqgE4H*hX+iocK(`>2f#$!J#iS*7EP@8`4c40p!ekwmz zqIUhfx0%rnayl!e8XR*$5x#S1Q)yC5QfR^poUpzQz}vR{pfQ4D^Km+h^3RYM&4L-# zXpo&PUs`##EvA#NNxMzv=UOU!eCJ#!Y)|7ABBeX`be&bP#syb zm2nY~CL*Qo9lk3J?au7lj^r2-3fD&w1Yrps|IyKzznSV%7!;K+Nu`307~0|^nf5LN zU^6o|PeGeBH+2hN{^_3cgZUMn`O7{jS6V$%houZ>?yu&$GPNt;f3v)yVs9?Hpn4rj zh2Q{~+Y1p*arl`}W?^tzg8Qjyqnd$f7&*3V-hYLQ_YxnO5=qSm3^%K?bQB}>6`81) zWDm}pY}<^;i#h^LV(?WLzQdb9R;5K8pE(rMA2pXXC%!uZw2o{wf6zKY$Hxjblt+;h zWGA`9=8C%?YQN5tLk*qqA_^URG0uP$>D!F6wE68(Xbu(~`q1Tf{KyXT6v%#a*uH_E zq@l|VezdxIhy;~`ltT`?nEx!Fp~P?g?uH#4h%<@O?F&Q4%^?yb;v?fW}=PO^2*ME;N$rhzRq8Yyj-ayNRZ zbh@uCm63^RdB{U8ZzM$uizRny-B<9ajhpr}*l2AtCoJ?5O>I#8Q#cm`m8weLVuV`z z`I`$IBY)uR-}^>F6=`S<$v7EQU*}9#<19O?_tDHh|PRi|LA*Mrt)O)PP50-o^=aXR$avnQjpNvmxTCXsB$ zz2)2KKsk;(2`k(RV}t(1F_MpI99=X z_@NDe2uA2qA$ zzbYELsFhP6<8IQt54+rq)|1KSSM7b+<$eK*;j3y;Q{(UyX(Pa-se)P$#XSH_wjr48 zSuojiy$H-=J9G@Q30X}kS{0EmnL$vN9}r7${E6>EgvOXHkrRhUHVu+?f5CmGU&50f zS{Po$;RgkakqazF;;AcF=&u}>$Ml|F-JdJjFxnUqy$2s|upCHuLkIQHW;jgOzep)n zjA3?+{s4%f8!b%TQ~F$C)za^?S-caAj4PCfRRThpC=)VqI#5**s&kB?F_Z*kLY2z& zxv_F6#0&DQJ1RUp&<%?x#Huvi-8&*flJEQpWghBubi+&1JJdAb9*|i$AmPl0ARxE1 zE+Mbq9kMEv%#xUNT|(tN)l%t9v+)4G3gzI_xq|5tlkDw70;ObB&L{h1LVN$ zf^e&|N`O5ZA^p2}{!f1*!QXaS_9&n)IT!DrW4(L9scv;;Yt5y1_jP-5%D}+D)7jPW za+9Onw7Eo$t<+|Pv`)BfK`|50cDTjaj_=dN8+mQETJZE50I%5X zbjp9SnobU%NpH+wkI5F}EL_Ri;agH6+bF#5xx)|LZ?rkE5#C@ya{w+sK$`+cmtIcD zA5PU&-mWzAr;Pu37UrJ*?Ok#Fz}1az+Vmfl9KD9!awJKy$$;t_2E{wQjz)V^KkIk1 z;AP$wf$J^X5laDTo0D9n621vz=wiWpyUHvH@!zAyP&uAbF8c^$oF}N`yj?ceCQ6=0 zN-<9E>3e3&6P>HZd(}XDT->wAGXkHPN=tdZpD$=+xF`EP`BSi9A&9;~$~pD0$=bhK ztmKY_e?g6D)0K8%Sd#7hYNWDSIi>0LbRQ}aJ+m-fg?+mhPJVm4PkhyOxIR&x*)<%; zF|u%hbj;m?FH2u{8|}nJCRBEpW2n|wy`;I<=EO@pM04g>`KKOey@imI$~Wx9DVN_R zq*&8Z=j>gTgA=C8TPj|Nt9hAh^R1XZK~v1Tk~<;;0@*Io+S_OT`|D>z6V>sZm(lSH zHP3zY^EnS zw>{o`W;6!0+Ih|joYowTn_&;Vhi-Qbdvw>Gt$x7G*y~(Zn5YmEI20ef`WZ~KpIU+* z+GkaYp1*Is*SSSkT8}&96!te0UE_EXGZ0v=(!`xW$1KowaLqN z$4<7}8a9`&M#-7$giz&jE}`GAFjyn&a05!w$6(nLC85&+$DhezLM2;XRYEzb+Px!| zs#fOoTYa2&Jk7&sl|ml}^VMRGFGLqSWI(w_+0x5kXrA0z?}eC>NXpP5gZW|>LZmsD zAEkk=>40&M{?4AW%ot||*O;>x8Qmp!LItg%sWe~ixXxoT|6FHWah-c5DxAKmWD~}n z*z`5_d>c1$GO8Qz;u+W+>Pa`GMb6b4dNX_Wg4Hy+x_rpM>@vA5VAeD#X{2yqKk2pO z9*1~azXs+5$6|u`MvY>@T{I%c+)*`^cyAnFw=7RpbV-*byz$nKZTHFegg_XDs zO;4{s?JtWiRppo9tGV4Mky^M9jc}dZWO+?)ENy8il+TRq zJUv-Df}soxdQbrAs-LXYIZ$@aR@T&^rFNuyn|VmDj5|4Wc2cm1j-PGwU3F+3Sq0y& z5L8eZ-xEo2Xg;tJ6i{l(5+I|U%snv0aLk^2QLy)0r_cm-cfM64sIm||n1KW+=#9+q zJ*N;~!ZX;*`&ElJKGT?EJQ>@nK_;Z4*}5s#m#qX_nvu~=z8ZG_q3KoZQ~|^5lBh>iD8{x}qFC>Jc0dFK|Fy0F~1&7H3EInEqV)4?Q{ zo~yQPDZX}e)>F_bY|4DK-!JB%XS|Ci&$g0Y8}m*nKGyz(l(u*BxM0A*tM$uNS>a_! zBhI?e1tk52&fY(h2pr<2cahI|F6Yl-3hsJmU)W;0m#{&=3z_ z0GEl%&PXcGyNajJqvvB{M+%&zlwoN|D2^5eByX1Noa}b{Wv5dfQ+Bwe`So)Y4)F8c z5eO_f+6tGPDa|yhqkq|LpR}$Vw2>Lum(+O&2XmZ#0O*w3?RSo*b;a4OgS@klJgS9h zpTNf%;HGL5+c-$yq+C)(R|T$j9d{c1;6<0vD4{B_y9F&W)Z^qA7GJo(RfSNrkbI%m z7uFUUMH%LLh@Z$u=6ET)z+L&8t2RP)hNIiEp|jRTT}Wh!zB{*U$}+ssJ+x7UjG+*a z6-9B>EH2U7`&-wgzS)X`$)#+y#~W3y8KQv~e_EGIW0Rj;Y0fv#X&BZ_ha&yq+0{4| z$z(o|{9HghgeIydWhfh8-8wBl<9aM8Ge`_pWV_RSMRE?{JX3{97&g%%))CWH=&7*n z%6KuMlNT}=xM#t|Wd^o;SQPX%;nkb<}u9m{n_o`%noMWM61iJD+_h znqBs5TxM4#;?0t}7DGYu-lp;lIkVFR>SC=ciKyJ8<@vg`3ZVAz;f)6Cc|Po)1}3=v z^lzIXj%R-F(^y9wZw%e73d6I~TM6Y?m$>sw#4_5gtGDOQC3dD-s+Xmg)Z6LaT%~f{ zBvy|RKyh4{s{dGar%3WPw0#vw;(Z#>+?`ntfWw>oC**^6gK;< zml7pqwIuTP$0MF%t`uR!GN|?>=zr{a{B<=l2I!`4i$R^{WliM>|Yk&*<9s|?rU8Yp^M8lG>#L*(n zPz~aDHT~&0BBU!rXcS* z<9$P-`2s)=gCA&2=#f}CG3?ep=qXwb`pQTW@Tu4hIZwEk?qXicP9oQ<*ksUdN`)+N z-Ji&xCk*M9hlDDsn5;&(D_Z>f?3k|nsah)K)-HU{aYD04R`4TwZy4*YPXHGR`>HST1+SXR7 z!gB9q22|I72mjG*p>C(g4w+(8H9RYNY}HAkbs1g7x9oHuKE-|bxQKSBmKA@6kNhlA zj5(}<()@8^1#m^*+hgw;hS8&r?7a@|S5AGz?@2-rc4KOy zu*_ro5Z+3i{>S!9 zRpGPgns#g&pQh&EkJGrhO$%rCXo2rj{rhLYZVtE$-ngab3hOaQU31=Qsybk_c^D^|Yt5 z*?TCF0;`0)coX?cMOOJ`^pusL8i}T7PK>PADnDTzQ+G*0^ygFV8S3b8r zGgW6BWy}SCqQk8QtDuXk`-C7Mfqi(EEDT&PB^S4~wq6~c?4ESsPgd&(TEvFv+cbr^ zO$=Di5E6NMMLfT*ns~6naJVIYI1_s36#WH&M0DET=9!FO+fpKx$Li(zHhiBcLp`dk zIsv!}K3&uoKjS#K;Je=1Bfdd&rgE6go3JifG(}>KEuD=$=P!LQ&=ss{7|T4`jPT-X0mi%7-y>YVe^#sD3^`5bJ%8h=<~<%)|c4? zrwbgmjlVsIVSj3eKl^6CdV96~oV|K%>CrYw z4Nt6?Fg8gWAwD!l&8_^K^-q_1KM58URkl{&xZ#+b4j=E8&TNqm!XpPhwH%a)%C=Eh z=Ni~bce%W}aTD-Z(>wD(#;(+Ew!+`v3>H}u`lsl}mNhUB{*FHU&ELUuDgPC`qmDh^IIR9`$PV!|tQs9N>eJ-rX^5-zuf^x_Ze-9LnvvrV@gj3zroP$#9R2C zRM1L|OlQycCxAAWs}y5?Qf8n2RqrPn!P|7_KOG0wjE%(n-lt)Olbp*_@4vWec8N3> zXFXchKA1V8OG^vBDqFpfYg-{adZfI>NkMV+KvmDmi}q;r=83A*RonZt4~qy#B#tEN zQ{Pid!?FpIo!3cJ$RB8x5Ai1?qaEphuQpL3g~jgHQ{w{bscJpPKfgGim>J2?_&FaO z)_Y(U5I-;t>T1F@Gx6=`-wI!dD?ep)l}dh~qSC>S)%$nO>mL4>=i}-N zCGBwS(KRDF+O7W9Tx?9StgighAXUl&)NY!g;X=uXbIuMikOpEKk$lS=#V5TiI7z z%W^MhG|t`UeyF>%C!M}{lXRj?UidwVo&Jk6jPMzQPj~S%yAx-WqF#E#q7FtLb)Rn4 zgmp$1p$jLZNgOjOq>U+nN<`QqbbnNL?7_#X#7Sy&#~#Rcy-$gUtq3GQV`qfPdGNZ@)aKJYM<`lUGOw1KGCnOF6cM~ez)lS3oUckdQPPfOx^&AWORuHG6Fx)7wVVl3*0qqIb)WcS@xavRB0zQe) zc0b5G+bzV+$M);S>L=%50H} zhyGRFCn6Oc;kxWr8aI{N-^g5-`esau&+D8Fw33W>Pva;%w17%nVk8yO-SFr^{5qx;1nrVp zf98A~Ln;FTeojrC2gD~io8v;*(9jWWGITD(U%C}v0;Y^jv<@GmapmQxv}>eO=~k-0 zK%On4_&fNZ>{2xn?UCey)c1EJg!Qf6<6!h<<@eE#Xt3YKpw+3O!39~)0^ zgGW60Q2B}Rhmdi#%&pR;{Ti9@r2QOMD`~%Wnobs%-@iDhoP~9ZT#IlaO|A@j4|aWG zDLWoOD#a*pbG)p31|i^_%Xr}%b~-?X0KxVCT#9ni@$R)A;=<(H8*Xx$Z)A+h{38g&N3&PF{gs@k zPz%#+>($UrFGDf%tQ5X6kAiP|O-%&sXk4z;F$@-5%#}Y+XGt6iZ9hoqz9LdfeBy-tiXk_v<;!} zh9>%GW?i5V|2&d5AD3?IT`m&nr|{})QwjmXfJX?#-}x;V(GiHRYBnanFwZLRnm&R8 zVf((8Mdh>Oo2qiwY;jz(-8mUjeGCpeQsND;lC zVL0a@=oKH zRXN6n(HhufLf-N+0ks0JXXkTib{@^_U~+&lECyi?HV z%bCmpI>g!D_g~S5&K|aFa2A}V1r1)xRe+E6trosD#cN=w6GVbAviFg)_;^%IZ6j+! z)sY|7(f1-HPkp>8uH0sw%S6MjJ>5^IeC*e!MTE@NZaA(*hFmB3JIJdLTdyMZLodQC zi6`)MYEr9m?g}fYvSaIqEbZ_$@q!xeI{pVa{il!u7doh0r8-F6fCjDs+a=eqoXpE;AJkPXlg)w; z%|T0It{*J0^+zoRq$pQbia$T;a4Hza1iVX8MB6nGFAa-}H%n&)wENIvW4{Rw<2@Ke z$i53b_-y=GDK@0`u_#?L@s&bdH&$oQjUpVJuzX+tg$Kz8beROi@Pjqoir4b8AoXcc zdOLJ;(u()MxXHkQDa=$mp*6IciOJbWV$Hy9=zHo*n78 z^A(1Hhgta{Bw6%tcjHtpQsk-~Me~Z~E%-yYdl69~+1~Wml9+*=-udc)sD1Q3U5v!F zi{ZARgC8^BB-W@E!_C%FxPw^n`CMn^>d4awnP+9HSrJndDZ;+k>zLbX$x0AKf;seOR>Q!8)qLesuM#F*9=| zp^)PX?6;JQz8iK+Tc<@= zH*u_ezvj`dzC&PGd+zXw6|+H~*O^c+={i%(l*hr=jaGl?KGV9IsMP%Z66Na8HSOPu z-yh0aYeT)Bw>EV!6)uAoupJ_X)kPO#O8p}8jc;}RP;W$AgIq0jQiQ0pKt`H)AB90< z$e2DaKIqL61s;zMmm?_t2wNP^=!GP{Nj7Fm=N2$Dn~+Dg1;8CaGPJV8P{34Ot85f6 z*Yhh`peCD|F_m_dcQy|BTD-o=jU2oDPo)1rYyM!9aga_k&(ofnL*83)pZ$8@xoWD$6K}~i2z)wCc7K*yw(f6MT-aFJzk?7EU=r~WggSgjjqo^zkT@S@vLb2TuyqB9;# z1)En&T?kyXuI^y|a@0fKxJ6aUb$&gSXGY)HoNl6GMxkiScMSyZ;~udj6jj@J-sDO4 z7`1!bPP-Sk|5)ov_32&i^-ttC&;SN``)_>zs`hDOxwrU5duO$NQ;r(Ws?_*5u&VhQ z`oUDi5or8>By2a@Y1u?g1>XBO&e?r5s_Y;?MfUCI0>N?)Mm1@4XB}VsdUoeueSnl% zVTIs}2WmX(8Q+;D@R-#!7_<6?vp7%)-Z9=pSRr0dEM;9oXYm>Z?o#xpa;v9zjw+s+ zb)RV`(Ek;!^g4I$|4X$0NVfRqza)F4++Zb%ajl6!E3pg_)buaOLa=D3{MvL4#aXH7|WW;SeoUuUh&6JXc8J8IXc zP)MnA*limnW>GZZB$W4thFxVe{d%?Ta}(1*MU@=lp7&FpmMRgei_Kw)OotyKL)i|Vpg%rh#=l=yVu`%vuO}7xZ#~%Y zs~Q4&Ao5oacK)LW+$rly3!VCu@Y^)#L6@dx-u2UVdyM2Lh4iU7c2&0_SB)HM?GY+(H|j3baEU){c!&$bG zkRl!#$&-(BO*G7pOlf1L5$Q4Pq#G4D*-!M4?#q&$seI$W4Qus>nIPBIGN#PAu9^q_ zR?8t)9-sPl3o~9-bfd!fML31}DF;Uya1d8Htog2hxzQ2PM8Gm0s(AYi z`XiGm$3WJU=W~sSlSODK>>b?(rgE3WGOe(H7sn{zG=-JMm; z$G+)PQa^v9StLF6+t`JsiMg>1etI?2jFuW5z`yqQr6d zSb@U@)E*g%QV0!|(yRnoD;z%8krKX|< zE+CCY$YnG=3D+Yf?(ww4b_m6WbJxr_U+j3*KT1oLzAwXtTmm?{a`lp-)Q4u#`j$Gh z9Z*oA@vZS6>Y^Jl2|@)zziG|(6yN!_i`ZO9=B{RKGO1`$%cJ@mhcxKrt793Z#*-Z< zuWwLe6H-wflC+|?|Eg(YseYpHM#6HAa<$YuUpBK88WH!^SrE&{6~K?2rkb;Td&Lp| zJGC(~*u0FFMMUcE97Iv!2XY0Ac4m>Y-Q3+Mv}as2&UmC>AdO-f)qA0x@vz6!*~uXD zT$=QayFwwGiq?Hu0*IwZNcsyzl`6jG_gx(*5Z3&c1Bl*Mo0+q$u5wy_p7L=r!}%c2 zNX?FZL;R-d|LFzfT}DUmkB<@4La-ZezAJL3abJJ%^)Gu32~^28?8rX)2ZAY2>0}%zv2v}5nq%W- zs-j-=ju`{qU>x%&sVq5qBp3q)05&T(fa)_{NNImpV~w9&^uA7d;~$81J&VSC&Vv0` zww@G?@pv-W%h{mDB@C_HQOdENOD9i6hxwcR6Mf4pi?^v2ar-2mxx{J({f)k=WzmTb zz)NZySMbASQJT%XF<6woXx(PskCZ7GL)+jb-IRlS>B`erfInbiVM7u>dR-lY=jrwRp- z=KRbeYTH)8%qX)&^5jghw}%d?=-*x*4Z8mQ5xx5(KN97>Zv(5O&Syqn+Too)^gYTH zsk}KMNFKir_7JatmP?~fyxf2%Lp3yK4)pGC<7NA_rO_O1<9!NTX%G=PiI%Ol{;M5< zuy%ZRx;A|M^DgH`+h3;}2y`1b-M+;)u0XZ_o6~i5`IpnJ#<)gHOL^;-N?Kqp^nZFY z5fQ%S({WBc`GCN{sP6J9zCf+j$$t#fd}Mx3D26u0cYhna$GDLd7#L_ajvwA~x}(vV z)lYD12dK1+h}3Etw|Tpah%d*y(0w9R;D29_EM@tindglHi8s`U2=i-{s*9zg(MR{@ zC6=RAArvQ{kRjuLQw^XQjQ`dQbL=1&b8+!;Z^o3^YwF_vd^pYu$N&-i%@PnBI;8UHpd&cBZ9!Y_AUgE zTB5})$|js)$MF_84r!EDOEbsT;Oo0^pm^s30>w}mt}?-gAhVDEHBJNt{wGc_0?~pv z5d=Km|Be&VK(ZiC5CLyj<{&Nd?>GUy3tCYFGtg)OuUVEwGt$zE4yXjX#K0O%1Z!{$ zZwvvf!7aQW8B;KB?|=ky0~DAX=5ma*XygC^$xcyMbs3cspM~=bBdv+(N!fyAGzRND z#ix&N&<9Unj6deSwE@Fm&l(lXHV>S08rbsPD(5EWw{80@06q&FV=H(dmY2keD4RZGOSJ+M7m0G)Oq3G~xIJ?p10ND-AZw;gO&K3f(=7XDcdK?`d zyB6)q2<+}`9xe5&8(^ci3~cm{gN@z|u+i&`=*yP$91%x>B531E91i{s5H+#~HRu(q z1BBbk;PPi&h?9iU!595i$^Qjp1$yuQDS!G4TC?qudK}oR8h=AZ91a{Z^fTU zW9$Rxd!AO?JgW*N7C2()a$q-Smw?x&fO#!y7zGBQjg#M)@jP96IIhg{tZZRvvfT@1 zNUk?-T|u(+rc&!SG8NtRRC4?W_l*r0ehDiCw344z*K9$ykII~K(QwATMuI&^;Fwp2 zxG`9e-4TIiqk(g=?0<5xyuU#%`=4CQdfc?<*MFXA);nKh&eVAxEw)4Y`jDIR#h<;Q zQaNb!mg}?=U24k1zId~^E{Q5Fuw9KF%x-FC8&`-6j>^k{Xf%kH;<`guH9#sqZWq_Z z>iM5rTm646!AiB3i_noc%7ol=+>WjFszaXDe^v7pjsH<|C4V@g{L=Wpv^)+6*76D3 zY)M$n!-IKVQuS-?5KNz1-fsJU?HnhR#MV&r`iF z+f)CXw%b5|R=Mgu1YRC5jfmBp?TKBU&|Mxl*Pk7PLw`wfw%314$;{1O_zx|R+1y4DSMsIG0} ztjB%wnATutv|Y~j=(s|{`&+wQ(c$rpURpYa2r`jv%s%(V1^w+ZGLdymNtbjy{nu(s z-|-VXP9UnH*O75l6!npNR8Q+8kEr77BhQZdXTQ7KU#3jfvmI@L>A;{vb?s*<4*p|+ z=v!D_!l=9y-xP~DBV7C=`wy&kNQVU7l=dOq@LV!lRjz6h)y>LwebFfQ&0@06;<)g| zKiCCHfaqTzeyZ4#OYg}`@v*<3xIeX6G*J8`#Cnw4d0}RM`41@2&Qf{#Xj3fujBD`^ zZsn!qW_`r}fL1DCa{iML%aK9n#S{C>_b^zN%H{Y_|Cd{h#}s*fayjD})rhf9d1zzC z8n-P~w9JU{EWhl#g7yaMZc@E)qZa~O#iiA#=IYWK)DTo%T8mn!F0DiDRTtNP3%y!r zeRtd1*vE#7%433jZlVomhX3X9*W%`Hp$q`EV{II4L-ib>7AD##XZV)^s{LE21VHUt z8%NntB?8paL>mX-qBuMA$~2-Xqamoap0)jiN2z^rAv+;rJ}ToIaNDN8=ngji$_kWb z6h}C|{1Exxd!hzA+hfMuxSxMZVuN6E`C-K~tk-+Ax}F%{2C$#(HCXRAPT9?@XGl!^ z@~yU?CgHOm5KMg22eo&@IpG{d(MgIwlN8KT6pB+6wo??bQxHYX6vg}$#f@nS&S_}& z=akN`Q16%I?lT`&LY=0`S3<3)KP-ouPLnT(>P>%G3Vl3Hz7(pQm}QNgszm8I zN42an+ifw|W<)b%vqhc>UZ;`STo8YtMP04Jcx2~?3Z4uUvPD!94$ULGM7v`$k!SZ^ z18|yuF?WfEe1?0YVHxYq$Ee^ELb)cjx!2_EVYU!cYvU5LA|ru>RIBf2yT%cGJf*Kb7lZnQ-q#*MlnEMu7I zwLK!6R{cX}hewMer-fTR|8N!<8JpEM{koI(cA~QQ4hJU^z z!b8=;v^F2<Rc=AaxDgyT?l@f3po{tCV+g=OlGCgv>`oWP-ty zav^g_d)3^f;E!!svg->#Eb~YROfIOCT4s}}&H+)GJ7g~-ZGo{`rc0D89NexfT@^O( zeOtXW(`8Zm`fH@{J+kE3J1@NGWaARm@rStq;zX zi4Y-^IKS&-Qh8(ElxTjNKR5|1(;S0RW}OmqJz(wu9yvj&C3z9Gtg{g`-@%XL5{5Bx ze^w~WvRS;%PKOFhBP?_LeuM+{Fz)S@GIjbD+q?J}LV?dM$UB6R6r06+=QKDUQTNGu zCpD+?;Vn|jl^W5n2z~%G?ZsArhG5D6E$rnnK9f+7tJn!orEs;sV7CjK@en=D{99$Cqxdx-j{%vk zK)j6&gFL*{zI)BSesg>3smJ>=UAf^TUm-UNQM$(g*sI(7;U1@qOGDVXXSs2J!qg># zK=raA7vja2-oo|78V=%bAANuy~hw|ai5WffW4t+|>R&&2|rDm&-bgN-4<*M69%p zEBO2a7hZ)>`(!FS?+Gqww=GVB24x56M_#Uol~9`o^a$$;b{9Q$n4^bcofWBHHgr+h zR6h-U7XXi^JJtk`_w!@N)jN*zyA_m~hH5WIlR|L=zm0yb>2P`f)Z6{#bMr=PmDU@i zE;%wLbG#A!uQb{|`2_@pVrD4^$6$c=(-TM;TI zxo6YY{xvkz|McbP=QjW5=T^OKHw?c&r|xU}_=|*=|BmBaL-Vp#h+6eF%o4sK62Y&S z+x~z8vxleor81{3^seJu97PeUfekJYgC$Q_vE@(h<{iI~D)BiZ2T4w9m(iq%NON`( z>JbyI6kI}`=`fQX`ZjL`O=h=y9+CX z%e+zzpD{bO{oK11a)#vlv2s{NR_4(bo+{a|~Y&*{FpWO96 z{&DvmTIx-s(dyrEUQ9T1mIt3PtQNb2oG%2fHeC~|7KyYV%R+eQ`q zGoOp$>owqBMqci3oo){?P%P=1rJSVt|5jZY51|F$GqJFiZ5&JOg>KuWpAJ?2&LA95 z^(q-qCqByMEzk$oZM!>gxX87l^yOa7!R%g9sPf^WZ+1=8VskuBXke+cfzc`8p*54nJs=I1+=qa?_%^GQiQr>E)#tQH z0h#wQzj=3$jo&YA=%^WOEUEydDbKaRVPmd^C9zGF{_?Tk2UEH=zj0*}EUcy`t$-Mi?|AFXgWm}?=L@9c?PHx+E&4ab`?*Sun@_(IHH zrToA@>znaCQ%yw%_N^a_Ll%KgpShy6)phPy+Pp%x6XWEw94TKljZ9b+Sh^jx>n!Er z{8NE{2@#cYH+)inBwFUT)!wY}%_U)NB^`3W!t!o7r7l0lM4dTqtx}~#LBZw|b34y2 zD_t$bK0#ADka(>#r+V%~@U+%Ce`};Mt=mY~eTc?9Y=R@!v2!oRIFA|n)~@>}2iau4 zaH&bWniO`&qT^iXsC%xu+aYbd+Sq@pa#n$P;4Z(#%iXWW*D(V7`9q4vy^1+(x!2AO3oe{^BU(e+a|BCQ z@SuE~nyaDI7oX4ZOP=0#%OKNRupGMH>M}ph7r{O6woZJYJDKQqQwCj}fG(bQF1{}G zbGnVcI0$8%=-GblsKMHUdb~dUWAbjp_d5oc^RH_v4%%L(kL1aP5>0#8K;E@NtYdF&kobx@G^8dEZY)@BL z19Ha}s<4b%<1^vljPQycH6wJA^jM&}Ey9$Js2rpLMXYc>+Xd&dye1z7r2tm$WhV&q zCiQU459ozKB77281vd4=NR$)cI|144VWck_fUfp12z?jOLg2xi>L82rMCikub{%lG zkdH@lzy&zflN|s#i8LTrUjk_f-FqDvyvMIaeXNqPo+-NtQqCk|aL&jHa0mY2*81=g z@Xd{YgoQA*2aL5pDG0#AA$62xIroz}`q6$z9b9YhRgY^Bdqrpuj@h?ae(gJw5k3<& za)Mo9xNKSd`~d>z0X`ESrf*2&gekE<9Q0Xu(G~Wz-5SsK55d=2{;lHT#<3aQw%7Ya zZ(DpOelaywfY#VJc#o`D6m1+*T3-)puNxyZa0}JKE!(smRc2Cs=si$>@uP(bhdGS} zpwl3YCymzoM3|L-*;Dq8^Zz~8%uM(pCaKYz1*0SsT4&PhYGgju%`)| zr;;Y_R9_S;c@K&M$Nk-Tdn)-{ZZ1w|1eu13C{3#=VwF+O4k8-x?0xs$nqF_GreYFa zDkPj{>Pv#<9N1eycBNcZ(bs*AL2-AfbqT0jrYXFhWwAoRC1#@^$l@l%1JYdWDuFis zO0oyKQH}{Sq8E`}UdBnQMw9W(6+;GJa_1ZCLPtJ*!;5qIiEelnZD9^XlIT_L*&P=oHho)GEq zq<=zSGgP~mur1PI&8aVxQtK8r-!&K7=&bMWwX)IdJgx4rqTJ>@4LN(PeCcqFpvtc? z5=#6E>}OA7(<*V-JLaKHWZhoL_W3pcp4NBmTQyT|%vVnFXP9DH-*k#-p(hMI*rbDtpCVY-{P|`IBXUwgv*erD zXBD~M8aG6HxvY@eX2r$yV=+T3uGOsFb8Epx)H?DGh73I`1rxRQ;OOnohh6Zl@;@M| z{6FAw5Vvi{X9h9(CE?1qlsKFMUZ(s-hPf32qbK`5_!_BC&^^Tp*U+y+eej8k9B9a_ zBHkoZl^Xh9U!Ro1q+&K)DOM|zxQ5>J2YB#?U)B$qv=%m}^k9ehqbvc6O`nIW%A`}p z3ct@e-aRW~tL?-_jz&)-mPpnWY;Z1d4zmO*Z)3U-CZ31DlmzmPDTj$7(J;)Z)R?l* zYS0FF-J+v40WW)^E%(jbw*(xJowwgltVk%~UD`(suZtp^HyIyY`J$#V!NgVF9)xt!N z{oq#F2WE4_fam_032q+@!GnI%M?mo56=Ge&<`bHnk6qc4!$)v8jknxEcsGsP$q&F> zk2R=W`(t%2!ZEQzjN~8hD6mc!*b3j-c&g zMuGF??%-~iNN&N{!2y_UNfw^zVmSj8J?NMGh&X0I;6XS;FNikv4j2u!+VbYWw7)xO-`rq$YGF5+`$DSB{j~5g@Xq+AI z^Ys875)jWP(yH}{B88EI6;E{sG34KFHD?17)J)^vn;pi>*E)>PaTmFRuk9kFoD6?` zc3+`!-i6MDHy70%Cp)#BCRY*b6~6jKPAbnL)t||{J+EkX+4G#PHO%b3x~?VNh?Qq- znn0b%Y?v#F!!O^Ul8t~3E0}$h{wnIdCa|claSLs1bUxSDwKU=d;FJ6@CPJst z(=pCmdq69htAUETs)0dO-8A7=>Yu~^PaECI1uP-P#MvsUYI>0s0hG3@nhdn|%s`vt zj)$?hAS)HFEU(|DmTnRUyjE$a>JQ{Eq$#t!w(&H+;f}>@s%jlpMw}XnVnw-UhkO@L zX;35`YGUWr4cIG>S-FR-iM21o(m?-YcVRPqPBRqRLlb(_*;K(3QK9{Fhha5z>$nbAsmaIIG*jJ zr<7K?JWC$aI16K>_*#>tLgAyD187K)`2IkPwxT^}QI z1aa7>$Lo|Sxy-WuJUjXBk*bvUMUwGIQHumo8K;ay+7~iwNJP44`%$wrtHs5QV9`NU zH*kaR$UXGNY<-`}CnsUIgzQmQ(-nGE?hrFb4gN9s4(P_z+Eao*bjnZul7@7DkV~OB zhL`$2AzR=CceN4X3kuU-dw&D;2Fi@-&1Blc zypu>aC}p`nYl2=L+;b8J42V^jAq|jFs*EekSo4Qx@aBs527jT(5W3@LkGJ@FKGF#B zPzWAv5s+q6fs1i8!`FiQ@v<5+x2Uo;0yP_;(ie>FZ_HW+!>;xPKc$vh<9VptjQnYf zql~*T-nrHkYoW6wj(7I%?4_66%NJ3qazQabyV7LQj1)PleEH{FE@qs8keOp)(5(RePg(Cu~d?YnF)M$=J)-`PBSTG$3=1v)Gag$VUAx?g+z!gJtY zF?C?g-eF&vh-9b@Teo~rr`4A0Jk}=H8MJPR5>=2j8IkdL64FseHh=qtw4@vkVbJ>8 z_PvW>efeL@LUmUIgh;eLEJhEmtgi{xt+xu;`n!26+iyHFfRl6zNY^8g9 z94*XRwoVmzD8MzHDwFG{oy>XD+AWow+Sh3NduEoZ;!CH~FI4u!U8YBJA4Lh*f^ey*sB$KYW!o937^ex;G z<(M$dVBF>e7CG@}_)MwKt!Cs6JDf$h7uPZY(pKJX+v^OXI3jm$aEJKZ%6(&o$pEYc z9yf)={_dme4BJ@4Ga&hyNuzIx#4f!0Qo!eyh#o^=PkfB$t@)0KY0(>YCZDIn)=NU^ z{X7oKX(Vn$>X8xo-5NWRyv`tf=t+}$m$js@`G({hKL;X!yzmIJVJ99NaRAtP5h&d^ zgT4h`FL2#PijV)?h2(@vyI-v5LjRxTpJ&~piKx`;ndU>N>;K1cO`L+|D&6pn@JaqX zYPdp0Y862s(b4qsmWI6Mm47VshCiQxGlQ}OVsNs+AHfw!-=Z#zk88nE_|K{^9^sHk z;spPD=>U@LpM{L0n!;j(_&tE7;YgDHzUOtLwI}me3rL3(Q+zs8d3;&9!Qd$&=T;pnqny{E{N|W zfM}&D_nwK6Qqu#3!Mb7Zr4HY(2*U9}ZL?U-BG(`BOXOCNUaN0_I^4H``|Hn~UJ7Bk zYbQSqYYcmA7Hfnc6vmXx7A~ds_0@n+a_9Bl1qS)M8+MT{{r3R?7W#jk`xnR)GB1() zZ@T}5&WHgn7rvy(FJRm|Y0%#;?3M{RAGP=jYLXBN@7nIN(>gBBP5NRZcIZJt6u3>AqCyC}^|#fPTSP4d}PKTrJLY7kPc_<1Yle(Afpmz9A4R(gM4f_`pAMnv9Z z#*&DT_@*=CMa!Y=Z<=op9vP_bq!}0Wf~#Pyyq%Y5hLE(5IC{FLL5{Y?0s;h#7gECC z_6h7#x+yb?A1UoUw>7(w0?~L6g?G>EABJGJTdprO+6SI_5V5VA+|4@S@#kAIkl*vi zv3Qjhv8+Tg=Q$Emwux!{=wSf|>rNJTeSFif`0f>y2Bcu@U zur$v>e9Wi@_DeDadtA>oq>M8hIIHdeOHKR+ELX-Ew%jU*7{;%XfDD4k%s&A{t1OHd zWJh-Bd%yEWln7$_Jh?GX9;Cxh1Rf}Q>{dKbJpmfzp7RV@>8;-M))~m>V@H-5>#VUHa z+eQeDz9HVJpLv6FeIE01ngT0T`K@Bs9`BOT-nKD+nzU@gN@H?fML0jBDxLqgSu?9` zhLnyQ6@1IPW#4930=DfEg5r}?D}{6^lkMl2ByF;`o8_}+ed=|dplvWXpN9OH|B%-x zbMqc5#~|$%B_G}<`OTAK5eLGu862N%(39j*MMzh|<4^g9Myw9wf*O6GQ=@NXo)z}9v( zKl9}6qbp0wnROo=&u;hHH|8!K+1mw=`qdmLw4}*Z*s04O#Y|VRw0n(3snVY<>8C)p84k|b zN=~A57kB9xm*k2#1{g1D-Hqj9tB3}IZ1GR_O$eHVyu6

uk4dxJnG0KKvc@9pwl{_hcAA5 zGadzbVZSOU$!Mp&gO4BSPIBTw-_&46p6)Y`VmuPU+NFt8C0{XGor3YUZ{hLXb8erO!y05)OACoK zP7@V!4)fk!JQu|JemnkWZis(AM6mm_ah+VAieiwBkTpeLWZvb?u8B1NMqbSuyP(gL zx8tjGDX}~d(@LS(VU3g;7{10uJ`v>}pPn|!GMt@g4fz`vc@5Xhk$ammcb|9?)=5<;Z7B?+u+8TzQ=KVymJ!h%cz@I$vNJ z#%z2Ysop)eXO3mR%m#Wg;{2QGQP_#b!PCubr=-o2h5UYH{r-H9HROk0AO;sdM=UdP zWaY(5Cb+R@<$aJ$NMMJure8*qj;oo+J$f>oD_K1v9*NE8k?pR(JpX*{*beb5Yv>^t z5{D$2e>Ek}8^JN&0Qwm0T6`(F?wc3`Eh(F>66%6uZRI}q9R2^YMTzrH^!JOr2o9)7 z8}JqQIr!4mZfx!D?&`pk7?@bfz7IEe3wboDW*+3p0a?tF-_XBWW!w;@;T3jO${fq9 z3%tr;&f&!|Hc$T9iSNGHlEXNXPe*jgK^SYRwWsIy73K6fhw*N6PW;p%ZWpe{$uz#k z>OU;oXT>#0Cb@M=&HFw74zcg~$$ks0i_;ajYGCsQ3)R1P9@A%$*?;#UrVlPa^biod zI-zqgOas6H+dqrxT&Y9L62>dhf!1Hcmrpt}`6sl=uukWNz8hqyJK?W)hb7;T!CS_qdfQlBsBS9q+ib_?nfqimr;K)gHd3vwXNJ zlJ@@SEqZ2U`3GCznnvd%Gg4^KV?;9H8haLdxnx4dy{t}Y24xnK!C?~yWhd0lxCDZu z7aZwn9S=9J^ew)ikl(Z`UnK`^rA3acr<<-#f|o8RJ|?fGq!`1WV2J3_MPqGVAtdYK)}cC`}2(Pm_S{HV+S3(|Qs4JAxBR6y z2gE+S{zxc&G$9`8?h$SUR#WsS@wK@tV`aMla@W+iKjuNTlo_7 z_H_;0DUN}}O|FS$iCoj;sW9)7fy`4tocy9NO=O^+jQuqv9E)8=Vj%H0rlijoGiCy;4ybEie0U_4%RfET&%%$Pi`hHnM8E2wVRs4i{L>?>;JUr+yQ&t1|aT{%Jq#P^0 zVs6`bx-Y&><+Huxi8!RMB^0LHf4G~Nop*H3znal+oiUKrtQf7}{9@tDpJgarfJ)4ICD|)tn^(en(IR3=Jr8X66OQPu%65-Ft_9QT(*@052J^4@{AQREw{y!vVtv9! z`wmN0OZ;w}qCZe`jBqQ1JY?<^lm^$dh(|s)VZ{pm%qYOEW~*_OlwYLMzcO0G#V-3v~$}?Ihx3Fo@CBU$K7#84&K|-xY&|qls)jT#IxM zpP@T>I`YK)oVA-fIdyxP2E%K+yyuC@_`;Lo!%e}4X(kkL6fd``s( zPjqmznWtAy{?gXWZ5!1FeGm6FAS$YvUy(6Rc1BS|>O5V(816I>sSGfx(B{k?J3 zH%}0nyDM&WT2OI57PcYIX_tsk@f(dEm+6-n2U3hs@{{QtuC^Ox7p_zo!JcIGMEC7v zm)moHdn|9|lKwKqIo>-hK1Du=UEXvxJDX`JL^SYUNSxzMDv zhO>A^{uW}g5^vEXjv?NQta@2>GEeGK z47)(?Ba6F=^4;tWvrXqp2_@>kYH+%L*S#|nG8O%fJpLixT{;;P@j-JrG2u?Mnbv^` zt&S66C-fzL{f~X)oC5_kcF#b~Ar&#`A!DF>{KufTTy2&4?pRi;hWy@JP+03S^pva1 zYnu2Emq&ghCCAwqi-DJ9@X;W_-^K% zSe$OmnbXww?|ROuY~c!co7s1dAfA1aBM$yfb#IvL_0PKP(sW$q6|&cO^|nJt{sCu? z-jUR~+oJf1tYovG)~*Jx8)4pw_?3}Y_lYf9?EO^ha4cvI{P|QV*yf(cx>`y|^eh2s z_~Ycclfk`#E9`nJNRN0Ci1e|Vrk{U{a|_u}X>kP}^U?9SllXY?3k6AEd+; z?MJDpJT@|K95Z7k9Z}(h)TY&?nK3FL&_8BSjwdCC9^z)Z;s%SRH7P(09$XiBP4(W} z$=mWj?>$;>!Obh2?0!q8H6l$b7dEKE#jFzkKC#k_E@-P;lu@Wg&2>zj;o#umVBI1u zU0k2mM#3FSasOe}&>G>7X{XDoacOD7`SG9beXQdyxn+v<&=r0CkY`|)cPBF6=@HrE z$y^h1SIAXmRZi;oLzp*lQG7H1xNw8nSo4(KBQmuLo`A-{fo2V1Eb4jQUvXajFEfW1 z))3btkJC>4`{E1~kH9T0=OW0W zs<9f`Fhi`snJC-g{uYO8s!O+wbhpx)9I0Aqg$v!@;8*b$@XkJq+1kvs73uPK#Ji4k z?%^(q3BF2=k$4CD=Y9LLN0e#OOm#-5`3Ad6WX$id3TP{|iAXC_80ax?w>cvGln`QM z@wo~JTvFnpJI8`%q<)_CqSwH0aH=0C89cixHCJ6kgr>ln!48dXxPKfw=Q3)O*mB=x zYSW9tBy`f@L4~YY+H!->Z}w#GguXi;^Wr2EEaSwsz$1#>2wU8C|2y9pQ@)<(;)Q53 z+E7!B>(Ga-#?QHEw(mc(`Jm9g-)()}Cv0_Ww}X>hHaA?8F*n&JU9+3}p(V{2LHoX< zgx_e`s?ehCUA)W(%kgH`Ba%M4nG98F^kW~tkRnW|oa%gh9GkbC5T9_z4As>ZMZaIk z3o!3t$6#25D)bA}=$8|HIOIB~xR^ix3Oc|Ip8Wm|-a-s?06SN^NjSkJPo8zDcQqq4 z3?>)uWPR3TxrzBe`;((%i5lx!S;`;c)vz#66AKQfdq?d$PcRZSi*CNhMdSSpR9p*d z{H>Py%_s&JjT0L{Nk;AKpWe}y+Uwd-x{2J4Z!DdMIG%hRKf!&A`%DZUiR3h2dW##3 z`>a+Rvla78U53xRPpqaP(y3Jl^KQqq5Ee*TdX{qTZc#q?Dl^igQzy~%RosFn;go;k z8fM?G!wExm*--ul{I6TE_LZkmBOCwHCn(Hz$IOlHEWUf&XD z)9HQ=sA%{(ZE1ssjiRUZarX3XM0?F};^1PUYo0)Mw1CcUWs7?JST`k%krRJzkEe%3 z;Ea&cZba+;-7&7U5ZAnKnmf>+Oa*xF?*@QdKVoB?Z=D*-Q-dlwBmLSD~Er??b#kxJ`^rW1gF;m>EpQ zignW*bZ0X7eea%5>XX{9e_ktGi#@xy!B*tBG+dS`@cJgiV5=@9L@+?X)bqHP)xmzoyEZpCEfn5 zK@uR3yhAhm$MK`0SnFbvnwD^zr^-hKv0(sf2rpWzRBUo7tjdGu#MeY<7@CzdPLuj0 zz1lj3(lhb&Vc0E4h|MuZLNoQYaMzoBrgSC}sbj}qNM15)71O+pV*hiB2FtT8tfmm3BjX1JDQV|Wd_~R|C zceTQ!6-3!--g;);d9&?Ea?`W7SyV#|?3bR&i*cYAjp*{ue?cAK+~!1NdikHte)T^= z*-Yt~LuNb2<+WL5Lh+b?XP!Gu$&1eQqlqTZr4IOXjkPb!QM5RmhifQuR4(2O$mLf| zwYbXOQcR_|BYv9C>_6vdd5(_Is&c{KDo<9taYENIeay;RQ67q{1LSN%LY znY~4Ag+Jwe;bDtKfDVuw^%A8vJgc=^y}mCA9eb3hn-nMUw3;AJuB*fsZX&`YalOyg zxu%a?GxS~=We|NwMiOu9U;T19XmUR;E!vSI&Rf%k^G)xudDyDv(mf+fU488>W|}eo zVV3vb{3sM9g4Gcr726GLZVV|n;vOlSyXN^j@n<})l1@93~V>0&(mL5x77`=7@WVI5kE$X&=}AM8_2jo9a`@+m*;oMnv*Ls|DVFnJF1Cq z+vAX!1S!%II)VroP(kTUItT~~p%($AOYcQUXi-22Ef~a5qgd#@O7B$=L7KE62&nX4 zZuoicy6e67$D2Q9_GjA(pgdiTuDdBeJ8XKcwEAUOl8s zOs(NOFHriPXY}`mNX3u=7^yfo70q5CManJb)$hfV(oWDaDeHuJ$by|!$jcvjT>Fid z^%N#)6s~LrHi`aj`((Qx0wu=EdJ>d+N7d))XWaMOx41VdHok1SOXAvg!Gf}EMuk-JPs@9og!VUH&o&4?55bSR)AUU?Q+?>Y z@@HT0z0fcznaMhIUiuUO`YLI2`mHqUP!_Y!@+S(%zXujXnFvbl&;NGh0+r0S1~SW6 zF*jP5i$~EOsKx$ZsmIL=cUs?`1)}Lus0#EUs7E<~XLVG&eyT!c!xbs~wVYKM;0FxfO1<#K&v_EA0-2^1@cayM#rK6e}W`7-~?)5e`Z_DYx=jnC=D}7f|!&QEpH^ z$;d#f`gXaoQ8pgO3%kmKCpsUJZ5UE;fiTb^Dfo0YGT9@VE#2gLQ5L)&c{i0bmaEuEH*Spgv#BU%9yY= z+fEcSzet`urMqD7Z$hz&U8n2iMTzwA9l})ZBahDJn6lFA|wqb z(WFKEXDLzgF=2#h4!TZAXuduByi)@HK#fjf@JHW|ar6%1IAgH2EcTt-(!p7&FSw=> ze~a!RVp}pnbEF=p1oppZ^@@8YYP zXp@1R(F@-I#iV2LKNC%m&WN=)s($8f_j>&^7oFcoceLDyBHvfGa+Z3o8y{w;LTbx3 zYGWO@`nHI$6Sw-_=W4cD)7h@H!LL!5_hcbgIqlrv2o!CmvyJH;sJ9$`OMha4Cn)dX z@@~P+RqmT3O}u`B?_c%Ac-69vjYI=_-7WBy$Hl#d6vTon?+U7e7FswK(?H4L3!1MO z#oUZHt(oDsGUVvO0D|2>a(Hl(Tq-IL-#~2EUff1Ah0fpoBot2t$#JL&8>fXT>Mgr~ z%HA$}ZCZBge4K4KU?y=ofS$686+)pO^$J3_(W{+ zSmp`8UR-qlrGm(0#VYqpG$=%tGKSwT+C3fraQ=!>Sk05B%J4nHw1RXyInvC}1tt-H23jycJ-gB80jYnB{we8|Tlskm#R$qPXfq>ga#VKTv3> zOb++P+LxH3I+!KpnR;R!DON~Xt9IQ^BuRNoe(dC`JCAvP5sGNVJ2>(^zCN1xO60i7 zNJjHjLGGQCzMPQ7+k}477Ob!CW6?Bi%%FjgoeZIyfJwMp>iz=R}Ry zXk}>5j+FPxGHXJ$GCP`z+ltlYPk-ADzaxWFdgTdmTlFL&%3ELy5aZ~RD3wZ?tJ*!R zj}e$~zD4*0T@T-}gHxiCLfc&H4nl#2{$#fH{q>7UOZo1Ifgpa6cV~spnVH@7zV!8| zYNLbM!#AjYz3tf5WF(O%kXvP*d|vr2eL8{5;{CR;-ln3wyGdFtbwJ{^E17}xh_9D6 z_~2XPpFenRiCXkGmmn>=Uhl@vH^>C#5C3YwFQ}(6dhXvzC5v!!zb4xP+YT}Gy@Xnr z9h4Tfpt1bMIdG$Gsd$yy+MHQY4c{M!v_@AdzEegS7)Ysw`=$!k756hyhn)#}Kc>@t zgc#|cQ$B%H(mgW1G6sF{2sq8&73z_X%kr`-+1nLCRE1j9iqoy0<+Z zJep92ExI+zEezxVU-u%t+4ZIW zdjJz4))o^-ZYoN+mFcvqc|Q%a`ZL_Dq2ki?(-i&G#}Mm$ugq{=-`~rp?jQrh^{5WS zG!tO7Jg1_9{3R3YjL`(l_wDie0_yiQ*zk0zphb{{RsXw7I? z2)^B(-2V1SkTsmD9dXJ>ZKu~KD$pqcYX5euq+BtrE+(bY7Y5Rti?)vtNOueqcE7tPUZ*7CkFU0D} zu86owK4VmJS|w~1(KwO5LAJG#iJ4&vi;%f*#x6ao|8Ay#&2?<0-E*;7DKknKp5M|~ zclx83K5{=2dYdsJV8%bYHakJtOQg%~5U?MoeIOMVCBRcn%hS{FIGJ3&?Z~PWrKK^3 za~h02=!-c#(&2S@T_tu?q{+)5;$q6xXN43c-KBT0I|U#xK@Vf%hdB}q8WQa@0vw|4 zjgPpc)6!@X1q;tUclhoqT`du==OaF3Qf|Von%1U@Ld?t+#*!nFyxFuB0YL*DT_0|> z#*0LUw{-j6uv`~Nw1AI%3sGX^L=`*HIDo%Pi8iYibCE~Cq0qfZp88fs-0Vqcv`(%T zM|@NWrY|w?zL}qON9Ueev!+P7vRR5Wf2)?Qc5p7e%hzG1D|tQj2?L{(D^!7MtrKk& zi3i*0wtbncdRPaA(1GMe$o8*~jr$FQU5@I*k|O@#w(fDBGdLAfsS#aK0cuT~IYmJ0 zA~)K=Skaqr2v!>|@|+V5CjK^~OA`b_pGnB2N;NB~jhu|r;u z*v^9i%>-!4r7*ZXbcvxyg$o5O7DC_3;li$r>gVemen}W}ca_y$Vly1hN|!d#oT4jP zg}sP;ikM_hRUkX^K3)vC@)M)DU1&wHSSR!x&_;7zbuSuuThp-f(k-8VFaUe`@Yk@# zhErcdmdp;X`($s|aErO_eFgbvY5EE-?39q5L!^H02kEDY@5%P(TG~-OW7)Y{)+L^N zpHDr7ZZu%b)&V8X=ArU0!zG&0Pc6S19!7Jd>z)^3Gj&2zsP5`$f9YtJ2>4heFG!a6o!g@C}R6@)DQT zNJkLCRhZAZEGPSvHZ4vk(*op@_#J2;{uCgDc1)5Dk-R-OVh2}0$^t=Iiu72d;+Evt ze+>~W(>bNvhZ-aZ;&#_3K62+SxcFiOc6)?Tr^ic!GpC0KdyS2!xa=e_4D=G*p=w#h z41@@iqq2z&Iuk2X%9CMV9!3G1qvs!LoVqqk2x$6DZtcSxQl09)#^m6-rO$BQ$Rr(q zL)QAR5=0(HJG~M)ybx`$%5mq$(i{tD^fsT#2N=e9!)U6qPyfJ_YL>B?n{Q?J2U>+G{yL#QJ5^ z#x~!e6G1vlR5F?fa*)Qc1U}Nypcfw}Vev z6mGixnf#b-&|fH(#lwjA0`@uSPc6s$bM~bQRL~Uq4}{t_haVIOyq*gyF@4gVZ@zz0 zbe}h>_e7yg;pB9>(tb}WstNM$VLxFrb)fL2w*fD&rm`0k|AL)d?nWek@)G|*)j_U? zzaFRZiH^347d^uR-fg+;pN@)hfEenteYy5)$t5(fs$396gz_TwD+p!@NJi#_o1=xa zP~N3*jbgMSBfDjRE1-iI0koQN3NAnxj*T8742Yik3)bi0_Z*i<4^aiC+yvkhU4T&B z8p#U;PW+oh7)XSF0z8kg;zAf8g21$~e+Y_eAjJUdX1G5L5H(%Bi-v*eXh>aq{(WpSg8wR#86hyvpbMORcT~v8v~&PutpAbxb9LnSw{C)wbpI(U z92FFz0LZh!X+t5>fIp77=TL|u0QwwP%mm@UEkYrp0H&yOV8@BWAYuU4=)dsn95`bB z!q_=*z4!}LiC{|HC=+Rll}TVa>i>?;6MHV;z|AK8M^KymKLq@7=K@{8bqtQ21;UHt zXC}SXEjV&!2p{e#$p)Cd{u}sw4nMQcL7zPIB?~DY#6ohxivGq2Ss*Zu|J~l`zZ3ab z@sbt7!}-tBAtxh?29S}_|2ImqERVrB1y+b0aO)I|L$X3-flvShH-H6S#m%rnVBilF H5R&R&7V!P- diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 04bf7a10c..410dfcb1f 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -1135,131 +1135,6 @@ void io_soft_pwm_update(void) } #endif -void io_set_analogvalue(uint8_t pin, uint8_t value) -{ -#if (defined(IC74HC595_HAS_PWMS) || defined(IC74HC595_HAS_SERVOS)) - if (pin > 127) - { - pin = ~pin; - io_set_pwm(pin, value); - return; - } -#endif - switch (pin) - { -#if ASSERT_PIN(PWM0) - case PWM0: - io_set_pwm(PWM0, value); - break; -#endif -#if ASSERT_PIN(PWM1) - case PWM1: - io_set_pwm(PWM1, value); - break; -#endif -#if ASSERT_PIN(PWM2) - case PWM2: - io_set_pwm(PWM2, value); - break; -#endif -#if ASSERT_PIN(PWM3) - case PWM3: - io_set_pwm(PWM3, value); - break; -#endif -#if ASSERT_PIN(PWM4) - case PWM4: - io_set_pwm(PWM4, value); - break; -#endif -#if ASSERT_PIN(PWM5) - case PWM5: - io_set_pwm(PWM5, value); - break; -#endif -#if ASSERT_PIN(PWM6) - case PWM6: - io_set_pwm(PWM6, value); - break; -#endif -#if ASSERT_PIN(PWM7) - case PWM7: - io_set_pwm(PWM7, value); - break; -#endif -#if ASSERT_PIN(PWM8) - case PWM8: - io_set_pwm(PWM8, value); - break; -#endif -#if ASSERT_PIN(PWM9) - case PWM9: - io_set_pwm(PWM9, value); - break; -#endif -#if ASSERT_PIN(PWM10) - case PWM10: - io_set_pwm(PWM10, value); - break; -#endif -#if ASSERT_PIN(PWM11) - case PWM11: - io_set_pwm(PWM11, value); - break; -#endif -#if ASSERT_PIN(PWM12) - case PWM12: - io_set_pwm(PWM12, value); - break; -#endif -#if ASSERT_PIN(PWM13) - case PWM13: - io_set_pwm(PWM13, value); - break; -#endif -#if ASSERT_PIN(PWM14) - case PWM14: - io_set_pwm(PWM14, value); - break; -#endif -#if ASSERT_PIN(PWM15) - case PWM15: - io_set_pwm(PWM15, value); - break; -#endif -#if ASSERT_PIN(SERVO0) - case SERVO0: - mcu_set_servo(SERVO0, value); - break; -#endif -#if ASSERT_PIN(SERVO1) - case SERVO1: - mcu_set_servo(SERVO1, value); - break; -#endif -#if ASSERT_PIN(SERVO2) - case SERVO2: - mcu_set_servo(SERVO2, value); - break; -#endif -#if ASSERT_PIN(SERVO3) - case SERVO3: - mcu_set_servo(SERVO3, value); - break; -#endif -#if ASSERT_PIN(SERVO4) - case SERVO4: - mcu_set_servo(SERVO4, value); - break; -#endif -#if ASSERT_PIN(SERVO5) - case SERVO5: - mcu_set_servo(SERVO5, value); - break; -#endif - } -} - void io_set_pinvalue(uint8_t pin, uint8_t value) { // #ifdef ENABLE_IO_MODULES @@ -1820,86 +1695,13 @@ void io_set_pinvalue(uint8_t pin, uint8_t value) } } } -/* -uint8_t io_get_analog(uint8_t pin) -{ - switch (pin) - { -#if ASSERT_PIN(ANALOG0) - case ANALOG0: - return mcu_get_analog(ANALOG0); -#endif -#if ASSERT_PIN(ANALOG1) - case ANALOG1: - return mcu_get_analog(ANALOG1); -#endif -#if ASSERT_PIN(ANALOG2) - case ANALOG2: - return mcu_get_analog(ANALOG2); -#endif -#if ASSERT_PIN(ANALOG3) - case ANALOG3: - return mcu_get_analog(ANALOG3); -#endif -#if ASSERT_PIN(ANALOG4) - case ANALOG4: - return mcu_get_analog(ANALOG4); -#endif -#if ASSERT_PIN(ANALOG5) - case ANALOG5: - return mcu_get_analog(ANALOG5); -#endif -#if ASSERT_PIN(ANALOG6) - case ANALOG6: - return mcu_get_analog(ANALOG6); -#endif -#if ASSERT_PIN(ANALOG7) - case ANALOG7: - return mcu_get_analog(ANALOG7); -#endif -#if ASSERT_PIN(ANALOG8) - case ANALOG8: - return mcu_get_analog(ANALOG8); -#endif -#if ASSERT_PIN(ANALOG9) - case ANALOG9: - return mcu_get_analog(ANALOG9); -#endif -#if ASSERT_PIN(ANALOG10) - case ANALOG10: - return mcu_get_analog(ANALOG10); -#endif -#if ASSERT_PIN(ANALOG11) - case ANALOG11: - return mcu_get_analog(ANALOG11); -#endif -#if ASSERT_PIN(ANALOG12) - case ANALOG12: - return mcu_get_analog(ANALOG12); -#endif -#if ASSERT_PIN(ANALOG13) - case ANALOG13: - return mcu_get_analog(ANALOG13); -#endif -#if ASSERT_PIN(ANALOG14) - case ANALOG14: - return mcu_get_analog(ANALOG14); -#endif -#if ASSERT_PIN(ANALOG15) - case ANALOG15: - return mcu_get_analog(ANALOG15); -#endif - } - - return 0; -}*/ int16_t io_get_pinvalue(uint8_t pin) { switch (pin) { #if ASSERT_PIN(STEP0) - case ABS(STEP0): + case STEP0: return (io_get_output(STEP0) != 0); #endif #if ASSERT_PIN(STEP1) diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h index 58b712d20..11f6e3e8f 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h @@ -51,13 +51,19 @@ extern "C" #define DOUT8_BIT 21 #define DOUT9_BIT 16 #define DOUT10_BIT 17 + +// bitbanging 74hc595 (not used) // uses 3 x 74HS595 -#define IC74HC595_COUNT 1 +// #define IC74HC595_COUNT 1 +// #define IC74HC595_DELAY_CYCLES 0 #define IC74HC595_CUSTOM_SHIFT_IO //Enables custom MCU data shift transmission. In ESP32 that is via I2S #define IC74HC595_I2S_WS 17 #define IC74HC595_I2S_CLK 16 #define IC74HC595_I2S_DATA 21 +// #define IC74HC595_I2S_PORT 0 +// uses 1 x 74HS595 but for I2S use this value has to be set to 4 (I2S sends data as 32-bit (4bytes)) +#define IC74HC595_COUNT 4 #define STEP0_EN_IO_OFFSET 0 #define STEP0_IO_OFFSET 1 diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h index b250accfb..371e5dcc5 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h @@ -47,8 +47,10 @@ extern "C" #define DOUT8_BIT 27 #define DOUT9_BIT 25 #define DOUT10_BIT 26 + +// bitbanging 74hc595 (not used) // uses 3 x 74HS595 -#define IC74HC595_COUNT 3 +// #define IC74HC595_COUNT 3 // #define IC74HC595_DELAY_CYCLES 0 //Use I2S to shift data in ESP32 @@ -57,6 +59,8 @@ extern "C" #define IC74HC595_I2S_CLK 25 #define IC74HC595_I2S_DATA 27 // #define IC74HC595_I2S_PORT 0 +// uses 3 x 74HS595 but for I2S use this value has to be set to 4 (I2S sends data as 32-bit (4bytes)) +#define IC74HC595_COUNT 4 #define STEP0_EN_IO_OFFSET 0 #define STEP0_IO_OFFSET 1 diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index b0eab5b8d..1fd5a9128 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -8,21 +8,21 @@ extern "C" #endif /*IO HAL*/ -#if ASSERT_PIN_IO(1) -#define io1_config_output mcu_config_output(1) -#define io1_set_output mcu_set_output(1) -#define io1_clear_output mcu_clear_output(1) -#define io1_toggle_output mcu_toggle_output(1) -#define io1_get_output mcu_get_output(1) -#define io1_config_input mcu_config_input(1) -#define io1_config_pullup mcu_config_pullup(1) -#define io1_get_input mcu_get_input(1) -#elif ASSERT_PIN_EXTENDED(1) +#if ASSERT_PIN_IO(STEP0) +#define io1_config_output mcu_config_output(STEP0) +#define io1_set_output mcu_set_output(STEP0) +#define io1_clear_output mcu_clear_output(STEP0) +#define io1_toggle_output mcu_toggle_output(STEP0) +#define io1_get_output mcu_get_output(STEP0) +#define io1_config_input mcu_config_input(STEP0) +#define io1_config_pullup mcu_config_pullup(STEP0) +#define io1_get_input mcu_get_input(STEP0) +#elif ASSERT_PIN_EXTENDED(STEP0) #define io1_config_output -#define io1_set_output ic74hc595_set_pin(1);ic74hc595_shift_io_pins() -#define io1_clear_output ic74hc595_clear_pin(1);ic74hc595_shift_io_pins() -#define io1_toggle_output ic74hc595_toggle_pin(1);ic74hc595_shift_io_pins() -#define io1_get_output ic74hc595_get_pin(1) +#define io1_set_output ic74hc595_set_pin(STEP0);ic74hc595_shift_io_pins() +#define io1_clear_output ic74hc595_clear_pin(STEP0);ic74hc595_shift_io_pins() +#define io1_toggle_output ic74hc595_toggle_pin(STEP0);ic74hc595_shift_io_pins() +#define io1_get_output ic74hc595_get_pin(STEP0) #define io1_config_input #define io1_config_pullup #define io1_get_input 0 @@ -36,21 +36,21 @@ extern "C" #define io1_config_pullup #define io1_get_input 0 #endif -#if ASSERT_PIN_IO(2) -#define io2_config_output mcu_config_output(2) -#define io2_set_output mcu_set_output(2) -#define io2_clear_output mcu_clear_output(2) -#define io2_toggle_output mcu_toggle_output(2) -#define io2_get_output mcu_get_output(2) -#define io2_config_input mcu_config_input(2) -#define io2_config_pullup mcu_config_pullup(2) -#define io2_get_input mcu_get_input(2) -#elif ASSERT_PIN_EXTENDED(2) +#if ASSERT_PIN_IO(STEP1) +#define io2_config_output mcu_config_output(STEP1) +#define io2_set_output mcu_set_output(STEP1) +#define io2_clear_output mcu_clear_output(STEP1) +#define io2_toggle_output mcu_toggle_output(STEP1) +#define io2_get_output mcu_get_output(STEP1) +#define io2_config_input mcu_config_input(STEP1) +#define io2_config_pullup mcu_config_pullup(STEP1) +#define io2_get_input mcu_get_input(STEP1) +#elif ASSERT_PIN_EXTENDED(STEP1) #define io2_config_output -#define io2_set_output ic74hc595_set_pin(2);ic74hc595_shift_io_pins() -#define io2_clear_output ic74hc595_clear_pin(2);ic74hc595_shift_io_pins() -#define io2_toggle_output ic74hc595_toggle_pin(2);ic74hc595_shift_io_pins() -#define io2_get_output ic74hc595_get_pin(2) +#define io2_set_output ic74hc595_set_pin(STEP1);ic74hc595_shift_io_pins() +#define io2_clear_output ic74hc595_clear_pin(STEP1);ic74hc595_shift_io_pins() +#define io2_toggle_output ic74hc595_toggle_pin(STEP1);ic74hc595_shift_io_pins() +#define io2_get_output ic74hc595_get_pin(STEP1) #define io2_config_input #define io2_config_pullup #define io2_get_input 0 @@ -64,21 +64,21 @@ extern "C" #define io2_config_pullup #define io2_get_input 0 #endif -#if ASSERT_PIN_IO(3) -#define io3_config_output mcu_config_output(3) -#define io3_set_output mcu_set_output(3) -#define io3_clear_output mcu_clear_output(3) -#define io3_toggle_output mcu_toggle_output(3) -#define io3_get_output mcu_get_output(3) -#define io3_config_input mcu_config_input(3) -#define io3_config_pullup mcu_config_pullup(3) -#define io3_get_input mcu_get_input(3) -#elif ASSERT_PIN_EXTENDED(3) +#if ASSERT_PIN_IO(STEP2) +#define io3_config_output mcu_config_output(STEP2) +#define io3_set_output mcu_set_output(STEP2) +#define io3_clear_output mcu_clear_output(STEP2) +#define io3_toggle_output mcu_toggle_output(STEP2) +#define io3_get_output mcu_get_output(STEP2) +#define io3_config_input mcu_config_input(STEP2) +#define io3_config_pullup mcu_config_pullup(STEP2) +#define io3_get_input mcu_get_input(STEP2) +#elif ASSERT_PIN_EXTENDED(STEP2) #define io3_config_output -#define io3_set_output ic74hc595_set_pin(3);ic74hc595_shift_io_pins() -#define io3_clear_output ic74hc595_clear_pin(3);ic74hc595_shift_io_pins() -#define io3_toggle_output ic74hc595_toggle_pin(3);ic74hc595_shift_io_pins() -#define io3_get_output ic74hc595_get_pin(3) +#define io3_set_output ic74hc595_set_pin(STEP2);ic74hc595_shift_io_pins() +#define io3_clear_output ic74hc595_clear_pin(STEP2);ic74hc595_shift_io_pins() +#define io3_toggle_output ic74hc595_toggle_pin(STEP2);ic74hc595_shift_io_pins() +#define io3_get_output ic74hc595_get_pin(STEP2) #define io3_config_input #define io3_config_pullup #define io3_get_input 0 @@ -92,21 +92,21 @@ extern "C" #define io3_config_pullup #define io3_get_input 0 #endif -#if ASSERT_PIN_IO(4) -#define io4_config_output mcu_config_output(4) -#define io4_set_output mcu_set_output(4) -#define io4_clear_output mcu_clear_output(4) -#define io4_toggle_output mcu_toggle_output(4) -#define io4_get_output mcu_get_output(4) -#define io4_config_input mcu_config_input(4) -#define io4_config_pullup mcu_config_pullup(4) -#define io4_get_input mcu_get_input(4) -#elif ASSERT_PIN_EXTENDED(4) +#if ASSERT_PIN_IO(STEP3) +#define io4_config_output mcu_config_output(STEP3) +#define io4_set_output mcu_set_output(STEP3) +#define io4_clear_output mcu_clear_output(STEP3) +#define io4_toggle_output mcu_toggle_output(STEP3) +#define io4_get_output mcu_get_output(STEP3) +#define io4_config_input mcu_config_input(STEP3) +#define io4_config_pullup mcu_config_pullup(STEP3) +#define io4_get_input mcu_get_input(STEP3) +#elif ASSERT_PIN_EXTENDED(STEP3) #define io4_config_output -#define io4_set_output ic74hc595_set_pin(4);ic74hc595_shift_io_pins() -#define io4_clear_output ic74hc595_clear_pin(4);ic74hc595_shift_io_pins() -#define io4_toggle_output ic74hc595_toggle_pin(4);ic74hc595_shift_io_pins() -#define io4_get_output ic74hc595_get_pin(4) +#define io4_set_output ic74hc595_set_pin(STEP3);ic74hc595_shift_io_pins() +#define io4_clear_output ic74hc595_clear_pin(STEP3);ic74hc595_shift_io_pins() +#define io4_toggle_output ic74hc595_toggle_pin(STEP3);ic74hc595_shift_io_pins() +#define io4_get_output ic74hc595_get_pin(STEP3) #define io4_config_input #define io4_config_pullup #define io4_get_input 0 @@ -120,21 +120,21 @@ extern "C" #define io4_config_pullup #define io4_get_input 0 #endif -#if ASSERT_PIN_IO(5) -#define io5_config_output mcu_config_output(5) -#define io5_set_output mcu_set_output(5) -#define io5_clear_output mcu_clear_output(5) -#define io5_toggle_output mcu_toggle_output(5) -#define io5_get_output mcu_get_output(5) -#define io5_config_input mcu_config_input(5) -#define io5_config_pullup mcu_config_pullup(5) -#define io5_get_input mcu_get_input(5) -#elif ASSERT_PIN_EXTENDED(5) +#if ASSERT_PIN_IO(STEP4) +#define io5_config_output mcu_config_output(STEP4) +#define io5_set_output mcu_set_output(STEP4) +#define io5_clear_output mcu_clear_output(STEP4) +#define io5_toggle_output mcu_toggle_output(STEP4) +#define io5_get_output mcu_get_output(STEP4) +#define io5_config_input mcu_config_input(STEP4) +#define io5_config_pullup mcu_config_pullup(STEP4) +#define io5_get_input mcu_get_input(STEP4) +#elif ASSERT_PIN_EXTENDED(STEP4) #define io5_config_output -#define io5_set_output ic74hc595_set_pin(5);ic74hc595_shift_io_pins() -#define io5_clear_output ic74hc595_clear_pin(5);ic74hc595_shift_io_pins() -#define io5_toggle_output ic74hc595_toggle_pin(5);ic74hc595_shift_io_pins() -#define io5_get_output ic74hc595_get_pin(5) +#define io5_set_output ic74hc595_set_pin(STEP4);ic74hc595_shift_io_pins() +#define io5_clear_output ic74hc595_clear_pin(STEP4);ic74hc595_shift_io_pins() +#define io5_toggle_output ic74hc595_toggle_pin(STEP4);ic74hc595_shift_io_pins() +#define io5_get_output ic74hc595_get_pin(STEP4) #define io5_config_input #define io5_config_pullup #define io5_get_input 0 @@ -148,21 +148,21 @@ extern "C" #define io5_config_pullup #define io5_get_input 0 #endif -#if ASSERT_PIN_IO(6) -#define io6_config_output mcu_config_output(6) -#define io6_set_output mcu_set_output(6) -#define io6_clear_output mcu_clear_output(6) -#define io6_toggle_output mcu_toggle_output(6) -#define io6_get_output mcu_get_output(6) -#define io6_config_input mcu_config_input(6) -#define io6_config_pullup mcu_config_pullup(6) -#define io6_get_input mcu_get_input(6) -#elif ASSERT_PIN_EXTENDED(6) +#if ASSERT_PIN_IO(STEP5) +#define io6_config_output mcu_config_output(STEP5) +#define io6_set_output mcu_set_output(STEP5) +#define io6_clear_output mcu_clear_output(STEP5) +#define io6_toggle_output mcu_toggle_output(STEP5) +#define io6_get_output mcu_get_output(STEP5) +#define io6_config_input mcu_config_input(STEP5) +#define io6_config_pullup mcu_config_pullup(STEP5) +#define io6_get_input mcu_get_input(STEP5) +#elif ASSERT_PIN_EXTENDED(STEP5) #define io6_config_output -#define io6_set_output ic74hc595_set_pin(6);ic74hc595_shift_io_pins() -#define io6_clear_output ic74hc595_clear_pin(6);ic74hc595_shift_io_pins() -#define io6_toggle_output ic74hc595_toggle_pin(6);ic74hc595_shift_io_pins() -#define io6_get_output ic74hc595_get_pin(6) +#define io6_set_output ic74hc595_set_pin(STEP5);ic74hc595_shift_io_pins() +#define io6_clear_output ic74hc595_clear_pin(STEP5);ic74hc595_shift_io_pins() +#define io6_toggle_output ic74hc595_toggle_pin(STEP5);ic74hc595_shift_io_pins() +#define io6_get_output ic74hc595_get_pin(STEP5) #define io6_config_input #define io6_config_pullup #define io6_get_input 0 @@ -176,21 +176,21 @@ extern "C" #define io6_config_pullup #define io6_get_input 0 #endif -#if ASSERT_PIN_IO(7) -#define io7_config_output mcu_config_output(7) -#define io7_set_output mcu_set_output(7) -#define io7_clear_output mcu_clear_output(7) -#define io7_toggle_output mcu_toggle_output(7) -#define io7_get_output mcu_get_output(7) -#define io7_config_input mcu_config_input(7) -#define io7_config_pullup mcu_config_pullup(7) -#define io7_get_input mcu_get_input(7) -#elif ASSERT_PIN_EXTENDED(7) +#if ASSERT_PIN_IO(STEP6) +#define io7_config_output mcu_config_output(STEP6) +#define io7_set_output mcu_set_output(STEP6) +#define io7_clear_output mcu_clear_output(STEP6) +#define io7_toggle_output mcu_toggle_output(STEP6) +#define io7_get_output mcu_get_output(STEP6) +#define io7_config_input mcu_config_input(STEP6) +#define io7_config_pullup mcu_config_pullup(STEP6) +#define io7_get_input mcu_get_input(STEP6) +#elif ASSERT_PIN_EXTENDED(STEP6) #define io7_config_output -#define io7_set_output ic74hc595_set_pin(7);ic74hc595_shift_io_pins() -#define io7_clear_output ic74hc595_clear_pin(7);ic74hc595_shift_io_pins() -#define io7_toggle_output ic74hc595_toggle_pin(7);ic74hc595_shift_io_pins() -#define io7_get_output ic74hc595_get_pin(7) +#define io7_set_output ic74hc595_set_pin(STEP6);ic74hc595_shift_io_pins() +#define io7_clear_output ic74hc595_clear_pin(STEP6);ic74hc595_shift_io_pins() +#define io7_toggle_output ic74hc595_toggle_pin(STEP6);ic74hc595_shift_io_pins() +#define io7_get_output ic74hc595_get_pin(STEP6) #define io7_config_input #define io7_config_pullup #define io7_get_input 0 @@ -204,21 +204,21 @@ extern "C" #define io7_config_pullup #define io7_get_input 0 #endif -#if ASSERT_PIN_IO(8) -#define io8_config_output mcu_config_output(8) -#define io8_set_output mcu_set_output(8) -#define io8_clear_output mcu_clear_output(8) -#define io8_toggle_output mcu_toggle_output(8) -#define io8_get_output mcu_get_output(8) -#define io8_config_input mcu_config_input(8) -#define io8_config_pullup mcu_config_pullup(8) -#define io8_get_input mcu_get_input(8) -#elif ASSERT_PIN_EXTENDED(8) +#if ASSERT_PIN_IO(STEP7) +#define io8_config_output mcu_config_output(STEP7) +#define io8_set_output mcu_set_output(STEP7) +#define io8_clear_output mcu_clear_output(STEP7) +#define io8_toggle_output mcu_toggle_output(STEP7) +#define io8_get_output mcu_get_output(STEP7) +#define io8_config_input mcu_config_input(STEP7) +#define io8_config_pullup mcu_config_pullup(STEP7) +#define io8_get_input mcu_get_input(STEP7) +#elif ASSERT_PIN_EXTENDED(STEP7) #define io8_config_output -#define io8_set_output ic74hc595_set_pin(8);ic74hc595_shift_io_pins() -#define io8_clear_output ic74hc595_clear_pin(8);ic74hc595_shift_io_pins() -#define io8_toggle_output ic74hc595_toggle_pin(8);ic74hc595_shift_io_pins() -#define io8_get_output ic74hc595_get_pin(8) +#define io8_set_output ic74hc595_set_pin(STEP7);ic74hc595_shift_io_pins() +#define io8_clear_output ic74hc595_clear_pin(STEP7);ic74hc595_shift_io_pins() +#define io8_toggle_output ic74hc595_toggle_pin(STEP7);ic74hc595_shift_io_pins() +#define io8_get_output ic74hc595_get_pin(STEP7) #define io8_config_input #define io8_config_pullup #define io8_get_input 0 @@ -232,21 +232,21 @@ extern "C" #define io8_config_pullup #define io8_get_input 0 #endif -#if ASSERT_PIN_IO(9) -#define io9_config_output mcu_config_output(9) -#define io9_set_output mcu_set_output(9) -#define io9_clear_output mcu_clear_output(9) -#define io9_toggle_output mcu_toggle_output(9) -#define io9_get_output mcu_get_output(9) -#define io9_config_input mcu_config_input(9) -#define io9_config_pullup mcu_config_pullup(9) -#define io9_get_input mcu_get_input(9) -#elif ASSERT_PIN_EXTENDED(9) +#if ASSERT_PIN_IO(DIR0) +#define io9_config_output mcu_config_output(DIR0) +#define io9_set_output mcu_set_output(DIR0) +#define io9_clear_output mcu_clear_output(DIR0) +#define io9_toggle_output mcu_toggle_output(DIR0) +#define io9_get_output mcu_get_output(DIR0) +#define io9_config_input mcu_config_input(DIR0) +#define io9_config_pullup mcu_config_pullup(DIR0) +#define io9_get_input mcu_get_input(DIR0) +#elif ASSERT_PIN_EXTENDED(DIR0) #define io9_config_output -#define io9_set_output ic74hc595_set_pin(9);ic74hc595_shift_io_pins() -#define io9_clear_output ic74hc595_clear_pin(9);ic74hc595_shift_io_pins() -#define io9_toggle_output ic74hc595_toggle_pin(9);ic74hc595_shift_io_pins() -#define io9_get_output ic74hc595_get_pin(9) +#define io9_set_output ic74hc595_set_pin(DIR0);ic74hc595_shift_io_pins() +#define io9_clear_output ic74hc595_clear_pin(DIR0);ic74hc595_shift_io_pins() +#define io9_toggle_output ic74hc595_toggle_pin(DIR0);ic74hc595_shift_io_pins() +#define io9_get_output ic74hc595_get_pin(DIR0) #define io9_config_input #define io9_config_pullup #define io9_get_input 0 @@ -260,21 +260,21 @@ extern "C" #define io9_config_pullup #define io9_get_input 0 #endif -#if ASSERT_PIN_IO(10) -#define io10_config_output mcu_config_output(10) -#define io10_set_output mcu_set_output(10) -#define io10_clear_output mcu_clear_output(10) -#define io10_toggle_output mcu_toggle_output(10) -#define io10_get_output mcu_get_output(10) -#define io10_config_input mcu_config_input(10) -#define io10_config_pullup mcu_config_pullup(10) -#define io10_get_input mcu_get_input(10) -#elif ASSERT_PIN_EXTENDED(10) +#if ASSERT_PIN_IO(DIR1) +#define io10_config_output mcu_config_output(DIR1) +#define io10_set_output mcu_set_output(DIR1) +#define io10_clear_output mcu_clear_output(DIR1) +#define io10_toggle_output mcu_toggle_output(DIR1) +#define io10_get_output mcu_get_output(DIR1) +#define io10_config_input mcu_config_input(DIR1) +#define io10_config_pullup mcu_config_pullup(DIR1) +#define io10_get_input mcu_get_input(DIR1) +#elif ASSERT_PIN_EXTENDED(DIR1) #define io10_config_output -#define io10_set_output ic74hc595_set_pin(10);ic74hc595_shift_io_pins() -#define io10_clear_output ic74hc595_clear_pin(10);ic74hc595_shift_io_pins() -#define io10_toggle_output ic74hc595_toggle_pin(10);ic74hc595_shift_io_pins() -#define io10_get_output ic74hc595_get_pin(10) +#define io10_set_output ic74hc595_set_pin(DIR1);ic74hc595_shift_io_pins() +#define io10_clear_output ic74hc595_clear_pin(DIR1);ic74hc595_shift_io_pins() +#define io10_toggle_output ic74hc595_toggle_pin(DIR1);ic74hc595_shift_io_pins() +#define io10_get_output ic74hc595_get_pin(DIR1) #define io10_config_input #define io10_config_pullup #define io10_get_input 0 @@ -288,21 +288,21 @@ extern "C" #define io10_config_pullup #define io10_get_input 0 #endif -#if ASSERT_PIN_IO(11) -#define io11_config_output mcu_config_output(11) -#define io11_set_output mcu_set_output(11) -#define io11_clear_output mcu_clear_output(11) -#define io11_toggle_output mcu_toggle_output(11) -#define io11_get_output mcu_get_output(11) -#define io11_config_input mcu_config_input(11) -#define io11_config_pullup mcu_config_pullup(11) -#define io11_get_input mcu_get_input(11) -#elif ASSERT_PIN_EXTENDED(11) +#if ASSERT_PIN_IO(DIR2) +#define io11_config_output mcu_config_output(DIR2) +#define io11_set_output mcu_set_output(DIR2) +#define io11_clear_output mcu_clear_output(DIR2) +#define io11_toggle_output mcu_toggle_output(DIR2) +#define io11_get_output mcu_get_output(DIR2) +#define io11_config_input mcu_config_input(DIR2) +#define io11_config_pullup mcu_config_pullup(DIR2) +#define io11_get_input mcu_get_input(DIR2) +#elif ASSERT_PIN_EXTENDED(DIR2) #define io11_config_output -#define io11_set_output ic74hc595_set_pin(11);ic74hc595_shift_io_pins() -#define io11_clear_output ic74hc595_clear_pin(11);ic74hc595_shift_io_pins() -#define io11_toggle_output ic74hc595_toggle_pin(11);ic74hc595_shift_io_pins() -#define io11_get_output ic74hc595_get_pin(11) +#define io11_set_output ic74hc595_set_pin(DIR2);ic74hc595_shift_io_pins() +#define io11_clear_output ic74hc595_clear_pin(DIR2);ic74hc595_shift_io_pins() +#define io11_toggle_output ic74hc595_toggle_pin(DIR2);ic74hc595_shift_io_pins() +#define io11_get_output ic74hc595_get_pin(DIR2) #define io11_config_input #define io11_config_pullup #define io11_get_input 0 @@ -316,21 +316,21 @@ extern "C" #define io11_config_pullup #define io11_get_input 0 #endif -#if ASSERT_PIN_IO(12) -#define io12_config_output mcu_config_output(12) -#define io12_set_output mcu_set_output(12) -#define io12_clear_output mcu_clear_output(12) -#define io12_toggle_output mcu_toggle_output(12) -#define io12_get_output mcu_get_output(12) -#define io12_config_input mcu_config_input(12) -#define io12_config_pullup mcu_config_pullup(12) -#define io12_get_input mcu_get_input(12) -#elif ASSERT_PIN_EXTENDED(12) +#if ASSERT_PIN_IO(DIR3) +#define io12_config_output mcu_config_output(DIR3) +#define io12_set_output mcu_set_output(DIR3) +#define io12_clear_output mcu_clear_output(DIR3) +#define io12_toggle_output mcu_toggle_output(DIR3) +#define io12_get_output mcu_get_output(DIR3) +#define io12_config_input mcu_config_input(DIR3) +#define io12_config_pullup mcu_config_pullup(DIR3) +#define io12_get_input mcu_get_input(DIR3) +#elif ASSERT_PIN_EXTENDED(DIR3) #define io12_config_output -#define io12_set_output ic74hc595_set_pin(12);ic74hc595_shift_io_pins() -#define io12_clear_output ic74hc595_clear_pin(12);ic74hc595_shift_io_pins() -#define io12_toggle_output ic74hc595_toggle_pin(12);ic74hc595_shift_io_pins() -#define io12_get_output ic74hc595_get_pin(12) +#define io12_set_output ic74hc595_set_pin(DIR3);ic74hc595_shift_io_pins() +#define io12_clear_output ic74hc595_clear_pin(DIR3);ic74hc595_shift_io_pins() +#define io12_toggle_output ic74hc595_toggle_pin(DIR3);ic74hc595_shift_io_pins() +#define io12_get_output ic74hc595_get_pin(DIR3) #define io12_config_input #define io12_config_pullup #define io12_get_input 0 @@ -344,21 +344,21 @@ extern "C" #define io12_config_pullup #define io12_get_input 0 #endif -#if ASSERT_PIN_IO(13) -#define io13_config_output mcu_config_output(13) -#define io13_set_output mcu_set_output(13) -#define io13_clear_output mcu_clear_output(13) -#define io13_toggle_output mcu_toggle_output(13) -#define io13_get_output mcu_get_output(13) -#define io13_config_input mcu_config_input(13) -#define io13_config_pullup mcu_config_pullup(13) -#define io13_get_input mcu_get_input(13) -#elif ASSERT_PIN_EXTENDED(13) +#if ASSERT_PIN_IO(DIR4) +#define io13_config_output mcu_config_output(DIR4) +#define io13_set_output mcu_set_output(DIR4) +#define io13_clear_output mcu_clear_output(DIR4) +#define io13_toggle_output mcu_toggle_output(DIR4) +#define io13_get_output mcu_get_output(DIR4) +#define io13_config_input mcu_config_input(DIR4) +#define io13_config_pullup mcu_config_pullup(DIR4) +#define io13_get_input mcu_get_input(DIR4) +#elif ASSERT_PIN_EXTENDED(DIR4) #define io13_config_output -#define io13_set_output ic74hc595_set_pin(13);ic74hc595_shift_io_pins() -#define io13_clear_output ic74hc595_clear_pin(13);ic74hc595_shift_io_pins() -#define io13_toggle_output ic74hc595_toggle_pin(13);ic74hc595_shift_io_pins() -#define io13_get_output ic74hc595_get_pin(13) +#define io13_set_output ic74hc595_set_pin(DIR4);ic74hc595_shift_io_pins() +#define io13_clear_output ic74hc595_clear_pin(DIR4);ic74hc595_shift_io_pins() +#define io13_toggle_output ic74hc595_toggle_pin(DIR4);ic74hc595_shift_io_pins() +#define io13_get_output ic74hc595_get_pin(DIR4) #define io13_config_input #define io13_config_pullup #define io13_get_input 0 @@ -372,21 +372,21 @@ extern "C" #define io13_config_pullup #define io13_get_input 0 #endif -#if ASSERT_PIN_IO(14) -#define io14_config_output mcu_config_output(14) -#define io14_set_output mcu_set_output(14) -#define io14_clear_output mcu_clear_output(14) -#define io14_toggle_output mcu_toggle_output(14) -#define io14_get_output mcu_get_output(14) -#define io14_config_input mcu_config_input(14) -#define io14_config_pullup mcu_config_pullup(14) -#define io14_get_input mcu_get_input(14) -#elif ASSERT_PIN_EXTENDED(14) +#if ASSERT_PIN_IO(DIR5) +#define io14_config_output mcu_config_output(DIR5) +#define io14_set_output mcu_set_output(DIR5) +#define io14_clear_output mcu_clear_output(DIR5) +#define io14_toggle_output mcu_toggle_output(DIR5) +#define io14_get_output mcu_get_output(DIR5) +#define io14_config_input mcu_config_input(DIR5) +#define io14_config_pullup mcu_config_pullup(DIR5) +#define io14_get_input mcu_get_input(DIR5) +#elif ASSERT_PIN_EXTENDED(DIR5) #define io14_config_output -#define io14_set_output ic74hc595_set_pin(14);ic74hc595_shift_io_pins() -#define io14_clear_output ic74hc595_clear_pin(14);ic74hc595_shift_io_pins() -#define io14_toggle_output ic74hc595_toggle_pin(14);ic74hc595_shift_io_pins() -#define io14_get_output ic74hc595_get_pin(14) +#define io14_set_output ic74hc595_set_pin(DIR5);ic74hc595_shift_io_pins() +#define io14_clear_output ic74hc595_clear_pin(DIR5);ic74hc595_shift_io_pins() +#define io14_toggle_output ic74hc595_toggle_pin(DIR5);ic74hc595_shift_io_pins() +#define io14_get_output ic74hc595_get_pin(DIR5) #define io14_config_input #define io14_config_pullup #define io14_get_input 0 @@ -400,21 +400,21 @@ extern "C" #define io14_config_pullup #define io14_get_input 0 #endif -#if ASSERT_PIN_IO(15) -#define io15_config_output mcu_config_output(15) -#define io15_set_output mcu_set_output(15) -#define io15_clear_output mcu_clear_output(15) -#define io15_toggle_output mcu_toggle_output(15) -#define io15_get_output mcu_get_output(15) -#define io15_config_input mcu_config_input(15) -#define io15_config_pullup mcu_config_pullup(15) -#define io15_get_input mcu_get_input(15) -#elif ASSERT_PIN_EXTENDED(15) +#if ASSERT_PIN_IO(DIR6) +#define io15_config_output mcu_config_output(DIR6) +#define io15_set_output mcu_set_output(DIR6) +#define io15_clear_output mcu_clear_output(DIR6) +#define io15_toggle_output mcu_toggle_output(DIR6) +#define io15_get_output mcu_get_output(DIR6) +#define io15_config_input mcu_config_input(DIR6) +#define io15_config_pullup mcu_config_pullup(DIR6) +#define io15_get_input mcu_get_input(DIR6) +#elif ASSERT_PIN_EXTENDED(DIR6) #define io15_config_output -#define io15_set_output ic74hc595_set_pin(15);ic74hc595_shift_io_pins() -#define io15_clear_output ic74hc595_clear_pin(15);ic74hc595_shift_io_pins() -#define io15_toggle_output ic74hc595_toggle_pin(15);ic74hc595_shift_io_pins() -#define io15_get_output ic74hc595_get_pin(15) +#define io15_set_output ic74hc595_set_pin(DIR6);ic74hc595_shift_io_pins() +#define io15_clear_output ic74hc595_clear_pin(DIR6);ic74hc595_shift_io_pins() +#define io15_toggle_output ic74hc595_toggle_pin(DIR6);ic74hc595_shift_io_pins() +#define io15_get_output ic74hc595_get_pin(DIR6) #define io15_config_input #define io15_config_pullup #define io15_get_input 0 @@ -428,21 +428,21 @@ extern "C" #define io15_config_pullup #define io15_get_input 0 #endif -#if ASSERT_PIN_IO(16) -#define io16_config_output mcu_config_output(16) -#define io16_set_output mcu_set_output(16) -#define io16_clear_output mcu_clear_output(16) -#define io16_toggle_output mcu_toggle_output(16) -#define io16_get_output mcu_get_output(16) -#define io16_config_input mcu_config_input(16) -#define io16_config_pullup mcu_config_pullup(16) -#define io16_get_input mcu_get_input(16) -#elif ASSERT_PIN_EXTENDED(16) +#if ASSERT_PIN_IO(DIR7) +#define io16_config_output mcu_config_output(DIR7) +#define io16_set_output mcu_set_output(DIR7) +#define io16_clear_output mcu_clear_output(DIR7) +#define io16_toggle_output mcu_toggle_output(DIR7) +#define io16_get_output mcu_get_output(DIR7) +#define io16_config_input mcu_config_input(DIR7) +#define io16_config_pullup mcu_config_pullup(DIR7) +#define io16_get_input mcu_get_input(DIR7) +#elif ASSERT_PIN_EXTENDED(DIR7) #define io16_config_output -#define io16_set_output ic74hc595_set_pin(16);ic74hc595_shift_io_pins() -#define io16_clear_output ic74hc595_clear_pin(16);ic74hc595_shift_io_pins() -#define io16_toggle_output ic74hc595_toggle_pin(16);ic74hc595_shift_io_pins() -#define io16_get_output ic74hc595_get_pin(16) +#define io16_set_output ic74hc595_set_pin(DIR7);ic74hc595_shift_io_pins() +#define io16_clear_output ic74hc595_clear_pin(DIR7);ic74hc595_shift_io_pins() +#define io16_toggle_output ic74hc595_toggle_pin(DIR7);ic74hc595_shift_io_pins() +#define io16_get_output ic74hc595_get_pin(DIR7) #define io16_config_input #define io16_config_pullup #define io16_get_input 0 @@ -456,21 +456,21 @@ extern "C" #define io16_config_pullup #define io16_get_input 0 #endif -#if ASSERT_PIN_IO(17) -#define io17_config_output mcu_config_output(17) -#define io17_set_output mcu_set_output(17) -#define io17_clear_output mcu_clear_output(17) -#define io17_toggle_output mcu_toggle_output(17) -#define io17_get_output mcu_get_output(17) -#define io17_config_input mcu_config_input(17) -#define io17_config_pullup mcu_config_pullup(17) -#define io17_get_input mcu_get_input(17) -#elif ASSERT_PIN_EXTENDED(17) +#if ASSERT_PIN_IO(STEP0_EN) +#define io17_config_output mcu_config_output(STEP0_EN) +#define io17_set_output mcu_set_output(STEP0_EN) +#define io17_clear_output mcu_clear_output(STEP0_EN) +#define io17_toggle_output mcu_toggle_output(STEP0_EN) +#define io17_get_output mcu_get_output(STEP0_EN) +#define io17_config_input mcu_config_input(STEP0_EN) +#define io17_config_pullup mcu_config_pullup(STEP0_EN) +#define io17_get_input mcu_get_input(STEP0_EN) +#elif ASSERT_PIN_EXTENDED(STEP0_EN) #define io17_config_output -#define io17_set_output ic74hc595_set_pin(17);ic74hc595_shift_io_pins() -#define io17_clear_output ic74hc595_clear_pin(17);ic74hc595_shift_io_pins() -#define io17_toggle_output ic74hc595_toggle_pin(17);ic74hc595_shift_io_pins() -#define io17_get_output ic74hc595_get_pin(17) +#define io17_set_output ic74hc595_set_pin(STEP0_EN);ic74hc595_shift_io_pins() +#define io17_clear_output ic74hc595_clear_pin(STEP0_EN);ic74hc595_shift_io_pins() +#define io17_toggle_output ic74hc595_toggle_pin(STEP0_EN);ic74hc595_shift_io_pins() +#define io17_get_output ic74hc595_get_pin(STEP0_EN) #define io17_config_input #define io17_config_pullup #define io17_get_input 0 @@ -484,21 +484,21 @@ extern "C" #define io17_config_pullup #define io17_get_input 0 #endif -#if ASSERT_PIN_IO(18) -#define io18_config_output mcu_config_output(18) -#define io18_set_output mcu_set_output(18) -#define io18_clear_output mcu_clear_output(18) -#define io18_toggle_output mcu_toggle_output(18) -#define io18_get_output mcu_get_output(18) -#define io18_config_input mcu_config_input(18) -#define io18_config_pullup mcu_config_pullup(18) -#define io18_get_input mcu_get_input(18) -#elif ASSERT_PIN_EXTENDED(18) +#if ASSERT_PIN_IO(STEP1_EN) +#define io18_config_output mcu_config_output(STEP1_EN) +#define io18_set_output mcu_set_output(STEP1_EN) +#define io18_clear_output mcu_clear_output(STEP1_EN) +#define io18_toggle_output mcu_toggle_output(STEP1_EN) +#define io18_get_output mcu_get_output(STEP1_EN) +#define io18_config_input mcu_config_input(STEP1_EN) +#define io18_config_pullup mcu_config_pullup(STEP1_EN) +#define io18_get_input mcu_get_input(STEP1_EN) +#elif ASSERT_PIN_EXTENDED(STEP1_EN) #define io18_config_output -#define io18_set_output ic74hc595_set_pin(18);ic74hc595_shift_io_pins() -#define io18_clear_output ic74hc595_clear_pin(18);ic74hc595_shift_io_pins() -#define io18_toggle_output ic74hc595_toggle_pin(18);ic74hc595_shift_io_pins() -#define io18_get_output ic74hc595_get_pin(18) +#define io18_set_output ic74hc595_set_pin(STEP1_EN);ic74hc595_shift_io_pins() +#define io18_clear_output ic74hc595_clear_pin(STEP1_EN);ic74hc595_shift_io_pins() +#define io18_toggle_output ic74hc595_toggle_pin(STEP1_EN);ic74hc595_shift_io_pins() +#define io18_get_output ic74hc595_get_pin(STEP1_EN) #define io18_config_input #define io18_config_pullup #define io18_get_input 0 @@ -512,21 +512,21 @@ extern "C" #define io18_config_pullup #define io18_get_input 0 #endif -#if ASSERT_PIN_IO(19) -#define io19_config_output mcu_config_output(19) -#define io19_set_output mcu_set_output(19) -#define io19_clear_output mcu_clear_output(19) -#define io19_toggle_output mcu_toggle_output(19) -#define io19_get_output mcu_get_output(19) -#define io19_config_input mcu_config_input(19) -#define io19_config_pullup mcu_config_pullup(19) -#define io19_get_input mcu_get_input(19) -#elif ASSERT_PIN_EXTENDED(19) +#if ASSERT_PIN_IO(STEP2_EN) +#define io19_config_output mcu_config_output(STEP2_EN) +#define io19_set_output mcu_set_output(STEP2_EN) +#define io19_clear_output mcu_clear_output(STEP2_EN) +#define io19_toggle_output mcu_toggle_output(STEP2_EN) +#define io19_get_output mcu_get_output(STEP2_EN) +#define io19_config_input mcu_config_input(STEP2_EN) +#define io19_config_pullup mcu_config_pullup(STEP2_EN) +#define io19_get_input mcu_get_input(STEP2_EN) +#elif ASSERT_PIN_EXTENDED(STEP2_EN) #define io19_config_output -#define io19_set_output ic74hc595_set_pin(19);ic74hc595_shift_io_pins() -#define io19_clear_output ic74hc595_clear_pin(19);ic74hc595_shift_io_pins() -#define io19_toggle_output ic74hc595_toggle_pin(19);ic74hc595_shift_io_pins() -#define io19_get_output ic74hc595_get_pin(19) +#define io19_set_output ic74hc595_set_pin(STEP2_EN);ic74hc595_shift_io_pins() +#define io19_clear_output ic74hc595_clear_pin(STEP2_EN);ic74hc595_shift_io_pins() +#define io19_toggle_output ic74hc595_toggle_pin(STEP2_EN);ic74hc595_shift_io_pins() +#define io19_get_output ic74hc595_get_pin(STEP2_EN) #define io19_config_input #define io19_config_pullup #define io19_get_input 0 @@ -540,21 +540,21 @@ extern "C" #define io19_config_pullup #define io19_get_input 0 #endif -#if ASSERT_PIN_IO(20) -#define io20_config_output mcu_config_output(20) -#define io20_set_output mcu_set_output(20) -#define io20_clear_output mcu_clear_output(20) -#define io20_toggle_output mcu_toggle_output(20) -#define io20_get_output mcu_get_output(20) -#define io20_config_input mcu_config_input(20) -#define io20_config_pullup mcu_config_pullup(20) -#define io20_get_input mcu_get_input(20) -#elif ASSERT_PIN_EXTENDED(20) +#if ASSERT_PIN_IO(STEP3_EN) +#define io20_config_output mcu_config_output(STEP3_EN) +#define io20_set_output mcu_set_output(STEP3_EN) +#define io20_clear_output mcu_clear_output(STEP3_EN) +#define io20_toggle_output mcu_toggle_output(STEP3_EN) +#define io20_get_output mcu_get_output(STEP3_EN) +#define io20_config_input mcu_config_input(STEP3_EN) +#define io20_config_pullup mcu_config_pullup(STEP3_EN) +#define io20_get_input mcu_get_input(STEP3_EN) +#elif ASSERT_PIN_EXTENDED(STEP3_EN) #define io20_config_output -#define io20_set_output ic74hc595_set_pin(20);ic74hc595_shift_io_pins() -#define io20_clear_output ic74hc595_clear_pin(20);ic74hc595_shift_io_pins() -#define io20_toggle_output ic74hc595_toggle_pin(20);ic74hc595_shift_io_pins() -#define io20_get_output ic74hc595_get_pin(20) +#define io20_set_output ic74hc595_set_pin(STEP3_EN);ic74hc595_shift_io_pins() +#define io20_clear_output ic74hc595_clear_pin(STEP3_EN);ic74hc595_shift_io_pins() +#define io20_toggle_output ic74hc595_toggle_pin(STEP3_EN);ic74hc595_shift_io_pins() +#define io20_get_output ic74hc595_get_pin(STEP3_EN) #define io20_config_input #define io20_config_pullup #define io20_get_input 0 @@ -568,21 +568,21 @@ extern "C" #define io20_config_pullup #define io20_get_input 0 #endif -#if ASSERT_PIN_IO(21) -#define io21_config_output mcu_config_output(21) -#define io21_set_output mcu_set_output(21) -#define io21_clear_output mcu_clear_output(21) -#define io21_toggle_output mcu_toggle_output(21) -#define io21_get_output mcu_get_output(21) -#define io21_config_input mcu_config_input(21) -#define io21_config_pullup mcu_config_pullup(21) -#define io21_get_input mcu_get_input(21) -#elif ASSERT_PIN_EXTENDED(21) +#if ASSERT_PIN_IO(STEP4_EN) +#define io21_config_output mcu_config_output(STEP4_EN) +#define io21_set_output mcu_set_output(STEP4_EN) +#define io21_clear_output mcu_clear_output(STEP4_EN) +#define io21_toggle_output mcu_toggle_output(STEP4_EN) +#define io21_get_output mcu_get_output(STEP4_EN) +#define io21_config_input mcu_config_input(STEP4_EN) +#define io21_config_pullup mcu_config_pullup(STEP4_EN) +#define io21_get_input mcu_get_input(STEP4_EN) +#elif ASSERT_PIN_EXTENDED(STEP4_EN) #define io21_config_output -#define io21_set_output ic74hc595_set_pin(21);ic74hc595_shift_io_pins() -#define io21_clear_output ic74hc595_clear_pin(21);ic74hc595_shift_io_pins() -#define io21_toggle_output ic74hc595_toggle_pin(21);ic74hc595_shift_io_pins() -#define io21_get_output ic74hc595_get_pin(21) +#define io21_set_output ic74hc595_set_pin(STEP4_EN);ic74hc595_shift_io_pins() +#define io21_clear_output ic74hc595_clear_pin(STEP4_EN);ic74hc595_shift_io_pins() +#define io21_toggle_output ic74hc595_toggle_pin(STEP4_EN);ic74hc595_shift_io_pins() +#define io21_get_output ic74hc595_get_pin(STEP4_EN) #define io21_config_input #define io21_config_pullup #define io21_get_input 0 @@ -596,21 +596,21 @@ extern "C" #define io21_config_pullup #define io21_get_input 0 #endif -#if ASSERT_PIN_IO(22) -#define io22_config_output mcu_config_output(22) -#define io22_set_output mcu_set_output(22) -#define io22_clear_output mcu_clear_output(22) -#define io22_toggle_output mcu_toggle_output(22) -#define io22_get_output mcu_get_output(22) -#define io22_config_input mcu_config_input(22) -#define io22_config_pullup mcu_config_pullup(22) -#define io22_get_input mcu_get_input(22) -#elif ASSERT_PIN_EXTENDED(22) +#if ASSERT_PIN_IO(STEP5_EN) +#define io22_config_output mcu_config_output(STEP5_EN) +#define io22_set_output mcu_set_output(STEP5_EN) +#define io22_clear_output mcu_clear_output(STEP5_EN) +#define io22_toggle_output mcu_toggle_output(STEP5_EN) +#define io22_get_output mcu_get_output(STEP5_EN) +#define io22_config_input mcu_config_input(STEP5_EN) +#define io22_config_pullup mcu_config_pullup(STEP5_EN) +#define io22_get_input mcu_get_input(STEP5_EN) +#elif ASSERT_PIN_EXTENDED(STEP5_EN) #define io22_config_output -#define io22_set_output ic74hc595_set_pin(22);ic74hc595_shift_io_pins() -#define io22_clear_output ic74hc595_clear_pin(22);ic74hc595_shift_io_pins() -#define io22_toggle_output ic74hc595_toggle_pin(22);ic74hc595_shift_io_pins() -#define io22_get_output ic74hc595_get_pin(22) +#define io22_set_output ic74hc595_set_pin(STEP5_EN);ic74hc595_shift_io_pins() +#define io22_clear_output ic74hc595_clear_pin(STEP5_EN);ic74hc595_shift_io_pins() +#define io22_toggle_output ic74hc595_toggle_pin(STEP5_EN);ic74hc595_shift_io_pins() +#define io22_get_output ic74hc595_get_pin(STEP5_EN) #define io22_config_input #define io22_config_pullup #define io22_get_input 0 @@ -624,21 +624,21 @@ extern "C" #define io22_config_pullup #define io22_get_input 0 #endif -#if ASSERT_PIN_IO(23) -#define io23_config_output mcu_config_output(23) -#define io23_set_output mcu_set_output(23) -#define io23_clear_output mcu_clear_output(23) -#define io23_toggle_output mcu_toggle_output(23) -#define io23_get_output mcu_get_output(23) -#define io23_config_input mcu_config_input(23) -#define io23_config_pullup mcu_config_pullup(23) -#define io23_get_input mcu_get_input(23) -#elif ASSERT_PIN_EXTENDED(23) +#if ASSERT_PIN_IO(STEP6_EN) +#define io23_config_output mcu_config_output(STEP6_EN) +#define io23_set_output mcu_set_output(STEP6_EN) +#define io23_clear_output mcu_clear_output(STEP6_EN) +#define io23_toggle_output mcu_toggle_output(STEP6_EN) +#define io23_get_output mcu_get_output(STEP6_EN) +#define io23_config_input mcu_config_input(STEP6_EN) +#define io23_config_pullup mcu_config_pullup(STEP6_EN) +#define io23_get_input mcu_get_input(STEP6_EN) +#elif ASSERT_PIN_EXTENDED(STEP6_EN) #define io23_config_output -#define io23_set_output ic74hc595_set_pin(23);ic74hc595_shift_io_pins() -#define io23_clear_output ic74hc595_clear_pin(23);ic74hc595_shift_io_pins() -#define io23_toggle_output ic74hc595_toggle_pin(23);ic74hc595_shift_io_pins() -#define io23_get_output ic74hc595_get_pin(23) +#define io23_set_output ic74hc595_set_pin(STEP6_EN);ic74hc595_shift_io_pins() +#define io23_clear_output ic74hc595_clear_pin(STEP6_EN);ic74hc595_shift_io_pins() +#define io23_toggle_output ic74hc595_toggle_pin(STEP6_EN);ic74hc595_shift_io_pins() +#define io23_get_output ic74hc595_get_pin(STEP6_EN) #define io23_config_input #define io23_config_pullup #define io23_get_input 0 @@ -652,21 +652,21 @@ extern "C" #define io23_config_pullup #define io23_get_input 0 #endif -#if ASSERT_PIN_IO(24) -#define io24_config_output mcu_config_output(24) -#define io24_set_output mcu_set_output(24) -#define io24_clear_output mcu_clear_output(24) -#define io24_toggle_output mcu_toggle_output(24) -#define io24_get_output mcu_get_output(24) -#define io24_config_input mcu_config_input(24) -#define io24_config_pullup mcu_config_pullup(24) -#define io24_get_input mcu_get_input(24) -#elif ASSERT_PIN_EXTENDED(24) +#if ASSERT_PIN_IO(STEP7_EN) +#define io24_config_output mcu_config_output(STEP7_EN) +#define io24_set_output mcu_set_output(STEP7_EN) +#define io24_clear_output mcu_clear_output(STEP7_EN) +#define io24_toggle_output mcu_toggle_output(STEP7_EN) +#define io24_get_output mcu_get_output(STEP7_EN) +#define io24_config_input mcu_config_input(STEP7_EN) +#define io24_config_pullup mcu_config_pullup(STEP7_EN) +#define io24_get_input mcu_get_input(STEP7_EN) +#elif ASSERT_PIN_EXTENDED(STEP7_EN) #define io24_config_output -#define io24_set_output ic74hc595_set_pin(24);ic74hc595_shift_io_pins() -#define io24_clear_output ic74hc595_clear_pin(24);ic74hc595_shift_io_pins() -#define io24_toggle_output ic74hc595_toggle_pin(24);ic74hc595_shift_io_pins() -#define io24_get_output ic74hc595_get_pin(24) +#define io24_set_output ic74hc595_set_pin(STEP7_EN);ic74hc595_shift_io_pins() +#define io24_clear_output ic74hc595_clear_pin(STEP7_EN);ic74hc595_shift_io_pins() +#define io24_toggle_output ic74hc595_toggle_pin(STEP7_EN);ic74hc595_shift_io_pins() +#define io24_get_output ic74hc595_get_pin(STEP7_EN) #define io24_config_input #define io24_config_pullup #define io24_get_input 0 @@ -680,21 +680,21 @@ extern "C" #define io24_config_pullup #define io24_get_input 0 #endif -#if ASSERT_PIN_IO(25) -#define io25_config_output mcu_config_output(25) -#define io25_set_output mcu_set_output(25) -#define io25_clear_output mcu_clear_output(25) -#define io25_toggle_output mcu_toggle_output(25) -#define io25_get_output mcu_get_output(25) -#define io25_config_input mcu_config_input(25) -#define io25_config_pullup mcu_config_pullup(25) -#define io25_get_input mcu_get_input(25) -#elif ASSERT_PIN_EXTENDED(25) +#if ASSERT_PIN_IO(PWM0) +#define io25_config_output mcu_config_output(PWM0) +#define io25_set_output mcu_set_output(PWM0) +#define io25_clear_output mcu_clear_output(PWM0) +#define io25_toggle_output mcu_toggle_output(PWM0) +#define io25_get_output mcu_get_output(PWM0) +#define io25_config_input mcu_config_input(PWM0) +#define io25_config_pullup mcu_config_pullup(PWM0) +#define io25_get_input mcu_get_input(PWM0) +#elif ASSERT_PIN_EXTENDED(PWM0) #define io25_config_output -#define io25_set_output ic74hc595_set_pin(25);ic74hc595_shift_io_pins() -#define io25_clear_output ic74hc595_clear_pin(25);ic74hc595_shift_io_pins() -#define io25_toggle_output ic74hc595_toggle_pin(25);ic74hc595_shift_io_pins() -#define io25_get_output ic74hc595_get_pin(25) +#define io25_set_output ic74hc595_set_pin(PWM0);ic74hc595_shift_io_pins() +#define io25_clear_output ic74hc595_clear_pin(PWM0);ic74hc595_shift_io_pins() +#define io25_toggle_output ic74hc595_toggle_pin(PWM0);ic74hc595_shift_io_pins() +#define io25_get_output ic74hc595_get_pin(PWM0) #define io25_config_input #define io25_config_pullup #define io25_get_input 0 @@ -708,21 +708,21 @@ extern "C" #define io25_config_pullup #define io25_get_input 0 #endif -#if ASSERT_PIN_IO(26) -#define io26_config_output mcu_config_output(26) -#define io26_set_output mcu_set_output(26) -#define io26_clear_output mcu_clear_output(26) -#define io26_toggle_output mcu_toggle_output(26) -#define io26_get_output mcu_get_output(26) -#define io26_config_input mcu_config_input(26) -#define io26_config_pullup mcu_config_pullup(26) -#define io26_get_input mcu_get_input(26) -#elif ASSERT_PIN_EXTENDED(26) +#if ASSERT_PIN_IO(PWM1) +#define io26_config_output mcu_config_output(PWM1) +#define io26_set_output mcu_set_output(PWM1) +#define io26_clear_output mcu_clear_output(PWM1) +#define io26_toggle_output mcu_toggle_output(PWM1) +#define io26_get_output mcu_get_output(PWM1) +#define io26_config_input mcu_config_input(PWM1) +#define io26_config_pullup mcu_config_pullup(PWM1) +#define io26_get_input mcu_get_input(PWM1) +#elif ASSERT_PIN_EXTENDED(PWM1) #define io26_config_output -#define io26_set_output ic74hc595_set_pin(26);ic74hc595_shift_io_pins() -#define io26_clear_output ic74hc595_clear_pin(26);ic74hc595_shift_io_pins() -#define io26_toggle_output ic74hc595_toggle_pin(26);ic74hc595_shift_io_pins() -#define io26_get_output ic74hc595_get_pin(26) +#define io26_set_output ic74hc595_set_pin(PWM1);ic74hc595_shift_io_pins() +#define io26_clear_output ic74hc595_clear_pin(PWM1);ic74hc595_shift_io_pins() +#define io26_toggle_output ic74hc595_toggle_pin(PWM1);ic74hc595_shift_io_pins() +#define io26_get_output ic74hc595_get_pin(PWM1) #define io26_config_input #define io26_config_pullup #define io26_get_input 0 @@ -736,21 +736,21 @@ extern "C" #define io26_config_pullup #define io26_get_input 0 #endif -#if ASSERT_PIN_IO(27) -#define io27_config_output mcu_config_output(27) -#define io27_set_output mcu_set_output(27) -#define io27_clear_output mcu_clear_output(27) -#define io27_toggle_output mcu_toggle_output(27) -#define io27_get_output mcu_get_output(27) -#define io27_config_input mcu_config_input(27) -#define io27_config_pullup mcu_config_pullup(27) -#define io27_get_input mcu_get_input(27) -#elif ASSERT_PIN_EXTENDED(27) +#if ASSERT_PIN_IO(PWM2) +#define io27_config_output mcu_config_output(PWM2) +#define io27_set_output mcu_set_output(PWM2) +#define io27_clear_output mcu_clear_output(PWM2) +#define io27_toggle_output mcu_toggle_output(PWM2) +#define io27_get_output mcu_get_output(PWM2) +#define io27_config_input mcu_config_input(PWM2) +#define io27_config_pullup mcu_config_pullup(PWM2) +#define io27_get_input mcu_get_input(PWM2) +#elif ASSERT_PIN_EXTENDED(PWM2) #define io27_config_output -#define io27_set_output ic74hc595_set_pin(27);ic74hc595_shift_io_pins() -#define io27_clear_output ic74hc595_clear_pin(27);ic74hc595_shift_io_pins() -#define io27_toggle_output ic74hc595_toggle_pin(27);ic74hc595_shift_io_pins() -#define io27_get_output ic74hc595_get_pin(27) +#define io27_set_output ic74hc595_set_pin(PWM2);ic74hc595_shift_io_pins() +#define io27_clear_output ic74hc595_clear_pin(PWM2);ic74hc595_shift_io_pins() +#define io27_toggle_output ic74hc595_toggle_pin(PWM2);ic74hc595_shift_io_pins() +#define io27_get_output ic74hc595_get_pin(PWM2) #define io27_config_input #define io27_config_pullup #define io27_get_input 0 @@ -764,21 +764,21 @@ extern "C" #define io27_config_pullup #define io27_get_input 0 #endif -#if ASSERT_PIN_IO(28) -#define io28_config_output mcu_config_output(28) -#define io28_set_output mcu_set_output(28) -#define io28_clear_output mcu_clear_output(28) -#define io28_toggle_output mcu_toggle_output(28) -#define io28_get_output mcu_get_output(28) -#define io28_config_input mcu_config_input(28) -#define io28_config_pullup mcu_config_pullup(28) -#define io28_get_input mcu_get_input(28) -#elif ASSERT_PIN_EXTENDED(28) +#if ASSERT_PIN_IO(PWM3) +#define io28_config_output mcu_config_output(PWM3) +#define io28_set_output mcu_set_output(PWM3) +#define io28_clear_output mcu_clear_output(PWM3) +#define io28_toggle_output mcu_toggle_output(PWM3) +#define io28_get_output mcu_get_output(PWM3) +#define io28_config_input mcu_config_input(PWM3) +#define io28_config_pullup mcu_config_pullup(PWM3) +#define io28_get_input mcu_get_input(PWM3) +#elif ASSERT_PIN_EXTENDED(PWM3) #define io28_config_output -#define io28_set_output ic74hc595_set_pin(28);ic74hc595_shift_io_pins() -#define io28_clear_output ic74hc595_clear_pin(28);ic74hc595_shift_io_pins() -#define io28_toggle_output ic74hc595_toggle_pin(28);ic74hc595_shift_io_pins() -#define io28_get_output ic74hc595_get_pin(28) +#define io28_set_output ic74hc595_set_pin(PWM3);ic74hc595_shift_io_pins() +#define io28_clear_output ic74hc595_clear_pin(PWM3);ic74hc595_shift_io_pins() +#define io28_toggle_output ic74hc595_toggle_pin(PWM3);ic74hc595_shift_io_pins() +#define io28_get_output ic74hc595_get_pin(PWM3) #define io28_config_input #define io28_config_pullup #define io28_get_input 0 @@ -792,21 +792,21 @@ extern "C" #define io28_config_pullup #define io28_get_input 0 #endif -#if ASSERT_PIN_IO(29) -#define io29_config_output mcu_config_output(29) -#define io29_set_output mcu_set_output(29) -#define io29_clear_output mcu_clear_output(29) -#define io29_toggle_output mcu_toggle_output(29) -#define io29_get_output mcu_get_output(29) -#define io29_config_input mcu_config_input(29) -#define io29_config_pullup mcu_config_pullup(29) -#define io29_get_input mcu_get_input(29) -#elif ASSERT_PIN_EXTENDED(29) +#if ASSERT_PIN_IO(PWM4) +#define io29_config_output mcu_config_output(PWM4) +#define io29_set_output mcu_set_output(PWM4) +#define io29_clear_output mcu_clear_output(PWM4) +#define io29_toggle_output mcu_toggle_output(PWM4) +#define io29_get_output mcu_get_output(PWM4) +#define io29_config_input mcu_config_input(PWM4) +#define io29_config_pullup mcu_config_pullup(PWM4) +#define io29_get_input mcu_get_input(PWM4) +#elif ASSERT_PIN_EXTENDED(PWM4) #define io29_config_output -#define io29_set_output ic74hc595_set_pin(29);ic74hc595_shift_io_pins() -#define io29_clear_output ic74hc595_clear_pin(29);ic74hc595_shift_io_pins() -#define io29_toggle_output ic74hc595_toggle_pin(29);ic74hc595_shift_io_pins() -#define io29_get_output ic74hc595_get_pin(29) +#define io29_set_output ic74hc595_set_pin(PWM4);ic74hc595_shift_io_pins() +#define io29_clear_output ic74hc595_clear_pin(PWM4);ic74hc595_shift_io_pins() +#define io29_toggle_output ic74hc595_toggle_pin(PWM4);ic74hc595_shift_io_pins() +#define io29_get_output ic74hc595_get_pin(PWM4) #define io29_config_input #define io29_config_pullup #define io29_get_input 0 @@ -820,21 +820,21 @@ extern "C" #define io29_config_pullup #define io29_get_input 0 #endif -#if ASSERT_PIN_IO(30) -#define io30_config_output mcu_config_output(30) -#define io30_set_output mcu_set_output(30) -#define io30_clear_output mcu_clear_output(30) -#define io30_toggle_output mcu_toggle_output(30) -#define io30_get_output mcu_get_output(30) -#define io30_config_input mcu_config_input(30) -#define io30_config_pullup mcu_config_pullup(30) -#define io30_get_input mcu_get_input(30) -#elif ASSERT_PIN_EXTENDED(30) +#if ASSERT_PIN_IO(PWM5) +#define io30_config_output mcu_config_output(PWM5) +#define io30_set_output mcu_set_output(PWM5) +#define io30_clear_output mcu_clear_output(PWM5) +#define io30_toggle_output mcu_toggle_output(PWM5) +#define io30_get_output mcu_get_output(PWM5) +#define io30_config_input mcu_config_input(PWM5) +#define io30_config_pullup mcu_config_pullup(PWM5) +#define io30_get_input mcu_get_input(PWM5) +#elif ASSERT_PIN_EXTENDED(PWM5) #define io30_config_output -#define io30_set_output ic74hc595_set_pin(30);ic74hc595_shift_io_pins() -#define io30_clear_output ic74hc595_clear_pin(30);ic74hc595_shift_io_pins() -#define io30_toggle_output ic74hc595_toggle_pin(30);ic74hc595_shift_io_pins() -#define io30_get_output ic74hc595_get_pin(30) +#define io30_set_output ic74hc595_set_pin(PWM5);ic74hc595_shift_io_pins() +#define io30_clear_output ic74hc595_clear_pin(PWM5);ic74hc595_shift_io_pins() +#define io30_toggle_output ic74hc595_toggle_pin(PWM5);ic74hc595_shift_io_pins() +#define io30_get_output ic74hc595_get_pin(PWM5) #define io30_config_input #define io30_config_pullup #define io30_get_input 0 @@ -848,21 +848,21 @@ extern "C" #define io30_config_pullup #define io30_get_input 0 #endif -#if ASSERT_PIN_IO(31) -#define io31_config_output mcu_config_output(31) -#define io31_set_output mcu_set_output(31) -#define io31_clear_output mcu_clear_output(31) -#define io31_toggle_output mcu_toggle_output(31) -#define io31_get_output mcu_get_output(31) -#define io31_config_input mcu_config_input(31) -#define io31_config_pullup mcu_config_pullup(31) -#define io31_get_input mcu_get_input(31) -#elif ASSERT_PIN_EXTENDED(31) +#if ASSERT_PIN_IO(PWM6) +#define io31_config_output mcu_config_output(PWM6) +#define io31_set_output mcu_set_output(PWM6) +#define io31_clear_output mcu_clear_output(PWM6) +#define io31_toggle_output mcu_toggle_output(PWM6) +#define io31_get_output mcu_get_output(PWM6) +#define io31_config_input mcu_config_input(PWM6) +#define io31_config_pullup mcu_config_pullup(PWM6) +#define io31_get_input mcu_get_input(PWM6) +#elif ASSERT_PIN_EXTENDED(PWM6) #define io31_config_output -#define io31_set_output ic74hc595_set_pin(31);ic74hc595_shift_io_pins() -#define io31_clear_output ic74hc595_clear_pin(31);ic74hc595_shift_io_pins() -#define io31_toggle_output ic74hc595_toggle_pin(31);ic74hc595_shift_io_pins() -#define io31_get_output ic74hc595_get_pin(31) +#define io31_set_output ic74hc595_set_pin(PWM6);ic74hc595_shift_io_pins() +#define io31_clear_output ic74hc595_clear_pin(PWM6);ic74hc595_shift_io_pins() +#define io31_toggle_output ic74hc595_toggle_pin(PWM6);ic74hc595_shift_io_pins() +#define io31_get_output ic74hc595_get_pin(PWM6) #define io31_config_input #define io31_config_pullup #define io31_get_input 0 @@ -876,21 +876,21 @@ extern "C" #define io31_config_pullup #define io31_get_input 0 #endif -#if ASSERT_PIN_IO(32) -#define io32_config_output mcu_config_output(32) -#define io32_set_output mcu_set_output(32) -#define io32_clear_output mcu_clear_output(32) -#define io32_toggle_output mcu_toggle_output(32) -#define io32_get_output mcu_get_output(32) -#define io32_config_input mcu_config_input(32) -#define io32_config_pullup mcu_config_pullup(32) -#define io32_get_input mcu_get_input(32) -#elif ASSERT_PIN_EXTENDED(32) +#if ASSERT_PIN_IO(PWM7) +#define io32_config_output mcu_config_output(PWM7) +#define io32_set_output mcu_set_output(PWM7) +#define io32_clear_output mcu_clear_output(PWM7) +#define io32_toggle_output mcu_toggle_output(PWM7) +#define io32_get_output mcu_get_output(PWM7) +#define io32_config_input mcu_config_input(PWM7) +#define io32_config_pullup mcu_config_pullup(PWM7) +#define io32_get_input mcu_get_input(PWM7) +#elif ASSERT_PIN_EXTENDED(PWM7) #define io32_config_output -#define io32_set_output ic74hc595_set_pin(32);ic74hc595_shift_io_pins() -#define io32_clear_output ic74hc595_clear_pin(32);ic74hc595_shift_io_pins() -#define io32_toggle_output ic74hc595_toggle_pin(32);ic74hc595_shift_io_pins() -#define io32_get_output ic74hc595_get_pin(32) +#define io32_set_output ic74hc595_set_pin(PWM7);ic74hc595_shift_io_pins() +#define io32_clear_output ic74hc595_clear_pin(PWM7);ic74hc595_shift_io_pins() +#define io32_toggle_output ic74hc595_toggle_pin(PWM7);ic74hc595_shift_io_pins() +#define io32_get_output ic74hc595_get_pin(PWM7) #define io32_config_input #define io32_config_pullup #define io32_get_input 0 @@ -904,21 +904,21 @@ extern "C" #define io32_config_pullup #define io32_get_input 0 #endif -#if ASSERT_PIN_IO(33) -#define io33_config_output mcu_config_output(33) -#define io33_set_output mcu_set_output(33) -#define io33_clear_output mcu_clear_output(33) -#define io33_toggle_output mcu_toggle_output(33) -#define io33_get_output mcu_get_output(33) -#define io33_config_input mcu_config_input(33) -#define io33_config_pullup mcu_config_pullup(33) -#define io33_get_input mcu_get_input(33) -#elif ASSERT_PIN_EXTENDED(33) +#if ASSERT_PIN_IO(PWM8) +#define io33_config_output mcu_config_output(PWM8) +#define io33_set_output mcu_set_output(PWM8) +#define io33_clear_output mcu_clear_output(PWM8) +#define io33_toggle_output mcu_toggle_output(PWM8) +#define io33_get_output mcu_get_output(PWM8) +#define io33_config_input mcu_config_input(PWM8) +#define io33_config_pullup mcu_config_pullup(PWM8) +#define io33_get_input mcu_get_input(PWM8) +#elif ASSERT_PIN_EXTENDED(PWM8) #define io33_config_output -#define io33_set_output ic74hc595_set_pin(33);ic74hc595_shift_io_pins() -#define io33_clear_output ic74hc595_clear_pin(33);ic74hc595_shift_io_pins() -#define io33_toggle_output ic74hc595_toggle_pin(33);ic74hc595_shift_io_pins() -#define io33_get_output ic74hc595_get_pin(33) +#define io33_set_output ic74hc595_set_pin(PWM8);ic74hc595_shift_io_pins() +#define io33_clear_output ic74hc595_clear_pin(PWM8);ic74hc595_shift_io_pins() +#define io33_toggle_output ic74hc595_toggle_pin(PWM8);ic74hc595_shift_io_pins() +#define io33_get_output ic74hc595_get_pin(PWM8) #define io33_config_input #define io33_config_pullup #define io33_get_input 0 @@ -932,21 +932,21 @@ extern "C" #define io33_config_pullup #define io33_get_input 0 #endif -#if ASSERT_PIN_IO(34) -#define io34_config_output mcu_config_output(34) -#define io34_set_output mcu_set_output(34) -#define io34_clear_output mcu_clear_output(34) -#define io34_toggle_output mcu_toggle_output(34) -#define io34_get_output mcu_get_output(34) -#define io34_config_input mcu_config_input(34) -#define io34_config_pullup mcu_config_pullup(34) -#define io34_get_input mcu_get_input(34) -#elif ASSERT_PIN_EXTENDED(34) +#if ASSERT_PIN_IO(PWM9) +#define io34_config_output mcu_config_output(PWM9) +#define io34_set_output mcu_set_output(PWM9) +#define io34_clear_output mcu_clear_output(PWM9) +#define io34_toggle_output mcu_toggle_output(PWM9) +#define io34_get_output mcu_get_output(PWM9) +#define io34_config_input mcu_config_input(PWM9) +#define io34_config_pullup mcu_config_pullup(PWM9) +#define io34_get_input mcu_get_input(PWM9) +#elif ASSERT_PIN_EXTENDED(PWM9) #define io34_config_output -#define io34_set_output ic74hc595_set_pin(34);ic74hc595_shift_io_pins() -#define io34_clear_output ic74hc595_clear_pin(34);ic74hc595_shift_io_pins() -#define io34_toggle_output ic74hc595_toggle_pin(34);ic74hc595_shift_io_pins() -#define io34_get_output ic74hc595_get_pin(34) +#define io34_set_output ic74hc595_set_pin(PWM9);ic74hc595_shift_io_pins() +#define io34_clear_output ic74hc595_clear_pin(PWM9);ic74hc595_shift_io_pins() +#define io34_toggle_output ic74hc595_toggle_pin(PWM9);ic74hc595_shift_io_pins() +#define io34_get_output ic74hc595_get_pin(PWM9) #define io34_config_input #define io34_config_pullup #define io34_get_input 0 @@ -960,21 +960,21 @@ extern "C" #define io34_config_pullup #define io34_get_input 0 #endif -#if ASSERT_PIN_IO(35) -#define io35_config_output mcu_config_output(35) -#define io35_set_output mcu_set_output(35) -#define io35_clear_output mcu_clear_output(35) -#define io35_toggle_output mcu_toggle_output(35) -#define io35_get_output mcu_get_output(35) -#define io35_config_input mcu_config_input(35) -#define io35_config_pullup mcu_config_pullup(35) -#define io35_get_input mcu_get_input(35) -#elif ASSERT_PIN_EXTENDED(35) +#if ASSERT_PIN_IO(PWM10) +#define io35_config_output mcu_config_output(PWM10) +#define io35_set_output mcu_set_output(PWM10) +#define io35_clear_output mcu_clear_output(PWM10) +#define io35_toggle_output mcu_toggle_output(PWM10) +#define io35_get_output mcu_get_output(PWM10) +#define io35_config_input mcu_config_input(PWM10) +#define io35_config_pullup mcu_config_pullup(PWM10) +#define io35_get_input mcu_get_input(PWM10) +#elif ASSERT_PIN_EXTENDED(PWM10) #define io35_config_output -#define io35_set_output ic74hc595_set_pin(35);ic74hc595_shift_io_pins() -#define io35_clear_output ic74hc595_clear_pin(35);ic74hc595_shift_io_pins() -#define io35_toggle_output ic74hc595_toggle_pin(35);ic74hc595_shift_io_pins() -#define io35_get_output ic74hc595_get_pin(35) +#define io35_set_output ic74hc595_set_pin(PWM10);ic74hc595_shift_io_pins() +#define io35_clear_output ic74hc595_clear_pin(PWM10);ic74hc595_shift_io_pins() +#define io35_toggle_output ic74hc595_toggle_pin(PWM10);ic74hc595_shift_io_pins() +#define io35_get_output ic74hc595_get_pin(PWM10) #define io35_config_input #define io35_config_pullup #define io35_get_input 0 @@ -988,21 +988,21 @@ extern "C" #define io35_config_pullup #define io35_get_input 0 #endif -#if ASSERT_PIN_IO(36) -#define io36_config_output mcu_config_output(36) -#define io36_set_output mcu_set_output(36) -#define io36_clear_output mcu_clear_output(36) -#define io36_toggle_output mcu_toggle_output(36) -#define io36_get_output mcu_get_output(36) -#define io36_config_input mcu_config_input(36) -#define io36_config_pullup mcu_config_pullup(36) -#define io36_get_input mcu_get_input(36) -#elif ASSERT_PIN_EXTENDED(36) +#if ASSERT_PIN_IO(PWM11) +#define io36_config_output mcu_config_output(PWM11) +#define io36_set_output mcu_set_output(PWM11) +#define io36_clear_output mcu_clear_output(PWM11) +#define io36_toggle_output mcu_toggle_output(PWM11) +#define io36_get_output mcu_get_output(PWM11) +#define io36_config_input mcu_config_input(PWM11) +#define io36_config_pullup mcu_config_pullup(PWM11) +#define io36_get_input mcu_get_input(PWM11) +#elif ASSERT_PIN_EXTENDED(PWM11) #define io36_config_output -#define io36_set_output ic74hc595_set_pin(36);ic74hc595_shift_io_pins() -#define io36_clear_output ic74hc595_clear_pin(36);ic74hc595_shift_io_pins() -#define io36_toggle_output ic74hc595_toggle_pin(36);ic74hc595_shift_io_pins() -#define io36_get_output ic74hc595_get_pin(36) +#define io36_set_output ic74hc595_set_pin(PWM11);ic74hc595_shift_io_pins() +#define io36_clear_output ic74hc595_clear_pin(PWM11);ic74hc595_shift_io_pins() +#define io36_toggle_output ic74hc595_toggle_pin(PWM11);ic74hc595_shift_io_pins() +#define io36_get_output ic74hc595_get_pin(PWM11) #define io36_config_input #define io36_config_pullup #define io36_get_input 0 @@ -1016,21 +1016,21 @@ extern "C" #define io36_config_pullup #define io36_get_input 0 #endif -#if ASSERT_PIN_IO(37) -#define io37_config_output mcu_config_output(37) -#define io37_set_output mcu_set_output(37) -#define io37_clear_output mcu_clear_output(37) -#define io37_toggle_output mcu_toggle_output(37) -#define io37_get_output mcu_get_output(37) -#define io37_config_input mcu_config_input(37) -#define io37_config_pullup mcu_config_pullup(37) -#define io37_get_input mcu_get_input(37) -#elif ASSERT_PIN_EXTENDED(37) +#if ASSERT_PIN_IO(PWM12) +#define io37_config_output mcu_config_output(PWM12) +#define io37_set_output mcu_set_output(PWM12) +#define io37_clear_output mcu_clear_output(PWM12) +#define io37_toggle_output mcu_toggle_output(PWM12) +#define io37_get_output mcu_get_output(PWM12) +#define io37_config_input mcu_config_input(PWM12) +#define io37_config_pullup mcu_config_pullup(PWM12) +#define io37_get_input mcu_get_input(PWM12) +#elif ASSERT_PIN_EXTENDED(PWM12) #define io37_config_output -#define io37_set_output ic74hc595_set_pin(37);ic74hc595_shift_io_pins() -#define io37_clear_output ic74hc595_clear_pin(37);ic74hc595_shift_io_pins() -#define io37_toggle_output ic74hc595_toggle_pin(37);ic74hc595_shift_io_pins() -#define io37_get_output ic74hc595_get_pin(37) +#define io37_set_output ic74hc595_set_pin(PWM12);ic74hc595_shift_io_pins() +#define io37_clear_output ic74hc595_clear_pin(PWM12);ic74hc595_shift_io_pins() +#define io37_toggle_output ic74hc595_toggle_pin(PWM12);ic74hc595_shift_io_pins() +#define io37_get_output ic74hc595_get_pin(PWM12) #define io37_config_input #define io37_config_pullup #define io37_get_input 0 @@ -1044,21 +1044,21 @@ extern "C" #define io37_config_pullup #define io37_get_input 0 #endif -#if ASSERT_PIN_IO(38) -#define io38_config_output mcu_config_output(38) -#define io38_set_output mcu_set_output(38) -#define io38_clear_output mcu_clear_output(38) -#define io38_toggle_output mcu_toggle_output(38) -#define io38_get_output mcu_get_output(38) -#define io38_config_input mcu_config_input(38) -#define io38_config_pullup mcu_config_pullup(38) -#define io38_get_input mcu_get_input(38) -#elif ASSERT_PIN_EXTENDED(38) +#if ASSERT_PIN_IO(PWM13) +#define io38_config_output mcu_config_output(PWM13) +#define io38_set_output mcu_set_output(PWM13) +#define io38_clear_output mcu_clear_output(PWM13) +#define io38_toggle_output mcu_toggle_output(PWM13) +#define io38_get_output mcu_get_output(PWM13) +#define io38_config_input mcu_config_input(PWM13) +#define io38_config_pullup mcu_config_pullup(PWM13) +#define io38_get_input mcu_get_input(PWM13) +#elif ASSERT_PIN_EXTENDED(PWM13) #define io38_config_output -#define io38_set_output ic74hc595_set_pin(38);ic74hc595_shift_io_pins() -#define io38_clear_output ic74hc595_clear_pin(38);ic74hc595_shift_io_pins() -#define io38_toggle_output ic74hc595_toggle_pin(38);ic74hc595_shift_io_pins() -#define io38_get_output ic74hc595_get_pin(38) +#define io38_set_output ic74hc595_set_pin(PWM13);ic74hc595_shift_io_pins() +#define io38_clear_output ic74hc595_clear_pin(PWM13);ic74hc595_shift_io_pins() +#define io38_toggle_output ic74hc595_toggle_pin(PWM13);ic74hc595_shift_io_pins() +#define io38_get_output ic74hc595_get_pin(PWM13) #define io38_config_input #define io38_config_pullup #define io38_get_input 0 @@ -1072,21 +1072,21 @@ extern "C" #define io38_config_pullup #define io38_get_input 0 #endif -#if ASSERT_PIN_IO(39) -#define io39_config_output mcu_config_output(39) -#define io39_set_output mcu_set_output(39) -#define io39_clear_output mcu_clear_output(39) -#define io39_toggle_output mcu_toggle_output(39) -#define io39_get_output mcu_get_output(39) -#define io39_config_input mcu_config_input(39) -#define io39_config_pullup mcu_config_pullup(39) -#define io39_get_input mcu_get_input(39) -#elif ASSERT_PIN_EXTENDED(39) +#if ASSERT_PIN_IO(PWM14) +#define io39_config_output mcu_config_output(PWM14) +#define io39_set_output mcu_set_output(PWM14) +#define io39_clear_output mcu_clear_output(PWM14) +#define io39_toggle_output mcu_toggle_output(PWM14) +#define io39_get_output mcu_get_output(PWM14) +#define io39_config_input mcu_config_input(PWM14) +#define io39_config_pullup mcu_config_pullup(PWM14) +#define io39_get_input mcu_get_input(PWM14) +#elif ASSERT_PIN_EXTENDED(PWM14) #define io39_config_output -#define io39_set_output ic74hc595_set_pin(39);ic74hc595_shift_io_pins() -#define io39_clear_output ic74hc595_clear_pin(39);ic74hc595_shift_io_pins() -#define io39_toggle_output ic74hc595_toggle_pin(39);ic74hc595_shift_io_pins() -#define io39_get_output ic74hc595_get_pin(39) +#define io39_set_output ic74hc595_set_pin(PWM14);ic74hc595_shift_io_pins() +#define io39_clear_output ic74hc595_clear_pin(PWM14);ic74hc595_shift_io_pins() +#define io39_toggle_output ic74hc595_toggle_pin(PWM14);ic74hc595_shift_io_pins() +#define io39_get_output ic74hc595_get_pin(PWM14) #define io39_config_input #define io39_config_pullup #define io39_get_input 0 @@ -1100,21 +1100,21 @@ extern "C" #define io39_config_pullup #define io39_get_input 0 #endif -#if ASSERT_PIN_IO(40) -#define io40_config_output mcu_config_output(40) -#define io40_set_output mcu_set_output(40) -#define io40_clear_output mcu_clear_output(40) -#define io40_toggle_output mcu_toggle_output(40) -#define io40_get_output mcu_get_output(40) -#define io40_config_input mcu_config_input(40) -#define io40_config_pullup mcu_config_pullup(40) -#define io40_get_input mcu_get_input(40) -#elif ASSERT_PIN_EXTENDED(40) +#if ASSERT_PIN_IO(PWM15) +#define io40_config_output mcu_config_output(PWM15) +#define io40_set_output mcu_set_output(PWM15) +#define io40_clear_output mcu_clear_output(PWM15) +#define io40_toggle_output mcu_toggle_output(PWM15) +#define io40_get_output mcu_get_output(PWM15) +#define io40_config_input mcu_config_input(PWM15) +#define io40_config_pullup mcu_config_pullup(PWM15) +#define io40_get_input mcu_get_input(PWM15) +#elif ASSERT_PIN_EXTENDED(PWM15) #define io40_config_output -#define io40_set_output ic74hc595_set_pin(40);ic74hc595_shift_io_pins() -#define io40_clear_output ic74hc595_clear_pin(40);ic74hc595_shift_io_pins() -#define io40_toggle_output ic74hc595_toggle_pin(40);ic74hc595_shift_io_pins() -#define io40_get_output ic74hc595_get_pin(40) +#define io40_set_output ic74hc595_set_pin(PWM15);ic74hc595_shift_io_pins() +#define io40_clear_output ic74hc595_clear_pin(PWM15);ic74hc595_shift_io_pins() +#define io40_toggle_output ic74hc595_toggle_pin(PWM15);ic74hc595_shift_io_pins() +#define io40_get_output ic74hc595_get_pin(PWM15) #define io40_config_input #define io40_config_pullup #define io40_get_input 0 @@ -1128,21 +1128,21 @@ extern "C" #define io40_config_pullup #define io40_get_input 0 #endif -#if ASSERT_PIN_IO(41) -#define io41_config_output mcu_config_output(41) -#define io41_set_output mcu_set_output(41) -#define io41_clear_output mcu_clear_output(41) -#define io41_toggle_output mcu_toggle_output(41) -#define io41_get_output mcu_get_output(41) -#define io41_config_input mcu_config_input(41) -#define io41_config_pullup mcu_config_pullup(41) -#define io41_get_input mcu_get_input(41) -#elif ASSERT_PIN_EXTENDED(41) +#if ASSERT_PIN_IO(SERVO0) +#define io41_config_output mcu_config_output(SERVO0) +#define io41_set_output mcu_set_output(SERVO0) +#define io41_clear_output mcu_clear_output(SERVO0) +#define io41_toggle_output mcu_toggle_output(SERVO0) +#define io41_get_output mcu_get_output(SERVO0) +#define io41_config_input mcu_config_input(SERVO0) +#define io41_config_pullup mcu_config_pullup(SERVO0) +#define io41_get_input mcu_get_input(SERVO0) +#elif ASSERT_PIN_EXTENDED(SERVO0) #define io41_config_output -#define io41_set_output ic74hc595_set_pin(41);ic74hc595_shift_io_pins() -#define io41_clear_output ic74hc595_clear_pin(41);ic74hc595_shift_io_pins() -#define io41_toggle_output ic74hc595_toggle_pin(41);ic74hc595_shift_io_pins() -#define io41_get_output ic74hc595_get_pin(41) +#define io41_set_output ic74hc595_set_pin(SERVO0);ic74hc595_shift_io_pins() +#define io41_clear_output ic74hc595_clear_pin(SERVO0);ic74hc595_shift_io_pins() +#define io41_toggle_output ic74hc595_toggle_pin(SERVO0);ic74hc595_shift_io_pins() +#define io41_get_output ic74hc595_get_pin(SERVO0) #define io41_config_input #define io41_config_pullup #define io41_get_input 0 @@ -1156,21 +1156,21 @@ extern "C" #define io41_config_pullup #define io41_get_input 0 #endif -#if ASSERT_PIN_IO(42) -#define io42_config_output mcu_config_output(42) -#define io42_set_output mcu_set_output(42) -#define io42_clear_output mcu_clear_output(42) -#define io42_toggle_output mcu_toggle_output(42) -#define io42_get_output mcu_get_output(42) -#define io42_config_input mcu_config_input(42) -#define io42_config_pullup mcu_config_pullup(42) -#define io42_get_input mcu_get_input(42) -#elif ASSERT_PIN_EXTENDED(42) +#if ASSERT_PIN_IO(SERVO1) +#define io42_config_output mcu_config_output(SERVO1) +#define io42_set_output mcu_set_output(SERVO1) +#define io42_clear_output mcu_clear_output(SERVO1) +#define io42_toggle_output mcu_toggle_output(SERVO1) +#define io42_get_output mcu_get_output(SERVO1) +#define io42_config_input mcu_config_input(SERVO1) +#define io42_config_pullup mcu_config_pullup(SERVO1) +#define io42_get_input mcu_get_input(SERVO1) +#elif ASSERT_PIN_EXTENDED(SERVO1) #define io42_config_output -#define io42_set_output ic74hc595_set_pin(42);ic74hc595_shift_io_pins() -#define io42_clear_output ic74hc595_clear_pin(42);ic74hc595_shift_io_pins() -#define io42_toggle_output ic74hc595_toggle_pin(42);ic74hc595_shift_io_pins() -#define io42_get_output ic74hc595_get_pin(42) +#define io42_set_output ic74hc595_set_pin(SERVO1);ic74hc595_shift_io_pins() +#define io42_clear_output ic74hc595_clear_pin(SERVO1);ic74hc595_shift_io_pins() +#define io42_toggle_output ic74hc595_toggle_pin(SERVO1);ic74hc595_shift_io_pins() +#define io42_get_output ic74hc595_get_pin(SERVO1) #define io42_config_input #define io42_config_pullup #define io42_get_input 0 @@ -1184,21 +1184,21 @@ extern "C" #define io42_config_pullup #define io42_get_input 0 #endif -#if ASSERT_PIN_IO(43) -#define io43_config_output mcu_config_output(43) -#define io43_set_output mcu_set_output(43) -#define io43_clear_output mcu_clear_output(43) -#define io43_toggle_output mcu_toggle_output(43) -#define io43_get_output mcu_get_output(43) -#define io43_config_input mcu_config_input(43) -#define io43_config_pullup mcu_config_pullup(43) -#define io43_get_input mcu_get_input(43) -#elif ASSERT_PIN_EXTENDED(43) +#if ASSERT_PIN_IO(SERVO2) +#define io43_config_output mcu_config_output(SERVO2) +#define io43_set_output mcu_set_output(SERVO2) +#define io43_clear_output mcu_clear_output(SERVO2) +#define io43_toggle_output mcu_toggle_output(SERVO2) +#define io43_get_output mcu_get_output(SERVO2) +#define io43_config_input mcu_config_input(SERVO2) +#define io43_config_pullup mcu_config_pullup(SERVO2) +#define io43_get_input mcu_get_input(SERVO2) +#elif ASSERT_PIN_EXTENDED(SERVO2) #define io43_config_output -#define io43_set_output ic74hc595_set_pin(43);ic74hc595_shift_io_pins() -#define io43_clear_output ic74hc595_clear_pin(43);ic74hc595_shift_io_pins() -#define io43_toggle_output ic74hc595_toggle_pin(43);ic74hc595_shift_io_pins() -#define io43_get_output ic74hc595_get_pin(43) +#define io43_set_output ic74hc595_set_pin(SERVO2);ic74hc595_shift_io_pins() +#define io43_clear_output ic74hc595_clear_pin(SERVO2);ic74hc595_shift_io_pins() +#define io43_toggle_output ic74hc595_toggle_pin(SERVO2);ic74hc595_shift_io_pins() +#define io43_get_output ic74hc595_get_pin(SERVO2) #define io43_config_input #define io43_config_pullup #define io43_get_input 0 @@ -1212,21 +1212,21 @@ extern "C" #define io43_config_pullup #define io43_get_input 0 #endif -#if ASSERT_PIN_IO(44) -#define io44_config_output mcu_config_output(44) -#define io44_set_output mcu_set_output(44) -#define io44_clear_output mcu_clear_output(44) -#define io44_toggle_output mcu_toggle_output(44) -#define io44_get_output mcu_get_output(44) -#define io44_config_input mcu_config_input(44) -#define io44_config_pullup mcu_config_pullup(44) -#define io44_get_input mcu_get_input(44) -#elif ASSERT_PIN_EXTENDED(44) +#if ASSERT_PIN_IO(SERVO3) +#define io44_config_output mcu_config_output(SERVO3) +#define io44_set_output mcu_set_output(SERVO3) +#define io44_clear_output mcu_clear_output(SERVO3) +#define io44_toggle_output mcu_toggle_output(SERVO3) +#define io44_get_output mcu_get_output(SERVO3) +#define io44_config_input mcu_config_input(SERVO3) +#define io44_config_pullup mcu_config_pullup(SERVO3) +#define io44_get_input mcu_get_input(SERVO3) +#elif ASSERT_PIN_EXTENDED(SERVO3) #define io44_config_output -#define io44_set_output ic74hc595_set_pin(44);ic74hc595_shift_io_pins() -#define io44_clear_output ic74hc595_clear_pin(44);ic74hc595_shift_io_pins() -#define io44_toggle_output ic74hc595_toggle_pin(44);ic74hc595_shift_io_pins() -#define io44_get_output ic74hc595_get_pin(44) +#define io44_set_output ic74hc595_set_pin(SERVO3);ic74hc595_shift_io_pins() +#define io44_clear_output ic74hc595_clear_pin(SERVO3);ic74hc595_shift_io_pins() +#define io44_toggle_output ic74hc595_toggle_pin(SERVO3);ic74hc595_shift_io_pins() +#define io44_get_output ic74hc595_get_pin(SERVO3) #define io44_config_input #define io44_config_pullup #define io44_get_input 0 @@ -1240,21 +1240,21 @@ extern "C" #define io44_config_pullup #define io44_get_input 0 #endif -#if ASSERT_PIN_IO(45) -#define io45_config_output mcu_config_output(45) -#define io45_set_output mcu_set_output(45) -#define io45_clear_output mcu_clear_output(45) -#define io45_toggle_output mcu_toggle_output(45) -#define io45_get_output mcu_get_output(45) -#define io45_config_input mcu_config_input(45) -#define io45_config_pullup mcu_config_pullup(45) -#define io45_get_input mcu_get_input(45) -#elif ASSERT_PIN_EXTENDED(45) +#if ASSERT_PIN_IO(SERVO4) +#define io45_config_output mcu_config_output(SERVO4) +#define io45_set_output mcu_set_output(SERVO4) +#define io45_clear_output mcu_clear_output(SERVO4) +#define io45_toggle_output mcu_toggle_output(SERVO4) +#define io45_get_output mcu_get_output(SERVO4) +#define io45_config_input mcu_config_input(SERVO4) +#define io45_config_pullup mcu_config_pullup(SERVO4) +#define io45_get_input mcu_get_input(SERVO4) +#elif ASSERT_PIN_EXTENDED(SERVO4) #define io45_config_output -#define io45_set_output ic74hc595_set_pin(45);ic74hc595_shift_io_pins() -#define io45_clear_output ic74hc595_clear_pin(45);ic74hc595_shift_io_pins() -#define io45_toggle_output ic74hc595_toggle_pin(45);ic74hc595_shift_io_pins() -#define io45_get_output ic74hc595_get_pin(45) +#define io45_set_output ic74hc595_set_pin(SERVO4);ic74hc595_shift_io_pins() +#define io45_clear_output ic74hc595_clear_pin(SERVO4);ic74hc595_shift_io_pins() +#define io45_toggle_output ic74hc595_toggle_pin(SERVO4);ic74hc595_shift_io_pins() +#define io45_get_output ic74hc595_get_pin(SERVO4) #define io45_config_input #define io45_config_pullup #define io45_get_input 0 @@ -1268,21 +1268,21 @@ extern "C" #define io45_config_pullup #define io45_get_input 0 #endif -#if ASSERT_PIN_IO(46) -#define io46_config_output mcu_config_output(46) -#define io46_set_output mcu_set_output(46) -#define io46_clear_output mcu_clear_output(46) -#define io46_toggle_output mcu_toggle_output(46) -#define io46_get_output mcu_get_output(46) -#define io46_config_input mcu_config_input(46) -#define io46_config_pullup mcu_config_pullup(46) -#define io46_get_input mcu_get_input(46) -#elif ASSERT_PIN_EXTENDED(46) +#if ASSERT_PIN_IO(SERVO5) +#define io46_config_output mcu_config_output(SERVO5) +#define io46_set_output mcu_set_output(SERVO5) +#define io46_clear_output mcu_clear_output(SERVO5) +#define io46_toggle_output mcu_toggle_output(SERVO5) +#define io46_get_output mcu_get_output(SERVO5) +#define io46_config_input mcu_config_input(SERVO5) +#define io46_config_pullup mcu_config_pullup(SERVO5) +#define io46_get_input mcu_get_input(SERVO5) +#elif ASSERT_PIN_EXTENDED(SERVO5) #define io46_config_output -#define io46_set_output ic74hc595_set_pin(46);ic74hc595_shift_io_pins() -#define io46_clear_output ic74hc595_clear_pin(46);ic74hc595_shift_io_pins() -#define io46_toggle_output ic74hc595_toggle_pin(46);ic74hc595_shift_io_pins() -#define io46_get_output ic74hc595_get_pin(46) +#define io46_set_output ic74hc595_set_pin(SERVO5);ic74hc595_shift_io_pins() +#define io46_clear_output ic74hc595_clear_pin(SERVO5);ic74hc595_shift_io_pins() +#define io46_toggle_output ic74hc595_toggle_pin(SERVO5);ic74hc595_shift_io_pins() +#define io46_get_output ic74hc595_get_pin(SERVO5) #define io46_config_input #define io46_config_pullup #define io46_get_input 0 @@ -1296,21 +1296,21 @@ extern "C" #define io46_config_pullup #define io46_get_input 0 #endif -#if ASSERT_PIN_IO(47) -#define io47_config_output mcu_config_output(47) -#define io47_set_output mcu_set_output(47) -#define io47_clear_output mcu_clear_output(47) -#define io47_toggle_output mcu_toggle_output(47) -#define io47_get_output mcu_get_output(47) -#define io47_config_input mcu_config_input(47) -#define io47_config_pullup mcu_config_pullup(47) -#define io47_get_input mcu_get_input(47) -#elif ASSERT_PIN_EXTENDED(47) +#if ASSERT_PIN_IO(DOUT0) +#define io47_config_output mcu_config_output(DOUT0) +#define io47_set_output mcu_set_output(DOUT0) +#define io47_clear_output mcu_clear_output(DOUT0) +#define io47_toggle_output mcu_toggle_output(DOUT0) +#define io47_get_output mcu_get_output(DOUT0) +#define io47_config_input mcu_config_input(DOUT0) +#define io47_config_pullup mcu_config_pullup(DOUT0) +#define io47_get_input mcu_get_input(DOUT0) +#elif ASSERT_PIN_EXTENDED(DOUT0) #define io47_config_output -#define io47_set_output ic74hc595_set_pin(47);ic74hc595_shift_io_pins() -#define io47_clear_output ic74hc595_clear_pin(47);ic74hc595_shift_io_pins() -#define io47_toggle_output ic74hc595_toggle_pin(47);ic74hc595_shift_io_pins() -#define io47_get_output ic74hc595_get_pin(47) +#define io47_set_output ic74hc595_set_pin(DOUT0);ic74hc595_shift_io_pins() +#define io47_clear_output ic74hc595_clear_pin(DOUT0);ic74hc595_shift_io_pins() +#define io47_toggle_output ic74hc595_toggle_pin(DOUT0);ic74hc595_shift_io_pins() +#define io47_get_output ic74hc595_get_pin(DOUT0) #define io47_config_input #define io47_config_pullup #define io47_get_input 0 @@ -1324,21 +1324,21 @@ extern "C" #define io47_config_pullup #define io47_get_input 0 #endif -#if ASSERT_PIN_IO(48) -#define io48_config_output mcu_config_output(48) -#define io48_set_output mcu_set_output(48) -#define io48_clear_output mcu_clear_output(48) -#define io48_toggle_output mcu_toggle_output(48) -#define io48_get_output mcu_get_output(48) -#define io48_config_input mcu_config_input(48) -#define io48_config_pullup mcu_config_pullup(48) -#define io48_get_input mcu_get_input(48) -#elif ASSERT_PIN_EXTENDED(48) +#if ASSERT_PIN_IO(DOUT1) +#define io48_config_output mcu_config_output(DOUT1) +#define io48_set_output mcu_set_output(DOUT1) +#define io48_clear_output mcu_clear_output(DOUT1) +#define io48_toggle_output mcu_toggle_output(DOUT1) +#define io48_get_output mcu_get_output(DOUT1) +#define io48_config_input mcu_config_input(DOUT1) +#define io48_config_pullup mcu_config_pullup(DOUT1) +#define io48_get_input mcu_get_input(DOUT1) +#elif ASSERT_PIN_EXTENDED(DOUT1) #define io48_config_output -#define io48_set_output ic74hc595_set_pin(48);ic74hc595_shift_io_pins() -#define io48_clear_output ic74hc595_clear_pin(48);ic74hc595_shift_io_pins() -#define io48_toggle_output ic74hc595_toggle_pin(48);ic74hc595_shift_io_pins() -#define io48_get_output ic74hc595_get_pin(48) +#define io48_set_output ic74hc595_set_pin(DOUT1);ic74hc595_shift_io_pins() +#define io48_clear_output ic74hc595_clear_pin(DOUT1);ic74hc595_shift_io_pins() +#define io48_toggle_output ic74hc595_toggle_pin(DOUT1);ic74hc595_shift_io_pins() +#define io48_get_output ic74hc595_get_pin(DOUT1) #define io48_config_input #define io48_config_pullup #define io48_get_input 0 @@ -1352,21 +1352,21 @@ extern "C" #define io48_config_pullup #define io48_get_input 0 #endif -#if ASSERT_PIN_IO(49) -#define io49_config_output mcu_config_output(49) -#define io49_set_output mcu_set_output(49) -#define io49_clear_output mcu_clear_output(49) -#define io49_toggle_output mcu_toggle_output(49) -#define io49_get_output mcu_get_output(49) -#define io49_config_input mcu_config_input(49) -#define io49_config_pullup mcu_config_pullup(49) -#define io49_get_input mcu_get_input(49) -#elif ASSERT_PIN_EXTENDED(49) +#if ASSERT_PIN_IO(DOUT2) +#define io49_config_output mcu_config_output(DOUT2) +#define io49_set_output mcu_set_output(DOUT2) +#define io49_clear_output mcu_clear_output(DOUT2) +#define io49_toggle_output mcu_toggle_output(DOUT2) +#define io49_get_output mcu_get_output(DOUT2) +#define io49_config_input mcu_config_input(DOUT2) +#define io49_config_pullup mcu_config_pullup(DOUT2) +#define io49_get_input mcu_get_input(DOUT2) +#elif ASSERT_PIN_EXTENDED(DOUT2) #define io49_config_output -#define io49_set_output ic74hc595_set_pin(49);ic74hc595_shift_io_pins() -#define io49_clear_output ic74hc595_clear_pin(49);ic74hc595_shift_io_pins() -#define io49_toggle_output ic74hc595_toggle_pin(49);ic74hc595_shift_io_pins() -#define io49_get_output ic74hc595_get_pin(49) +#define io49_set_output ic74hc595_set_pin(DOUT2);ic74hc595_shift_io_pins() +#define io49_clear_output ic74hc595_clear_pin(DOUT2);ic74hc595_shift_io_pins() +#define io49_toggle_output ic74hc595_toggle_pin(DOUT2);ic74hc595_shift_io_pins() +#define io49_get_output ic74hc595_get_pin(DOUT2) #define io49_config_input #define io49_config_pullup #define io49_get_input 0 @@ -1380,21 +1380,21 @@ extern "C" #define io49_config_pullup #define io49_get_input 0 #endif -#if ASSERT_PIN_IO(50) -#define io50_config_output mcu_config_output(50) -#define io50_set_output mcu_set_output(50) -#define io50_clear_output mcu_clear_output(50) -#define io50_toggle_output mcu_toggle_output(50) -#define io50_get_output mcu_get_output(50) -#define io50_config_input mcu_config_input(50) -#define io50_config_pullup mcu_config_pullup(50) -#define io50_get_input mcu_get_input(50) -#elif ASSERT_PIN_EXTENDED(50) +#if ASSERT_PIN_IO(DOUT3) +#define io50_config_output mcu_config_output(DOUT3) +#define io50_set_output mcu_set_output(DOUT3) +#define io50_clear_output mcu_clear_output(DOUT3) +#define io50_toggle_output mcu_toggle_output(DOUT3) +#define io50_get_output mcu_get_output(DOUT3) +#define io50_config_input mcu_config_input(DOUT3) +#define io50_config_pullup mcu_config_pullup(DOUT3) +#define io50_get_input mcu_get_input(DOUT3) +#elif ASSERT_PIN_EXTENDED(DOUT3) #define io50_config_output -#define io50_set_output ic74hc595_set_pin(50);ic74hc595_shift_io_pins() -#define io50_clear_output ic74hc595_clear_pin(50);ic74hc595_shift_io_pins() -#define io50_toggle_output ic74hc595_toggle_pin(50);ic74hc595_shift_io_pins() -#define io50_get_output ic74hc595_get_pin(50) +#define io50_set_output ic74hc595_set_pin(DOUT3);ic74hc595_shift_io_pins() +#define io50_clear_output ic74hc595_clear_pin(DOUT3);ic74hc595_shift_io_pins() +#define io50_toggle_output ic74hc595_toggle_pin(DOUT3);ic74hc595_shift_io_pins() +#define io50_get_output ic74hc595_get_pin(DOUT3) #define io50_config_input #define io50_config_pullup #define io50_get_input 0 @@ -1408,21 +1408,21 @@ extern "C" #define io50_config_pullup #define io50_get_input 0 #endif -#if ASSERT_PIN_IO(51) -#define io51_config_output mcu_config_output(51) -#define io51_set_output mcu_set_output(51) -#define io51_clear_output mcu_clear_output(51) -#define io51_toggle_output mcu_toggle_output(51) -#define io51_get_output mcu_get_output(51) -#define io51_config_input mcu_config_input(51) -#define io51_config_pullup mcu_config_pullup(51) -#define io51_get_input mcu_get_input(51) -#elif ASSERT_PIN_EXTENDED(51) +#if ASSERT_PIN_IO(DOUT4) +#define io51_config_output mcu_config_output(DOUT4) +#define io51_set_output mcu_set_output(DOUT4) +#define io51_clear_output mcu_clear_output(DOUT4) +#define io51_toggle_output mcu_toggle_output(DOUT4) +#define io51_get_output mcu_get_output(DOUT4) +#define io51_config_input mcu_config_input(DOUT4) +#define io51_config_pullup mcu_config_pullup(DOUT4) +#define io51_get_input mcu_get_input(DOUT4) +#elif ASSERT_PIN_EXTENDED(DOUT4) #define io51_config_output -#define io51_set_output ic74hc595_set_pin(51);ic74hc595_shift_io_pins() -#define io51_clear_output ic74hc595_clear_pin(51);ic74hc595_shift_io_pins() -#define io51_toggle_output ic74hc595_toggle_pin(51);ic74hc595_shift_io_pins() -#define io51_get_output ic74hc595_get_pin(51) +#define io51_set_output ic74hc595_set_pin(DOUT4);ic74hc595_shift_io_pins() +#define io51_clear_output ic74hc595_clear_pin(DOUT4);ic74hc595_shift_io_pins() +#define io51_toggle_output ic74hc595_toggle_pin(DOUT4);ic74hc595_shift_io_pins() +#define io51_get_output ic74hc595_get_pin(DOUT4) #define io51_config_input #define io51_config_pullup #define io51_get_input 0 @@ -1436,21 +1436,21 @@ extern "C" #define io51_config_pullup #define io51_get_input 0 #endif -#if ASSERT_PIN_IO(52) -#define io52_config_output mcu_config_output(52) -#define io52_set_output mcu_set_output(52) -#define io52_clear_output mcu_clear_output(52) -#define io52_toggle_output mcu_toggle_output(52) -#define io52_get_output mcu_get_output(52) -#define io52_config_input mcu_config_input(52) -#define io52_config_pullup mcu_config_pullup(52) -#define io52_get_input mcu_get_input(52) -#elif ASSERT_PIN_EXTENDED(52) +#if ASSERT_PIN_IO(DOUT5) +#define io52_config_output mcu_config_output(DOUT5) +#define io52_set_output mcu_set_output(DOUT5) +#define io52_clear_output mcu_clear_output(DOUT5) +#define io52_toggle_output mcu_toggle_output(DOUT5) +#define io52_get_output mcu_get_output(DOUT5) +#define io52_config_input mcu_config_input(DOUT5) +#define io52_config_pullup mcu_config_pullup(DOUT5) +#define io52_get_input mcu_get_input(DOUT5) +#elif ASSERT_PIN_EXTENDED(DOUT5) #define io52_config_output -#define io52_set_output ic74hc595_set_pin(52);ic74hc595_shift_io_pins() -#define io52_clear_output ic74hc595_clear_pin(52);ic74hc595_shift_io_pins() -#define io52_toggle_output ic74hc595_toggle_pin(52);ic74hc595_shift_io_pins() -#define io52_get_output ic74hc595_get_pin(52) +#define io52_set_output ic74hc595_set_pin(DOUT5);ic74hc595_shift_io_pins() +#define io52_clear_output ic74hc595_clear_pin(DOUT5);ic74hc595_shift_io_pins() +#define io52_toggle_output ic74hc595_toggle_pin(DOUT5);ic74hc595_shift_io_pins() +#define io52_get_output ic74hc595_get_pin(DOUT5) #define io52_config_input #define io52_config_pullup #define io52_get_input 0 @@ -1464,21 +1464,21 @@ extern "C" #define io52_config_pullup #define io52_get_input 0 #endif -#if ASSERT_PIN_IO(53) -#define io53_config_output mcu_config_output(53) -#define io53_set_output mcu_set_output(53) -#define io53_clear_output mcu_clear_output(53) -#define io53_toggle_output mcu_toggle_output(53) -#define io53_get_output mcu_get_output(53) -#define io53_config_input mcu_config_input(53) -#define io53_config_pullup mcu_config_pullup(53) -#define io53_get_input mcu_get_input(53) -#elif ASSERT_PIN_EXTENDED(53) +#if ASSERT_PIN_IO(DOUT6) +#define io53_config_output mcu_config_output(DOUT6) +#define io53_set_output mcu_set_output(DOUT6) +#define io53_clear_output mcu_clear_output(DOUT6) +#define io53_toggle_output mcu_toggle_output(DOUT6) +#define io53_get_output mcu_get_output(DOUT6) +#define io53_config_input mcu_config_input(DOUT6) +#define io53_config_pullup mcu_config_pullup(DOUT6) +#define io53_get_input mcu_get_input(DOUT6) +#elif ASSERT_PIN_EXTENDED(DOUT6) #define io53_config_output -#define io53_set_output ic74hc595_set_pin(53);ic74hc595_shift_io_pins() -#define io53_clear_output ic74hc595_clear_pin(53);ic74hc595_shift_io_pins() -#define io53_toggle_output ic74hc595_toggle_pin(53);ic74hc595_shift_io_pins() -#define io53_get_output ic74hc595_get_pin(53) +#define io53_set_output ic74hc595_set_pin(DOUT6);ic74hc595_shift_io_pins() +#define io53_clear_output ic74hc595_clear_pin(DOUT6);ic74hc595_shift_io_pins() +#define io53_toggle_output ic74hc595_toggle_pin(DOUT6);ic74hc595_shift_io_pins() +#define io53_get_output ic74hc595_get_pin(DOUT6) #define io53_config_input #define io53_config_pullup #define io53_get_input 0 @@ -1492,21 +1492,21 @@ extern "C" #define io53_config_pullup #define io53_get_input 0 #endif -#if ASSERT_PIN_IO(54) -#define io54_config_output mcu_config_output(54) -#define io54_set_output mcu_set_output(54) -#define io54_clear_output mcu_clear_output(54) -#define io54_toggle_output mcu_toggle_output(54) -#define io54_get_output mcu_get_output(54) -#define io54_config_input mcu_config_input(54) -#define io54_config_pullup mcu_config_pullup(54) -#define io54_get_input mcu_get_input(54) -#elif ASSERT_PIN_EXTENDED(54) +#if ASSERT_PIN_IO(DOUT7) +#define io54_config_output mcu_config_output(DOUT7) +#define io54_set_output mcu_set_output(DOUT7) +#define io54_clear_output mcu_clear_output(DOUT7) +#define io54_toggle_output mcu_toggle_output(DOUT7) +#define io54_get_output mcu_get_output(DOUT7) +#define io54_config_input mcu_config_input(DOUT7) +#define io54_config_pullup mcu_config_pullup(DOUT7) +#define io54_get_input mcu_get_input(DOUT7) +#elif ASSERT_PIN_EXTENDED(DOUT7) #define io54_config_output -#define io54_set_output ic74hc595_set_pin(54);ic74hc595_shift_io_pins() -#define io54_clear_output ic74hc595_clear_pin(54);ic74hc595_shift_io_pins() -#define io54_toggle_output ic74hc595_toggle_pin(54);ic74hc595_shift_io_pins() -#define io54_get_output ic74hc595_get_pin(54) +#define io54_set_output ic74hc595_set_pin(DOUT7);ic74hc595_shift_io_pins() +#define io54_clear_output ic74hc595_clear_pin(DOUT7);ic74hc595_shift_io_pins() +#define io54_toggle_output ic74hc595_toggle_pin(DOUT7);ic74hc595_shift_io_pins() +#define io54_get_output ic74hc595_get_pin(DOUT7) #define io54_config_input #define io54_config_pullup #define io54_get_input 0 @@ -1520,21 +1520,21 @@ extern "C" #define io54_config_pullup #define io54_get_input 0 #endif -#if ASSERT_PIN_IO(55) -#define io55_config_output mcu_config_output(55) -#define io55_set_output mcu_set_output(55) -#define io55_clear_output mcu_clear_output(55) -#define io55_toggle_output mcu_toggle_output(55) -#define io55_get_output mcu_get_output(55) -#define io55_config_input mcu_config_input(55) -#define io55_config_pullup mcu_config_pullup(55) -#define io55_get_input mcu_get_input(55) -#elif ASSERT_PIN_EXTENDED(55) +#if ASSERT_PIN_IO(DOUT8) +#define io55_config_output mcu_config_output(DOUT8) +#define io55_set_output mcu_set_output(DOUT8) +#define io55_clear_output mcu_clear_output(DOUT8) +#define io55_toggle_output mcu_toggle_output(DOUT8) +#define io55_get_output mcu_get_output(DOUT8) +#define io55_config_input mcu_config_input(DOUT8) +#define io55_config_pullup mcu_config_pullup(DOUT8) +#define io55_get_input mcu_get_input(DOUT8) +#elif ASSERT_PIN_EXTENDED(DOUT8) #define io55_config_output -#define io55_set_output ic74hc595_set_pin(55);ic74hc595_shift_io_pins() -#define io55_clear_output ic74hc595_clear_pin(55);ic74hc595_shift_io_pins() -#define io55_toggle_output ic74hc595_toggle_pin(55);ic74hc595_shift_io_pins() -#define io55_get_output ic74hc595_get_pin(55) +#define io55_set_output ic74hc595_set_pin(DOUT8);ic74hc595_shift_io_pins() +#define io55_clear_output ic74hc595_clear_pin(DOUT8);ic74hc595_shift_io_pins() +#define io55_toggle_output ic74hc595_toggle_pin(DOUT8);ic74hc595_shift_io_pins() +#define io55_get_output ic74hc595_get_pin(DOUT8) #define io55_config_input #define io55_config_pullup #define io55_get_input 0 @@ -1548,21 +1548,21 @@ extern "C" #define io55_config_pullup #define io55_get_input 0 #endif -#if ASSERT_PIN_IO(56) -#define io56_config_output mcu_config_output(56) -#define io56_set_output mcu_set_output(56) -#define io56_clear_output mcu_clear_output(56) -#define io56_toggle_output mcu_toggle_output(56) -#define io56_get_output mcu_get_output(56) -#define io56_config_input mcu_config_input(56) -#define io56_config_pullup mcu_config_pullup(56) -#define io56_get_input mcu_get_input(56) -#elif ASSERT_PIN_EXTENDED(56) +#if ASSERT_PIN_IO(DOUT9) +#define io56_config_output mcu_config_output(DOUT9) +#define io56_set_output mcu_set_output(DOUT9) +#define io56_clear_output mcu_clear_output(DOUT9) +#define io56_toggle_output mcu_toggle_output(DOUT9) +#define io56_get_output mcu_get_output(DOUT9) +#define io56_config_input mcu_config_input(DOUT9) +#define io56_config_pullup mcu_config_pullup(DOUT9) +#define io56_get_input mcu_get_input(DOUT9) +#elif ASSERT_PIN_EXTENDED(DOUT9) #define io56_config_output -#define io56_set_output ic74hc595_set_pin(56);ic74hc595_shift_io_pins() -#define io56_clear_output ic74hc595_clear_pin(56);ic74hc595_shift_io_pins() -#define io56_toggle_output ic74hc595_toggle_pin(56);ic74hc595_shift_io_pins() -#define io56_get_output ic74hc595_get_pin(56) +#define io56_set_output ic74hc595_set_pin(DOUT9);ic74hc595_shift_io_pins() +#define io56_clear_output ic74hc595_clear_pin(DOUT9);ic74hc595_shift_io_pins() +#define io56_toggle_output ic74hc595_toggle_pin(DOUT9);ic74hc595_shift_io_pins() +#define io56_get_output ic74hc595_get_pin(DOUT9) #define io56_config_input #define io56_config_pullup #define io56_get_input 0 @@ -1576,21 +1576,21 @@ extern "C" #define io56_config_pullup #define io56_get_input 0 #endif -#if ASSERT_PIN_IO(57) -#define io57_config_output mcu_config_output(57) -#define io57_set_output mcu_set_output(57) -#define io57_clear_output mcu_clear_output(57) -#define io57_toggle_output mcu_toggle_output(57) -#define io57_get_output mcu_get_output(57) -#define io57_config_input mcu_config_input(57) -#define io57_config_pullup mcu_config_pullup(57) -#define io57_get_input mcu_get_input(57) -#elif ASSERT_PIN_EXTENDED(57) +#if ASSERT_PIN_IO(DOUT10) +#define io57_config_output mcu_config_output(DOUT10) +#define io57_set_output mcu_set_output(DOUT10) +#define io57_clear_output mcu_clear_output(DOUT10) +#define io57_toggle_output mcu_toggle_output(DOUT10) +#define io57_get_output mcu_get_output(DOUT10) +#define io57_config_input mcu_config_input(DOUT10) +#define io57_config_pullup mcu_config_pullup(DOUT10) +#define io57_get_input mcu_get_input(DOUT10) +#elif ASSERT_PIN_EXTENDED(DOUT10) #define io57_config_output -#define io57_set_output ic74hc595_set_pin(57);ic74hc595_shift_io_pins() -#define io57_clear_output ic74hc595_clear_pin(57);ic74hc595_shift_io_pins() -#define io57_toggle_output ic74hc595_toggle_pin(57);ic74hc595_shift_io_pins() -#define io57_get_output ic74hc595_get_pin(57) +#define io57_set_output ic74hc595_set_pin(DOUT10);ic74hc595_shift_io_pins() +#define io57_clear_output ic74hc595_clear_pin(DOUT10);ic74hc595_shift_io_pins() +#define io57_toggle_output ic74hc595_toggle_pin(DOUT10);ic74hc595_shift_io_pins() +#define io57_get_output ic74hc595_get_pin(DOUT10) #define io57_config_input #define io57_config_pullup #define io57_get_input 0 @@ -1604,21 +1604,21 @@ extern "C" #define io57_config_pullup #define io57_get_input 0 #endif -#if ASSERT_PIN_IO(58) -#define io58_config_output mcu_config_output(58) -#define io58_set_output mcu_set_output(58) -#define io58_clear_output mcu_clear_output(58) -#define io58_toggle_output mcu_toggle_output(58) -#define io58_get_output mcu_get_output(58) -#define io58_config_input mcu_config_input(58) -#define io58_config_pullup mcu_config_pullup(58) -#define io58_get_input mcu_get_input(58) -#elif ASSERT_PIN_EXTENDED(58) +#if ASSERT_PIN_IO(DOUT11) +#define io58_config_output mcu_config_output(DOUT11) +#define io58_set_output mcu_set_output(DOUT11) +#define io58_clear_output mcu_clear_output(DOUT11) +#define io58_toggle_output mcu_toggle_output(DOUT11) +#define io58_get_output mcu_get_output(DOUT11) +#define io58_config_input mcu_config_input(DOUT11) +#define io58_config_pullup mcu_config_pullup(DOUT11) +#define io58_get_input mcu_get_input(DOUT11) +#elif ASSERT_PIN_EXTENDED(DOUT11) #define io58_config_output -#define io58_set_output ic74hc595_set_pin(58);ic74hc595_shift_io_pins() -#define io58_clear_output ic74hc595_clear_pin(58);ic74hc595_shift_io_pins() -#define io58_toggle_output ic74hc595_toggle_pin(58);ic74hc595_shift_io_pins() -#define io58_get_output ic74hc595_get_pin(58) +#define io58_set_output ic74hc595_set_pin(DOUT11);ic74hc595_shift_io_pins() +#define io58_clear_output ic74hc595_clear_pin(DOUT11);ic74hc595_shift_io_pins() +#define io58_toggle_output ic74hc595_toggle_pin(DOUT11);ic74hc595_shift_io_pins() +#define io58_get_output ic74hc595_get_pin(DOUT11) #define io58_config_input #define io58_config_pullup #define io58_get_input 0 @@ -1632,21 +1632,21 @@ extern "C" #define io58_config_pullup #define io58_get_input 0 #endif -#if ASSERT_PIN_IO(59) -#define io59_config_output mcu_config_output(59) -#define io59_set_output mcu_set_output(59) -#define io59_clear_output mcu_clear_output(59) -#define io59_toggle_output mcu_toggle_output(59) -#define io59_get_output mcu_get_output(59) -#define io59_config_input mcu_config_input(59) -#define io59_config_pullup mcu_config_pullup(59) -#define io59_get_input mcu_get_input(59) -#elif ASSERT_PIN_EXTENDED(59) +#if ASSERT_PIN_IO(DOUT12) +#define io59_config_output mcu_config_output(DOUT12) +#define io59_set_output mcu_set_output(DOUT12) +#define io59_clear_output mcu_clear_output(DOUT12) +#define io59_toggle_output mcu_toggle_output(DOUT12) +#define io59_get_output mcu_get_output(DOUT12) +#define io59_config_input mcu_config_input(DOUT12) +#define io59_config_pullup mcu_config_pullup(DOUT12) +#define io59_get_input mcu_get_input(DOUT12) +#elif ASSERT_PIN_EXTENDED(DOUT12) #define io59_config_output -#define io59_set_output ic74hc595_set_pin(59);ic74hc595_shift_io_pins() -#define io59_clear_output ic74hc595_clear_pin(59);ic74hc595_shift_io_pins() -#define io59_toggle_output ic74hc595_toggle_pin(59);ic74hc595_shift_io_pins() -#define io59_get_output ic74hc595_get_pin(59) +#define io59_set_output ic74hc595_set_pin(DOUT12);ic74hc595_shift_io_pins() +#define io59_clear_output ic74hc595_clear_pin(DOUT12);ic74hc595_shift_io_pins() +#define io59_toggle_output ic74hc595_toggle_pin(DOUT12);ic74hc595_shift_io_pins() +#define io59_get_output ic74hc595_get_pin(DOUT12) #define io59_config_input #define io59_config_pullup #define io59_get_input 0 @@ -1660,21 +1660,21 @@ extern "C" #define io59_config_pullup #define io59_get_input 0 #endif -#if ASSERT_PIN_IO(60) -#define io60_config_output mcu_config_output(60) -#define io60_set_output mcu_set_output(60) -#define io60_clear_output mcu_clear_output(60) -#define io60_toggle_output mcu_toggle_output(60) -#define io60_get_output mcu_get_output(60) -#define io60_config_input mcu_config_input(60) -#define io60_config_pullup mcu_config_pullup(60) -#define io60_get_input mcu_get_input(60) -#elif ASSERT_PIN_EXTENDED(60) +#if ASSERT_PIN_IO(DOUT13) +#define io60_config_output mcu_config_output(DOUT13) +#define io60_set_output mcu_set_output(DOUT13) +#define io60_clear_output mcu_clear_output(DOUT13) +#define io60_toggle_output mcu_toggle_output(DOUT13) +#define io60_get_output mcu_get_output(DOUT13) +#define io60_config_input mcu_config_input(DOUT13) +#define io60_config_pullup mcu_config_pullup(DOUT13) +#define io60_get_input mcu_get_input(DOUT13) +#elif ASSERT_PIN_EXTENDED(DOUT13) #define io60_config_output -#define io60_set_output ic74hc595_set_pin(60);ic74hc595_shift_io_pins() -#define io60_clear_output ic74hc595_clear_pin(60);ic74hc595_shift_io_pins() -#define io60_toggle_output ic74hc595_toggle_pin(60);ic74hc595_shift_io_pins() -#define io60_get_output ic74hc595_get_pin(60) +#define io60_set_output ic74hc595_set_pin(DOUT13);ic74hc595_shift_io_pins() +#define io60_clear_output ic74hc595_clear_pin(DOUT13);ic74hc595_shift_io_pins() +#define io60_toggle_output ic74hc595_toggle_pin(DOUT13);ic74hc595_shift_io_pins() +#define io60_get_output ic74hc595_get_pin(DOUT13) #define io60_config_input #define io60_config_pullup #define io60_get_input 0 @@ -1688,21 +1688,21 @@ extern "C" #define io60_config_pullup #define io60_get_input 0 #endif -#if ASSERT_PIN_IO(61) -#define io61_config_output mcu_config_output(61) -#define io61_set_output mcu_set_output(61) -#define io61_clear_output mcu_clear_output(61) -#define io61_toggle_output mcu_toggle_output(61) -#define io61_get_output mcu_get_output(61) -#define io61_config_input mcu_config_input(61) -#define io61_config_pullup mcu_config_pullup(61) -#define io61_get_input mcu_get_input(61) -#elif ASSERT_PIN_EXTENDED(61) +#if ASSERT_PIN_IO(DOUT14) +#define io61_config_output mcu_config_output(DOUT14) +#define io61_set_output mcu_set_output(DOUT14) +#define io61_clear_output mcu_clear_output(DOUT14) +#define io61_toggle_output mcu_toggle_output(DOUT14) +#define io61_get_output mcu_get_output(DOUT14) +#define io61_config_input mcu_config_input(DOUT14) +#define io61_config_pullup mcu_config_pullup(DOUT14) +#define io61_get_input mcu_get_input(DOUT14) +#elif ASSERT_PIN_EXTENDED(DOUT14) #define io61_config_output -#define io61_set_output ic74hc595_set_pin(61);ic74hc595_shift_io_pins() -#define io61_clear_output ic74hc595_clear_pin(61);ic74hc595_shift_io_pins() -#define io61_toggle_output ic74hc595_toggle_pin(61);ic74hc595_shift_io_pins() -#define io61_get_output ic74hc595_get_pin(61) +#define io61_set_output ic74hc595_set_pin(DOUT14);ic74hc595_shift_io_pins() +#define io61_clear_output ic74hc595_clear_pin(DOUT14);ic74hc595_shift_io_pins() +#define io61_toggle_output ic74hc595_toggle_pin(DOUT14);ic74hc595_shift_io_pins() +#define io61_get_output ic74hc595_get_pin(DOUT14) #define io61_config_input #define io61_config_pullup #define io61_get_input 0 @@ -1716,21 +1716,21 @@ extern "C" #define io61_config_pullup #define io61_get_input 0 #endif -#if ASSERT_PIN_IO(62) -#define io62_config_output mcu_config_output(62) -#define io62_set_output mcu_set_output(62) -#define io62_clear_output mcu_clear_output(62) -#define io62_toggle_output mcu_toggle_output(62) -#define io62_get_output mcu_get_output(62) -#define io62_config_input mcu_config_input(62) -#define io62_config_pullup mcu_config_pullup(62) -#define io62_get_input mcu_get_input(62) -#elif ASSERT_PIN_EXTENDED(62) +#if ASSERT_PIN_IO(DOUT15) +#define io62_config_output mcu_config_output(DOUT15) +#define io62_set_output mcu_set_output(DOUT15) +#define io62_clear_output mcu_clear_output(DOUT15) +#define io62_toggle_output mcu_toggle_output(DOUT15) +#define io62_get_output mcu_get_output(DOUT15) +#define io62_config_input mcu_config_input(DOUT15) +#define io62_config_pullup mcu_config_pullup(DOUT15) +#define io62_get_input mcu_get_input(DOUT15) +#elif ASSERT_PIN_EXTENDED(DOUT15) #define io62_config_output -#define io62_set_output ic74hc595_set_pin(62);ic74hc595_shift_io_pins() -#define io62_clear_output ic74hc595_clear_pin(62);ic74hc595_shift_io_pins() -#define io62_toggle_output ic74hc595_toggle_pin(62);ic74hc595_shift_io_pins() -#define io62_get_output ic74hc595_get_pin(62) +#define io62_set_output ic74hc595_set_pin(DOUT15);ic74hc595_shift_io_pins() +#define io62_clear_output ic74hc595_clear_pin(DOUT15);ic74hc595_shift_io_pins() +#define io62_toggle_output ic74hc595_toggle_pin(DOUT15);ic74hc595_shift_io_pins() +#define io62_get_output ic74hc595_get_pin(DOUT15) #define io62_config_input #define io62_config_pullup #define io62_get_input 0 @@ -1744,21 +1744,21 @@ extern "C" #define io62_config_pullup #define io62_get_input 0 #endif -#if ASSERT_PIN_IO(63) -#define io63_config_output mcu_config_output(63) -#define io63_set_output mcu_set_output(63) -#define io63_clear_output mcu_clear_output(63) -#define io63_toggle_output mcu_toggle_output(63) -#define io63_get_output mcu_get_output(63) -#define io63_config_input mcu_config_input(63) -#define io63_config_pullup mcu_config_pullup(63) -#define io63_get_input mcu_get_input(63) -#elif ASSERT_PIN_EXTENDED(63) +#if ASSERT_PIN_IO(DOUT16) +#define io63_config_output mcu_config_output(DOUT16) +#define io63_set_output mcu_set_output(DOUT16) +#define io63_clear_output mcu_clear_output(DOUT16) +#define io63_toggle_output mcu_toggle_output(DOUT16) +#define io63_get_output mcu_get_output(DOUT16) +#define io63_config_input mcu_config_input(DOUT16) +#define io63_config_pullup mcu_config_pullup(DOUT16) +#define io63_get_input mcu_get_input(DOUT16) +#elif ASSERT_PIN_EXTENDED(DOUT16) #define io63_config_output -#define io63_set_output ic74hc595_set_pin(63);ic74hc595_shift_io_pins() -#define io63_clear_output ic74hc595_clear_pin(63);ic74hc595_shift_io_pins() -#define io63_toggle_output ic74hc595_toggle_pin(63);ic74hc595_shift_io_pins() -#define io63_get_output ic74hc595_get_pin(63) +#define io63_set_output ic74hc595_set_pin(DOUT16);ic74hc595_shift_io_pins() +#define io63_clear_output ic74hc595_clear_pin(DOUT16);ic74hc595_shift_io_pins() +#define io63_toggle_output ic74hc595_toggle_pin(DOUT16);ic74hc595_shift_io_pins() +#define io63_get_output ic74hc595_get_pin(DOUT16) #define io63_config_input #define io63_config_pullup #define io63_get_input 0 @@ -1772,21 +1772,21 @@ extern "C" #define io63_config_pullup #define io63_get_input 0 #endif -#if ASSERT_PIN_IO(64) -#define io64_config_output mcu_config_output(64) -#define io64_set_output mcu_set_output(64) -#define io64_clear_output mcu_clear_output(64) -#define io64_toggle_output mcu_toggle_output(64) -#define io64_get_output mcu_get_output(64) -#define io64_config_input mcu_config_input(64) -#define io64_config_pullup mcu_config_pullup(64) -#define io64_get_input mcu_get_input(64) -#elif ASSERT_PIN_EXTENDED(64) +#if ASSERT_PIN_IO(DOUT17) +#define io64_config_output mcu_config_output(DOUT17) +#define io64_set_output mcu_set_output(DOUT17) +#define io64_clear_output mcu_clear_output(DOUT17) +#define io64_toggle_output mcu_toggle_output(DOUT17) +#define io64_get_output mcu_get_output(DOUT17) +#define io64_config_input mcu_config_input(DOUT17) +#define io64_config_pullup mcu_config_pullup(DOUT17) +#define io64_get_input mcu_get_input(DOUT17) +#elif ASSERT_PIN_EXTENDED(DOUT17) #define io64_config_output -#define io64_set_output ic74hc595_set_pin(64);ic74hc595_shift_io_pins() -#define io64_clear_output ic74hc595_clear_pin(64);ic74hc595_shift_io_pins() -#define io64_toggle_output ic74hc595_toggle_pin(64);ic74hc595_shift_io_pins() -#define io64_get_output ic74hc595_get_pin(64) +#define io64_set_output ic74hc595_set_pin(DOUT17);ic74hc595_shift_io_pins() +#define io64_clear_output ic74hc595_clear_pin(DOUT17);ic74hc595_shift_io_pins() +#define io64_toggle_output ic74hc595_toggle_pin(DOUT17);ic74hc595_shift_io_pins() +#define io64_get_output ic74hc595_get_pin(DOUT17) #define io64_config_input #define io64_config_pullup #define io64_get_input 0 @@ -1800,21 +1800,21 @@ extern "C" #define io64_config_pullup #define io64_get_input 0 #endif -#if ASSERT_PIN_IO(65) -#define io65_config_output mcu_config_output(65) -#define io65_set_output mcu_set_output(65) -#define io65_clear_output mcu_clear_output(65) -#define io65_toggle_output mcu_toggle_output(65) -#define io65_get_output mcu_get_output(65) -#define io65_config_input mcu_config_input(65) -#define io65_config_pullup mcu_config_pullup(65) -#define io65_get_input mcu_get_input(65) -#elif ASSERT_PIN_EXTENDED(65) +#if ASSERT_PIN_IO(DOUT18) +#define io65_config_output mcu_config_output(DOUT18) +#define io65_set_output mcu_set_output(DOUT18) +#define io65_clear_output mcu_clear_output(DOUT18) +#define io65_toggle_output mcu_toggle_output(DOUT18) +#define io65_get_output mcu_get_output(DOUT18) +#define io65_config_input mcu_config_input(DOUT18) +#define io65_config_pullup mcu_config_pullup(DOUT18) +#define io65_get_input mcu_get_input(DOUT18) +#elif ASSERT_PIN_EXTENDED(DOUT18) #define io65_config_output -#define io65_set_output ic74hc595_set_pin(65);ic74hc595_shift_io_pins() -#define io65_clear_output ic74hc595_clear_pin(65);ic74hc595_shift_io_pins() -#define io65_toggle_output ic74hc595_toggle_pin(65);ic74hc595_shift_io_pins() -#define io65_get_output ic74hc595_get_pin(65) +#define io65_set_output ic74hc595_set_pin(DOUT18);ic74hc595_shift_io_pins() +#define io65_clear_output ic74hc595_clear_pin(DOUT18);ic74hc595_shift_io_pins() +#define io65_toggle_output ic74hc595_toggle_pin(DOUT18);ic74hc595_shift_io_pins() +#define io65_get_output ic74hc595_get_pin(DOUT18) #define io65_config_input #define io65_config_pullup #define io65_get_input 0 @@ -1828,21 +1828,21 @@ extern "C" #define io65_config_pullup #define io65_get_input 0 #endif -#if ASSERT_PIN_IO(66) -#define io66_config_output mcu_config_output(66) -#define io66_set_output mcu_set_output(66) -#define io66_clear_output mcu_clear_output(66) -#define io66_toggle_output mcu_toggle_output(66) -#define io66_get_output mcu_get_output(66) -#define io66_config_input mcu_config_input(66) -#define io66_config_pullup mcu_config_pullup(66) -#define io66_get_input mcu_get_input(66) -#elif ASSERT_PIN_EXTENDED(66) +#if ASSERT_PIN_IO(DOUT19) +#define io66_config_output mcu_config_output(DOUT19) +#define io66_set_output mcu_set_output(DOUT19) +#define io66_clear_output mcu_clear_output(DOUT19) +#define io66_toggle_output mcu_toggle_output(DOUT19) +#define io66_get_output mcu_get_output(DOUT19) +#define io66_config_input mcu_config_input(DOUT19) +#define io66_config_pullup mcu_config_pullup(DOUT19) +#define io66_get_input mcu_get_input(DOUT19) +#elif ASSERT_PIN_EXTENDED(DOUT19) #define io66_config_output -#define io66_set_output ic74hc595_set_pin(66);ic74hc595_shift_io_pins() -#define io66_clear_output ic74hc595_clear_pin(66);ic74hc595_shift_io_pins() -#define io66_toggle_output ic74hc595_toggle_pin(66);ic74hc595_shift_io_pins() -#define io66_get_output ic74hc595_get_pin(66) +#define io66_set_output ic74hc595_set_pin(DOUT19);ic74hc595_shift_io_pins() +#define io66_clear_output ic74hc595_clear_pin(DOUT19);ic74hc595_shift_io_pins() +#define io66_toggle_output ic74hc595_toggle_pin(DOUT19);ic74hc595_shift_io_pins() +#define io66_get_output ic74hc595_get_pin(DOUT19) #define io66_config_input #define io66_config_pullup #define io66_get_input 0 @@ -1856,21 +1856,21 @@ extern "C" #define io66_config_pullup #define io66_get_input 0 #endif -#if ASSERT_PIN_IO(67) -#define io67_config_output mcu_config_output(67) -#define io67_set_output mcu_set_output(67) -#define io67_clear_output mcu_clear_output(67) -#define io67_toggle_output mcu_toggle_output(67) -#define io67_get_output mcu_get_output(67) -#define io67_config_input mcu_config_input(67) -#define io67_config_pullup mcu_config_pullup(67) -#define io67_get_input mcu_get_input(67) -#elif ASSERT_PIN_EXTENDED(67) +#if ASSERT_PIN_IO(DOUT20) +#define io67_config_output mcu_config_output(DOUT20) +#define io67_set_output mcu_set_output(DOUT20) +#define io67_clear_output mcu_clear_output(DOUT20) +#define io67_toggle_output mcu_toggle_output(DOUT20) +#define io67_get_output mcu_get_output(DOUT20) +#define io67_config_input mcu_config_input(DOUT20) +#define io67_config_pullup mcu_config_pullup(DOUT20) +#define io67_get_input mcu_get_input(DOUT20) +#elif ASSERT_PIN_EXTENDED(DOUT20) #define io67_config_output -#define io67_set_output ic74hc595_set_pin(67);ic74hc595_shift_io_pins() -#define io67_clear_output ic74hc595_clear_pin(67);ic74hc595_shift_io_pins() -#define io67_toggle_output ic74hc595_toggle_pin(67);ic74hc595_shift_io_pins() -#define io67_get_output ic74hc595_get_pin(67) +#define io67_set_output ic74hc595_set_pin(DOUT20);ic74hc595_shift_io_pins() +#define io67_clear_output ic74hc595_clear_pin(DOUT20);ic74hc595_shift_io_pins() +#define io67_toggle_output ic74hc595_toggle_pin(DOUT20);ic74hc595_shift_io_pins() +#define io67_get_output ic74hc595_get_pin(DOUT20) #define io67_config_input #define io67_config_pullup #define io67_get_input 0 @@ -1884,21 +1884,21 @@ extern "C" #define io67_config_pullup #define io67_get_input 0 #endif -#if ASSERT_PIN_IO(68) -#define io68_config_output mcu_config_output(68) -#define io68_set_output mcu_set_output(68) -#define io68_clear_output mcu_clear_output(68) -#define io68_toggle_output mcu_toggle_output(68) -#define io68_get_output mcu_get_output(68) -#define io68_config_input mcu_config_input(68) -#define io68_config_pullup mcu_config_pullup(68) -#define io68_get_input mcu_get_input(68) -#elif ASSERT_PIN_EXTENDED(68) +#if ASSERT_PIN_IO(DOUT21) +#define io68_config_output mcu_config_output(DOUT21) +#define io68_set_output mcu_set_output(DOUT21) +#define io68_clear_output mcu_clear_output(DOUT21) +#define io68_toggle_output mcu_toggle_output(DOUT21) +#define io68_get_output mcu_get_output(DOUT21) +#define io68_config_input mcu_config_input(DOUT21) +#define io68_config_pullup mcu_config_pullup(DOUT21) +#define io68_get_input mcu_get_input(DOUT21) +#elif ASSERT_PIN_EXTENDED(DOUT21) #define io68_config_output -#define io68_set_output ic74hc595_set_pin(68);ic74hc595_shift_io_pins() -#define io68_clear_output ic74hc595_clear_pin(68);ic74hc595_shift_io_pins() -#define io68_toggle_output ic74hc595_toggle_pin(68);ic74hc595_shift_io_pins() -#define io68_get_output ic74hc595_get_pin(68) +#define io68_set_output ic74hc595_set_pin(DOUT21);ic74hc595_shift_io_pins() +#define io68_clear_output ic74hc595_clear_pin(DOUT21);ic74hc595_shift_io_pins() +#define io68_toggle_output ic74hc595_toggle_pin(DOUT21);ic74hc595_shift_io_pins() +#define io68_get_output ic74hc595_get_pin(DOUT21) #define io68_config_input #define io68_config_pullup #define io68_get_input 0 @@ -1912,21 +1912,21 @@ extern "C" #define io68_config_pullup #define io68_get_input 0 #endif -#if ASSERT_PIN_IO(69) -#define io69_config_output mcu_config_output(69) -#define io69_set_output mcu_set_output(69) -#define io69_clear_output mcu_clear_output(69) -#define io69_toggle_output mcu_toggle_output(69) -#define io69_get_output mcu_get_output(69) -#define io69_config_input mcu_config_input(69) -#define io69_config_pullup mcu_config_pullup(69) -#define io69_get_input mcu_get_input(69) -#elif ASSERT_PIN_EXTENDED(69) +#if ASSERT_PIN_IO(DOUT22) +#define io69_config_output mcu_config_output(DOUT22) +#define io69_set_output mcu_set_output(DOUT22) +#define io69_clear_output mcu_clear_output(DOUT22) +#define io69_toggle_output mcu_toggle_output(DOUT22) +#define io69_get_output mcu_get_output(DOUT22) +#define io69_config_input mcu_config_input(DOUT22) +#define io69_config_pullup mcu_config_pullup(DOUT22) +#define io69_get_input mcu_get_input(DOUT22) +#elif ASSERT_PIN_EXTENDED(DOUT22) #define io69_config_output -#define io69_set_output ic74hc595_set_pin(69);ic74hc595_shift_io_pins() -#define io69_clear_output ic74hc595_clear_pin(69);ic74hc595_shift_io_pins() -#define io69_toggle_output ic74hc595_toggle_pin(69);ic74hc595_shift_io_pins() -#define io69_get_output ic74hc595_get_pin(69) +#define io69_set_output ic74hc595_set_pin(DOUT22);ic74hc595_shift_io_pins() +#define io69_clear_output ic74hc595_clear_pin(DOUT22);ic74hc595_shift_io_pins() +#define io69_toggle_output ic74hc595_toggle_pin(DOUT22);ic74hc595_shift_io_pins() +#define io69_get_output ic74hc595_get_pin(DOUT22) #define io69_config_input #define io69_config_pullup #define io69_get_input 0 @@ -1940,21 +1940,21 @@ extern "C" #define io69_config_pullup #define io69_get_input 0 #endif -#if ASSERT_PIN_IO(70) -#define io70_config_output mcu_config_output(70) -#define io70_set_output mcu_set_output(70) -#define io70_clear_output mcu_clear_output(70) -#define io70_toggle_output mcu_toggle_output(70) -#define io70_get_output mcu_get_output(70) -#define io70_config_input mcu_config_input(70) -#define io70_config_pullup mcu_config_pullup(70) -#define io70_get_input mcu_get_input(70) -#elif ASSERT_PIN_EXTENDED(70) +#if ASSERT_PIN_IO(DOUT23) +#define io70_config_output mcu_config_output(DOUT23) +#define io70_set_output mcu_set_output(DOUT23) +#define io70_clear_output mcu_clear_output(DOUT23) +#define io70_toggle_output mcu_toggle_output(DOUT23) +#define io70_get_output mcu_get_output(DOUT23) +#define io70_config_input mcu_config_input(DOUT23) +#define io70_config_pullup mcu_config_pullup(DOUT23) +#define io70_get_input mcu_get_input(DOUT23) +#elif ASSERT_PIN_EXTENDED(DOUT23) #define io70_config_output -#define io70_set_output ic74hc595_set_pin(70);ic74hc595_shift_io_pins() -#define io70_clear_output ic74hc595_clear_pin(70);ic74hc595_shift_io_pins() -#define io70_toggle_output ic74hc595_toggle_pin(70);ic74hc595_shift_io_pins() -#define io70_get_output ic74hc595_get_pin(70) +#define io70_set_output ic74hc595_set_pin(DOUT23);ic74hc595_shift_io_pins() +#define io70_clear_output ic74hc595_clear_pin(DOUT23);ic74hc595_shift_io_pins() +#define io70_toggle_output ic74hc595_toggle_pin(DOUT23);ic74hc595_shift_io_pins() +#define io70_get_output ic74hc595_get_pin(DOUT23) #define io70_config_input #define io70_config_pullup #define io70_get_input 0 @@ -1968,21 +1968,21 @@ extern "C" #define io70_config_pullup #define io70_get_input 0 #endif -#if ASSERT_PIN_IO(71) -#define io71_config_output mcu_config_output(71) -#define io71_set_output mcu_set_output(71) -#define io71_clear_output mcu_clear_output(71) -#define io71_toggle_output mcu_toggle_output(71) -#define io71_get_output mcu_get_output(71) -#define io71_config_input mcu_config_input(71) -#define io71_config_pullup mcu_config_pullup(71) -#define io71_get_input mcu_get_input(71) -#elif ASSERT_PIN_EXTENDED(71) +#if ASSERT_PIN_IO(DOUT24) +#define io71_config_output mcu_config_output(DOUT24) +#define io71_set_output mcu_set_output(DOUT24) +#define io71_clear_output mcu_clear_output(DOUT24) +#define io71_toggle_output mcu_toggle_output(DOUT24) +#define io71_get_output mcu_get_output(DOUT24) +#define io71_config_input mcu_config_input(DOUT24) +#define io71_config_pullup mcu_config_pullup(DOUT24) +#define io71_get_input mcu_get_input(DOUT24) +#elif ASSERT_PIN_EXTENDED(DOUT24) #define io71_config_output -#define io71_set_output ic74hc595_set_pin(71);ic74hc595_shift_io_pins() -#define io71_clear_output ic74hc595_clear_pin(71);ic74hc595_shift_io_pins() -#define io71_toggle_output ic74hc595_toggle_pin(71);ic74hc595_shift_io_pins() -#define io71_get_output ic74hc595_get_pin(71) +#define io71_set_output ic74hc595_set_pin(DOUT24);ic74hc595_shift_io_pins() +#define io71_clear_output ic74hc595_clear_pin(DOUT24);ic74hc595_shift_io_pins() +#define io71_toggle_output ic74hc595_toggle_pin(DOUT24);ic74hc595_shift_io_pins() +#define io71_get_output ic74hc595_get_pin(DOUT24) #define io71_config_input #define io71_config_pullup #define io71_get_input 0 @@ -1996,21 +1996,21 @@ extern "C" #define io71_config_pullup #define io71_get_input 0 #endif -#if ASSERT_PIN_IO(72) -#define io72_config_output mcu_config_output(72) -#define io72_set_output mcu_set_output(72) -#define io72_clear_output mcu_clear_output(72) -#define io72_toggle_output mcu_toggle_output(72) -#define io72_get_output mcu_get_output(72) -#define io72_config_input mcu_config_input(72) -#define io72_config_pullup mcu_config_pullup(72) -#define io72_get_input mcu_get_input(72) -#elif ASSERT_PIN_EXTENDED(72) +#if ASSERT_PIN_IO(DOUT25) +#define io72_config_output mcu_config_output(DOUT25) +#define io72_set_output mcu_set_output(DOUT25) +#define io72_clear_output mcu_clear_output(DOUT25) +#define io72_toggle_output mcu_toggle_output(DOUT25) +#define io72_get_output mcu_get_output(DOUT25) +#define io72_config_input mcu_config_input(DOUT25) +#define io72_config_pullup mcu_config_pullup(DOUT25) +#define io72_get_input mcu_get_input(DOUT25) +#elif ASSERT_PIN_EXTENDED(DOUT25) #define io72_config_output -#define io72_set_output ic74hc595_set_pin(72);ic74hc595_shift_io_pins() -#define io72_clear_output ic74hc595_clear_pin(72);ic74hc595_shift_io_pins() -#define io72_toggle_output ic74hc595_toggle_pin(72);ic74hc595_shift_io_pins() -#define io72_get_output ic74hc595_get_pin(72) +#define io72_set_output ic74hc595_set_pin(DOUT25);ic74hc595_shift_io_pins() +#define io72_clear_output ic74hc595_clear_pin(DOUT25);ic74hc595_shift_io_pins() +#define io72_toggle_output ic74hc595_toggle_pin(DOUT25);ic74hc595_shift_io_pins() +#define io72_get_output ic74hc595_get_pin(DOUT25) #define io72_config_input #define io72_config_pullup #define io72_get_input 0 @@ -2024,21 +2024,21 @@ extern "C" #define io72_config_pullup #define io72_get_input 0 #endif -#if ASSERT_PIN_IO(73) -#define io73_config_output mcu_config_output(73) -#define io73_set_output mcu_set_output(73) -#define io73_clear_output mcu_clear_output(73) -#define io73_toggle_output mcu_toggle_output(73) -#define io73_get_output mcu_get_output(73) -#define io73_config_input mcu_config_input(73) -#define io73_config_pullup mcu_config_pullup(73) -#define io73_get_input mcu_get_input(73) -#elif ASSERT_PIN_EXTENDED(73) +#if ASSERT_PIN_IO(DOUT26) +#define io73_config_output mcu_config_output(DOUT26) +#define io73_set_output mcu_set_output(DOUT26) +#define io73_clear_output mcu_clear_output(DOUT26) +#define io73_toggle_output mcu_toggle_output(DOUT26) +#define io73_get_output mcu_get_output(DOUT26) +#define io73_config_input mcu_config_input(DOUT26) +#define io73_config_pullup mcu_config_pullup(DOUT26) +#define io73_get_input mcu_get_input(DOUT26) +#elif ASSERT_PIN_EXTENDED(DOUT26) #define io73_config_output -#define io73_set_output ic74hc595_set_pin(73);ic74hc595_shift_io_pins() -#define io73_clear_output ic74hc595_clear_pin(73);ic74hc595_shift_io_pins() -#define io73_toggle_output ic74hc595_toggle_pin(73);ic74hc595_shift_io_pins() -#define io73_get_output ic74hc595_get_pin(73) +#define io73_set_output ic74hc595_set_pin(DOUT26);ic74hc595_shift_io_pins() +#define io73_clear_output ic74hc595_clear_pin(DOUT26);ic74hc595_shift_io_pins() +#define io73_toggle_output ic74hc595_toggle_pin(DOUT26);ic74hc595_shift_io_pins() +#define io73_get_output ic74hc595_get_pin(DOUT26) #define io73_config_input #define io73_config_pullup #define io73_get_input 0 @@ -2052,21 +2052,21 @@ extern "C" #define io73_config_pullup #define io73_get_input 0 #endif -#if ASSERT_PIN_IO(74) -#define io74_config_output mcu_config_output(74) -#define io74_set_output mcu_set_output(74) -#define io74_clear_output mcu_clear_output(74) -#define io74_toggle_output mcu_toggle_output(74) -#define io74_get_output mcu_get_output(74) -#define io74_config_input mcu_config_input(74) -#define io74_config_pullup mcu_config_pullup(74) -#define io74_get_input mcu_get_input(74) -#elif ASSERT_PIN_EXTENDED(74) +#if ASSERT_PIN_IO(DOUT27) +#define io74_config_output mcu_config_output(DOUT27) +#define io74_set_output mcu_set_output(DOUT27) +#define io74_clear_output mcu_clear_output(DOUT27) +#define io74_toggle_output mcu_toggle_output(DOUT27) +#define io74_get_output mcu_get_output(DOUT27) +#define io74_config_input mcu_config_input(DOUT27) +#define io74_config_pullup mcu_config_pullup(DOUT27) +#define io74_get_input mcu_get_input(DOUT27) +#elif ASSERT_PIN_EXTENDED(DOUT27) #define io74_config_output -#define io74_set_output ic74hc595_set_pin(74);ic74hc595_shift_io_pins() -#define io74_clear_output ic74hc595_clear_pin(74);ic74hc595_shift_io_pins() -#define io74_toggle_output ic74hc595_toggle_pin(74);ic74hc595_shift_io_pins() -#define io74_get_output ic74hc595_get_pin(74) +#define io74_set_output ic74hc595_set_pin(DOUT27);ic74hc595_shift_io_pins() +#define io74_clear_output ic74hc595_clear_pin(DOUT27);ic74hc595_shift_io_pins() +#define io74_toggle_output ic74hc595_toggle_pin(DOUT27);ic74hc595_shift_io_pins() +#define io74_get_output ic74hc595_get_pin(DOUT27) #define io74_config_input #define io74_config_pullup #define io74_get_input 0 @@ -2080,21 +2080,21 @@ extern "C" #define io74_config_pullup #define io74_get_input 0 #endif -#if ASSERT_PIN_IO(75) -#define io75_config_output mcu_config_output(75) -#define io75_set_output mcu_set_output(75) -#define io75_clear_output mcu_clear_output(75) -#define io75_toggle_output mcu_toggle_output(75) -#define io75_get_output mcu_get_output(75) -#define io75_config_input mcu_config_input(75) -#define io75_config_pullup mcu_config_pullup(75) -#define io75_get_input mcu_get_input(75) -#elif ASSERT_PIN_EXTENDED(75) +#if ASSERT_PIN_IO(DOUT28) +#define io75_config_output mcu_config_output(DOUT28) +#define io75_set_output mcu_set_output(DOUT28) +#define io75_clear_output mcu_clear_output(DOUT28) +#define io75_toggle_output mcu_toggle_output(DOUT28) +#define io75_get_output mcu_get_output(DOUT28) +#define io75_config_input mcu_config_input(DOUT28) +#define io75_config_pullup mcu_config_pullup(DOUT28) +#define io75_get_input mcu_get_input(DOUT28) +#elif ASSERT_PIN_EXTENDED(DOUT28) #define io75_config_output -#define io75_set_output ic74hc595_set_pin(75);ic74hc595_shift_io_pins() -#define io75_clear_output ic74hc595_clear_pin(75);ic74hc595_shift_io_pins() -#define io75_toggle_output ic74hc595_toggle_pin(75);ic74hc595_shift_io_pins() -#define io75_get_output ic74hc595_get_pin(75) +#define io75_set_output ic74hc595_set_pin(DOUT28);ic74hc595_shift_io_pins() +#define io75_clear_output ic74hc595_clear_pin(DOUT28);ic74hc595_shift_io_pins() +#define io75_toggle_output ic74hc595_toggle_pin(DOUT28);ic74hc595_shift_io_pins() +#define io75_get_output ic74hc595_get_pin(DOUT28) #define io75_config_input #define io75_config_pullup #define io75_get_input 0 @@ -2108,21 +2108,21 @@ extern "C" #define io75_config_pullup #define io75_get_input 0 #endif -#if ASSERT_PIN_IO(76) -#define io76_config_output mcu_config_output(76) -#define io76_set_output mcu_set_output(76) -#define io76_clear_output mcu_clear_output(76) -#define io76_toggle_output mcu_toggle_output(76) -#define io76_get_output mcu_get_output(76) -#define io76_config_input mcu_config_input(76) -#define io76_config_pullup mcu_config_pullup(76) -#define io76_get_input mcu_get_input(76) -#elif ASSERT_PIN_EXTENDED(76) +#if ASSERT_PIN_IO(DOUT29) +#define io76_config_output mcu_config_output(DOUT29) +#define io76_set_output mcu_set_output(DOUT29) +#define io76_clear_output mcu_clear_output(DOUT29) +#define io76_toggle_output mcu_toggle_output(DOUT29) +#define io76_get_output mcu_get_output(DOUT29) +#define io76_config_input mcu_config_input(DOUT29) +#define io76_config_pullup mcu_config_pullup(DOUT29) +#define io76_get_input mcu_get_input(DOUT29) +#elif ASSERT_PIN_EXTENDED(DOUT29) #define io76_config_output -#define io76_set_output ic74hc595_set_pin(76);ic74hc595_shift_io_pins() -#define io76_clear_output ic74hc595_clear_pin(76);ic74hc595_shift_io_pins() -#define io76_toggle_output ic74hc595_toggle_pin(76);ic74hc595_shift_io_pins() -#define io76_get_output ic74hc595_get_pin(76) +#define io76_set_output ic74hc595_set_pin(DOUT29);ic74hc595_shift_io_pins() +#define io76_clear_output ic74hc595_clear_pin(DOUT29);ic74hc595_shift_io_pins() +#define io76_toggle_output ic74hc595_toggle_pin(DOUT29);ic74hc595_shift_io_pins() +#define io76_get_output ic74hc595_get_pin(DOUT29) #define io76_config_input #define io76_config_pullup #define io76_get_input 0 @@ -2136,21 +2136,21 @@ extern "C" #define io76_config_pullup #define io76_get_input 0 #endif -#if ASSERT_PIN_IO(77) -#define io77_config_output mcu_config_output(77) -#define io77_set_output mcu_set_output(77) -#define io77_clear_output mcu_clear_output(77) -#define io77_toggle_output mcu_toggle_output(77) -#define io77_get_output mcu_get_output(77) -#define io77_config_input mcu_config_input(77) -#define io77_config_pullup mcu_config_pullup(77) -#define io77_get_input mcu_get_input(77) -#elif ASSERT_PIN_EXTENDED(77) +#if ASSERT_PIN_IO(DOUT30) +#define io77_config_output mcu_config_output(DOUT30) +#define io77_set_output mcu_set_output(DOUT30) +#define io77_clear_output mcu_clear_output(DOUT30) +#define io77_toggle_output mcu_toggle_output(DOUT30) +#define io77_get_output mcu_get_output(DOUT30) +#define io77_config_input mcu_config_input(DOUT30) +#define io77_config_pullup mcu_config_pullup(DOUT30) +#define io77_get_input mcu_get_input(DOUT30) +#elif ASSERT_PIN_EXTENDED(DOUT30) #define io77_config_output -#define io77_set_output ic74hc595_set_pin(77);ic74hc595_shift_io_pins() -#define io77_clear_output ic74hc595_clear_pin(77);ic74hc595_shift_io_pins() -#define io77_toggle_output ic74hc595_toggle_pin(77);ic74hc595_shift_io_pins() -#define io77_get_output ic74hc595_get_pin(77) +#define io77_set_output ic74hc595_set_pin(DOUT30);ic74hc595_shift_io_pins() +#define io77_clear_output ic74hc595_clear_pin(DOUT30);ic74hc595_shift_io_pins() +#define io77_toggle_output ic74hc595_toggle_pin(DOUT30);ic74hc595_shift_io_pins() +#define io77_get_output ic74hc595_get_pin(DOUT30) #define io77_config_input #define io77_config_pullup #define io77_get_input 0 @@ -2164,21 +2164,21 @@ extern "C" #define io77_config_pullup #define io77_get_input 0 #endif -#if ASSERT_PIN_IO(78) -#define io78_config_output mcu_config_output(78) -#define io78_set_output mcu_set_output(78) -#define io78_clear_output mcu_clear_output(78) -#define io78_toggle_output mcu_toggle_output(78) -#define io78_get_output mcu_get_output(78) -#define io78_config_input mcu_config_input(78) -#define io78_config_pullup mcu_config_pullup(78) -#define io78_get_input mcu_get_input(78) -#elif ASSERT_PIN_EXTENDED(78) +#if ASSERT_PIN_IO(DOUT31) +#define io78_config_output mcu_config_output(DOUT31) +#define io78_set_output mcu_set_output(DOUT31) +#define io78_clear_output mcu_clear_output(DOUT31) +#define io78_toggle_output mcu_toggle_output(DOUT31) +#define io78_get_output mcu_get_output(DOUT31) +#define io78_config_input mcu_config_input(DOUT31) +#define io78_config_pullup mcu_config_pullup(DOUT31) +#define io78_get_input mcu_get_input(DOUT31) +#elif ASSERT_PIN_EXTENDED(DOUT31) #define io78_config_output -#define io78_set_output ic74hc595_set_pin(78);ic74hc595_shift_io_pins() -#define io78_clear_output ic74hc595_clear_pin(78);ic74hc595_shift_io_pins() -#define io78_toggle_output ic74hc595_toggle_pin(78);ic74hc595_shift_io_pins() -#define io78_get_output ic74hc595_get_pin(78) +#define io78_set_output ic74hc595_set_pin(DOUT31);ic74hc595_shift_io_pins() +#define io78_clear_output ic74hc595_clear_pin(DOUT31);ic74hc595_shift_io_pins() +#define io78_toggle_output ic74hc595_toggle_pin(DOUT31);ic74hc595_shift_io_pins() +#define io78_get_output ic74hc595_get_pin(DOUT31) #define io78_config_input #define io78_config_pullup #define io78_get_input 0 @@ -2192,21 +2192,21 @@ extern "C" #define io78_config_pullup #define io78_get_input 0 #endif -#if ASSERT_PIN_IO(100) -#define io100_config_output mcu_config_output(100) -#define io100_set_output mcu_set_output(100) -#define io100_clear_output mcu_clear_output(100) -#define io100_toggle_output mcu_toggle_output(100) -#define io100_get_output mcu_get_output(100) -#define io100_config_input mcu_config_input(100) -#define io100_config_pullup mcu_config_pullup(100) -#define io100_get_input mcu_get_input(100) -#elif ASSERT_PIN_EXTENDED(100) +#if ASSERT_PIN_IO(LIMIT_X) +#define io100_config_output mcu_config_output(LIMIT_X) +#define io100_set_output mcu_set_output(LIMIT_X) +#define io100_clear_output mcu_clear_output(LIMIT_X) +#define io100_toggle_output mcu_toggle_output(LIMIT_X) +#define io100_get_output mcu_get_output(LIMIT_X) +#define io100_config_input mcu_config_input(LIMIT_X) +#define io100_config_pullup mcu_config_pullup(LIMIT_X) +#define io100_get_input mcu_get_input(LIMIT_X) +#elif ASSERT_PIN_EXTENDED(LIMIT_X) #define io100_config_output -#define io100_set_output ic74hc595_set_pin(100);ic74hc595_shift_io_pins() -#define io100_clear_output ic74hc595_clear_pin(100);ic74hc595_shift_io_pins() -#define io100_toggle_output ic74hc595_toggle_pin(100);ic74hc595_shift_io_pins() -#define io100_get_output ic74hc595_get_pin(100) +#define io100_set_output ic74hc595_set_pin(LIMIT_X);ic74hc595_shift_io_pins() +#define io100_clear_output ic74hc595_clear_pin(LIMIT_X);ic74hc595_shift_io_pins() +#define io100_toggle_output ic74hc595_toggle_pin(LIMIT_X);ic74hc595_shift_io_pins() +#define io100_get_output ic74hc595_get_pin(LIMIT_X) #define io100_config_input #define io100_config_pullup #define io100_get_input 0 @@ -2220,21 +2220,21 @@ extern "C" #define io100_config_pullup #define io100_get_input 0 #endif -#if ASSERT_PIN_IO(101) -#define io101_config_output mcu_config_output(101) -#define io101_set_output mcu_set_output(101) -#define io101_clear_output mcu_clear_output(101) -#define io101_toggle_output mcu_toggle_output(101) -#define io101_get_output mcu_get_output(101) -#define io101_config_input mcu_config_input(101) -#define io101_config_pullup mcu_config_pullup(101) -#define io101_get_input mcu_get_input(101) -#elif ASSERT_PIN_EXTENDED(101) +#if ASSERT_PIN_IO(LIMIT_Y) +#define io101_config_output mcu_config_output(LIMIT_Y) +#define io101_set_output mcu_set_output(LIMIT_Y) +#define io101_clear_output mcu_clear_output(LIMIT_Y) +#define io101_toggle_output mcu_toggle_output(LIMIT_Y) +#define io101_get_output mcu_get_output(LIMIT_Y) +#define io101_config_input mcu_config_input(LIMIT_Y) +#define io101_config_pullup mcu_config_pullup(LIMIT_Y) +#define io101_get_input mcu_get_input(LIMIT_Y) +#elif ASSERT_PIN_EXTENDED(LIMIT_Y) #define io101_config_output -#define io101_set_output ic74hc595_set_pin(101);ic74hc595_shift_io_pins() -#define io101_clear_output ic74hc595_clear_pin(101);ic74hc595_shift_io_pins() -#define io101_toggle_output ic74hc595_toggle_pin(101);ic74hc595_shift_io_pins() -#define io101_get_output ic74hc595_get_pin(101) +#define io101_set_output ic74hc595_set_pin(LIMIT_Y);ic74hc595_shift_io_pins() +#define io101_clear_output ic74hc595_clear_pin(LIMIT_Y);ic74hc595_shift_io_pins() +#define io101_toggle_output ic74hc595_toggle_pin(LIMIT_Y);ic74hc595_shift_io_pins() +#define io101_get_output ic74hc595_get_pin(LIMIT_Y) #define io101_config_input #define io101_config_pullup #define io101_get_input 0 @@ -2248,21 +2248,21 @@ extern "C" #define io101_config_pullup #define io101_get_input 0 #endif -#if ASSERT_PIN_IO(102) -#define io102_config_output mcu_config_output(102) -#define io102_set_output mcu_set_output(102) -#define io102_clear_output mcu_clear_output(102) -#define io102_toggle_output mcu_toggle_output(102) -#define io102_get_output mcu_get_output(102) -#define io102_config_input mcu_config_input(102) -#define io102_config_pullup mcu_config_pullup(102) -#define io102_get_input mcu_get_input(102) -#elif ASSERT_PIN_EXTENDED(102) +#if ASSERT_PIN_IO(LIMIT_Z) +#define io102_config_output mcu_config_output(LIMIT_Z) +#define io102_set_output mcu_set_output(LIMIT_Z) +#define io102_clear_output mcu_clear_output(LIMIT_Z) +#define io102_toggle_output mcu_toggle_output(LIMIT_Z) +#define io102_get_output mcu_get_output(LIMIT_Z) +#define io102_config_input mcu_config_input(LIMIT_Z) +#define io102_config_pullup mcu_config_pullup(LIMIT_Z) +#define io102_get_input mcu_get_input(LIMIT_Z) +#elif ASSERT_PIN_EXTENDED(LIMIT_Z) #define io102_config_output -#define io102_set_output ic74hc595_set_pin(102);ic74hc595_shift_io_pins() -#define io102_clear_output ic74hc595_clear_pin(102);ic74hc595_shift_io_pins() -#define io102_toggle_output ic74hc595_toggle_pin(102);ic74hc595_shift_io_pins() -#define io102_get_output ic74hc595_get_pin(102) +#define io102_set_output ic74hc595_set_pin(LIMIT_Z);ic74hc595_shift_io_pins() +#define io102_clear_output ic74hc595_clear_pin(LIMIT_Z);ic74hc595_shift_io_pins() +#define io102_toggle_output ic74hc595_toggle_pin(LIMIT_Z);ic74hc595_shift_io_pins() +#define io102_get_output ic74hc595_get_pin(LIMIT_Z) #define io102_config_input #define io102_config_pullup #define io102_get_input 0 @@ -2276,21 +2276,21 @@ extern "C" #define io102_config_pullup #define io102_get_input 0 #endif -#if ASSERT_PIN_IO(103) -#define io103_config_output mcu_config_output(103) -#define io103_set_output mcu_set_output(103) -#define io103_clear_output mcu_clear_output(103) -#define io103_toggle_output mcu_toggle_output(103) -#define io103_get_output mcu_get_output(103) -#define io103_config_input mcu_config_input(103) -#define io103_config_pullup mcu_config_pullup(103) -#define io103_get_input mcu_get_input(103) -#elif ASSERT_PIN_EXTENDED(103) +#if ASSERT_PIN_IO(LIMIT_X2) +#define io103_config_output mcu_config_output(LIMIT_X2) +#define io103_set_output mcu_set_output(LIMIT_X2) +#define io103_clear_output mcu_clear_output(LIMIT_X2) +#define io103_toggle_output mcu_toggle_output(LIMIT_X2) +#define io103_get_output mcu_get_output(LIMIT_X2) +#define io103_config_input mcu_config_input(LIMIT_X2) +#define io103_config_pullup mcu_config_pullup(LIMIT_X2) +#define io103_get_input mcu_get_input(LIMIT_X2) +#elif ASSERT_PIN_EXTENDED(LIMIT_X2) #define io103_config_output -#define io103_set_output ic74hc595_set_pin(103);ic74hc595_shift_io_pins() -#define io103_clear_output ic74hc595_clear_pin(103);ic74hc595_shift_io_pins() -#define io103_toggle_output ic74hc595_toggle_pin(103);ic74hc595_shift_io_pins() -#define io103_get_output ic74hc595_get_pin(103) +#define io103_set_output ic74hc595_set_pin(LIMIT_X2);ic74hc595_shift_io_pins() +#define io103_clear_output ic74hc595_clear_pin(LIMIT_X2);ic74hc595_shift_io_pins() +#define io103_toggle_output ic74hc595_toggle_pin(LIMIT_X2);ic74hc595_shift_io_pins() +#define io103_get_output ic74hc595_get_pin(LIMIT_X2) #define io103_config_input #define io103_config_pullup #define io103_get_input 0 @@ -2304,21 +2304,21 @@ extern "C" #define io103_config_pullup #define io103_get_input 0 #endif -#if ASSERT_PIN_IO(104) -#define io104_config_output mcu_config_output(104) -#define io104_set_output mcu_set_output(104) -#define io104_clear_output mcu_clear_output(104) -#define io104_toggle_output mcu_toggle_output(104) -#define io104_get_output mcu_get_output(104) -#define io104_config_input mcu_config_input(104) -#define io104_config_pullup mcu_config_pullup(104) -#define io104_get_input mcu_get_input(104) -#elif ASSERT_PIN_EXTENDED(104) +#if ASSERT_PIN_IO(LIMIT_Y2) +#define io104_config_output mcu_config_output(LIMIT_Y2) +#define io104_set_output mcu_set_output(LIMIT_Y2) +#define io104_clear_output mcu_clear_output(LIMIT_Y2) +#define io104_toggle_output mcu_toggle_output(LIMIT_Y2) +#define io104_get_output mcu_get_output(LIMIT_Y2) +#define io104_config_input mcu_config_input(LIMIT_Y2) +#define io104_config_pullup mcu_config_pullup(LIMIT_Y2) +#define io104_get_input mcu_get_input(LIMIT_Y2) +#elif ASSERT_PIN_EXTENDED(LIMIT_Y2) #define io104_config_output -#define io104_set_output ic74hc595_set_pin(104);ic74hc595_shift_io_pins() -#define io104_clear_output ic74hc595_clear_pin(104);ic74hc595_shift_io_pins() -#define io104_toggle_output ic74hc595_toggle_pin(104);ic74hc595_shift_io_pins() -#define io104_get_output ic74hc595_get_pin(104) +#define io104_set_output ic74hc595_set_pin(LIMIT_Y2);ic74hc595_shift_io_pins() +#define io104_clear_output ic74hc595_clear_pin(LIMIT_Y2);ic74hc595_shift_io_pins() +#define io104_toggle_output ic74hc595_toggle_pin(LIMIT_Y2);ic74hc595_shift_io_pins() +#define io104_get_output ic74hc595_get_pin(LIMIT_Y2) #define io104_config_input #define io104_config_pullup #define io104_get_input 0 @@ -2332,21 +2332,21 @@ extern "C" #define io104_config_pullup #define io104_get_input 0 #endif -#if ASSERT_PIN_IO(105) -#define io105_config_output mcu_config_output(105) -#define io105_set_output mcu_set_output(105) -#define io105_clear_output mcu_clear_output(105) -#define io105_toggle_output mcu_toggle_output(105) -#define io105_get_output mcu_get_output(105) -#define io105_config_input mcu_config_input(105) -#define io105_config_pullup mcu_config_pullup(105) -#define io105_get_input mcu_get_input(105) -#elif ASSERT_PIN_EXTENDED(105) +#if ASSERT_PIN_IO(LIMIT_Z2) +#define io105_config_output mcu_config_output(LIMIT_Z2) +#define io105_set_output mcu_set_output(LIMIT_Z2) +#define io105_clear_output mcu_clear_output(LIMIT_Z2) +#define io105_toggle_output mcu_toggle_output(LIMIT_Z2) +#define io105_get_output mcu_get_output(LIMIT_Z2) +#define io105_config_input mcu_config_input(LIMIT_Z2) +#define io105_config_pullup mcu_config_pullup(LIMIT_Z2) +#define io105_get_input mcu_get_input(LIMIT_Z2) +#elif ASSERT_PIN_EXTENDED(LIMIT_Z2) #define io105_config_output -#define io105_set_output ic74hc595_set_pin(105);ic74hc595_shift_io_pins() -#define io105_clear_output ic74hc595_clear_pin(105);ic74hc595_shift_io_pins() -#define io105_toggle_output ic74hc595_toggle_pin(105);ic74hc595_shift_io_pins() -#define io105_get_output ic74hc595_get_pin(105) +#define io105_set_output ic74hc595_set_pin(LIMIT_Z2);ic74hc595_shift_io_pins() +#define io105_clear_output ic74hc595_clear_pin(LIMIT_Z2);ic74hc595_shift_io_pins() +#define io105_toggle_output ic74hc595_toggle_pin(LIMIT_Z2);ic74hc595_shift_io_pins() +#define io105_get_output ic74hc595_get_pin(LIMIT_Z2) #define io105_config_input #define io105_config_pullup #define io105_get_input 0 @@ -2360,21 +2360,21 @@ extern "C" #define io105_config_pullup #define io105_get_input 0 #endif -#if ASSERT_PIN_IO(106) -#define io106_config_output mcu_config_output(106) -#define io106_set_output mcu_set_output(106) -#define io106_clear_output mcu_clear_output(106) -#define io106_toggle_output mcu_toggle_output(106) -#define io106_get_output mcu_get_output(106) -#define io106_config_input mcu_config_input(106) -#define io106_config_pullup mcu_config_pullup(106) -#define io106_get_input mcu_get_input(106) -#elif ASSERT_PIN_EXTENDED(106) +#if ASSERT_PIN_IO(LIMIT_A) +#define io106_config_output mcu_config_output(LIMIT_A) +#define io106_set_output mcu_set_output(LIMIT_A) +#define io106_clear_output mcu_clear_output(LIMIT_A) +#define io106_toggle_output mcu_toggle_output(LIMIT_A) +#define io106_get_output mcu_get_output(LIMIT_A) +#define io106_config_input mcu_config_input(LIMIT_A) +#define io106_config_pullup mcu_config_pullup(LIMIT_A) +#define io106_get_input mcu_get_input(LIMIT_A) +#elif ASSERT_PIN_EXTENDED(LIMIT_A) #define io106_config_output -#define io106_set_output ic74hc595_set_pin(106);ic74hc595_shift_io_pins() -#define io106_clear_output ic74hc595_clear_pin(106);ic74hc595_shift_io_pins() -#define io106_toggle_output ic74hc595_toggle_pin(106);ic74hc595_shift_io_pins() -#define io106_get_output ic74hc595_get_pin(106) +#define io106_set_output ic74hc595_set_pin(LIMIT_A);ic74hc595_shift_io_pins() +#define io106_clear_output ic74hc595_clear_pin(LIMIT_A);ic74hc595_shift_io_pins() +#define io106_toggle_output ic74hc595_toggle_pin(LIMIT_A);ic74hc595_shift_io_pins() +#define io106_get_output ic74hc595_get_pin(LIMIT_A) #define io106_config_input #define io106_config_pullup #define io106_get_input 0 @@ -2388,21 +2388,21 @@ extern "C" #define io106_config_pullup #define io106_get_input 0 #endif -#if ASSERT_PIN_IO(107) -#define io107_config_output mcu_config_output(107) -#define io107_set_output mcu_set_output(107) -#define io107_clear_output mcu_clear_output(107) -#define io107_toggle_output mcu_toggle_output(107) -#define io107_get_output mcu_get_output(107) -#define io107_config_input mcu_config_input(107) -#define io107_config_pullup mcu_config_pullup(107) -#define io107_get_input mcu_get_input(107) -#elif ASSERT_PIN_EXTENDED(107) +#if ASSERT_PIN_IO(LIMIT_B) +#define io107_config_output mcu_config_output(LIMIT_B) +#define io107_set_output mcu_set_output(LIMIT_B) +#define io107_clear_output mcu_clear_output(LIMIT_B) +#define io107_toggle_output mcu_toggle_output(LIMIT_B) +#define io107_get_output mcu_get_output(LIMIT_B) +#define io107_config_input mcu_config_input(LIMIT_B) +#define io107_config_pullup mcu_config_pullup(LIMIT_B) +#define io107_get_input mcu_get_input(LIMIT_B) +#elif ASSERT_PIN_EXTENDED(LIMIT_B) #define io107_config_output -#define io107_set_output ic74hc595_set_pin(107);ic74hc595_shift_io_pins() -#define io107_clear_output ic74hc595_clear_pin(107);ic74hc595_shift_io_pins() -#define io107_toggle_output ic74hc595_toggle_pin(107);ic74hc595_shift_io_pins() -#define io107_get_output ic74hc595_get_pin(107) +#define io107_set_output ic74hc595_set_pin(LIMIT_B);ic74hc595_shift_io_pins() +#define io107_clear_output ic74hc595_clear_pin(LIMIT_B);ic74hc595_shift_io_pins() +#define io107_toggle_output ic74hc595_toggle_pin(LIMIT_B);ic74hc595_shift_io_pins() +#define io107_get_output ic74hc595_get_pin(LIMIT_B) #define io107_config_input #define io107_config_pullup #define io107_get_input 0 @@ -2416,21 +2416,21 @@ extern "C" #define io107_config_pullup #define io107_get_input 0 #endif -#if ASSERT_PIN_IO(108) -#define io108_config_output mcu_config_output(108) -#define io108_set_output mcu_set_output(108) -#define io108_clear_output mcu_clear_output(108) -#define io108_toggle_output mcu_toggle_output(108) -#define io108_get_output mcu_get_output(108) -#define io108_config_input mcu_config_input(108) -#define io108_config_pullup mcu_config_pullup(108) -#define io108_get_input mcu_get_input(108) -#elif ASSERT_PIN_EXTENDED(108) +#if ASSERT_PIN_IO(LIMIT_C) +#define io108_config_output mcu_config_output(LIMIT_C) +#define io108_set_output mcu_set_output(LIMIT_C) +#define io108_clear_output mcu_clear_output(LIMIT_C) +#define io108_toggle_output mcu_toggle_output(LIMIT_C) +#define io108_get_output mcu_get_output(LIMIT_C) +#define io108_config_input mcu_config_input(LIMIT_C) +#define io108_config_pullup mcu_config_pullup(LIMIT_C) +#define io108_get_input mcu_get_input(LIMIT_C) +#elif ASSERT_PIN_EXTENDED(LIMIT_C) #define io108_config_output -#define io108_set_output ic74hc595_set_pin(108);ic74hc595_shift_io_pins() -#define io108_clear_output ic74hc595_clear_pin(108);ic74hc595_shift_io_pins() -#define io108_toggle_output ic74hc595_toggle_pin(108);ic74hc595_shift_io_pins() -#define io108_get_output ic74hc595_get_pin(108) +#define io108_set_output ic74hc595_set_pin(LIMIT_C);ic74hc595_shift_io_pins() +#define io108_clear_output ic74hc595_clear_pin(LIMIT_C);ic74hc595_shift_io_pins() +#define io108_toggle_output ic74hc595_toggle_pin(LIMIT_C);ic74hc595_shift_io_pins() +#define io108_get_output ic74hc595_get_pin(LIMIT_C) #define io108_config_input #define io108_config_pullup #define io108_get_input 0 @@ -2444,21 +2444,21 @@ extern "C" #define io108_config_pullup #define io108_get_input 0 #endif -#if ASSERT_PIN_IO(109) -#define io109_config_output mcu_config_output(109) -#define io109_set_output mcu_set_output(109) -#define io109_clear_output mcu_clear_output(109) -#define io109_toggle_output mcu_toggle_output(109) -#define io109_get_output mcu_get_output(109) -#define io109_config_input mcu_config_input(109) -#define io109_config_pullup mcu_config_pullup(109) -#define io109_get_input mcu_get_input(109) -#elif ASSERT_PIN_EXTENDED(109) +#if ASSERT_PIN_IO(PROBE) +#define io109_config_output mcu_config_output(PROBE) +#define io109_set_output mcu_set_output(PROBE) +#define io109_clear_output mcu_clear_output(PROBE) +#define io109_toggle_output mcu_toggle_output(PROBE) +#define io109_get_output mcu_get_output(PROBE) +#define io109_config_input mcu_config_input(PROBE) +#define io109_config_pullup mcu_config_pullup(PROBE) +#define io109_get_input mcu_get_input(PROBE) +#elif ASSERT_PIN_EXTENDED(PROBE) #define io109_config_output -#define io109_set_output ic74hc595_set_pin(109);ic74hc595_shift_io_pins() -#define io109_clear_output ic74hc595_clear_pin(109);ic74hc595_shift_io_pins() -#define io109_toggle_output ic74hc595_toggle_pin(109);ic74hc595_shift_io_pins() -#define io109_get_output ic74hc595_get_pin(109) +#define io109_set_output ic74hc595_set_pin(PROBE);ic74hc595_shift_io_pins() +#define io109_clear_output ic74hc595_clear_pin(PROBE);ic74hc595_shift_io_pins() +#define io109_toggle_output ic74hc595_toggle_pin(PROBE);ic74hc595_shift_io_pins() +#define io109_get_output ic74hc595_get_pin(PROBE) #define io109_config_input #define io109_config_pullup #define io109_get_input 0 @@ -2472,21 +2472,21 @@ extern "C" #define io109_config_pullup #define io109_get_input 0 #endif -#if ASSERT_PIN_IO(110) -#define io110_config_output mcu_config_output(110) -#define io110_set_output mcu_set_output(110) -#define io110_clear_output mcu_clear_output(110) -#define io110_toggle_output mcu_toggle_output(110) -#define io110_get_output mcu_get_output(110) -#define io110_config_input mcu_config_input(110) -#define io110_config_pullup mcu_config_pullup(110) -#define io110_get_input mcu_get_input(110) -#elif ASSERT_PIN_EXTENDED(110) +#if ASSERT_PIN_IO(ESTOP) +#define io110_config_output mcu_config_output(ESTOP) +#define io110_set_output mcu_set_output(ESTOP) +#define io110_clear_output mcu_clear_output(ESTOP) +#define io110_toggle_output mcu_toggle_output(ESTOP) +#define io110_get_output mcu_get_output(ESTOP) +#define io110_config_input mcu_config_input(ESTOP) +#define io110_config_pullup mcu_config_pullup(ESTOP) +#define io110_get_input mcu_get_input(ESTOP) +#elif ASSERT_PIN_EXTENDED(ESTOP) #define io110_config_output -#define io110_set_output ic74hc595_set_pin(110);ic74hc595_shift_io_pins() -#define io110_clear_output ic74hc595_clear_pin(110);ic74hc595_shift_io_pins() -#define io110_toggle_output ic74hc595_toggle_pin(110);ic74hc595_shift_io_pins() -#define io110_get_output ic74hc595_get_pin(110) +#define io110_set_output ic74hc595_set_pin(ESTOP);ic74hc595_shift_io_pins() +#define io110_clear_output ic74hc595_clear_pin(ESTOP);ic74hc595_shift_io_pins() +#define io110_toggle_output ic74hc595_toggle_pin(ESTOP);ic74hc595_shift_io_pins() +#define io110_get_output ic74hc595_get_pin(ESTOP) #define io110_config_input #define io110_config_pullup #define io110_get_input 0 @@ -2500,21 +2500,21 @@ extern "C" #define io110_config_pullup #define io110_get_input 0 #endif -#if ASSERT_PIN_IO(111) -#define io111_config_output mcu_config_output(111) -#define io111_set_output mcu_set_output(111) -#define io111_clear_output mcu_clear_output(111) -#define io111_toggle_output mcu_toggle_output(111) -#define io111_get_output mcu_get_output(111) -#define io111_config_input mcu_config_input(111) -#define io111_config_pullup mcu_config_pullup(111) -#define io111_get_input mcu_get_input(111) -#elif ASSERT_PIN_EXTENDED(111) +#if ASSERT_PIN_IO(SAFETY_DOOR) +#define io111_config_output mcu_config_output(SAFETY_DOOR) +#define io111_set_output mcu_set_output(SAFETY_DOOR) +#define io111_clear_output mcu_clear_output(SAFETY_DOOR) +#define io111_toggle_output mcu_toggle_output(SAFETY_DOOR) +#define io111_get_output mcu_get_output(SAFETY_DOOR) +#define io111_config_input mcu_config_input(SAFETY_DOOR) +#define io111_config_pullup mcu_config_pullup(SAFETY_DOOR) +#define io111_get_input mcu_get_input(SAFETY_DOOR) +#elif ASSERT_PIN_EXTENDED(SAFETY_DOOR) #define io111_config_output -#define io111_set_output ic74hc595_set_pin(111);ic74hc595_shift_io_pins() -#define io111_clear_output ic74hc595_clear_pin(111);ic74hc595_shift_io_pins() -#define io111_toggle_output ic74hc595_toggle_pin(111);ic74hc595_shift_io_pins() -#define io111_get_output ic74hc595_get_pin(111) +#define io111_set_output ic74hc595_set_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() +#define io111_clear_output ic74hc595_clear_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() +#define io111_toggle_output ic74hc595_toggle_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() +#define io111_get_output ic74hc595_get_pin(SAFETY_DOOR) #define io111_config_input #define io111_config_pullup #define io111_get_input 0 @@ -2528,21 +2528,21 @@ extern "C" #define io111_config_pullup #define io111_get_input 0 #endif -#if ASSERT_PIN_IO(112) -#define io112_config_output mcu_config_output(112) -#define io112_set_output mcu_set_output(112) -#define io112_clear_output mcu_clear_output(112) -#define io112_toggle_output mcu_toggle_output(112) -#define io112_get_output mcu_get_output(112) -#define io112_config_input mcu_config_input(112) -#define io112_config_pullup mcu_config_pullup(112) -#define io112_get_input mcu_get_input(112) -#elif ASSERT_PIN_EXTENDED(112) +#if ASSERT_PIN_IO(FHOLD) +#define io112_config_output mcu_config_output(FHOLD) +#define io112_set_output mcu_set_output(FHOLD) +#define io112_clear_output mcu_clear_output(FHOLD) +#define io112_toggle_output mcu_toggle_output(FHOLD) +#define io112_get_output mcu_get_output(FHOLD) +#define io112_config_input mcu_config_input(FHOLD) +#define io112_config_pullup mcu_config_pullup(FHOLD) +#define io112_get_input mcu_get_input(FHOLD) +#elif ASSERT_PIN_EXTENDED(FHOLD) #define io112_config_output -#define io112_set_output ic74hc595_set_pin(112);ic74hc595_shift_io_pins() -#define io112_clear_output ic74hc595_clear_pin(112);ic74hc595_shift_io_pins() -#define io112_toggle_output ic74hc595_toggle_pin(112);ic74hc595_shift_io_pins() -#define io112_get_output ic74hc595_get_pin(112) +#define io112_set_output ic74hc595_set_pin(FHOLD);ic74hc595_shift_io_pins() +#define io112_clear_output ic74hc595_clear_pin(FHOLD);ic74hc595_shift_io_pins() +#define io112_toggle_output ic74hc595_toggle_pin(FHOLD);ic74hc595_shift_io_pins() +#define io112_get_output ic74hc595_get_pin(FHOLD) #define io112_config_input #define io112_config_pullup #define io112_get_input 0 @@ -2556,21 +2556,21 @@ extern "C" #define io112_config_pullup #define io112_get_input 0 #endif -#if ASSERT_PIN_IO(113) -#define io113_config_output mcu_config_output(113) -#define io113_set_output mcu_set_output(113) -#define io113_clear_output mcu_clear_output(113) -#define io113_toggle_output mcu_toggle_output(113) -#define io113_get_output mcu_get_output(113) -#define io113_config_input mcu_config_input(113) -#define io113_config_pullup mcu_config_pullup(113) -#define io113_get_input mcu_get_input(113) -#elif ASSERT_PIN_EXTENDED(113) +#if ASSERT_PIN_IO(CS_RES) +#define io113_config_output mcu_config_output(CS_RES) +#define io113_set_output mcu_set_output(CS_RES) +#define io113_clear_output mcu_clear_output(CS_RES) +#define io113_toggle_output mcu_toggle_output(CS_RES) +#define io113_get_output mcu_get_output(CS_RES) +#define io113_config_input mcu_config_input(CS_RES) +#define io113_config_pullup mcu_config_pullup(CS_RES) +#define io113_get_input mcu_get_input(CS_RES) +#elif ASSERT_PIN_EXTENDED(CS_RES) #define io113_config_output -#define io113_set_output ic74hc595_set_pin(113);ic74hc595_shift_io_pins() -#define io113_clear_output ic74hc595_clear_pin(113);ic74hc595_shift_io_pins() -#define io113_toggle_output ic74hc595_toggle_pin(113);ic74hc595_shift_io_pins() -#define io113_get_output ic74hc595_get_pin(113) +#define io113_set_output ic74hc595_set_pin(CS_RES);ic74hc595_shift_io_pins() +#define io113_clear_output ic74hc595_clear_pin(CS_RES);ic74hc595_shift_io_pins() +#define io113_toggle_output ic74hc595_toggle_pin(CS_RES);ic74hc595_shift_io_pins() +#define io113_get_output ic74hc595_get_pin(CS_RES) #define io113_config_input #define io113_config_pullup #define io113_get_input 0 @@ -2584,21 +2584,21 @@ extern "C" #define io113_config_pullup #define io113_get_input 0 #endif -#if ASSERT_PIN_IO(114) -#define io114_config_output mcu_config_output(114) -#define io114_set_output mcu_set_output(114) -#define io114_clear_output mcu_clear_output(114) -#define io114_toggle_output mcu_toggle_output(114) -#define io114_get_output mcu_get_output(114) -#define io114_config_input mcu_config_input(114) -#define io114_config_pullup mcu_config_pullup(114) -#define io114_get_input mcu_get_input(114) -#elif ASSERT_PIN_EXTENDED(114) +#if ASSERT_PIN_IO(ANALOG0) +#define io114_config_output mcu_config_output(ANALOG0) +#define io114_set_output mcu_set_output(ANALOG0) +#define io114_clear_output mcu_clear_output(ANALOG0) +#define io114_toggle_output mcu_toggle_output(ANALOG0) +#define io114_get_output mcu_get_output(ANALOG0) +#define io114_config_input mcu_config_input(ANALOG0) +#define io114_config_pullup mcu_config_pullup(ANALOG0) +#define io114_get_input mcu_get_input(ANALOG0) +#elif ASSERT_PIN_EXTENDED(ANALOG0) #define io114_config_output -#define io114_set_output ic74hc595_set_pin(114);ic74hc595_shift_io_pins() -#define io114_clear_output ic74hc595_clear_pin(114);ic74hc595_shift_io_pins() -#define io114_toggle_output ic74hc595_toggle_pin(114);ic74hc595_shift_io_pins() -#define io114_get_output ic74hc595_get_pin(114) +#define io114_set_output ic74hc595_set_pin(ANALOG0);ic74hc595_shift_io_pins() +#define io114_clear_output ic74hc595_clear_pin(ANALOG0);ic74hc595_shift_io_pins() +#define io114_toggle_output ic74hc595_toggle_pin(ANALOG0);ic74hc595_shift_io_pins() +#define io114_get_output ic74hc595_get_pin(ANALOG0) #define io114_config_input #define io114_config_pullup #define io114_get_input 0 @@ -2612,21 +2612,21 @@ extern "C" #define io114_config_pullup #define io114_get_input 0 #endif -#if ASSERT_PIN_IO(115) -#define io115_config_output mcu_config_output(115) -#define io115_set_output mcu_set_output(115) -#define io115_clear_output mcu_clear_output(115) -#define io115_toggle_output mcu_toggle_output(115) -#define io115_get_output mcu_get_output(115) -#define io115_config_input mcu_config_input(115) -#define io115_config_pullup mcu_config_pullup(115) -#define io115_get_input mcu_get_input(115) -#elif ASSERT_PIN_EXTENDED(115) +#if ASSERT_PIN_IO(ANALOG1) +#define io115_config_output mcu_config_output(ANALOG1) +#define io115_set_output mcu_set_output(ANALOG1) +#define io115_clear_output mcu_clear_output(ANALOG1) +#define io115_toggle_output mcu_toggle_output(ANALOG1) +#define io115_get_output mcu_get_output(ANALOG1) +#define io115_config_input mcu_config_input(ANALOG1) +#define io115_config_pullup mcu_config_pullup(ANALOG1) +#define io115_get_input mcu_get_input(ANALOG1) +#elif ASSERT_PIN_EXTENDED(ANALOG1) #define io115_config_output -#define io115_set_output ic74hc595_set_pin(115);ic74hc595_shift_io_pins() -#define io115_clear_output ic74hc595_clear_pin(115);ic74hc595_shift_io_pins() -#define io115_toggle_output ic74hc595_toggle_pin(115);ic74hc595_shift_io_pins() -#define io115_get_output ic74hc595_get_pin(115) +#define io115_set_output ic74hc595_set_pin(ANALOG1);ic74hc595_shift_io_pins() +#define io115_clear_output ic74hc595_clear_pin(ANALOG1);ic74hc595_shift_io_pins() +#define io115_toggle_output ic74hc595_toggle_pin(ANALOG1);ic74hc595_shift_io_pins() +#define io115_get_output ic74hc595_get_pin(ANALOG1) #define io115_config_input #define io115_config_pullup #define io115_get_input 0 @@ -2640,21 +2640,21 @@ extern "C" #define io115_config_pullup #define io115_get_input 0 #endif -#if ASSERT_PIN_IO(116) -#define io116_config_output mcu_config_output(116) -#define io116_set_output mcu_set_output(116) -#define io116_clear_output mcu_clear_output(116) -#define io116_toggle_output mcu_toggle_output(116) -#define io116_get_output mcu_get_output(116) -#define io116_config_input mcu_config_input(116) -#define io116_config_pullup mcu_config_pullup(116) -#define io116_get_input mcu_get_input(116) -#elif ASSERT_PIN_EXTENDED(116) +#if ASSERT_PIN_IO(ANALOG2) +#define io116_config_output mcu_config_output(ANALOG2) +#define io116_set_output mcu_set_output(ANALOG2) +#define io116_clear_output mcu_clear_output(ANALOG2) +#define io116_toggle_output mcu_toggle_output(ANALOG2) +#define io116_get_output mcu_get_output(ANALOG2) +#define io116_config_input mcu_config_input(ANALOG2) +#define io116_config_pullup mcu_config_pullup(ANALOG2) +#define io116_get_input mcu_get_input(ANALOG2) +#elif ASSERT_PIN_EXTENDED(ANALOG2) #define io116_config_output -#define io116_set_output ic74hc595_set_pin(116);ic74hc595_shift_io_pins() -#define io116_clear_output ic74hc595_clear_pin(116);ic74hc595_shift_io_pins() -#define io116_toggle_output ic74hc595_toggle_pin(116);ic74hc595_shift_io_pins() -#define io116_get_output ic74hc595_get_pin(116) +#define io116_set_output ic74hc595_set_pin(ANALOG2);ic74hc595_shift_io_pins() +#define io116_clear_output ic74hc595_clear_pin(ANALOG2);ic74hc595_shift_io_pins() +#define io116_toggle_output ic74hc595_toggle_pin(ANALOG2);ic74hc595_shift_io_pins() +#define io116_get_output ic74hc595_get_pin(ANALOG2) #define io116_config_input #define io116_config_pullup #define io116_get_input 0 @@ -2668,21 +2668,21 @@ extern "C" #define io116_config_pullup #define io116_get_input 0 #endif -#if ASSERT_PIN_IO(117) -#define io117_config_output mcu_config_output(117) -#define io117_set_output mcu_set_output(117) -#define io117_clear_output mcu_clear_output(117) -#define io117_toggle_output mcu_toggle_output(117) -#define io117_get_output mcu_get_output(117) -#define io117_config_input mcu_config_input(117) -#define io117_config_pullup mcu_config_pullup(117) -#define io117_get_input mcu_get_input(117) -#elif ASSERT_PIN_EXTENDED(117) +#if ASSERT_PIN_IO(ANALOG3) +#define io117_config_output mcu_config_output(ANALOG3) +#define io117_set_output mcu_set_output(ANALOG3) +#define io117_clear_output mcu_clear_output(ANALOG3) +#define io117_toggle_output mcu_toggle_output(ANALOG3) +#define io117_get_output mcu_get_output(ANALOG3) +#define io117_config_input mcu_config_input(ANALOG3) +#define io117_config_pullup mcu_config_pullup(ANALOG3) +#define io117_get_input mcu_get_input(ANALOG3) +#elif ASSERT_PIN_EXTENDED(ANALOG3) #define io117_config_output -#define io117_set_output ic74hc595_set_pin(117);ic74hc595_shift_io_pins() -#define io117_clear_output ic74hc595_clear_pin(117);ic74hc595_shift_io_pins() -#define io117_toggle_output ic74hc595_toggle_pin(117);ic74hc595_shift_io_pins() -#define io117_get_output ic74hc595_get_pin(117) +#define io117_set_output ic74hc595_set_pin(ANALOG3);ic74hc595_shift_io_pins() +#define io117_clear_output ic74hc595_clear_pin(ANALOG3);ic74hc595_shift_io_pins() +#define io117_toggle_output ic74hc595_toggle_pin(ANALOG3);ic74hc595_shift_io_pins() +#define io117_get_output ic74hc595_get_pin(ANALOG3) #define io117_config_input #define io117_config_pullup #define io117_get_input 0 @@ -2696,21 +2696,21 @@ extern "C" #define io117_config_pullup #define io117_get_input 0 #endif -#if ASSERT_PIN_IO(118) -#define io118_config_output mcu_config_output(118) -#define io118_set_output mcu_set_output(118) -#define io118_clear_output mcu_clear_output(118) -#define io118_toggle_output mcu_toggle_output(118) -#define io118_get_output mcu_get_output(118) -#define io118_config_input mcu_config_input(118) -#define io118_config_pullup mcu_config_pullup(118) -#define io118_get_input mcu_get_input(118) -#elif ASSERT_PIN_EXTENDED(118) +#if ASSERT_PIN_IO(ANALOG4) +#define io118_config_output mcu_config_output(ANALOG4) +#define io118_set_output mcu_set_output(ANALOG4) +#define io118_clear_output mcu_clear_output(ANALOG4) +#define io118_toggle_output mcu_toggle_output(ANALOG4) +#define io118_get_output mcu_get_output(ANALOG4) +#define io118_config_input mcu_config_input(ANALOG4) +#define io118_config_pullup mcu_config_pullup(ANALOG4) +#define io118_get_input mcu_get_input(ANALOG4) +#elif ASSERT_PIN_EXTENDED(ANALOG4) #define io118_config_output -#define io118_set_output ic74hc595_set_pin(118);ic74hc595_shift_io_pins() -#define io118_clear_output ic74hc595_clear_pin(118);ic74hc595_shift_io_pins() -#define io118_toggle_output ic74hc595_toggle_pin(118);ic74hc595_shift_io_pins() -#define io118_get_output ic74hc595_get_pin(118) +#define io118_set_output ic74hc595_set_pin(ANALOG4);ic74hc595_shift_io_pins() +#define io118_clear_output ic74hc595_clear_pin(ANALOG4);ic74hc595_shift_io_pins() +#define io118_toggle_output ic74hc595_toggle_pin(ANALOG4);ic74hc595_shift_io_pins() +#define io118_get_output ic74hc595_get_pin(ANALOG4) #define io118_config_input #define io118_config_pullup #define io118_get_input 0 @@ -2724,21 +2724,21 @@ extern "C" #define io118_config_pullup #define io118_get_input 0 #endif -#if ASSERT_PIN_IO(119) -#define io119_config_output mcu_config_output(119) -#define io119_set_output mcu_set_output(119) -#define io119_clear_output mcu_clear_output(119) -#define io119_toggle_output mcu_toggle_output(119) -#define io119_get_output mcu_get_output(119) -#define io119_config_input mcu_config_input(119) -#define io119_config_pullup mcu_config_pullup(119) -#define io119_get_input mcu_get_input(119) -#elif ASSERT_PIN_EXTENDED(119) +#if ASSERT_PIN_IO(ANALOG5) +#define io119_config_output mcu_config_output(ANALOG5) +#define io119_set_output mcu_set_output(ANALOG5) +#define io119_clear_output mcu_clear_output(ANALOG5) +#define io119_toggle_output mcu_toggle_output(ANALOG5) +#define io119_get_output mcu_get_output(ANALOG5) +#define io119_config_input mcu_config_input(ANALOG5) +#define io119_config_pullup mcu_config_pullup(ANALOG5) +#define io119_get_input mcu_get_input(ANALOG5) +#elif ASSERT_PIN_EXTENDED(ANALOG5) #define io119_config_output -#define io119_set_output ic74hc595_set_pin(119);ic74hc595_shift_io_pins() -#define io119_clear_output ic74hc595_clear_pin(119);ic74hc595_shift_io_pins() -#define io119_toggle_output ic74hc595_toggle_pin(119);ic74hc595_shift_io_pins() -#define io119_get_output ic74hc595_get_pin(119) +#define io119_set_output ic74hc595_set_pin(ANALOG5);ic74hc595_shift_io_pins() +#define io119_clear_output ic74hc595_clear_pin(ANALOG5);ic74hc595_shift_io_pins() +#define io119_toggle_output ic74hc595_toggle_pin(ANALOG5);ic74hc595_shift_io_pins() +#define io119_get_output ic74hc595_get_pin(ANALOG5) #define io119_config_input #define io119_config_pullup #define io119_get_input 0 @@ -2752,21 +2752,21 @@ extern "C" #define io119_config_pullup #define io119_get_input 0 #endif -#if ASSERT_PIN_IO(120) -#define io120_config_output mcu_config_output(120) -#define io120_set_output mcu_set_output(120) -#define io120_clear_output mcu_clear_output(120) -#define io120_toggle_output mcu_toggle_output(120) -#define io120_get_output mcu_get_output(120) -#define io120_config_input mcu_config_input(120) -#define io120_config_pullup mcu_config_pullup(120) -#define io120_get_input mcu_get_input(120) -#elif ASSERT_PIN_EXTENDED(120) +#if ASSERT_PIN_IO(ANALOG6) +#define io120_config_output mcu_config_output(ANALOG6) +#define io120_set_output mcu_set_output(ANALOG6) +#define io120_clear_output mcu_clear_output(ANALOG6) +#define io120_toggle_output mcu_toggle_output(ANALOG6) +#define io120_get_output mcu_get_output(ANALOG6) +#define io120_config_input mcu_config_input(ANALOG6) +#define io120_config_pullup mcu_config_pullup(ANALOG6) +#define io120_get_input mcu_get_input(ANALOG6) +#elif ASSERT_PIN_EXTENDED(ANALOG6) #define io120_config_output -#define io120_set_output ic74hc595_set_pin(120);ic74hc595_shift_io_pins() -#define io120_clear_output ic74hc595_clear_pin(120);ic74hc595_shift_io_pins() -#define io120_toggle_output ic74hc595_toggle_pin(120);ic74hc595_shift_io_pins() -#define io120_get_output ic74hc595_get_pin(120) +#define io120_set_output ic74hc595_set_pin(ANALOG6);ic74hc595_shift_io_pins() +#define io120_clear_output ic74hc595_clear_pin(ANALOG6);ic74hc595_shift_io_pins() +#define io120_toggle_output ic74hc595_toggle_pin(ANALOG6);ic74hc595_shift_io_pins() +#define io120_get_output ic74hc595_get_pin(ANALOG6) #define io120_config_input #define io120_config_pullup #define io120_get_input 0 @@ -2780,21 +2780,21 @@ extern "C" #define io120_config_pullup #define io120_get_input 0 #endif -#if ASSERT_PIN_IO(121) -#define io121_config_output mcu_config_output(121) -#define io121_set_output mcu_set_output(121) -#define io121_clear_output mcu_clear_output(121) -#define io121_toggle_output mcu_toggle_output(121) -#define io121_get_output mcu_get_output(121) -#define io121_config_input mcu_config_input(121) -#define io121_config_pullup mcu_config_pullup(121) -#define io121_get_input mcu_get_input(121) -#elif ASSERT_PIN_EXTENDED(121) +#if ASSERT_PIN_IO(ANALOG7) +#define io121_config_output mcu_config_output(ANALOG7) +#define io121_set_output mcu_set_output(ANALOG7) +#define io121_clear_output mcu_clear_output(ANALOG7) +#define io121_toggle_output mcu_toggle_output(ANALOG7) +#define io121_get_output mcu_get_output(ANALOG7) +#define io121_config_input mcu_config_input(ANALOG7) +#define io121_config_pullup mcu_config_pullup(ANALOG7) +#define io121_get_input mcu_get_input(ANALOG7) +#elif ASSERT_PIN_EXTENDED(ANALOG7) #define io121_config_output -#define io121_set_output ic74hc595_set_pin(121);ic74hc595_shift_io_pins() -#define io121_clear_output ic74hc595_clear_pin(121);ic74hc595_shift_io_pins() -#define io121_toggle_output ic74hc595_toggle_pin(121);ic74hc595_shift_io_pins() -#define io121_get_output ic74hc595_get_pin(121) +#define io121_set_output ic74hc595_set_pin(ANALOG7);ic74hc595_shift_io_pins() +#define io121_clear_output ic74hc595_clear_pin(ANALOG7);ic74hc595_shift_io_pins() +#define io121_toggle_output ic74hc595_toggle_pin(ANALOG7);ic74hc595_shift_io_pins() +#define io121_get_output ic74hc595_get_pin(ANALOG7) #define io121_config_input #define io121_config_pullup #define io121_get_input 0 @@ -2808,21 +2808,21 @@ extern "C" #define io121_config_pullup #define io121_get_input 0 #endif -#if ASSERT_PIN_IO(122) -#define io122_config_output mcu_config_output(122) -#define io122_set_output mcu_set_output(122) -#define io122_clear_output mcu_clear_output(122) -#define io122_toggle_output mcu_toggle_output(122) -#define io122_get_output mcu_get_output(122) -#define io122_config_input mcu_config_input(122) -#define io122_config_pullup mcu_config_pullup(122) -#define io122_get_input mcu_get_input(122) -#elif ASSERT_PIN_EXTENDED(122) +#if ASSERT_PIN_IO(ANALOG8) +#define io122_config_output mcu_config_output(ANALOG8) +#define io122_set_output mcu_set_output(ANALOG8) +#define io122_clear_output mcu_clear_output(ANALOG8) +#define io122_toggle_output mcu_toggle_output(ANALOG8) +#define io122_get_output mcu_get_output(ANALOG8) +#define io122_config_input mcu_config_input(ANALOG8) +#define io122_config_pullup mcu_config_pullup(ANALOG8) +#define io122_get_input mcu_get_input(ANALOG8) +#elif ASSERT_PIN_EXTENDED(ANALOG8) #define io122_config_output -#define io122_set_output ic74hc595_set_pin(122);ic74hc595_shift_io_pins() -#define io122_clear_output ic74hc595_clear_pin(122);ic74hc595_shift_io_pins() -#define io122_toggle_output ic74hc595_toggle_pin(122);ic74hc595_shift_io_pins() -#define io122_get_output ic74hc595_get_pin(122) +#define io122_set_output ic74hc595_set_pin(ANALOG8);ic74hc595_shift_io_pins() +#define io122_clear_output ic74hc595_clear_pin(ANALOG8);ic74hc595_shift_io_pins() +#define io122_toggle_output ic74hc595_toggle_pin(ANALOG8);ic74hc595_shift_io_pins() +#define io122_get_output ic74hc595_get_pin(ANALOG8) #define io122_config_input #define io122_config_pullup #define io122_get_input 0 @@ -2836,21 +2836,21 @@ extern "C" #define io122_config_pullup #define io122_get_input 0 #endif -#if ASSERT_PIN_IO(123) -#define io123_config_output mcu_config_output(123) -#define io123_set_output mcu_set_output(123) -#define io123_clear_output mcu_clear_output(123) -#define io123_toggle_output mcu_toggle_output(123) -#define io123_get_output mcu_get_output(123) -#define io123_config_input mcu_config_input(123) -#define io123_config_pullup mcu_config_pullup(123) -#define io123_get_input mcu_get_input(123) -#elif ASSERT_PIN_EXTENDED(123) +#if ASSERT_PIN_IO(ANALOG9) +#define io123_config_output mcu_config_output(ANALOG9) +#define io123_set_output mcu_set_output(ANALOG9) +#define io123_clear_output mcu_clear_output(ANALOG9) +#define io123_toggle_output mcu_toggle_output(ANALOG9) +#define io123_get_output mcu_get_output(ANALOG9) +#define io123_config_input mcu_config_input(ANALOG9) +#define io123_config_pullup mcu_config_pullup(ANALOG9) +#define io123_get_input mcu_get_input(ANALOG9) +#elif ASSERT_PIN_EXTENDED(ANALOG9) #define io123_config_output -#define io123_set_output ic74hc595_set_pin(123);ic74hc595_shift_io_pins() -#define io123_clear_output ic74hc595_clear_pin(123);ic74hc595_shift_io_pins() -#define io123_toggle_output ic74hc595_toggle_pin(123);ic74hc595_shift_io_pins() -#define io123_get_output ic74hc595_get_pin(123) +#define io123_set_output ic74hc595_set_pin(ANALOG9);ic74hc595_shift_io_pins() +#define io123_clear_output ic74hc595_clear_pin(ANALOG9);ic74hc595_shift_io_pins() +#define io123_toggle_output ic74hc595_toggle_pin(ANALOG9);ic74hc595_shift_io_pins() +#define io123_get_output ic74hc595_get_pin(ANALOG9) #define io123_config_input #define io123_config_pullup #define io123_get_input 0 @@ -2864,21 +2864,21 @@ extern "C" #define io123_config_pullup #define io123_get_input 0 #endif -#if ASSERT_PIN_IO(124) -#define io124_config_output mcu_config_output(124) -#define io124_set_output mcu_set_output(124) -#define io124_clear_output mcu_clear_output(124) -#define io124_toggle_output mcu_toggle_output(124) -#define io124_get_output mcu_get_output(124) -#define io124_config_input mcu_config_input(124) -#define io124_config_pullup mcu_config_pullup(124) -#define io124_get_input mcu_get_input(124) -#elif ASSERT_PIN_EXTENDED(124) +#if ASSERT_PIN_IO(ANALOG10) +#define io124_config_output mcu_config_output(ANALOG10) +#define io124_set_output mcu_set_output(ANALOG10) +#define io124_clear_output mcu_clear_output(ANALOG10) +#define io124_toggle_output mcu_toggle_output(ANALOG10) +#define io124_get_output mcu_get_output(ANALOG10) +#define io124_config_input mcu_config_input(ANALOG10) +#define io124_config_pullup mcu_config_pullup(ANALOG10) +#define io124_get_input mcu_get_input(ANALOG10) +#elif ASSERT_PIN_EXTENDED(ANALOG10) #define io124_config_output -#define io124_set_output ic74hc595_set_pin(124);ic74hc595_shift_io_pins() -#define io124_clear_output ic74hc595_clear_pin(124);ic74hc595_shift_io_pins() -#define io124_toggle_output ic74hc595_toggle_pin(124);ic74hc595_shift_io_pins() -#define io124_get_output ic74hc595_get_pin(124) +#define io124_set_output ic74hc595_set_pin(ANALOG10);ic74hc595_shift_io_pins() +#define io124_clear_output ic74hc595_clear_pin(ANALOG10);ic74hc595_shift_io_pins() +#define io124_toggle_output ic74hc595_toggle_pin(ANALOG10);ic74hc595_shift_io_pins() +#define io124_get_output ic74hc595_get_pin(ANALOG10) #define io124_config_input #define io124_config_pullup #define io124_get_input 0 @@ -2892,21 +2892,21 @@ extern "C" #define io124_config_pullup #define io124_get_input 0 #endif -#if ASSERT_PIN_IO(125) -#define io125_config_output mcu_config_output(125) -#define io125_set_output mcu_set_output(125) -#define io125_clear_output mcu_clear_output(125) -#define io125_toggle_output mcu_toggle_output(125) -#define io125_get_output mcu_get_output(125) -#define io125_config_input mcu_config_input(125) -#define io125_config_pullup mcu_config_pullup(125) -#define io125_get_input mcu_get_input(125) -#elif ASSERT_PIN_EXTENDED(125) +#if ASSERT_PIN_IO(ANALOG11) +#define io125_config_output mcu_config_output(ANALOG11) +#define io125_set_output mcu_set_output(ANALOG11) +#define io125_clear_output mcu_clear_output(ANALOG11) +#define io125_toggle_output mcu_toggle_output(ANALOG11) +#define io125_get_output mcu_get_output(ANALOG11) +#define io125_config_input mcu_config_input(ANALOG11) +#define io125_config_pullup mcu_config_pullup(ANALOG11) +#define io125_get_input mcu_get_input(ANALOG11) +#elif ASSERT_PIN_EXTENDED(ANALOG11) #define io125_config_output -#define io125_set_output ic74hc595_set_pin(125);ic74hc595_shift_io_pins() -#define io125_clear_output ic74hc595_clear_pin(125);ic74hc595_shift_io_pins() -#define io125_toggle_output ic74hc595_toggle_pin(125);ic74hc595_shift_io_pins() -#define io125_get_output ic74hc595_get_pin(125) +#define io125_set_output ic74hc595_set_pin(ANALOG11);ic74hc595_shift_io_pins() +#define io125_clear_output ic74hc595_clear_pin(ANALOG11);ic74hc595_shift_io_pins() +#define io125_toggle_output ic74hc595_toggle_pin(ANALOG11);ic74hc595_shift_io_pins() +#define io125_get_output ic74hc595_get_pin(ANALOG11) #define io125_config_input #define io125_config_pullup #define io125_get_input 0 @@ -2920,21 +2920,21 @@ extern "C" #define io125_config_pullup #define io125_get_input 0 #endif -#if ASSERT_PIN_IO(126) -#define io126_config_output mcu_config_output(126) -#define io126_set_output mcu_set_output(126) -#define io126_clear_output mcu_clear_output(126) -#define io126_toggle_output mcu_toggle_output(126) -#define io126_get_output mcu_get_output(126) -#define io126_config_input mcu_config_input(126) -#define io126_config_pullup mcu_config_pullup(126) -#define io126_get_input mcu_get_input(126) -#elif ASSERT_PIN_EXTENDED(126) +#if ASSERT_PIN_IO(ANALOG12) +#define io126_config_output mcu_config_output(ANALOG12) +#define io126_set_output mcu_set_output(ANALOG12) +#define io126_clear_output mcu_clear_output(ANALOG12) +#define io126_toggle_output mcu_toggle_output(ANALOG12) +#define io126_get_output mcu_get_output(ANALOG12) +#define io126_config_input mcu_config_input(ANALOG12) +#define io126_config_pullup mcu_config_pullup(ANALOG12) +#define io126_get_input mcu_get_input(ANALOG12) +#elif ASSERT_PIN_EXTENDED(ANALOG12) #define io126_config_output -#define io126_set_output ic74hc595_set_pin(126);ic74hc595_shift_io_pins() -#define io126_clear_output ic74hc595_clear_pin(126);ic74hc595_shift_io_pins() -#define io126_toggle_output ic74hc595_toggle_pin(126);ic74hc595_shift_io_pins() -#define io126_get_output ic74hc595_get_pin(126) +#define io126_set_output ic74hc595_set_pin(ANALOG12);ic74hc595_shift_io_pins() +#define io126_clear_output ic74hc595_clear_pin(ANALOG12);ic74hc595_shift_io_pins() +#define io126_toggle_output ic74hc595_toggle_pin(ANALOG12);ic74hc595_shift_io_pins() +#define io126_get_output ic74hc595_get_pin(ANALOG12) #define io126_config_input #define io126_config_pullup #define io126_get_input 0 @@ -2948,21 +2948,21 @@ extern "C" #define io126_config_pullup #define io126_get_input 0 #endif -#if ASSERT_PIN_IO(127) -#define io127_config_output mcu_config_output(127) -#define io127_set_output mcu_set_output(127) -#define io127_clear_output mcu_clear_output(127) -#define io127_toggle_output mcu_toggle_output(127) -#define io127_get_output mcu_get_output(127) -#define io127_config_input mcu_config_input(127) -#define io127_config_pullup mcu_config_pullup(127) -#define io127_get_input mcu_get_input(127) -#elif ASSERT_PIN_EXTENDED(127) +#if ASSERT_PIN_IO(ANALOG13) +#define io127_config_output mcu_config_output(ANALOG13) +#define io127_set_output mcu_set_output(ANALOG13) +#define io127_clear_output mcu_clear_output(ANALOG13) +#define io127_toggle_output mcu_toggle_output(ANALOG13) +#define io127_get_output mcu_get_output(ANALOG13) +#define io127_config_input mcu_config_input(ANALOG13) +#define io127_config_pullup mcu_config_pullup(ANALOG13) +#define io127_get_input mcu_get_input(ANALOG13) +#elif ASSERT_PIN_EXTENDED(ANALOG13) #define io127_config_output -#define io127_set_output ic74hc595_set_pin(127);ic74hc595_shift_io_pins() -#define io127_clear_output ic74hc595_clear_pin(127);ic74hc595_shift_io_pins() -#define io127_toggle_output ic74hc595_toggle_pin(127);ic74hc595_shift_io_pins() -#define io127_get_output ic74hc595_get_pin(127) +#define io127_set_output ic74hc595_set_pin(ANALOG13);ic74hc595_shift_io_pins() +#define io127_clear_output ic74hc595_clear_pin(ANALOG13);ic74hc595_shift_io_pins() +#define io127_toggle_output ic74hc595_toggle_pin(ANALOG13);ic74hc595_shift_io_pins() +#define io127_get_output ic74hc595_get_pin(ANALOG13) #define io127_config_input #define io127_config_pullup #define io127_get_input 0 @@ -2976,21 +2976,21 @@ extern "C" #define io127_config_pullup #define io127_get_input 0 #endif -#if ASSERT_PIN_IO(128) -#define io128_config_output mcu_config_output(128) -#define io128_set_output mcu_set_output(128) -#define io128_clear_output mcu_clear_output(128) -#define io128_toggle_output mcu_toggle_output(128) -#define io128_get_output mcu_get_output(128) -#define io128_config_input mcu_config_input(128) -#define io128_config_pullup mcu_config_pullup(128) -#define io128_get_input mcu_get_input(128) -#elif ASSERT_PIN_EXTENDED(128) +#if ASSERT_PIN_IO(ANALOG14) +#define io128_config_output mcu_config_output(ANALOG14) +#define io128_set_output mcu_set_output(ANALOG14) +#define io128_clear_output mcu_clear_output(ANALOG14) +#define io128_toggle_output mcu_toggle_output(ANALOG14) +#define io128_get_output mcu_get_output(ANALOG14) +#define io128_config_input mcu_config_input(ANALOG14) +#define io128_config_pullup mcu_config_pullup(ANALOG14) +#define io128_get_input mcu_get_input(ANALOG14) +#elif ASSERT_PIN_EXTENDED(ANALOG14) #define io128_config_output -#define io128_set_output ic74hc595_set_pin(128);ic74hc595_shift_io_pins() -#define io128_clear_output ic74hc595_clear_pin(128);ic74hc595_shift_io_pins() -#define io128_toggle_output ic74hc595_toggle_pin(128);ic74hc595_shift_io_pins() -#define io128_get_output ic74hc595_get_pin(128) +#define io128_set_output ic74hc595_set_pin(ANALOG14);ic74hc595_shift_io_pins() +#define io128_clear_output ic74hc595_clear_pin(ANALOG14);ic74hc595_shift_io_pins() +#define io128_toggle_output ic74hc595_toggle_pin(ANALOG14);ic74hc595_shift_io_pins() +#define io128_get_output ic74hc595_get_pin(ANALOG14) #define io128_config_input #define io128_config_pullup #define io128_get_input 0 @@ -3004,21 +3004,21 @@ extern "C" #define io128_config_pullup #define io128_get_input 0 #endif -#if ASSERT_PIN_IO(129) -#define io129_config_output mcu_config_output(129) -#define io129_set_output mcu_set_output(129) -#define io129_clear_output mcu_clear_output(129) -#define io129_toggle_output mcu_toggle_output(129) -#define io129_get_output mcu_get_output(129) -#define io129_config_input mcu_config_input(129) -#define io129_config_pullup mcu_config_pullup(129) -#define io129_get_input mcu_get_input(129) -#elif ASSERT_PIN_EXTENDED(129) +#if ASSERT_PIN_IO(ANALOG15) +#define io129_config_output mcu_config_output(ANALOG15) +#define io129_set_output mcu_set_output(ANALOG15) +#define io129_clear_output mcu_clear_output(ANALOG15) +#define io129_toggle_output mcu_toggle_output(ANALOG15) +#define io129_get_output mcu_get_output(ANALOG15) +#define io129_config_input mcu_config_input(ANALOG15) +#define io129_config_pullup mcu_config_pullup(ANALOG15) +#define io129_get_input mcu_get_input(ANALOG15) +#elif ASSERT_PIN_EXTENDED(ANALOG15) #define io129_config_output -#define io129_set_output ic74hc595_set_pin(129);ic74hc595_shift_io_pins() -#define io129_clear_output ic74hc595_clear_pin(129);ic74hc595_shift_io_pins() -#define io129_toggle_output ic74hc595_toggle_pin(129);ic74hc595_shift_io_pins() -#define io129_get_output ic74hc595_get_pin(129) +#define io129_set_output ic74hc595_set_pin(ANALOG15);ic74hc595_shift_io_pins() +#define io129_clear_output ic74hc595_clear_pin(ANALOG15);ic74hc595_shift_io_pins() +#define io129_toggle_output ic74hc595_toggle_pin(ANALOG15);ic74hc595_shift_io_pins() +#define io129_get_output ic74hc595_get_pin(ANALOG15) #define io129_config_input #define io129_config_pullup #define io129_get_input 0 @@ -3032,21 +3032,21 @@ extern "C" #define io129_config_pullup #define io129_get_input 0 #endif -#if ASSERT_PIN_IO(130) -#define io130_config_output mcu_config_output(130) -#define io130_set_output mcu_set_output(130) -#define io130_clear_output mcu_clear_output(130) -#define io130_toggle_output mcu_toggle_output(130) -#define io130_get_output mcu_get_output(130) -#define io130_config_input mcu_config_input(130) -#define io130_config_pullup mcu_config_pullup(130) -#define io130_get_input mcu_get_input(130) -#elif ASSERT_PIN_EXTENDED(130) +#if ASSERT_PIN_IO(DIN0) +#define io130_config_output mcu_config_output(DIN0) +#define io130_set_output mcu_set_output(DIN0) +#define io130_clear_output mcu_clear_output(DIN0) +#define io130_toggle_output mcu_toggle_output(DIN0) +#define io130_get_output mcu_get_output(DIN0) +#define io130_config_input mcu_config_input(DIN0) +#define io130_config_pullup mcu_config_pullup(DIN0) +#define io130_get_input mcu_get_input(DIN0) +#elif ASSERT_PIN_EXTENDED(DIN0) #define io130_config_output -#define io130_set_output ic74hc595_set_pin(130);ic74hc595_shift_io_pins() -#define io130_clear_output ic74hc595_clear_pin(130);ic74hc595_shift_io_pins() -#define io130_toggle_output ic74hc595_toggle_pin(130);ic74hc595_shift_io_pins() -#define io130_get_output ic74hc595_get_pin(130) +#define io130_set_output ic74hc595_set_pin(DIN0);ic74hc595_shift_io_pins() +#define io130_clear_output ic74hc595_clear_pin(DIN0);ic74hc595_shift_io_pins() +#define io130_toggle_output ic74hc595_toggle_pin(DIN0);ic74hc595_shift_io_pins() +#define io130_get_output ic74hc595_get_pin(DIN0) #define io130_config_input #define io130_config_pullup #define io130_get_input 0 @@ -3060,21 +3060,21 @@ extern "C" #define io130_config_pullup #define io130_get_input 0 #endif -#if ASSERT_PIN_IO(131) -#define io131_config_output mcu_config_output(131) -#define io131_set_output mcu_set_output(131) -#define io131_clear_output mcu_clear_output(131) -#define io131_toggle_output mcu_toggle_output(131) -#define io131_get_output mcu_get_output(131) -#define io131_config_input mcu_config_input(131) -#define io131_config_pullup mcu_config_pullup(131) -#define io131_get_input mcu_get_input(131) -#elif ASSERT_PIN_EXTENDED(131) +#if ASSERT_PIN_IO(DIN1) +#define io131_config_output mcu_config_output(DIN1) +#define io131_set_output mcu_set_output(DIN1) +#define io131_clear_output mcu_clear_output(DIN1) +#define io131_toggle_output mcu_toggle_output(DIN1) +#define io131_get_output mcu_get_output(DIN1) +#define io131_config_input mcu_config_input(DIN1) +#define io131_config_pullup mcu_config_pullup(DIN1) +#define io131_get_input mcu_get_input(DIN1) +#elif ASSERT_PIN_EXTENDED(DIN1) #define io131_config_output -#define io131_set_output ic74hc595_set_pin(131);ic74hc595_shift_io_pins() -#define io131_clear_output ic74hc595_clear_pin(131);ic74hc595_shift_io_pins() -#define io131_toggle_output ic74hc595_toggle_pin(131);ic74hc595_shift_io_pins() -#define io131_get_output ic74hc595_get_pin(131) +#define io131_set_output ic74hc595_set_pin(DIN1);ic74hc595_shift_io_pins() +#define io131_clear_output ic74hc595_clear_pin(DIN1);ic74hc595_shift_io_pins() +#define io131_toggle_output ic74hc595_toggle_pin(DIN1);ic74hc595_shift_io_pins() +#define io131_get_output ic74hc595_get_pin(DIN1) #define io131_config_input #define io131_config_pullup #define io131_get_input 0 @@ -3088,21 +3088,21 @@ extern "C" #define io131_config_pullup #define io131_get_input 0 #endif -#if ASSERT_PIN_IO(132) -#define io132_config_output mcu_config_output(132) -#define io132_set_output mcu_set_output(132) -#define io132_clear_output mcu_clear_output(132) -#define io132_toggle_output mcu_toggle_output(132) -#define io132_get_output mcu_get_output(132) -#define io132_config_input mcu_config_input(132) -#define io132_config_pullup mcu_config_pullup(132) -#define io132_get_input mcu_get_input(132) -#elif ASSERT_PIN_EXTENDED(132) +#if ASSERT_PIN_IO(DIN2) +#define io132_config_output mcu_config_output(DIN2) +#define io132_set_output mcu_set_output(DIN2) +#define io132_clear_output mcu_clear_output(DIN2) +#define io132_toggle_output mcu_toggle_output(DIN2) +#define io132_get_output mcu_get_output(DIN2) +#define io132_config_input mcu_config_input(DIN2) +#define io132_config_pullup mcu_config_pullup(DIN2) +#define io132_get_input mcu_get_input(DIN2) +#elif ASSERT_PIN_EXTENDED(DIN2) #define io132_config_output -#define io132_set_output ic74hc595_set_pin(132);ic74hc595_shift_io_pins() -#define io132_clear_output ic74hc595_clear_pin(132);ic74hc595_shift_io_pins() -#define io132_toggle_output ic74hc595_toggle_pin(132);ic74hc595_shift_io_pins() -#define io132_get_output ic74hc595_get_pin(132) +#define io132_set_output ic74hc595_set_pin(DIN2);ic74hc595_shift_io_pins() +#define io132_clear_output ic74hc595_clear_pin(DIN2);ic74hc595_shift_io_pins() +#define io132_toggle_output ic74hc595_toggle_pin(DIN2);ic74hc595_shift_io_pins() +#define io132_get_output ic74hc595_get_pin(DIN2) #define io132_config_input #define io132_config_pullup #define io132_get_input 0 @@ -3116,21 +3116,21 @@ extern "C" #define io132_config_pullup #define io132_get_input 0 #endif -#if ASSERT_PIN_IO(133) -#define io133_config_output mcu_config_output(133) -#define io133_set_output mcu_set_output(133) -#define io133_clear_output mcu_clear_output(133) -#define io133_toggle_output mcu_toggle_output(133) -#define io133_get_output mcu_get_output(133) -#define io133_config_input mcu_config_input(133) -#define io133_config_pullup mcu_config_pullup(133) -#define io133_get_input mcu_get_input(133) -#elif ASSERT_PIN_EXTENDED(133) +#if ASSERT_PIN_IO(DIN3) +#define io133_config_output mcu_config_output(DIN3) +#define io133_set_output mcu_set_output(DIN3) +#define io133_clear_output mcu_clear_output(DIN3) +#define io133_toggle_output mcu_toggle_output(DIN3) +#define io133_get_output mcu_get_output(DIN3) +#define io133_config_input mcu_config_input(DIN3) +#define io133_config_pullup mcu_config_pullup(DIN3) +#define io133_get_input mcu_get_input(DIN3) +#elif ASSERT_PIN_EXTENDED(DIN3) #define io133_config_output -#define io133_set_output ic74hc595_set_pin(133);ic74hc595_shift_io_pins() -#define io133_clear_output ic74hc595_clear_pin(133);ic74hc595_shift_io_pins() -#define io133_toggle_output ic74hc595_toggle_pin(133);ic74hc595_shift_io_pins() -#define io133_get_output ic74hc595_get_pin(133) +#define io133_set_output ic74hc595_set_pin(DIN3);ic74hc595_shift_io_pins() +#define io133_clear_output ic74hc595_clear_pin(DIN3);ic74hc595_shift_io_pins() +#define io133_toggle_output ic74hc595_toggle_pin(DIN3);ic74hc595_shift_io_pins() +#define io133_get_output ic74hc595_get_pin(DIN3) #define io133_config_input #define io133_config_pullup #define io133_get_input 0 @@ -3144,21 +3144,21 @@ extern "C" #define io133_config_pullup #define io133_get_input 0 #endif -#if ASSERT_PIN_IO(134) -#define io134_config_output mcu_config_output(134) -#define io134_set_output mcu_set_output(134) -#define io134_clear_output mcu_clear_output(134) -#define io134_toggle_output mcu_toggle_output(134) -#define io134_get_output mcu_get_output(134) -#define io134_config_input mcu_config_input(134) -#define io134_config_pullup mcu_config_pullup(134) -#define io134_get_input mcu_get_input(134) -#elif ASSERT_PIN_EXTENDED(134) +#if ASSERT_PIN_IO(DIN4) +#define io134_config_output mcu_config_output(DIN4) +#define io134_set_output mcu_set_output(DIN4) +#define io134_clear_output mcu_clear_output(DIN4) +#define io134_toggle_output mcu_toggle_output(DIN4) +#define io134_get_output mcu_get_output(DIN4) +#define io134_config_input mcu_config_input(DIN4) +#define io134_config_pullup mcu_config_pullup(DIN4) +#define io134_get_input mcu_get_input(DIN4) +#elif ASSERT_PIN_EXTENDED(DIN4) #define io134_config_output -#define io134_set_output ic74hc595_set_pin(134);ic74hc595_shift_io_pins() -#define io134_clear_output ic74hc595_clear_pin(134);ic74hc595_shift_io_pins() -#define io134_toggle_output ic74hc595_toggle_pin(134);ic74hc595_shift_io_pins() -#define io134_get_output ic74hc595_get_pin(134) +#define io134_set_output ic74hc595_set_pin(DIN4);ic74hc595_shift_io_pins() +#define io134_clear_output ic74hc595_clear_pin(DIN4);ic74hc595_shift_io_pins() +#define io134_toggle_output ic74hc595_toggle_pin(DIN4);ic74hc595_shift_io_pins() +#define io134_get_output ic74hc595_get_pin(DIN4) #define io134_config_input #define io134_config_pullup #define io134_get_input 0 @@ -3172,21 +3172,21 @@ extern "C" #define io134_config_pullup #define io134_get_input 0 #endif -#if ASSERT_PIN_IO(135) -#define io135_config_output mcu_config_output(135) -#define io135_set_output mcu_set_output(135) -#define io135_clear_output mcu_clear_output(135) -#define io135_toggle_output mcu_toggle_output(135) -#define io135_get_output mcu_get_output(135) -#define io135_config_input mcu_config_input(135) -#define io135_config_pullup mcu_config_pullup(135) -#define io135_get_input mcu_get_input(135) -#elif ASSERT_PIN_EXTENDED(135) +#if ASSERT_PIN_IO(DIN5) +#define io135_config_output mcu_config_output(DIN5) +#define io135_set_output mcu_set_output(DIN5) +#define io135_clear_output mcu_clear_output(DIN5) +#define io135_toggle_output mcu_toggle_output(DIN5) +#define io135_get_output mcu_get_output(DIN5) +#define io135_config_input mcu_config_input(DIN5) +#define io135_config_pullup mcu_config_pullup(DIN5) +#define io135_get_input mcu_get_input(DIN5) +#elif ASSERT_PIN_EXTENDED(DIN5) #define io135_config_output -#define io135_set_output ic74hc595_set_pin(135);ic74hc595_shift_io_pins() -#define io135_clear_output ic74hc595_clear_pin(135);ic74hc595_shift_io_pins() -#define io135_toggle_output ic74hc595_toggle_pin(135);ic74hc595_shift_io_pins() -#define io135_get_output ic74hc595_get_pin(135) +#define io135_set_output ic74hc595_set_pin(DIN5);ic74hc595_shift_io_pins() +#define io135_clear_output ic74hc595_clear_pin(DIN5);ic74hc595_shift_io_pins() +#define io135_toggle_output ic74hc595_toggle_pin(DIN5);ic74hc595_shift_io_pins() +#define io135_get_output ic74hc595_get_pin(DIN5) #define io135_config_input #define io135_config_pullup #define io135_get_input 0 @@ -3200,21 +3200,21 @@ extern "C" #define io135_config_pullup #define io135_get_input 0 #endif -#if ASSERT_PIN_IO(136) -#define io136_config_output mcu_config_output(136) -#define io136_set_output mcu_set_output(136) -#define io136_clear_output mcu_clear_output(136) -#define io136_toggle_output mcu_toggle_output(136) -#define io136_get_output mcu_get_output(136) -#define io136_config_input mcu_config_input(136) -#define io136_config_pullup mcu_config_pullup(136) -#define io136_get_input mcu_get_input(136) -#elif ASSERT_PIN_EXTENDED(136) +#if ASSERT_PIN_IO(DIN6) +#define io136_config_output mcu_config_output(DIN6) +#define io136_set_output mcu_set_output(DIN6) +#define io136_clear_output mcu_clear_output(DIN6) +#define io136_toggle_output mcu_toggle_output(DIN6) +#define io136_get_output mcu_get_output(DIN6) +#define io136_config_input mcu_config_input(DIN6) +#define io136_config_pullup mcu_config_pullup(DIN6) +#define io136_get_input mcu_get_input(DIN6) +#elif ASSERT_PIN_EXTENDED(DIN6) #define io136_config_output -#define io136_set_output ic74hc595_set_pin(136);ic74hc595_shift_io_pins() -#define io136_clear_output ic74hc595_clear_pin(136);ic74hc595_shift_io_pins() -#define io136_toggle_output ic74hc595_toggle_pin(136);ic74hc595_shift_io_pins() -#define io136_get_output ic74hc595_get_pin(136) +#define io136_set_output ic74hc595_set_pin(DIN6);ic74hc595_shift_io_pins() +#define io136_clear_output ic74hc595_clear_pin(DIN6);ic74hc595_shift_io_pins() +#define io136_toggle_output ic74hc595_toggle_pin(DIN6);ic74hc595_shift_io_pins() +#define io136_get_output ic74hc595_get_pin(DIN6) #define io136_config_input #define io136_config_pullup #define io136_get_input 0 @@ -3228,21 +3228,21 @@ extern "C" #define io136_config_pullup #define io136_get_input 0 #endif -#if ASSERT_PIN_IO(137) -#define io137_config_output mcu_config_output(137) -#define io137_set_output mcu_set_output(137) -#define io137_clear_output mcu_clear_output(137) -#define io137_toggle_output mcu_toggle_output(137) -#define io137_get_output mcu_get_output(137) -#define io137_config_input mcu_config_input(137) -#define io137_config_pullup mcu_config_pullup(137) -#define io137_get_input mcu_get_input(137) -#elif ASSERT_PIN_EXTENDED(137) +#if ASSERT_PIN_IO(DIN7) +#define io137_config_output mcu_config_output(DIN7) +#define io137_set_output mcu_set_output(DIN7) +#define io137_clear_output mcu_clear_output(DIN7) +#define io137_toggle_output mcu_toggle_output(DIN7) +#define io137_get_output mcu_get_output(DIN7) +#define io137_config_input mcu_config_input(DIN7) +#define io137_config_pullup mcu_config_pullup(DIN7) +#define io137_get_input mcu_get_input(DIN7) +#elif ASSERT_PIN_EXTENDED(DIN7) #define io137_config_output -#define io137_set_output ic74hc595_set_pin(137);ic74hc595_shift_io_pins() -#define io137_clear_output ic74hc595_clear_pin(137);ic74hc595_shift_io_pins() -#define io137_toggle_output ic74hc595_toggle_pin(137);ic74hc595_shift_io_pins() -#define io137_get_output ic74hc595_get_pin(137) +#define io137_set_output ic74hc595_set_pin(DIN7);ic74hc595_shift_io_pins() +#define io137_clear_output ic74hc595_clear_pin(DIN7);ic74hc595_shift_io_pins() +#define io137_toggle_output ic74hc595_toggle_pin(DIN7);ic74hc595_shift_io_pins() +#define io137_get_output ic74hc595_get_pin(DIN7) #define io137_config_input #define io137_config_pullup #define io137_get_input 0 @@ -3256,21 +3256,21 @@ extern "C" #define io137_config_pullup #define io137_get_input 0 #endif -#if ASSERT_PIN_IO(138) -#define io138_config_output mcu_config_output(138) -#define io138_set_output mcu_set_output(138) -#define io138_clear_output mcu_clear_output(138) -#define io138_toggle_output mcu_toggle_output(138) -#define io138_get_output mcu_get_output(138) -#define io138_config_input mcu_config_input(138) -#define io138_config_pullup mcu_config_pullup(138) -#define io138_get_input mcu_get_input(138) -#elif ASSERT_PIN_EXTENDED(138) +#if ASSERT_PIN_IO(DIN8) +#define io138_config_output mcu_config_output(DIN8) +#define io138_set_output mcu_set_output(DIN8) +#define io138_clear_output mcu_clear_output(DIN8) +#define io138_toggle_output mcu_toggle_output(DIN8) +#define io138_get_output mcu_get_output(DIN8) +#define io138_config_input mcu_config_input(DIN8) +#define io138_config_pullup mcu_config_pullup(DIN8) +#define io138_get_input mcu_get_input(DIN8) +#elif ASSERT_PIN_EXTENDED(DIN8) #define io138_config_output -#define io138_set_output ic74hc595_set_pin(138);ic74hc595_shift_io_pins() -#define io138_clear_output ic74hc595_clear_pin(138);ic74hc595_shift_io_pins() -#define io138_toggle_output ic74hc595_toggle_pin(138);ic74hc595_shift_io_pins() -#define io138_get_output ic74hc595_get_pin(138) +#define io138_set_output ic74hc595_set_pin(DIN8);ic74hc595_shift_io_pins() +#define io138_clear_output ic74hc595_clear_pin(DIN8);ic74hc595_shift_io_pins() +#define io138_toggle_output ic74hc595_toggle_pin(DIN8);ic74hc595_shift_io_pins() +#define io138_get_output ic74hc595_get_pin(DIN8) #define io138_config_input #define io138_config_pullup #define io138_get_input 0 @@ -3284,21 +3284,21 @@ extern "C" #define io138_config_pullup #define io138_get_input 0 #endif -#if ASSERT_PIN_IO(139) -#define io139_config_output mcu_config_output(139) -#define io139_set_output mcu_set_output(139) -#define io139_clear_output mcu_clear_output(139) -#define io139_toggle_output mcu_toggle_output(139) -#define io139_get_output mcu_get_output(139) -#define io139_config_input mcu_config_input(139) -#define io139_config_pullup mcu_config_pullup(139) -#define io139_get_input mcu_get_input(139) -#elif ASSERT_PIN_EXTENDED(139) +#if ASSERT_PIN_IO(DIN9) +#define io139_config_output mcu_config_output(DIN9) +#define io139_set_output mcu_set_output(DIN9) +#define io139_clear_output mcu_clear_output(DIN9) +#define io139_toggle_output mcu_toggle_output(DIN9) +#define io139_get_output mcu_get_output(DIN9) +#define io139_config_input mcu_config_input(DIN9) +#define io139_config_pullup mcu_config_pullup(DIN9) +#define io139_get_input mcu_get_input(DIN9) +#elif ASSERT_PIN_EXTENDED(DIN9) #define io139_config_output -#define io139_set_output ic74hc595_set_pin(139);ic74hc595_shift_io_pins() -#define io139_clear_output ic74hc595_clear_pin(139);ic74hc595_shift_io_pins() -#define io139_toggle_output ic74hc595_toggle_pin(139);ic74hc595_shift_io_pins() -#define io139_get_output ic74hc595_get_pin(139) +#define io139_set_output ic74hc595_set_pin(DIN9);ic74hc595_shift_io_pins() +#define io139_clear_output ic74hc595_clear_pin(DIN9);ic74hc595_shift_io_pins() +#define io139_toggle_output ic74hc595_toggle_pin(DIN9);ic74hc595_shift_io_pins() +#define io139_get_output ic74hc595_get_pin(DIN9) #define io139_config_input #define io139_config_pullup #define io139_get_input 0 @@ -3312,21 +3312,21 @@ extern "C" #define io139_config_pullup #define io139_get_input 0 #endif -#if ASSERT_PIN_IO(140) -#define io140_config_output mcu_config_output(140) -#define io140_set_output mcu_set_output(140) -#define io140_clear_output mcu_clear_output(140) -#define io140_toggle_output mcu_toggle_output(140) -#define io140_get_output mcu_get_output(140) -#define io140_config_input mcu_config_input(140) -#define io140_config_pullup mcu_config_pullup(140) -#define io140_get_input mcu_get_input(140) -#elif ASSERT_PIN_EXTENDED(140) +#if ASSERT_PIN_IO(DIN10) +#define io140_config_output mcu_config_output(DIN10) +#define io140_set_output mcu_set_output(DIN10) +#define io140_clear_output mcu_clear_output(DIN10) +#define io140_toggle_output mcu_toggle_output(DIN10) +#define io140_get_output mcu_get_output(DIN10) +#define io140_config_input mcu_config_input(DIN10) +#define io140_config_pullup mcu_config_pullup(DIN10) +#define io140_get_input mcu_get_input(DIN10) +#elif ASSERT_PIN_EXTENDED(DIN10) #define io140_config_output -#define io140_set_output ic74hc595_set_pin(140);ic74hc595_shift_io_pins() -#define io140_clear_output ic74hc595_clear_pin(140);ic74hc595_shift_io_pins() -#define io140_toggle_output ic74hc595_toggle_pin(140);ic74hc595_shift_io_pins() -#define io140_get_output ic74hc595_get_pin(140) +#define io140_set_output ic74hc595_set_pin(DIN10);ic74hc595_shift_io_pins() +#define io140_clear_output ic74hc595_clear_pin(DIN10);ic74hc595_shift_io_pins() +#define io140_toggle_output ic74hc595_toggle_pin(DIN10);ic74hc595_shift_io_pins() +#define io140_get_output ic74hc595_get_pin(DIN10) #define io140_config_input #define io140_config_pullup #define io140_get_input 0 @@ -3340,21 +3340,21 @@ extern "C" #define io140_config_pullup #define io140_get_input 0 #endif -#if ASSERT_PIN_IO(141) -#define io141_config_output mcu_config_output(141) -#define io141_set_output mcu_set_output(141) -#define io141_clear_output mcu_clear_output(141) -#define io141_toggle_output mcu_toggle_output(141) -#define io141_get_output mcu_get_output(141) -#define io141_config_input mcu_config_input(141) -#define io141_config_pullup mcu_config_pullup(141) -#define io141_get_input mcu_get_input(141) -#elif ASSERT_PIN_EXTENDED(141) +#if ASSERT_PIN_IO(DIN11) +#define io141_config_output mcu_config_output(DIN11) +#define io141_set_output mcu_set_output(DIN11) +#define io141_clear_output mcu_clear_output(DIN11) +#define io141_toggle_output mcu_toggle_output(DIN11) +#define io141_get_output mcu_get_output(DIN11) +#define io141_config_input mcu_config_input(DIN11) +#define io141_config_pullup mcu_config_pullup(DIN11) +#define io141_get_input mcu_get_input(DIN11) +#elif ASSERT_PIN_EXTENDED(DIN11) #define io141_config_output -#define io141_set_output ic74hc595_set_pin(141);ic74hc595_shift_io_pins() -#define io141_clear_output ic74hc595_clear_pin(141);ic74hc595_shift_io_pins() -#define io141_toggle_output ic74hc595_toggle_pin(141);ic74hc595_shift_io_pins() -#define io141_get_output ic74hc595_get_pin(141) +#define io141_set_output ic74hc595_set_pin(DIN11);ic74hc595_shift_io_pins() +#define io141_clear_output ic74hc595_clear_pin(DIN11);ic74hc595_shift_io_pins() +#define io141_toggle_output ic74hc595_toggle_pin(DIN11);ic74hc595_shift_io_pins() +#define io141_get_output ic74hc595_get_pin(DIN11) #define io141_config_input #define io141_config_pullup #define io141_get_input 0 @@ -3368,21 +3368,21 @@ extern "C" #define io141_config_pullup #define io141_get_input 0 #endif -#if ASSERT_PIN_IO(142) -#define io142_config_output mcu_config_output(142) -#define io142_set_output mcu_set_output(142) -#define io142_clear_output mcu_clear_output(142) -#define io142_toggle_output mcu_toggle_output(142) -#define io142_get_output mcu_get_output(142) -#define io142_config_input mcu_config_input(142) -#define io142_config_pullup mcu_config_pullup(142) -#define io142_get_input mcu_get_input(142) -#elif ASSERT_PIN_EXTENDED(142) +#if ASSERT_PIN_IO(DIN12) +#define io142_config_output mcu_config_output(DIN12) +#define io142_set_output mcu_set_output(DIN12) +#define io142_clear_output mcu_clear_output(DIN12) +#define io142_toggle_output mcu_toggle_output(DIN12) +#define io142_get_output mcu_get_output(DIN12) +#define io142_config_input mcu_config_input(DIN12) +#define io142_config_pullup mcu_config_pullup(DIN12) +#define io142_get_input mcu_get_input(DIN12) +#elif ASSERT_PIN_EXTENDED(DIN12) #define io142_config_output -#define io142_set_output ic74hc595_set_pin(142);ic74hc595_shift_io_pins() -#define io142_clear_output ic74hc595_clear_pin(142);ic74hc595_shift_io_pins() -#define io142_toggle_output ic74hc595_toggle_pin(142);ic74hc595_shift_io_pins() -#define io142_get_output ic74hc595_get_pin(142) +#define io142_set_output ic74hc595_set_pin(DIN12);ic74hc595_shift_io_pins() +#define io142_clear_output ic74hc595_clear_pin(DIN12);ic74hc595_shift_io_pins() +#define io142_toggle_output ic74hc595_toggle_pin(DIN12);ic74hc595_shift_io_pins() +#define io142_get_output ic74hc595_get_pin(DIN12) #define io142_config_input #define io142_config_pullup #define io142_get_input 0 @@ -3396,21 +3396,21 @@ extern "C" #define io142_config_pullup #define io142_get_input 0 #endif -#if ASSERT_PIN_IO(143) -#define io143_config_output mcu_config_output(143) -#define io143_set_output mcu_set_output(143) -#define io143_clear_output mcu_clear_output(143) -#define io143_toggle_output mcu_toggle_output(143) -#define io143_get_output mcu_get_output(143) -#define io143_config_input mcu_config_input(143) -#define io143_config_pullup mcu_config_pullup(143) -#define io143_get_input mcu_get_input(143) -#elif ASSERT_PIN_EXTENDED(143) +#if ASSERT_PIN_IO(DIN13) +#define io143_config_output mcu_config_output(DIN13) +#define io143_set_output mcu_set_output(DIN13) +#define io143_clear_output mcu_clear_output(DIN13) +#define io143_toggle_output mcu_toggle_output(DIN13) +#define io143_get_output mcu_get_output(DIN13) +#define io143_config_input mcu_config_input(DIN13) +#define io143_config_pullup mcu_config_pullup(DIN13) +#define io143_get_input mcu_get_input(DIN13) +#elif ASSERT_PIN_EXTENDED(DIN13) #define io143_config_output -#define io143_set_output ic74hc595_set_pin(143);ic74hc595_shift_io_pins() -#define io143_clear_output ic74hc595_clear_pin(143);ic74hc595_shift_io_pins() -#define io143_toggle_output ic74hc595_toggle_pin(143);ic74hc595_shift_io_pins() -#define io143_get_output ic74hc595_get_pin(143) +#define io143_set_output ic74hc595_set_pin(DIN13);ic74hc595_shift_io_pins() +#define io143_clear_output ic74hc595_clear_pin(DIN13);ic74hc595_shift_io_pins() +#define io143_toggle_output ic74hc595_toggle_pin(DIN13);ic74hc595_shift_io_pins() +#define io143_get_output ic74hc595_get_pin(DIN13) #define io143_config_input #define io143_config_pullup #define io143_get_input 0 @@ -3424,21 +3424,21 @@ extern "C" #define io143_config_pullup #define io143_get_input 0 #endif -#if ASSERT_PIN_IO(144) -#define io144_config_output mcu_config_output(144) -#define io144_set_output mcu_set_output(144) -#define io144_clear_output mcu_clear_output(144) -#define io144_toggle_output mcu_toggle_output(144) -#define io144_get_output mcu_get_output(144) -#define io144_config_input mcu_config_input(144) -#define io144_config_pullup mcu_config_pullup(144) -#define io144_get_input mcu_get_input(144) -#elif ASSERT_PIN_EXTENDED(144) +#if ASSERT_PIN_IO(DIN14) +#define io144_config_output mcu_config_output(DIN14) +#define io144_set_output mcu_set_output(DIN14) +#define io144_clear_output mcu_clear_output(DIN14) +#define io144_toggle_output mcu_toggle_output(DIN14) +#define io144_get_output mcu_get_output(DIN14) +#define io144_config_input mcu_config_input(DIN14) +#define io144_config_pullup mcu_config_pullup(DIN14) +#define io144_get_input mcu_get_input(DIN14) +#elif ASSERT_PIN_EXTENDED(DIN14) #define io144_config_output -#define io144_set_output ic74hc595_set_pin(144);ic74hc595_shift_io_pins() -#define io144_clear_output ic74hc595_clear_pin(144);ic74hc595_shift_io_pins() -#define io144_toggle_output ic74hc595_toggle_pin(144);ic74hc595_shift_io_pins() -#define io144_get_output ic74hc595_get_pin(144) +#define io144_set_output ic74hc595_set_pin(DIN14);ic74hc595_shift_io_pins() +#define io144_clear_output ic74hc595_clear_pin(DIN14);ic74hc595_shift_io_pins() +#define io144_toggle_output ic74hc595_toggle_pin(DIN14);ic74hc595_shift_io_pins() +#define io144_get_output ic74hc595_get_pin(DIN14) #define io144_config_input #define io144_config_pullup #define io144_get_input 0 @@ -3452,21 +3452,21 @@ extern "C" #define io144_config_pullup #define io144_get_input 0 #endif -#if ASSERT_PIN_IO(145) -#define io145_config_output mcu_config_output(145) -#define io145_set_output mcu_set_output(145) -#define io145_clear_output mcu_clear_output(145) -#define io145_toggle_output mcu_toggle_output(145) -#define io145_get_output mcu_get_output(145) -#define io145_config_input mcu_config_input(145) -#define io145_config_pullup mcu_config_pullup(145) -#define io145_get_input mcu_get_input(145) -#elif ASSERT_PIN_EXTENDED(145) +#if ASSERT_PIN_IO(DIN15) +#define io145_config_output mcu_config_output(DIN15) +#define io145_set_output mcu_set_output(DIN15) +#define io145_clear_output mcu_clear_output(DIN15) +#define io145_toggle_output mcu_toggle_output(DIN15) +#define io145_get_output mcu_get_output(DIN15) +#define io145_config_input mcu_config_input(DIN15) +#define io145_config_pullup mcu_config_pullup(DIN15) +#define io145_get_input mcu_get_input(DIN15) +#elif ASSERT_PIN_EXTENDED(DIN15) #define io145_config_output -#define io145_set_output ic74hc595_set_pin(145);ic74hc595_shift_io_pins() -#define io145_clear_output ic74hc595_clear_pin(145);ic74hc595_shift_io_pins() -#define io145_toggle_output ic74hc595_toggle_pin(145);ic74hc595_shift_io_pins() -#define io145_get_output ic74hc595_get_pin(145) +#define io145_set_output ic74hc595_set_pin(DIN15);ic74hc595_shift_io_pins() +#define io145_clear_output ic74hc595_clear_pin(DIN15);ic74hc595_shift_io_pins() +#define io145_toggle_output ic74hc595_toggle_pin(DIN15);ic74hc595_shift_io_pins() +#define io145_get_output ic74hc595_get_pin(DIN15) #define io145_config_input #define io145_config_pullup #define io145_get_input 0 @@ -3480,21 +3480,21 @@ extern "C" #define io145_config_pullup #define io145_get_input 0 #endif -#if ASSERT_PIN_IO(146) -#define io146_config_output mcu_config_output(146) -#define io146_set_output mcu_set_output(146) -#define io146_clear_output mcu_clear_output(146) -#define io146_toggle_output mcu_toggle_output(146) -#define io146_get_output mcu_get_output(146) -#define io146_config_input mcu_config_input(146) -#define io146_config_pullup mcu_config_pullup(146) -#define io146_get_input mcu_get_input(146) -#elif ASSERT_PIN_EXTENDED(146) +#if ASSERT_PIN_IO(DIN16) +#define io146_config_output mcu_config_output(DIN16) +#define io146_set_output mcu_set_output(DIN16) +#define io146_clear_output mcu_clear_output(DIN16) +#define io146_toggle_output mcu_toggle_output(DIN16) +#define io146_get_output mcu_get_output(DIN16) +#define io146_config_input mcu_config_input(DIN16) +#define io146_config_pullup mcu_config_pullup(DIN16) +#define io146_get_input mcu_get_input(DIN16) +#elif ASSERT_PIN_EXTENDED(DIN16) #define io146_config_output -#define io146_set_output ic74hc595_set_pin(146);ic74hc595_shift_io_pins() -#define io146_clear_output ic74hc595_clear_pin(146);ic74hc595_shift_io_pins() -#define io146_toggle_output ic74hc595_toggle_pin(146);ic74hc595_shift_io_pins() -#define io146_get_output ic74hc595_get_pin(146) +#define io146_set_output ic74hc595_set_pin(DIN16);ic74hc595_shift_io_pins() +#define io146_clear_output ic74hc595_clear_pin(DIN16);ic74hc595_shift_io_pins() +#define io146_toggle_output ic74hc595_toggle_pin(DIN16);ic74hc595_shift_io_pins() +#define io146_get_output ic74hc595_get_pin(DIN16) #define io146_config_input #define io146_config_pullup #define io146_get_input 0 @@ -3508,21 +3508,21 @@ extern "C" #define io146_config_pullup #define io146_get_input 0 #endif -#if ASSERT_PIN_IO(147) -#define io147_config_output mcu_config_output(147) -#define io147_set_output mcu_set_output(147) -#define io147_clear_output mcu_clear_output(147) -#define io147_toggle_output mcu_toggle_output(147) -#define io147_get_output mcu_get_output(147) -#define io147_config_input mcu_config_input(147) -#define io147_config_pullup mcu_config_pullup(147) -#define io147_get_input mcu_get_input(147) -#elif ASSERT_PIN_EXTENDED(147) +#if ASSERT_PIN_IO(DIN17) +#define io147_config_output mcu_config_output(DIN17) +#define io147_set_output mcu_set_output(DIN17) +#define io147_clear_output mcu_clear_output(DIN17) +#define io147_toggle_output mcu_toggle_output(DIN17) +#define io147_get_output mcu_get_output(DIN17) +#define io147_config_input mcu_config_input(DIN17) +#define io147_config_pullup mcu_config_pullup(DIN17) +#define io147_get_input mcu_get_input(DIN17) +#elif ASSERT_PIN_EXTENDED(DIN17) #define io147_config_output -#define io147_set_output ic74hc595_set_pin(147);ic74hc595_shift_io_pins() -#define io147_clear_output ic74hc595_clear_pin(147);ic74hc595_shift_io_pins() -#define io147_toggle_output ic74hc595_toggle_pin(147);ic74hc595_shift_io_pins() -#define io147_get_output ic74hc595_get_pin(147) +#define io147_set_output ic74hc595_set_pin(DIN17);ic74hc595_shift_io_pins() +#define io147_clear_output ic74hc595_clear_pin(DIN17);ic74hc595_shift_io_pins() +#define io147_toggle_output ic74hc595_toggle_pin(DIN17);ic74hc595_shift_io_pins() +#define io147_get_output ic74hc595_get_pin(DIN17) #define io147_config_input #define io147_config_pullup #define io147_get_input 0 @@ -3536,21 +3536,21 @@ extern "C" #define io147_config_pullup #define io147_get_input 0 #endif -#if ASSERT_PIN_IO(148) -#define io148_config_output mcu_config_output(148) -#define io148_set_output mcu_set_output(148) -#define io148_clear_output mcu_clear_output(148) -#define io148_toggle_output mcu_toggle_output(148) -#define io148_get_output mcu_get_output(148) -#define io148_config_input mcu_config_input(148) -#define io148_config_pullup mcu_config_pullup(148) -#define io148_get_input mcu_get_input(148) -#elif ASSERT_PIN_EXTENDED(148) +#if ASSERT_PIN_IO(DIN18) +#define io148_config_output mcu_config_output(DIN18) +#define io148_set_output mcu_set_output(DIN18) +#define io148_clear_output mcu_clear_output(DIN18) +#define io148_toggle_output mcu_toggle_output(DIN18) +#define io148_get_output mcu_get_output(DIN18) +#define io148_config_input mcu_config_input(DIN18) +#define io148_config_pullup mcu_config_pullup(DIN18) +#define io148_get_input mcu_get_input(DIN18) +#elif ASSERT_PIN_EXTENDED(DIN18) #define io148_config_output -#define io148_set_output ic74hc595_set_pin(148);ic74hc595_shift_io_pins() -#define io148_clear_output ic74hc595_clear_pin(148);ic74hc595_shift_io_pins() -#define io148_toggle_output ic74hc595_toggle_pin(148);ic74hc595_shift_io_pins() -#define io148_get_output ic74hc595_get_pin(148) +#define io148_set_output ic74hc595_set_pin(DIN18);ic74hc595_shift_io_pins() +#define io148_clear_output ic74hc595_clear_pin(DIN18);ic74hc595_shift_io_pins() +#define io148_toggle_output ic74hc595_toggle_pin(DIN18);ic74hc595_shift_io_pins() +#define io148_get_output ic74hc595_get_pin(DIN18) #define io148_config_input #define io148_config_pullup #define io148_get_input 0 @@ -3564,21 +3564,21 @@ extern "C" #define io148_config_pullup #define io148_get_input 0 #endif -#if ASSERT_PIN_IO(149) -#define io149_config_output mcu_config_output(149) -#define io149_set_output mcu_set_output(149) -#define io149_clear_output mcu_clear_output(149) -#define io149_toggle_output mcu_toggle_output(149) -#define io149_get_output mcu_get_output(149) -#define io149_config_input mcu_config_input(149) -#define io149_config_pullup mcu_config_pullup(149) -#define io149_get_input mcu_get_input(149) -#elif ASSERT_PIN_EXTENDED(149) +#if ASSERT_PIN_IO(DIN19) +#define io149_config_output mcu_config_output(DIN19) +#define io149_set_output mcu_set_output(DIN19) +#define io149_clear_output mcu_clear_output(DIN19) +#define io149_toggle_output mcu_toggle_output(DIN19) +#define io149_get_output mcu_get_output(DIN19) +#define io149_config_input mcu_config_input(DIN19) +#define io149_config_pullup mcu_config_pullup(DIN19) +#define io149_get_input mcu_get_input(DIN19) +#elif ASSERT_PIN_EXTENDED(DIN19) #define io149_config_output -#define io149_set_output ic74hc595_set_pin(149);ic74hc595_shift_io_pins() -#define io149_clear_output ic74hc595_clear_pin(149);ic74hc595_shift_io_pins() -#define io149_toggle_output ic74hc595_toggle_pin(149);ic74hc595_shift_io_pins() -#define io149_get_output ic74hc595_get_pin(149) +#define io149_set_output ic74hc595_set_pin(DIN19);ic74hc595_shift_io_pins() +#define io149_clear_output ic74hc595_clear_pin(DIN19);ic74hc595_shift_io_pins() +#define io149_toggle_output ic74hc595_toggle_pin(DIN19);ic74hc595_shift_io_pins() +#define io149_get_output ic74hc595_get_pin(DIN19) #define io149_config_input #define io149_config_pullup #define io149_get_input 0 @@ -3592,21 +3592,21 @@ extern "C" #define io149_config_pullup #define io149_get_input 0 #endif -#if ASSERT_PIN_IO(150) -#define io150_config_output mcu_config_output(150) -#define io150_set_output mcu_set_output(150) -#define io150_clear_output mcu_clear_output(150) -#define io150_toggle_output mcu_toggle_output(150) -#define io150_get_output mcu_get_output(150) -#define io150_config_input mcu_config_input(150) -#define io150_config_pullup mcu_config_pullup(150) -#define io150_get_input mcu_get_input(150) -#elif ASSERT_PIN_EXTENDED(150) +#if ASSERT_PIN_IO(DIN20) +#define io150_config_output mcu_config_output(DIN20) +#define io150_set_output mcu_set_output(DIN20) +#define io150_clear_output mcu_clear_output(DIN20) +#define io150_toggle_output mcu_toggle_output(DIN20) +#define io150_get_output mcu_get_output(DIN20) +#define io150_config_input mcu_config_input(DIN20) +#define io150_config_pullup mcu_config_pullup(DIN20) +#define io150_get_input mcu_get_input(DIN20) +#elif ASSERT_PIN_EXTENDED(DIN20) #define io150_config_output -#define io150_set_output ic74hc595_set_pin(150);ic74hc595_shift_io_pins() -#define io150_clear_output ic74hc595_clear_pin(150);ic74hc595_shift_io_pins() -#define io150_toggle_output ic74hc595_toggle_pin(150);ic74hc595_shift_io_pins() -#define io150_get_output ic74hc595_get_pin(150) +#define io150_set_output ic74hc595_set_pin(DIN20);ic74hc595_shift_io_pins() +#define io150_clear_output ic74hc595_clear_pin(DIN20);ic74hc595_shift_io_pins() +#define io150_toggle_output ic74hc595_toggle_pin(DIN20);ic74hc595_shift_io_pins() +#define io150_get_output ic74hc595_get_pin(DIN20) #define io150_config_input #define io150_config_pullup #define io150_get_input 0 @@ -3620,21 +3620,21 @@ extern "C" #define io150_config_pullup #define io150_get_input 0 #endif -#if ASSERT_PIN_IO(151) -#define io151_config_output mcu_config_output(151) -#define io151_set_output mcu_set_output(151) -#define io151_clear_output mcu_clear_output(151) -#define io151_toggle_output mcu_toggle_output(151) -#define io151_get_output mcu_get_output(151) -#define io151_config_input mcu_config_input(151) -#define io151_config_pullup mcu_config_pullup(151) -#define io151_get_input mcu_get_input(151) -#elif ASSERT_PIN_EXTENDED(151) +#if ASSERT_PIN_IO(DIN21) +#define io151_config_output mcu_config_output(DIN21) +#define io151_set_output mcu_set_output(DIN21) +#define io151_clear_output mcu_clear_output(DIN21) +#define io151_toggle_output mcu_toggle_output(DIN21) +#define io151_get_output mcu_get_output(DIN21) +#define io151_config_input mcu_config_input(DIN21) +#define io151_config_pullup mcu_config_pullup(DIN21) +#define io151_get_input mcu_get_input(DIN21) +#elif ASSERT_PIN_EXTENDED(DIN21) #define io151_config_output -#define io151_set_output ic74hc595_set_pin(151);ic74hc595_shift_io_pins() -#define io151_clear_output ic74hc595_clear_pin(151);ic74hc595_shift_io_pins() -#define io151_toggle_output ic74hc595_toggle_pin(151);ic74hc595_shift_io_pins() -#define io151_get_output ic74hc595_get_pin(151) +#define io151_set_output ic74hc595_set_pin(DIN21);ic74hc595_shift_io_pins() +#define io151_clear_output ic74hc595_clear_pin(DIN21);ic74hc595_shift_io_pins() +#define io151_toggle_output ic74hc595_toggle_pin(DIN21);ic74hc595_shift_io_pins() +#define io151_get_output ic74hc595_get_pin(DIN21) #define io151_config_input #define io151_config_pullup #define io151_get_input 0 @@ -3648,21 +3648,21 @@ extern "C" #define io151_config_pullup #define io151_get_input 0 #endif -#if ASSERT_PIN_IO(152) -#define io152_config_output mcu_config_output(152) -#define io152_set_output mcu_set_output(152) -#define io152_clear_output mcu_clear_output(152) -#define io152_toggle_output mcu_toggle_output(152) -#define io152_get_output mcu_get_output(152) -#define io152_config_input mcu_config_input(152) -#define io152_config_pullup mcu_config_pullup(152) -#define io152_get_input mcu_get_input(152) -#elif ASSERT_PIN_EXTENDED(152) +#if ASSERT_PIN_IO(DIN22) +#define io152_config_output mcu_config_output(DIN22) +#define io152_set_output mcu_set_output(DIN22) +#define io152_clear_output mcu_clear_output(DIN22) +#define io152_toggle_output mcu_toggle_output(DIN22) +#define io152_get_output mcu_get_output(DIN22) +#define io152_config_input mcu_config_input(DIN22) +#define io152_config_pullup mcu_config_pullup(DIN22) +#define io152_get_input mcu_get_input(DIN22) +#elif ASSERT_PIN_EXTENDED(DIN22) #define io152_config_output -#define io152_set_output ic74hc595_set_pin(152);ic74hc595_shift_io_pins() -#define io152_clear_output ic74hc595_clear_pin(152);ic74hc595_shift_io_pins() -#define io152_toggle_output ic74hc595_toggle_pin(152);ic74hc595_shift_io_pins() -#define io152_get_output ic74hc595_get_pin(152) +#define io152_set_output ic74hc595_set_pin(DIN22);ic74hc595_shift_io_pins() +#define io152_clear_output ic74hc595_clear_pin(DIN22);ic74hc595_shift_io_pins() +#define io152_toggle_output ic74hc595_toggle_pin(DIN22);ic74hc595_shift_io_pins() +#define io152_get_output ic74hc595_get_pin(DIN22) #define io152_config_input #define io152_config_pullup #define io152_get_input 0 @@ -3676,21 +3676,21 @@ extern "C" #define io152_config_pullup #define io152_get_input 0 #endif -#if ASSERT_PIN_IO(153) -#define io153_config_output mcu_config_output(153) -#define io153_set_output mcu_set_output(153) -#define io153_clear_output mcu_clear_output(153) -#define io153_toggle_output mcu_toggle_output(153) -#define io153_get_output mcu_get_output(153) -#define io153_config_input mcu_config_input(153) -#define io153_config_pullup mcu_config_pullup(153) -#define io153_get_input mcu_get_input(153) -#elif ASSERT_PIN_EXTENDED(153) +#if ASSERT_PIN_IO(DIN23) +#define io153_config_output mcu_config_output(DIN23) +#define io153_set_output mcu_set_output(DIN23) +#define io153_clear_output mcu_clear_output(DIN23) +#define io153_toggle_output mcu_toggle_output(DIN23) +#define io153_get_output mcu_get_output(DIN23) +#define io153_config_input mcu_config_input(DIN23) +#define io153_config_pullup mcu_config_pullup(DIN23) +#define io153_get_input mcu_get_input(DIN23) +#elif ASSERT_PIN_EXTENDED(DIN23) #define io153_config_output -#define io153_set_output ic74hc595_set_pin(153);ic74hc595_shift_io_pins() -#define io153_clear_output ic74hc595_clear_pin(153);ic74hc595_shift_io_pins() -#define io153_toggle_output ic74hc595_toggle_pin(153);ic74hc595_shift_io_pins() -#define io153_get_output ic74hc595_get_pin(153) +#define io153_set_output ic74hc595_set_pin(DIN23);ic74hc595_shift_io_pins() +#define io153_clear_output ic74hc595_clear_pin(DIN23);ic74hc595_shift_io_pins() +#define io153_toggle_output ic74hc595_toggle_pin(DIN23);ic74hc595_shift_io_pins() +#define io153_get_output ic74hc595_get_pin(DIN23) #define io153_config_input #define io153_config_pullup #define io153_get_input 0 @@ -3704,21 +3704,21 @@ extern "C" #define io153_config_pullup #define io153_get_input 0 #endif -#if ASSERT_PIN_IO(154) -#define io154_config_output mcu_config_output(154) -#define io154_set_output mcu_set_output(154) -#define io154_clear_output mcu_clear_output(154) -#define io154_toggle_output mcu_toggle_output(154) -#define io154_get_output mcu_get_output(154) -#define io154_config_input mcu_config_input(154) -#define io154_config_pullup mcu_config_pullup(154) -#define io154_get_input mcu_get_input(154) -#elif ASSERT_PIN_EXTENDED(154) +#if ASSERT_PIN_IO(DIN24) +#define io154_config_output mcu_config_output(DIN24) +#define io154_set_output mcu_set_output(DIN24) +#define io154_clear_output mcu_clear_output(DIN24) +#define io154_toggle_output mcu_toggle_output(DIN24) +#define io154_get_output mcu_get_output(DIN24) +#define io154_config_input mcu_config_input(DIN24) +#define io154_config_pullup mcu_config_pullup(DIN24) +#define io154_get_input mcu_get_input(DIN24) +#elif ASSERT_PIN_EXTENDED(DIN24) #define io154_config_output -#define io154_set_output ic74hc595_set_pin(154);ic74hc595_shift_io_pins() -#define io154_clear_output ic74hc595_clear_pin(154);ic74hc595_shift_io_pins() -#define io154_toggle_output ic74hc595_toggle_pin(154);ic74hc595_shift_io_pins() -#define io154_get_output ic74hc595_get_pin(154) +#define io154_set_output ic74hc595_set_pin(DIN24);ic74hc595_shift_io_pins() +#define io154_clear_output ic74hc595_clear_pin(DIN24);ic74hc595_shift_io_pins() +#define io154_toggle_output ic74hc595_toggle_pin(DIN24);ic74hc595_shift_io_pins() +#define io154_get_output ic74hc595_get_pin(DIN24) #define io154_config_input #define io154_config_pullup #define io154_get_input 0 @@ -3732,21 +3732,21 @@ extern "C" #define io154_config_pullup #define io154_get_input 0 #endif -#if ASSERT_PIN_IO(155) -#define io155_config_output mcu_config_output(155) -#define io155_set_output mcu_set_output(155) -#define io155_clear_output mcu_clear_output(155) -#define io155_toggle_output mcu_toggle_output(155) -#define io155_get_output mcu_get_output(155) -#define io155_config_input mcu_config_input(155) -#define io155_config_pullup mcu_config_pullup(155) -#define io155_get_input mcu_get_input(155) -#elif ASSERT_PIN_EXTENDED(155) +#if ASSERT_PIN_IO(DIN25) +#define io155_config_output mcu_config_output(DIN25) +#define io155_set_output mcu_set_output(DIN25) +#define io155_clear_output mcu_clear_output(DIN25) +#define io155_toggle_output mcu_toggle_output(DIN25) +#define io155_get_output mcu_get_output(DIN25) +#define io155_config_input mcu_config_input(DIN25) +#define io155_config_pullup mcu_config_pullup(DIN25) +#define io155_get_input mcu_get_input(DIN25) +#elif ASSERT_PIN_EXTENDED(DIN25) #define io155_config_output -#define io155_set_output ic74hc595_set_pin(155);ic74hc595_shift_io_pins() -#define io155_clear_output ic74hc595_clear_pin(155);ic74hc595_shift_io_pins() -#define io155_toggle_output ic74hc595_toggle_pin(155);ic74hc595_shift_io_pins() -#define io155_get_output ic74hc595_get_pin(155) +#define io155_set_output ic74hc595_set_pin(DIN25);ic74hc595_shift_io_pins() +#define io155_clear_output ic74hc595_clear_pin(DIN25);ic74hc595_shift_io_pins() +#define io155_toggle_output ic74hc595_toggle_pin(DIN25);ic74hc595_shift_io_pins() +#define io155_get_output ic74hc595_get_pin(DIN25) #define io155_config_input #define io155_config_pullup #define io155_get_input 0 @@ -3760,21 +3760,21 @@ extern "C" #define io155_config_pullup #define io155_get_input 0 #endif -#if ASSERT_PIN_IO(156) -#define io156_config_output mcu_config_output(156) -#define io156_set_output mcu_set_output(156) -#define io156_clear_output mcu_clear_output(156) -#define io156_toggle_output mcu_toggle_output(156) -#define io156_get_output mcu_get_output(156) -#define io156_config_input mcu_config_input(156) -#define io156_config_pullup mcu_config_pullup(156) -#define io156_get_input mcu_get_input(156) -#elif ASSERT_PIN_EXTENDED(156) +#if ASSERT_PIN_IO(DIN26) +#define io156_config_output mcu_config_output(DIN26) +#define io156_set_output mcu_set_output(DIN26) +#define io156_clear_output mcu_clear_output(DIN26) +#define io156_toggle_output mcu_toggle_output(DIN26) +#define io156_get_output mcu_get_output(DIN26) +#define io156_config_input mcu_config_input(DIN26) +#define io156_config_pullup mcu_config_pullup(DIN26) +#define io156_get_input mcu_get_input(DIN26) +#elif ASSERT_PIN_EXTENDED(DIN26) #define io156_config_output -#define io156_set_output ic74hc595_set_pin(156);ic74hc595_shift_io_pins() -#define io156_clear_output ic74hc595_clear_pin(156);ic74hc595_shift_io_pins() -#define io156_toggle_output ic74hc595_toggle_pin(156);ic74hc595_shift_io_pins() -#define io156_get_output ic74hc595_get_pin(156) +#define io156_set_output ic74hc595_set_pin(DIN26);ic74hc595_shift_io_pins() +#define io156_clear_output ic74hc595_clear_pin(DIN26);ic74hc595_shift_io_pins() +#define io156_toggle_output ic74hc595_toggle_pin(DIN26);ic74hc595_shift_io_pins() +#define io156_get_output ic74hc595_get_pin(DIN26) #define io156_config_input #define io156_config_pullup #define io156_get_input 0 @@ -3788,21 +3788,21 @@ extern "C" #define io156_config_pullup #define io156_get_input 0 #endif -#if ASSERT_PIN_IO(157) -#define io157_config_output mcu_config_output(157) -#define io157_set_output mcu_set_output(157) -#define io157_clear_output mcu_clear_output(157) -#define io157_toggle_output mcu_toggle_output(157) -#define io157_get_output mcu_get_output(157) -#define io157_config_input mcu_config_input(157) -#define io157_config_pullup mcu_config_pullup(157) -#define io157_get_input mcu_get_input(157) -#elif ASSERT_PIN_EXTENDED(157) +#if ASSERT_PIN_IO(DIN27) +#define io157_config_output mcu_config_output(DIN27) +#define io157_set_output mcu_set_output(DIN27) +#define io157_clear_output mcu_clear_output(DIN27) +#define io157_toggle_output mcu_toggle_output(DIN27) +#define io157_get_output mcu_get_output(DIN27) +#define io157_config_input mcu_config_input(DIN27) +#define io157_config_pullup mcu_config_pullup(DIN27) +#define io157_get_input mcu_get_input(DIN27) +#elif ASSERT_PIN_EXTENDED(DIN27) #define io157_config_output -#define io157_set_output ic74hc595_set_pin(157);ic74hc595_shift_io_pins() -#define io157_clear_output ic74hc595_clear_pin(157);ic74hc595_shift_io_pins() -#define io157_toggle_output ic74hc595_toggle_pin(157);ic74hc595_shift_io_pins() -#define io157_get_output ic74hc595_get_pin(157) +#define io157_set_output ic74hc595_set_pin(DIN27);ic74hc595_shift_io_pins() +#define io157_clear_output ic74hc595_clear_pin(DIN27);ic74hc595_shift_io_pins() +#define io157_toggle_output ic74hc595_toggle_pin(DIN27);ic74hc595_shift_io_pins() +#define io157_get_output ic74hc595_get_pin(DIN27) #define io157_config_input #define io157_config_pullup #define io157_get_input 0 @@ -3816,21 +3816,21 @@ extern "C" #define io157_config_pullup #define io157_get_input 0 #endif -#if ASSERT_PIN_IO(158) -#define io158_config_output mcu_config_output(158) -#define io158_set_output mcu_set_output(158) -#define io158_clear_output mcu_clear_output(158) -#define io158_toggle_output mcu_toggle_output(158) -#define io158_get_output mcu_get_output(158) -#define io158_config_input mcu_config_input(158) -#define io158_config_pullup mcu_config_pullup(158) -#define io158_get_input mcu_get_input(158) -#elif ASSERT_PIN_EXTENDED(158) +#if ASSERT_PIN_IO(DIN28) +#define io158_config_output mcu_config_output(DIN28) +#define io158_set_output mcu_set_output(DIN28) +#define io158_clear_output mcu_clear_output(DIN28) +#define io158_toggle_output mcu_toggle_output(DIN28) +#define io158_get_output mcu_get_output(DIN28) +#define io158_config_input mcu_config_input(DIN28) +#define io158_config_pullup mcu_config_pullup(DIN28) +#define io158_get_input mcu_get_input(DIN28) +#elif ASSERT_PIN_EXTENDED(DIN28) #define io158_config_output -#define io158_set_output ic74hc595_set_pin(158);ic74hc595_shift_io_pins() -#define io158_clear_output ic74hc595_clear_pin(158);ic74hc595_shift_io_pins() -#define io158_toggle_output ic74hc595_toggle_pin(158);ic74hc595_shift_io_pins() -#define io158_get_output ic74hc595_get_pin(158) +#define io158_set_output ic74hc595_set_pin(DIN28);ic74hc595_shift_io_pins() +#define io158_clear_output ic74hc595_clear_pin(DIN28);ic74hc595_shift_io_pins() +#define io158_toggle_output ic74hc595_toggle_pin(DIN28);ic74hc595_shift_io_pins() +#define io158_get_output ic74hc595_get_pin(DIN28) #define io158_config_input #define io158_config_pullup #define io158_get_input 0 @@ -3844,21 +3844,21 @@ extern "C" #define io158_config_pullup #define io158_get_input 0 #endif -#if ASSERT_PIN_IO(159) -#define io159_config_output mcu_config_output(159) -#define io159_set_output mcu_set_output(159) -#define io159_clear_output mcu_clear_output(159) -#define io159_toggle_output mcu_toggle_output(159) -#define io159_get_output mcu_get_output(159) -#define io159_config_input mcu_config_input(159) -#define io159_config_pullup mcu_config_pullup(159) -#define io159_get_input mcu_get_input(159) -#elif ASSERT_PIN_EXTENDED(159) +#if ASSERT_PIN_IO(DIN29) +#define io159_config_output mcu_config_output(DIN29) +#define io159_set_output mcu_set_output(DIN29) +#define io159_clear_output mcu_clear_output(DIN29) +#define io159_toggle_output mcu_toggle_output(DIN29) +#define io159_get_output mcu_get_output(DIN29) +#define io159_config_input mcu_config_input(DIN29) +#define io159_config_pullup mcu_config_pullup(DIN29) +#define io159_get_input mcu_get_input(DIN29) +#elif ASSERT_PIN_EXTENDED(DIN29) #define io159_config_output -#define io159_set_output ic74hc595_set_pin(159);ic74hc595_shift_io_pins() -#define io159_clear_output ic74hc595_clear_pin(159);ic74hc595_shift_io_pins() -#define io159_toggle_output ic74hc595_toggle_pin(159);ic74hc595_shift_io_pins() -#define io159_get_output ic74hc595_get_pin(159) +#define io159_set_output ic74hc595_set_pin(DIN29);ic74hc595_shift_io_pins() +#define io159_clear_output ic74hc595_clear_pin(DIN29);ic74hc595_shift_io_pins() +#define io159_toggle_output ic74hc595_toggle_pin(DIN29);ic74hc595_shift_io_pins() +#define io159_get_output ic74hc595_get_pin(DIN29) #define io159_config_input #define io159_config_pullup #define io159_get_input 0 @@ -3872,21 +3872,21 @@ extern "C" #define io159_config_pullup #define io159_get_input 0 #endif -#if ASSERT_PIN_IO(160) -#define io160_config_output mcu_config_output(160) -#define io160_set_output mcu_set_output(160) -#define io160_clear_output mcu_clear_output(160) -#define io160_toggle_output mcu_toggle_output(160) -#define io160_get_output mcu_get_output(160) -#define io160_config_input mcu_config_input(160) -#define io160_config_pullup mcu_config_pullup(160) -#define io160_get_input mcu_get_input(160) -#elif ASSERT_PIN_EXTENDED(160) +#if ASSERT_PIN_IO(DIN30) +#define io160_config_output mcu_config_output(DIN30) +#define io160_set_output mcu_set_output(DIN30) +#define io160_clear_output mcu_clear_output(DIN30) +#define io160_toggle_output mcu_toggle_output(DIN30) +#define io160_get_output mcu_get_output(DIN30) +#define io160_config_input mcu_config_input(DIN30) +#define io160_config_pullup mcu_config_pullup(DIN30) +#define io160_get_input mcu_get_input(DIN30) +#elif ASSERT_PIN_EXTENDED(DIN30) #define io160_config_output -#define io160_set_output ic74hc595_set_pin(160);ic74hc595_shift_io_pins() -#define io160_clear_output ic74hc595_clear_pin(160);ic74hc595_shift_io_pins() -#define io160_toggle_output ic74hc595_toggle_pin(160);ic74hc595_shift_io_pins() -#define io160_get_output ic74hc595_get_pin(160) +#define io160_set_output ic74hc595_set_pin(DIN30);ic74hc595_shift_io_pins() +#define io160_clear_output ic74hc595_clear_pin(DIN30);ic74hc595_shift_io_pins() +#define io160_toggle_output ic74hc595_toggle_pin(DIN30);ic74hc595_shift_io_pins() +#define io160_get_output ic74hc595_get_pin(DIN30) #define io160_config_input #define io160_config_pullup #define io160_get_input 0 @@ -3900,21 +3900,21 @@ extern "C" #define io160_config_pullup #define io160_get_input 0 #endif -#if ASSERT_PIN_IO(161) -#define io161_config_output mcu_config_output(161) -#define io161_set_output mcu_set_output(161) -#define io161_clear_output mcu_clear_output(161) -#define io161_toggle_output mcu_toggle_output(161) -#define io161_get_output mcu_get_output(161) -#define io161_config_input mcu_config_input(161) -#define io161_config_pullup mcu_config_pullup(161) -#define io161_get_input mcu_get_input(161) -#elif ASSERT_PIN_EXTENDED(161) +#if ASSERT_PIN_IO(DIN31) +#define io161_config_output mcu_config_output(DIN31) +#define io161_set_output mcu_set_output(DIN31) +#define io161_clear_output mcu_clear_output(DIN31) +#define io161_toggle_output mcu_toggle_output(DIN31) +#define io161_get_output mcu_get_output(DIN31) +#define io161_config_input mcu_config_input(DIN31) +#define io161_config_pullup mcu_config_pullup(DIN31) +#define io161_get_input mcu_get_input(DIN31) +#elif ASSERT_PIN_EXTENDED(DIN31) #define io161_config_output -#define io161_set_output ic74hc595_set_pin(161);ic74hc595_shift_io_pins() -#define io161_clear_output ic74hc595_clear_pin(161);ic74hc595_shift_io_pins() -#define io161_toggle_output ic74hc595_toggle_pin(161);ic74hc595_shift_io_pins() -#define io161_get_output ic74hc595_get_pin(161) +#define io161_set_output ic74hc595_set_pin(DIN31);ic74hc595_shift_io_pins() +#define io161_clear_output ic74hc595_clear_pin(DIN31);ic74hc595_shift_io_pins() +#define io161_toggle_output ic74hc595_toggle_pin(DIN31);ic74hc595_shift_io_pins() +#define io161_get_output ic74hc595_get_pin(DIN31) #define io161_config_input #define io161_config_pullup #define io161_get_input 0 @@ -3929,6 +3929,7 @@ extern "C" #define io161_get_input 0 #endif + /*PWM*/ #if ASSERT_PIN_IO(PWM0) #define io25_config_pwm(freq) mcu_config_pwm(PWM0, freq) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index e97f4755c..61bfec7b8 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -73,7 +73,6 @@ static flash_eeprom_t mcu_eeprom; hw_timer_t *esp32_step_timer; #ifdef IC74HC595_CUSTOM_SHIFT_IO -extern uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; static volatile uint8_t ic74hc595_update_lock; void ic74hc595_shift_io_pins(void) { @@ -89,327 +88,9 @@ void ic74hc595_shift_io_pins(void) #endif #ifdef IC74HC595_HAS_PWMS -// pwm channels -uint8_t esp32_pwm[16]; -uint16_t esp32_pwm_mask; -// pwm resolution -uint8_t esp32_pwm_res; IRAM_ATTR void mcu_pwm_isr(void *arg) { - static uint8_t pwm_counter = 0; - uint8_t resolution = esp32_pwm_res; -#ifdef IC74HC595_HAS_PWMS - static uint16_t pwm_mask_last = 0; - uint16_t pwm_mask = esp32_pwm_mask; -#endif - // software PWM - if ((++pwm_counter) >> resolution) - { - uint8_t pwm_ref = pwm_counter << resolution; -#if ASSERT_PIN(PWM0) - if (pwm_ref > esp32_pwm[0]) - { - io_clear_output(PWM0); - } -#endif -#if ASSERT_PIN(PWM1) - if (pwm_ref > esp32_pwm[1]) - { - io_clear_output(PWM1); - } -#endif -#if ASSERT_PIN(PWM2) - if (pwm_ref > esp32_pwm[2]) - { - io_clear_output(PWM2); - } -#endif -#if ASSERT_PIN(PWM3) - if (pwm_ref > esp32_pwm[3]) - { - io_clear_output(PWM3); - } -#endif -#if ASSERT_PIN(PWM4) - if (pwm_ref > esp32_pwm[4]) - { - io_clear_output(PWM4); - } -#endif -#if ASSERT_PIN(PWM5) - if (pwm_ref > esp32_pwm[5]) - { - io_clear_output(PWM5); - } -#endif -#if ASSERT_PIN(PWM6) - if (pwm_ref > esp32_pwm[6]) - { - io_clear_output(PWM6); - } -#endif -#if ASSERT_PIN(PWM7) - if (pwm_ref > esp32_pwm[7]) - { - io_clear_output(PWM7); - } -#endif -#if ASSERT_PIN(PWM8) - if (pwm_ref > esp32_pwm[8]) - { - io_clear_output(PWM8); - } -#endif -#if ASSERT_PIN(PWM9) - if (pwm_ref > esp32_pwm[9]) - { - io_clear_output(PWM9); - } -#endif -#if ASSERT_PIN(PWM10) - if (pwm_ref > esp32_pwm[10]) - { - io_clear_output(PWM10); - } -#endif -#if ASSERT_PIN(PWM11) - if (pwm_ref > esp32_pwm[11]) - { - io_clear_output(PWM11); - } -#endif -#if ASSERT_PIN(PWM12) - if (pwm_ref > esp32_pwm[12]) - { - io_clear_output(PWM12); - } -#endif -#if ASSERT_PIN(PWM13) - if (pwm_ref > esp32_pwm[13]) - { - io_clear_output(PWM13); - } -#endif -#if ASSERT_PIN(PWM14) - if (pwm_ref > esp32_pwm[14]) - { - io_clear_output(PWM14); - } -#endif -#if ASSERT_PIN(PWM15) - if (pwm_ref > esp32_pwm[15]) - { - io_clear_output(PWM15); - } -#endif - -#ifdef IC74HC595_HAS_PWMS -#if ASSERT_PIN_EXTENDER(PWM0_IO_OFFSET) - if (pwm_ref > esp32_pwm[0]) - { - pwm_mask &= ~(1 << 0); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM1_IO_OFFSET) - if (pwm_ref > esp32_pwm[1]) - { - pwm_mask &= ~(1 << 1); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM2_IO_OFFSET) - if (pwm_ref > esp32_pwm[2]) - { - pwm_mask &= ~(1 << 2); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM3_IO_OFFSET) - if (pwm_ref > esp32_pwm[3]) - { - pwm_mask &= ~(1 << 3); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM4_IO_OFFSET) - if (pwm_ref > esp32_pwm[4]) - { - pwm_mask &= ~(1 << 4); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM5_IO_OFFSET) - if (pwm_ref > esp32_pwm[5]) - { - pwm_mask &= ~(1 << 5); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM6_IO_OFFSET) - if (pwm_ref > esp32_pwm[6]) - { - pwm_mask &= ~(1 << 6); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM7_IO_OFFSET) - if (pwm_ref > esp32_pwm[7]) - { - pwm_mask &= ~(1 << 7); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM8_IO_OFFSET) - if (pwm_ref > esp32_pwm[8]) - { - pwm_mask &= ~(1 << 8); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM9_IO_OFFSET) - if (pwm_ref > esp32_pwm[9]) - { - pwm_mask &= ~(1 << 9); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM10_IO_OFFSET) - if (pwm_ref > esp32_pwm[10]) - { - pwm_mask &= ~(1 << 10); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM11_IO_OFFSET) - if (pwm_ref > esp32_pwm[11]) - { - pwm_mask &= ~(1 << 11); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM12_IO_OFFSET) - if (pwm_ref > esp32_pwm[12]) - { - pwm_mask &= ~(1 << 12); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM13_IO_OFFSET) - if (pwm_ref > esp32_pwm[13]) - { - pwm_mask &= ~(1 << 13); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM14_IO_OFFSET) - if (pwm_ref > esp32_pwm[14]) - { - pwm_mask &= ~(1 << 14); - } -#endif -#if ASSERT_PIN_EXTENDER(PWM15_IO_OFFSET) - if (pwm_ref > esp32_pwm[15]) - { - pwm_mask &= ~(1 << 15); - } -#endif -#endif - } - else - { - pwm_counter = 0; -#if ASSERT_PIN(PWM0) - if (esp32_pwm[0]) - { - io_set_output(PWM0); - } -#endif -#if ASSERT_PIN(PWM1) - if (esp32_pwm[1]) - { - io_set_output(PWM1); - } -#endif -#if ASSERT_PIN(PWM2) - if (esp32_pwm[2]) - { - io_set_output(PWM2); - } -#endif -#if ASSERT_PIN(PWM3) - if (esp32_pwm[3]) - { - io_set_output(PWM3); - } -#endif -#if ASSERT_PIN(PWM4) - if (esp32_pwm[4]) - { - io_set_output(PWM4); - } -#endif -#if ASSERT_PIN(PWM5) - if (esp32_pwm[5]) - { - io_set_output(PWM5); - } -#endif -#if ASSERT_PIN(PWM6) - if (esp32_pwm[6]) - { - io_set_output(PWM6); - } -#endif -#if ASSERT_PIN(PWM7) - if (esp32_pwm[7]) - { - io_set_output(PWM7); - } -#endif -#if ASSERT_PIN(PWM8) - if (esp32_pwm[8]) - { - io_set_output(PWM8); - } -#endif -#if ASSERT_PIN(PWM9) - if (esp32_pwm[9]) - { - io_set_output(PWM9); - } -#endif -#if ASSERT_PIN(PWM10) - if (esp32_pwm[10]) - { - io_set_output(PWM10); - } -#endif -#if ASSERT_PIN(PWM11) - if (esp32_pwm[11]) - { - io_set_output(PWM11); - } -#endif -#if ASSERT_PIN(PWM12) - if (esp32_pwm[12]) - { - io_set_output(PWM12); - } -#endif -#if ASSERT_PIN(PWM13) - if (esp32_pwm[13]) - { - io_set_output(PWM13); - } -#endif -#if ASSERT_PIN(PWM14) - if (esp32_pwm[14]) - { - io_set_output(PWM14); - } -#endif -#if ASSERT_PIN(PWM15) - if (esp32_pwm[15]) - { - io_set_output(PWM15); - } -#endif - } - -#ifdef IC74HC595_HAS_PWMS - if (pwm_mask_last != pwm_mask) - { - ic74hc595_set_pwms(pwm_mask); - pwm_mask_last = pwm_mask; - } -#endif + io_soft_pwm_update(); timer_group_clr_intr_status_in_isr(PWM_TIMER_TG, PWM_TIMER_IDX); /* After the alarm has been triggered @@ -498,7 +179,7 @@ IRAM_ATTR void mcu_gpio_isr(void *type) } #ifdef IC74HC595_HAS_PWMS -void mcu_pwm_freq_config(uint16_t freq) +uint8_t mcu_softpwm_freq_config(uint16_t freq) { // keeps 8 bit resolution up to 1KHz // reduces bit resolution for higher frequencies @@ -506,10 +187,10 @@ void mcu_pwm_freq_config(uint16_t freq) // determines the bit resolution (8 - esp32_pwm_res); uint8_t res = (uint8_t)MAX((int8_t)ceilf(log2(freq * 0.001f)), 0); freq >>= res; - esp32_pwm_res = res; // timer base frequency is APB clock/2 // it's then divided by 256 timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)roundf((float)(getApbFrequency() >> 9) / (float)freq)); + return res; } #endif diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 2f3985474..1d396beeb 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2746,8 +2746,10 @@ extern "C" // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif // I2C #if (defined(I2C_CLK) && defined(I2C_DATA)) @@ -2832,28 +2834,8 @@ extern "C" } #ifdef IC74HC595_HAS_PWMS - extern void mcu_pwm_freq_config(uint16_t freq); -#define mcu_config_pwm(X, freq) \ - { \ - mcu_config_output(X); \ - mcu_pwm_freq_config(freq); \ - } - extern uint8_t esp32_pwm[16]; - extern uint16_t esp32_pwm_mask; -#define mcu_set_pwm(X, Y) \ - { \ - if (Y) \ - { \ - esp32_pwm_mask |= (1 << (X - PWM_PINS_OFFSET)); \ - } \ - else \ - { \ - esp32_pwm_mask &= ~(1 << (X - PWM_PINS_OFFSET)); \ - } \ - esp32_pwm[X - PWM_PINS_OFFSET] = (0xFF & Y); \ - } -#define mcu_get_pwm(X) (esp32_pwm[X - PWM_PINS_OFFSET]) -#else + extern uint8_t mcu_softpwm_freq_config(uint16_t freq); +#endif #define mcu_config_pwm(X, Y) \ { \ ledc_timer_config_t pwmtimer = {0}; \ @@ -2879,7 +2861,6 @@ extern "C" ledc_update_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)); \ } #define mcu_get_pwm(X) ledc_get_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)) -#endif #define mcu_get_analog(X) (adc1_get_raw(__indirect__(X, ADC_CHANNEL)) >> 1) #ifdef MCU_HAS_ONESHOT_TIMER diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index b4d21fc55..f91b7ee8a 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1021,8 +1021,10 @@ extern "C" // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #define mcu_config_output(X) pinMode(__indirect__(X, BIT), OUTPUT) #define mcu_config_pwm(X, freq) pinMode(__indirect__(X, BIT), OUTPUT) diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index ae2c9660b..a794a25cd 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -3836,8 +3836,10 @@ extern "C" #endif // Indirect macro access -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #define mcu_config_output(diopin) \ { \ diff --git a/uCNC/src/hal/mcus/mcu.c b/uCNC/src/hal/mcus/mcu.c index 58759abee..4da909a20 100644 --- a/uCNC/src/hal/mcus/mcu.c +++ b/uCNC/src/hal/mcus/mcu.c @@ -37,241 +37,241 @@ __attribute__((noinline, optimize("O3"))) void mcu_delay_loop(uint16_t loops) void __attribute__((weak)) mcu_io_init(void) { -#if ASSERT_PIN(STEP0) +#if ASSERT_PIN_IO(STEP0) mcu_config_output(STEP0); #endif -#if ASSERT_PIN(STEP1) +#if ASSERT_PIN_IO(STEP1) mcu_config_output(STEP1); #endif -#if ASSERT_PIN(STEP2) +#if ASSERT_PIN_IO(STEP2) mcu_config_output(STEP2); #endif -#if ASSERT_PIN(STEP3) +#if ASSERT_PIN_IO(STEP3) mcu_config_output(STEP3); #endif -#if ASSERT_PIN(STEP4) +#if ASSERT_PIN_IO(STEP4) mcu_config_output(STEP4); #endif -#if ASSERT_PIN(STEP5) +#if ASSERT_PIN_IO(STEP5) mcu_config_output(STEP5); #endif -#if ASSERT_PIN(STEP6) +#if ASSERT_PIN_IO(STEP6) mcu_config_output(STEP6); #endif -#if ASSERT_PIN(STEP7) +#if ASSERT_PIN_IO(STEP7) mcu_config_output(STEP7); #endif -#if ASSERT_PIN(DIR0) +#if ASSERT_PIN_IO(DIR0) mcu_config_output(DIR0); #endif -#if ASSERT_PIN(DIR1) +#if ASSERT_PIN_IO(DIR1) mcu_config_output(DIR1); #endif -#if ASSERT_PIN(DIR2) +#if ASSERT_PIN_IO(DIR2) mcu_config_output(DIR2); #endif -#if ASSERT_PIN(DIR3) +#if ASSERT_PIN_IO(DIR3) mcu_config_output(DIR3); #endif -#if ASSERT_PIN(DIR4) +#if ASSERT_PIN_IO(DIR4) mcu_config_output(DIR4); #endif -#if ASSERT_PIN(DIR5) +#if ASSERT_PIN_IO(DIR5) mcu_config_output(DIR5); #endif -#if ASSERT_PIN(DIR6) +#if ASSERT_PIN_IO(DIR6) mcu_config_output(DIR6); #endif -#if ASSERT_PIN(DIR7) +#if ASSERT_PIN_IO(DIR7) mcu_config_output(DIR7); #endif -#if ASSERT_PIN(STEP0_EN) +#if ASSERT_PIN_IO(STEP0_EN) mcu_config_output(STEP0_EN); #endif -#if ASSERT_PIN(STEP1_EN) +#if ASSERT_PIN_IO(STEP1_EN) mcu_config_output(STEP1_EN); #endif -#if ASSERT_PIN(STEP2_EN) +#if ASSERT_PIN_IO(STEP2_EN) mcu_config_output(STEP2_EN); #endif -#if ASSERT_PIN(STEP3_EN) +#if ASSERT_PIN_IO(STEP3_EN) mcu_config_output(STEP3_EN); #endif -#if ASSERT_PIN(STEP4_EN) +#if ASSERT_PIN_IO(STEP4_EN) mcu_config_output(STEP4_EN); #endif -#if ASSERT_PIN(STEP5_EN) +#if ASSERT_PIN_IO(STEP5_EN) mcu_config_output(STEP5_EN); #endif -#if ASSERT_PIN(STEP6_EN) +#if ASSERT_PIN_IO(STEP6_EN) mcu_config_output(STEP6_EN); #endif -#if ASSERT_PIN(STEP7_EN) +#if ASSERT_PIN_IO(STEP7_EN) mcu_config_output(STEP7_EN); #endif -#if ASSERT_PIN(PWM0) +#if ASSERT_PIN_IO(PWM0) mcu_config_pwm(PWM0, 1000); #endif -#if ASSERT_PIN(PWM1) +#if ASSERT_PIN_IO(PWM1) mcu_config_pwm(PWM1, 1000); #endif -#if ASSERT_PIN(PWM2) +#if ASSERT_PIN_IO(PWM2) mcu_config_pwm(PWM2, 1000); #endif -#if ASSERT_PIN(PWM3) +#if ASSERT_PIN_IO(PWM3) mcu_config_pwm(PWM3, 1000); #endif -#if ASSERT_PIN(PWM4) +#if ASSERT_PIN_IO(PWM4) mcu_config_pwm(PWM4, 1000); #endif -#if ASSERT_PIN(PWM5) +#if ASSERT_PIN_IO(PWM5) mcu_config_pwm(PWM5, 1000); #endif -#if ASSERT_PIN(PWM6) +#if ASSERT_PIN_IO(PWM6) mcu_config_pwm(PWM6, 1000); #endif -#if ASSERT_PIN(PWM7) +#if ASSERT_PIN_IO(PWM7) mcu_config_pwm(PWM7, 1000); #endif -#if ASSERT_PIN(PWM8) +#if ASSERT_PIN_IO(PWM8) mcu_config_pwm(PWM8, 1000); #endif -#if ASSERT_PIN(PWM9) +#if ASSERT_PIN_IO(PWM9) mcu_config_pwm(PWM9, 1000); #endif -#if ASSERT_PIN(PWM10) +#if ASSERT_PIN_IO(PWM10) mcu_config_pwm(PWM10, 1000); #endif -#if ASSERT_PIN(PWM11) +#if ASSERT_PIN_IO(PWM11) mcu_config_pwm(PWM11, 1000); #endif -#if ASSERT_PIN(PWM12) +#if ASSERT_PIN_IO(PWM12) mcu_config_pwm(PWM12, 1000); #endif -#if ASSERT_PIN(PWM13) +#if ASSERT_PIN_IO(PWM13) mcu_config_pwm(PWM13, 1000); #endif -#if ASSERT_PIN(PWM14) +#if ASSERT_PIN_IO(PWM14) mcu_config_pwm(PWM14, 1000); #endif -#if ASSERT_PIN(PWM15) +#if ASSERT_PIN_IO(PWM15) mcu_config_pwm(PWM15, 1000); #endif -#if ASSERT_PIN(SERVO0) +#if ASSERT_PIN_IO(SERVO0) mcu_config_output(SERVO0); #endif -#if ASSERT_PIN(SERVO1) +#if ASSERT_PIN_IO(SERVO1) mcu_config_output(SERVO1); #endif -#if ASSERT_PIN(SERVO2) +#if ASSERT_PIN_IO(SERVO2) mcu_config_output(SERVO2); #endif -#if ASSERT_PIN(SERVO3) +#if ASSERT_PIN_IO(SERVO3) mcu_config_output(SERVO3); #endif -#if ASSERT_PIN(SERVO4) +#if ASSERT_PIN_IO(SERVO4) mcu_config_output(SERVO4); #endif -#if ASSERT_PIN(SERVO5) +#if ASSERT_PIN_IO(SERVO5) mcu_config_output(SERVO5); #endif -#if ASSERT_PIN(DOUT0) +#if ASSERT_PIN_IO(DOUT0) mcu_config_output(DOUT0); #endif -#if ASSERT_PIN(DOUT1) +#if ASSERT_PIN_IO(DOUT1) mcu_config_output(DOUT1); #endif -#if ASSERT_PIN(DOUT2) +#if ASSERT_PIN_IO(DOUT2) mcu_config_output(DOUT2); #endif -#if ASSERT_PIN(DOUT3) +#if ASSERT_PIN_IO(DOUT3) mcu_config_output(DOUT3); #endif -#if ASSERT_PIN(DOUT4) +#if ASSERT_PIN_IO(DOUT4) mcu_config_output(DOUT4); #endif -#if ASSERT_PIN(DOUT5) +#if ASSERT_PIN_IO(DOUT5) mcu_config_output(DOUT5); #endif -#if ASSERT_PIN(DOUT6) +#if ASSERT_PIN_IO(DOUT6) mcu_config_output(DOUT6); #endif -#if ASSERT_PIN(DOUT7) +#if ASSERT_PIN_IO(DOUT7) mcu_config_output(DOUT7); #endif -#if ASSERT_PIN(DOUT8) +#if ASSERT_PIN_IO(DOUT8) mcu_config_output(DOUT8); #endif -#if ASSERT_PIN(DOUT9) +#if ASSERT_PIN_IO(DOUT9) mcu_config_output(DOUT9); #endif -#if ASSERT_PIN(DOUT10) +#if ASSERT_PIN_IO(DOUT10) mcu_config_output(DOUT10); #endif -#if ASSERT_PIN(DOUT11) +#if ASSERT_PIN_IO(DOUT11) mcu_config_output(DOUT11); #endif -#if ASSERT_PIN(DOUT12) +#if ASSERT_PIN_IO(DOUT12) mcu_config_output(DOUT12); #endif -#if ASSERT_PIN(DOUT13) +#if ASSERT_PIN_IO(DOUT13) mcu_config_output(DOUT13); #endif -#if ASSERT_PIN(DOUT14) +#if ASSERT_PIN_IO(DOUT14) mcu_config_output(DOUT14); #endif -#if ASSERT_PIN(DOUT15) +#if ASSERT_PIN_IO(DOUT15) mcu_config_output(DOUT15); #endif -#if ASSERT_PIN(DOUT16) +#if ASSERT_PIN_IO(DOUT16) mcu_config_output(DOUT16); #endif -#if ASSERT_PIN(DOUT17) +#if ASSERT_PIN_IO(DOUT17) mcu_config_output(DOUT17); #endif -#if ASSERT_PIN(DOUT18) +#if ASSERT_PIN_IO(DOUT18) mcu_config_output(DOUT18); #endif -#if ASSERT_PIN(DOUT19) +#if ASSERT_PIN_IO(DOUT19) mcu_config_output(DOUT19); #endif -#if ASSERT_PIN(DOUT20) +#if ASSERT_PIN_IO(DOUT20) mcu_config_output(DOUT20); #endif -#if ASSERT_PIN(DOUT21) +#if ASSERT_PIN_IO(DOUT21) mcu_config_output(DOUT21); #endif -#if ASSERT_PIN(DOUT22) +#if ASSERT_PIN_IO(DOUT22) mcu_config_output(DOUT22); #endif -#if ASSERT_PIN(DOUT23) +#if ASSERT_PIN_IO(DOUT23) mcu_config_output(DOUT23); #endif -#if ASSERT_PIN(DOUT24) +#if ASSERT_PIN_IO(DOUT24) mcu_config_output(DOUT24); #endif -#if ASSERT_PIN(DOUT25) +#if ASSERT_PIN_IO(DOUT25) mcu_config_output(DOUT25); #endif -#if ASSERT_PIN(DOUT26) +#if ASSERT_PIN_IO(DOUT26) mcu_config_output(DOUT26); #endif -#if ASSERT_PIN(DOUT27) +#if ASSERT_PIN_IO(DOUT27) mcu_config_output(DOUT27); #endif -#if ASSERT_PIN(DOUT28) +#if ASSERT_PIN_IO(DOUT28) mcu_config_output(DOUT28); #endif -#if ASSERT_PIN(DOUT29) +#if ASSERT_PIN_IO(DOUT29) mcu_config_output(DOUT29); #endif -#if ASSERT_PIN(DOUT30) +#if ASSERT_PIN_IO(DOUT30) mcu_config_output(DOUT30); #endif -#if ASSERT_PIN(DOUT31) +#if ASSERT_PIN_IO(DOUT31) mcu_config_output(DOUT31); #endif -#if ASSERT_PIN(LIMIT_X) +#if ASSERT_PIN_IO(LIMIT_X) mcu_config_input(LIMIT_X); #ifdef LIMIT_X_PULLUP mcu_config_pullup(LIMIT_X); @@ -280,7 +280,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_X); #endif #endif -#if ASSERT_PIN(LIMIT_Y) +#if ASSERT_PIN_IO(LIMIT_Y) mcu_config_input(LIMIT_Y); #ifdef LIMIT_Y_PULLUP mcu_config_pullup(LIMIT_Y); @@ -289,7 +289,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_Y); #endif #endif -#if ASSERT_PIN(LIMIT_Z) +#if ASSERT_PIN_IO(LIMIT_Z) mcu_config_input(LIMIT_Z); #ifdef LIMIT_Z_PULLUP mcu_config_pullup(LIMIT_Z); @@ -298,7 +298,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_Z); #endif #endif -#if ASSERT_PIN(LIMIT_X2) +#if ASSERT_PIN_IO(LIMIT_X2) mcu_config_input(LIMIT_X2); #ifdef LIMIT_X2_PULLUP mcu_config_pullup(LIMIT_X2); @@ -307,7 +307,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_X2); #endif #endif -#if ASSERT_PIN(LIMIT_Y2) +#if ASSERT_PIN_IO(LIMIT_Y2) mcu_config_input(LIMIT_Y2); #ifdef LIMIT_Y2_PULLUP mcu_config_pullup(LIMIT_Y2); @@ -316,7 +316,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_Y2); #endif #endif -#if ASSERT_PIN(LIMIT_Z2) +#if ASSERT_PIN_IO(LIMIT_Z2) mcu_config_input(LIMIT_Z2); #ifdef LIMIT_Z2_PULLUP mcu_config_pullup(LIMIT_Z2); @@ -325,7 +325,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_Z2); #endif #endif -#if ASSERT_PIN(LIMIT_A) +#if ASSERT_PIN_IO(LIMIT_A) mcu_config_input(LIMIT_A); #ifdef LIMIT_A_PULLUP mcu_config_pullup(LIMIT_A); @@ -334,7 +334,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_A); #endif #endif -#if ASSERT_PIN(LIMIT_B) +#if ASSERT_PIN_IO(LIMIT_B) mcu_config_input(LIMIT_B); #ifdef LIMIT_B_PULLUP mcu_config_pullup(LIMIT_B); @@ -343,7 +343,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_B); #endif #endif -#if ASSERT_PIN(LIMIT_C) +#if ASSERT_PIN_IO(LIMIT_C) mcu_config_input(LIMIT_C); #ifdef LIMIT_C_PULLUP mcu_config_pullup(LIMIT_C); @@ -352,7 +352,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(LIMIT_C); #endif #endif -#if ASSERT_PIN(PROBE) +#if ASSERT_PIN_IO(PROBE) mcu_config_input(PROBE); #ifdef PROBE_PULLUP mcu_config_pullup(PROBE); @@ -361,7 +361,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(PROBE); #endif #endif -#if ASSERT_PIN(ESTOP) +#if ASSERT_PIN_IO(ESTOP) mcu_config_input(ESTOP); #ifdef ESTOP_PULLUP mcu_config_pullup(ESTOP); @@ -370,7 +370,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(ESTOP); #endif #endif -#if ASSERT_PIN(SAFETY_DOOR) +#if ASSERT_PIN_IO(SAFETY_DOOR) mcu_config_input(SAFETY_DOOR); #ifdef SAFETY_DOOR_PULLUP mcu_config_pullup(SAFETY_DOOR); @@ -379,7 +379,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(SAFETY_DOOR); #endif #endif -#if ASSERT_PIN(FHOLD) +#if ASSERT_PIN_IO(FHOLD) mcu_config_input(FHOLD); #ifdef FHOLD_PULLUP mcu_config_pullup(FHOLD); @@ -388,7 +388,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(FHOLD); #endif #endif -#if ASSERT_PIN(CS_RES) +#if ASSERT_PIN_IO(CS_RES) mcu_config_input(CS_RES); #ifdef CS_RES_PULLUP mcu_config_pullup(CS_RES); @@ -397,55 +397,55 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(CS_RES); #endif #endif -#if ASSERT_PIN(ANALOG0) +#if ASSERT_PIN_IO(ANALOG0) mcu_config_analog(ANALOG0); #endif -#if ASSERT_PIN(ANALOG1) +#if ASSERT_PIN_IO(ANALOG1) mcu_config_analog(ANALOG1); #endif -#if ASSERT_PIN(ANALOG2) +#if ASSERT_PIN_IO(ANALOG2) mcu_config_analog(ANALOG2); #endif -#if ASSERT_PIN(ANALOG3) +#if ASSERT_PIN_IO(ANALOG3) mcu_config_analog(ANALOG3); #endif -#if ASSERT_PIN(ANALOG4) +#if ASSERT_PIN_IO(ANALOG4) mcu_config_analog(ANALOG4); #endif -#if ASSERT_PIN(ANALOG5) +#if ASSERT_PIN_IO(ANALOG5) mcu_config_analog(ANALOG5); #endif -#if ASSERT_PIN(ANALOG6) +#if ASSERT_PIN_IO(ANALOG6) mcu_config_analog(ANALOG6); #endif -#if ASSERT_PIN(ANALOG7) +#if ASSERT_PIN_IO(ANALOG7) mcu_config_analog(ANALOG7); #endif -#if ASSERT_PIN(ANALOG8) +#if ASSERT_PIN_IO(ANALOG8) mcu_config_analog(ANALOG8); #endif -#if ASSERT_PIN(ANALOG9) +#if ASSERT_PIN_IO(ANALOG9) mcu_config_analog(ANALOG9); #endif -#if ASSERT_PIN(ANALOG10) +#if ASSERT_PIN_IO(ANALOG10) mcu_config_analog(ANALOG10); #endif -#if ASSERT_PIN(ANALOG11) +#if ASSERT_PIN_IO(ANALOG11) mcu_config_analog(ANALOG11); #endif -#if ASSERT_PIN(ANALOG12) +#if ASSERT_PIN_IO(ANALOG12) mcu_config_analog(ANALOG12); #endif -#if ASSERT_PIN(ANALOG13) +#if ASSERT_PIN_IO(ANALOG13) mcu_config_analog(ANALOG13); #endif -#if ASSERT_PIN(ANALOG14) +#if ASSERT_PIN_IO(ANALOG14) mcu_config_analog(ANALOG14); #endif -#if ASSERT_PIN(ANALOG15) +#if ASSERT_PIN_IO(ANALOG15) mcu_config_analog(ANALOG15); #endif -#if ASSERT_PIN(DIN0) +#if ASSERT_PIN_IO(DIN0) mcu_config_input(DIN0); #ifdef DIN0_PULLUP mcu_config_pullup(DIN0); @@ -454,7 +454,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN0); #endif #endif -#if ASSERT_PIN(DIN1) +#if ASSERT_PIN_IO(DIN1) mcu_config_input(DIN1); #ifdef DIN1_PULLUP mcu_config_pullup(DIN1); @@ -463,7 +463,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN1); #endif #endif -#if ASSERT_PIN(DIN2) +#if ASSERT_PIN_IO(DIN2) mcu_config_input(DIN2); #ifdef DIN2_PULLUP mcu_config_pullup(DIN2); @@ -472,7 +472,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN2); #endif #endif -#if ASSERT_PIN(DIN3) +#if ASSERT_PIN_IO(DIN3) mcu_config_input(DIN3); #ifdef DIN3_PULLUP mcu_config_pullup(DIN3); @@ -481,7 +481,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN3); #endif #endif -#if ASSERT_PIN(DIN4) +#if ASSERT_PIN_IO(DIN4) mcu_config_input(DIN4); #ifdef DIN4_PULLUP mcu_config_pullup(DIN4); @@ -490,7 +490,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN4); #endif #endif -#if ASSERT_PIN(DIN5) +#if ASSERT_PIN_IO(DIN5) mcu_config_input(DIN5); #ifdef DIN5_PULLUP mcu_config_pullup(DIN5); @@ -499,7 +499,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN5); #endif #endif -#if ASSERT_PIN(DIN6) +#if ASSERT_PIN_IO(DIN6) mcu_config_input(DIN6); #ifdef DIN6_PULLUP mcu_config_pullup(DIN6); @@ -508,7 +508,7 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN6); #endif #endif -#if ASSERT_PIN(DIN7) +#if ASSERT_PIN_IO(DIN7) mcu_config_input(DIN7); #ifdef DIN7_PULLUP mcu_config_pullup(DIN7); @@ -517,198 +517,198 @@ void __attribute__((weak)) mcu_io_init(void) mcu_config_input_isr(DIN7); #endif #endif -#if ASSERT_PIN(DIN8) +#if ASSERT_PIN_IO(DIN8) mcu_config_input(DIN8); #ifdef DIN8_PULLUP mcu_config_pullup(DIN8); #endif #endif -#if ASSERT_PIN(DIN9) +#if ASSERT_PIN_IO(DIN9) mcu_config_input(DIN9); #ifdef DIN9_PULLUP mcu_config_pullup(DIN9); #endif #endif -#if ASSERT_PIN(DIN10) +#if ASSERT_PIN_IO(DIN10) mcu_config_input(DIN10); #ifdef DIN10_PULLUP mcu_config_pullup(DIN10); #endif #endif -#if ASSERT_PIN(DIN11) +#if ASSERT_PIN_IO(DIN11) mcu_config_input(DIN11); #ifdef DIN11_PULLUP mcu_config_pullup(DIN11); #endif #endif -#if ASSERT_PIN(DIN12) +#if ASSERT_PIN_IO(DIN12) mcu_config_input(DIN12); #ifdef DIN12_PULLUP mcu_config_pullup(DIN12); #endif #endif -#if ASSERT_PIN(DIN13) +#if ASSERT_PIN_IO(DIN13) mcu_config_input(DIN13); #ifdef DIN13_PULLUP mcu_config_pullup(DIN13); #endif #endif -#if ASSERT_PIN(DIN14) +#if ASSERT_PIN_IO(DIN14) mcu_config_input(DIN14); #ifdef DIN14_PULLUP mcu_config_pullup(DIN14); #endif #endif -#if ASSERT_PIN(DIN15) +#if ASSERT_PIN_IO(DIN15) mcu_config_input(DIN15); #ifdef DIN15_PULLUP mcu_config_pullup(DIN15); #endif #endif -#if ASSERT_PIN(DIN16) +#if ASSERT_PIN_IO(DIN16) mcu_config_input(DIN16); #ifdef DIN16_PULLUP mcu_config_pullup(DIN16); #endif #endif -#if ASSERT_PIN(DIN17) +#if ASSERT_PIN_IO(DIN17) mcu_config_input(DIN17); #ifdef DIN17_PULLUP mcu_config_pullup(DIN17); #endif #endif -#if ASSERT_PIN(DIN18) +#if ASSERT_PIN_IO(DIN18) mcu_config_input(DIN18); #ifdef DIN18_PULLUP mcu_config_pullup(DIN18); #endif #endif -#if ASSERT_PIN(DIN19) +#if ASSERT_PIN_IO(DIN19) mcu_config_input(DIN19); #ifdef DIN19_PULLUP mcu_config_pullup(DIN19); #endif #endif -#if ASSERT_PIN(DIN20) +#if ASSERT_PIN_IO(DIN20) mcu_config_input(DIN20); #ifdef DIN20_PULLUP mcu_config_pullup(DIN20); #endif #endif -#if ASSERT_PIN(DIN21) +#if ASSERT_PIN_IO(DIN21) mcu_config_input(DIN21); #ifdef DIN21_PULLUP mcu_config_pullup(DIN21); #endif #endif -#if ASSERT_PIN(DIN22) +#if ASSERT_PIN_IO(DIN22) mcu_config_input(DIN22); #ifdef DIN22_PULLUP mcu_config_pullup(DIN22); #endif #endif -#if ASSERT_PIN(DIN23) +#if ASSERT_PIN_IO(DIN23) mcu_config_input(DIN23); #ifdef DIN23_PULLUP mcu_config_pullup(DIN23); #endif #endif -#if ASSERT_PIN(DIN24) +#if ASSERT_PIN_IO(DIN24) mcu_config_input(DIN24); #ifdef DIN24_PULLUP mcu_config_pullup(DIN24); #endif #endif -#if ASSERT_PIN(DIN25) +#if ASSERT_PIN_IO(DIN25) mcu_config_input(DIN25); #ifdef DIN25_PULLUP mcu_config_pullup(DIN25); #endif #endif -#if ASSERT_PIN(DIN26) +#if ASSERT_PIN_IO(DIN26) mcu_config_input(DIN26); #ifdef DIN26_PULLUP mcu_config_pullup(DIN26); #endif #endif -#if ASSERT_PIN(DIN27) +#if ASSERT_PIN_IO(DIN27) mcu_config_input(DIN27); #ifdef DIN27_PULLUP mcu_config_pullup(DIN27); #endif #endif -#if ASSERT_PIN(DIN28) +#if ASSERT_PIN_IO(DIN28) mcu_config_input(DIN28); #ifdef DIN28_PULLUP mcu_config_pullup(DIN28); #endif #endif -#if ASSERT_PIN(DIN29) +#if ASSERT_PIN_IO(DIN29) mcu_config_input(DIN29); #ifdef DIN29_PULLUP mcu_config_pullup(DIN29); #endif #endif -#if ASSERT_PIN(DIN30) +#if ASSERT_PIN_IO(DIN30) mcu_config_input(DIN30); #ifdef DIN30_PULLUP mcu_config_pullup(DIN30); #endif #endif -#if ASSERT_PIN(DIN31) +#if ASSERT_PIN_IO(DIN31) mcu_config_input(DIN31); #ifdef DIN31_PULLUP mcu_config_pullup(DIN31); #endif #endif -#if ASSERT_PIN(TX) +#if ASSERT_PIN_IO(TX) mcu_config_output(TX); #endif -#if ASSERT_PIN(RX) +#if ASSERT_PIN_IO(RX) mcu_config_input(RX); #ifdef RX_PULLUP mcu_config_pullup(RX); #endif #endif -#if ASSERT_PIN(USB_DM) +#if ASSERT_PIN_IO(USB_DM) mcu_config_input(USB_DM); #ifdef USB_DM_PULLUP mcu_config_pullup(USB_DM); #endif #endif -#if ASSERT_PIN(USB_DP) +#if ASSERT_PIN_IO(USB_DP) mcu_config_input(USB_DP); #ifdef USB_DP_PULLUP mcu_config_pullup(USB_DP); #endif #endif -#if ASSERT_PIN(SPI_CLK) +#if ASSERT_PIN_IO(SPI_CLK) mcu_config_output(SPI_CLK); #endif -#if ASSERT_PIN(SPI_SDI) +#if ASSERT_PIN_IO(SPI_SDI) mcu_config_input(SPI_SDI); #ifdef SPI_SDI_PULLUP mcu_config_pullup(SPI_SDI); #endif #endif -#if ASSERT_PIN(SPI_SDO) +#if ASSERT_PIN_IO(SPI_SDO) mcu_config_output(SPI_SDO); #endif -#if ASSERT_PIN(SPI_CS) +#if ASSERT_PIN_IO(SPI_CS) mcu_config_output(SPI_CS); #endif -#if ASSERT_PIN(I2C_CLK) +#if ASSERT_PIN_IO(I2C_CLK) mcu_config_input(I2C_CLK); mcu_config_pullup(I2C_CLK); #endif -#if ASSERT_PIN(I2C_DATA) +#if ASSERT_PIN_IO(I2C_DATA) mcu_config_input(I2C_DATA); mcu_config_pullup(I2C_DATA); #endif -#if ASSERT_PIN(TX2) +#if ASSERT_PIN_IO(TX2) mcu_config_output(TX2); #endif -#if ASSERT_PIN(RX2) +#if ASSERT_PIN_IO(RX2) mcu_config_input(RX2); #ifdef RX2_PULLUP mcu_config_pullup(RX2); diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index adec8b214..cfb3c0311 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -1105,8 +1105,10 @@ extern "C" // Helper macros #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #ifndef BYTE_OPS #define BYTE_OPS diff --git a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h index d22df1fab..7f6a9311d 100644 --- a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h +++ b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h @@ -2980,8 +2980,10 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #endif -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #ifndef BYTE_OPS #define BYTE_OPS diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index 386bf7bb7..f309a2108 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -4624,8 +4624,10 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #endif -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #ifndef BYTE_OPS #define BYTE_OPS diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index ae58d4c0c..94c37ba7d 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -3195,8 +3195,10 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #endif -#define __indirect__ex__(X, Y) DIO##X##_##Y +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #ifndef BYTE_OPS #define BYTE_OPS diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index 7f7be6cbb..8fecb7814 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -41,6 +41,8 @@ extern "C" #define DIO1 -1 #define STEP0_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_IO_OFFSET >> 3)-1) #define STEP0_IO_BITMASK (1 << (STEP0_IO_OFFSET & 0x7)) +#define DIO1_IO_BYTEOFFSET STEP0_IO_BYTEOFFSET +#define DIO1_IO_BITMASK STEP0_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -58,6 +60,8 @@ extern "C" #define DIO2 -2 #define STEP1_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_IO_OFFSET >> 3)-1) #define STEP1_IO_BITMASK (1 << (STEP1_IO_OFFSET & 0x7)) +#define DIO2_IO_BYTEOFFSET STEP1_IO_BYTEOFFSET +#define DIO2_IO_BITMASK STEP1_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -75,6 +79,8 @@ extern "C" #define DIO3 -3 #define STEP2_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_IO_OFFSET >> 3)-1) #define STEP2_IO_BITMASK (1 << (STEP2_IO_OFFSET & 0x7)) +#define DIO3_IO_BYTEOFFSET STEP2_IO_BYTEOFFSET +#define DIO3_IO_BITMASK STEP2_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -92,6 +98,8 @@ extern "C" #define DIO4 -4 #define STEP3_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_IO_OFFSET >> 3)-1) #define STEP3_IO_BITMASK (1 << (STEP3_IO_OFFSET & 0x7)) +#define DIO4_IO_BYTEOFFSET STEP3_IO_BYTEOFFSET +#define DIO4_IO_BITMASK STEP3_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -109,6 +117,8 @@ extern "C" #define DIO5 -5 #define STEP4_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_IO_OFFSET >> 3)-1) #define STEP4_IO_BITMASK (1 << (STEP4_IO_OFFSET & 0x7)) +#define DIO5_IO_BYTEOFFSET STEP4_IO_BYTEOFFSET +#define DIO5_IO_BITMASK STEP4_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -126,6 +136,8 @@ extern "C" #define DIO6 -6 #define STEP5_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_IO_OFFSET >> 3)-1) #define STEP5_IO_BITMASK (1 << (STEP5_IO_OFFSET & 0x7)) +#define DIO6_IO_BYTEOFFSET STEP5_IO_BYTEOFFSET +#define DIO6_IO_BITMASK STEP5_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -143,6 +155,8 @@ extern "C" #define DIO7 -7 #define STEP6_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_IO_OFFSET >> 3)-1) #define STEP6_IO_BITMASK (1 << (STEP6_IO_OFFSET & 0x7)) +#define DIO7_IO_BYTEOFFSET STEP6_IO_BYTEOFFSET +#define DIO7_IO_BITMASK STEP6_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -160,6 +174,8 @@ extern "C" #define DIO8 -8 #define STEP7_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_IO_OFFSET >> 3)-1) #define STEP7_IO_BITMASK (1 << (STEP7_IO_OFFSET & 0x7)) +#define DIO8_IO_BYTEOFFSET STEP7_IO_BYTEOFFSET +#define DIO8_IO_BITMASK STEP7_IO_BITMASK #ifndef IC74HC595_HAS_STEPS #define IC74HC595_HAS_STEPS #endif @@ -177,6 +193,8 @@ extern "C" #define DIO9 -9 #define DIR0_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR0_IO_OFFSET >> 3)-1) #define DIR0_IO_BITMASK (1 << (DIR0_IO_OFFSET & 0x7)) +#define DIO9_IO_BYTEOFFSET DIR0_IO_BYTEOFFSET +#define DIO9_IO_BITMASK DIR0_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -194,6 +212,8 @@ extern "C" #define DIO10 -10 #define DIR1_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR1_IO_OFFSET >> 3)-1) #define DIR1_IO_BITMASK (1 << (DIR1_IO_OFFSET & 0x7)) +#define DIO10_IO_BYTEOFFSET DIR1_IO_BYTEOFFSET +#define DIO10_IO_BITMASK DIR1_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -211,6 +231,8 @@ extern "C" #define DIO11 -11 #define DIR2_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR2_IO_OFFSET >> 3)-1) #define DIR2_IO_BITMASK (1 << (DIR2_IO_OFFSET & 0x7)) +#define DIO11_IO_BYTEOFFSET DIR2_IO_BYTEOFFSET +#define DIO11_IO_BITMASK DIR2_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -228,6 +250,8 @@ extern "C" #define DIO12 -12 #define DIR3_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR3_IO_OFFSET >> 3)-1) #define DIR3_IO_BITMASK (1 << (DIR3_IO_OFFSET & 0x7)) +#define DIO12_IO_BYTEOFFSET DIR3_IO_BYTEOFFSET +#define DIO12_IO_BITMASK DIR3_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -245,6 +269,8 @@ extern "C" #define DIO13 -13 #define DIR4_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR4_IO_OFFSET >> 3)-1) #define DIR4_IO_BITMASK (1 << (DIR4_IO_OFFSET & 0x7)) +#define DIO13_IO_BYTEOFFSET DIR4_IO_BYTEOFFSET +#define DIO13_IO_BITMASK DIR4_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -262,6 +288,8 @@ extern "C" #define DIO14 -14 #define DIR5_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR5_IO_OFFSET >> 3)-1) #define DIR5_IO_BITMASK (1 << (DIR5_IO_OFFSET & 0x7)) +#define DIO14_IO_BYTEOFFSET DIR5_IO_BYTEOFFSET +#define DIO14_IO_BITMASK DIR5_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -279,6 +307,8 @@ extern "C" #define DIO15 -15 #define DIR6_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR6_IO_OFFSET >> 3)-1) #define DIR6_IO_BITMASK (1 << (DIR6_IO_OFFSET & 0x7)) +#define DIO15_IO_BYTEOFFSET DIR6_IO_BYTEOFFSET +#define DIO15_IO_BITMASK DIR6_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -296,6 +326,8 @@ extern "C" #define DIO16 -16 #define DIR7_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR7_IO_OFFSET >> 3)-1) #define DIR7_IO_BITMASK (1 << (DIR7_IO_OFFSET & 0x7)) +#define DIO16_IO_BYTEOFFSET DIR7_IO_BYTEOFFSET +#define DIO16_IO_BITMASK DIR7_IO_BITMASK #ifndef IC74HC595_HAS_DIRS #define IC74HC595_HAS_DIRS #endif @@ -313,6 +345,8 @@ extern "C" #define DIO17 -17 #define STEP0_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_EN_IO_OFFSET >> 3)-1) #define STEP0_EN_IO_BITMASK (1 << (STEP0_EN_IO_OFFSET & 0x7)) +#define DIO17_IO_BYTEOFFSET STEP0_EN_IO_BYTEOFFSET +#define DIO17_IO_BITMASK STEP0_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -330,6 +364,8 @@ extern "C" #define DIO18 -18 #define STEP1_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_EN_IO_OFFSET >> 3)-1) #define STEP1_EN_IO_BITMASK (1 << (STEP1_EN_IO_OFFSET & 0x7)) +#define DIO18_IO_BYTEOFFSET STEP1_EN_IO_BYTEOFFSET +#define DIO18_IO_BITMASK STEP1_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -347,6 +383,8 @@ extern "C" #define DIO19 -19 #define STEP2_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_EN_IO_OFFSET >> 3)-1) #define STEP2_EN_IO_BITMASK (1 << (STEP2_EN_IO_OFFSET & 0x7)) +#define DIO19_IO_BYTEOFFSET STEP2_EN_IO_BYTEOFFSET +#define DIO19_IO_BITMASK STEP2_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -364,6 +402,8 @@ extern "C" #define DIO20 -20 #define STEP3_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_EN_IO_OFFSET >> 3)-1) #define STEP3_EN_IO_BITMASK (1 << (STEP3_EN_IO_OFFSET & 0x7)) +#define DIO20_IO_BYTEOFFSET STEP3_EN_IO_BYTEOFFSET +#define DIO20_IO_BITMASK STEP3_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -381,6 +421,8 @@ extern "C" #define DIO21 -21 #define STEP4_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_EN_IO_OFFSET >> 3)-1) #define STEP4_EN_IO_BITMASK (1 << (STEP4_EN_IO_OFFSET & 0x7)) +#define DIO21_IO_BYTEOFFSET STEP4_EN_IO_BYTEOFFSET +#define DIO21_IO_BITMASK STEP4_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -398,6 +440,8 @@ extern "C" #define DIO22 -22 #define STEP5_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_EN_IO_OFFSET >> 3)-1) #define STEP5_EN_IO_BITMASK (1 << (STEP5_EN_IO_OFFSET & 0x7)) +#define DIO22_IO_BYTEOFFSET STEP5_EN_IO_BYTEOFFSET +#define DIO22_IO_BITMASK STEP5_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -415,6 +459,8 @@ extern "C" #define DIO23 -23 #define STEP6_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_EN_IO_OFFSET >> 3)-1) #define STEP6_EN_IO_BITMASK (1 << (STEP6_EN_IO_OFFSET & 0x7)) +#define DIO23_IO_BYTEOFFSET STEP6_EN_IO_BYTEOFFSET +#define DIO23_IO_BITMASK STEP6_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -432,6 +478,8 @@ extern "C" #define DIO24 -24 #define STEP7_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_EN_IO_OFFSET >> 3)-1) #define STEP7_EN_IO_BITMASK (1 << (STEP7_EN_IO_OFFSET & 0x7)) +#define DIO24_IO_BYTEOFFSET STEP7_EN_IO_BYTEOFFSET +#define DIO24_IO_BITMASK STEP7_EN_IO_BITMASK #ifndef IC74HC595_HAS_STEPS_EN #define IC74HC595_HAS_STEPS_EN #endif @@ -449,6 +497,8 @@ extern "C" #define DIO25 -25 #define PWM0_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM0_IO_OFFSET >> 3)-1) #define PWM0_IO_BITMASK (1 << (PWM0_IO_OFFSET & 0x7)) +#define DIO25_IO_BYTEOFFSET PWM0_IO_BYTEOFFSET +#define DIO25_IO_BITMASK PWM0_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -466,6 +516,8 @@ extern "C" #define DIO26 -26 #define PWM1_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM1_IO_OFFSET >> 3)-1) #define PWM1_IO_BITMASK (1 << (PWM1_IO_OFFSET & 0x7)) +#define DIO26_IO_BYTEOFFSET PWM1_IO_BYTEOFFSET +#define DIO26_IO_BITMASK PWM1_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -483,6 +535,8 @@ extern "C" #define DIO27 -27 #define PWM2_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM2_IO_OFFSET >> 3)-1) #define PWM2_IO_BITMASK (1 << (PWM2_IO_OFFSET & 0x7)) +#define DIO27_IO_BYTEOFFSET PWM2_IO_BYTEOFFSET +#define DIO27_IO_BITMASK PWM2_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -500,6 +554,8 @@ extern "C" #define DIO28 -28 #define PWM3_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM3_IO_OFFSET >> 3)-1) #define PWM3_IO_BITMASK (1 << (PWM3_IO_OFFSET & 0x7)) +#define DIO28_IO_BYTEOFFSET PWM3_IO_BYTEOFFSET +#define DIO28_IO_BITMASK PWM3_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -517,6 +573,8 @@ extern "C" #define DIO29 -29 #define PWM4_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM4_IO_OFFSET >> 3)-1) #define PWM4_IO_BITMASK (1 << (PWM4_IO_OFFSET & 0x7)) +#define DIO29_IO_BYTEOFFSET PWM4_IO_BYTEOFFSET +#define DIO29_IO_BITMASK PWM4_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -534,6 +592,8 @@ extern "C" #define DIO30 -30 #define PWM5_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM5_IO_OFFSET >> 3)-1) #define PWM5_IO_BITMASK (1 << (PWM5_IO_OFFSET & 0x7)) +#define DIO30_IO_BYTEOFFSET PWM5_IO_BYTEOFFSET +#define DIO30_IO_BITMASK PWM5_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -551,6 +611,8 @@ extern "C" #define DIO31 -31 #define PWM6_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM6_IO_OFFSET >> 3)-1) #define PWM6_IO_BITMASK (1 << (PWM6_IO_OFFSET & 0x7)) +#define DIO31_IO_BYTEOFFSET PWM6_IO_BYTEOFFSET +#define DIO31_IO_BITMASK PWM6_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -568,6 +630,8 @@ extern "C" #define DIO32 -32 #define PWM7_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM7_IO_OFFSET >> 3)-1) #define PWM7_IO_BITMASK (1 << (PWM7_IO_OFFSET & 0x7)) +#define DIO32_IO_BYTEOFFSET PWM7_IO_BYTEOFFSET +#define DIO32_IO_BITMASK PWM7_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -585,6 +649,8 @@ extern "C" #define DIO33 -33 #define PWM8_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM8_IO_OFFSET >> 3)-1) #define PWM8_IO_BITMASK (1 << (PWM8_IO_OFFSET & 0x7)) +#define DIO33_IO_BYTEOFFSET PWM8_IO_BYTEOFFSET +#define DIO33_IO_BITMASK PWM8_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -602,6 +668,8 @@ extern "C" #define DIO34 -34 #define PWM9_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM9_IO_OFFSET >> 3)-1) #define PWM9_IO_BITMASK (1 << (PWM9_IO_OFFSET & 0x7)) +#define DIO34_IO_BYTEOFFSET PWM9_IO_BYTEOFFSET +#define DIO34_IO_BITMASK PWM9_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -619,6 +687,8 @@ extern "C" #define DIO35 -35 #define PWM10_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM10_IO_OFFSET >> 3)-1) #define PWM10_IO_BITMASK (1 << (PWM10_IO_OFFSET & 0x7)) +#define DIO35_IO_BYTEOFFSET PWM10_IO_BYTEOFFSET +#define DIO35_IO_BITMASK PWM10_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -636,6 +706,8 @@ extern "C" #define DIO36 -36 #define PWM11_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM11_IO_OFFSET >> 3)-1) #define PWM11_IO_BITMASK (1 << (PWM11_IO_OFFSET & 0x7)) +#define DIO36_IO_BYTEOFFSET PWM11_IO_BYTEOFFSET +#define DIO36_IO_BITMASK PWM11_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -653,6 +725,8 @@ extern "C" #define DIO37 -37 #define PWM12_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM12_IO_OFFSET >> 3)-1) #define PWM12_IO_BITMASK (1 << (PWM12_IO_OFFSET & 0x7)) +#define DIO37_IO_BYTEOFFSET PWM12_IO_BYTEOFFSET +#define DIO37_IO_BITMASK PWM12_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -670,6 +744,8 @@ extern "C" #define DIO38 -38 #define PWM13_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM13_IO_OFFSET >> 3)-1) #define PWM13_IO_BITMASK (1 << (PWM13_IO_OFFSET & 0x7)) +#define DIO38_IO_BYTEOFFSET PWM13_IO_BYTEOFFSET +#define DIO38_IO_BITMASK PWM13_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -687,6 +763,8 @@ extern "C" #define DIO39 -39 #define PWM14_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM14_IO_OFFSET >> 3)-1) #define PWM14_IO_BITMASK (1 << (PWM14_IO_OFFSET & 0x7)) +#define DIO39_IO_BYTEOFFSET PWM14_IO_BYTEOFFSET +#define DIO39_IO_BITMASK PWM14_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -704,6 +782,8 @@ extern "C" #define DIO40 -40 #define PWM15_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM15_IO_OFFSET >> 3)-1) #define PWM15_IO_BITMASK (1 << (PWM15_IO_OFFSET & 0x7)) +#define DIO40_IO_BYTEOFFSET PWM15_IO_BYTEOFFSET +#define DIO40_IO_BITMASK PWM15_IO_BITMASK #ifndef IC74HC595_HAS_PWMS #define IC74HC595_HAS_PWMS #endif @@ -721,6 +801,8 @@ extern "C" #define DIO41 -41 #define SERVO0_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO0_IO_OFFSET >> 3)-1) #define SERVO0_IO_BITMASK (1 << (SERVO0_IO_OFFSET & 0x7)) +#define DIO41_IO_BYTEOFFSET SERVO0_IO_BYTEOFFSET +#define DIO41_IO_BITMASK SERVO0_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -738,6 +820,8 @@ extern "C" #define DIO42 -42 #define SERVO1_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO1_IO_OFFSET >> 3)-1) #define SERVO1_IO_BITMASK (1 << (SERVO1_IO_OFFSET & 0x7)) +#define DIO42_IO_BYTEOFFSET SERVO1_IO_BYTEOFFSET +#define DIO42_IO_BITMASK SERVO1_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -755,6 +839,8 @@ extern "C" #define DIO43 -43 #define SERVO2_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO2_IO_OFFSET >> 3)-1) #define SERVO2_IO_BITMASK (1 << (SERVO2_IO_OFFSET & 0x7)) +#define DIO43_IO_BYTEOFFSET SERVO2_IO_BYTEOFFSET +#define DIO43_IO_BITMASK SERVO2_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -772,6 +858,8 @@ extern "C" #define DIO44 -44 #define SERVO3_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO3_IO_OFFSET >> 3)-1) #define SERVO3_IO_BITMASK (1 << (SERVO3_IO_OFFSET & 0x7)) +#define DIO44_IO_BYTEOFFSET SERVO3_IO_BYTEOFFSET +#define DIO44_IO_BITMASK SERVO3_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -789,6 +877,8 @@ extern "C" #define DIO45 -45 #define SERVO4_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO4_IO_OFFSET >> 3)-1) #define SERVO4_IO_BITMASK (1 << (SERVO4_IO_OFFSET & 0x7)) +#define DIO45_IO_BYTEOFFSET SERVO4_IO_BYTEOFFSET +#define DIO45_IO_BITMASK SERVO4_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -806,6 +896,8 @@ extern "C" #define DIO46 -46 #define SERVO5_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO5_IO_OFFSET >> 3)-1) #define SERVO5_IO_BITMASK (1 << (SERVO5_IO_OFFSET & 0x7)) +#define DIO46_IO_BYTEOFFSET SERVO5_IO_BYTEOFFSET +#define DIO46_IO_BITMASK SERVO5_IO_BITMASK #ifndef IC74HC595_HAS_SERVOS #define IC74HC595_HAS_SERVOS #endif @@ -823,6 +915,8 @@ extern "C" #define DIO47 -47 #define DOUT0_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT0_IO_OFFSET >> 3)-1) #define DOUT0_IO_BITMASK (1 << (DOUT0_IO_OFFSET & 0x7)) +#define DIO47_IO_BYTEOFFSET DOUT0_IO_BYTEOFFSET +#define DIO47_IO_BITMASK DOUT0_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -840,6 +934,8 @@ extern "C" #define DIO48 -48 #define DOUT1_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT1_IO_OFFSET >> 3)-1) #define DOUT1_IO_BITMASK (1 << (DOUT1_IO_OFFSET & 0x7)) +#define DIO48_IO_BYTEOFFSET DOUT1_IO_BYTEOFFSET +#define DIO48_IO_BITMASK DOUT1_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -857,6 +953,8 @@ extern "C" #define DIO49 -49 #define DOUT2_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT2_IO_OFFSET >> 3)-1) #define DOUT2_IO_BITMASK (1 << (DOUT2_IO_OFFSET & 0x7)) +#define DIO49_IO_BYTEOFFSET DOUT2_IO_BYTEOFFSET +#define DIO49_IO_BITMASK DOUT2_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -874,6 +972,8 @@ extern "C" #define DIO50 -50 #define DOUT3_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT3_IO_OFFSET >> 3)-1) #define DOUT3_IO_BITMASK (1 << (DOUT3_IO_OFFSET & 0x7)) +#define DIO50_IO_BYTEOFFSET DOUT3_IO_BYTEOFFSET +#define DIO50_IO_BITMASK DOUT3_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -891,6 +991,8 @@ extern "C" #define DIO51 -51 #define DOUT4_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT4_IO_OFFSET >> 3)-1) #define DOUT4_IO_BITMASK (1 << (DOUT4_IO_OFFSET & 0x7)) +#define DIO51_IO_BYTEOFFSET DOUT4_IO_BYTEOFFSET +#define DIO51_IO_BITMASK DOUT4_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -908,6 +1010,8 @@ extern "C" #define DIO52 -52 #define DOUT5_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT5_IO_OFFSET >> 3)-1) #define DOUT5_IO_BITMASK (1 << (DOUT5_IO_OFFSET & 0x7)) +#define DIO52_IO_BYTEOFFSET DOUT5_IO_BYTEOFFSET +#define DIO52_IO_BITMASK DOUT5_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -925,6 +1029,8 @@ extern "C" #define DIO53 -53 #define DOUT6_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT6_IO_OFFSET >> 3)-1) #define DOUT6_IO_BITMASK (1 << (DOUT6_IO_OFFSET & 0x7)) +#define DIO53_IO_BYTEOFFSET DOUT6_IO_BYTEOFFSET +#define DIO53_IO_BITMASK DOUT6_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -942,6 +1048,8 @@ extern "C" #define DIO54 -54 #define DOUT7_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT7_IO_OFFSET >> 3)-1) #define DOUT7_IO_BITMASK (1 << (DOUT7_IO_OFFSET & 0x7)) +#define DIO54_IO_BYTEOFFSET DOUT7_IO_BYTEOFFSET +#define DIO54_IO_BITMASK DOUT7_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -959,6 +1067,8 @@ extern "C" #define DIO55 -55 #define DOUT8_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT8_IO_OFFSET >> 3)-1) #define DOUT8_IO_BITMASK (1 << (DOUT8_IO_OFFSET & 0x7)) +#define DIO55_IO_BYTEOFFSET DOUT8_IO_BYTEOFFSET +#define DIO55_IO_BITMASK DOUT8_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -976,6 +1086,8 @@ extern "C" #define DIO56 -56 #define DOUT9_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT9_IO_OFFSET >> 3)-1) #define DOUT9_IO_BITMASK (1 << (DOUT9_IO_OFFSET & 0x7)) +#define DIO56_IO_BYTEOFFSET DOUT9_IO_BYTEOFFSET +#define DIO56_IO_BITMASK DOUT9_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -993,6 +1105,8 @@ extern "C" #define DIO57 -57 #define DOUT10_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT10_IO_OFFSET >> 3)-1) #define DOUT10_IO_BITMASK (1 << (DOUT10_IO_OFFSET & 0x7)) +#define DIO57_IO_BYTEOFFSET DOUT10_IO_BYTEOFFSET +#define DIO57_IO_BITMASK DOUT10_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1010,6 +1124,8 @@ extern "C" #define DIO58 -58 #define DOUT11_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT11_IO_OFFSET >> 3)-1) #define DOUT11_IO_BITMASK (1 << (DOUT11_IO_OFFSET & 0x7)) +#define DIO58_IO_BYTEOFFSET DOUT11_IO_BYTEOFFSET +#define DIO58_IO_BITMASK DOUT11_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1027,6 +1143,8 @@ extern "C" #define DIO59 -59 #define DOUT12_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT12_IO_OFFSET >> 3)-1) #define DOUT12_IO_BITMASK (1 << (DOUT12_IO_OFFSET & 0x7)) +#define DIO59_IO_BYTEOFFSET DOUT12_IO_BYTEOFFSET +#define DIO59_IO_BITMASK DOUT12_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1044,6 +1162,8 @@ extern "C" #define DIO60 -60 #define DOUT13_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT13_IO_OFFSET >> 3)-1) #define DOUT13_IO_BITMASK (1 << (DOUT13_IO_OFFSET & 0x7)) +#define DIO60_IO_BYTEOFFSET DOUT13_IO_BYTEOFFSET +#define DIO60_IO_BITMASK DOUT13_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1061,6 +1181,8 @@ extern "C" #define DIO61 -61 #define DOUT14_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT14_IO_OFFSET >> 3)-1) #define DOUT14_IO_BITMASK (1 << (DOUT14_IO_OFFSET & 0x7)) +#define DIO61_IO_BYTEOFFSET DOUT14_IO_BYTEOFFSET +#define DIO61_IO_BITMASK DOUT14_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1078,6 +1200,8 @@ extern "C" #define DIO62 -62 #define DOUT15_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT15_IO_OFFSET >> 3)-1) #define DOUT15_IO_BITMASK (1 << (DOUT15_IO_OFFSET & 0x7)) +#define DIO62_IO_BYTEOFFSET DOUT15_IO_BYTEOFFSET +#define DIO62_IO_BITMASK DOUT15_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1095,6 +1219,8 @@ extern "C" #define DIO63 -63 #define DOUT16_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT16_IO_OFFSET >> 3)-1) #define DOUT16_IO_BITMASK (1 << (DOUT16_IO_OFFSET & 0x7)) +#define DIO63_IO_BYTEOFFSET DOUT16_IO_BYTEOFFSET +#define DIO63_IO_BITMASK DOUT16_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1112,6 +1238,8 @@ extern "C" #define DIO64 -64 #define DOUT17_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT17_IO_OFFSET >> 3)-1) #define DOUT17_IO_BITMASK (1 << (DOUT17_IO_OFFSET & 0x7)) +#define DIO64_IO_BYTEOFFSET DOUT17_IO_BYTEOFFSET +#define DIO64_IO_BITMASK DOUT17_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1129,6 +1257,8 @@ extern "C" #define DIO65 -65 #define DOUT18_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT18_IO_OFFSET >> 3)-1) #define DOUT18_IO_BITMASK (1 << (DOUT18_IO_OFFSET & 0x7)) +#define DIO65_IO_BYTEOFFSET DOUT18_IO_BYTEOFFSET +#define DIO65_IO_BITMASK DOUT18_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1146,6 +1276,8 @@ extern "C" #define DIO66 -66 #define DOUT19_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT19_IO_OFFSET >> 3)-1) #define DOUT19_IO_BITMASK (1 << (DOUT19_IO_OFFSET & 0x7)) +#define DIO66_IO_BYTEOFFSET DOUT19_IO_BYTEOFFSET +#define DIO66_IO_BITMASK DOUT19_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1163,6 +1295,8 @@ extern "C" #define DIO67 -67 #define DOUT20_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT20_IO_OFFSET >> 3)-1) #define DOUT20_IO_BITMASK (1 << (DOUT20_IO_OFFSET & 0x7)) +#define DIO67_IO_BYTEOFFSET DOUT20_IO_BYTEOFFSET +#define DIO67_IO_BITMASK DOUT20_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1180,6 +1314,8 @@ extern "C" #define DIO68 -68 #define DOUT21_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT21_IO_OFFSET >> 3)-1) #define DOUT21_IO_BITMASK (1 << (DOUT21_IO_OFFSET & 0x7)) +#define DIO68_IO_BYTEOFFSET DOUT21_IO_BYTEOFFSET +#define DIO68_IO_BITMASK DOUT21_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1197,6 +1333,8 @@ extern "C" #define DIO69 -69 #define DOUT22_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT22_IO_OFFSET >> 3)-1) #define DOUT22_IO_BITMASK (1 << (DOUT22_IO_OFFSET & 0x7)) +#define DIO69_IO_BYTEOFFSET DOUT22_IO_BYTEOFFSET +#define DIO69_IO_BITMASK DOUT22_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1214,6 +1352,8 @@ extern "C" #define DIO70 -70 #define DOUT23_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT23_IO_OFFSET >> 3)-1) #define DOUT23_IO_BITMASK (1 << (DOUT23_IO_OFFSET & 0x7)) +#define DIO70_IO_BYTEOFFSET DOUT23_IO_BYTEOFFSET +#define DIO70_IO_BITMASK DOUT23_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1231,6 +1371,8 @@ extern "C" #define DIO71 -71 #define DOUT24_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT24_IO_OFFSET >> 3)-1) #define DOUT24_IO_BITMASK (1 << (DOUT24_IO_OFFSET & 0x7)) +#define DIO71_IO_BYTEOFFSET DOUT24_IO_BYTEOFFSET +#define DIO71_IO_BITMASK DOUT24_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1248,6 +1390,8 @@ extern "C" #define DIO72 -72 #define DOUT25_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT25_IO_OFFSET >> 3)-1) #define DOUT25_IO_BITMASK (1 << (DOUT25_IO_OFFSET & 0x7)) +#define DIO72_IO_BYTEOFFSET DOUT25_IO_BYTEOFFSET +#define DIO72_IO_BITMASK DOUT25_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1265,6 +1409,8 @@ extern "C" #define DIO73 -73 #define DOUT26_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT26_IO_OFFSET >> 3)-1) #define DOUT26_IO_BITMASK (1 << (DOUT26_IO_OFFSET & 0x7)) +#define DIO73_IO_BYTEOFFSET DOUT26_IO_BYTEOFFSET +#define DIO73_IO_BITMASK DOUT26_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1282,6 +1428,8 @@ extern "C" #define DIO74 -74 #define DOUT27_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT27_IO_OFFSET >> 3)-1) #define DOUT27_IO_BITMASK (1 << (DOUT27_IO_OFFSET & 0x7)) +#define DIO74_IO_BYTEOFFSET DOUT27_IO_BYTEOFFSET +#define DIO74_IO_BITMASK DOUT27_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1299,6 +1447,8 @@ extern "C" #define DIO75 -75 #define DOUT28_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT28_IO_OFFSET >> 3)-1) #define DOUT28_IO_BITMASK (1 << (DOUT28_IO_OFFSET & 0x7)) +#define DIO75_IO_BYTEOFFSET DOUT28_IO_BYTEOFFSET +#define DIO75_IO_BITMASK DOUT28_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1316,6 +1466,8 @@ extern "C" #define DIO76 -76 #define DOUT29_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT29_IO_OFFSET >> 3)-1) #define DOUT29_IO_BITMASK (1 << (DOUT29_IO_OFFSET & 0x7)) +#define DIO76_IO_BYTEOFFSET DOUT29_IO_BYTEOFFSET +#define DIO76_IO_BITMASK DOUT29_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1333,6 +1485,8 @@ extern "C" #define DIO77 -77 #define DOUT30_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT30_IO_OFFSET >> 3)-1) #define DOUT30_IO_BITMASK (1 << (DOUT30_IO_OFFSET & 0x7)) +#define DIO77_IO_BYTEOFFSET DOUT30_IO_BYTEOFFSET +#define DIO77_IO_BITMASK DOUT30_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif @@ -1350,12 +1504,13 @@ extern "C" #define DIO78 -78 #define DOUT31_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT31_IO_OFFSET >> 3)-1) #define DOUT31_IO_BITMASK (1 << (DOUT31_IO_OFFSET & 0x7)) +#define DIO78_IO_BYTEOFFSET DOUT31_IO_BYTEOFFSET +#define DIO78_IO_BITMASK DOUT31_IO_BITMASK #ifndef IC74HC595_HAS_DOUTS #define IC74HC595_HAS_DOUTS #endif #endif - #if (IC74HC595_COUNT < 0) #undef IC74HC595_COUNT #define IC74HC595_COUNT 0 @@ -1364,15 +1519,15 @@ extern "C" #endif #if (IC74HC595_COUNT>0) -#ifndef __helper__ -#define __helper_ex__(left, mid, right) (left##mid##right) -#define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) +#ifndef __indirect__ +#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__(X, Y) __indirect__ex__(X, Y) #endif extern uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; -#define ic74hc595_set_pin(pin) ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] |= (__helper__(pin, _IO_BITMASK)) -#define ic74hc595_clear_pin(pin) ic74hc595_io_pins[__helper__(pin, _IO_BYTEOFFSET)] &= ~(__helper__(pin, _IO_BITMASK)) -#define ic74hc595_toggle_pin(pin) ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] ^= (__helper__(pin, _IO_BITMASK)) -#define ic74hc595_get_pin(pin) (ic74hc595_io_pins[(__helper__(pin, _IO_BYTEOFFSET))] & (__helper__(pin, _IO_BITMASK))) +#define ic74hc595_set_pin(pin) ic74hc595_io_pins[(__indirect__(pin, IO_BYTEOFFSET))] |= (__indirect__(pin, IO_BITMASK)) +#define ic74hc595_clear_pin(pin) ic74hc595_io_pins[__indirect__(pin, IO_BYTEOFFSET)] &= ~(__indirect__(pin, IO_BITMASK)) +#define ic74hc595_toggle_pin(pin) ic74hc595_io_pins[(__indirect__(pin, IO_BYTEOFFSET))] ^= (__indirect__(pin, IO_BITMASK)) +#define ic74hc595_get_pin(pin) (ic74hc595_io_pins[(__indirect__(pin, IO_BYTEOFFSET))] & (__indirect__(pin, IO_BITMASK))) #else #define ic74hc595_set_pin(pin) #define ic74hc595_clear_pin(pin) From 39fee0eae3439f4a1f4b7dedd6f297576ae26624 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 8 Jul 2023 19:24:06 +0100 Subject: [PATCH 013/168] fixed compilation errors --- uCNC/src/core/parser.c | 2 +- uCNC/src/modules/digimstep.c | 64 ++++++++++++++++++------------------ 2 files changed, 33 insertions(+), 33 deletions(-) diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index d22507868..9d9cb6d27 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -1161,7 +1161,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa case M10: if (words->p < 6) { - io_set_pwm(words->p + SERVO_PINS_OFFSET, (uint8_t)CLAMP(words->s, 0, 255)); + io_set_pinvalue(words->p + SERVO_PINS_OFFSET, (uint8_t)CLAMP(words->s, 0, 255)); } break; #endif diff --git a/uCNC/src/modules/digimstep.c b/uCNC/src/modules/digimstep.c index 1843e56d4..5cff99317 100644 --- a/uCNC/src/modules/digimstep.c +++ b/uCNC/src/modules/digimstep.c @@ -161,73 +161,73 @@ bool m351_exec(void *args) if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_X)) { #if ASSERT_PIN(STEPPER0_MSTEP0) - io_set_output(STEPPER0_MSTEP0, ((uint8_t)ptr->words->xyzabc[0] & 0x01)); + io_set_pinvalue(STEPPER0_MSTEP0, ((uint8_t)ptr->words->xyzabc[0] & 0x01)); #endif #if ASSERT_PIN(STEPPER0_MSTEP1) - io_set_output(STEPPER0_MSTEP1, ((uint8_t)ptr->words->xyzabc[0] & 0x02)); + io_set_pinvalue(STEPPER0_MSTEP1, ((uint8_t)ptr->words->xyzabc[0] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_Y)) { #if ASSERT_PIN(STEPPER1_MSTEP0) - io_set_output(STEPPER1_MSTEP0, ((uint8_t)ptr->words->xyzabc[1] & 0x01)); + io_set_pinvalue(STEPPER1_MSTEP0, ((uint8_t)ptr->words->xyzabc[1] & 0x01)); #endif #if ASSERT_PIN(STEPPER1_MSTEP1) - io_set_output(STEPPER1_MSTEP1, ((uint8_t)ptr->words->xyzabc[1] & 0x02)); + io_set_pinvalue(STEPPER1_MSTEP1, ((uint8_t)ptr->words->xyzabc[1] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_Z)) { #if ASSERT_PIN(STEPPER2_MSTEP0) - io_set_output(STEPPER2_MSTEP0, (((uint8_t)ptr->words->xyzabc[2]) & 0x01)); + io_set_pinvalue(STEPPER2_MSTEP0, (((uint8_t)ptr->words->xyzabc[2]) & 0x01)); #endif #if ASSERT_PIN(STEPPER2_MSTEP1) - io_set_output(STEPPER2_MSTEP1, (((uint8_t)ptr->words->xyzabc[2]) & 0x02)); + io_set_pinvalue(STEPPER2_MSTEP1, (((uint8_t)ptr->words->xyzabc[2]) & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_A)) { #if ASSERT_PIN(STEPPER3_MSTEP0) - io_set_output(STEPPER3_MSTEP0, ((uint8_t)ptr->words->xyzabc[3] & 0x01)); + io_set_pinvalue(STEPPER3_MSTEP0, ((uint8_t)ptr->words->xyzabc[3] & 0x01)); #endif #if ASSERT_PIN(STEPPER3_MSTEP1) - io_set_output(STEPPER3_MSTEP1, ((uint8_t)ptr->words->xyzabc[3] & 0x02)); + io_set_pinvalue(STEPPER3_MSTEP1, ((uint8_t)ptr->words->xyzabc[3] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_B)) { #if ASSERT_PIN(STEPPER4_MSTEP0) - io_set_output(STEPPER4_MSTEP0, ((uint8_t)ptr->words->xyzabc[4] & 0x01)); + io_set_pinvalue(STEPPER4_MSTEP0, ((uint8_t)ptr->words->xyzabc[4] & 0x01)); #endif #if ASSERT_PIN(STEPPER4_MSTEP1) - io_set_output(STEPPER4_MSTEP1, ((uint8_t)ptr->words->xyzabc[4] & 0x02)); + io_set_pinvalue(STEPPER4_MSTEP1, ((uint8_t)ptr->words->xyzabc[4] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_C)) { #if ASSERT_PIN(STEPPER5_MSTEP0) - io_set_output(STEPPER5_MSTEP0, ((uint8_t)ptr->words->xyzabc[5] & 0x01)); + io_set_pinvalue(STEPPER5_MSTEP0, ((uint8_t)ptr->words->xyzabc[5] & 0x01)); #endif #if ASSERT_PIN(STEPPER5_MSTEP1) - io_set_output(STEPPER5_MSTEP1, ((uint8_t)ptr->words->xyzabc[5] & 0x02)); + io_set_pinvalue(STEPPER5_MSTEP1, ((uint8_t)ptr->words->xyzabc[5] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_I)) { #if ASSERT_PIN(STEPPER6_MSTEP0) - io_set_output(STEPPER6_MSTEP0, ((uint8_t)ptr->words->ijk[0] & 0x01)); + io_set_pinvalue(STEPPER6_MSTEP0, ((uint8_t)ptr->words->ijk[0] & 0x01)); #endif #if ASSERT_PIN(STEPPER6_MSTEP1) - io_set_output(STEPPER6_MSTEP1, ((uint8_t)ptr->words->ijk[0] & 0x02)); + io_set_pinvalue(STEPPER6_MSTEP1, ((uint8_t)ptr->words->ijk[0] & 0x02)); #endif } if (CHECKFLAG(ptr->cmd->words, GCODE_WORD_J)) { #if ASSERT_PIN(STEPPER7_MSTEP0) - io_set_output(STEPPER7_MSTEP0, ((uint8_t)ptr->words->ijk[1] & 0x01)); + io_set_pinvalue(STEPPER7_MSTEP0, ((uint8_t)ptr->words->ijk[1] & 0x01)); #endif #if ASSERT_PIN(STEPPER7_MSTEP1) - io_set_output(STEPPER7_MSTEP1, ((uint8_t)ptr->words->ijk[1] & 0x02)); + io_set_pinvalue(STEPPER7_MSTEP1, ((uint8_t)ptr->words->ijk[1] & 0x02)); #endif } @@ -243,52 +243,52 @@ bool m351_exec(void *args) DECL_MODULE(digimstep) { #if ASSERT_PIN(STEPPER0_MSTEP0) - io_set_output(STEPPER0_MSTEP0, (STEPPER0_MSTEP & 0x01)); + io_set_pinvalue(STEPPER0_MSTEP0, (STEPPER0_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER0_MSTEP1) - io_set_output(STEPPER0_MSTEP1, (STEPPER0_MSTEP & 0x02)); + io_set_pinvalue(STEPPER0_MSTEP1, (STEPPER0_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER1_MSTEP0) - io_set_output(STEPPER1_MSTEP0, (STEPPER1_MSTEP & 0x01)); + io_set_pinvalue(STEPPER1_MSTEP0, (STEPPER1_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER1_MSTEP1) - io_set_output(STEPPER1_MSTEP1, (STEPPER1_MSTEP & 0x02)); + io_set_pinvalue(STEPPER1_MSTEP1, (STEPPER1_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER2_MSTEP0) - io_set_output(STEPPER2_MSTEP0, (STEPPER2_MSTEP & 0x01)); + io_set_pinvalue(STEPPER2_MSTEP0, (STEPPER2_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER2_MSTEP1) - io_set_output(STEPPER2_MSTEP1, (STEPPER2_MSTEP & 0x02)); + io_set_pinvalue(STEPPER2_MSTEP1, (STEPPER2_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER3_MSTEP0) - io_set_output(STEPPER3_MSTEP0, (STEPPER3_MSTEP & 0x01)); + io_set_pinvalue(STEPPER3_MSTEP0, (STEPPER3_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER3_MSTEP1) - io_set_output(STEPPER3_MSTEP1, (STEPPER3_MSTEP & 0x02)); + io_set_pinvalue(STEPPER3_MSTEP1, (STEPPER3_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER4_MSTEP0) - io_set_output(STEPPER4_MSTEP0, (STEPPER4_MSTEP & 0x01)); + io_set_pinvalue(STEPPER4_MSTEP0, (STEPPER4_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER4_MSTEP1) - io_set_output(STEPPER4_MSTEP1, (STEPPER4_MSTEP & 0x02)); + io_set_pinvalue(STEPPER4_MSTEP1, (STEPPER4_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER5_MSTEP0) - io_set_output(STEPPER5_MSTEP0, (STEPPER5_MSTEP & 0x01)); + io_set_pinvalue(STEPPER5_MSTEP0, (STEPPER5_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER5_MSTEP1) - io_set_output(STEPPER5_MSTEP1, (STEPPER5_MSTEP & 0x02)); + io_set_pinvalue(STEPPER5_MSTEP1, (STEPPER5_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER6_MSTEP0) - io_set_output(STEPPER6_MSTEP0, (STEPPER6_MSTEP & 0x01)); + io_set_pinvalue(STEPPER6_MSTEP0, (STEPPER6_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER6_MSTEP1) - io_set_output(STEPPER6_MSTEP1, (STEPPER6_MSTEP & 0x02)); + io_set_pinvalue(STEPPER6_MSTEP1, (STEPPER6_MSTEP & 0x02)); #endif #if ASSERT_PIN(STEPPER7_MSTEP0) - io_set_output(STEPPER7_MSTEP0, (STEPPER7_MSTEP & 0x01)); + io_set_pinvalue(STEPPER7_MSTEP0, (STEPPER7_MSTEP & 0x01)); #endif #if ASSERT_PIN(STEPPER7_MSTEP1) - io_set_output(STEPPER7_MSTEP1, (STEPPER7_MSTEP & 0x02)); + io_set_pinvalue(STEPPER7_MSTEP1, (STEPPER7_MSTEP & 0x02)); #endif #ifdef ENABLE_PARSER_MODULES From da1e1a2b46e1ee99e508ac98de14580b2220f1a1 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 8 Jul 2023 19:47:21 +0100 Subject: [PATCH 014/168] removed parentesis to prevent compilation error --- uCNC/src/hal/mcus/avr/mcumap_avr.h | 4 +++- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 2 +- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 2 +- uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h | 2 +- uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h | 2 +- uCNC/src/hal/mcus/samd21/mcumap_samd21.h | 2 +- uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h | 2 +- uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h | 2 +- uCNC/src/modules/ic74hc595.h | 2 +- 9 files changed, 11 insertions(+), 9 deletions(-) diff --git a/uCNC/src/hal/mcus/avr/mcumap_avr.h b/uCNC/src/hal/mcus/avr/mcumap_avr.h index df12eb897..6b3941f9d 100644 --- a/uCNC/src/hal/mcus/avr/mcumap_avr.h +++ b/uCNC/src/hal/mcus/avr/mcumap_avr.h @@ -4523,8 +4523,10 @@ extern "C" #define PCINT2_MASK (PCINT2_LIMITS_MASK | PCINT2_CONTROLS_MASK | PROBE_ISR2 | PCINT2_DIN_IO_MASK) // Indirect macro access -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#ifndef __indirect__ +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif #ifndef BYTE_OPS #define BYTE_OPS diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 1d396beeb..8aa4624d9 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2747,7 +2747,7 @@ extern "C" #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index f91b7ee8a..0e50cf0a6 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1022,7 +1022,7 @@ extern "C" #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index a794a25cd..2c2dbb75c 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -3837,7 +3837,7 @@ extern "C" // Indirect macro access #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index cfb3c0311..69f3293e9 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -1106,7 +1106,7 @@ extern "C" #define __helper_ex__(left, mid, right) (left##mid##right) #define __helper__(left, mid, right) (__helper_ex__(left, mid, right)) #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h index 7f6a9311d..2fdd8680f 100644 --- a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h +++ b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h @@ -2981,7 +2981,7 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index f309a2108..09ddd1ab6 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -4625,7 +4625,7 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index 94c37ba7d..5c38f66d5 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -3196,7 +3196,7 @@ extern bool tud_cdc_n_connected (uint8_t itf); #endif #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index 8fecb7814..dd0f796bc 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -1520,7 +1520,7 @@ extern "C" #if (IC74HC595_COUNT>0) #ifndef __indirect__ -#define __indirect__ex__(X, Y) (DIO##X##_##Y) +#define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif extern uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; From 0747ea917cd5ffea57985635b95f0d5f8e81c628 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 11 Jul 2023 23:31:48 +0100 Subject: [PATCH 015/168] working for ESPs --- docs/mcumap_gen.xlsx | Bin 465402 -> 464549 bytes uCNC/src/core/io_control.c | 364 ++-- uCNC/src/core/io_control.h | 6 +- uCNC/src/hal/io_hal.h | 1883 +++++++++++++++----- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 11 +- uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 61 - uCNC/src/modules/ic74hc595.h | 158 +- 7 files changed, 1672 insertions(+), 811 deletions(-) diff --git a/docs/mcumap_gen.xlsx b/docs/mcumap_gen.xlsx index ef31de9d3afb1d231d0b939c65ef6e0ee1210408..70e29b4d691f0033d9c6cb91430ec3708522844a 100644 GIT binary patch literal 464549 zcmeEt1yfw@x@F_;F2N-b+zBqh2`<6if=h6BcMtCF&_Hl^37*D7a1E~0@SS_^nVOkj zaEB_Opt{#u&wA|Ln~kC@6f`yf761H=1H_?Fa}7K^G|X$G(+LDCC$jMB5v6y zOjSMd{*WmQZnKvK(w=eTi-^h5F0!ah#gymBK0nD^m~@m@>+PbbS1Gc7tiWL{^*aAU zny8dEQ3;E6=`=OVIS4&!04Lm0VO)QdcH$pKBu38dL1Pch+1J+K)G%W?vhHUF-NT{w z4G-yd%&%U2qxzcLrV?(eI@K{&l-MPv#UET-+7fxx&fy+@p!elvvSUCKZ zm*Dc112-}fxYP9=O|6}nnO?vC{|^5j+}8gQdS!yVLLUoq$f?w0=4I*D8PX!7%yt7Dr_yCN>{svujmI>b-*t z96gO=iiAVuWoZ${o$7;|x0)nJ-s+4O^36-4Uv( zSnyib8f80vq;S_avF`pWp4o-<-+v2j(r?l;jX~?v<}rBggqzmU}-pLSM!3 z*+@VnY3bVkwMpWu%vThl001NKc0>a^<7Un5YUlXX$jnbc%pRvss#`az}dGR0T z3l0#O?9CdvB-2SA)+?HQpovQ9y zF4%4{!B#*sd8E2pCzeD>OktHy@3WVr|vtsee z>0j~L!Yo98BTQK!^2st`<{Qwfhm1p0=S96&leX3@-p5BUq$|hQIVV8v)T#GFb&I3r zP{Rq&WmO{6mtaWLZl=0L))nnn$=-)hV9V94O)E=Hz_yg$h|!?KGr>!3IE-$-DdM^Ge6-YdARvo!dT8ZhC2DmY|96d>4;AJRm>>7|sc;>63x zX6=)S64)eD1C0B@T;KH72KOVMZhhJ${h<}rn5~quD!qi3Tp?kI+|0DtyR-|=Rc&>X7b)UJ6|_}^%cEIUsjiN=0B~z+f!mB!|r`iznAV_3?(tK zms!Z5l1C5jScu5ff!bs8Nz)td{J?<5^#t?xkV%9l$>z?;Uk0m&IMA7VypC^(*IOiu z*IF1QTe3tHPIYggR`*f7tux;>tT(Td;co&VXj>!J4z(3MheM1=Y;+SRzQJYMPWEO+ zY5aYfjeO{-UG@9`$@FnKYNiRqo0n#l36~P$bxi(F8+~r<*;&_CuvYPtK~c6PRH0UT zp*4=b5$FUrGJ>J_Q!FIk%Cw?%?h<8+9j)$| zKa*yp|1RO$6JRZ1$%+NL4K`JvIQ_gLJeF^=7~+%@$%G_9fmYqJMt3mNvR@MCov`=i za|kCRpv2tVzaW22!n&;3d4S5f)6BA`t34;ViL*HyNs3r5NF5{->r(fnNyYf#X5)wy z+*<$VhN1(!i&X=+bQ;(p zcINH!z1fm4Z?c)cYYFbrvRKLF{aRj6hcCIf2p6bzPUpJ78dN zFDm@YIK}iRc62q{wU3*-W&?cIT(EU?NK_VJnW?MmSEuNQETJHmpT@rnEXFmDbzX*f z%LzY*v;Pdd<}0epa$al1IW77)is*(pMAzbLT4@X)&}^xY%p?q#W%fe29FKFbS9344GQj6a4t2A=}+(u%<7}-GGp_#9s7g97{#_Y~`>hbskc3 z98Y3Ifk{QS)$*P!9vV{wMI%ik)qWCAua?&PweMG_xOyf8ts{`Zws?qU%BHq%7s|>6 z7+QoPn+#At8KiA!ibPzko}Ay&{H&4xbMy1#o;@~ea09$tL#_drzaf`N9!>J#-8zoW z{cr1wzaMqp3EpS#2>oA+(*Kwo6I~SmfH;H%;DcZBuZ`ejVQT8^#QgS+^>sCTPn3<# zWI^{kO};0MJB5%Vqk3Q}y@Pe9k9ca^yr!)6rTY*5WSh_UC%aQQ7c_8hkcQz*RR zNJq6@c_LCsP^pTduR{Bs8+pg|^r;pe{+)Eo-Fk43L+&z?E6R`D{F~sQ#CRNCgP*Rw zW|ZT}vgUAlzxNcD^s(ZW7&lD`CZF@?>o=wiQB}c*Abg|^FjojGdX*a(wwyxzJ*Wq(OYsq6{e3*Y*^RBV932OP5 zVd=&PSO+_RqkYmn52|@JytdgLO3GA7ImxzlGo(pcP*BptW*dD1IzoEXn8qz;G5nS!OzdU$e zB=vb%Jn7@c>l--PKCM~v4br%Y!E4tS?1{Xq*>CotOVmT&X*(?wtDMM^&fXuf8E%f ztereUe8wW#-RgQdWIp@Te&c%dv?`PX67;&fSl*^R3wO2q8^i5BH1)}Q;Fs&^`VY^s z!|0tty~p35Zi`tvcZK-9zNNbk$&(Wwbs+MSR;6G{bN^FXFs%EAxG%Py7&3v;S{rP=fmYi%T$if%i})M z3bX#nGoI?r&iclO3-y&dnzGoi(;KuP((NnuHHNASi?$mJeALb_5*8^!Vg>y0boG&T zg_E&%{YSr^2s~e=Rsp0#BoFLfJwgPVn@9U!F0#&or&hTu&-Da-?l1NWB&SH9&vsCM z62JT^%UKC-e!P&y3HAQXX6QtMt!7?a&s+WI9kyU2E;)XP*EeVP&XG@3 zYS>dTN97J!V@VAKLZrPeXbOIh31Z&{u{Ln{Aik9kC7vF8onE6)b|i+j@e56k-m(6u z$szq4^ZPMvJ!L9Zx#Qq&#>J7xrroy0ymjuu*xkpO=<3elD4P^TfD@?y-WTL*{)sf& z%Zkvtq&UyXiVd3M-tQR{{rr9F`F8l07lz)cOD5^?Z_D2fJL8CMHIk`^$0V%#DyPvh z!FisYez~xc@85ZUCmByRT+^9bWI0BN9w)IMT{AV^OE2>5bfX>EeCDmrcN;Yn60? zrzP@CE!FvH4@aOUQljZ&w=)Dk1sJxl-BmN85tW&qbM!A%HIzQ!*D* z&A)T_z>M#yU$zq0pBzTe&})B(jxNx?fMlNY6=k2@TU;%^lg$K!C^ce)h)?0 zuu}{Dx)c9)Ju-DNV2g5vG;+F9E#;HZTc(6&deI*J@eXbEH#hWfg0E77Zyoi^thA4q zFx?&6e}y6IQ)=yf!Cdv58L{cN{x{D>q9-3Ks+TMEkyHAJk*Vy!wSG30i-s%(6Z4$M z$C2hdAM!ihUpONQDmj|fmCZmAKPlgcj;Ky z?((55{;_XIeL0qM;L=>7$5uIy?qzw6wyg!uZgvM;h!!Pw`&IMq zX-F7IeEBE%#g0|DZtwEcmk@j9XZ?rA8{gdI@=I_win<~d$9%MCsD-#D*RI4zy_;gS zTD#Iigxogy!lsie$Wk&Ad=1)jly`vbQ$F7k?PY~jgrr^3HV%%Mv5_s5KXv01Q|6o- zmSHu3)U#foK81396wLItK!}HAflmeCl_2ey$3@=(x7L5==wns^JhAkXdorg7L4cWy6vn zr4j5MGT!g)15)hSU__=!9`!BCBOukLZ54CrAx^Z-M3ZvFa-j_DOb{=#t(0oh;rWy3 z&$>-FUezP@IJ+u9qy{jCmeRe4hOlt`goYo69i@QmY1A^N;R;`TE)i8WhBjvw%0pRdR1sBLgO! zH}kMV;Hr^Jl!;(;h>F`i5eE-wXFS~T3G1ifK`C3lGzVv7V|`-!q$iwEE7YW@L!M}G zw0b>H{885L<)`~*GO2?z|7=*rH{fQn(h_``!N1wBgU z4W<<)&^kizXg|Ap3}k+Fwb!8O{@BRcU>ZZP)*Wmr0TkF&d}|tCw4!GLdkFsI6_yQ5 zp4C<3?p1{pF?h_4ov~0`6Qw-JHdk!IFkHc5quXhXKE^yYI`lwgi51}=gFRelBP0Z0 zgB)(lv!mWe8zGc-8sl_FhgvaKFjczk3 z$93h`Qb3gIrWBt;WpiwyMw*dOMkPGoY(kEhyd)|&3o`pz_T5Sqm%X%V*24f$M30$kvd^#P# zrOOPz<(UyD;6S_V}NW?CoYN zjIkEZFylN)X8Gjj#9o};)SWul26+_z1R5x^Iad$!;0^+^4BtPhWlU28Nj5%&La(xbfc8!(!H0puX-|+Gf zYZMgqOSw8$Je0%~tAB}Gz!AOL8#I8=>bgq%}46Ry(p^jxFAO=WuC zcY$rcM8f&~p5&!(@{5%(oMsx@nV`6rRF}kOme^hoh z3F9SK16|b4hL=x;OQMX;oT1EzlVplmZ6tQ1F)RO&4c#8bv1gJlqVal>0mAu5 z{qHPftT(}%ywqQ8B?WF4qsBs+cbwLr2HeU)`p5G2^Bj&{?C;?MmyAh&gBBl3k{>eN zu?A-|Ssd*|>6>;0Z)m1hy-%D%V|LJ8PVfR9bJdbXcqx?{9Atrvhn|=WQPkF=FXUh^Ma4jL8pd#!ew zw%yZ+V221=b-u5Hg!WpyBnENjW_YB1d&-jwgptKS!S?R3FNS zJ%k+Q1(R1MA9R{Z+8;o>pIOGp5B~bF62fSy5k#|LWZ|_0fle!~QqV0=WZ4~BdD>fj z=bU__nS@|;NnVVg)LOf=5?$X)2Nvc(OK1NKEB#y6;aS;S%7aem8}=F#7#rm3DsA|P z&`95*J7FWctEWMue>!&h3a^h~>w#y^eN%G@(&yaq`0lj&Gyq%f=-WhbTyFW>N2!>9 zy(@rVaX;zMOUab`W>ps zDHVOMW^i_2v?iYpZBO(MTf58#U2c`1Z#o~4q>)-Wy;$?-F&iq1;~zeyCp;|1J(vu- zfbNM)Bq`r)GTA9hN~UG{P@=4T;`Al`FR0YIenDI}e%@yP1Vd4-RmDL=Gv>5+xakLx}#tj+}( zu=~5x!>onJiYXLv!2`QxU2o9s{TChKMK(+kYbee?i;MO%ZkG7!Z#6-Wki``n1Uc;) zpu4*yFJelDkd^*WQFT9T#nbgZB)2&D0h@=npwnADjK24VT;xihycYhUqihZqLc?SK zgaoqsQVW$_Shz?pO}$F*3X_H;D=Z~U8xq>PY7vtvP#D8Av~z`T&#{I&23aJ|llEru zTtlH_??4+(ME306eFSrV-OxYiegZf95B50k5qIOSs;PqGDAOHl8uc0z00c1YY=Zn(wvYKbD02B207pK#U zzHqvL=Kgqcct{p6Av6(z^ZW`s0cb`9x4p03(_cJ~B9Q&p5Dpzb|ZUJJpvc zV?jSM_~yTY!&|?CtNAaFJCwPYQ$TI2KRH>PjCH>WN9Df^-Vo6UV055@-|*Z_B!4{g zL7o50)ONohHa!~<+KG?saP(i<Isq4yBJ5EF%*`k0-E7f@^8^EY(;C8uO(>k`PQ|G_L@YAeN0TAwwgm#Tqz z(xKJG1?B!0;pu#Ts2$Ds5jT{iKlVe#)Wa!56moCC8mkvpd8{R4R)Qh&>}3?xxVO%u zNL7XX&Tm1@_>Y)j$q`r&w~E(G`vg(~WQ3{gjuRbCU1m_R_dAr z9K8hMweQJ)Q6X0|j$KVUXp6+a=QZ$GdT~{{uUR4q;aX%HGAQ!%qByfm6XTsPq$B6l zvJnWb87O-ggfwzyr@5azl{nKZO8uGs@eCO*w(M=LCRa^59D~D|epID)BDQR-ZbEYv zWy#u_?kt!(+uC0EqqqJ-xLDOHT@=l(IYPBKx&Q1xauBi~#d-wRQ8ebDZI}Sx z*uaoG{7Ih5LpJRJ z95NjNLPwvLly!0GR8hX5(TSR3!ATO z%9e?ivR}`Nf z?tu!)|2!avo84TczTy38qC(sb!+G7t^C&4QXw8t3iVJIVS2-xB6&`$kQ^;zCS8%;i z$g21nWQflSwROEO2=-Q8go?X6F*87v7l@#I;SI!=MfDP&* zBXV_{P8AodfdFAfrJ_zO>h_YchY8EooTXo@wHb1E#%xmr5tMQnikvNSZo4PTUGk_S zJjA$Tw4Q~=00kG;06|O8q3Sxm0RpCCKU^G34P)_lpj-{o{Gga!o}R2!dgum5+BtJG z-fqu)i({RYhC*cMnpOw?5Q!)C-`pF`$j}LXNZEaiv{p&7cVlcTBPw?yk8YthEH3^)!Ddc z9crGeF#^{ze?(5}aM3cCVNx8&Z+nj+%jWu_)}O>(Z}`txslb<5{7Hw`qV4p9b-_z8 z_7#5&_kY1Kh&Yn;7kTQIa*=pM-e`%+@ONwUKX|_U121#(27mPr{8rwKF(V0=6DmWI zlfmYszpB-?{}c{5Z~SKt)Nk+~Zo%**^})m4K06@>uP>R*Tz}e^2&)Rx}#UKE<%c zgyfRs>v?UuMQ2j}UGJyAuhPH%adw@8a*g@&ip_KY#vbRWM}NX;fhM^RXr-2#4CGi0 zlO-SXXge{^+LcX-V?z_+)IVcx))?r!cUjXFs9KlpNVfk^=jr~)mZdT4u!5H=3DDrP zt0c*-z+lx5IwabTGH|+j^oSA(L*GGmBd;b!8*Gi#-&h_JhOy1I*ef?p%5-KCwwr&v z`S9n~R10ib{{YYR(uZ`ojv+06YnoK%BArhAR`7+h+lJMfF^p=jwqs)@0DY9qsJ?_< zM7$bP26{CnBN1Ax=}E8c;Jj9XSwBGU%k_rBf)*zvvQ!% zOzTb=RY@PHo-Jd;Z(sKPy#N-qS8rk6-VRh2tnje7`v$)w3v z*QZ~qJ3>(03)K~D_#Q)?-8|Mbs>bq4rFuX`@TtteJ}=|sq-R64X$Kt>U#CpH@E{mI z2T1KVlUmMbsBTcI)udK=QZ}Dbda>%FSdm(&zL=N^M4SQ?RB32Ke@$D5=A#YFbJanL zn!r93E7N4wsry{S#R4>vcfB#NA6RjOM?j|e@|FENgE+(hBSciEnGHe%q!?CJk@V;O z4-yK^&Em;D@by=ire6(vu{1Ub3^;-h*OF-62K;yxYMovsH+3(`wFxH8Uir%|md!!K zzV)bq{r($vvF_J~Y~nDtXl+jX&`!5EaFv>(a0PJ|kNYO-a%fmD*}0l0{Tr3?Z0G?s zH&}dmn09Uy!~lrDxdyvbEQIeCA&uEl9u%#X;HnM5U4*aG2fn|=0t~U?4T6Tns%uJD zL>0$+lOFMgo>*5jq6kJ8ZKf_qmO!sZQyLE8+IC&5?q%<`kXi01Q$j~ZZ>amX^l`x? zqig@jW$*zH7Ow$(z(Zy-(?%ut@0qi<`IZEQA?Y9sC}1|%?yc;ezO=Rsz{ZHm&bJAt z55&Me7E^5u9#Pf_HusyEYxMkCM24ShWxQ*`avAg0zb?Jp`@PyRltz)z4Lo zsLhNq+!SLe6Bb=h#h_!TcxeY&vI1snF!u0t(s9pw8#Do%Uzln%lor22OKrq5)l#Dx z`j7Lj_7AbO`9Iw!gDymExXtzMzzMkcJbQTHUwbk<9!9 z!>8%bqO;(;RlIcNq-1(07#MymRX!N27bJZn+;DOD8OU$)@hKPn3XbAoE2Y~Je3Qpn zZ=k+-4y`wXf?`adY7JA(jMw4{?lICvv!OELDvftt^p962yE&?HQr8)h_K$GNNMlqB zLP6Q$W~&i)JJLT!444x+fCXBzscPMO3O7_M4|Lc-1c(I3Si00HMURiolZu(G=%__V zo87wbWpm#`wwR#XJbA>_@)N+PDHUa6hfF`xbTmWNkR#Ht@6pd{MHoDfvc^N!oKU!8 zG6^thi!H=?>?y%_6Y6@R;hk@~VHcAbhR~M{)Pt1jD2T)I!8AnP9|Gtm<3b$f`1=cM z4I3$<1U>{%myb)-QV{3kKx}PW0}-#Z1+$`y@eDcKFvwB_u0NZJowniLxPkD zF(ss)Az*jHQEpQ#q|SUdX%JT`+iW>d5bj+H_NDMq z0uRVvl^YezI5Bc@IZ+YIO7_O{VJeqJqnt?Pw!?AV)=H1DigTsW8mdYxkcKzDNmqE2 z{zn==+W2rNo3;mB6_jq6F*At(8}+)GOR7C<4tWG)^A22BZnV0iI#)I#kEy1mrST+t z26+TYTN&^zF)kpT|4EE>RI1l8(;ERJm|&SSyzPxZ`;EX%7C(CXXegWUjbI5(kn%>* zNDU_N1`}vWn?QLXEb*nIbnI$bTmO;eN$CutyrC{sCL#i*3cI3N+v^AH;8PHdr?Jov z22swmILI0l*vYXBj4V$_Ar#D{v0O(XfLofVC(S-;5Za<4BD$DW#Jpf%4j%>T^v#-o zC6yN|riguWI1Ax5sjlE#P*6mmbOYXyVb}(ms0hwYDQsI1=F*-vmYjnl7suCLi$B zF%Gk4aq2Bi!-^5#1|R&QJ9&GsY0bshX`>{ZdY9N~HSDAkeR@kykE*Fr32WNg%STe!C+ znO_YaArks{+yf&^erYDhc5DY*DhhZluZ7-r%X+Ydu0Js7-gY}TH!!9wj~A+W{ZAqZ ztv5s=yShAHFo^YTHYje9N;&%;7cou>^n9Oh_gnN|d~Qz6z5W{AoErLE-LGZ7fY!Xd zyl+SZ-S!3XaDzPkI6vt=4!fMIS{Vl(ZoPH)0OMX zRXg~^F{dOi+vjM^zT?-EXCXfj5&L0s9*?RtV{`5&2+`fTu5FcT&ieFfeaMq4HrM*T z-Z+DnRW`+)H|3~$;M_PbaYe&(EaXBjPrU0;Wgfl0zDrsXyfS4-az?`yTs(LE@{zsn zfRK1V>V;xZbF)pa98Jygd7@ksk}IU)<}M-5#!LliWdi!4Lb;Zdsg*uGB6`~KOTtO) z^u-rgTgIWdyr*!nheTM$_?C^Yy)l@L-j=i2M+sR0ox8r6K7WHTDH(*W48ot5_DUgB zazBg80ytR*5mT;Kyi3bb#uRK4osi)S9G+CWXZHqh88Yc^HHrd+bR5&!aEJ^yKT@x* z_w^RxkFlC)>e*}RS=6F;Aaxc)%Ia5ez-aeehz9QjW2E2-Xc`Hv7$7)OH;M=Be0mbI z??^kvdiq3^lCRlS|6>V)p*jaqldxkcz?5D3r99~}RJK~X*ocxr2Uz&vsR`sV<_)=U zsepy3YBC z>%^>_Hh*Q>F-UrN@JM**Mynz&9DP_FkRf5-T)HfG)I~q=yqWMJqijhEC6#0UIh(M0 zMKdPvk))#ZPP!;0%=qk6a-^L85=XH13q_*!;AU!Qaz>8FXJc85f!KO7J5l4`q^3>3 zmekrV!o?o-vT{smta2s&3F|+$tTUX1k4;)DHKe0#ls7^kr|KNa4Mqj-IvWSwm-}<`^d>$Irn2vxxq}?$0E?J%7M98f!;sks?$$X zWA`RKoN!MmchE({p~}+PEHYyP8B(K2!~po4-h!S>xzALwt*a#DgFuS$@Erd}3p-ll zF9M2^o<-HPec8NXgAZmTrQlyifj>QjCKtw6&`{9*9hkimgi7tq7d&A^)ogS~G*6yL zc{Fu|aB4X`>R`sqV*D#+Sy^-(zi_-}yzMU_w~AmmtdVDPxn33ueWu_<%2 z!ScAMy_yz$$e0W*XOw5xEeA z0Lmge3}Lj-*Sxy)qKynqL|DOW9-Lp(8xJ{q&m<^_f^4zX1!0G7$vYB*sbI)1d?D9zt)Jm}h=sR)>;OW)f{r)RY{_2UV)fu~J?pn9QU zFCw+D7nvVy@`Xc#aKTXvE@7th-JXz~>wBow3za$y6sDb@PXdHGqb_k4=fr0d0ffU;fE>_|^>Z7;hl^Lk|(*u3Jl|w`H5bIS8+jsWNqJB7JhdZA7i4yS4 z$><1m07_Nh&_qCd{exDNH4R7~Ytv_=*PEV;tvA@St;;+J=_bY4UV?<*{cQE8U8Dp1 zCQ39W{V%i#>nYqS47%{+B91UuA${f>l3s;V17AVKhrd^|4MIZ-bI4Ek_kYK7P6a!> zuAb*#9*%c;zI=UrO!bXacpq{1&9%lP9|keLjJh;_3Q(AG5+^Z>~)6vs;U=f@>urJM&Z@*JLDCMJ!yz8~EZ zB9`UW7qV$kSGG#Yo=r*eZvr&awTBR#AxV6)qX*#1e0W@*W*8M?zkl;SUI)MjUGgz4RJlj&s_OipG$Vk9VEq5OSP^rbCnI%pmH=?9z04rzq z(L3y@pJ$^Ox>sj{P!c5!=y~lt`$XLW1sI(Z0 z24%U>{md`vXinW~;J@Gt4`6rWHpG)qFXdMm#M2BQlM@+!QPq?q$8o)w!3C^y%_>iY zhbLD%!v-q*nJ8W1e>)N}{RqIS=-%!XfGjQ; z24b_D+?%Nv4-?x@q(&jxBBtUtV@E|rilma#>lC`Pi49BWprYuge}Mt5FuFPP;MJ|( z4#0TsFzC#Mv-Rbzd~U#>TD$pjjojE)8$M=M41rH2W4~GLuVdRE{0mkSCTt8R$7is=435P|Fx9Z=+wEhp3ADnwrO z^?VV#yIB;ReO`>8Iv$t9@;D}-Kn#HigcUay4YXGQyoR9*@fOBk3vd|V3`kg^bju^8 zKBxI=H{vkOT4#`(P%>$NBS?oDv_S0!>$lQbcz_bswbA+b*K*JefOmjt;bMrDI$;gT zf|>;GRmfIQ7!o&PEh0Y?h|b_+M3gLRQ?Z?ysqKVep&0}y$$mffuH}>VCWU-0fhgCO z<7&5QvPL)K{ZuLfC(jFa(H#qXycKfiu0;D*y$~ zG!i#TT1>u0e6o$-a#CbY=NvZ+eJ4b7ZIsu|EGz1UxMdSDoqYR#qA@znS`y627%Y28 z>BUp0Hu4~QVzQ^Xr&)!x@%nccIQCK}yTMcI)=>XAKO*||Z8HZ_tE5vy{@rh}!^0LY z@kqDNiYMuQ@kG@d4T${QI=$TQK5Z7`o^#^(7Sapa%HU;mM%YER{E^5=VE-NWWtfx@ zRGDzGD$1IjDLPt1yVHN_LBf6T6I8)}2In$p2qVm77qqn}zn$hFYrp*EO9t9ts0&9nh#-ppRGPUY9Xd<3$ zi_(YXJBFzjUZeS#>Q9uofwqbOQXC-VMzW1^0(7HKAN!PGO!)rJ=n|TXShv)RajOdjwdSKUg>OsMImNcaYG{?QtF!^N=>E4qD!LWe;k@B+TXTHN*k zhNbQ;mTqt?#DM9nZj>g#hFOpNa$?mXO2%AE9l${C%g;&%KpDubql^L22stHh3QAji>=qIkaFBXrLAj!3VA~k!FiIV_mpE5h6O&-cof9p1xQh6 z0EPJ_7w$k(V!P4#k1X$_$F`CqIK!#grpRKc8eLRUXlfE+VE?rVyWl6S(#j#;$QCQuv;Q&^k|~=+(ugN=%O&x z#f!;sJ&xEAKOJ$hh7=lyzG1nLZWITV^>`aZ{7sWw7jB8H*z5j<%jSW!*S+-Ho*lH8 z6%b`1U@yB1pg`A_AM{xFuP7CfFds(=fiO{Q7pa)aFtIl0_VfBMZmnXKCW9jKUy^G5nrnQUvPjwhfIHN4I=9a^OriHZ8T7$NSxYrns5RW?TuX8VbrbWSSR9 ztx6i>j)89POjv@fA^Rlgq!=>M0QVQTr zuw&PA{hP?Su&%H-ip4{ER16{#6UYU=IrV4_r?qtzs}mp=TfB#7&KPHKTCBPHhL@(dhP_Jba+vipr}!C1KtQ>iE}>`LQNtycBQ`nTN#tf zMMOW5<|ii((C=xp?qemn0W z2?oLlEDUUbg7F}kx1=Q?-#k*LvoxZpgESaB>UAa8VjhKim%BRt|24g{ZcvKGXR`CPk& zK@ciCs9*~@=v~1U<|?&9fi0YV54#`?^|io?<^U1AouZ$e0W25aI09CBK-}=IdY8K$<3?oAarqh^R zZv)X@etBGq!D^Na4ezz_wv9jr2rSA`CdD5Bl$p>p_kit2gn_N`3O$9f! zJsbpn_))_9eJ`p$EHF8XbjIj8XIHXD~N9^-U4k`itxpkQorg0V&?eeClqesPYh*J5Jf|6Of z=qtKehcy&pDwf<*$F?lU*PkJz3r;iQtV^0=#lPl!s1isfA}?#aR)h#H#Qen=8edJN zYNIjKGp=e2HVrcnWE+trlD~HxC~Z&L7ST>u2$}G{bxOq1wc+J2d200}JDFwpiI~32 zP(1Sz9}HD==U37CtRq3pW$$W}8&%t&!h}^Z80-WY@H58}0YQkT2f3-~^rt{N5hKMl z`FJ)d?0sFr6N*RBLB#2s=zGBjJOz*z0EfzapH!S8ir%|THWdsKZfYrHiXU{!u;Cm(2A(uIM$W`E zLb-!gg)xI~m%IFUprt02w?b2}^>MA@fUJ!FEgN45lhvoX|Mpcj=JuQH=r`G;=LhyF z=?CYpvZuG-WQ*t#4pZnzwUjW*8^hOynpZZ7RIA+UOR2~fY^}j5b{xlj zHNwcZwnr)FyVltql~#-dnN&2Kq_`+AIwzn*3;bGdG@sfZLqT`<@kO~JcTf@;tJL3O zDFUhpE}^vkyS$3YOi_BWaL4;2eSU|ZXBu(ei%QTKMLHPf$Q%+r{yU$vWwGMQIUl6o z@=0~|noo5}hLu_X0?xc4mpcq*dHK|+@Z)lBxi(>tI|(_%%q4tw!pn1w?(NOy$rZtxHpdc{m8@A0L!d<>UHD-;+s8Oeb3+ei;ke0<@pfNk)?--+|`4wpM zMENplyMQJtMc(RvmUB>K+Ub<9on+%z;1U-Eod>?DNWoAkS%=mfl4Hz$)7T}5Yy5qk zSJNT}2T7%BKQsZEP=BhWkzmQ!^R7ZBjv;v?d(w4iCjwz(8;IdHq!UZEZz+f}8|S~EW%7+c(PWUS%99h^k&Z?}(gbJokL z?V_-Cpo2EDL^!R7OMgR!K0+clVS*a3zRpR${MjKVY^zf>!jqm`RGIE157L9W%sFAr zaGC&>A^OHPbU>QVRwneTP!ZI#PP7V(T)|D~Zd0Or_*vw*?{C<01-=KBRK@P4tsJtZ zZSzPM%|5h4S{@;%L;M1gqA*i-weC zK?Dv!-2R2tC>iH6n{HtW?35>f{?qt?=j(p+?I!p%iray6H3=c(QzEU}FME}ujkT`7 zx#K*(GD5UC?io8Z+f2laSmIwwvs%6*K(f~W|8QK?yRWTGLbGCE^(&{7DYu^gP)jEh zg}MBpCasau*X>RpGb%?5;M(!y+U*t%b_OMV2Ebwk(J6m(SfqJZJMnRvQzT84{xe_( zx~|_H4jL<{LZu4`b!O>jZL}sb``x{p<;pMf8SCEzfL%ncAG%JJChWB+*hGR5-%}+! zoAO3MBXEjzTR&YiBn2bxzji8%NE&z~zNZPB;ehB_dSf9ArwOA@BLh*u&8yW5@Fl@Y zk3q9uo0I!V0Wd$Jh*Z3mw0S^U7=lrm9C{fDUfMJO9!F8CoVDm}!eBvbhvf1QDUo|C zrLbxu)4;0~B4Z9fvu4Pl8!ti|B9{44Wsq$gZZ%-Hl#9Sf|Afxdlh&dMs}mxJ5QmJL zCP1)f7m_9SUJNqf!|E58LzguT0B=PpdMxqRF@^%y^g1Im$PAc#c4S0@F9&R7G%y1Z zda>yO#aTt7iY*ZatHD1hLr8OoF!Vrgrm&QfS!R%_O1*J#zj2Hp*f;nU9<|d@{YodJ zF$&NGgTEHqYf7*atPDzbSTL#PpnGuf--9Q;lztKnBJO`v(14#|{x758Z`+<_DALGu zz#|~B5gehf7Q~*gU(nxt9H6MEY*Q{eCj6!43=fgVHNtGf5 zRM993i^`)%f;IdpTA!dv6&RRoA`^BVr%|(kUe%-JO!s(lL~D4&5yh0s}~QNiz&c3@M;e(w##nNSD&h zy9clPzOVQBKlk-~ct5?r-}AxE%-(CA>o|||IM21#>~YT=3sqG*)#@$yFhD@S+LSg4 zoksHo)sMdNMXbL9t&~wYm!OK*@gbG!zw<+Z3q)a4=AJj{R8ATV&f>&M zPm1IiX`duBB&q;$7)QpT_xOP%*T#ZQN`9h6x+Z|9dt;eXFB#SKG+OJe)-+zw%y4#5RwC>6Bkggyoc z^kke>S65xEcIvYq-S!X8f4n5Ye)v!=drt9uPC94>Ztgah<0NxYehEK-JqRBV% zXlhy4u4^&DYfd+)rWLNPEyGvsvFTZbEOFJisM8mO@{BX~m6i$)#g0RTt)fPgYvA_n z9f|Ev{+G37DC+T=Pt>c`>DG(I{DX#CWF7{1AN|->=7QqjeLIm+2&gQg&7)YtJ9_A~ z_&)x320o*Wbru(0JIUD7-Jz!)2E{*p^v-;F>H2UP>8MfUu>=D|)NTVn$;XkZ;0>#?Ay)R<@iVhL8Gw}`j-=mmHZJg)}b)&{1 zuxaZ;F5b7?55ESDKX#tlXfzr=(z3BqHexEYd3awvsa$D^KT4AoQJGeTuxWBF-H1s^ z5@tvu(}24?7PZRT+{Nb~r zP3|8`O-9dpf(1=AAu1QQ z5qH176DQ4{+Sp_=EEWHLbnSicTuQC%+SF^;B}qW+(lQRJ-Q8WCr4p{SVgMtj1k6K| zR^Cp2AFA-vBO*4iA%XP|R>XFX^{o}}xl{uz+0)g<{#LK^|9o*(3}T$6(HAzRD(9?y z>=2#D5szO)#5P3?S{nWC9i6uc!>iRah+wGX{27cj1fGwY#+qQaBs%Hc#&);aFeXqu zqg=j&@-Cy@kq||9p1jZFZd_H_;}Ou`Rf)F`T=F(1jpbIPj>9Vt0b94M_( zo+x&EG3pC__rHtceCh$Po3>Ru2p3lPrh6MFzZRoM81B5>$Hx*EYch}rT*Nz;8Ot$t(Bz*oRxP}IN>yWlx0>e$;;!Bx}2y-;gm_gikBBRhnp7BR=H$BR1FQHFcxA=9a9Gf$(z!TeZ~b*oeJA7A`!#L|29i`1`YN zWkznyQQdPk8B0>sa7s)y*wYU@VeAIO?v~m4(WPnV;nr3~QFpi!dd*;bc9yFi`_oII zS#RxxL^xk??blN^N7lEV|3b9w24ddqh<#3^?DN=vpnWuO54}^oZ^%)Cp;MnFafiZ@ z{kn<;J+$p!9=>ChYMrlB<7u}IE&erOi2A2a$(h|ZV@o*+?^RFrpD6q$#9aB9H9-vh z(5T+xj%r2*qUL-}sNkLdaH_=kd-n~;&BVa`)%ij9tG282lV(rx06xV9K0r9e)qUYAE@;i=C+*9IH2U@GMD^*PbY?Z4f3Dr+**V$NW{@3$O^%Fw%hKiwO02HgxvhhZkWxcXg zKGReSY_f3&#H5KFk6E*D5X{>QCMDHs+y%o1!Bgs1TBE~5Q(|t~ottwWtONzpcPZ2> z9PHd3nv)-?1K4XMwKnG_s{u@ENl*kR3sF%hsrCQ)ybsdOU|B(4PNn~PdE^ulp&Y=@ z5R!q(gM<(so-!Bz`0uwcw0d6Q9_!^XxjSr~$x9-!i^>1`GXj4m_C zLEM^_)Y?x7@z*X<$U^u8#J>-d)v6c*w;=t^V>*-nDz;V9`!G5BdFIVslXdy8HRIHD z*jMCI5(;UE7<+X;hm7#BM8tvzn(Ss-{M@mgKl}K57gq$%!;*yf~EI_jVAwg2?qV!B`m>-|6Iy6D*f9f74}4VJ;f}CjIe-gY(J|k zhYKyF0;uSAzz- zSJkB2dhj29u6hBx01FPn3*Xh??jS%Yf4Tum*?IS>s80D6?yMNI9AMQshD~1H7g0AP zR0t84D!YDRS9*Y*7#1)qhF>t=2=4Pm@bDBE%zKa*GC>s<5ETE{2PnW+wqTf zj{QTYsOk2A#u7m6TiNl13VyZ#!bduGlEfOGh)gFcAPW|W%*fUE7jDPf0WVHrli#X6 zI8mtHpWR!$0GUSj7~LH%j0*k#t<2+=kEgdF-4z5YjxB(T7|n|EQsUs-%sp=LJNS(i??V?aX9q_eZJz6=KP zMW+_JnkPFL4@btEaVFA(K)z=PtntZSu2H?3V23F_J_k|cHS^x3(EMdGq!A3X%%l?z z8>}-NsYoyT`8S*Rs9zc}tn06aPdM+4-Bzs=N^d=#G{y3e^j(JvVocT;iaxh+$ z@>CJh_`y&{or@0W=P?iuza4Lg_9x5C!JD=Uh4}@(d)-~^413^8z3MukrB;taMveK< zgX?N0cfIQ58guXUHDaN_e!!?k65x}dqQ_%oJb^~6$U^Zd2xhILruA?8O)N7t=Hu{uB=2jdm@xglPusn!J7X+4utB8z4^+nRLDg z0Am@TT41y(7CmTRyr^PUOMH!aclp>7V1m`EXMcEz^EQe8B6Z$FrrFkq&Z-AA82?lX zsBpf2=tq`$0JtVl`~?*!EA*rT)x7hNAVZ$KyQGgZXknBXsH1J$g-M^0+>#( z``4ush55ha08oNze@jUY5COer%N~$n^0pq+Whyrv@Mac}h8CUpUx;ij|AT0!amN$c za`W`=N?wlH`sqFYN^6}S%5^;^Ir+rxRDy!U#+{RFT;FWfRbYZaEF3o@K@*h4Gt6)T zvz5K$MT@D81W+b?`yZ+I&K>)9js_>X(f>g9RIA=2P{dFlT{s5bedk7Bp6ofH?{Un& zk05GaL#^xdqOmi6Tyy5nxlMLq>Xid$4-0I*Fg=~B2VRI@m?pIa5u{4oQ0??G1>O;% zt6|KjO1Qac9q@lMa%BIe4GrRXFTXi0cx1%>%}6KkuhITZ6{7_P1WN{^zx~So&TPa1 zm8ixGVP^`E)g$ZYgLjvd?(B4U6K62yW(i=6J-c_%z@;DLu_Qv;k3X!E+3l2u3Uv9# zeA|Ux=Fw`NY8?vD0VUzKgD}^4gbUViNYh;%iBDpUj(q9OX9iDRlV>~}b!d2NE zMD`FMV@x$jM~=Yt8aeV$7;*q~E+p23XI%F_;)y3b#J!i(^LrW<`8tggc?yr|_RoQl zL=lR|lGVbGaD1h~cH|J1MYlLH7H)xX@!s0xK-%ole~;R$D|R5shCKJ_^410RbW)vo{dLDeI%K5r79Y5l2U+1}cQG-316bh+MH0cz zV1l&L_u^kx+)4hjqJeaHZQ#kRl@-)mD~>_`va*Nv8foP*f*WXM^)U-+OX?@kRvG}x z?H%2UYQd62Vq=Lke#(LDT;z!)hMO?zUnbt>Z!-flQY#~!dMu5Mq1EYoz>pkCpH&#} z0Et`xZN3w7d=lYXYTgkc4Rw{i3sxafEQS;gea5+X^bzj@f`a7q0)pT`{^_4aB4;$) zI3SQf`ZBt<<#kKx1V7T&Svm=FK)*r^^%u8RG=LUR1zk)4=~VEo)64?5?cIsw?pUy7 zaV7s5ZHyc_=HHJ%PhgnDD!26ia_rR=`eVTL*393J{~FpRrVudmKaYP50|o}F-2Rv2 zzcC5kBKx052+|~AfT#O^IpXx{hHw$)L1e6BWEjkF(#?=3R&UP%0Sg`T-rfUt*JsAJ&rZBO zNUI$ftl3j~zwu~JE^VAMwH;WTLa?TFP2j1Jzhr*u9=o*WGnuT*?q zjXi+#!gcCtSC6S&X+_PNs3*z^+ICMYO|-gp1oQ$)FLpCTInDt4CRNhk0W(Wfkn zZ}AfBscFimQFatWHFq5Ly3&F|pBC4h6_+ixBv4H!HRLAY+AMhm>_uPE$G*((p~%#! zW3=Xa$M{BeR)KdbxV4ofABRrtT@mgqpXxB4*SWyerH#u+hb?}TH&l7Q@6Cq{uR^>V z?>xKwTsQnZXIAJLYCse30qm~Yk+Li|MK^Z;!--*TYR?l6dqZY)S7y)q=}ut+!!)^p zZECQ#VaTTkRw0PpSvk-cjcH-+qhbn$h`6(ZrYeK0XoQCeAE~;LdCC6{~E;)Yu@xTOIN7vJUZLzd0 zH}GuCuWL+?oHeY6L7{s_gC{b9g{j*@o4${leQcjHONA+ve@T8m>-Tq5>GEi&kA=tc&|p;=%L+s@NpM8P5ea{1$NIL7bQ1N1;L-KLIhz>7 zzmuo~&)5eZV|**m+AO=+dD-})HujGZ2Agm1@6;wa{Id-!Ni% z6l`FD@t!W4*4Kw)`leN$3%jS`lcRLD#zhZTTHJ{r4OW!nujZk)g?azRfUA|GH{assy&R*90U#({3+$^8(9%MA17*oJhZoFIcMXz_2jgRGx zPe*KP^s*9#bNW`qDRKf%jwoZ>F3y!%_iG7fDq1UaDmIf016Q_2H^&c~3O8DR4I@fd zRN(fC-WiJ}ahn(~_uk)}sG$sOy86+1QqOJ_ zz{}?WCz&<4T4}pZ5x?^Dyg9y_??GT+1VHK?7X7>eZ;n$C*lmGlrxz&+iwl=*l|18z zXS;pX>1ToZJ_ozIN6$ynIzz*JTK!H}QanBTB0G}8(gWi1({JkiV-{O=G(-%nE7z9y z_7<+Log1~6le*Lf<~JUMp1Yi=I8<2OoR8J)RpuB{Hg$f}Hn7jFcO0y5Yn?INb-0M4 zTx^{h@NZ`Ly@j|Ky}|ac8ZsVfX`M54z2_L#hduFb&c~Jc=v<1oW;(@{>`JEi&FLvN zl#+<-goKfQryyZWeRFqyt(nC~{UTVaPFG)Dsa%EQeQ!qq?H$n@aplE}oW+I8vbK+q zz@xDmN|jEJJ;`)mzEp$*M&fX`Oo!>veT@_d>8~W+7x5p&y!$hIB{jpC;d3VQL7$pV zSRQmYxtuazP}3OcyQ9~^wd5EHS>c&*(r>!b?)8}po8!4~RoI<5xBB-SX5u0xN}?R( zX}h#x6JwHLQA1r$&NbNqDkA(k4#_&w9iPAvsTW@_-sy#IygE5~(IL|HZ3S4~<8K*1 z&98bG$*!p?LKr7eh2B$Hzi5y%@$M5djvyqhUcj=VzM9kZLlKAN;2}L8_w!BpuKtMh zuc?CK-6EEQQ+S>IJ!)~O-fB|#-1QEe&rxO^JC*uBIaV-QW*_@-S&Eg#`Sts0a;K#> zI@`q;zQHQJMqM0oVzSImHal|_g|q8odjrk6BhymuQghajqDH1^ah@jJRWc^$_N1{i zDmJwQx0_jxNfLA0MJe@{gT4A6%PN~%zLqevtbD~_Nzpr+npQFHVqCeL+IXRe6=)%D zZo2B{-jgb5Y(mUkQNdOS zX$PsgC44BU`+?8P8iGGTND^sFrlQ7SE2;Kcf^qW*UCoU_kx@a%)?1RFQ)Ws&GWqI# zo^@*zt;_*I7`}xfs}-iY8=k6W7HKVE8Sje`%%b&a?AQ+)*pFq3g_A#6>SD>fY-M4z zt(aq}d>EMxSFL6LRJ^WzrREyQE~94Q$4iP4>9OgUHf5IfjH3yMc)p0E3@jk4j6p36 zm${!m8)k+NNq>#6s|xY)mn44Ls}31W0#S^BAtTDT`2b5C>6L5|BYvUOvNP&^dT)v6 z?-Oek--m_TV!n2Z;uJb=Z(kq3`*vg_rn7`3`Rzy?yCNhVNfB!P)!5)+AEW;dQCZJN z`4_&75T<45h_0z-%bAmCvLI@{{+kiQM@RtUwNFen_04Z_eJMegeRHp~Wa@dyNFGZk zgJJ0k&eNO2S2tL7%BHp3;g4kxCg?cRD>*tC^lb(0p5!;9jL zgD(rm>@KmP?kK7I_F5C+1PNBdgP>wWs#U&vm@lOlsn(?4_soazWqvcQY+t~)*F46C zxcO&~q#)Hu0de{ezWystK_lFdkt#|G*9nR?7&BINQ|GJ>9|3oo)Hc)YbAV@ zbCzhqOta|f2N6Y^l zY&yP$_jO%0*)*|YeE(f`H?gSV|CX4wJF*j{5_Wl@yTqd1#7{4Nn7D1e`LgcTZ94wA z@5}nP6gt^~q>L4UHzT{Xq4`o9qH+_y8n22o7~`3?pth`PW!ZT~Q<5(~9vXZ+r0G-# zx9b5|^Z+a@6MUJ4ug60QKL=L>SWGumldF+fGL1S|L|;`SgQN%qNe>8;IU_Pi?+c0U zDE@_orR6gVfTaq+VzS}ZT@7F{vANfeTXZ}c-9YO+TlAf5!YiLc=}P{}roJuhYiV_B z*(7f9rrxGIs~eR{rST=h5o!vx@>9IW8kGUP>fKb5rDnnMkq;ifh{U9NDG@FL*^QEn zl*OnO$xR{uAf?sFpWVy$j(Ap6A2m<;NGP1+SLt8H}OV+p)QBY=BitM87Fg=N3E3)pNo#4FDvKWT)UdbmpGzauC!gj&D#`2 zf)bEiLAcM`gynUGNsiY&Q5)B#<*>D9csWwSDHnI|St;Uqkoxtx^$%3zk`+DHD7nRa zN+v~xirxUZVV;XRs|`J@VoU;AkwQgS5oT0{%Cm_iAps{*x2T{ppQ6MW(_zUW!5rhe zlV{0vc8yb00uBQbo11y?Rp9>%PZ%_nz96+>9+^$7$;Fe$aGMO?aKM5I@k;QfSWonz z+vc^8Fc~*)nF`torgnvWn5cV_H=#>A44?x6=so#4i2U@K_$95swP2;F;(v+GA zy%2Y%w-I6jWlLv4>x4Lph@97+0HdV(oenvn#~XOr7h_^@n@ zsRYRj=z-P%9SDwFMkquM+n@NvmMoc+U=DBr#=rqZ%b>yliU^`f^9l4gYMcB~tylK4 zeG+0uNagavdgHB?{Wy&KJ;3!wC{jjZF&R zKfBSX9gKJkr{l5F1|dXf11zx{v~D--AMZTmvF5V zDZ69;@oM8|wWEcE9W;_3X0arg)#M1wg0uyj%eaYQx^%ob#uw#q8?S}Ccc6)7hd9`1 zx!PrRxQdvC#Sc(HY`pUWd0H4nWsTBXvm!VG3fx*Tp?=|&QM?-2m=;hlwJEep?&HL? zYTXAlvpO1#F70~YBmGOd38%b{#>YGwQWo-c^gJ5iiIwSee|h-!)H|44=|t_1a9EtJ z0ws9^MU%{-bPz-F&)gNfJLOsFzUv_{k|WJ~@elQ30SbxnCUyzIWwC^7KM^1)07{h> zw4|)j6zWaul=!}k9OF#Imw;!%`qTRlFCYwm^9FH`Jjv?e@_Hn&;m?BPCmhE0{!HYtBrlIUwpbogSyDMTK4m zQcGf>o0+ABZYDRCsbD~X(A3%5Xz`}lPbl1g)*niI-q@+xvzXk<{M=i!{1v61E^>z2 ztZJ<7A^aQGGNImh`~CN1x@uKH{A35h99QAbif%4!XRwAMpRyJS%%I~;4)@W9B}kUn zG2t;}TRxwE6}jB6tvdEDj=ZN@=tCdV$>)4D!Lc&#Q#I5{%YpfivAFMqps54;gspWJ zM|w%1B{ft{Ygh(8NNQt4EjZa)+0#{Sk`!iJ@zwBZB)heZ4v}+O(m!l;RiK=T@sYb& zpm=P5TOfWuS(4UQn}pWagS^L_{$YFsfehDX4iV-_;&jTIyiR^6em8&K3MokW16%2u zEtD(bXPtr+?MrhwUK~p>BD#-O^dv5D= zThe5~K8Rh*C@b0f7L`z?EnA#@Yd+uc_lLBV1B@}9Mxrz#!ZGIcg-?32weI(1KYhuS zh8}EgDia4e4+nlqXo$N(Hi|LEG52wXwqV515RvkhUfTHZ8Tk`#X_s1paUN6Jmp)Z7 z54(CrgUpdE5%=iw@Oie=q0(a)#ywUw>n z_6Q|Nu)3ke^Pl5an(gQYR{t}WnlG|ZjUufUc|;hifn#>oyk`-?Azk*f0vk*Tat>Qo z?|xb{m)L~Jv1yd27B0+9gkx63I^c*XvK>hP50-1lVND(UB(Xmyb-@CJ-}}J_8U^Vd zZAW?qd0PIBfl0-dnOQ#-fm5Z5^YxU;jEP>lcz3=KKwz|v1B`?Ik|QnsA9!CT)DcO*Z76B@fkq--vqKS zjf~wQ3WM^2wZ$xU&I)&r(Ah2=xrH>1%nQjBtM0h%I((X$nqI0I03AKI#CxT3hIqA` zC-EmM-pRApoc9!Qjei3oq7gi!tE@xP1m*cx;KCP=Oev2+NRFt}{1H)pb5VZtQT_|e z`HoN|j&nXW1)4_r#X6%+#3X2uZ+?JUZwpb@cz%#=vOltTF2vm}aMHp)6vI6OW;Cz1 zN;0Xo>P}O#4CYAFRin?prl#NPJ4mb_F^$a6I;Ec;wvF%U*$akirJ1|v7g8tW!*Yvo zxCPG@rqdrT_liEDH#0G)`tpkHSMk?XhiQ(q_3KEzC6nqa16_*@uhhrl#B~n1T|iNc zO|mnYbK~zeXN5plBYT9jR9M}mGyNQ5oOhQ^vY%R215d{`A7W}Z2Y{vZqnU73eNd9U zl2TeoSu1q~(uzag@3p-(Z_m%4FS};Tl(-sUqwjl0kQtvw?(br+jPJfe@tR9}oPey~ zyu2i%*(6N~-@TLNi#fCeI*zLp7TM&U@WFvWlv9s+6R1V>b~1*%DN1~DVhXA!?KkH{ zY5JZ|F*ZfWAg1;AB29*9BtKfc{jDgAIjqP+<)M}%@^iOOaxM&mju_|RCQuVol^<@- zmMK!z!6YN6tbx*OQY#xQtxY#>Cys%F8^%40>{5*-o9D#|dE+j) z?$M%A=bP7FSGy<8RjpTa8Z)|K6O*spO2NQhq<&XJT+GWUHa+U*a^?6S{37peea@~} zjtFVfh%u94(~i{#l?egQ#p}f|@3WxaI|Z3p2udTro6X~ugSE=+ ztHVHr1LLgg<+FnX6TMemjTgrud`&s6lXYQ?SAN}HHPf`wzBDxpV>zU! z@6~4cl38J=)X3NESeu{Nt^_S)cMBw(kyF4=w!IELwuHUEQ|Ld|cVJd6u1O(enX62^ zyPZa}xf-DJwk=1rvH&0F`K9V|lf0D(@H_w&74noa3|LBN!Ze@>O7F^8gN;eT36UR~T5MkrS z1$#>X4Fb%i%Zi6$<(&0tX=H@EqqwiCYU1gqb8#5mNNH(yKD~3J6*{G!xOk$Mdq`-8iH>Latfr*(i>sKa~TGdZh|GO_sRJmTW=O#p_8EY1HQY*`t~jNGgQ^1-(q(vy+I4G zyk{4zD@_x?bsL2V&cy7?8kGso`GGU5tg`%cjGIp*=t*{Y?N>FI3SWg(#?-K)tMaaA z>YkignZ^AY>Iyrz;<4S%iMw|&&kPpV2Gjg`HV>g?!sv zi(bp=KI^z{Bo@5(&gAVDr}R6d=oQcSEpYAaS`wHY4!*3>DPGH2%UV9Sn)i1vp}8?Q znb>C+T8j6Y3K&bQw_p$j{HV8R$~YJja#Z9^xz@AdFAv2!8QRw%+Y+!+{8IIg-Ymxd z@rJVR)*F|qKi)X@{Kp#!`CD%S3yJUEKn^PL$+mNxuanL$K{se8Gyk7J+w z9?~BYk3EREa^-ZnJP@#p2^2eB7flT0TXw!YI99z8!A6`~RjLe$4+(c44K-bCs)ktz^gxo+eng`G7K3eAc4?ZNGr(8Pc*wE)pT zNdC-;mia19Mz)zVQc@KtOV}^o?2me#7Wn>KhTD2hAC2r#eGTR1#!0&id{s$&c_r3y zF_8C=b!}JCUGQdZxb2(xSfSAe^M#A!J5G&L^>43gfIW%nqBwL$i*HzbYS634Yt@1H zW{wYVFZSbdiODqy1@%&nXG~zl1=+=#sri*_)?cyuCXPVH$}>06=<%(8-Qw&XF>5)> zClg{=S2Y9cnl0&TIT>6+;AE04KB4?EH~zI8ciCcFwyT;!Ul7LA-JBKvKt5-_;$Sl~ zsjC_=_5M&7&5xXD%%dUe@oDjA7^^w+Vs~!(#cfxVg^q_Lii+~83#63IZET@zYdJNP zaHb31{UNu~dkS)!z&_&l5G}U`=lyFED@!K6Y4PQLrGqp0b)$_}b|8g`XG37v%Xg=1 z-2XjLGkMqE6m`FcjIy!=vpr+Ba@&R>c;7FiK!S-K{$TI)i5en$7Bg#5}BYJ}sn~#r&1eB-z z0$_m-q}gjZFQ)<4e&EntpUoW%E&G|?7(mExL ze)yOf_5F-benuPeCa{YU5s3-7Vu3)qLeGfU{v~pg*~8S6?b!ZI`tl(3zt)1YrT>yY z1*o5Z{5cp>_P*gWt0>zk81Bfp0pP_~5c4_S)D1h$I&y<`tMBTKfBW?mql4YgyL&cUUt2G+NM)S2RQ ztE{^&w?*!OIkL#D1(k=!eEaq+;e~^`Je9DSv}i3Wn~@OdXe+Cq$4yrpul%XCope_1 z7z}%FZ!sBsdA+=6oIJB0h7nMYHY#(!d2zAj;ws;fr(HE5G=NlKAo;V7Qf7<*nR!}B z0d%nNt$iu`8dTpF5}-z1Y8#&%@l7|ks?IRA0MM`&%Z&nXS^ zp7Ga5<1r^j%gW+?39RDwgDJK9EfqiKUCECHl)6n~4TaYqizW8)N$smAlc&p6Zb!9@ z)e0(pQV=Z`b)=fI*}7AbMIp3fG5Cr9c@724VKe3+(?f%_Wgr#1PzanQ>)4dxIx7@y z#G9g`UpxX0jd7agG8?2%c{xPvTnt7$woWdCt4d@ zW~NtpNt0*9XJ**Ojl1WWa{c@*N)p4a`L(=3N>eN6g1Xsy?M6Jbv|UA5p{)27jsf00 zjms=;sgaExr)}I<^W8A_S=SFG)D4J37K_d)q$V6&34f)*GA)b z&RVZ`*gV7AtetnDE`GWyTAdKP$Qb1slQbKz!k6M!UfBAReJ6|}OeKS@5e1`1SQ{&1 z-3sv}D>+E2!#BXnZ5B7;@ci{?v z`HyrBWrl1h1MXAy+E~TMx`$g*>O8j3Sjx-tUl>Ub>mSR{zDG8S+}0h9NL+tUTXAAK6zQ7tc-Q_ ze2c{Nm=z$I@k`xd-zoYb7}&4!CR_+`BX#U}G;V@~uB~?7&)l6rwAlZY#E+pkt4D6~ zX?napr^{Atf?&^T3ooYLQ%VxK(u|Si-%TyaZMB_rzZHEEi3#=$qJrS81p8a{J=a63 zZ;kek8ybKciT?*T!v451({t;F;;X;AaZgw7QKgFY*a_w=sw%CZ4rg}Q?f6!^Wce6OGqj^`GNs&&?Z*#) zGe~yQf3Vt56R_r2!by*zOvG_$GL&v2z7crs{FxWKx3O~TbS{O&1iH(Lh9@@+0 z@@V>n@+sC@NNh5_TLAY{wdY#WXtw*C-WdRV&Fh-S~-w z);nw`48pLo&c=M`=hf=Zn^GzeLq9OLXco8TyBa6_pj2)jVI6sItK>tmx|kk59X{1t z53=`K|9<>94C_*PwqrCx1IJt+IzcBDF5L>Bd{mPsb^P?KI(B*Z4O>gP7`YIHHF|5k z%7~J&fvrjAmx6C8b~u*6*6bW6nb7-kJ9iqQ_5;ZW2~W4YSBS3Fxc!7$@h?`->HMw9^!le z{5+t{*so8+UulnhjLtf9QXJM}DN;Bub*e7Z{SB$VH(?1{bzJq!Pa8~ia+R>2qhE6b zXjn~LXw4LxZuff7GeI990Ty3*92^MzX;(y$fJ9^kMHvALTB(fZzG&s?>| z#m6{hQI0wl+BIZARQ;o(Z->Oq@DipIi1TslkxL06*b3%285sO)`BrbMztOStcGLPO z#*|Ea^hENzEtrU-bbJIw}_`!xWby*fUQ)M zXAVTn9jqni+-gEiGKJrZA+4G&b?9eZADbu#Rfa7hoOXe707VZ zovu0(VA|bq#`9yJSd1Z&q0f&dxmDOKuCw8$TxsN+t$5dR`;S{+BRW?Tz=k?wzeJ`i zxWq+Y#YNm~x{$ORrd$NO|BGYy0h=a(V|9CgW5X$z4~1K{y~VsDQaKBvlV`QJ6d%|i zDL&N6wk%mRtdb-)0o7oNdJWQ0(a1XGzM-UNYw|Y5#gS>R zw-6t)x=tEEKhM%^Z zzkIpXv`b+^GET~FQR^*fuKOWRtdi23P5cSu)3y4?$vU$uxoiTnbzYndURc)5UWA(d4(#*q6me^nXY@VtbN%`gnkHuSfzS?b zZnI7p1ZxM5)DQ}x)^1`(2>2?t8AszhfPtT(!8m(@CW)PgKjh&J)8IV<)$2d3y)?x2 z-2a`2Rb3B((@A7}TNu?f#;x5rflE{1QP#Tk+&h-@NdPCd6ykq_MF1aP)zbPZ?m(E) za+*ve5IiE-wS5Mp%VR0MA1tJq+2n`$Eas-8o4(`J3e&}S3(YIP(MC?J=%6c`E?{CE z?rmG!TY`{X*>K5{*VaWpsqLb@3o`4Fhze7A5v9an4XoIP_xUO3dcwn-%2!QI?7O0? z>d37xvT!WstjpQaXSWeDh2cN)?>7BZ+#Y!F#d59$Gn#o_bauR0PHX!nR9pFD^&1=* zIb2Ro)U!RP4(vr?t*j8TmL!8(+ouljrHAX$$AT`LMQ75KaThiiuR1_yeZ+rkoA>Mm z^Ue9EC|BCU;vRsaSw6{O(uBv>0CTLQLU&lX@^amqLtpgWsO+hT-3PxXH7RFBpOv-@ z={k?k9cabSICgjlYWf)rrgeM)eixKnAj8mwQY*kJS@k8i(*|d?-Tn_-e5{fdaVR_0 ziD=-2BES0a#J$=gKO~gNL>(kehP8iaO4>D*@eWLf{6pX>dv|}D4d0jCud1W9#uM8A zgQQXI4-(W`X$wO#np`b_n8z=epX<)N9yY}}^Gjv529{87CL_NwN1<8gef5|s`1n*| z?}oT;>=6REqgo3x(FZtjpRGg!$v)E4DcbwIW9kq7M=(+*=aYAgIe}Zp`EP5?s|N$D z%qgDoj03usil(;Sh`)I7#oLV|k^$X1qM)w-847FiI3d|%5KCzmcFjH3xN*XoQ`p-_ z6u-MU@~c~L3eBYv1rO#~k8*`!53+VwUqFv?Ck%qL#lN*wgvOxkG@^ma@9#+1K?JP9 zWYpHt^7m`I-n}Kn%nBk*Qyp%am&|?oNMm@P0I&9;bndb`{j=GS`?XcAwAMp46;!H0 zO=R`gq#tQ%9`(#mKe@w-6GUi+0%Ad7-kHTfpVe)i-qQgTY=?L#VW-5E%L@qGdL6CyTS)Na z4k7A}YHDzDWhx4oN{>8+3w<`kvbSwIGD47i=&=|mrr3+=JxAc?u)w`Kb1#>O1VduFVthVE3WT{3D0z5K>SHEGC5x{NC=?NiVmsJIIH-!&#PA4%H8LBf_mZNUZYMYj( zR>_-8>E4@`S+<&%;UjN$7*fqd(4m?6ZFDdWGIUi3mj}d}Un^*bz5m%TDv{OCjxt4e zqubiV->?+MWVSt8s5ACprO|>9bsKj=m-Bus!AINj>F?G=&@Nz>u2PhC_VB{;U=B+T zWT;7T=%B;d$>uHX3LC}qfZGDxwO42Zo7o6M7%9NrmkRvRZI|k*K>!XM20TfHk8zt6 ziqdR-`MCL8nAy}0NrwXqWldC2U_bq#Sz!|`T>@%#@}rs&2PsM<5~6838mNmYfCN*I z^Zsq}3Y^kD6yM%hDCM zZ87y&-5z@smanorr`dvN1sNg~AckfMUn{B}eT?cF`WR&|;4z;qvE60L)%@^DvxQ!} z&Q}F@!R=#TT7n%u&D2f@sU%L1jZyY0;haYoAl=69DrjtC*>rbBx|zk@Dt+N)QS;Ph zlaB~K5$tAdHSHeSj~E0NR?3mpd52=NqGOQ&7_4THn)U#l2mC`hq0s$ib#vF`ghcl) zrq2~%x~_`<5iKeYGn+I+G{}5NUAbmThl9Goq`C=VGp0YJN-@Rgeayp;z&7Qh;-N(+ z@oS>3zDUe2w#k%%=Lpk!8!rkESZjH_{A;4kzQOcE3#kqCW{@%Pk)Mgq7O-#XsF+Nd zknDb~qu?;;f?D&BQQ-liQk9{ap0pW1t*kHrV(K@o&x=J;fw7G%s4d8O$0K64ocQjx zDO|7W%XFu0&6&CWHXr6tdxchp78m-qBz#6MVHVg?o9I9XfJuDY7OuxjG`+)i)Yk|f z=bTG=lv$IxP|mG=#}mxV=^3pY+1$nSosCp{nXUTAoV)M+MzXEJZJO7+_ZMBsuZ@x> z+>d-|j}r6pzOs0dl|dQ-E}T+IYJguNn4?>&F@4++)oImv-<2q82#{$bFp0-DAN$56 zDFrw8sqg=ANI2cLXA~12TdLV`h-n7-X%7&19yK@JA~7wh$-MkWBz?n3B=m09g-zz4 zGVnjZHB(oR8r=mnI!6bp1vI*g%L?MWKi3JWHGSI{1-AwyItNI!+Yl-PHOHL`1=ZHj zv(BpeM0&yr!A%*<6_X#dTssY~HXT^qAA1(oZLk!}0t)>MD6}6?=n|mN20)<=fI>Y1 zh3+z^Zx|WCNm0_|BGCl*KDQ2BfMdoaYuoauE^&@O@;4>(6sn$lG=9{vN*v-0L?M z550sBJ&%g(PoBRrN^&&0a=U1c+H*AibZL9EHr3{TdAzx8db+2;Fxln%>iDGK*Q)uj zFeLuX@5&NocM~K2qj&0`3X9(Du)3QpQF0(YW0R}m9b&=E4*bG29*p~we_Bgc8qY{* zh3Dz_3zF8{=8KmwMWyHADJ^DDOzgHCDDU5%H`xCCb8bC70+>cDcnG zwaeu48H3g0NA#kqlT7GdYir=;JY_8GIdQh2!kukBmFhVXC>3cvtYf61N?vBUi|Jk0 z$f+JrjJ+4n?(t*U!{C4`Fths5I@@PY9H8_1Akn2 zbw(QE+|0$mjfVcwjm^o`vo)DPGa%<(Ay~*9oR4G|#5`yy5b)K|TB>pD`pIVO!|Trx#PXc}JKNc?1)!}Y*K#31TjFklIre>q zABO7M4;t+5^(PqzH>-a3TcCYSq3~*M0(JFP;hzlvg~N;Tlb2rQ2znMm4p@p`8<9bS zn(LBMo4e>c4b2Fgh@x|xiDsO3n?&EvMHBRU;5dECP~}M3jGt3xN(ESPL8iPXkn-a= z5spC0dqxB|65ri5z2{o>Wv=tlDvD=HYFp6&m3exbX+ncFKU3JF|3T%rtGvcScVhaVbJXmA2PUco7v?L)V1o!3=hb(~ zOvr@O84F*Ym-|{Ci*G2f1$VG=y!I6vq6hz<0@BeREY9AQgybU-f8P*wL$V;D(wKFf(+{hdrwKjhq<(ZrB+GfSG|P*(J8S`5f5Q zUU}&ZR8_y3gJu1`uI2G;cd7@L>z=T%#&~%rBHPrV44!_e4gXKR6}eAm1Y$Vq`sYgM5CR(`W!D%A4g6}JmWCeDiGY?=5;&liSD@aQ=76) z&^2b@bJqW@5|un-0;CI6A{fU^!X71{{smU9Xj3I!k(O#d8;&f8Gr{RxHU|0@)8bXaXKu?xR8 zCqm})oN`I3qPzSqy;eUffn_6NxI4AkZR4J2M1Or|YEZLurvc=SXH{h5^y^(yf&;&5 zR!?BBKwnzh1>yIEKk%F`(aJ`j+^_obrj{ZNDjU(GzDfqx| zrO*OAP2}%VSZ6{?VFXHml!6X3QVNxP|CWLe{8kD&!j7X*Or#WAfX_DpDd+%SYH9{m zYAZhdG9Nt-&00IOos4vyvZ4D~0q=2|0?O&v-*~%{WW9!MR_~h4Y|3;nl2wA9<>@dZ zlVThSOwT_Z6qBeu&qkpeZ};|+k#pnv|3lkb#?|#L+k&_UXG0)Za3{E12n0y5;I09J zySoK<2tk4bcemid-QC?c?$B%VKli+MZ}&U>>ks{9?FAH7V~!fLYQmB^1?i2`MUdWD ztP1Ik0IoTRBL53Ulj;8n2B64!-jTg2uK%RS=AYVdZ%(K$zP%K3w;Es}yJ)#1Kq1y-GK*fU9xkATMXfCnobEkd1=DX_2qB$Av_1MwRS{!>*LF4Yn zPIts*c@sytE)kE)HTauLd-yKqnXv8mGx*PE>v;>_cm-q9k{u4Fz383zwc@8?#c!b~ z_`_HAsG$O28NTaJ3uF8ZJ7a~BE!o1ReiUN?Sv)n`cvn1EgIl`aL{#Uf_KZ)QHzJYkKe*bh>{{Jfgs;)}bnI*iOKHR&zf``g0=M{(va4kNPQx zdybd=piYQ2ykHdENX%W<3C08O#LC6Sc01a7GA--mja<9@8vz`w?v`=e^DDKi`a9*9?>XOIHF3w)a%~Y9%AXMkTDph9wp<%No3w0Xvb|*2crq7OLxKZ-~QIf$mUrd zv)pw^Y%88Eu-k?%W!7)i3~eP>Xni>oof$<|+Zru@kQA3xmX3dFBcwlI{u%H1e(&|P z#yXJ24h?gG!sdV)uc>+v-?2jQa%e?=_LEUf&{`*YUdiADx_P30cHrZor@kEn_- z@B1K330uSyzO6ViyR46=Y`(VO%V?En)V9Ndvn`nIYS;qaYI z51$=9CMp#e;{F$P(<;2E+l+8TEYTM{Sm&26>9_MSW;_jBO4=J|?RA)<8-t$-qm24R zS35ga?nMyb_JdwvY8$%}oDK&aOz=2+dIX0tZd-itsxC>1koRr1+r!c$ctls%yYb%j zq4s?5#C*^)BaIAAFT+g-9zu8NF9rbS<-nzvD5H-6(~> z@9hr{=K^aC3YYybf4#H49M7CL?e5=7?%U3X`tl@;c3y5<7pG79OxTfm5wI%j?P1oK z_P)HfweX5fY?`n`V^;)D*!^;1fRxg&NlkQDQy

h1SnA1*yFSPlA-?x>G;8ICld2{rdRVp(#}Oe zhqOHX5oIza1ANesIQv$(~9oXr3SR13jUo6!Bz$yitP$@N1b(GJ8+>m`m-fjvF(V!C%GK* z3>*d;ENoNcp1VqUSz2UGhEJ>YHPR^SE_;^`Sa89F9g${81D^x*vd9@#C@ZN6I~rKf z{gQ*q3A(+XibSwuYGUw~zbj(50~s7pSgw>TpT-2hAOX4i#)4JM832GmYH@SC->6az zZLjdd{GpGO?L-^ss}P{C7sNYA1MTyJNEAD6*p)Ut>^;aNQNDw66cxBi%ORT&pJEPx zX^`#T_zN1f|LF6^6T0xAmnP#b1*un@My(hrIs}q6SfgAV#vo)e%``o##P1=QvfxT7 z8lL#{UtH#Cs}B6gMkP4KSJ=H8G-{~CNSib(!nX$lM9JB}16avqm7O1hm=vffijewy z(ZBHiK=#>cL$OP~9DzO05}>sI2B{j3t1aD(DLCtGSM)eGR%P+yyj6G?0@wn<{UV;r zV8UdTH44;RG{&PfNzlZcGk7rGw`P1bCQunc#S2*=D(7mENY}{y&)vkreH=}hj^O=i z9^}qx@B8&F)gs~6r=yKJ)ug7iRt7B9$d^01S6o~lpDvp)T2mjcww+yb3QE1MKzKvX z2U9R32kp(e$1s9}A7+A*3?_92cZ;hh7oL;#FPCPnA7yBr^!;$)@O|~iet{98HqaSI+&`v$=e+^eS04=`=)-w`v?)jGw!rdTcZC4wH7bOE->9r=+)^1t zR>X(%CbEopH#T`!H#P{|Z|5G|)rqYLX&k9A((+P>N;M~;OS3t4iS}hBveKFzH{%N& z1}CFQFRGgraO1?cQGnp6gt*n^?QnUUGYkYKYou5jHC@J11(BtH8Z9MdKiQDRo2p+s z@V^E=oNJOqLlPZo6Zt*@`2I3|SaS$z%67UcRg(14WVJ90yK| zGK~1{W#v1JmTJbyXe%m@`&qE!!*gup*(AtCP$EW^RB6G^PccSM$NBH~Zi{SN<-NI? z#D~*wnyAwrwrF=3@A*sOep%5xrcL*$y6>G-%eH{{`d2I`e;F92J=7NzYj2*UCSpGg zYivEF)r36|ry}p4WGJtmJUr=pbH`&mXqP9({_vIc0vd>S(r90uYVwtHN-<^?s>7M7 zy{Z9Uqz`hhxjCw&o{p#q->pI96SIuNSy$+TcH-`4*xLJ76YlW9OAi=Y16qk>h__Bw z-yuDuc~d60^6$&LJ$=(6-apCx&_9RcJrnP;YWGV$!+UYXk?*w4fq(DBVcqu|%VV0X zfIKSjo3;HbT_K1Plxj`AE4)lp0NVaresla=ejc33715%$mD|V8Co5XgnI1_z=X=?e0h)y0a$MQxQ6aBB!&2q?F#3wWzNk&^vEQY>Yuq z+eNnpRzYtQ91JBdWN#Xr(wo=RzlU_yCySoyQ|ri z1eX1T;44zy*5?P)DbFuns?XUAEneqCBhR*;*SAAU_p$P87r$n{u*lS4h2%0C@yG=9Ox!F+XPx!0& zPMqHdr!C71*|@c9Nax}Ic9|`+o8F^}6{uECc5-W~p1>(Ux2PqqZm5_r#%Z@GE_I7Hz`T&0T|O3v;-JXsE^ifkXh=cja7;>fBv2 zO=iS8!d~iexmuRjef#?7nMphg5r~`jwz)<&0t)O=MR13`BwF63oXTfvN{Ox6< z&reNEIV|YQV#+_`QrE}mshaK9HC4%08g+#a1-TYqcICA~JnrTlhAxT|$vNq{g!Ssc=cbi2PP^u>!rM~) z4+Eb)pYD48@PeLumIXk&>B2+u*AHR!+%4aLY^ve=?f#2ksVFRQ@pNm0ehJm> zt;2|di9o8lr!$I^=`IvHAqY9=!;!xp&lkI1KLy?_TFc^4rY2M3{-Gwx zGC_TbV!!#~%Xs5;=ydb?(CJ)P+5riDaAmx*?(Yvzf_ZNS9WazUV`#zGB>8u2J^ux@ zEOG@Y*YRZeIQlq;Kl9(*QYp7$$ux>?R_=}VV!<;pcUM{ftqV?-S^qb_et%==@HgtnAILF8J*HjOt? z2cSal8v zvF0F42(eioG>Z)J;6BY|1u|(mocS8R^37n${qBRYQO!bNpe{j{hMw;wDi<0Qm7{p< zcXO%@A4|S{=Zujrjf@*s*!OvgCDuzF`8O&-jomomY=3_|PFqqynoNeD@hgg^+cQVI z=G+yxEJBI#l}@-Hy7wZlvU!JhXM~)8W}@7^l^`0aMv*WMCy_zHJZ|=I2C@A(l>P0G zcy03A==wH5y1on#KPtXlSyED`wJ3fRG!BTEsye};7ES}%k}j=e>KzqF7c!{vMAvN*#vx?246*P6L0e06hehtTUbE8s-Glx(x`((q}TQR8oyfn;z6zltj{H z(rK2L<7vqXl`C~*ut*?#5)=eL&K>y5v2*nku)E*GN%!JLAWb7YjEg7O#l#=31UN7y zsmSUe^HUhdW9njS#L1`O%xO%;v3@ zjb$E^5eHqo$H*ZSy&?^WK)eXnKV^u`<1kU#y^r${{(o=;8BgIG4(O?z7 z0(k8W`)!mEU3xa&-^ZYD@;e-RT}JExo&MsjW|5+p((Z>2b}G0)9ZD2ha@q?vQOt+W zv;0Hy$euY#5hfbQ!XhO}9{ftu1Shij0X}mBb+De8g(V6Xnv#8{{xlMkt@* z%wglB>7U=ysZ;$vXsw2%`!!v5z)kF^^!IPsz0-y9m&Y2&V!e2rt7Iu%M}w9Bl{dvNM$Kc)jF(QBI-lIfyq}s3&FzAHxoVPe2Pm}suGvDpV&z=Er!D7fyamI?309V-^MA> z{#^Qa+gPttMWah;Txx14o_X#W+4XG69R(k{EysShU_~)y$1r^RD0!kQ?Ab73?nNDX zrS@8)`SQeJACFc&<-|KERogfAkq22@|rQ^l(?!n4jzY)CgwXSU!YqvF-D zBrQYCsg3Bq{ME4j$b3iJ=3MXxW6AFC1~0REE`VLLNh~WIK)GK~QaoqBjVhO5jU!I1f+E0Bg5>UXKY( zxD^*QWRKGc&b39@8;~RGw8LQy^b~RDo zwrtBlLtqa0Lk-JC-@%F9wi?XMl`MOJwfwz7c9P$TAwTSjPC-x{{gjPU4&l`XrH6Jw zP>e|DOu{#U7jg#M8%ih0_y_+JB3R-VL|p{a4vZcl(r7~-Z#?!8i#O*>AmqSeD^n9_ zliy^)pkb%C%29idj1&4R$MP*^Q46v3VrCaViY_%@1{FvF!fZCvC52l{ zNq0kE;ec!BCQ*UWeW-HexrS;9y!80o(~(r3#(i!J&LO3UF|YGu(Xor*+iWM%&g9pv zim^CGYjI1o#Pwk*|2guRxUJ6lC%Fe~(X9jv{7R1#LW`j4g;Yb<$S__rDb3n}))<9v zP?`OQD3y`mGS}121}E|V7aST9HpkE&sCDNMLe?Ctwl`K~TGu5?mrz<<`Z)Kan_L|N zSHl*EAi1eep+ac`jyt*N|LE4Y$@RZfl8$v9)O1T&S;fA7+#_|vM{)cyW9=Zk{v|cb zLN=wJ>nl4w0I`lr!t0WXwaoyE$<0gek~GbXh= zQUQ0#l&*yhMr1R<>29vYgV9>rI_VUkfFtj}wJMNG)Qsyvx?pz0+>Ad`Hnd~kGHg{3 zNzGvpBsEn;k&x6Bbb6JR1pQ}1R2wjMNZRVku}b&UZm>ZeUxmt1Z~+g@dPh;rTUkB z25)l!(}pj2!PK$MNT1OPzkmI!d5{e5U+YmF!HVaTljovz>p!k#egrUWqPUbc9F@-x z7sox`k@(J~6z(@=6`soyM;ITPWX({@Ct{{XsJz@;Qd zT%RUjz{Zy;lNYG_06z48lgjW~=+fLdVJIzQ_EU94zk+}St_JhAnm}ku-s>zLm(JVn z%AR|@%Vbg8k(1hdd^_FL6-!~+tl8To37Ek32~-moq9OG1Sr;GX)QurYeGp=Ed^$I2 zXZb8}4m{Sof-a-r+RPMgMyqctP#NA;b6%px%l|hRK2-e^|A5sDQs=s?SZr5XJXP4~ zcqdgYA_IuxKIM~1w*h$CG6aTE#hQ2qJ-ne47V>SlpA%^6Z)R7xe$at-uIh43yfsr! zR;0929|1^}vvVsFFr5ZF-YYlRrcORx z-Q*6L4>q-%W#TXFFkZbw3-iSN3T!9u(`ANc^g>Gx3$q$*+xk2~PZDaYHU(Ok8AS>u zrTU_jdL;o%a}beTL?0Mn#y)jkpmZj_tM?7J1g^JaMHH2uEl>kNh}-qAzJ_)+@LKI9 zZ%l8;bq&9%Bc)M49JHnI)vvJciTH}BW`Xt|zn{b;Y*-qIJu1^@@b4sHsHJv`fO;qf z)U@U|{Wzf*OFiv8+V>YYJIa4t)kyt2J?8Xpagxzm4Jv?#h@G#9;lcfLyj67P_Xgm| z#fJOrvaSN>O{-N!;U(VZ)CY$o_pQWq)fZC!*u9X#@Ip$}KcomdWG>p(9v1v3Qq2D$ zg{vp&Q_Bk}DgTX>v-lTM4qiyPXd!6MaSW$zVL`AqOKTD~sNf$0xA2q?Te5z+?rLzf z+Ed?oVTSL8nPPhiUxU-L4na|YpTv3<6*$_o=Zk&+==c9QLm~fw`9O2qyEFGcgbOee zmOLogWw7}>4t&@`z_Uk*^5BG+>R=y?xT0|JqLkk+O5xv2OpkjZCDq}D6e$QP_lTh< zSMjinT*q0cTRHr<|BsqwjFe2QsK1zmH-}QwO4+9*9WWSHo{|1oSFQILfl+ZBIJ~P(jYh!-IC49?w5#6*~K39Vs%Xl1KVf0SNZOFh#Bu?;41;OnhrGVi(@SGH`9&j8YCMmB6 z`eYdFuO$TbuJuI|XMY|4F7xv~gPp2{s5nL^p{5v-s+-Mp7Lu2O62%-pal8q{_1BRG z-4g_LLEs2_x2# z!eWkOJJ><63u)rez;S7D4LZy{?{$R>?97I>^HWus>^}R^CC{~mv-x>im#RtALXfyBoSI&FfLOYnopU^#MRAR6CuO?U$%6E3G2zuye|ZnD3m{bRyjJg6cQ?NX zZTPl@D`TY2P!_yNq3+Qn@%MfnoVYyvt5Rj&A3p4;w11}i^5>%y4V^t` zpgp*1W(0qv!UZ&9*lz7ivG?eweG~{Vw6cUy)pKufnXGR+;!MM0=9&M;$+4yBkq6+a zi3k}jZ0Wo!TYY%_TKJFq*L&K}Po*6loUqbG8Ls2I}cMmDnPZxEq-uE+Q z&kw*V|Mq6DZsqZQNBBDmCqx{&NS`<&%2G2WzVagXV2|R zv3^#@?gqD`mX!aB*+29Bdx2IJJp$K2@v(w&6qTBIm?UK|Ms^S$@ z`rBC|*Wv0V>5t33&fRLuy&E}o=ZIFD1I~%_+6iS52b|3@lDU?9EUht!CyZ$u;Z~b; z6IV_%MJ-CU5>~g0RNR)o+;fj=ZXXo8l54LwHY5J9TSmccO91Z|l3;(x=^t2duVx1k z?d&JGn->6G1Ko{I{m>AYr@+L#cz_O@An09xX&@6e?|+r; zG~u@O@oGzFbhGb)*LYDd%GtCl!9OHLvmQh%N+wl#Z{w(#tgs9|s0m3-^d0{8r%pKClJ}tad zr)oi_7pP}BPW$Sj`{qY2_m6`6 z^~Gw>I%Gn-P#w&#%U3<5% zpuBg{U8lWlprqU*y;o3S<`cD>hU$aKwVIH{MYkHHr+31Uxrl4+@qMbasZ8F70@n*rx=Xqbv*t< zL;qRp4{7M17hsNjPM+XAYv^t~yK(?E-`W+-=}%rkMo=9Nmw>K3&a_g&rgcz(Ozg zNap`GIXJ@b|9?jiuJ*_G;Ixkac}|t)GWqG~cpSomGpN-8GD&+3QdWn|{!0wEj6y^c zS2F$8#NwhL$z~-+bOR(1qC#}n?d=ZZupwqxTnrUsOPxgS(La5n$Yh?9v~PWZQ%qoD zTDrHQKB3aUw&KF+>1-#=SO^8Q@J|_Yj}%kfW+b6N`DK=3c*>aG4g1UfdvhSV#KPrcrJEU?L3b{$$9uNPgKJMwT2-`kgRIcKr&qgO=yr$Adg! z%S;2dMWK7Pn@>;Dy=g2->F36lEp!uS9SjqX4OX|;PRy+>NmZ_OPuIFD&ChG3*M%f3 z$J=dny3buy(R1~{J;Q71V4|T53%HT=C?^bd%BmP)cdtD`_ZF^SRcivt_qKLisWkSK z5W9-kfL%R};MP1+`jgVHa(A&7MrTf!BVj!tStddrv~U@lV~`R4E(>OF|Cnb&@tnLm zf1j*pDP+54{lQ#BgB&g}# z;~B^N-dt~(xRyJ2k@@-KeEC!eeA>bgBR3IOdkT~9G9AlfjqQo#h=kq*$;Mb!%t~?T z=FY)6@JF{reah5}NAq}y$5yUm?o>A}zm%yM*^!`D^~WWa=exCF-4(Cv1Lt3lr2l@g zy?A6hN{0xVxHr`%Z1D$i#wOJ9I7GQezp31Xu1587-1f3M<-$7GPD=J|QSAI&eS)>_ zFN$GQeCPI}`Bg6TMU8(ulGjO{sqaPbS;%v-5canxj<$Ws-dz-_43j!X*%&K(6;H-l zOM&Le9R?dav??DgKjxv$nZ#1J^sZz1QYk8y#l&?DX02xrdn#Kn^*1~+dsHs=q<>r@ zf?$M&l9z#n!-YbCLIU2yPY!jCV&sGh{DiXu>i@LS0{hEG3vmmP3uKr5RT^+Ujaq{N-H#H-Uu%3<7*O?k_)VRkaK_%u?`ubbLB1FTOh#GK%E8K0IZ=_&)gm#(xxQ{}p<+L^4HSK#HsR%lwG^j+}z zmOu!p(1*A~^2l+XWXbbe`iNK#U24}BwbQPBmbA|dfi#P%z(xyHY3BxgRq>T`4mP85 z@QBa3a(+iGBE;#U2SR*(w0nY$wN48?Eg4q?6(k(J%S_^WRl)WT>?3v@cPFCX2r|%{ zP@0c)#Z~>QTKN=3nVk4Ms)9!{xIVX;2h7{;_;bz(*F!h^hwfKHv5YnT7@{4%v->^O z`X{qH7#=jL?oTh2N_|Y!#86}Im zBT5B!w}_F>Zzf_n$)3xm6D@R!;1?5zapIA5vAH5i% zT=x@MTAm)j;G?tCg&tLwmWK`RMiv&;$HM!&k*HR$glG2_ZAW46xaXK>ue+17m8a8d zVZnzp-D8@fWAFQ+9=Q?kyVilu899vBe&qvi;@Tor7NH?otFM5Qjr#q+XUbj=!21)! zOj?`WP7lA-Z{jk~6{iROO6`=Z-J`*Oj`O^0-}JWm;SK%-BddTxtuUhV#uwK?PV|5Q z;m>+;8Nq4jKtj`n=AW;PPD9Mvu&s@(TsQthIy$9X$1Gi~4%H2Gn_LIgpuQAcfW+5 z4}zv=wb>_zLZ!gnK@S(;+az65KJWAMT?4g1@8tmRQn8Px>-X0a3yyW-h(6rZJ|-+! zte44Os_~%Qe~)hwzdyDaoqZ>O+4(Sif&b&rD}ut-qiR>7qmEy-Ny1Fz%Vg`|5%cf& zR>&ln1E}2@7$Z7w4cvBR$5aA;5dO-nc<({^_qJpYgTqx5>-1sfXa|4Zy6o(j$3X_S z?VCx*w<~OQ%UvpbOXcGH)7OOeGsuE&&dSTcvNa>*o4;7t4-dZMF=vwO)}p$ z-^T4*mXz0OuT?QbqPa~UQgvj>tM3lnb6l14VDz1QE~c?I53D&zWX&+SG{?~x z{`~iYZo?NgmD8+g6N@9?u?;8R1spIPfo9B66BV}j*ZA-E;d3-j7gKzfV`_on8ow%P zBqcDGsI=`rK!0kV^*gk?w_0NIC3{DNHG03u|GPuFM%)~)GX3YTxbqMAmlucHtWekp z?X$hbCzT&De@1xhiVBzee4OSpEygZyI5928A%hxj^Q*v`AH9VCFuL#&W`{b283f;_ zff!*7&2>GhMj!%}8Uk-fQC)F>%KIb`s`sukI&WSu@AjCQeVh+?0?W`IBjU@W!_b5D zMmQq@QKn_%A%1($1ogtnd3@83hp_rVhHZD$5OKBd7cV3q_9{J#fZC%RAj~&XDGEYhMklelLlj zB>2j`N7Vn5O#Ps(g0^itv+2~78Lq9fet8z9)Oi)9L$4eQVfZslPydSrN82_@Dj~v1 z0#&Ph#fYPhRM?VkQF3_6YWRMnVrI zOOB3c^8nGIVh@u{g}=z{>G5;rA8 zPTiax3( zqXPZgy?9>{5s2DX7b)!+2>_Pfpdwh1^j2g9Bk_cxc5k`=#S%=sCW zQ1lc+r?}gpXfYG=#G#^Vv^75-U>q>JC#~nTOK_mM_79i+`cgS9YB=UIB*>wnfeAGd zgJ4L(k$lMbi5QLRXM2N`U6R6*X)I;Et-X z=-DG$ZpL6D`Bc>biRW^f>xC8ocCA*ivBKt(F7Ejgy*! z6w%a9r(Tp{d(IA6xUk{EtO6th0&8N#J~WdUh_;JhEe!nlnb0@o*UpxyRk7X}5=GIt z!w_RBk3MR*glQ9V7@)FU|985p?3F?vryJ9|@1Rod)4M|fS6UEPM@@(LqNZH)dI3{n z#jj#(&CGA)Wx060WNFc!xZ74$w(m3^x|M^cp; zNmJ4A+T|5v@WY=wx*GvNf zs9^Jfa{20xGOc2fV#R3c9}&T2WA&En7$wiBq@#OiWOmWe&=Lwde+jXDKGbr-xI*Nv zqCx=?5@;V1=oAfx%X#*WvvrXS<|!7z5ViJxZ%OxfdMUU1vd#2Flo^wY5tHll0!IDq z>lAmZKgUP0%s-72=Ka9|uLF`bSB%^BysO5LQnV;6)F>#;wY?1^e1>4TFWuZN3`N1C ziz`9Q_uA1Z5uaw;j$sm!`!sqYjA6Ji7ANnIDg+VQ-?MYi8OzI~SZz$4teC7W{=Oz+ z2sA3$=$3{~L9`Nh@WmR9wqoV7UvNnAQ<|Oq2&mB3umDiuq8h#4d0T{}2pJ5CIcoP; zt203+)4+%q4RS*?*z=-6v+w&>I>gXEf06h zd?Gh6ay(8eukP)1LX3J*C;@G}@RG@HW>omIs1is;z~-C=hAtW52uzDfm%p!IR&NXS zEOMw9u2AUp&9kvnQ^X^b#VV&2Hq78GjtfqGh!8~jBw1?}7n~M42(wGZayJCtuT)Cd za3?2ED?lg~lq7StyeWML%U{M^gm}5(y7T>*URnvoDlOKRtnF z0Wc}JMZa;eBWuonAG`xHpI;%=2EYYw+xFQh_Nz#k&s+dawogkC^KkDqzi1=Bf)8R5 z23XLPKrAX2K-GW+5rh_Ve+Vt}Pyj8(ugIWC`m5FZIwsnHvBP4zX$innUMYKD@J$>b`9; zD7L1wr$VC*u*$Q+6diGc*bp~ri?SYC!1>$9wN>Z=EzO3JpxhNI&yHtSd?=Q@p4QJE z@$7R`=Xrs%dG?l1g(&GlE&pnR<>?9oAJIqzI%$)(sMVpxW{`c{kE%uB_qQ3j%U$(K z&suNsL$JWzgLL&S)m7*&p$lkMYR*l5%d-o+uORKEIR?^Rto6>JB5_2%`&>K9w$G!L zo;bm`SJYv>f%HW`3P|T%h2S;u!GyLRO!cdIy*PS=5^89j%>&eHtC3I&^`bUNy~bGO zfe%1JNKZhT{%T{G^Z}N1vpHfDP&ZHF8=yo+QXv8+F2w|I30w@`0>id!^c1x}wB!he z40{_g>|);X23YQ5S4V2`Hll$%JxheTqbv9^01Pn%Ox6pST?m*k^zS~-P7t`V=!A^l zBby_3A%Q@|kU%>$0DC=Iuy1?0KHM2k0!CIVN2oGCuDG%~8>Cj%94O6+0n=FlAHy+d zEO3nUmvSzDeusO%-Pwij=n!JYUWjpk5c2_1JlZl6O|W!*^|v`PxMBf6zH?cEmxmkq z4MVU|32aY4P>O7d-;lv97xKcJn@17NEVX33LFeiRn&zq+FC>-6c*TN2qK-! ze_MpCx((yW_Gx{Ptr0eK4`xnzZzHz>FSZ(J-#!a-e0hXXcOv{i+Y`V%Oa?DBYl^t@ zRkVlKhD|kVgOXr@-$5YHwjI+nL5j6D`#vRufwCQu=yG+DahC^Gc3avZ6~WLwDl(22 z$v0^f-jKiX8P_3@<3=x=G&KdDc&EKjDmz0@Gcn~sHFWSfX3;o>c=1qF8YoJ^;ui4)WL*99^&q+bYdDu zOc<6=7=V{b_9ihQk8&*R;h~O5oOPp8qn_9AYOfD@%KR~V+i}B>4z1v{$ti?pKO#fM zLuU&aPb$HJy90fd`ytx&Y6kI=)M$d80nt0#A4`n8N{VlW5_XkT(2fN8NbrI%U4|J6 z7RJ)xwaFQT=6hd!!0tmvBRTor{Wd>mU26``cO;Y?ZaCDx0)A=1**QYuZ zmuDb#gFL(+CYBDud>DE|vLjM$tUxx5G_eiXZw8PpPTDI{eK6Hz;S5ph&mV)GCz_)f zz5`Z204qC2>ezupnV=kx9D%cWMC(>6s;zwC%az|x_Z3h+m4 z4p@#=B(`DR7^^BYM6_U&q)q11B~bFr|HH8&Fp#l|__iw&Vi{y4(dJ!xS-r+kt5W$d z(b$qibO8KaHE94oUn2JGa<(BIGbwjc=+T|gueZ{Wks6}5ypzX+Yd zmqKN-_k9wAnEh=9cJNO^mx9s6NFw=^J5VGpbA5JWXwj-9l7MA_NgTYm;AsBaMMCM0 z(=*_;eX|Zf%*#;lqhT?k;kzM*l3%iFh*w3SK;l7Y^hB3!50km+Ne#$tx%MgXuzS9% zZLmg}6*#d+0Dlk9q4dmJYXnwYexKrCD>w~ ztcJ9V)VAbj*$YgfsR+&YYdktP)JWOQ*yID~cB@#G$7;-WNPDl7`itZeNwNf`6J8np zp3BGY*efcm_idHy3=Y^r>S;w01~SfTaVX`6nzEBrJ(K5LP`#{2T`} zl$vfzBwE3gC_w(HVF%t$@e}X2MCkzOIIRLvPx+s4+45PxbI~p@^$8THazc^Vuq^{H zl|tx4S5Lk?GbA#QYuVgJ$MrCo(4!d zL{IS3OP#s6?*F`-{PXGJD#9aJh7;T9>3DH-@N_i92g|79fJyFpcK z{!I<=HN>Q>5WNQRC0w}=8>3S_lf!fy@FgnG&!O%*r}MQx8E=3l@R$c-Ik$8 zzZAlL(=2+|_H%vut}g+)P0 zr<}yIG#8&`U-StIBni5JQOavD7yqqkhsO5S z5)Lz7Ql*Ow#^MXfp$OEstr%pJ?$+qsL4se1N?5BVg&JJn13A$R9+JFVJB^ixEisPAc`b zz{pd6EKuNt&|A57S*Q1zR6+9JU7g zHP082k1N4`YLzK7%thW=pRpa|FNRd|p0kKMHK7Kmku4cvwbOQwI%|ZncR7WaY=xEq zqz<1{WXad9HG8|z;aZ)29#tcB-WyvvYG?q@Mm-bn`3OPN^5rU#i6PWRK>0-~aK3%; z+;>C+#_M)$w2Bj$^SrH}|79Yp0WV|shhhoR>jf?tBtD6RFz~e*RPVh+7VM$#H#8!8 zr=p38tT;ddhSJ6qMlK6TWGG0>0_!IeQ1VP0C^>al8HC+I`%C+{H3T0RL;!dw*lZm@ z!r;VJ+{jyC7aY*|qa|-bBm1~$132DDhZIdr{>xn#rBO8C4(WR_!h5*cT*Fyks6SbT zH@*6*U_Iu|*Vlhff860?-^5 zp#H)vcw~+Dt>mo{=OBT!h!Mgat44#V*6JlJC_TmQ~UHQk8!dMtnSnN&h%3 z5W2v8Y;hJ=QsHe*KMvcdB^;~j+x=)2*MOAx?{;KR?Y^3SfBv$^Y3YapK}QK`+%!K| z4EVR_Jd`@rwzI;;uaZ=D_8Xj-YqaOQK@w?v+sJ1j ze`gEDs5g=!4E*z}Vmz!bBD&bf7lzjvWDQ=IuB1%hClBvCn_E$+L@xFQjX6*=iz?ZB zr?2X8vm9|*Z;(W6Frf;&(AEk|>WY?CD`Em#h|yOyq1EOGjg$zr5c+dydKCVW^Vc)N zSSXV9`$EAXqK^W5h5q)ggiCm!#5;Z~4e zpyA@fZ@>0DLTRs}f=_#XcoR&#qEzu^lfy7_d1vf86qe-@G2J6x^U zqAf2l{bdzs8gK7CB+=P4aaVjK8E zFgxW*Pk$P0Yo->v?d(1OjKiI?JHV@Tr@ZD7LA5Y6*8$)Fsda5&wSpQ)pUv-8zG%Sh0yJ7d2Ut<5y3uv$c z&l%f=P*AOO@c*X^XdEvW(3IvPQ&@35%O<@=yfE}&)a85ge~#sUxy&qS6yWcMW8liI ztt!}Wy`G1|rpx9ajKA^o9N~5L@9Go{)$6HVE2P6jH^eOuDvaemfO))m68M?frZyfg zo*#s_+l%I=*5X|^%h3Fe(~t`)s2exGwst7Hcl4)}f!I_ff-HRwRRuVICdQ1DA_q|l zi^^6YgmUfGK7pMlMsOj$>|9)yW*^}~j4Ac^z?;uQniEx0ZWw8lZdI0&N_`+&6)hY0 zi{G@-9Ny~O(s2nse=vBcICxBNsKBJxY+ldOQg($23JI@#dG`%kWW7m-D8vwR4<1gk z+Rc8?MK&R%7sS>D22}Yn@Ww@~eB^rFtJUDpvSsZ1^f%8O4%9?N(lyJ3Kcic%75|3s zuo8u%2;~BLN7q(BR=!&62J5bGZdq#)QKjaWx-n@o=CEK8+G2ER{5;PJK4z5f3~PHn zQIe0(T*dG+j_j8o7b`jg!alMbNZQNSStDN6t-BdUcylQC`F~k-<_UGOIX=Z%@O4TB z-A!13dyYAEv|J-_+M8CR3MS5vA}aqQAoT9NekJ)d<|rndG7PT%D@x}w+E3KHE=?zs z+k%>9USf_<^6)1og=4pJofd>qo)+4;W$PKnB#2i5onXs)XrD7zs99*t;Y!A|!QA&9 zWzy{hl752ZJ$;_NQo7+)rm+D$5j3S|+9Yb{Ul%Kx79)2p~J<_y= zZl)r;gL3hv*>O%&c=2&wl}tI+t}E)ZEtMb*2cDN+sU2e`<-*{ zz0dh0nP(=QnR=_Ms`XB{SrlPo!k*KQci1hAE|VWPrTEv1b4pM}NiA{-#eW)?TPY|} z0y32970~W}yiGb+t$%bRUAz#c6vso0D8(f0Mu2Cyp~VCxX?wmNy}!@wjY!jUK415? zeqeBMuwq07MqOxkyn%n*Ics1;b9?xHs9`}@a(Myn*B-lj>y7HzHF+Fh@p?MGg8lGt z`M8>UQ?FusAE{$`J|0o7NMcwRi_2X)HStc3l6f6b9?a?B^6?KB_Kal$7Y4gO{{SzGq^_(EiNQytVj2H=NuGr$kJ6dLb>64xv zLw@i(#5!51WcJ+JlvJ-Ptr8ps~^^k?oD2AyN6aY zJDm~UK2fmWqH-%E-_N%0U>_=jP*G7QqTU~`$6h+urQSa>0zTNE-!4W=NCv##-Y(wH z-p^oRE2BDIx9fi(9iKf?GIDb9J1*(c^QW^TY-NAHIj?dkXe&HF8hvv;;Dc>CW0t?f+X zD{0F_P&2@>ifz(<$3=Tx*i9sAEJ;+#=awJu+fQ>dTT^RmtrMACs~^rzg)k;gRqsp< zUe2x3HzRj9i|;`}u&CK(;s7)ZTtv6a5!j8l3D6g*rt>3=_ZpppDqw z2{m=0_mTNO(?GkoXVT<*&8IW5%V?X(`ODc*nEe}$m>Fx&9oDZzMzFUs7(}seDUKd$2$E>19RM8i)OV^HzBEBSztI7neNPN>dbZ@mES=%s zBT4D+*6@D*lxzMfN&mk0K3B*ME92zU(cIqjG;`UH+S{w%l-v6f)Y#kF*jt*Z)$w-a z`RM$yl@z4>&>an?&;}#b9uD0);j5PkJr$BXs6`?zSp$^a#_x1<2wAs*jJ;Wy@1{ehS>}LGN|BgUaxOBJBQN4|< zxxPDdcC%NekzOL~YMnz8P4vF-#>M7pM#K)V5k(ObDHDH0_($d$ta?iEFEspUtOdfE z@FRPl5P!w>ihH~OU1WaGZCJa)tzV*g4@yJZ<_?pZkkdRv1g<`c_|ShO$0x><^;eHXZ3kfnhwLw0<5Bd0|lys~>?026gG!&^T+Ghvm(VM7+1#VmV#C|ywwLQ9>-&wb znO4<#a^gFGfi`BJa$zw}Aqj(&GVxKw-)(xSoqK{8rq;721PYm`5rpEx4Ws;Xp+&di zNQ{TdIoaGbUx%g`*D5K8`hK?RBba%cYOV&<6H6jn@BWq(Vh}T-=Y!%33YFS_sChPz zMx*P-)K`m?^V$I|9yt!dWkz-PJ_&*+Pqc+w4uMd3gJZIFk#BJ(oHSExw-YV3IS!{` zf+s0B zu`-i(fs^AUD}?el@E0Mo)h2ee9idji6KewgIwPn~`oBdY9Y_Q<2GfBs>kDPDY zOhqkY-_H-8zj3Y0NSkV*7qyCK9p|pLv~~mawipPw)bXJ1^qGJ~ES-3G2lad}?exj~ z2({YWB0lzEo106V>nmWF88Ez?)l$mDB9;MQ&N8Yr`J`Lsi*E4Q@CyLj8taJ1_Ykwc zic)=+2NY0>l6qr>=0T{v9~%UG*zTo)?rMOKCjkb4oUNuoDMEG4Y6y?`MmF{qfabGY zrSzj-cjcZRYW9ftfM@K>0Qy>?Jncnb#{uX?6mhpgX*;KDHhwENiVgz-Dn1xgC8(XE zS?gQ+_29GYUS)wi?GFRT)`=rNCAjh{^c3JzM>AOZpBbcQ%|Ko1@=WK$g zYwoB`b%a#8aDfs_$5txd5} zml~fL)+hbJ*30yXbI*4ko5elwgi~HZu2MaLT4ob4Z>VV+Ws)N9!GBjQTO~0Hdi?Xx z99K(qlnY(TBwBL|2;6~$)M(&cbd-yXj{Q^LdXA@I{ig{ywE%r9ed&7?pzq`_ed{@T zPP3YX#hS_1oTp^qTUH+1xEcOCTUKbF+HVP7%>%nSYB>Px{~gh(S?L+K*gn!|2H)!R z;Rs#r_F=VfB^9_ihCg1bp{i~spSym^85MTs;#SRx^CwMZS$J=o1kvj63vWv=vzZ64 zdeG%qho^=Srl5}tGKCZL1{^PWs=GGDo=;&f;1K4CsH2U>LORE!anVCA=xlZ;sh4RW zrz7xw3vJSze2Wrb@m@4)o{*&mn@YqUQc& z>w6t8;iCUOH1}`GP6?q{7*1JG(gTUDI)pG^K;+w;XV=7DXCM?`aa4dEV4v_drk}%| zbXQT)Sc)O4OUYX-_*xr`(Fjd*_#@qCc&1orh-}5~s5A?U6pKXaVwi^RTsfmfiQ;*C zaOZ70{`C3dyxV%Iz9gdJuD5`q-zx=G>uo?Qa3@ z9}|c;;2;z&+w=q8p8HfOs`P3XlVWhcHN;we@zj4rHJ7oH_asZ^f%um(1C4tXf@(`bfKgxC ztx;D`0&6XvvjdTOiOLya7vPTqx zw09XIev!`#GbgoACw+h`3nN-2*x03YG^v6=xwe3*YYw9RNVQF|z_M?~r%*coz7~oP zg%d|Si1EGHq|mQc52R6l`FOKcrUSmO9L5FsIzmU+TPTjnCkVsnr#v=&i2)=vZ%~Ed z+DTw5t0cF=VW=d`Q!(mcs09osLmYo&&Va4-XrLt@uMaiNl7SbbeGGI!MVzV8VGoAq zMxCud)ClqgwRZXkUDL%4&O+PF{`ZzR6*_&`CJ~bRDlkV1d~9c_R3T&FBK)=1FE9ul zFVsk>QFc1e+t( zi5BzfnCWx2o^nyvP8*r_Nu}UWi}4@ZQzZk8^N^)QN%=aRq$KkiZV!DRM|m(D7NJEd-}4%DO`*ibbcVJY8-n>Rb6X(qLFXP42R9PGNp<0`r>2~2l5^?Xxl298-7^7U*F z`OZ);+tjDY0Y#;7s4R4NEgH}P_qewdyD|M)O+q7W(vpX*P>ibFQL0%qk+^V7UpV~j zJAs~6LSvE64Empe3KmHMjB#Ng#PTp2k5iJqU0ZaeAr0hY^BBsCOcvtPa^*KRQMQpiGwbLT816i2jSiu-fhbp?qs1TZ z{H~|ExOp^bA`d8#)5g7hv5cQI5dR*Z)d0;E5nf8YF+n=&SnQHNQY7rDiq^8y%M!Cd zqP9Vu;DbUwN`P;1my4mcw{mGf%5##?NkPaBv3Fu+nhsc|+R4I8Uoo$S7G#rceS^%? zuV3k#vwZ*NXPHg@Nr7MsAe8fq{;;Q3dn2o&ke-nl_*m_y9 zBTT8~sTg;BT20t-z#%k2`9i=}jlwKUI9Q_nEqj0(Lc|YkEjCs-lO_R898R#cH}>WM z!#@~DXt0U*gNB-;^#yWW9XbgS-h(m`pR_YkUS-g%%P7be4!+_$LC7XCY4Ga~nayD) zMZA2BAo0UHe3gf0c=I&RqAC=~me*ORvbYF3*f$7{g_+~4yHyVXKLY2?Q(Z4$Sngsw zwf{zxBEZx?BxtA9V%9p84oJM{G2qlB#o#?;loaqhv*6Rf4K+zIK@YH$y0w_ ztxiqbzPwUqct0JDfw9=3V0RBu=dO>q9PM%6pY9#6)ZUCGNL#S4uC;$uGCx>tw7ouN z?n%g8{rpC3ttQ8o6#dN3;X*HgoSDhl`Fy@@Ufb--h4rzsc=h-;F*m-N5`4QkXIp4$ zZ29E%aU;yqRXKs<_%o2eMSa1JUYDd{-9M|vn z#c5!-Ass5V+NlscSeqhgML4o?6WvWI^jn@1MvHChuZ)2wOHsfILYSuTPjskXbEa4#AvDKyaHwQl9LoTNQD5=qiq3u8Uklol<;TrLY z#f7o{_|Qd|@TG0R%=@2x5PhHMMf^_H-eFJWYjPvJcr)Th!@O>R$z?AAG<;oJb`!stPBqlQpXP-vJ}>OS@EL=sQf z_~!kMwKgFM_~#ZkhwV8UXA}9$8lT8(?a1Dm@28?Y8d;+Iyn29MLJn9b>OC${G`6MF zf}Ef_*n?QQYA^bRIoGMkmz*}~iVr-fgCNLW(~-%nXPC%dJy30(U}j&mA#cD9)n4#D z6lreOo%Jnbt&)$;T;Fb`6t}c1zyzPIyFDy{R|;^CTLWYs4+^!`sn{G{DX+H@{7nX0 zL8l^}6mziAr}$Fg6HN4(GfYO3<5{}@;Vtj_>s2C@8)_3RZ!7&;UX0;x6ofuW-)PMb7_;Rd=mGZKDXDy zsSgWbQBw?75ii_xwN}!03lzW6jKJ& zWAaf1^D3~G_=fY9U3GAiA3~y`tYC$uJbT#~sB1z&RQ4-4Cy zw>&#w=josujTPZ!_c%<8a|pYC6CFe_mlEdHwy-^A26{iXr|7FCNqYU68d)jiHo+Mz z%x^SF{n450_u#>GOG4tsq#2dSUE0ffgVi+L7efY&HLszcQzaJ$0w0{;I3w{^;y-;D|UilF3Er z1QP2KL=u*HaKt#j5RAqEsR(!r7hebl04LNW0kpXUZ5?n%sf0N}e94nRLdmpZza*>( zAa48-3s%f^;r2y6?Vy=`+yo#Hxl#RS-AH{93lf3o5DL;iXkp_aplF38Uv^IeP~^Tz_-6mc%e}|;EjsC^W))AeQepYNfi2T@n{7?V(Au~ zWpzLW(C#QrasZu;XOX8APBtzi57W+th>dxHCuJcP7_J=%HGOurdyv#QZsaF2UETJ5 zc$05XbjMHpS&jW6L=P2u!q=R8DD~xlfH8OEtv=I$BJdb}U1m)CW8BUH zRrh)ywax`k!t*Dijkhs&M1mWf5zz_hWK5!iy(7oyq|hH@K}c^zBU8ls3qAzm*}@H> zC*H}904YWKjY8)6|KWlFlKS2ip1NrwLTBZcpGcybj*a_{FL|hd9u~SsqYm6omShx! zKw|K<2*K#|AEFU@90J}V+W$=x1yTQZO;BU_LuB#b=eehWH+xH>{1Oy)_V_i*C@KIO zKzpMhV~(KfipiV23GqUB((rub57BTGXWj(i&M21r*sS8e6r=A4ki|JOKo%#=i2T1K zY;dBhmbMYZlEK9IX?sn z8kPm%4whf}IG3O9n1R`aAH*ym+KCZ$^l*zP{`u*S-S+?7;bG~YHuFhFj1=A%8AeV$ zqipaFxjvmUigZ)4{~08AzVCn2fvz4_J^j!u?BrDS{g)*+kJQcke{M-3q&H{hN#6WV zCb~E=M&!DHxTOWeEiE8!AsER2@N8BN-uKQ5`lnbS5+xBDk~?KCp!P__3EawnGfaT= z6T=rY#`qrrc3R$`4QUB}NCId043SUMgwe9o&sg`&+L{aZ)FGN1>yi2o$vc?)|ECt2 z>qvB|b-JA)c3TTv-Rqe=lN+974ntHM?}LTNFST?sjXIxE-YzkY%1pxm)Phwd*8{T= zz?V#?DvaX;S3uMllT!Y_=?P!@|I_17@W1JCg$bk0P3|o-A_SF|B^q6fAQ`16CSt5S zjAp-l-GM19Uo5ps9x}DmCK?4aL8F9*G5!#UJ;V~TfVi6t}X0kBcK{K*E{ zxHaPEumj?TN7UMg1!OFoq&QQj(1To>1S%VL7o0J-X zMCm~RF1c=~1`}ZD-Xp=(ifA-%w`iCB9O%*mjwm2ct}7%N{7H+K+&rd{In}?Kby}(y za$S^0NL^yGFhU7HOY?tC6Z8a{drYJGCzhVk#*kR?SS%N)W=)VPZE%LK_C})e+$M|! zpc5mdZ#I}h$pRpK7KplmX6B!bsx*V?g1ST^6SlJiA?~{;XCujZhsn!r zJ`&_d*(PA<{+pHUQ2SI#2KP z0pcb;2JN$j$tC_W5Vt}Yt-cvuqF{2OM*?k_dH`))ydVNGhd~;xEQ3&TTZ&lnDj;e( z_y|W+D;0afhf&jLYsUxRjXEUbHDY%M)k*zR=5*HaBtF|-i6%5bA}Dy!VuSXGS3+?{ zu5SGs=FuXjYp#&Dbn1+lxAd=2u}P*T8I@0?mA2?X8k(n9+_fOeF$fbU)x{xQTK;*! zmUd-e*4z+9>r(Uki;xB(EHsyfdX-i%{m46eGa0Iz@-d!${+sfMEMR=&)2;nOgMXzMG zm3yo*kF_ywR0irlZnQhDRogrP%dD68?_iy>Y$xoLKml%w6VY9E@XaJ82O`0o0fZ2S zI#>Qw7-JPCRI}3cj$z~pe6{gRIo77f;^K+lW-4Q;ejVw12e`BVuggp%b(PooLpVnd z7CA(f{)Lp3Z@*$Uo(Fo02Y(8*IW;zvu?@tGf0*R35x^z20@5fDDpQ3;Y7b!?anq~J zq0JF3mqkb3q-jn#tkVlOA(B4KhLx(&Ct8~{Ilvs|Pk4~E$*cMb<4Uk$X2#y9KqHO~ znToSqI3BX`hb;UsCm_k3e!oF7$*-qoU5fJ-#Nv!V8`(xK~cC&h#M7u zihmZOprV2tL_aTSyIN?*EV`Tg)C@$*KhVNr7q3mZpRVkbYDUO%(fN8E0X83S0z&g%`<*iJJ=l|B;c`WfRiBmFJ zI><_B4w!J6JbC3|4RYruJD3b_SIYoQK)LR*2ASANSK4LR1+&mz=kb5>VvLPZU&qe? zhc#8lPhb)&6OyYO?*z^!dst716Y3`eIFAZ8e_TapHV*cS7FFN>H!UW&shQ3_L-Mk= zYYY@+yUk-*0@h|HxIr!`_$E4&6yyBBO2Z)-)Pwt{3|E?r8M*MKj5VXpCc7)88R6jn zie^d^BT3i5BeY5(Lah0vDmBSMR!=RbOJn1U&H;K-cM17MnXGl!C!nKns5m0Ai>G|3 zC@H!7%yV0EKny9AqII_`pwo9WH!cPIFGVZiR)G3c*7a;qdX^v8SBnB7REV8l7KePM zlyoUL_ERgaSw98s{$`u}V?f&bry3ut@qCotMwVny#gk zegBIN*WAzOIL}-MKQ}(vu_oxA8f3r%1gdzNbtC~JErB@u2z;F^_Z^C6SeA0FV7gYl zg0QJQKnO#TUqU#F#HvWWEg|G6anmSVP#P!r1_dy|5j+~Q>s$>E>mahL;tWnR7hL_wd9rD%(+^BOJQQMq+r{(+ejHrSf=(hfz2?z_(|#^FFB%(!V`FKbC-L$_Sn` zdm&wQ;XtC|3l{K~sYj>AnEtn3 zwbmd$>68XH8yaMHU!%%NOksD@mD&qSP{tZ<0W$sXhU_D&?3^FBrpoqUr32D4(CiTd zHKxk+uU7-oULfVq7hVs?djl_MPB-oDuP+Tj7&xzvkDKdBDVse-9j$?Q^6nR-CDSzp_`V zb5Z$zbtaqC_k;R8GGPw(XQ{g$0#QO}%L+Gzc)f6am@V7c*9h$tbFLx}{i=TP$40!WsUA)OoJ z<1e*Ty4GG?FAVL)dgKFG=#X3-gm!C1*pOUo1Q+Tm2dJ8@s)?u9tLHv4^UZW!j{QQ9 z@q>NSOiCl6-an(Wvn|zW)?TN{LzU;m1Ac8A3i0MP5D_V0!zPRa=n?xIxv~{!VJRHB z@D@1w1&>pRZe7T&)j{ogMuIgbnF$3;=@WshVrEF6SCYajz~CPcRIm&ZRs#pSQj%ADiorv=WBw8!R<-Hz;&kJ80nEuV7y#M=oudGYasUab5~2*fO zkTue~WM+WQ<~gqc-HqLMmz>LEz;M2|}Ltw0CoT+oKdcm^?@omJp% z8k9vNA)T;9Bb}4WAg~5>D02qRDi`czoJAu?ogGuRdClkqA4&P5Eo61U{C}EFLs?W5 zOqR9%OpI07r2KLtQ4!a$ij;>AE#FNWcWO4w1v7eO*M5mHpC-nXCoW6p0y zU@Wp_bRsOWF#DVaf;2S4FXrTKULm=A=X+MnVV{GILp+=UQ zVFYaBor%~>b@*R209ZY!1ZEnS#BFfj#ffbnwHQLpN1nEa8pz;y_C8H_1o zNN){96@8IW5fsK8*$~uei@3%62j=J0A;uz19ffD4Q~$(M#p5T=#|r0V4shIlUubqb ze{}4XOp>SCKB6)%a&Cv9KYK~%bF>5Mo0>Frz`knBNKyZ?I_(A|uMFW7&feq_g^C!k zc-or5@qX(Qd7|yV%ROse?YCDr?=(>SAw*2u-XSEX{ajyWJ?Xw2gRk{1y(gZRHx%d2jlUNU zBlR9C`!8=MH{OPxsbDtVAGgR958bwVNi+{xv$!2nL9FYm2csqsqla~CH1;`dW_@R# zUnqoWK2gM$6&RU+6Zv=(TRS(tJ+IX0ubFdNK}H_YYt_#9;ll0v9|}V%8X*mXmsTD9 z6f2^ZAs7QKl+Sg?YWJ)$K`3{XXWw$03BaUPqRZ!cpH2!cBM;VQ3Z32_mrBL!;to#y zz52wqvkG2*CUY*)$%^2zIucuq3h0jyL`QUgJ=M2#Fo%CtWd{F>&@sQsdDVQEj`-bR zSfRH>Z`qoor+P{?Y?q~zvQpN%U)*K8M*`y&WkGr40mZ!J<7@coJ){w^<)NxBc61bX z68?&_Uiyt8o-{DZ8?3{=?;X(GO6Pui!xxz6yr$e%l>c;nkaX6=6TcmfEW32gu0h`W9&-Y#y?vPX4~HnV_8oZep`iJQJ+SKIYGmALidZzeMo}FUjfM z!%6x9g~2{>>VMHOsz#B00QU^gZ}jkDZ5GP?haz$LmoR&h zYc(3mqc^RwkodO|QD`(a*($7l?@ycD1mW!!8DA7a;*9`w;Tq2PrHi%&WUsX4iXs&h z;XuF$zlzepTJuIhN0prtRd(OqjpJ<^AP5c~kgq@M#a} zrT}reD)W?wmTfEfPp59X=K%V@i2>K8W*Lx_W(Usrlq<$A`&*ES{idWnMu2$_fHGdx zbe86PPdWf|g^A7QVV}xqq1pCk8DW?|CqgkL?cC-~JH@vBO__WP6?sD_NGn@?Pk|jL z3QV9AX0AEF*_p&Ps?1DcXvTE)Kzb~aTa;e-iwL6%mRHi0A=_^i|{bX%wbdZa$=Tpv>uPH%~kg)U+S_F=IO3vCI9mSnxBexujk z=xhIzp*b%+(^W)?fmBV5lneLSY2v+r2(_e!CV&a{8`V40Iyqr6jIM%oyl)E6(K4199#1f=_XArhlzs%nZz#`FaTo+f{jlM*b?u6Il#lsX zQ_v|n19(k?!!eyi)OWtcY+cNrxlS*^F8YTfXWdjn?DaY57dz06g73>piI&F87YS^c(Ou-5?*Xf<|D}KG?`x=(ELOY zYs(ia+?b6~J4VG(yiIMr$k%9CnY;4Yqx>HXbm`91!(9z6BK$^bT zrdF@r_EI!Gq`a5QMSe^azPSjhnvDHsJ!E8a$cJj>bb$AL1vaV4#Yv9F(|VF@%i;~a z7+9-DV3Zc=frAvwX|D%A0_&gDL83NBddc0UJi#tO6(oqYL2dKy9BWy$pmN4BTrqjC zzhOTO^DHa{y%f8^VbnDYmQFMbK80@^Gbz0PsMsWONYI*7wwn{kV_SzD>(bRD$oGrv z^CE4he2`+r%c3=G0}Lw8cJM2r0XHh4+K_=>>Fi<*si6;f3W@}kKX!ocS z#EC{yr~zO8V;f@p`4j?13E9@m@^igFf&Ok_%OaS_!VXHNqyQePVbfyidxTGwC{O%ryu zbNIwiGo;dr+lJXQBr7jPy;UDWMlyi-`RUW5heEnmdFkOhw9YG?$;Y80hk^rfrk3Bu z<^+0(R4@N?Tp2)V>wJPKg#tc}GO~`68W0zO;kI=S@h)9JR@u2opEBR_z{B1{I3Z2a z5Kb|B*&K6-uXFKloHW*f6{^S!*E|Kg2u!q{?TZ&z31Ohya~2EJY0&#kWS`rGIYhPt zxbl1Hf))`3*QqOmRCRAT!&qxkls2jtOQ%=plS`q1MmVK?GTBWk{{&4$<(}5;GAs*I zL!7EEbrFiM6+UNN5w+&N>0zQIB|sO!+0K;60%wZ~7-P{dgk&yE^AzNw_*aF$tDy}H zg$;4V-%Vpp4d7bjFp3#kdz;9<1RE?!D^kYI_~#u__n$WT7M9<{%rpz`l#5P*qU z!RZUr0VyBB_c|uiXED;c%{(aLY@bMynN^_pk|f|Dr^|s2UrVPphahJ1HbLSJ4kCKD z&-DM4Vg7b)l-BSM6lW-x{Lj>dy!bIhp{%0SynQ{au>xZCnYvMz`xwyM-F>xyvn1X& z*8tmZsPT2oT~+A;jhG6B%{Nj|R{2{Jy7>wEG!j?&E1~>F3c*k2`++SDXoN@=fgoTm zHlsR0*3O+zKC2>Z*ZtE6fQSFYQ2F=tNAOo2Xn)l~&kN7RLScFX zZj}KR>`Z$F>{0E=?aYjn7?+r9^&5twpz7~_9k>yNk_sO)WLr!RpaM`1_F-jXvD1QP#WK2)iw>ay(zN&NDmj%b>j zv-E&@fVC(`@*^w97Xm^6f(EPK&=kbge^KhdHzSA=CnJEY2&+G>n8q!T|IX3|9RiTz zcQIt%|E%cXtUiyuUUZ3qFv39u*%r`OW40~k%nW!Z4>ZXyGf@67Gw3zx$!XP%dqMf1dx^$orWEb`@&;-5KC^7~N8hgq(?-v+I13^zy43u`^_ z&lpqVxBTPb%~(oj^?SB9sxR`P=G4A?P(T0MhNum*q<%=LeD6C{TfiU5&pCyF2OkA9 ziZV5In>n?LGe2hK@~M6Jb&Yx)x=KT9NMf;ly; zpzalg@~;b@OZ~j?xrFYo4EkRe4ugnfX?tiXAZKsXQ1H_+H4$$7^T6DQ&s<{P-xDBy-nv@CrCg#X| z7ADAsNCV1%?qh>j$h3pWWEc$T%qm|zIlrHH&85YXQ|pcuVA6%WqZgRyai6^YghL#m zX4eHNd{Xh zH5ZNp8&v@1y9YstU5*+4S#U{2axZjgpSj;F{-u#-zNMD&4`hR{iTJZA+J52bsYgzX zC~vZ+TDadzgIX}T3AUovAix;~yaMR;T&VIlf!@hAHTd?kAXbcR9?+9(sOxU2VFZFN zbmd?vBmc{O3{(Qmkn=M4faxdCGPnC7tM-E@>#0L$89;^G#idZcQ*svYhDM=dy0K`t zQ|bcymfO5c1z;52bc!yd))b@CPJX%XTc?rVx z7@E3_vU$Ir+rfQ*xqja%eQDHjcug|>u5u$fKkm*g+T5@`To35lTUBV}juCV;+eSFk z?hFG~6LC8*hwD=cG}OEG{*o;iUAmzwR+LxSLbu31Vv;Rvv;5rHj{ZQb@Z@#0;1F&>OV(n3IG85gC+yxu~F7| zg6i}^v1xaS{`0jn5cgc0yA7~0w=8`$2P`UG7dJ@VR6L4Sg;n?91NZK@0i!ij#`%?V zjv2J~E~Jcr$R3biIVj}Ma^kD)_^L^hsWSzv>;aPBOuKcy|JrV!s5-dNalJf_Jx5%> zh5o&LMIq52wW@wUZ+5MclcD&vcT|d{EJy4bo0^D42q22!U zn2CGt)z&IrOeunD3CYnmUy{MWnutzfy|S}4#nQBMw#H5O0gA`KhHaSKx z7>!Hh(WzPk_R4hIEX16?5EBXMWNFCL(&9UODJ3_S-%x$PFs*anAZ1Z7J!DCiM9(}U zxOg7TC{~d#y^yhX@-G?fcyzXx9trPfUtyDV0hA|M3izubs;-##Z~S!O)7dhF+NGIPhnxWeDHr^h1KhgZN?`gR*4|1j_{k^7*qxT)nfM`||X&MO?hA>w?je z?&x-ddE@h6XXc?Yw1@oWb_!jHxS=Rq%piia*5YN{IhvjkO3SpOrPPiLPftOH=n}LF z#<#AD$oX9^Cc{HJTtUe=7q|UYKSF*)0D=-siz82aYuHKbCv#T1?a4f3xs8$gt#_@oL&A$jt6)pH;hG*hb)-|PNVb{!;!O!{X7WRcg$7>+4@LFG zlnM(FM*PwsQco!)$ zh+ic<;;g@aS9@2xV4=US!DJL)Sd$nP-kK45_+461jO)yed>Qm!p@hm6k39pjCc%~5 zYw=3q9gYK8PrP`Ch?``AHv{s+n_oJ=PWgmSy1&rac?Qk(PIDb}h@GlBV>kkViDL!= zGm+gZuN7I^mHb_zv0R%2*=v8szPnI8wnsl>_`wbEGbyh+Lq`8Fbw0O3`x6oEmy|}QaXqFRs4*XW(k6Kz7Co&TjM*{vB zCo(l`hFHw`Y^c=+v=>+gq&oEH)4Bx7g4;L<_1_tx93jWYF5pvT*5x4}VvJ0dY%R5{UV1LyV5~m4E*-aF*xTA?dE3&1 zICsw)sCUn}E~eA|0hYHP*e>cK_s*Dy`)(zS_0-PYD-xABhE_akP}Dmw9WzI}?Yj?T z<9qygcl|hu4Rbt$=<}!b@nS2k>lHL9_CmDn8W`1yj`U53~7)*6#=#^d?LsMfrmTcje`&}>H0?q~R zyL}5oL;mvJ`@^Krpjarm2;=2R{oQgIgnxuFWTMGdNC5BGA;`gF@A%e!?Pb9<*icmb zuk1Psu3&77sbga1v0!TR9L71_No}Cz2lMdiqlB@g#<{y?qY}pv%;TtT2KX?x2d-w3+@Ty=7L8eZ%s)8s9{79>^sepjv(y!r(f9nZSgv`EUz3c?T8(MTh!a zZnbm_t%Xdz&pf5SO(UZD6VgC>u+%Mu6!JMB4q}r+ck|@^?Oa&*ks)-M!#Tzd7Ak?I z_R3+w5nYcw=P2|*!^1xs-nW)Pz@|Jzhc_bs+;9o~ova%S|)Sd zkbCslW?inOa_Ox@^SWonX%NqXoM=4Lg)>3MftLJWAV~S4Ci@+UL_{?d%UiP< z)H4%lDc! zogLW8UJ4HrTUM-%pKG7o8t_o<^qq5fn&C4kJmqn9&e)dReKn{o%;D^3l^h z109Prf{~U!r#F)+`hOJ^t)JB3ZaP{Z<1|b60)pmG3It6J2LA25*(-RAEh+6_!a68k z1<7#qQYFo6>UY@#bo;2@3HSz%B*>UEws4JMd(C25XB0j*4&N6JUMd>35+6(o)EjeD z*FkBlCry;>HHR?yI%YEaD(|_hT|DH|*x^Gy85obkxEDoWk=Vi|@55a3`w8Aj`=90g zI`rWfa#luiI+{E=OoR9c@s>~3;2DI!wuPxLOA}uHss6v~Qf#qUL2^m-H zuAZm@b&N~lPy*7Hcq{k3L+-V5d87BTvrzOBWn}lV9U`zL@G|a90@i~1l@v?Nl@$By zkSEw$lZsTgW=NvYyEB2oO?>$$WwTClF}gRl zUAb}DKXVenyMA5cjq8O$n+78-m;ju04J8P8vpcq4_-$bI|8w_$$+OO#z#y$c(}}x0mn3?~jY4q-@ z1K*Na0ol?JV`*3Yi=%T~fqzv{K{u%8$>G^YwXaoWjO`!?bI~~sQpGEDa?5p91j`t4 zbf;?tDZx371jPE=S{Yyi1Z?D1vRDG4m~#_VL$EB8f|=tRm;bJ+PQSQYk<$zUTEOG8 z8O4QNrHZJdPhvj?Knj%MRnqnEHn(VXDDQ6x13f<&drw&{?25*h=`f+yH@tB$fteeq zfUQsJg|Y-9Q(4**dGx8$#IcSy;9ZBl|JvXH=!aY;$I;mwymvRN<+@X<6Hh5Mvr`*r z8~LbycE0#R)p7QMgxTulc?aslqOJXi=QOs+<_6mEk3Om49({5*Ury*W{<8MZiEcSxf$hWtf+T;g5K8%>nqzVI2%f^S zDVMezWGd%T1vJ>eh8nOjjOo65qj*${YMlU1`^%STKd!>>u*WH}BExeP+k?w-nFxa@KtDluQR?0-WGf@`M^-tzM`OzAv*nWH~h*xLQb$IG$V^dkR5=>E8m`|Ijk>T+)EE0mW zbBhhHdC2c7A_-&rxl;X5kj%7Od7v9+YjS1Lo4HaYT`-(V@RRo0wvq~=(FDfmBN_Mx! z79A@sgiChvW)5ytt5T;ao<4EdYwtQzC4ONcyGsowb^c6=WGu%^KS|3Td{Ied6*O<-9j>7Ku zPMBg_M4*pH;G&O4kX9a+tX5%_RF-&+X`%0dkhf?;?V^Agim*+Mh1qC<1#EBv8@VWh z-u8rn2%5uUTCKGR9o{qvAF#5<;U$&1QezJkq#UX9K_4V9ayi+k)rWL-TL*acS}~b9 z2E7wh?hR%>AQ>2$y}-iUV{4aH%h755$eEuSYn2Ca%z8!(v4Cx$WA?%u;haVgO9|!8 zZOJZno<%nQ317(zT|)y0~XfmpwtkgUEy4+rb->js~H4)O~Amz+wXtVg^NqwZpg6J4H4Xr*R1U_Il@0 zyPiQU(XA5a-u!&`ySVdri=%mHq>Vk7#fn1tv4wUYvA#XGS8KLy)Yv9a{e~)K|+8K0Y1zr7AS{=K?cu(pH-tA!}Ia9{!QE0dj(O+FO@CskuC+wY&lU zCQo=`HxKdrlTL5*$JEtDEm%5Ek{y%xdx(teO+$qSn*)WbTevgh^|RA2c3ww2q3&}) zMxcegJH903+QoA-Q$4&<3!7oRpQ>EC=du7fLzkGZ;{Gb%U7&5xjB2v_ZoJATMw@<<-{#Y@XPNj+W}#5EwVu^a~l6N z{_xyB%86#E1~UC1{h@j_#|4Awp~`24ds9LFA9+E3BhV9E#yZ)RB``v(FR5zJor@wJ4Z7 zY6?`P)_P3Z{I16xU5SViua;WvV7Ai=wHV_SJ0t2fnsXCu%#;f?6+-M`Fd$KLQRsvimIQ>l zw!ZjKW9xl5CjN$4M*Q?N098=KLWaJ^R>>JrMhp+v9bD0hViHCH~-dDV{(fP0;(F zY52yRIJ;_JIIf!Yvu6vJhTr)=H)U3oR7L2r$BNmrCyU$b2$Z5 zV}7{OMr>$HoE~S1yWig&DpB-!f$s0tNtJiYiZ+S`U#%7Y;=k+Ht-;$pyuVzYce^|7 z^>eJd%G;h! zer?Lb4=OGiMqFj(z0z#55q@HI*_Cp4F?oLzq_lI+m&X_JdQ-+i9P6_yXnMY4;0%-d zPN=F%a6Ktn8NGfO+Y)Upu&P7za3YXKa7gpeU>g_xM5%t7>7u$lAWvTwouR}N3VnsF zW#Q8ZjAc;m&w`s$weYmMdGnm}x&YXpC=%Q*vRS!Pzls&&TSJ1$zL2@TK3A%Xd;bNI zcA=fq@kOiiY^hjAr(Kqad!{rx^er~4=1-~-vX}OUAlF`>DUY`$yW%4f1 z=8fGp!f_{-qEGf_awiTc(EQ%3DXv?K-U>%;vynCQqB^lOU(k_jRcLa!m{}?U%nk$d z3}d0dtW29+t%kT<$RYN((54=Hj@s9Q^9v1;odyCFS1ul@^mEKAC_h*{iZaxbzb}WW z6s=fGI=nkEyn;^cUGKV=rT*$$m_u)hZbzHdBrq8vHoSG=@KWKUe7eGMhKGT!*hVI! zw(^J-Dl@sMo0=lAhR}pdf$rj}n94D!5KcFn|BV+l}+oAPUNg85)6;yRw`Wzh~2ZT(4vrAoiP zgV7V_`WILWKERQ5HAPdULK>ulRDzzy{VhRM=LK}|8UwHDyTQ<+&hRvj5I1GPXWF#& z880$&1L>XVhvgx1eKVhps zeJbEviot|77dBn#5*e=awqINsT}0KEj1nIq4-qo1g)eXlnM~MWODDXCJ_Ctc@oUQu zvWSV;y~uKwQ5tAASJg4>6MZaK1yLSab@YL3*LqKOG*rVq2P*@M!zWyuZfHh(a^E-2 zD~VU0e&5AOEp4>{sxbf6v{-NJl*di1LJ5LSa53dYPOmj;C7&SM2&XM4Uh(6A4Owq=8aCu5=U04jg*_Y`_yH->K8>OObw;;?k4-089o>u1?2^4>Y%2R;x=r1EO(}RXE+sK7M z=5+G0)9#{UtHv_>Ju$pnI!X7)iw`Lv6LQK5;myVrKSCsovnEu!K4SCiF9RNe;Czx` z1)W{Q1jD(A9zJZNWt*-m(3|uMuKdbYpuy#-*^MBX;rA~g{0Mr^i-`<6oS4Idv}Lr; zbWp{MC{a&1?Fft%=1CCW4~d219GT>Fd5A!Hh9tt}(!raN*c1a7p^8&?#_`O6+-QBs zjj2C!!%Hd&$7HZG2;M9c6`j0Trp^||Y$l6Zo6{VP1}34lnh83=55R}_MGD?^FHgcl z3f_%V71hiF>#qJ++=U@&++A9Xv}Xv~mrt;WQy1_?lSrgcAA`bV2;XMBMtrjJI_e7- z7Hoqr%Lb!!RrFC{iSJkfaK4Ctqe$dG$eIJsVQD zm&)yPkOW_D)|K`T*gMX2jRrJz-N9|>43Tn1{;t_C`Pa)r1B(|PQi-b;Tvq!QU-A;Rx&Iu%)XIci@ns(pKT-(CrCZ zuz<#o+9*R#GBUC(%EF)T!oN$M(TSs#Bvn!q=)iySR?1&P>?VwBAG=53zd zMTBDP7EWghdg!n9kk*uCh#o$QxMcsJH*-jDlhvf)-Or%>j=LAiuGO5wMtHU{GC{a`%4+CHDZTO{RmJ{^KG) zUw$mfIm!JiJmvZwF&yUYFZbS4ON|Ry_XxusV!exlAxlAflSvMr$-upn8(&oZ8{fS;}#3aCuz}{-a#j58KC^qER7;~jJZ=I5+-{`UV9dvn9NJK!m!?tvfo3*EK5IM;| z)7*I3=t%7147J;B+jBr;uA8fd=Po2~lfs4Qj@tEXI}#pPt`^&C-`6*<@Z#%tI)Q6t zRyLX+5#3!_*cPSzr8y~r_!C(cU>$^`(~FYsy`Sh?7}2M+r=Wi~L&3U1fcPmDP?U{~ z@l)0X-TjkrWbffY@qNAP3?l2#-b(rv&qyW03Zl>h&gjV zjiRCf%i3Eo9?CCxQb{Q|{@G9j)!hQStUfk&RnA|aO3-@1iA@s|)hOTlzq;Lb5xl^T@b3-={z+zOf6HIQA{O`Zs5%5?Ln z_$7tEL9tpKXsb}{hN(}|?!u+)T1lB-55h*KbY|^L>({#9rD%`cqaN@Zp@Or=U6wGw>9&+XdA_X(el-)+v(;g@ET^2`|W+x z{Uvh>pEf0E@NOBcxQ}{A#C&QjNl+M)_u^|<{O~5P3_EAZ`l5kdsq|Q|)U{JJei9)iSqO_e-MsYWBjQK~1JH+Jev!x{W^Fq=)4{CtAO zBcxHeCz{hK;oTgYq3?`8D>%rPzSEm(=#xl}E zs7Vy~@amJ)2A9YS?RmsHYK|)Ni)Qbm)D48>5mbUiZ&XAHS{%8 zcdf5U-bT6lB#ZCD>B+BQ6TFX8%2qms8lgQ#oDEGl@BXnvU(Rj8FR`kQuH8mzO31Ru zoaYx^t0Y;?RWZ21A7#Z)?|q%cs7=)Ra#gTJC-OZ$ZSHq8WnNS9q!EEnTJMZ9swJT9 zf3B0dzeyR~Fm-|NOtN;wum)8H6MOmQQVaHSWD0ve=c||- z)wtAzwEwv5xTTVh>ukH}vkeudPm@%8CfB8-?toTGE54b9(cN+gmq0?+ z4~Pb*EA#=aD#eTCkg%kP5vYVLuj-Fin_7K)0cp0Bwd$WbwU^ z$y@j+fi?PWR>V0vfNrj&y`*%k>(b&N){v+5XWhq^ge*D3%#_N$sG0SZI{!tI&9gqQ z!Je%!PApn%l%G{~WxIuja(jFY`2@ zR3U|SY471(eEHpPhX+M!|@qbSh@~)oynz?&48v-OG8`-0{X~SOrM%x@6Qi$ef`-xoxi#& z8hN0_WVfFl(#1^a+S@xV(%D-xbaX^PFzpusd2GWu;RO67?JEa-)y1WeE~a_)$}9Sp z8go)&k_5*#<8daS8b>u`hz4B!CK)NO=3duYw53%Z_Oy&3nhHiumsuajgUh8HUMal$ zWoiEVqp&-BDJ%^8m^5k3v5#tRvz;r%!t}#xDNSQ*)1hefzuZ*by>MR!@%p!xxZR)a z?l*B3+~4$S-e2_&-rVhdU9MD|TLj*I%9gpun*Me<_w^pHzkh9BAk*HWBEA$(#PA9h zTYULZPqkn8un02V771H?tj5LIrQJD=-+Q9(dtQ{xC!;OPOf=k6Hl;(jROPj%6quY| z*>!rX#{GDa9$jj+w1nqRLMv8sW0{wAsX5>!XXWfgX606A3$?cRqCBAG92${drSF-3 z-^(8uYmm3&mpQA+e(ta};10JnFd{GuvZj%k?eI?DV?Y^mHEWe|;Kazjo&r9fzPG-y zqp&x06`9o!53METAkA@pVVQG1JSV=Tv8%S_HpKURZ@lrx9uUnfjefPQM$5TUjtTLx zhWM(n+wV>Svw5x(vuHEYInEVTB{2Gga_0e6PrvV(O~{^8yvt_8Ro&7Mp>#dJn~60N zo1KpRu_ww=3N&q*duI7^4*2w=Hu&QARc1L7*B|$?ow@K?jU{Il47Zqrvw7lSJ!-F4 zR7AQA4WKm}ng`UUoyBMf2t646@ZE0&;TalC#Gw_5UB{rK#Uu7#gH&UiI~i0$N@yVo z%k+#H#kDM>o(1g*E5Ol6lS?Slr%)A>OGM+bKy&K#urO)sPcYy45hlA`L5zy+5O!sB*z{U)1F6BU< zDnSs}nie4|)&)LKY}X%-20%xjVt7Oeazi=~xlk34*FP&3cP2$JtFT1a5xoA=tau&W zOi~&KZ}tM%(dg8xpiGJ}Wit14%4-e6qu`9uSESo z9bL1)=FYw#)n1G#HGPeYy2=+Gr(A=hqHVH#Z?%NiL|L`q&ARK2K4YNHNo+zu^1QT@ z#>6A3<{uuuig;IDz3GI2F%@t2wVw=TEXhS@D9FYhj=YCEvz-uV!dY z1##fNxm`r+V*S=#BB>7O=wx}DW;16kkLFTt%qiL7TM>K@#-B;eNAtiQfN8c>$bV(M z6oIr@(}zqeB?t)e{}Sz{nUli_tgzC>DiT^j&&h+;jS$Q*LQWVx^lyWkAHx6^J$12J zKBh80eS{oX^ytdQO})e(yVR6AVF>wKlD9q>9-^aU=*lS@G4MNm!3WSdtMbOsl^Jrz z(9s$dl#qGfii{w8(|Zu|3w#jFBxgZ*2^7Vw_C*sm&}WJ{&bSe^=UB4ml}B$O31xwM zl7zK{w=_nBVry2F*EHhOyz&{<17&GGSVTwk^k4J6@o%0mYiPh|h*eG%yN~Xr?^pH0 zSFNR$&=NF=R>v+AOH}oN^*}Jo4TU$$1-dCott^{u9Y_gjI-271|He5d?ha~xtQBq*}ikkQlsV#p8|7is5#%petuU@cE@72s`a+2s_QC|2u@! zCjUnGvsDx5%9Ul4-v}>tF#dz^{K2jFU6VR{=VWPk%0E`&cM5EpCt!kH=~gl!v}CS@CYEiG)^%H)Syc z3iKzlRt#lM4EUWX;ImmP<`f+?boBqC%(p*c#_awtaqd12k1-X8zlgw4n*g>KW>?DM zlU!m9W&5B8>SEsb#O4{WqxT9E=*saFA0D9>fGKA}TeSVc=yXP_PBQY72EnYF7pSL@ zgiL6x4OY~R&keEp-Ce#k{}kN~yAYtfUzd@xe1{oZbPQkayNCQL4kS1S2bj%gP51;s zXvIB51ahuQVq*cVGk+s5dz&6!*N&6(h~3HsC4Cp1Z|&9|%2XT~=_ z)CQXV&1i(+J^ud@y;(#42HXEvfA@d=H-EqVsPIir+b@eDxtWjn8M?CxrvGr>ClRfn zPxAy{(=~sOz?Jh4BRI}EK5UV4sJwC_kJ-Y&nzxW8pVyJI_PBjOSsNZP#4~{UEmEFB z`8NB4vQ+8Sm=h5wihrQN!JF0K(D6*PoeRRK3dg)p>N}O)_W~+xgH_;!2gi~S{7NY; zQ_R@850B*nyrs<+5C>OSO#ioe8i4;~^!?rTPrDRjsvR*tE-i^dlWIkKmj|Mi)u@PI ztQvexi~Gee^9}~*&OPd|j7ZFtv$ez!r)wi1%qrg~VU6KR_FY?T?zk(9h6pW6gFpJ) z00xQz2QDEh&asbMR-_8_DIytGq)~V*{#bkIY+xZNXPi8thzd$$6ImimgQOUKA)f_z zT!{KqweJ*>&J)A9o&1|Rf5$4s*M-^lvynb=aQ<&ba+Nw*zC=2q<9(I2_kNReWT8Yx zQ9)WqDU0qpo+ToEQp+Vll{)rW9O1{nw-13^jzg;Z)Pi|*kVCnmnBVpDg9W#>p;ggv z$~VOEJrsvYJQdZx5tn;znBNkAuAFcXTM^h+j8QIFdzxok-JTmY=n>6zV1oe#Ti*Ii zu@ZL?hn|-2i)!x$0X-dTORQmS#nz7OD$FpP>?W?t_$LONuVNCNs;X>SZ=$~OW{;Q# zy~#j5{%-ISkHbVd#GIrL##Q@vbD;Rl&634;JaH7Ut=^xdFG#~-SZis7F5mbmQk;sf zaT0FKq?2=G+m4l}doT*$^-;piF)Fk-3afY-&MUKOh0wL}6(c@BqW%Jxr-X?Rt-i78 zPBlnxc;G%Nyf0(?Fpjt-m zi{v?KP>()amR`-|&=Hi#Ok@yGERKVX_#&LkKa1}sf8Efsuwbk0Hf<=}fduIn%W7*f z0Bwaw6ROT&K9zifP84{DN8~byKveJF+!Eyf^7&UNKQ(<1bt#-~+iu9|pENDxdLCF% z@h=%1$WbzO#k!$rJH%t#USh03vI{2D?k`VUv@!v|bEEOYlS+7jox+%7ZAff!60w$oTznqG`7^Nd1`AzYFhJ40pXCN5yoN=8UHW(q6+S2dYyl281!WeYp> zS7+Q#$X`n8O(DLfu{!V~w>qGJgnMSQV3migme*5kkBVQZdP()t8(B@K*;DvUiGCf1 zjoI5n3}8jms#?(n?5ktkAO@=5UbUn zrK!KI`pfAIYdy7kbDG7|7H0AQi5l|}(&hU{NUaea`n=O_nP5oF2!DrEoP^cT5tC3s z@@kctYdyRnBTCv+xLbn)mf@xM$+JSjyCYm$K1kGMXlkTBEt^c2XNCzadI%Kphjcy& z_(BUqwy|#{aEMAz$j9TM;JE#Qn;}-woE~tEh7A23*A1=p1Fi##8Qbi%pfe(0zaCtN zc$e!q-vt(HHr|uO<`y(xAb#*fk=-6`1@C=}*7Po3B_dm{Ml7Je_YHzTLR~bf-W7XE z$kZX;tnKpBh1O5+c8w?rh95M#_`p_ITMs%U9H(X>2_#&5j%+E}u=VzN2I{0PSW+&L z39z<;nvMsfN!q)&b6QphGzait$&e?HCd9LQyh29XV%*D^J4;7v(Ow$+xbe!vixkZn#XAqym13YbpXZ zqJBvhNdANLnSB(uj*7C3t@H%`D&hTV$4Eo8E4-~%9t+24Lu)^$%6a39(1e$F7y*!Mzzb zcX?^(k!3qzhqG=bz0M#gVyi(sNG=Rda&<{$+|w%ji6ayEcRT^sN_di?>DY5U3YGAS z=O`%D9)9xfwd^<9XU<-WsYzop2Mg(G2qZe+PsZ{Q4p@RCHPo|D&UjE3wJCOL7+GP^ zSa)6-VZgj^OP*xBIiOB3d=XmGEDZ0w=DW5p#phRS$f~tS4!aX;;oWS=Y6DNwnL3CR z?8+yXaXj70#|%aV!yiEojrRIVMYZ%Gyn|oK6qUpZ+AcSd;SEu?q}SU8@^Qa|aFhLW z*f!xff=DFg7U8dl`2PH_uddg_5J>9%D+hBo(ss+VpBybwgjb34d;108tyH!H@9kL~ z3Oj{m^o0ANKi#&e$l7g|-9eTjjBG=nqK8HftAdQ@s4UbSx+~@{6ul&Tz!EB~p+$BS z*BUy=iSC3z;R%NwAnA+Fd-6dK%ok3udciBl=Ed$Dn^H3CF_s6WNLz(-8|De&(T+fb zjz-6+aJ$gM+xjLG&}S^jrytex_s=%`4p=aDL2GV)eq^83;L_7wE26#p)I_h7CCm3+ z{m;x-Z4VZJ3$ygWmt#>re(2@8wI#k*nn2>CZNHq02^6f~e+_d!S9g8txdD}P;y6DO zin2)=LQp};i0?>-ukmd>-Usem8g?ArG7Q4F6ASK%57>@o0NXzJKppPmhj#$Ve8XSP z^1_stcPP%I>27(_;bh_dEK8H`c9Y*7c*3j6Wy@i+=F9x9O6Y=i68wd^t!9f?*xoZo ze~2d4m4!t`h$b4$17}i5H?>PDUhglO;E;On##-c)FDM0~wY0rla`3@uI>(xG-Y*@$;q$vnq^)ft-IfX0h$LINI|HIapOyUjyjxq^3WVIG zsaMYVyl;RLFh_XuCY|P1VfbIHv&zEVMOdVseo4La+I;|Z7jvN4`4|311KZoc4rXHx z$0w{!rk_u_k(d8~6sx&q0*RJ$XJ>dJvkTT)9YW*&>+;L*i9vWLJTFWkd4nyNPL&S# zW;=K=PC#poo^bAdOeKDf1%)`T9IF+E_Isdj=ls6UEAk)~`($lWP5v`|=Z%)a1GajV1K&jD`LFkZ3DcIT>fuHtgM;T;zTO%FRbF{~iuj-o9$QUqc+Vpiy;3k1Ry{T&4DRQQUBnjHY))(?f#>9UrBTvp!tile zP&mXw-5Hym1VYq5F3`Dyg{hVB*qo#fzn*jI*`QDe!C|w#^+o4C34d$clO~Llsa){N zu9-Xn5D$qpJQWJHpr1Tx+Jh|xqw?W=8zL8zgvCe|9M9z35x;;hJwvuaaQt{eKv!q?fg%WX zT@6OEG<8qK`%8}^UjQn(mMk)!-2u6D(es$^wbE875RZT$BIuC;KpOxcmIpwHkARvV z03kgB`tk@U<8OdO{LVlQcJOIMThLn=6OnNheL0622-m1>jy>ZY5*E^K{-~IT-?UjQ zm$c@@hIuG$Hmvd-d&&Z0T%ImHQ@bSMc7$T4mC_21Il++jMy(~xLT3iL+o45{(3lJz zbmmKMPs)@j#~wL!SF$J)W))D$;kOJKN|KCcUZ_-U^rfn08v?TBWODlTB&pnJYo3k8 zfCoJ^x5PSbW1PfSg?i{1++%?;R(_)_>PIWB&#J^<3Be7oTMwh5b)MJF^*8RL!wPRK zq(G*6J$+?Ytx!!xI%oN7@hyCe*=ocFdh4@}FRQ5J>LYf`Sgp?<|8W;+pLyWIv z@mm&I8f{VQvmW#X)QsUF2yY45A9|v#@NZ=Okl5tjPf()9{JrNU*6{>jVR5$`_2j%= zu4yyIV|20^{ssyI#2;YP!-BVj$|`6AV9r309jpqB))U4iR!o_=fLXn)Tk(w7`cm!1 z`k|F>PpIB&Q!E4Z#Z!wD9RIHBrrSaW<;XDapA?4Q_xRK9PbaUd=BJx98}0;Fh46Bn z+Hfj$I-!gOKtg#%1Ts_}BHGj1FN){Bq}dTL+^RceLg_eUVLEnn;fcJTz>S7^1Qm@9R zVG4S2U&t}2;1Aw>J_4XE2!-DHclt`9GBt`75t*|nHs{It5{#FPwcsZ9tt9RD^6OF|;sOYu&&@q0SXb!6{(!8^0P;5JwKRnY2RpYu^ z$5Cl&BQwqbM8(nDYWVdp`4GNd<0()XmL}XWRvF#wGI39s_}p%P3mChYz^jDM)YJH%9?cFo1K&(r{9dURncoW?R` zbPPr1a!8RzsUdQaCK4L@i;f_cIb-+Y>HDV@N6?xVF=SQC(}v6&Q%N^O?Q|rgzi6c| zUSZ!|H{BM)938qK8itr*dI~IlFWofy6_^lkBZ`-x}{#v^C-8){2sZ>>M&1kX?RW6sCf=Y^ji+p4iiP7@ z{K^cp`Jz*OI9FaswB}Lh(=_ji#zk>V^)$|JbKg7d6$KlqrYjyMzAPR(KL0zRIJ|fw z5fQzSAw7~y#t*(I_K^r(@v4^$KfP_GCLq)MF8LDG(F;7;$WsC%GoMqEV(#s4=(gVC zL{vxxX7zM=U)N2CAxN=b#(wAp;d;{f*PV^#w!_)qUv)u)b}v{39dO1S+UKaP5-0qbo)okpa zbX5@GJ7ZT}*;+`-RwZZt_W5L>d@Z_>sB!c$ANr@{^O}CPnSk=1OsFY}!a4{R{eCAe z9<)P4k%wvOIT*#VYU= zB>xc}xp%Z~zdUHqbEMLlGHHCL{(}9EVKs?A=*hvlib9%Zt$QFsf(6uFJ~xudvzr=4 z0-5)tEK7q51uby$m0RyN$6dr0w; z#1j3cJZ1&IH4T#4uTW3EEGHiPj3h>fJh;;_LlD1Icnjj#8fem3zHh+3>0P%yE;yf= zxL@URL#|npiq30GVAxjtprK!Lb*T_-X$j-*6!XLF@c!!lln`x6bIyyD3+oQmZh`pL_TNhVNSM=@!N-=l!G&doxKKJtTwRzb0E|ehm!KS0k{(0+P&6D-0 zYQy5Weg)YSm1)FuYQxz|=9ytlW_Ooj7lIiSl@Wn^!RXtyTP+*I{+iH}_rh*)^20$G z{J+K(b~dmvmQkbd#BWc}P7ZNX{P5^0Is^SnD0K4u|84VE>eJ=yCX*z-yW(ARUD0-B z3|2*vU~G(k+vJhgAv*1H9_^YxCi*YK{XU7c-@D-SI|1XXi*0Y=|1#X~lk5$#c5-g@ zE>gr|$+4xoOxN+F71xofw_yotT~IoS2*#oVW=*>y(*K8wV<{`+r~5 zBMM?V*3d0>)!Ws<7{uabQu5)5pc9z}#a;r+EAdvmPExw)OiVH$Wa(UAd zawdBo+6U3du-Mj9dG}VLJBdp zV06}GRY^j9R*=uT;7YuLhh3vaK^TwU0mn@dnzK5~pLNRMjGD0u@s3sEk!J$Kv~vL8 zIcA%)3Q49jiuoJ!R>X4t)Tu;@GA{2h!Um6^L-5C!02tPg%GlR*qc4Bz#Dfoi-1C>A zV!>EO9Zgt|p9f7d*(Hjlg6LCu(w)=c(#6wh(hbvb)0NV>($Ar|-!Jn%OoV67swxU# zCf5P46$}E{BLpmUI{oSL^PsqY%>Mga6AFJj1o-ghS|9lVh9udN3yKq0>HCy=^Z}$( z9_Tj%tXSAQ2xBR=vIG7Q*ykPFSsREa&1gXKckWmx6dnor3){)6eg6U(VB`<%24O$v z0BQ^X4xGU&Y51Mt2U;F>ff;s+>;R$;kULEGM+_c``;BjB`AqA`j=sOf=x^Tx>dEOi z0c&F8Wr$Ffl8}Sgxfq&Qn3%NKpcu1Qk(i~}KAc@*C*S`I!<+xpG!_a001`W}z`$aA z5Z<5b1!5)5m>E_YyDPK`FlvO2RspQ~KUqG@mIOk%dFpq^tRy6<`|;0s>wfG2EASx- zV1eoo>9aQ64N3opAReLtDC6;v+2524R<+O$I0AnVIYsz8Bz?>On}%!uXASrM-!;tk z|H7~eka3S{`pYr_yy+zkWLR!kM3-)60Wv}^ptpu(+z#*|>D!~||&x2TX z2=rOSB-0r>0e36I3&kUN5wfMjSNJhg24`8J9XNmjeB_^_8sfCI(5LI<^PjMX05g!7 z0NxhSP^5hRcS7hVzCKhOZ%rvkpxjoQgF!Xwfv42ynFDO3$ATU=RirXNI+(zvbgU zTng-gV8hFMC|{E4wXvoJwd{Y?q(9~U$1#s34p7sBIX@JphgwBqqSi+e<@Y(VLw)*h z1?xe0zm>w@)oZK&*JALS_&8Q=0}KPcgbUF3I5_j=&wyg4 zSi%Kl&_fFRHHCjGf`$KcX4gDamC(`WcFv4;|JH$Y8Q1@_@chGOcVxf@tPZYJ52f{A zDsmQ%?d!kPY-OdtR?*+8VzMf-Uy3`|QsUh9uFx~^x*iVtH>(EQh;JETOi0$1ZewnPGzOvOX4GTE603rbMsi#|18oE%W($knEGGp$DdVm z?k{r!WtAheG}iP#p*%z%?EZ&iIu;K$y3Bz%tAX^dUSdsP`Ebb7e-rY993G1c*I&!Y zKUfFw{t5=yJAI%nQvGY~0=F!Gklok+AfN}o{@r2!-gum4gLz)-{A)wF-k(+u*7jqQ0yJ?uGI49L3!Yx z4d!3V84zrybilqo1b_?BpS%O9^SfgJ`H6N4a0g8F`!1jz{JWUJ+ItWLTgV=GuHRd| zKiv%wg+tzh_JV%v6#gX;zccffhVDVUk7n|lc|3M>>i@G{#QonDob}+Oz>;7E@ON3cRj=xc_5L07QQxx(zqB!!6_AawGhpV~6{1vIn{) zkoAc$Fw9O^?S1fnNaV5VJgktPs`E;i|DkDpXx0BMZs1d<^z^*|0Q5B3lP zo=~@LAS2HJ^tXp<{@?*wL;fhczl8y);=3=e$bk@pkL&#X{N|5PKPJ!PXm5fmV{c{7 zQ~o&70;2wBsRdekfC^{8{f1@EANu>>`_+HcqTkP^xK)GyyDeD*=-Y)0()XIwksdK@ z|3~&bo^1lNJyQC3z&{Q7ky17Q8~|OD|1UlA-$DdV_FEO#KbBYvKGFNDfjyo^{SoXz z@G0p-hu*HN^ncj<%7CcaH*ci78|jkn?oL5TK|;EuyBS(QN$HdlQ9wZH?k?$WP`aD< z%<$xYpWS_T-~I4@*e{$pXU<&lyZSyiGymfH;1L#V$KRM{jcu{Y0-d`%WJLb6nuY^8 z@%!pl7$E&Lx$8XEMFBwqP87dWf~?JeV-YAsV5zu(qWaKS{k`4!Epq`E zuXFdrOu$ndBoBTqfhZ9nk`-!jqXhQF-xs?erQqKH`ZvX3*4!sEBlz{ zDv1!uQOom>-rmN&@S6SyhQ~)SRt@9NWa59BP&>mRb0HY~-=@_KbN`at?^u2uRGro+ z5A*3C;~F?wfX7#0=HmkwGhnbgcHF%Uzy`0K{5keM5CuNF5zxzxUY<-s>N@nVvn6;u zhTMk$EUuVx@PVW3_X+jygRd(d#%W5&99RR-k7gX?ldRyexA-DFwuA5xiyD}Fsbzr) zcmX^zcXCD6K*|fidv%5uAOu$IHzog=sWSo0+$3*f0EPfHV8pKfb2^6bp3oHjQJxF~ zWO@pKUY5=MB}_EH5;EHUIr@4-CTWbwY_a9k-g#n1$|E=x+ZCUUyb?@fGj_ki3V}Qb4A!kM`rxW$A)&jg#`k$2b zzcrVC-VScuCdvE5fMFL>7QrPLKptrQ|Kk4-`RBi%>HlQ+TT*na`UIXrfNWXu$CL}H zwtr3sK)S1t>mn?LtfJ<2AkHr!{?l;v?2Y4Xi_b%mo%^S81)Kzam;8nQ7Cn$D|8=f> zFal5&$Exo>i_*xx?7#bXT}u9+Ksp3oKm2ng0U+{wkN&sx_MezV6YU?tjwS@eB4?$1p*!pU0>R;^ur zh;V3Oydq}$hxHlohzMSX_%}uKkBkiNCEI_a@_%O#AOruI+99s}C)#9k_l|pGY?J#z z*Fw>LSL62nw}oPN=U!K1174WkZjby#BU#JHNHg^VFqU?peTdBnUXc&7Hlru#2i#vw z!x4Vnf!?Mm39~YHk5O6ix-oG<_%#BWh8tDTi;nEuqsVAK4KLe42cL%YLQbD#Z=p|6 z`;?>P#aEO0#LY_xzWHTDFii?Rb%=qSCe2uYsa^5xjF5gdT+Yx3ld(yw5R#{Nyd7b# z3v$7pEVUSbkYf_a6?)O6$W_Hth;fzg458;Y^1=-Pkj{|xJ%sKgrHp%--+L7| z5SV~!&jSIjatPhjV2GH8Z&mk}${QuJ^eNKY`>v=Q+z^&&3?|McDufW}56c@5lIA7& z-z1$jls??96tVZpH=h>FUMwr;F8Y>rxBTvr|CuUS*4$mlP500EATo=wyxn_sThR`I z%s(O#B2*T+8AMrndWg(-DG~sLSqP>C009v1Y8 zv>EM6f^U*su-Ue03`P~|^Wu};n3I4@R$WdCLWz9|D#kNk^$J|D$KI`T=0o0OxOGtx zN>l(GR2xFtj-5nN7)DnU>X$wY2g zz^4H5axz!ETbxnw3;P6!VzImrMm2e`@d(}sX&z}GEg=3cf>Vq8V88}!7DEslpwv9r z7JFj{y;UK7^qrY*QwZ-Ry|Pso=a)s{R50XYSL1Qhq`~q0UkvG!A1>fIK}aUJF^^q^ z=uC@IX0%tDq)e0|^xh$X&5jiRVDJI3e!&;_3Y z&=#DYHf&`9caL55YC*s#-8Kd6V|+!{2k-&Y0A$K1{hvN*d?5PU;ZH{U5B&b|@P`oF z-Vnk5e)v<&-$eh{gA!o!L^o!Z-50tuUn@^UASb@j`T3+uN{c2|R$Zf`?;t0@ZH<4N z{PxZ{rO9ZLdlGRMXW{cKd6mV^qO1N>K>L z$6f@Uz>JX74<89)8V;Ts_-xo;u(F-u3}qf_62a4HEc(3JPIj5qeE}ND3cwGyDPU4O zQT7M5oL0M!dPkVIvks&VjefoGtF~EZAE8aAE4gLh$3bc*qMalg)T9N>i%+Cg13 zreSX6@}sj8PWdoIHP>`jWypMyxsad2`VjOI z$s<@OLg0$WYc_X#CmUx=Gcy-wHpqd8)x-96y2fn8EIXzz+X;E_g30u|T^hPUH8-8w zVM!e?Pc2gc{IAT~YOG4zP3|;?yfOK~Jl|y#H`2Mdh`oK?6VU{nY=f;)9>Y<})|-98 z-7RSrYZMzyBqUOrjpO~a4(GQFzi2D!_aZA{AuZK8G9ZTsuH?(ElO$?!O&;AdQhTF9 zHC;87QZG5>LID;Ld0raywkUZ<-8rtcD|~cK&A>y14)nOH@AM<}IruAl-?sX@>84p+ z;(p%dq;b#+Wlu%OP7$a^#F}1?m1w5gk#t`_rcKDH2o(yo5beD5?VGv<27HzJKRa`R;FQKMSNJ_>^(eaXf9*LN!Auc@5ZM=vE3;O>C04n}>w z7V3acXIEW)w=z(R>(I)|l;^3rr271h2YC!Neqg3*ShYoU!}#6jpN$8-3&#bHd&jWU zlX)-m&j!zt+NG9w>X-Y!p?rAt&gVpxV0gO;fyLtyDJPQtpxlVu;>;p9qo)kU+Xn3c zw&yd%qPaBkD=uH7R&b;1hJK!;MC#ibk!Ve~yr3<_`xtFgR`27v6e?jM_4!dYC1L^b zvtTTRWzpwb%3fz@KZ?J|et+&OetPHdZh?GfsR?mZhX4HQ>GS$GLDa|mWiYIP{%!tH z&+IT9%*cB&;rqCsmaiKtUOZ)(I+ZVjaUxp`?eAQB#VNkZA0Ef<{Jsf2@xu5H=8wSW z_qDMn<%>JpL}kCv$$bQm9+UC$dX9!3{gu9P#>n=QvWyf*H$y}N8I@qy*KJAt%=p)f zNlC_ES!wE~t*7k+Xn1uxO3bzKveaeD8$Hi|ot|FDZ|-OLUk}Vq-oIWDow7Mkb+^xK z^0K&dY0}@}X=>#2*WKmOCSPdqznz^v9bhXlE4|dN^YL@N-@F&C@pE^*?R~a;pZ{{# z_j=$x>3R<7M$1Ag>MO5>l#Ruv`TLFH#irYhVkQa!=(zO-?O`WW7N*w%hb$zo`A^Xh zrVcV*d(e;!nzm{2-e~fsUxz-KR^dI#TV~>N=J%Z!9t;bh(VV-4GE)lF^np@5V2X|j`JeTh-ejQg$itY2*ml_IB3F*#>StpTj^}hX@ z*I<9H@}0oj-|ucVt&}{q^sIFz+6s%BydrkKqT_Scvzp*XnOBWc_v4&S8LWF*AN0P& z{!-;*OZ65rY^wHjy*(CTTRv<>s&&6?>sT!`A^3Tti^8)T}vS ziQ%o!u`x!YaN04ws;d9gkm|R6e6AhhG+yMDq6^$OP*1m!6E1oPhn7eVh zylT7VBVRzNWouON4IA1Q*gg)b-s@(n*KQ#j`o>eWOS!p-ccU!UIdl?v?OV4$ue>>M zxq#6%yPxI7BaBfnC+6dHw*<1ElgLe}*p2TxkGUuXU7Y_aJ~!ko*gvv#cl5cFIUd&@ z7+~Vc9Y{;l9{8m_FkU)jcHF~ev|$!842BE7HYMJovq#jMhs*iNg24Yie5-AhK`D`#PKKI}7b`5CJNPD#^i{TUJJkGsUYAFH^>wj% zzQ4ctX}tM*b*p=*aKVtx*3 z@)G#F?UZo}Wwa9b@?~Y-*S;`@Xt*0Qto!ytFuJ>QtWYyc#$Qj8%^ki%)s7mEBoajO z*1fi>SH(Y_ZxxS9a*f!W)ZnjO3pwi2Ig9(jIi4bjQaY?-nuL zl9y82Rlns9^YwBeZJ2cK2*(HD(VvX8mS$WvDrELthkmwj8U)>8m#Gxm;LmZnA`QX9 zI1g23r+0F(e6Tn=>Az+k<`MwJ^`g5!iLyXe56V>FP45Z)V&Cmew;we;;$1!cUPM0W zlpGHUJ!SvuA(~O@n(U4mx75}EI?i19 z!IfN&eF6zqe^=DBoS?M)ad0Vn5U7S+M@?l_ zE)jU*<6Z7Hv(u0j>X%9*cY%_gF88-IC9vIu@{+HXf_M&g(iwTQdRrI&V{i~9IFd>L19=KPsHJB|v{mBg|SYj_#wkpij`p%y^Q7(j6 zu(s=bb)hUaAJFe+T$X(GYEN<^VXQjF)rB%Mv*ry?Ehc^FmK4ECR;DARk@av$cPQ6% z*(ut4R#Qzk%Hq!`3_g>`3A*wGl9#mDL^<&S1d;*WKUMVPWu8gb#Qe+-cciRB10LO_ z!h}p21)^Z}41nDy1QF~$`r-Z2V-_eFE&wbwnD*^D1S_9k)W*10EVG(sI8d^)yHk?% zTIqGu)ncj+&9%epLtsGxV5yD)V3GVC7J_otx)|4qkOx?Bk#lYs895~xD%gXiWhUH% zq!>R?5r=EY$uMKr*lM(!F>Ox8npR}C#E19y$9jkFK3-RZJ?GdwYm{bYp_eyN=Wiv* zklduPU)dG-^)y{V$-dkQy_#>DrXC5kzoF;RI`_gFg%^(MkZ|WCFB~v9_5e7Cbo_i< zDjIz$*3*(o`Et_Ui_n7K0&)EI+n21 z=@+4b(4=Tr8P;&>x9(4mYr>+=7z3}9oxMw`{JPUAo*D3sB5Iqy@8EwbJSha4V``ZPRdXz(xHP4#D?-zY5RFj z-QT}h^{@)a<#CIqNZ9?xvZqF(vh&*3Ndnalt?V9-JnK3m?|aX(9^ATsI?GGTqOl7} z;%UW{$%|~==c{IY=uLhu?e#dLP zLCqf?-yWe@{scaIP^q@TBl=P6hsShzTPZnD=CH%tEUU<8O6Mk(PVtx!j!(lYgx)5N zyu+aj=pU2-BWt?Z@2=J(07f<|hFXm{OL^d1rxxL+3<^oe9EI-ct!xej{G`W}dO-A$ zRsGD9U}roY16w@kRKd4wYnz`FJl|q`0?n4bb(CqE;~Wjnp6@&?)1xcl3BB~{3ST(zJ3U8QGx7PtwLF^&X~SDI z$()uhF4B98MOgT?pRbRX;Aa=9UrLJhD5hv%9+>6!_9c>jlGpH*Y}52B7$9I7aOsop z#X5VZ?pgCFs3NGBNl%LQnLzZLH1__&CwanprSDYiQWIadI7ln5$6vmiAVgWMw=}|l z?`;{M*>3^+>%r`|^uuS~?61CCRm$$RLZu46XQL6`VOrA^^_l*7RBjf=h^+}=`o2nG zOu)&9nTx3krIK2$g0=PMkZvCuO!|Cr{ajTzcaKNC|6LyQ;@$f8xm1`Rn#|9+(&g8> zU%i{rx>%aYd(l*vC9Wo>Fo;?*k7#ERpYfLLIx>N%Um@h&A|?a>>g5zEo?Mfy82#!) zk&Fj1Ht!n*wfoVu`*FR^5Q^3fyRtZEOi;R=Cd!YkA$eG9t^9`0o>f4TnlIqK9v;KtET}x!`Og;YA z1;<3n`0Diem!Y+xA;=U`H|)(ceOvG>ZO>_#+rIO$^la6}d%E%45&)q#LT4j5EO{7P7fDi>RZI=kRPb84eGf@RYe zuDYB!vRi?*L+K^|X!TVuC#np;0=cw_P3U$P4@^goPN?#!XlqSWV$NubxVjaQRw78< zLZa*td2nRR#0uS*}?&zd&D%!ipS!(g-Kb0KO$7 zOIt6e!@EzGM2x;sf>(6XGI1){1V zTbp#3AsLXKDq*hIKyBhOLeCV;egs$|KomtcS7c19WA71>;w*}4Sltn)doLh#v!E3! zP8)-SKxj0I{gsRxRxXwu765p~4@2%V8l|WVVQb*qS1mX-TQD`%AG-QP!R*i;b@UJg z_6n}*!TZhvg^+TJ9^_AJ1*E1n~j}U zh)yV^@!|!P0H~C&;n7;2)1bC|=gX+hZpE^Z3RlGnEi+ko|9uoWWWCZd?AZwy zn%SN3YS;GXA!eTm3%{Xut5YLPdSw-&8+VJIKlAY!B-Y3z-elC3%BD0NntyK1+KP7G z=|7O8ZwQuQW4hunF9g*?QIQyukcugbcHsek{i8)$!?7f?wa3>m>nyd ze}muU#?|indP8AXm+mvZA4yM*aGlfE-Dl;_w361ufF&|9pEI#(gK488G4;|hvAZhZ zyNmB^uJg(6*2U}>?$>)3$;CWpge_-E+o0YZW;HF;*Q+Qa9Ef?I-5!oat7djkHd+#Q zT@bxf_ld@eyFIu#={anh-!`Gv-;`x(99<;8+x_vza&DnD3{pPuk`d^IslrSFBoe z$v&}7kcf=F*Z0h+2wU{`uf6uSYmJWn@>Rdd$71hfKtxt&kCc%0g=EGpc0v7Dy_<{M zv7n~8iPY#@cGXN#pQ}|I`_Wg6t4$j;j@OYm1^h-Vp9M8Tr{VH4RJ>S= zli>E0{WXeBmtb*Fy}FQARbbvr5HWtfQIngSh|!S=rJ}G770JTl@pe`4Nt$$QiJYWd zbP9ukH12Iai4K*NDW=2lH+57(@)wJ9(xOgBH*DMO`V+a@V)-m>nx$b)LVV4=9!9J{u78 zk8fgJ9n{fX+&cEwO7BPf&Q!OIAC&6&GDpxa#}Y`@Fg0AHOMPUvA8rh1?oax|q^+M>|}jp>F-7_69v$4WD=mZ`V_nc#F0-#zG#!>+mTlV~_JM@zT^KpX{X9 zS#Hnx2)1n5a6kq@tuon@t4;*Qijv-4*)R>e`G_a2t8pNMu_W{p=y=qV@86|c`;mP3 zv}L1a#7pDnIR>z|-nMnD>4^TsEn@3rcH2U>_iRflOP(jh^mGBd6A&8})# z0~t_dpqvn&l45N=C4_rn#5pWviQ^3G)sv=y;DxuJ4q6C&bt!HSvWn^%NAMEc!_|QG z5*x27DjN|3aAHn`_jSN#Vaq- z-rwS}NbcsLdM6JT7_Z&!M$%~o)8g<53265g4MnlrV|<^K3l6k!7zS|0s+B+w7``=T9C;+Ml_^en@>G0luR`80WEhNc=x`6o24*b+$-0RXlQhZO zS+&^O46+!PJ8LiLC`To@nyj5qp4YGJ3&F7(b7EW|)IZ1Xk)W|)6xy&FQ(4~@RUt&v z5VJmz0(B%xyp>*_|G|N$LBjf{wHG*ACphHtVqA`_ul52Qb!pJf-`7Z-BqIB3>j2Su z0BUlEC(qKF+jlT`PztdYAmQ>xR)~*ZQwe<>XOI_D2>_aR8(hO9EU=mK;#{(`766jQ z_G(m~IGHBSU=A(L&G-k^b~iUloJvoO;RLlST->0%FrGr!GGmO3Y-o|ZAdgK@G4N`Z zdOJjXR9Y}B@9ot)@lm8)C?;j9ZHcsG7=?JgBH7UhcNH3aOy=l36lD|T5;6tuW`W zri`t?whylWcwejw;C%{!_p$wot%X*wpvjEL143P1kh)ESCL{G*ize`DH}*u0!ip+G zYE;%&j$%9bc>o?=>`C_1eo!6|=hRjmLiBO0h>3Eea0MK6+R=I7FsIm7J+)W{IGBiDl1Q$E0vLx$`I=9ls$RFVWCm8<_kn`IZ7*VD=!j<@4k}B{%Fm& zYFGeHfk1JaDEOn|_Vjo27WI#L<^KTq;3%1P~y?-JwE$h6+J^)Q{u+Rse;SDn)E1(IeIwhkwOVWa?w2LgA+q z=(xe8Etz)0*vik@-SV*xg z8DbCwqZwi_JHdRxAzED*NVRPmvLMsP&k`4U#jvNqNN4Ny2=Jh40U^_qFsn$flkntcRFhw}#XDz8jM}`(1BdQzv|Tq!Lji zSz{`3a`6@93Up#z6hm*y$%>eOpj`oi7F`>Z$Hl2EGYZrky?idtIWmP(xH!5|0UFyM z?yzwxK*d?+{x8SwGAERtGOZwm{0zC5hWt#H(HZcw8ZW?ps3oP)4H%;BaopLfTy%xf zW9^|Y74+y>9I`YlOeMRxPgP&?$7L45&jwDsdf83YQsyr$AZB1DBOipsdhj z0A(dk1t=?w89-T)_o9yBjvb`5%59{MacO%fW!TdN@Rxfa zXQ;+;wfS??q2(Sar4yiZTE%kXzUKM4BT$`sW&EXN47SkB zP<-_6P=Mx3MCFQ}3=OHJwejf9@VW%PLYgxgu|k_8QefWguR3r!A)@i6h~*Y$eUo>K z6$$%$M8o}83JMG;?~Mz(0?8>UC=W;Wkyf(wXb>+4LL8mF+S@#!2a>O)ctNH>kldN9 zClYs8t^N#@_gf1jGYS`(FP}D;JP>EtI8DUhdz@CYELzOW4J!zQ5l*nU; zG%U}I$YXFXwsNZ3u@x3m4qr9L89DCE;?7BaCgT!E{;EvpVAajxBAUvIP?KVtcC|7B z5pVJB2QTz@iN4?5CyQcEu-)A+x;A4fKOH?J$07+ZkVgLum^9@Tr;K9cXNeu?HQpPN+2aT;z3O zqoT`zDviI>1rGDCpw(cc;RvB4l^l09GYS8nY+?B?-FH+2wkOg_*W~t4Q%YD7sZoS& zRhY32A`5RFg^Ewi2^;ihNLzvoLOw26=Wc$ZTBG=OAFyU@m0p2Z1fHB(s~R$$Y7p-zD0Ksu#?M|kYzt_I(!pr#M} ztm=R|A|0)aUrkj!Y=;da1@E%4q-w{MX+3gGM!Yd&FWqVfm0*yPhf2ik>T9m@Cx}vw zUrG^8G(43Rl7rvE_9+M2{(96)$El=AcqBOPkmkocBy6Lf9B3KR$_`iZobClijo2Bt zM!=rxd5HDvGZjbokwAu{@9+eu0vHX;31R`LAq|Hwi~}ee{b0HV?mWuLC3E&2XkxSN zUErJu4d_CvKRv!X>&`>>uL|j1ux+g5qZ$Zr*0i#h83S6OW(&sMhV1+X0;*x3;D%Mq zYUbU6X%Xn8{Du^$FQ0eO8saf8#2xodk;I)ho+X@z#s_g{&(op!u=Oj*wc23uGaT&d zRJV2_FRI{A6S;*YcfH4~z7N0!^(9ttRD9&st@?2Fp=h8|sEQ)*a{cGJzkaHJ=|Yq1 zx^`3m18nA#W_c#|f=#ioW>+j(4@+VYJ>wv$x5uN`$e=|{%1#ZDCVGGWn>DNBY^x^t z{?VH*^815ni~F0?jdj;mWGOS`D}hcnV%0k$r?BTg?&r%Uz82&?VZM*8hX+{%XGS%z zdhj3$Q+JrcW~SCIj{~nz5%usqsG+@JMa!RTwK3G^2dL!}I{z zBp|7XFOho^TVr0(UrX}vdRHOVo3@~Wq8UalCE)e2jUC@eE_tMnP#(CX$a2B!;j9oK zzmayy=rqld<(8IXD+kVZlto;Tz%K2xev8 zKZf4dKz&S>D!cRs_*%JU&{N6-A;wBe15ZVk6Xll19zPNqEIkRfF0Mnn{T9)eXnkcbo3JZ46S_FQ~v z?^vGZ1C~cQW-d`E^}(`YRDd!gmPZb*Nm^+~xI7n?gJ$G&a1Tm(u&(@#aGpO0e^qkA zxP8G9QE$R{Z3i91X2v2*C(abfA-PWjYf#cTRiFs-eItrmjM%c98(LM%R4+OHeefjJ z!Hd`t)Lbn7MAMUUhlXe#B8lLBR@`(->7`HWult#;VF#n%5Hpk`&ZT$AQ#j}+W0|*< z9&cX`Q95X*k3?xsg~WZ7MnHT#g$v!33;kA0d1@GoU}2fiqhNRuaJ0A&WjAt1#ITuI zUYyX;tK$?0QMmC~9@alYwU484xhNcTF5X%v%Pp-&@OU-iLTA0Es%UTS@tLG{=n%F+ zt*6j^1R|)GO<974y^Af(fd~1QvuT)AxJNcC;rC-+B(J>1H-&}G{0RJa%p*`?A0P3D zfadwlSb1sc1Jg%x5bwi#4Dmimq%K~=Hmq1WDu?lMb#R$S^eG^Ir=;8FNNK|llzCWI z8-Ae7H=Ci!fnno+fNceU4f*@VYZ@`N2iTnSl5tWXu=PB^<^+N5+hd8~$I#jxj~xdc z$S;z0ejuikv+<~zVpR*Y#fmT0W>fbE$}K&>_5*-TeCZ9c+wVTNW7&}&(98t~O;3H0 zfE%(d7B>mtGz{SMxD*K8yyU26b#=b_RN&PkP+y>7+x%S$~aX#jSDNYI;DE_iU zZYjc33)TShOF%PvWyW5-o~3qL1>39115iw5o=0@LmAm zYUF=)wSxy&>y3VJwG+VAZXaCj8sciy2PxKKtX8{nMA^W4*mFd^a&l)dV7m~x^< z0|3MNUTn^QPCdy!+7k_W2vLLx)OBc$=^+~dL@tkOTd}8X1QC$Ix#f8JsSg}GC`AmBL8`p5 zI+)drG%wr>SFXS>qiDB=08lSx#SYUx>(_xodGKrAUjlsh7 z_@GPUf&iPzN?;WZ4eg#KM}_saIUbIBfc-HDLpuuARP9YO3N7`l&wxBQzZIv(MidmX zJO&MEa5*X1$g-LZ$OGL^GjJH(!}O?Q;|t_MTGM|roFcRIu-8f-*fqtvTXL0#;Qb5O zY<1^y{Go>6=gdwGCtp`z$n||D!cY-3f821hiI--?mfg)Fd8lLVM6aUN3=4_si_% zy>6T1&GYup^d%-ixd3y|Fzz^#iruljNc zEz8`ugpj&2_jIB7kUIW4cZ;L50vtM!@C)>ej(}FLA!V!HKxF#9`7SlNG+&zv8U(=r zb|ZD!e909MSz|kGwU3K~pUI`QC~I4>ZfmA0dA_Fuo>;*E2MYu)Or=hw zB=OXia3zWg^Ji01>pv82R}KN?^H>3E!1wrS06*8ea&E=CEc%pCJ`L3Lj0?Ga0P09i zIx3y$BNLC2@hYB}#V0cqmT%@Uy+&$WPu4ircQrRJZgYv`Q!_^$xRSR;nFxFkEj$yC zM45I-E#QH}Ai6mP3OpB*1{v4ffCeUo4Sa}nfjZNBg=2uTo)TOz5|=zZ*JRXe3A{rQ z9%|k|^P)8#+=_YG841xFLIJL4=ejNJYFuFFEaC~$pomSCpiF*J8pGeUPd@Owx=D)6 z+xgf^o<*<_b&Fsv&bNKO5k7mQ!93!wWpS*^>gS^yZg6RbRqyn6AZ`I=S#}v;ToymJ z7;TdW9?D%&8oy-uP6a7J#;tbqYN7Ru9ec-`7T>s2fiAEuBj;8n=4Rh!GUHyK8N)s^ z*Iar&33xJSRNIug&0k1@kObwKj^o|6-6%ZRGu^P)hZlfE0i!xBpm2`jNPnHLG1bGv ztK>yB7Hc)H+LeyZUpnH;Kd_xu;M*iN@TS~hK5Q(#u`2tTU#dD@=39DEB1@&lPd~~h zYis>KMg2@}I6mvT0sA^x^v*2=<-dMFU`RZofCDxx_z!UgM@RODGuK2Djqb>ZHMIVPSDbH=^1(mlTwKu!qxC7Pal&_Fw{z4^pp@PMxj z@+fd}O~k5s2;iEGv}N2sM66G%8d1mmeo=<;-UNY$V>!tCO}T^L+EX;{oOD^L!cMo<8#2 zK^Kmp9~QNR2=NB+bs1foFz+1gV<&xUG?yMXdHwKJ7*i)Mx#qGZdoeNq!&Ku51qO9a zxETzpBqOj`>4z>zzwJkPX3~^^d|TaVF5@%~VY*jgEdZd}t#NHsxpyti)7$DwZWsNI zYR$zkzsPYAU}9Ns^-~XeRh)64#_5`KFcRg#{)Km_tqla+@qEFw0A81?)(5X{cJ@N-n$Mm^mH@w&YGJx$Lh-)w>VO zdgqkqBr@IGjf%G`=`!=$MTTG%T?Ga!27fg&wn3OOwkcax?+qnf=#NzXQl#_y>Yl#W z*Uo0)Ud!f>lg|DKmO?NDu;V^;l+L_6mTb{=nz>9|qt@Zlo$hD7K5WApKko`YU#HdY6~AWlJN8Nk_ z(ba-lx*V-1n5R-I3z(;b&N;?WZK+!Q#dz*sF)myFa;=zpgu9Fq{uk2-08s5i?$|@`)Z;te3~|@_@Ei~I^E$t_VDcWRVL->liw z2E}vAZ@;{iYD+om_${8FYnl^SGP;UsG816efdi$uo)w~K>4Tz^0KPvJH(Vi#*0X{Y zJ+4)T(qt#_Dx|G~=d3IE`I73JjrB%}wA~~o9kyQ2ry8c9RF94Tyq>*O5cf{>wmuss zA7-3=1n9x?eA zN3EVIWu;@m(VRlPK7Bq7quGpioYy}0ulDD!t2US# z9Ql*+M3nx`hh`q-F6>>X@FFJtrUKLti@%LzHO zJZpR$Q)yolirSA`0h59(+P2+(N>Qdc(;~i6&>sB^DX( zkeVUH-6mIf3&j)}(goDEka`tPw}>BUFD~z$c#nLRxze6r+1plgD_hu{n~mgAfGXT` z+1Kk$|ldKMOq2Q2n4uf zRwOi_EH(o|Np=#VC^EvNKIS5_V7wEKNm+vIu+-%ult(8h!EG5L9T49LbO*PzbExLM z=%rR}9xN4Y;O@oLExAI7%M!yZH9%pw_lEt%e7AX#q1<3z49%h)gVR0Yvo`fUu0-oe z233xb-Wk>%**Jlnf3ssXT8}}BZIF;mr|3p_gLXA#Fppvn6-teIaHDHxOM~Li+dxOU zeO$*qGm4jsbYrKxwK|bL4V23K`KFzIwiK-Eyee-@cLu~6-7Ky~7z9Ao>Qn;WnADpI z8lz-*0-emj!O|M|LG_8ofx_L9vk&TOo8KUSsi!j7HWgT1e^Z_{+2=2$89PfSO^@qe zWJl6XsSaCMS@DUfCTa)VVx#eC!QSlC3j7*xspK*k!VC-cN%$2tI}-#NZ+rMrH_Wkf z0}49?8h;F6+7_ohaNPSq`Vm%i_y^#H@J$1S2ZzpbLNQ3!8NYdj+J#MOt6?9mD8wsT zH+Nnka3;0USejvzL);L*>1n~?Y>+w2(M2e`5kimh-Hf=NpRxB-&P#I&TLg~x`*166 z;!c+ovV-UvoaCFVGa$tcn5SPzQB99$eFVwH+$&*H>K7qhw@@-eMpMD|%{S#uKuN%b zdFnX^`U1>Kw4g>Wy!9(YGK_zn^#V)7@MZX`z@mH-D&iZIe1<*!SZ>y&152 zj44vITWdMCgvN2CE-*E|V_Dt1?sTXuPS>H&W+e#qr$7>#!c|RlHNH#BsbtRA1{Bkg z60b3-Ef5&1qMZqL#YbO*3eGSW#qFAAhh`-%=0?y>`_ND6hJp5dy2ZR;u91X(?QD{> zDjK}WYvW8nXbPmf!Hy*889)Mo)Tv2{?pz2b6u-w8Fkz6XlfUgVJk`BY1t&no$)M!9 zb7)5)iXLA~Y7+#0b;5demWTG$jol%xu5a_~&^ed%V`7H&Ls&aqlcdfX_RT$LI14dg zN*m4AnvorlN)eh?vduyao3^jU&&}x-R;i=&d-dc;;zjpzL6#0Ve*|q zb1-oH}BoGx3u%8cD@GU8r{?` zt0IWByTVU7P=)L$6q2{*_T#$h>&z;!9^hP4*niqr^OiJbt&vE6Rzi8t8&nOPh=#|$ z#Q0%kpI%o@_OWe2T-^o%rskH_zm42)&l0d~Dfnsq?yG{iyU>j@zCVpuR}o}q_*sA+ zU}$iN@P~#z?!^xp0wJ+>SFk$Qi7pQ|-!28+ImAPqARa1s@fPecq&M)Xx8|*C{O?Iwbz#`& zNOmJ0l9YWoEf9oaE=}nq=#P7bg$B^!k9zbuv*v75-*(fJv<8#X9QTj}eew|Xlsf8x z1bfyFIM|PRz`=f#l$S>4c=UntV=(9N58_sF$(la;ghOvRsb@%L5akfLXcPFjbLwM} z%mC#OIdl4_TQE%}Qvl_HIZsr$fiN6SY|dVYvtXL{KC!nH zb*JX)1)K%bR5qm|h_XA1Gd??>$P5SuL>QuV)|BUa=xJ}ep8yI{(s1>X1QmP8dP;Hj z0tzB>~5%8rLV}GIPZg=NugJ80J@}^i{w5j&~*gs3Jsjk+~?Bm(} z=$9z9+S~*T0Gzs5h6ix+A>b&cD3rx80J54QMuHN`w^j2J2t)Otgokw_9|6ejS& zzc@@d3e8IZg%x`#GkAkc*+Nw$qS7fZ*m_VU%wvWe1am2&US?1-!#njx`lt{!xpTw5 zSJwibW*dbrefJ%Dg=m)^qrT9c&I#ERst(>1%30V?^8&a6u}S(7Rf@Vn@>XFt0|X-H zUJ{tk9x9$vP5?v=RPE{I1mPsmJq$sFL{b4M)=$lQGjGmfty9u`5(=;#PEjpLcWDna zXZpnVJY$DMa&@yCe$Q1&DNaKO+~;$>P+M4T(VT=G{{5Hpdz5>%K?KQ8YWGFPAN#{meH~DVF@cQa) zc)?W$qDE%=>BYWvBG%Emp1!(H-g$Ni49_fmbUXoei$JV+(#IjCurfBxpE<^LRxTLR z_mg+-pY}?g$32m_Kj`svF1;ODSbTNQf}u&+m)QNCr>w^Umu;oka?#uQ_-7Tyz1q-M zKVUN{dRSw)pT7z1AzZi45xMLgVYj^?~mQ%i%g4PE<%eT6QmfAQc z!MgiNKQyK_T^HsCNYuU0{59#&42inb3`O`cSSYvO*mcAd*)v&$+cApkTo$fXk%$pH zweP`Z<<#D94R0tbzn_$H4rI$6k$4*X;wIMOqPyBUNSjMFys9PKdZ6VKHed5xJyl2Q zNS3dy`LB%-2K|!Hw_)V&b>#jRtK@!lR}P-1SL2ashOCP|9+yXLB-<=2gMB+MHj2wZ z>C8!d`wRG8akAq+ei$3f*Iq5@D>ga3=7wQM)p9E~F>DD~VjaIamkf_ftNZ1k@_0!h zbsvg*tRNSrcKhReQXNZ~Hw{$WEDL`VjQG(^EDmd6wdP|%dgyEmDX6WKo829;O)eP2 z?obp<+$LhlV&SWw^=f@`2e!CSo+H70C)cd4&7Gc~{GbCe1w5Ug5LuCppt^mftND8c zKJTN~UN6FhjqhD^bsiw49XdgD{lhAC3yiEE3?C%|eqF7jvQlidlNs2Pz3YNYsM^sRJFD}mz_bB*er#vbq(<*rF z1)`+WM7o^(JK>-h*kVcfPCaMD9(SbRwE-atnsxJLa`s@{1=(p~Ir$6x2v$m?10h*A zae0FoRLKY~8Z0%NCKV#e5SDi#`K|9SuWx6UmR`xf@m@3NVPS@5X%p#9Au7Lq>0-{J zmwg}rjXK;T@e0-j{fEP=;0X@Is4c?B&uNrBpa}Cjd!chJV4AmxJX!Rb;R9kf6&_I+ zvdO$^_l$3r-xCm#6UWRRg{&yTB&Av-UJko%6 zQGt~eLwl5)HQKyI4`b7fE?g=hMhn6c{y&6$cRXBe+ifC*D3OuqLJXoukLbbZLUcwa z2&1opb(~-#y!PU)Q?UTK7Hsx9vS6 zBJRU0=wAlc7gK$&DKlKRrQhuFU1xi$ ztkX6~^AMCt^PC;zM^OzFD0-6=oAUPrFKCy_ z`wp>B%?Bd)C$>Ka2!1(u?p8TX;TF=!aBhBcEoQsiWRlJ8^#|Fi3)_4;$I!zG+hV$v z6G2VOa6{l{o;U}2xDs?<$=p}Ka7bXPAkCJkgo7Q}(^L4BjZe>r`nkU~Dv+_v*IXeL z7*cjIN?fD5q7G)RFZOc;+dPeCuW(n$BZRMa4e?^GohWq<@+-$9c}JZjZaP7Ek0+Z$^3$EYHblmUReQGX-qcB*9Moqn)L5H zt({))f`mylr`nm>+YY7)^}ISXArOmf=-HK#O9r(szw@*0>aaFOCru^JD1kSjlhE6T z;Z+KA#M?fc@tDnhI3qjox;IA#H8@lBBvK25G@7jT9nv$yOO(5}U(MFnQd8SJyuVbs zn7KyuL@E572<#GNx4PV8f@j`H>m3^Ka7HHFepT+L?H&5WOQNT*TRwz8)J~$jD_Zzr zb-;)0oMR^;SEiD}nl3Zq!>aqk9%20cB>UC<@7+ASWvhcUZ{$s@MN`(Wd+rLf4sZ7~ zT#O40r}gw*B+l~L*BHh7KO5i_SsBggP8I!4zcA=g_AqI)`Q)orjuOTUC+*YofY5m| zUh~C{Jv@w=oh1p(Ez#>xgw+;e<7L?;BMB~RC;GjNgIe5y%)4tk4NTfSVWaWy8i~Yz zWqy*Q^;|gAyS^%TL(r9nkW6;#-@F4V3KS#X2E)P&8Um(PFVp0yUKhtRM}iU|YW;W5 ze{bL6?bUbHbmd75=Jzk@y_3WU3o=4k?de>7IMbf*qjAo6sDyfWu3T~X9O0eez>hsI zW`nvK_xQyyJKEuN;EU9%5an|$yXVsPN7mJQ9u3kEc9R_i==Jct?s&5B^ql?U$}eWa z*8?vTCA3uU@S5l}6u(B^NpeW8mqR@awk_R;zd&yDtfY?qiUywCp(}O2Z~yhD?+a_& zB7B_(t1SJWyL1m*7g;`je-TdYx*qr~yy{mn>{~?NBhR17%Bi5W=pQJ=@e?Ze(S#~ATM^rlCO*=m zmlsWiE8QD4!ako1P9xuJxAWg>x3fYYiZ-Tv7+Ix*omTg5zVP$*xnVti?1o++6^q0+ zp-Iak3u={qGDk_$#$n6in&;QlryGvk^NG}_jRq>M=1Av#UQju=G-*B7*f+ry`&?)} zUOA6019BjaSp!UI7tW(gb6{~_Ky>(`$1d)wEOdg!v--sf{l!Yp3*#wyR^!=r0z4-5 zNoCW*PZK;gd31Efnj&>O0~qBnym^(lt9@+aCgol^6*6Pmkq|b%TwK;Kd6>qn%T&Gn zV%`(ZL72upaZ_`sy)WcNfBrxc;Y#=f?#;kgPns{y) zG-2ydT64JcC-0M9ALo8O$D)ze&BND9y&(>DaeZe6JB-O(y~atj#gExsGqA__Qs!%2 zU&Om*Infx)nCa%Euzj)W!q%SS!!6kDb~|q6>2+T}7NsjpU6>vbzlMGN?2yP%CbR>3iIa3)}Zi{!68*2XWdS zL2PxLqY+}}#yC=uRJ`4-#J%p1{%2>}gZWFUC5xhB#pwr&Geac%2U!aY>`+*&Jx_h{d$M!pR<;%c>;td1!ced8L*zlNTPG5) z>f7cQLamhzzWgxtK*P#EE}djfAdhQW$=0fEN4Kf9r?MkxMD$L)H5?}BZA*+Aqc zHN0|)C%e-HoI0oLB;6A3{BrTi$Sp3VVB)TCioxQNJZ^ot4~xG>CIu1LDwzw%xsOhC(c&EB zykUqPrncb_9t%7gr1m}61~Z)BSqkzqc;A0VRB$ikz#q0Jy|@Jbr7lFt;;}x*=ICkA zqw2Jmd~y&tR@`{G?b{JbAr!nf#t6c!1E=QpFdsXB!9DWqFQ_`ktD>wYEFD*B7k7CE z;%XUrbNQy5K#D0n+~kx9D-Z86xsHryDsRT$42+6e=RJQVXx=g*G_J;$6v$Y1Pz}E_ zXE!l_jk9!QYV-{g`62nOy@X%rgNkQ@LY{N(0|7zTE0N-3)froLd_tYDkJKU1gV=(* z+a^AYo++Ug0vOLpi!imgfd@~*KH(dTihoE7JM0b!wMf#tS%PE!!NZI@qAp7zBaE=U zZU?UsM#HOmIcpcARg`Qs=zQD8_l+tFA^s3GKP_39C>~0Wwt*2caKjUppoUU{?zV+W z7EgUz@B@s|Ngs_6RZMWNKQi>b82hTU93$bEA}xSaJM!K~j0wPt^Sm~b%=#mY>BSCI z-`dn`9Kp(2gL82_^{Z~AOLbhWdLO(yN#qN7a}@CAP%suxP;h~KJho8VD$|3=Wy9E1 zyK_&<7b_Ygk0yfHzyJD5p-?T@e#Zl$L+DH+RR)$5)sc!gb<#kR!9!>B4cd0S17g?+-n8%YpJ|EMk^ z;Cuf!U7?N8(qLbG8z)RQm%9t&ZVIGnr8GjdA(&*5`b42h>C5~EWrBNb*97;<-XuD; zGG)muVyReDwV>VIyv!Gks`US%SE~;58z~Y;T|b83%iJE_6hUMPsrs3{WnK%_p%pn2 zUkg2pm!b*}SVTWg<#t~C zg;HYzPSayc28MkK@}G^T+jVLbQ2DL%w7j<;d&M$c7~ojY{2eRd{9$%W$JTXuq2HHP zDJgD1$CDW#NaRJ z4)43`!zgo=`U&{CpETw?^h`CwK zw$9gH$G+BzShR08jYmm3TIy)JK8Zk>@ywl!eC@UImDJgogHsSF3yvkjBJ^*cX zfPc5g)m^XXz0aTnOA@cF!F>z+GatV0%$(g*E{ zX#Wy3Z61{^{ggnZ&kk9FUezI*YGuRkwb`nO+_%9sZG6>jb;|_kjlyL?M`zI;?T(H6 zhk{@A8RI5Q>h~qt--}H<>V&_0Tl`opIXFUiN0favBvKgI0-}8*g@G+#-6aTRfTj%!LlB$%)wOwc^``U8#*i z892MAL7R9tRIj|_^eGZ6#MG@gMFWbBig`2)UC4EJ^I=877)6(*RC9m6yj3;wn1-*hkfBI6u zImuIa*76S5^5IJV58u6QamC%dFNm4o%sJ;I3~reho%d&vbu2tISY_LeiC$`fYAra~ zb8Y9umaouQ>^)gB%3A_;6OCf~_68nIXYOWuJbia`hu{TTF(>j9>BR#d(#*Ltf?-JI z6aHDQgccsOVmitG=6=Op;MCQ+HCM?hkEX}o6&Ark|4g7-1N?*BGK8wyl(3{rxX)5A z&^oeEWA1CP9HHfUago;-KCdrwDLr&()w!Y1443AfGX~GKM<9LB5fG})P0Ns#x#d?r zq+R6smdH7uo3rhYr0{l2()unO1ou&*5VBhh{E#+G;U2LqMhv+j%V}eUq6_fPhTREN zd&NUpVUq`KHL_)!i#K;%+derzTn}#hutiH`ANFQhQ*vaYtVSFU}+kLYmL6NsBbSY9CLdO?C19=XJ6Dyxy z8=V5`_*^(64>-DU5311=iO` zr{nUEPB+8fE@`SSAO6J4lZIgm4ywQB78Cx4zO?-@`ho+MqCe*DX$i($Im1O>)tW|& zHaXm^+PgV>#*XF-dEF|5m;B53cT--z*4{N0PQahLchFXqoFo|Qi8-f4LFqNYo{AOT z_>k_}5JS*-HL!VQne230_L~HrUqaOnx6pt)f<<5ez7*v2r_3FSez4gRW3%swUydiL z;0IKj@v~E%L4{2f`UX6>Ex!?pAbn!`+^6wg9j&$^Kk#m8ir%g;GR%sy&$Nf6+m352 zVhPve}Sj` z!ZkOdlZlVzNKbfi{IWPi$73l&bynC1NC9z~bT11PE> zsnORtP2#)oS6o@q#Q;@r((bdLTH8u*qRmz+OBbW2kZH$%l*cThJAI~D{y~bt855fN z`CEs(S2MalL*r*u!I&IH=*A}8HcwjN?QSWo%+14Ru2lo$4h6woxT+E2@SDkl&(6EK zX;1E_z?{i7ptC0II-%zm)F(rY3-LYV9b_sQW-LFSP&*GED3;N%RZ$GcL(1ZWfx^Wzs%H)g56F$?SITwk0OrDtfCX%v!oF7kl$mhGnQ z6B7)<%QVW5xPf;B^YM6H=E}Xl^Pi47VSbW-7-ZkvVelLTFB8T(t+>1HB_H^!;BLw> zxIn!GS8&Th>uLUWe}_(=bJqM{pi}OpTmYc+gl|EcKe`3Y{f&?g0Np5j3)=ei4d|eI z>u4)vQNI|g1RZVqP~G=`a0LkUaJ_Qv;``_rD`M7#gDu?2ziUB_ffuNJYUf*~nV+NhkRSKZ#?mg227^CzoW;wvy!^NeSYQY7J6G zz?taYgTNLLqYkwvC}6hOhUj7l_49J2d&J>!eR2({86?M|zdgK<4}y+CS#A%O=(1-- z*eYlzk2JPi>!lAYGNnj0wrapUuTv4(*Zy7-nbX;n;0NUm6Qh*FJeIC5+|yHpS(>&e z;2%zb&xV6oW@u$iE|ej>67h|G91Vp1_Sq{&y};Kud`l1yOy&~EdK0TqooHUoCvW-l z%_FJRzCN_4;0Mh-w-{~OxlsU&9W}QYd2TT-^){qpe^G>Qk*_h0ICH1+?!=siSSO{; z%upRo^j|DpCBUfqw!b-wyC&HsWb>_DgTQEw-Xtk)Fa@w-<$>Foxcf7}?u>Vkn(G-PDeL`JhZVo}iEf~zN!MUqdlh0p za>^d+B`D(S<472O?!9`oKir21e?r8(PUH7|a}`khjUVTn#Lm`{?$fxe$=y*$W>J?9 zG2jMLyUZ_5JP-pp&T3JS$cJE&%wWIa>Lr0^cpO=pXVMUZJWj4KkblkaD3-BI>@OH- zjY-#q`C*R&b2OhFTurh0!n3u*{vqG`pLFtvO_{}mPPg96iykw@X)+%x9u zkGhB&4sa9gooDe z>(Q4>ZvnjxLhWP38c0WSZedPxK9Y(X6@CJu&&sh1s|}BIA^oC|GrHy*vmfn8t-L<| zTAUiVmoqC$7_4Q+*hmoGACY^YjhfVXjCT)@m#d=AZ|W^tVBn#s|-emnwG z%ts!A{fpkMN1R{c4@cry#bQ-?w=I1wYLGXrreQ?A!=>0IlD}Sl& zpfsI7yIhAhJ`At+MAyPeeyM+b@cKhb@xz8NH49Z2wr2v37nZg)Y7EgEicPH>2+?Y6 zTnoq@v%X;%;?wArUnSl&e||K$DAh?{DYj8k|9nZAH-kOFv;A$vcC=G)>FNF7Os;!E z+4+aVZj4Q3SjF9LVuRgPMc7Si##P?RVz^6Ms!deXXinQdKL6JN@m)cg{%L43ckGz+U#7Eaw`}{BpA`; zb>6lTP>6e#d@dHea&XYQ=Ec06a)I(v^(GZWoUigRy&c?AydSru70zdP*NfG>8QXp! z`(kgXp$DzmclXP;r9PAwr`aES9#kQNjLqZkHX7Q~zrPqNBl#sxCL@ngXIL9u*xxsg zNI}urLV0`SHLsF7qxvf=wIQ2A3zye|89`DUq>0T9|F-yID{a4?NKo=eND_-E$7;#w z`iwF3{${lnN`z%3ycoRc`syy~MY6tGN7;9aa7d`@x|{jxv)rc$_)?>UB45GXrk$GD z(U5U0cQ@m#u}#K0erASx*`KM&#F{opb<6n19z8#DD*0ICRjC% z$Oh6K8-sp2Mf)Sp^MjUmmDMena6tOeHu!7y4Jr=@@J!!N^q_am=Pog-5qHg(-fv-` z;^9vtgcCm%Bn~@w>SN%be6RQZb7E;{Nq6;VQYKBlY)Y6-SnbEhGLuqU_NwuTrAp@_ zk4)^tCVll^S*Z}nc|=R4a1j@>yF!g3Y&DD&$I$a-FVry$*_G*w*n_`;)QD>w_xE__LD#nPgc)J^9jp=Q9yLdgItcVo5U*HfgEhSS@DbK|t zsa>79M3?2rtN!J2l(a4ePSC321?%@o6)6d~f;TBl#QIyFB`@g-3*Kl`=viDm!qjJ0 z2~eNPp$EbIV-zjoODZ}1x;AlOGR1AR4`DE0G1H2SD!HY8Y{$brS5|V^fCv43-5T}M zw)g6qnokOrn7H%`-^BHlR7yDKUQG5n=Bi_D^p+rP4Ed2?O^6IF3Vw7z`v&voewCbVPU%5LML}M318}VQ?qCF%S>WswDG(wSr(qUMMqez}-Bu1KX_+6N`qUtbS z!B*t^hl+%9R$c13Ne_|Bkb+@CTlK^m&wiGwTHgXle zPm0(2tIK$QG3)V0+$yH7>B5Y3P}k&RlBOy^+;mk^8Sj~KRGN8@)bCqtMXke7`04?=)lzHPF1;jgAj-T&E?K>kfrb_2If)tJ|0N2XN>Ad|E*Ad{-)fNc2O@fl%)(n;7M@3G0*I>h3IkN%~@oCDX1ju;(!UYcJf;R)K?UU;Hp@;+( zwdOYcLgOFK%q^3JW$VB)m=r^zeHgnzZT&F zogJ6NFo+dc#43sxWRcS6Ge1T;-e-$%*!qX_yb;LU>G-?ImmI9f_6R{_(b;>s*2!Ce zlu`Z&)F8vch+M`3URroL3LM4^UH;usA{oYgpJl87jGcC$Gq1J6)#qBLVJuEz@a99& zjhfx*JMYcT&{2@mje1wnpRrhCVbC=$b-o&n$8z8?v)j&gZaaI~_i6O=h^Cp|IRY?X z#kU&+UH~7DZIdeg?rsGQN%~vN`WA{W)W6gUew)l3Z-wSPDXpAoCN7P6F;`G2t3E~i z{oSz-B5TY*+ZTaoP3LTZZYXc}-hq7~CW0ACQNUy(R%(evEEGy&BE^E0ZI1bVURoA> z=rC!Ugg2SALDfxs5Zf=`h9cI8+to>7N2M`#WS)qG2lQaQ!jW{hE!Ft2y08b%VX~dj zMq6FR_%P(_Z_qAp?1r#9NZ}z#L6R0VCT+MTgpj!8CG`stV59JGUKL(%Sz}&fyMm&_ z>{<-huy|^(Y#EXa3ZL_;enCJaK+P*mCpL144Z1R>>}}*(T>;3q32;U`JjI=mzV*v9 zci@G{H~ye*>eWSff>mHCimA#7`i8P&7q1*+?Vfu+OKGN$+4-FCFgol^nmguD81}5X zG!xfHr?W6o)g_ozzG%_guG1|s5ZjWh>?)PUa=OXq09X_4G4yfng$wOGG9`zfr^nrS zqWh<-Npg(P16G*@zv~stlK!57^lUWfx?lYeaz7(pOY)HQxSk3HexcR3IGNbl<~P}5 z+k%LtW*OWvxL&>5`(kBz#p8U*fH?=5b#qH-lH*fr^a-~KPD zq<6Scs`3dYuF9e{pCjq7cd3o8zO1s#PrebLKN$W(J71HXT;bL6;;BdRfESHF1#a>p zq=MR_&2Sc-{6fKL69LbneGocB;+ISfIUdK+FVoypN#@Kh+YtK{82B;FJ?NcdjR9+J z)@L6M(NIOwm)atSbr+?Ai_EWxwzuQL17@BE&PjD^ zasfr{<6Q9eRR0uxnD?JW3GjXp?1UbF4vw~DEp3oB(NB-l|fV<{uh=<~pfP>Ipq4vRuM4PI^xy$lX- z->Jmz-EN5yexRGRoVY9Y`U3|VFBs0eoPaWexvzR;a1tWYrJ0VFN*YmhjP*k=vhTw) ztEZpqqut*NI0uq`M4REBM1XTym!m2aN z&=;wdqkz36);que=evWH&c$cT&CdY_w@d_qRDl3DI22UI-%t1rjp>2iPbS z5ID;$r7u2|GCj)TA#4LsNOjTuNHw}{j_ubLo;b*&CpMCQ7q!%EvJtU1;3mbQQef9{ zh6iho^@(L5uLNgg`mB@hP`~?AI>-PAq8mZzkw)rDnW4Vt&}hGG(6-$dFc+D)Y9@9) zNAv6G;(957HWx?NHkNT&s7rHlE8yu%OfxmzZjXm2PDk!-1g<$qJ6Ha!j5ws2YyDMJ zNZCr@asQx#tjD&Di>Xc$Uw`c3Fn=*%4^{gp(bSAY?-0cvweyHUg#yo2nf-MZdqWoc zCyb5#vCHr%x1HsB0V100P6^NCBAKh6135*~#?e!{_fi8gbS$p*4=K>He#Gvli0XDP z5RcK&WGa8Eb?7qF!E+s#e?adF&Sb(B)Q(ksq__^TS;=DmoWxR!u@Uh&oW(*+k_T0! zTMC07_}E~1K-os(*GOF@;cdCO1m(Of9t0FOt`K+y6qmfQ{%_lg$Wb2_E^$og`l+H( z=HkPlydOmL$j~$vHsS@GZOrrnGP2mHaD()om@IlKBl)1HrJC%b3a@a*6@R-d_D@NS zr5HtvkVR=tHpPdY;kJ0<(#*PR(k+su_tP1>mhJ$Y>t_O-7jb51Zt{J2?pB4KyZD5j zeo#qmeb&t(V$wQGTnbosYI#vn)0DQr8(`gOOVQK+aI*Bx9(xv#G%B)B5GVJGDC0jF zjaGfDxXy1=^!*T^7&A z-C2hn$lf>2S7OL}hojNw1-?Mfj9kdpeHv$L{Z0*r4ayIa(i;!0`dxBjY<+2H1pEk4 zaPuu|{4;&8q7F-FhgDmFM6Fw0 z1@!!2jS|p06CI#CdN~sv9#+2~oywdDUc2kEF6}nlDrE+Id&rvp8ES2F7mZK%{)J#_U8k=wy~Pw#DkA4rXRE(6ns`%Iae<#{c3V{~FVXjg@pk7DfN}cJ>;c=Nb~{pjq!**nkP&G;{gS?XlJZQPh8Wk?fS+kVz#$7i2;Dj6d z@?v!}lO#8VGG{Fnc>f|^NP~9QMBo7;SFLCXJH3*9fQt^kL1ITUlG3Oi5z-ocx;H1y zT1qbO8ZYu`(_i&P1oyrDqW4%y!Kh-^ZI9s z>u;#}qe7Fe%`_AQ8(hla8l{|lMZh_fbnvbo016*Utrsl^WRhkBP zD}=C6+LwNI{x$rMAiwr;)?R7(r=S&O##%Yuz<~Q^G{FrAPI~GgMRi;Csx=XuA64i% zKWesJALu#`EHx;u`V8(C*l$ZEajo@Oaa65nbRSCp=I_ysJ#Q_3D^6O+(&XlIUB!bP zT%E<(CpI9Qq>h^_6SgGQnTOh;jv0$jck()5*lN-Wx5`FV%}HrL7OMULlQV!TUXIXA5hJ>fec zk4f)xQJU$mVy~G!R2sP27Yj-$J248`G&qq-Y#xg4aA9S>gLNE#L=Gb4!oWy%`b1c+E|Gd;uj27<6)$2>Qg*T%{YuV zKGdD%zt|N-$_tuj3aSMsa+RM$i!)zcHE#3_rbG+r6Fg*0-KUjhv?Ojzk%wJPJaN4? z7lU0+RI%@^n8(g%!|h5pq=|jgtm;VYejBIXztmhK1ABSku90;Vu9D@ZEzh>F7c4Pe zX{!5_-aW8#wlRigYxQ#BNh{-;{7Q6AwuwQ%8#Oj&zm6YRF+vw+8>8*6udb$> znoNGT@Ah5sjm2GXmrKmecC&#%ms6%g?yig>T|;)V#{-|w)PWDVDpm@^dtDwUvX8~5 zM?Z*;?X*NxTVGvYUe!^M3)WNcIVq&#Pk*;o=x}GM9qMS6FNvfu#Omq_zPq*&PHOTn zb0Z-t`^D)s_L$ArSUugMpvR!*fnXbUp{~iNEDK8SXB59IuTsMX*eyGsJU4+FCw%LO zf`h@Q<6&^y=>T{Hi5V>CEf{vD=aMbs_K2zWVwr}h!jb1v;Kfn1cQ=8%XUp%i+27UP z9>dg+hu>X3I1riN_YGOkt+K{4o`L8cTh_R~cXkfo+qB_u)p@$OowhJDS?8Pg+}Siq z3#r)fC`b9dduyJ3Sj?}X8PTkzav?-ejBBGy=-V*c-&$ETUNjAujP5TSRPgBRDJoJ$ zPqx$A$_0fQzZfp24>n8sd0K}cp(IK{1wze4&H>DeYhPMj8)4p_@zc;J_KfciRcBKu z#TlYIFP|kk9G*WJ;k84SnzBwi?)n`ai#RagRDowypSx0W^p>cpZu2Uk8;+yvnlw`U z+R*&?!zClo@8geFQf<7S=FOJUI9vq;{T9qA7Qi=Hve6L?TbMVes*4`SyG7vgN2I;C zkj3TysN)uz*s;36WA%Id0^HZrsZa)oeMD}=xl4?roIPyR6AFL>gmD)~^e%R3aLX%&h!zX*QXV)UA z*=OaQ?hf&V&fUE{p7GtN{aP$~l$qVpuj!%PEWt1N^F1*6lzzh<4)8K-=l4SM9BN6E zPbK%Mla<-0clqIhcF!-T?|t(fc+DaaE9VvYYvUdB~v`F0=M`}pF!syAKRN#TCtqos|#KFz`iS$o{M0c)!F2o3jA>4OCcx( zC*o66c=nEiZMszku);R3UajvaF2_-br*daPgkS<7{P?vFRJ^O6{y<%Hu3rV0Sl6Z|RD{=5vjO zG3BWL`gBF_b)^ufFngJ55X?OjfbwDg!}Vqg7F%6Rv4fJnaR))~nDF+^kjL-M z6|AwptLG+*=CdhjcI@cb{kep{{Z_Sycoz~c5dEeBCW#}aI7tV4ZPPpyy0VEJgbx!r zrfA%HdHU*3+A!XDb44NM66GNMHTb#PPb3}SpQw<7_?f(L)R#P+>=Q`}MqE*9S{=As{NT8L2vr5B0T@(4di)PQX{Vj)PhV=$7A-eEXr-O^d zpkj=B<>mDtPPC3%@Q;u=uovm1h3H5uUiOc}+H{^t-(Nh&m%Jxjj2e@+5}!^=Fn+dz zokAanpO}l4$e{mlIb7x=-9l@P-)Q=Dg3(%ZEdovLb+tD=fCxE{=~-xP3#1tTEPoPl z@*0%_gNg4rd6L={*U7Qbct5$je8WYaa`LFY!*W2=y)Q+7VcI3>9uC&dOwz9?GqtT1 z$2eGyV>Uv$E`9ugT5LLg@wOVE$XIm<_FI8It5{Y-foS9&rmQ_@3awfO|f8lS&;+vJ*T$ z?B5xqsqjTEUK?cI1s;zOE6EDiYblz3*Bk@>#4L7SGXT4CG37I}2C8NmM&&z@`5NS1 zPvLv&>`MZHn`oLqJsBzzRLumYam9BfS)F<^;mt9Z<+sNPnq!!}n3Md>Yw)$_qGoN; z{z_r`f%N}3q26o!m%~r`rk>lH05JAIu+IOZ2HoVoaenN}+%#Q}B@6m=bZWn^r#2%l zOzCk37d7Ezvrw)HQzS}u8X;K+-#dmuf;@Zq!+NvSCLx`4_cF}r!($yGT3c=$s zj4c&RUPch(x2a_gFn;7%@g5rXH|*j93X% zpq>UnbD0Y!A&4nI+nNR3W9fj|L@$A6rQwW2jsPyJnyd+Z#r%D|Fd%d_pKl_LUC-lw zfcG8SaC)ohJeIJIl&`~0TgTJ=e2qfrYQJ@g;`h04)8*m8*bvX$19)7sQz-`URg*!4 zfvh@AE&qD+k1H>Ak^bLlp^ISCB^;nr2AoY>1C`*ll$@M2=I%1E4u6aIXfM0 zTw`p7Aliq<4^pOCWz@YjTEM+{1o|;0808T8C~ynY(BmvWRv91K?sqNBj$d*qlWF$% z>CE~}x~3>Ru3KS3@78OVthrsE+Lw$8yC-I?;b-)j$OOF%WSwMcd0&o^(FYEyOm-IY z9zt>y`>{^8a_sb}n*1CcWS_*^g1$)1%__HHV{$6W$fI4F)YCB5haoJiovBg9hbocGriiXX=Z&onS_M2iOjK> zqcQn-V*nA)0zhDFIc2&yr;Jya4kT<~T62G`8Ovb31$g9oGe z5d;lDSsU9?AgBv4rq>WwL74tBjOkn8`(-P9tZL?!#cj*%7#;2dF0Hqu_8hvcXz6GR zuxcQ%(FY5dQ%(?6JdeTxUa-P{QN87jbr{l`!*%j;pvjqtT*!3`yFaFiz(n1-(!R;% zxaxCD4bV6Qc$Fp zZf-Q|K<)?$j0a*chLUfJc^jo5^x!vd+bPI5tzt#z2+%J^2ggrgA#<%6Iu=uf{4V_j z%tX2a6JW2sqeNzakDCc5HxrV}t*UrUvVG|C(yJ833wci6aPzuWW`p*M$#hrdtEQ%` z$f4s$uP~ctpxYPHenD=Uo)K_x$F)`~3K&J&O#LEhV=VJz@r+f7^GF9TCgyN@^(HiBq>Zy&VA%2W7!s?RGdqV4b* z2(`b;sw~GJ+DP*InX_6L@H2N6aFW{X4VDW0)4+5kshi3d7dc!MYrl_9jrhA^2AmBF zj=@Dl`XTZ4lRwbuK81jg--7*ETS%%wAn`cFUjrwi>Y6DA>qwGcAOdpX(S*?5Y?g(E zjXXyes!bAYwic47c|x1w>KUTxpFyf${eb!1Pe33za6ktlSg&HgTI4M@ePPod=UfvA zJpj2MS+cjxkKNxo6d&iRHSp#cy+?t36y^7En8XVY^cE`m7VL!!!;psT>Sv2l)vI8v z7ZG~l-G_|wwthVA8-WWvY;tO*^B^SEVH+k}Y?g#&O5JeG>5oBG82%ijpUE{$4GubF z9k#Dh$)xA{{+^l1=ceh7Y{JJTI*)7DdCILE+K6DU^98+HVL0#o33j3PpkNdo*lQWc zHyE;o2=^ZJgC<&qq9|v3Rg1nK^ngvrlIH19k1Aq>)L?8i0EEoZxYFltA>n$=98@CS z2k{1u!~=a7d(B{0}B|vxas#N4LGQxy$<3XPTpPzRQ~`}&!qW@k3a?;TJjH%-ER=g z4llwf23UgsK)0dlgWim8`C_@5zYokmWZidYQdwl=`cB0hUYvt4&OB)i*ZHB!y&o-J z`x5S+xxs?yjP=vmfgA$&0jnI!iOuG%HUtRftkV1aieGon?^HAMlYoMC6<~dm6zx=Q z7Ke-%_7+ZUk}%W)LCFJCpip!zAWVf~EC3XV5$DG`+=?-Nr3xw;eH2;&`Ie4M2p0^I zaKU+MwmE{h=`+0KrcW-s=g?i#U~hj6!NPD>P;)jH-m=)@h^AP}HeYy&X4j@a6efPo zNxlZl(4WYLwK9rBsSJ*UrzOh?;J^s%B@cthLVyf@Kn8&zzZolhkPJ?#ybOfNtWV;+ zr?u5-p&>6VS@c3xEvU4;Wu2vt&6xRS1o37=sslLNNw6M++MS57>Sh@TVn}|m#i*-~ z^76GWFrVc4+&6?byVqR@O?|c@!mMKr{_Kz8S6Iplx?9Rc@ErWCvc09=?~!Z1`nX%F z)e;N#j1&`-S<=&mE@M|5O>@@v*v$$q5><-kvr_R^2$o^N5GzPOh>PSoI0!gU@7L~> z|9;%fPi}%ph7*`ay3qCFVp4rP)>p=Hoa8}1?wq(fl|HcUjG3Py#9JV!nMlbvzmKD> zk^r&c0I`%uNsyLwWDO{Jv#2=O%gwp^ok=06NV>k6iNzU?a>*?Os1B~BzV|>6AtSuRxgpJkpIDNd_ z->G`TS%!JJTevgqMrs|;v1}|3H{ENmq-S8ctB8RAxjCu(?h*eg6o2(S#r)~ApW1Z| zFK&PE?v|5xaj>JCbI#57`nUjl0}c;U);Gx~M< zatBz?*JV4l#xA(b*mwt4EDQ1*`xd~y@_lm{E+EqNhaqMi78q@qf3%#I5%8=3f--oa z%V^1n?anD^Va?`EcYorOE#?b>Ev0C#HHVhpZH!r3y4e!(ewf`*l@86jkp{qxxWSzh z1K`fcA!w|q`hkJo9j(tPf!H4?B%9yqfKNMY*+dvjAoN-{)cg zN0{;Tfdlvu&K6R!id{DPT9e0W-%2so{Fz*ohZynaUxW3j@SB71UMhlmJE0#%9+2i@ zynTg9I?pGpDNHHBttU><9K_^BO!G1W9H(Hw!SL5G9HA%f-W*K)U&D9IaSABUfSJB`!)8?PhK&xQOrZ_v{K_X;TmepVZg4cH z4w2$Fs0{JpyXB{!Fr25RXFm%VubyJ)4kH0`?4J=CzXSE=NH~L zVyJ(H3%hhpQ|ojoH=+KIZ$np%fKV450+4Y=axC!ZYz}Zh|K+;#MBw|EmJT{Pf}}^d z>^ES6_FS0of#e;EH#2UAozS@8n}PAdu6iw;+%=Hz)p0H*I~7IFpYY?yK)8v}P58~Q z6Uv&Ad<8+}csSr*&F@CVvG0s3gZ)?PZ+Ji~I@3+;zlOO-AD6@yM>U_8Slcwb;`%Ex z00cy46Wv7qbGQd)Ur^1COG-8XDy-9sL&kSY2>xea0a`YBvVo&!l7XVAcQBBFxmR4E z%@4zPR4K?$@1H{?phGqhJj9&Jd{jx+Y)X@$TtS`<++uzs6EN^1K6*k0Xni}>z%nLF zHaNabYx6Q-Ri7nY0{{PVvg#Lndc6L!oQ(@|Q}q3R^l>8^fE^&}rj3X4Y!`)cYyhV> z@3H(DkMhxxyQAasfpDv!xdEf1%{OnS3MQKS}%-wE&L)Pw{_q zMHsGRJZNGnW0;u;7d2RxSf_!hdOsoFx_y3aTkB#o7+|$_xmQC6JYN0MR_;KjJ3jSq{7Qj3~ghS@j>rd$MvR|4jKW&;1oS_~FKpqqndBn=k*x5c+?aT<(8pRPWbY{eylv^?xoc5a>TN z`bXfE5VGGw!nR;Cy~*qR-ZKuW)}P`Z?HP8eLf_-l%-ucDsT=Za5^62NG<6L=mg&3l z@ln+*>avAk_XUlAe;)_}xAV4%S_Fa&NG;ezZV!lS%7#h@WiTzj1O6(m8T5#4(!hKC zW-z6m?Kea~1qrH*Bi}Nte`>@w_4zo3^z*i*_jWLO5P5KNP;#(NkWTQ=pr65ljyd07 zbsJdzowl7}-cb7e zd_bH-A9>(L|AFI{=lPxYeCPc8{==TV=ic|e?rW`et+j3j z#+BU3c2955Y|m)VYR_QLV$WpHX0J#DW**k@e?m1(x{8EL6G#0AA^&5<6;*Jb44wcu z7MZ?W%%Ab~vPiZl9Dsghgnv8+7O3zD{LSqD81XYE{>M}Pim-*$Ht94vlN$M>DRutm ze|XPj$ODjIk>;UX4%k=vzi7RL&NSDw z$a@pE3w)gh<>+9-T$J1Y3LfTB8o-{H<}>++Ps8FJPR#!p@dssqBw*2-kizWSDWd() z1&zYx1?JzE3+n!_1zq`x3M`C&IsFy+SJXZU3&v-KN9bZ|fyLv0D%Pcnwu^+u1Ht8z ziUX`y$;&2B>8H5iwTxQ?if#CyHphh!42p#Vc>uVAWrsfvF{sUatPK|Md?`*#%PDP1Y$CHo0iZvE$y zFC!kXvUPNu6#)nqZc0DZ;VNMOYl8DTlvW&`MwbbM5B#QoAp!ow!O!&+hpS-z#_=mB zz~c4SlYraV+C;Rka?T&BL5M}484i<33Lq#lVe_;u|0}=z8q=PG%s2egQT~x%0EZ!h z3j*{1r1w0@13p9&u(Qms%=H(?e5G;5aBi4YvGibh6wd0efC4h?FSn!nFSq*@M_s>@ zA*lrr30Tg*bmymbPAiWC0#)+)DkJ}Cs4I^t34>8%3;;6S{9 z}B z(@<#ctRqH`?)l!4tKh{^@Wqh_AQW`%Ks>^p1c(J}&2YRhGGHW5+V6=N`^5kZ(mgT3NA0VKf6oCBdKo0J+xUv(hFtERy@u=Y)tc3_+_HhS!y#Of zV8%QK^OOGbGKFuOkNz`X0!0ddjJ#YyY}%LSCbnT263m}|`_Wa&7>r+X1?!i8{MO{3 z-u-hBP=WdmpB)tauJ-W&|TwSTPP{mVoC$en-Yhsz?CXZ2klP!If=`W2J#ittyTh_#>EHU;!=8^WHU z*wwr@|1*jBkW?&u6XP4^Sv?<;xa?N`J>6ydm6o;{Qj~+pta{mY0l^G!SuT?nAWA>| z5mTBI!d(0z5T4@^X=Ff&2O9{l^x#$APj9>Gl~xpBWnNfB^)gT| zHp1_OJrh3W{RdziR+F$GW+wCqD^<`f;5UN)_+-0(bg#p}||7ZY2#ins#I&c{=e{D&mga0D^X8;z5?~4fjV)I`u1JM7#df1`#6mLOBIcDgCzo( z5?pHQZ!RvokjpmdiltwD!fzUZeVCs)%-V?n@XCt~$27PG{o?!&Z->>qX>`DBC9v}4 zcWnKRV0bkT%fr8X-1TQ#{|D_hIafaZ8}dKQ2ivoQl}j+!0V)?*O86=HS6fEE`d_#- z0>N@=zCRlu*VUh!fk39?fNczH(2M@h0&}b#NQT&x*=d`CN&m5f^j9v-BRdB2_|NS$ z7@vQp!%Q(_61e@~!FlB_zdJ&h%KRn54RuQBm#h1^iT8{CU&{Z_OcUWHuJrFq>qOhHXx;E75 zr2pK%HM^*?2dcbQj@9fFIjTQ)ZvP6yzn(WsYVm6e>(AVFwT}x((Vyx6FLMG)RO!P+ zRvZp5D!VxTQ3JpP{E~m~zl+L0NPyY&Qs#iR;~!NeET7sk1DwwoSpDqKVfyrUVeETV zvBP}!GBaK6EBvpb?CO1BE_fI4?{V;6^&jHAG5|Ea2k<_$ztO_q{I2_*80=q)Y1|(Mv9nih5%a6AU;X6(y zTLKLX(E48X*jKZ_`)6Zj*w(TUGwg}6gt^4P-**^cShL!#s2D!=Jsp+u(b&pXDpyd(<&|e!iCMJEy%WI94I(bH1Q^;d!wb+oyYuRP${4 zd^=X~>~!ejY;#%g!tP{J?6dFT$f%r6%jQM}7Td*)=gEd+UBijR+T?hp?}}~xtoLEv z*;3cJtFE*h3G^1y(DP8_O$g?g`xqKQrUZJPCFq5P z<4B(e*01FmyS#A19V3q~<`w6(=YK+7?Z1zZuzqcYvLHCZ$n~|&7mxlYE-0{5bolA9 z|IWa@Ji!~u+V`hh_m@jbVE3JU0>0dLP)5s_lC#Dim@XOkG!E?T4!$&AbzfALn#a{4 zYmpbmu=$StZO8AWCsv++RD;hexPE84>DXU-90@i-JLTmB44>c=EQ8><&O-d)^EW7y z0b>K#;rMi$FCP*b3!l$toB@6-qxw_VLLX)j{F!4Cm-nLy!Jp;J@oriOfRc=63Ww5> z53I$PFdn{^$ob2$*R$czy7)!`pHI+9d~>e$od1c-3p?CC%b~<+p~{fuvd*r}`%|sE z&t{EWZ`*uvr+0zhoNxP{SDhpghEFFe(Jjg5i*t3z*qIqzPBwov7wmK>VzHKVnD`8L z5cZ-s9=@;_VQ?-;n`7apO_l@q((iR~Z>aaKF)NJ=J^*ZDmI_~9WYi_YsBd7W(!4Rd z9(uxia^k>?WAdX*3o&_IS|}(9J{#73G1u2W!3iEF08a)C_JtLWE!nvnZm_IV7!S;_ z2V%uOy$FCUL{JrcdH|dA-e?!P zp<|@xugOdq_qs}bBI#=U?Qpa9YedHH1tfCi&!z)wnQC1DO}CaB#t%jqSKrdb&ANOk z$s0qnp`Q8w$4Ns63-HuvpGafaTxXp~|rQS^UL{(s{@OE-f8T@6*vXdZ1|h*0YRUsND%Kya~L;I=Y;!EMs6X1r!c zjY?rRCfFd8s(Q&a;PRHyvr0Rx@3NU-^h4N5HT9fR`qDuqvZ;$xVmM1aHSaG;*F4c6f7nh`Kz0 z0Wg+C1-BbyGuto@VTTd;!N-+*H(2-le6j1pq2T%Pg6=sP0>Z@w0_=xX&VKRv#WU{V~nfE9N-p?koNc4VACy)a-OZpL)`e#ki}`9c(}G zU#o-Kn^u+=sL`wHk2>K*jF0wcq946sczjPHpt{1cKl)>n(617t+(AG_Kn2bpAS5j6p$g?8AXL@g zKp+IJxLGl}+B#S|ni(5AIWocz91L#ORuJX!SCdS4ycze%!e$J|Ba+%$i8=#PuhU1T zc9lHr3VCT%^|n~yc&qMhEQXPIOWbF*7~pF_Ygx0fsX}eC*XbS#_&-0IW6P@)v;=}TOnYS(e#f_P`Nd6G3dE9#l9^Ju4PQ;BB^|fKK>)gDC$KwSZdi*2mhPgur_&Nk>`^% zRFkF;$0ZGBRn**0pN;X%RPnwkL41LY1Yx(TZSuXSk~H_STX`1sg`EN{4 z>~}A|ZsG=hdPHR#nLkl$x;DbAyoTkycdo~KVIC)wRuq{Z{zc|)Y4<{-OC=$i$Mx4P z2!+@0LyR?e;$?yZW~2R-7?FJ0@3BY-f17OuZv{Pkv}v!$s}&P8#FY?vLH>=!Jk;Ul zLFS_anI9;>0wm8{(^k8qXvy>WX)q=->fJf%?lRj)cwNsW2ELH;#)#RQkRo4i7R$6o zELtc3RHesq;hmG4lUu{!J+S2SlDr^ib#nE?XhltKuAuwjLQBhu>1_SQ!I0d{`Dx_H zWR_{y`06y{Y`r_mg@=Q4`SExDQ$yEskNvfpL%|ED!|h`fFNgBu<>Ir0k*KZn{q_0j z++fZW=kt#J&GjKUoeW_CsSG~;NvmGf`|c=_7w0QSRAd)tLvjK>ZJ@EdV*Zo32;X%1_@FsOr%xxhOOJJ!&WOmV$AtVg#{i+#RYoeQ0!+sV3x^ zOF#(*)$B<{$}a!;ZinrxfETcolkKyilC_?wHDgc2jM|_o&x4iml9tetS>KZ(M&Dx$ z*>(oWUux(lwXeuc{Mek86Amk55L#X8FA?j(b{M z$rR9SIX?H7oP5x&Jzc`0J-vQWV)0Fztp2El%;zL=_KjPH)V!eJg0QB=VY0V(UHzHG z{=nJUq}qr2vqix%!PA}NSb;+{YDe&Ct|;fV5IPr`Q$8PY=1usu$h#=+RZN70$%_-q8me6RLj6I=Sx{?4KoeLM?Hrh zd@C=G#ts`!k7p{Q1y5-b20s_MU{f>1d^dIVeA{OOqVRRWw65wcZeI=;C}rCDVO$0g zBU*?p>qq$--M5<4<9ZZh)Wc|*;~|m$eJhyB`8XQ^JuTDn z1NPBtCd7Q?#!OiNTga@gHHb@mQ8&5|nv%Tj;^KZFcP9$OagsA-?WcG6bA#VDS*h+9 zlvts4xBn0&!i~d>@=+bL_G+U46mgBUr;akten*4JR*e@kVFRICD+FTpo9PK0c{=Y&4f2%;GW&kT~d}r zE*U=pf`EpJWP!w3TCd#G$9cM)0On0hLsOQ1L{!O0yFSjTLM3F+<7t`oX2kRglv(3$ zB0PvY#EVntDbKyWWCeVLegQu&$^^HY0A@Buv^XdunkvEn3rGM*k&U&G`#j zJJnMcjJ~eK(EN@%ssn>j%lVzr1=*=Pm!TTKKLQCK4|xcl3lFYU2^!5kC==5|dL@;_8i?Eg3cR zs6%;mZyPI?S>CW@Z%swDbZdRM4|z5qYWMaQqE`Z8b>RC?T$No&w@g;<_z@WTkO#*0 zx3=}Km{ucF7DNPgJgzJm!)RG6PZ%m0xu$TP+YTLEO}IqN7Bnru8bi)I7&hO|z`BYS z)I-XO-h!Ib$)sOd)uh#lYLKot^|6ZRy4yphTP|@z34ZbpU^Kh?w2yDO#tB`&N1Cv9 zo6<_^J?4~wrUSb;i0e~p%EwchWW$63q-j^#<&>;^EYkFT+?)2|GV2EJl^wMZN?F{{ zH;-jVpfrQrbdz?{*0RZlB(I^wdWQ)bZWuAVo;^%IY;w8zHR)CKh(OLo>zoM#?Y@yc z9F7G7r=-i_U-Hr+=v$a4X5zz{M@fZKQ+g(KE^I_USlN*o@o!O!NZsp*+ZL6jv9NlJ zM;FZ7o${vW?mClybm6*7oI>;L;`yzT?qok>0)-`~TdXBIzOlTC-R4$7vx`GFeCa_q zx`KQ|oNje-AV??T##p1qSv;S%Fqvmo-?U>B=rMv97TL6u5c-c&=F%&Fel)YAMD<7+QL{SQd@|AR@U$6b?hw2S;=b zj;IEX=pYV`hyji$9EPY4j>zU0q8&J*#w$cRa73PPM0IdPo^V9yzY*zQA~FCFA#}Z4 zsl{Kp8)JPM%Rxo=;oheLO+C(pssO{rsd2NQ@6IRPE8`Z>hmG=3bd!dzFb>jglSpng zGC%Gu98(G;lNrKWO>~o8&YhpDEYG0QP7{(!hU>E03>hX_+L<$)#idf_@~w@iGw(Q2Wg zl-qy2XuTTACi3VbAroO!FFvc}naOb5FF*}&K(3d7u;74j06-*{fXaUZGJ3L~z=Bl& zBwQv2se8Vi#mtBag{12~1yfD9aWqpL@S0&KblIrx?S?^vNoF0gqp2=;c+c%_n#YSb zxan6B=n@~zd&Ix=j5rZK`J^^SrgXZat`~`NX3tTm zEo)1<4;xO}lmns|5}00u>ILzDxw#V#Wi1ByME3pgw_ceJSz(gsp&@>%7aaRUs~;r_ z6)SsW#NykAw)HJQ8Q$+a<{mMqNwMqP{Gx)I;H1=25|Fw`puY%?$_|>f2#I=pZ|e~Q zu6?$LHGuH|63{Jn#6I_Ks){O@=+5}{F%hyiJiL3@Ss`+oW8cj~G39YrAd!XG784M! zfG$!M&PJOMM?|rsm;3!*EP0u0z8)@N3;sC^qb_l<*yr-A431Dp4AF9TYu;^)T*m-RRYz6*Q- zouF<8mT~%z?_)FU$(UpZ)L&xrpMqgy-NUAmBv%V=9N#}!+eZm()Yv7lmKA75&I*-1 zF4C`<&~S^6{EXp!!{Ua(Lw?=-T)Rp(M1`s?a>?+`IM;RZQX%g3>0N9yrA+5d{{!s2 z;XQ1X2VMs?zySB6NcH60@7KtRmioDgc$Uc@lP}xtB&FbhNEI*}nz^DM@?CR=L?U1= zVNao3+9H>%ky{~5JI1HBiK!>GV7yvC+D?rWPa-;gITSFOzozAH8EfM3y0SCfusGFO z(d}lG_N2J$2trL@UvrvQtIIcXdGc-Sl_Lx5or+WkID0GK;p_#~Ua_}9{*yg%cQ|_j z1_}${+d7MGQ8pG%it0KJ59@K2g%``~kshLtz z^^`4(NNA+p_$(VnkbXrK)IVyORp1NT15ZnEVNcL{h|_9C`@|x2Ut)5UBU*>OF(cdi z$xQk5FAGl?*@-OHM^dv_i>wqy_9HKvdGv{;$b84H!kQ2(R2&jh4&0X52L>#%d)@fz zHk9hK2I@+5Qc9~a^4Luh7Z4Uc$1(c@;+|Y*p}>3D9F?GqMRKhJ&Uf|313OIqM4m3* zABh#ag7W6sUiiMwsF9pEyMFP6XBpdSE}3H)PjVS&75_8Bb%uHBi9)jK8^fqt!XEX{ z5}(**Pr2UA5Opo(cey!{a@TIF>P9II!-GSinj5MX)d4xT1-52@0kuI=pR>P9J}-FN zCc()bC)La~dlQuU9&==SQn8gHCBpS4p-`OGwZrC##HRK0Qag#SMnRpxmYv!9%^#^! z;xc5_0Yj}=2CL6Lty(OgJmp!&u{urRFpbs2TFJ)$%!Gtbx`@LN#DK_tE%x=h52KVx zcR`2R!q9vh&} zKE-Vrskp#6STa)mYDgrbJeitZS>PI3LO)7=oR>(!OfX+cK&HJaC<+po%9xFj@xyGn zIC`M*LN;7Tn6U#S$;q}#tvbLNL+Ab@C$)5xOP$3^6)iV(%79T~UM6EQU-vqLR8n`g z-|l@X125B#<7*vz>*q_GB_Ham&x&1bgTMJW{@C5B^9SL}*qM3i}wDl0=*7Via zqC}l6V{J9mAMJ$hFWZuxuce`3mov)Kc|~n)`Fj1BWW=(a-+XP>e;mE7f990lo9ktl&g&nRw#VP=1s(e^^Drb7Y^<$K@Ixm5kfM+tU(b?yR9J=9Xm;pazfC6jpHAX~Tts|^oE zr)`%L5tQu9HkExH{Y7HV8R>2J);>fJ9Xr@!+%89`mK~|kt^2XYse7@XIC6osh@{|n zww@T9>no`3U7F(9@l_lh!u!MbbLp*0|24ZDckK~JZUs5Jo3iqRvYV4i#e zEu=Ikoq{5NaE(xm>ORu_66_NseY2?|*i%!0YkylsSO3^pXf|eW<_nkjJ3(^i2dcsM zKhi4|X!_J4WXea(-n8tqqUZeb5~sf=t?pf=vY;$~w8d5re>zl228R=QXZO=)c6uG! zJJQv*N}PT~1-zBy@u5}k@fI^Mg01C^e5zpUS98x3Asoj+`KK>X543;}G|0txM1$W< zEM%#2tVfwuLL3qn4AzbdW2PnQ@K>fBUhy+z_Ly_Gk)A1I7P?v$ZO1J}%g(S8>ck$> z@oVPiMk!_wYs-Fj@9S@8%u;?;3mN?A8FWw#G1z%mR9FUi$Z5Ga!ycn_d}y&TLilKI z$DEmN1jS~+yhtk}C=G(28#HL~bus#z2|XWudtJH9$bIKnnQ3$8cm-o_W4njgNlnwo zJD;>&kY7Jys(t9}eT3LWui;ud)tq2c^%SfZs~OFtWivp$u^5xbSvB?0a9gO0e%!*N z>S0peQ#h{o&)qdwg1YEE7?6Nz9_ZLWGwK%ciQ-9b_B6N^ z?{qta4s6g>R8p44Xg;wwsiKg#p|8kJjfmCk^zv+V2!&ETv$?s(?NZf7Fsflgv#=Pe z*-hfmrO-&zyokR)e34hqI3vrt)MqVHH>Frj!tlbVNXJG&Zjzn3r<^{$!@4AGRk4e{ z%KN*6R7}od%(1>{|GtBi`m<{5cP+0?bL?1ri0 zbmyJ+cj8~D_8rjIRJ-U;TNx_8cFa3S@eqwpPu+jURx{O z2PE}|M*nlRM^zg~Cw)bVpSH~>TWQ7$xvjdz0V zp7^TY)3BKjAv>*3UBnMk>kndMEJ9m5U5Ul3I`u=+6xOjR!i~+_bwKZ79uv{9`4rV^ zIcLKjk+bCq(8$;hejTexcyJ%9c@B#;7d6pA)1El;p!p+H$lfs^s=U&S=&yEAJC6nh#q+%#~A4xyN zG+qvTb3cSl+&p!d;*IFdj`+POaiHDHnzP;stBL0>$F!-;Dq2^{aZXmux0GzF#>@CZ z6{EP=@gPGI#at{Jt=%d{ao&?e5oDtfrHB;n5S=rSZHAINot>aKF3K$#hz1Pi%%mBa zPy%@jrzrQwH{BZbcmjR$AX8Zd6EWl3%5z1U@aKx)@oX9u4{(P9h-N?@r1S+lI)?!m z0p7y0vz>vViUip~y4Kx?ga4)kc+6q7<33>iCBrvvRu zpr|fEH8RB<$Xh{L8p)CF#mI@$i?@_=y9I8emL?RMx;f0^2www4%vNadC`fj~DY}HA z&06R3E}6ZB#xG(6mXwk>ePOIT)P+jK&H8|Rg8cg#YRZ=Au7&5H+6pH4s-*H|n53>0H zR*RNIE8-D`x_!~Ck_Wx}Bt+r{2K5bK(LYcE@!Ef4G?jen*u5`Lt@7@X&UG3*n1`n- zF9KrBl40qCXl`trAExvMmYjG2f}yXBLK9>2SX3RRAT9$t2=t6yG#Zxo#zZ zk54KBn+Oh(x$6=XSC>Qqgd_d>pK+b8)(j?AKC+Q5Ak$ma^7o z_qEUDcF#4vH_Ay5gSYw-g_CWZ8c7D^hl9uyhz@#zX`)n7TDOC+9(m^8I`ApbTvJ92OGx49O2WT#^(N z#FEC6e13`}6s^&qeN}}VKdrSAqlL&x%SF75x59Z5fB}BI&`l2)gxMiZagqBtmBL8U zn2N!DPa0|#QALWD(FrKc{fuUXeQ(C-oLWLP;Y?+W6a0*X${$)vIo}*;GnHEs^8t7F z4`~DLjD213l;aWoVEhL%jZy8l~P_UP&`V^ z?{EL07@wH$us;t{sZRmHJic}ut*i@#cTgY%t>)CU?i~SsDa;A!#j&)@RlY9+rSmrY zR4kvfZ9-cJ<9Zwo#&wS>oa=E(7}uMW-{QGPQPbi25OadH$xan3c5ow6m79ggU4?n z4~i$0kt`!o04cnrQBe_j41LU#qAW?CqHN4zA*qribNt$Id=pzsr>&&VFv9iCGn=2KSo=) zHO*!A5<_s%&rst72f-O1e7q0Omy`XVjRb??v<1pTfN`yH8p$6}C8Z2B z(F}&H9RiH^;mgWPeob25AE7(^FEk|VbC!_&v$eSZ8#O_z2{3H%fi&;}a!z2m4S5yO zb=3aWcwTuP$zR@ONx2Eh|2~E6A_L)*n~pi>Nd7FoXj#P)!2j@HQukL9TJ)AJ+j7kD z?t!XTd{I7ab;vp8`l?K$F!xePsKk^TufF0z))#zsZk2xO4k&T>D=w891@^4sa0dt) z9$i+at+ZoK-Lmptb`umx#M~o3tw0J`f~9~gAO$D^DL@HG0ormq88Z!bXR5euo>DJYENM#+g506pA%w<&X)D6z{6OUy>{7I$yCD^ zBP(Yp&()=w>`*HJM>%n+B2(bDsa9JYp>}s6;{il$HL+w$4+_G z0p#09JK-j4yy@OE5)1+9jwOKaWLeDYzM2SB(%&M6pW1XR0>*VzjJRW9SDw?e1*KTzw-jx;Q*EXe@|S2%|0j~(cy8Yb?&FWF9gr`p4i zSB8ePvOq4#0&;;Y*daTD3ziF%fXwRv%e+cJ=7j*6_oWh$3mk!5&;jHE2T=JJ0{?O3 z@BG!Qz69bW0G?K6ax|s)jXW8oF5Ky&!BKOF4^@fbMT$>@6inmN_ zyN>dUvTjF^r$QhHm8|iH3Y?@?sPxMd;8!d2%6BxTk3Z`hmCY;1=E^v8BBiVrJJM6W z^0x!ss#cv>p1O0q5}LI`UC4`;C8<9yO&~8}4+7{~?o zD#o*!#k*f_CB8nlaO&5_r7j)Q@&jVQojTunNtw+`RT2U!`z&Sj+GG5+(fJ)&W7~wv z#CStYStR;q`q@!R&_a+&$~ZVaY1Sjpg$I*3qGb z6{xf*@rC`h(tP%DJ%Ox>P8jV2M^KRW@q3Er38i4xQxV6UE*H|kuKCo4y-cDHJ!q zDers1*^ZbK%XY(MUzEWQgR_;4Tw9@vS{y@2%AhE0lHpqleL*yCr1T^ZwCfGFIviXh zs=zM9ecjLg8OP3`S7m)F7GK2!eA%N_$sIw&9JCa&;AiU;EaKXLC@sAqq9CF)g-cP_ zF=RET;m{Ru^wE4SAX`9yY{5M;awE&nq|X5q(D;8a0QU&^4<#CTsT2aZ_}@`5a9m-? z4HQRQDhYS-qD&^V2Om2xheAh%Ac7W=P6{ zmbrRb(9`tXp~3{`#W&!fqv({+PF*#{N#pkeIs|B``7JY$z|g^7bPoY(3=na6cZv#y zf`$BTtRHH`$M10{Q0SGES(ys?c=)rU&3FA1SRy5EKO-3Ucst=ZPbmOjOS4bOA;2Lm z$uj3{fF!dj)aa%$-;J55p@1)9D+jqL_qu^U*l8vs(+V;|D=UewZAeGU&{*aHc}Y`- ztEC#Hay9y3fGx17JF$`9FSJ1XqGF4c!b73vy?7GTU9=V~o) z>@>9Vh55&x)41lwQASy}b?#I?^VBzP+6T$=mJ|lonznc?R-^ma7jwy7w?|*%@u8hsc6q#O?tDMI@ySvpPg*CKKBKUh z+MPH0VPeGG;P+V}UKZLe+_4;tuG^~kkL-duP-)RwDzhT+Rb!UHjzevMo@6?@@hEkB zu4etN0Y1s!r6e%&+d5flR`NhZs-sd10^JMs(A`SGAOH=t^1=+a%8-6Huba|gY^k-= z>Y?j^kgCbGeOnEWJG5(A4!ZBPHql!{){Hh&Ms;b?hpPNl3RRbItCh%`pS$12OL$>T zKg25|7WUA#)is3P;knMULoI1TUYv+q$}MkhE9_MJLuVtSTQ`SU!$01oi;NWrfKI2n z=^G2#xZY+>SK6|k-?ww-q_Ac<8m&Q7qjkd;n3&2P#GeUTRj$KFY zop?&R3VruUA9)2|6OH|bp;({wq6_>a&kC}~5AN5cwaoBF=}H^xd=@fm9p8}$4p(Y0 zOx}N{L4L%`l>r!GeG6s;I@ya`l7Zl-N3%kyOgYqud}ZV%#Z1>vrHPt5{qAn-G3L>U zUrXkBrmhi(M5O?LMbORIEBGcSEp67lU@q$PcA~Pn~vh6go%N)LD4< z6RN&rQ>c>-%FvSE*wV+&at?x8i$;T}rjk8s)zLoWh9@g?1TWdfj^>2&`#PJ$w)OA| zS(0(z5o4FI^g2Y`L7vRf(7@qzWh$XBF4i$|Gef{1(lfUEkwP5N+9_$_#d78P4`_b~%wiaw`MFs5QF zBS?%dEZWdGobJ0uSyQLUPHWap=AO8MUO^T0Ge(_`qt7D80Bm`@_~iL z_anVl&Ge1k2e~-4wJHziE%Ni;ND8Qs=Y>tH0Im|$K&Uz@L5bz#-rBipwG*jt%&kvb z03LVRnFMxvRAg@^%IYNI(w3}zeTp*HX(iwe6Q1Lni?P&cr`L*Bc{2F2_ce&d48G93 z&)boY4oF$N*X^R?-p|0+VhVh!G74<0X=H3RHPIxU(1Y&DVds?!XWhkpGXgm&JvM8; ztl0vERhkK_4IK#3ZvVIkNeR~IAA)l$0K#($Sz--+OlHaeS66|#I^AxlBr6vAin<2* zfS0OuVR5|juDOm(NpY3YZj}n4F;O=4BY?*AP(WNUck}3^xsx~OXwl#H`ddVT!-slB z5Yx(vg}xlI+0~U5+piue3;X8hfxSrSB2A3*_jb#>4b{iF5cv-@K7iR3`~8(bd32pZ z$+fC&onId9r6>a=2a?`FqYWMGSK{4yrV$tHlZgQYDWyjtfhvCbd%1h`d34=RBSEFA zOHl(0gvyr2;Z}Q4V91%%9_wjaVX>@$$95OFsw!2wF9vNFw=OPCF}lXsWJp+HAQ=9e z$-HipbOJ!)IVkw0A`OhsAbV2L(LUq(F`Zf{dvX}8rf0*F$ocaEq! zQBCgXvvCyDQe7UJjV8uO_3;pg30uceb%5HeI`J$QrV8N5A*NamnQUYkx#o!+6)2;6 za4>(8Wm+-W6E$g#w(d`8B|heRP*Zvb+>+a87yr$qrs+a3Z9nImr#apW-C;4daJQ$v zzA;_&QGGE(CeHdpIVzmAoYEi6-&K?CwU-FyK53<7vOX+m!d!TprusD3ZH7mukGyW} z^p@z>lRNe}h2`&v%G25&4fKS(p+P>KSy<^WK+$#BTbiWYzIFO?e|SiLWE<0X%jMux z$1GK3%Im$@$=HkCr^`mHU6?lCRxC8937TG6>kYH3xXpDSBdc=voDbd+T+tA9tfP+k zjuW`87RmAf^lHgoTk-CrLha#?>0|<4p-)EW&-Bx9g%w&pB?PNr7SkgJ7ZS_T1`|S2uYUXw(a-Wad(;VbeNf|hI%EW_0>kUO@!~A_a&b#hK`7J=?+D{-4i62 z!H#v065K-^-%$@!F?dK0SidvQUrWX7UMW zvD$3Cr(SKBy1>zftq<@q>9d;PL*SFr$6X(`%qb@yT*u$pNlZK;;AH%uCZ}e!eXu3i za55|U{Q^}R%8wErVcy}c#rn=RY>kI8V-2w;3b9Kt3yZwnF95Oh-QAtrIy<+CeF?vI z`~W`mYMv5ipl?yXwjpe0b}c4Y4fD)(tcY=yYISP);7R|}imjyIFYbQ@8HSxU^c$Va!{Nv%&CpnMm3DuiN8ur@*JHdkE498|FojU^- zkc+R1Igv5kvNUKLkueZNdT$$_((0_o6_)HQD}?`tOQ z44}#S38U|bb=^aH8t+wlY${~BG_JE0?}bZO^P)w5$ui*PXa6lMOOA${N6pV~Z8LP% zE{Ei5U*Obe@zvg`nabF3*g!%KCK|Id*W}s`8>j*ugq5E&eho+bQD(}gAh2PbBhmQLgWGn^yfPdJDbJ$6W*B@Y>CyC3l@ zQw&+d7kr+gu6NOmzYw|K(R32X8sC)OYh;~}qrNN7^v-@-uPbkSFAR61=$*aw$8S6b zVQ$awAB3%yo0gh?#9}RI@@W62bsbkOf!w;+Z0$mr&wn?Js`FJ%e#sXbYgMf`z3!rk zcxs6yrcQ~~AjS{p?si=icbAEHQSNU)t;D^(=Tw&ecA@x7BkQrqZ7TwIQAdpTY#H-J zyZS-z&G^WZ^|#GMKEFQ*>uI_Delo0P(q`o2quF*E$MI25QM5;4#ImDhrWjaH9%Ht# zB2ztl{Ek137v}}b_b`7}Y;Nz(V0Y1zn}I2M3q+ileIFBK`nU#2*N8aVS#1pZUJBI~ znNF4Rr^zsS#o1$yvWgb9m6?Wp35{o+IBvMzH^;XS;-G1>HWj0pIH{QK_-yKu6U1A?AS_;WLQ6!8;_#fRFG4rarfJ>lW5xlOa~w(hiUI{O@6tpIHs=Yp)Yk zSofKg_>!7v`R|7*c@1q7D+^yv>=0}@;N%=6 zhFf+I`_zV5U9KTwn=|0NhAl>x9ljWhkFdqeKZh+Q8^Pw`weiZL4cft0$VXNV|7&Y+ zi5oHxEsWmUE?7BQt?`p*B+~K^17Dn-FIyvJuXkVj!#nmty9t(J)4kLeG$cuO?Lt;_ zt$gTwX=ee#c46PcYJyCSdNNHRW|8}0ybDCGMW(HKF`rpCCjh#?reP)uy(M1*R+2cu zDr(QMPGo(iTR4fzXPC5b^ZaZ9(0ue$Lf`-MUu&?p=6dd6 zB2npisbQG&b*)FePcoAzKKr^OH*F=wA>t&yM)azj7^Mj>j4qeUvw(g<`Ud^}Qk31g zR-C+6@DX8GmWlFVY*61#;ELJ-^D#`$_b1e`e$vTxm9j&MwIdbAI-wS zXy)a$`5ZjYSu1e=2sL1AncOwVM|Vr$n^!t}!@yF2oo7q>H@yjr620!`wA(Y|5>nUK zIR>}qEz|-v-aaFn_aO++yB3hh&u0E4Y`fN<(t>!t=Ztmm!|jfUVwrySqB; zKinS0^91;FwdIP*h)$x-&-W62?&9S8%ypf4$hX2a=zZAsd3k&{)X&aSZ>M(!U`!8q z7ign8+|&a}-xtBIOy{e9v@P-ni(GXILmH(f*mAhRGoYnQ4@1)`8o0RM%e- z1fbB|dfbibdO}FuiMnNL_z?n{wIfOKTn0YW48xW8bpej+I)Kah(PnS^wXI^OTk{WR3`8}=Fl5~!Sa&SL;n5SP(r&j&*Y3+>OmN%6@FTvTr3Lie$I%i^AT%sA4<8Y(D& z${=hHMcrmRaM{D{YN9x9J6D5=^iXnrOmtj z&Xpnm)qO}%|0|+-=(tWacCW~odU`D2Z8pHyl|y>Mx0DnQvv&Gxg0YecAxbu~UM%X?@6Dmzy=A>O4_nY=z zA63NS3=PeZ^kPc(-nVTTC$GxHsZOP93f7p7}!aCZytjS~n2cXxOBnmq4J%{Mhafa)%ay7pRYZ_c@`v7=q1>#?$e2!Dvd zLmzxW+BG3YT0K~Yf_ysNxBZp@qW)^R3N0Nfp_npF?4apP7Ohbv<*}QeAo~*^)OB8= zize9s%Flc^aZM}06ctX~+!?%!uWgBxDrX%0RhZ`Rk~{vX!!x}+fuMv+CH zmCaOk)Zy)L?JQgC8K;{A{+eKow~7$2CtAtyAF~G|DGN%v5C2S);kPAiz{;}0UbkG5 z;3t?CyEDK&vErCkM9h1s#E!+P<;qJQccrNtZdFsaL>BY^u|F8TJ;9_-6e2Wm;>l`1fLZmi2zVBXyq>tcA8~mp>RP)LRluy|Aw% zw4IB}p@47ad6#Ivj(2t3emWF<4ZBLKicBzj-;yP7B}U=1w8zry;(VlQZzv4D{6UI) z+;MX;9j1#f-ihIhy0MxQg65rE3}*)O>;p$SQD>GJP>K8ixZa9Cg{1Y&IF4f3Pmjiz z5Uxp75sMU`2HYfWPn{{*(LN`gj&osyl>s@Dl((kiL3)8`Z2w)k%IwA-^I{yX$A4oj zk0P|kUq9%Hk}x`L>Td7vx_!Q-$iuQ<^Y?U%&qXwkJF=bWVWx~$1GgO}wmdn12Xzz{=2iM({SFikcG z_-sy;aY#e^fm^3G_8A|GV(s3Vo@y0gumqtwlK1l)+`7Yef_%vr^9DX>M@Ocu(i&St zl;2ZALea4la6_u<#Nevlt&hJcJ4qOmZ9!$RtLTZ6%R3^EFM2Vf>-`-OiJM$1&2TMV zmt*?5_FGtxk6P-r7nqF8z7xu53;}r&a3VJ1T|8nt2~FT$=z}v9WQ-rV@2bHReWOu! zkS7Y!TVh0FZ!P8s#Eny}(ihL}1bLCXFCwm<8(I2KI;ZceDUvTP4SfEPB;M@|<~kV> zP>CXCmL4i82~vi|C#`7Q?LP<}vR38Xvq_sstL7V6< z!^$IscB^iayd#|jDG`0SnpNSJb_JF!dnlqM7cZ86A3k@MV8($aHK0QWG}WvA8u)Wr zK}O?Zb=nPIU?Pd^)cY#if@052{YW*ZP4<@Ke6GoKHX#ZcX7AORfBtG> zRzrBNwy5(tZrr=X=0)3P+|Y`|GVe?EoaN`F8-Wj@55;A+lO<>yX33mJE-gC8ihZn% z7#VVSNV;|d=k&E0&Hht*dO|z};!{pXEVrLdztR;=MP*2Toev!p;mefcb92E&CAbFr zsh0#;wCFC_B2A`XE&()Ng25s~l%e3yea+ z*)9bG%Div`DHqHLrCUW6aoO-`=9*ONA@>7yjM%`=5q{I)DHElsAR=w`*|zJL+{b)|26nFk z#x@ri^Zd?19`Eq91EnQVyzvA4qxd9SJ*DZY^zu)I>WSXTo(|O3#1d_-ZT-1pG%?Z} zME|A{&I=dcG_WqKOtl@2o%DxLZxZ)1h+ym}MbXdti<7$S8~jIAh&4@=m?n0AtGBI9 z?8Iwgp7r9x+k*$8Z@z7}#fm9@r7bAEP57khd%OM_@sSa4T=|CWX!pkkRGaV<@l;LI zBlAsCYeAf@iJg9Lw^Q+)E)h^S03y}&Fwx_j3&+UZ8=Ht?FLO(37D!yEfjUA1H2I?&DLsEgPiElzMKuHpLahw-(oAJqI87xH&LBG1WX?eLVa2F?99hFd;$wjt%U@h@n~Tz#>{Ob?U8x z1aq1jbg_(i(hUm<9BL=zXw~iGdK2I`%8kCs@ax3F-|IOCn$I1WoUgfS3=_TMdpqp~ zYVN-fW94ki8kgB(wm$24V7JvS({$O8yy#p#J)+CN1)hI0*Iz{>DHx%QC;F7t3(P`7 zNPiT@p&fnJw2~7lvK@X*j$2*XTT0+F@L?%v-RY?Eu_(J-y8S{r9XNIj=QCVjG5#D3 zI`C1>X$Z+j-IOL*;pYstn(3sXP9hE<4M8 z%VC!QMR0(y66%=xsOpDWV3lo{VSNT|J+P$wPD{c)`%&C4(hP75`C~+urYDHcHq|Yw z+~Pe;hDi2JN6p-=JDnh?TN#UrwsROgre(g{cBsEvyDg{c2C3xM2L2=ez~Efv)wOMl zAYk3_z5PoQbj>Op>5t)X$-mS_z1h0yB>8TO-su(R?!IUQL^fV8iRw&rEonpEA=!P2 zT?>gewGqBmM`qVE9(|SyK;8B}K}2Rx8d}Phw>Qg)YN5bw?%wg4fJ1ijrRrX;g>64t z>QoRJA<3M$7?8Iw_`bSy`%X`nZ1?2`T)~!=4#5ii4-3gvKK_gCUu{06Ak>h^mh4FT zTm#-)9Bg*yf|SQELGmHCC(6>zDv}e=B}fD|hb^6-C%TR_ssCYNt^W@e_J3GG|FE$C zVMYFjCH23ta(k9*Y04m2AQXsHzuL~3|C0*kpH!O7g^20e>yG=WkOByo)VkMh?hXc! z5xVWUZk@U*|BUSTP!r}?;yM|kA`DHAJ(n0^S?#rmj(LScqzY}KVj*l(4G@3R3JWbH zx_5~$K-{5L|B|JfvUNK7wuJ&NaI#~8F%=cTJ!gM1{cakSDEggqlSM?(e5cBdjl9|F zm|24NoWkmH>-n$<#KOn++6k@Q`O`%2H?A9p{nR?&+@nP`vsD)-=gkCfqvn+7mRigM zvpP}L8&&Oy`Km;3;GX%b#yld=)loL{<78vj^O*=R(VI_h9?^O8h+?>7(jn#f0ubEl zT~do_jc~~@EW&tNC(8I(t&rkdd9>+YIBgA{i=XgXPkt2Urd4bd$eVzIqo$F zUU+`ZPB=+_GFX6we(QEh1QL4r$L6ciq0ZPFo057vPeerGw$Yh@bHA!G$@ttOafQ{AzMIX8yphN_x^4yzbLc7pmf7)dciOyvL~MX zB)$-82Dsmy5+Sz?c?fJ&mf19VA!7peZW&rWHWoCV?f@1{E5jEj-uO7$ZNC@q}u#nq>9ZxL8I~bPU_uzcta|4GH{Hcw@{jH3grFV;af9Cv_W& zKa-=PV+G-jJeR#BaWgl|jF7jY;(aY2B?kTPqZ*YntQk6oi-u0Fw!JS9Z7AxiW}lsG zC@|l1-?t~627?B;?p=Y&=<&W(CyPlN9qA)skJUt}PX>6IW|{ z{oZ;WD_f%MecmcrVUN*g0wdv%UG^gPkBJ%0m_ADMoxCR$_a!X%TcNdFAw!c&KJOW0 z>f#Ov={{bw?3}V~Z*-8jQPo1e)17QC)~Y*&K?sd6NF1{H=bI=;Cm?`A_cfNhGbP}6K*mZj2EY6Zl)FZceyW_6*1AB zH;z!#@SS37JpwYIu;Cb{rJM8^(azVA=j79lpOXu$mo9wvEO0OPD7I#3{kFQBK`j|y z=&n}D)Zi`~l~jZybbh0L9c7uG8!<`lYRsuhf*z=5U&ZT^o>h!BLG{TiCwRaZ%do{) zBu!X>Y3lN6w8gB*QEmtfgm*Jpl2u!n#Ta1g-|$DIIwHcKhN^>q+8b~)OxNm3^~9hh>3^Z zuA$iFd$?ZpeYh=?eRcc(lpzOv)H5lw=gAJ54>13UR4Z`XW&Ts9 zX5+0F{E+{9!iHe!^MRh*4)fKR72dy$4i$kP+{QNERUvmb#--WdTSi@Rl);})IVYR<1CWSrqu{n&4g<6=0ryo%}P^_SD zAgm&8h~zl2Igs4q^(pcSIOyIc_mP>9!mSNd%3xxr9ea@vrt`(bz{j<#9&@?}}I4`CoOU2G!7A9dkJ z#{u9K8EVhNa5M^+4%sRFd6f=o0P&tfH5_#r8Y=anq{urWSGNh0J$k+}J9yrR9_~6R z8KnrRMkZ?5RYdB%!_U-tjdx7}U@$!cK>f9pwic_J28u7NT=F6??B8EUpbnI6q6C!2 zV-rR1F~!aQs^hC2kwOvv9VZbgE21YB;rcE$hM@XQ0;9R_-Lgnd>n*GB^!w13<6e00 z;I3Ao^AiCE<;klECRtD=>Aqz4vd;THiK~bnU7fr)jPOmouTqqsVZXD)$G}Yowsz^x zntuF7sz6DAL_v_7_M)(+PEpT+{!VQz%U@C;nwfJPgML$9{3G2YJFw%|XdUudmr(lB z+CJ-z_SjD2QqrpNcKN$_HZ9ae)7w=AKj2xPzE&Db_}7Msg;1B;-^0%pmv7AtO46RZg&{=mT_E;=vyU@dwl(iP?` z&xjDitag)CAf2)#PQW}#kdy%04#+f|#>SJm$6FPGmT<_ZT-~+;f%$F>yZ4Mly4m~_ zhg*sSUO*v&tX9;Ptu{XR-S)2>^vvWz=u7jOnlm9vrrPTeP3Zyr-; zJjsc8FA`eG`xe8Swd-mNAjzmNUMv@+x_LO(UjFn+13T8JuwgF=us z$i*$9Xx!3dKaSaVm%l+Bt zu_x(#f5ph)0S|^3g$w(>#|_(fb5(^CD5W{(hs$%uMET>0%?Oq;2Nd6)wQ`WRO1hA~ zSH34P7>#^6V5C^-CJsaP>WU__LU6IVO~LXN$H{V>hGK=KUod=h@OI%r3P{zX?Apz6 zy^b(WTWi5W?U{r#&n;$&2YG7c-TV*moufZEYg?*t6fq8>1GT4l7@DFmFGPp9Yy1>& zb$A-Mxh4W^Tb>>Z=3i=RWu*e3+#MstfoZq?{#y1YE|NdsMUFEr%rhVlE4TPSjDSO( zhwZ@|C#;J#U-uC>AryDsTpSLv(vXsY6~;&s111`a1HI8?sW&lBscK1NfsU8!sk+oO ztsjAW5#X*{fAF415*YM|LQRvN0WN=(r$(KphFe33J08Nv4m+9;0B6Df--D5xx>X@9 zfq&0EJYDaB0}lI2KWwhqVqWg2b^Wv8k7GWOh3 zokxrp_ggF`kPhp!nGV)xirzRdBn4qd;WU7^6tKp{L4KFv|E)k?+a)=eFHISO1~4dA1bL0Z<`C(qkCdcoH;Z%i;8sn3tP+{;5Vzt?e>#G`prwyGbs_OK*mmU+)IO0e2ZTmo~ z(SurBCLpUX;}7+Gz(1JEJ052sHJ(eoLCQt4wh*a4{@Zzw2QaQWhMVE!CnUT;6~%** zQDm_cC+*FMIAK7yyt8nme7rOX<6*}SNPykFT46AYa!Md!9?$J|M%YzZ#M?D0*&ziG z+y{G{5bdHJ-m%ka_S&mwsFT2t6HQDyMjvcojQcaJ*o`k)xdEOZdYSDp>VumCaQNHq z&k}!`29&|_>!0<)1R$WIYYQQy ziqy-;h4W8`-ug+h4d1A)5I6Nr(20~z5|DDf7Gr#OpM6Pr*Y)!vVdjPx*^Ou1Crh8 zafWmVD_=QH=cl*!D1x-dAf!Fe3V$_+w#wl8x6GUYAFe|+w^$-@j4%-kYXffAO1o5h zd+OA`I}OQGF(LK-ST8^{hwmOq21!X;+GC3r{Rj?e-==Ue9TKWp0Xeb9Bg0)f4ii)a zPQX$33knQcz|>raJ9*J#LFOcK5Guu}fNRxi`@@y9;s?DGolqb61Wf_4x!N5vZ>C_l zr#e$|yQN}_D>_HaWbAviUar)B$^r^?eSJn6%4M~FvDjnDM+AYOI`3jZCl$#Sk=k)5 z@0*JA@0PG+B^ktMY4pKazX(i7J)$v>qa#8Y`+JD&jF;S`r8LS@!&s2;_8np!;%Z}n z@0lUjw(nV*<0E|%RvY>FtH_h_>()i}EoqkVX#gNHU&>wRS1T;bJS+L{ul`91;kyNW z+jLyPPh=qd6C)G`#k^54y1y$kSFt?Z=W|XH>lq4@Puis++hr%~KdOJEaS!}bAdk_F zAKYBKbc47*aN#Zlai2ANu=hKa7v>??G3FEb%~h4MsPFy!)?}IO8h@lOf|1rIp@#^_z4q8*`PAr7q6%skwQPH3W>;p!Wp}6mS4%#sSNk0d?@)|n zMh96B)Fqh5`Cr2I0U|RP82DYrn<77^ZrIJ1)M^NKj|dHyL^s9DfW}WF8*7mSO@Fi7 z{5T@KF5taFU%>Q=o$ZBr1UW1e9gpH>=BMzdCk8^#hlZl)vW!dafn~2Vjei7@ej9UW zfB)HCXEeeHYU=U`g9$VK2|^_w5*7zV}Aa_$^OXSbZX+(5W_9YUrYS z@wRvIFR!jo=R6$bK{e}#r@l|R%F3(gvH^PAF)ORT@NT+`*;Wk|zAP_}086^e2L!_= z)TsIev6n4Ms;`lMdnchR!oN0@$XaIy@5RTDg2&bwxnGEKYT>cl@Q=)sAV-wEvV^ep444q10(8 zSU_qgA9n$=0mBl`a6s_3C~0?)58e~8>9P<@FwCjG(p4DooQ>;--&^Q>NR*dTk z77Ju&w;+t_2iB*H0N>Bn?ZC5{j(6t^>K^I61VR`Ch1L~ACrxK`nvTGZRqk#~=#E-F zwziN>U7gAfb{un`Z#|=!BBOe5{FvNL*T@}SDJ}aFbI>OasTSP?HcExE=W*!{PHLya z=M$V9nknv0`rQPE>}|?UX&W)C?T?Gf6h2mqSI5q1 zzpZ@QlvF@+b#01X2^}Gs(6r`rgOkUop;{ z^(s1|J*vy0rVnJ}#&8;Uf~%`)6wboWD+?G+pZB6qO(=-vzIX+)|kjMc()cx=qCP<4@G8m9cZIni8Xt0ns8L3Vi&rd_rk zNm90k8W7o#j@5CeXMOC8NQ$eM@pjO|fLwWh-2_pDtd(yXa$}wBTG`wFel3zrw>udV z`B@=k8)<4D&o84}d(oBmf9kNh3kd8)_u6k%yIY78rmXBxV!8WJv4*PjA%yIAcE`&) z0YAna&R(Cdvne|vf8iw867^aLwv87Pm6{tzK^gv!ViDZ zZ?0eb{8f}oGS46OOyy+nmEbPL3o4-lI4Lx(JlCh|Z>G4#L5-&Llp(EL*nJDL(Glzg zsnqup&>$b5SICF{yqwM^X{^3bMlyHkL2<2AoKr$p@?pPURG>{<77-MM!+7F{h|8P0 zzHwUrMBuV5hv5nnn6Z^W+DMr`sRg3Ts1_}Et#LLPiIul5`%ki&W$um9Qo1Y({T_i0 zYnXyIIZA@*8(=(2x&HjLFa5d?Y63SdTG=b`*8Ui5^@t1-z#@OtRAW> ziIq-6ua#AYAu?o#B4UWR5`&Zw`&&sB8YpZEJXNVB?j_6d;F;AmqU%#DI2^2DTx^_NC9Q?T>bQTLv8) z4AuBDO(ZsZqmLdd?t1~BikpB6I0L~0mbEZ|WQgV@yz9Xi=O|$ED*q!ux1GI49yEaB znRnO~CKc1y37s-l*unmO>85Ab;Hba?hREi(f*+czC3S4K%S7SN70an1TSa7`R|^y{ zgK-iTvZoM}@sxp&y$1QWOCrY_4|fxTJy6krZVkkcEforw@`qw8vT+#Ayay%@WgcVW z6@D{3EO7Z4BkXSUU`0VM&gM?MAsLafF57jUjV|_{k_xI8i|>!`2Uzd|MmaQKe(8dx zw&qat_^|1bm*rm#o9tEb;oG2_kKTBJ8-~WQgPq>{6<4@=MCk6yX4Kck>#S*kcHvP_+N^;B?!KQhf&&Y>2mgmWt_Kt!crkyb1uTg%fOs@CUa zh_kp39IaYxz$TgVsp+i(gSQHH*er$7OfwZv|K5PW1c|I1Mb zK4aoP{FI0{{K1krgJyyW<^M9o3(3%P8YDyabtOi4#79l>tUs4~C`|wODx2XiwT5^? zDnKlO0<_iy7W(9Gj;pl4ZR=to+qziDwk}qDDZ&K@hG?+DGL#?bCr8aPB}{6D>bGU` zFRE2Z^~U(DTQjw9Q^A03o^3l~RF z#2R;>rlEjMER?PKu=8dn1Z$IAus{(vh+i&2b~rG@(+UQ1 z8jacH^9ZmZm=dAdz{)_tin@Fx$F|Z#6AvNBL8~0*caBEY7DA<9Dt>^Z*XotCBxXm4uS9B5BZ!uINpMyo0OC<4W&RzL> zY;-^)(l64zUK{S0?q%FX5ldsZ<`nkr4WtNGfCggJZm z>(#*Phc!0q9M9E-00e0Zz7` zP?J8j(ccWi5(lxe6$qi;#~#)1^F#U4EQRzpKS|w3buwO3)1ksc#rr#)f7fT#I^=gz z4tIE&gTXl9oE2ikQA%vV z8c6N(8$(2xbSC$65CL@Yh!O5e!iHd*WME?K_3xT20feB`Li5jWLL2jNVc@zv!W}fj zpx&_2-{tru68@Eb5z3q9haQapcxpSx!F(SY`d~}WQr!?UIBXiGOs@sS9&40=fuF

k>Iy9u;4m`j-wSYoQX+e!-t!-m#r%)j>mT(d;v01g<$u&6YbtQqqzfl% zVboBEbOV|Wa4LL*&F_EsJ!qO_MA1=hR!8ef;fS%dM(g(B%g23lMt8s)kT| z0KZBv zJ8F?jdI8Q6?ET?3zjr}9cT>fCHJE=Nmc-!2aqJq$V2g5{apC?{*IIY6y73Y@ z)W=zf_<_A2ZgREK*K}Knm0!#Ol>z(#Lv|#9+jM&d2qJd$h8?(ifBAh548@qhKygM zZ9MOeJIfTK>g%IYHr{`;pN)|7e3&ey!n3mU6B*d2`Fi=NpD(+8hV|y;5uUJDDV0uYP%b?f=yVd@aSU!o<(##XTQwHT@NwWm znRm%8aKYKq$o`hhG5x$whD+W~csEFj4A|&la2QF;`t|f+=)D_KkmYkyv?5hC0;Jo%=po6uWw042QZUHYZ|Ezh zT&<;i&q$k@JuZLGobo5jktf`g#5C7##b}Q3E=xFYuG|R9hxZ`Wk9n8t ztx28<<})DGgrA6dIaV{fW{onTvs`Twsc-}KDgD8O{Zb2LlKEr?yU?I_)W^-xy^K^- zN|jTDbYTDHD^i)%kN#cD;s}3yU}aRHT`YOb5*VMmKg6kKY!w-bnk7_D?aLr=%7tTo z!IWVt5Vq!<_eC;*l3BkKD9_+TfuArV8~7Ed>d1uoewBzW{#=ZUOD^He2%CFYqNA5) zUr5HErof<6E)RA=QBa1+;xmuTdS4}c-rRICTHYj*v+^oH&guu39EESRYO|duq1h7d ziuyPsun$E2YF{ro=w!^YPHOI!Rbh5*YwiOk3`Tn=Q=>QodM8N_|NY@afO9y@Qfh=T zmGz((Q}p?UB^u>=LAuUrfKg7gfCyf8Tl95$6>>WHvrAlwEEeV!sp&yFRyc6 zVO5nK_ri^nDrOMtf^l2WwO$fT!)HWD7bKKs0C$d;oYl*SvyLa!OZm&H6FRT>qilT| zKo0kdaVD5i$!Ml38zA>r%9$pR$!tfno*Wd=q}`S`Dy=cN25$t90ql#U1xcuaK8Mzv z7$vY9I8pZgdhcMsNG}skq?K!0`z)$lg%Vo3wwriK2tOWJO0>O4XhteMv%|Byz(&}g zMQcVFEK}_Hkff>>4^n-&a{~2vFZMES7M^7}%23gmj@Z|N)X+o3rGkW$&u;l@%-y7pjWe+VP2xSxHF*c-`lHxaWey5@`c(!4McD+}SaSSdZh%^HcAwOui1)v#LFm=J}s6YzD)B$IUxJ?ri}5`1BH_ z`tg_n1T$d)NdZYQBn4(;jE%Di5V!YHf541E(yu-23XluC+D1Uj3;Jj{9m&Wl#63wc zupy-pR-oz(Ytoa4aw1*ElqZEvH5(4v=nH&)V9NX6Zpa5nQ8TBPffQ_}WYU<{pXUTP8s0c=qyoc>qugJ3#nqexz`QI;!{9k2*> z-Se*KjByVa(o{`Y+x((EWVx8ABf?-u7(f58F~*gvX8X@@X0oRLGvl~|rH?W|u`rY5 zi%ihFpK~qHm(h?PiX0LEJ9gnvRr=I6W6F^CE603BxHuu`TIw?4^Q|@8U`BR3*G`{d zM&YDiBt!~KPR@DPMhO6UzC}esIyYz?|G?ihjy;UHVOh?EhZr(L+)k2jo^v2_yG<{h z=Z6uQ#l@z}PPu~|xlI#D1{wK6RQUxxyBUG$0F)?|+bg!be0rk1tMgsL;K#;L)d9uz zK=A)R;(`%x5xrV)lVR#($UF6gQDT zpBp85I8D{Mf+1Zxk&y>>ZK>0~00{7@1Y<&QOWh7K z*-~;`t09w3AupOuR>lGO&*Qba%zoVAKhxiny_vp0^}kJjhev6e`?d&{2;-Ju zH`v5O_A6gDE>~Xl>cWScP&*MX3+Fv75&G^&<`g7|$gTKahmd@d_nPpx5mWfliBW#0W?DKzi zWWbQ!Gk-9XToozaMBX^>H5!XDrUf?sg9LDwhKX0GCbQ_n(Z zs3ZdnvyuTb0jaM8@c3N~+&U_shP12gb15IjNY`9Z#IGQWO#HV+CZpPt7rOXWBLP)J zR^&uPWLoI&!TK%EN?oOkc=Y^idfGu|Ds_(MG%48@p)Fvj!_=xIs9xkHGXjp%WY%`? zfHud6mOS~JhPc{g!e-H0Z1Ngqc!~05l%zXmd`~AUlGuJ1vV(1PoEX#aKKZbK8uJce z=uN}o*{M|nO`g25v`{LC&hl+8x+sCD3Q^a!{w`5DM`ah13PKaeUhPB90??x#miz<{J_&4}fYRf8A^s$|!JHaZF~bMoWDEWeC% zUYlbwI*R$R$c{@FdJOg)WRe>Cbg$Hfr0Tfj2M@xcw`j%Q*lNCG?Mgu$?hl%`c@T@8 z8wwd#R5vqC{2q+`11LC+K}cGfP{FCur8mleuAd1VlHXT2(gRniMYyDJPVR_;0o_HY z>hzV~n(@@n-?wGPKcBp)65Hb+q9aCSmmjv|Zgn~A0JV#fOfn3JkQc8Uit{E&QJ^bj zK+%DDzorL@LK(U@L}{$?OA{)*xUnECrvz34eLr>ZjxZHi4ymnRP`1ByV_f+F<%X+mnG z&}+iaaR~*IHUf=rwt3LCsDMVyP4twg2Baa!>14tj))82Zf+z|8qGvA#{{u{sSJ+$>>uDz+8f}SIRwQXN#P#*^2d&4$OQ)BU9zt5 zM>Xq%FTZ*SjXAzrnK#40%8ZVH%*Z(L<2V4naE*WUOD5f-Dc`nvippa+B^sCJ}nVF_`c7)S;=$HG9G zYF$Vzv6){H(PrZ;{Bq$QxNJDTJ0lSOxKCjhga)~fZ>rlPK@A{%{fI*@>5hn&+(@KN z_`^8uR}#!XnAOKi(q245P7^)YB7t(`ja~E_&vxEs|KS(=$0y+jrxr#QT8jA*P7=;W&GvfXN`7fq@1=-B-ed z(>~ki0D+h@c@O-G$ock` zs$FiAQ(Ltoq+Y>&p=ukhtkPnQ&${jzr=KAhDFxAfP^EE{}{K~x4%-bHR`U(kW zUCp0WVkR0Dhl921*$nfOa>nnY8#E{IL7`u*IY*m_Ux=S z7CUhbfPx3Sa(ILi=+!{+vHxI0d z1lFdL2w(zs7EUDTPelAG?}0PRMtq?ljaBr9ci=D-y8~$qBDqb)H#BCuYVBCAY4^Ns zIKUeiW-i~KXgNE^Q%~r-=BZvVVeG4ms|B;sKW_-Cw69X!X8FJkcVW7IJk7)ip4X%(4B{NorpA($TyKH*p< zR?X?$J(i0=odUpf4IR|Sz*2L^XqN6K^gJ5sE3m^&H)->TCkWI92@j)*={vAK#w0Eo*|_5}p=+;zi# z*;X^O_%1WFn(R_4?Wr(;%0NkjfIunpF;}2C^ssv(c576_U}QKyU;QLiAQ{mxGNAhQ z)8`3_arUD{1Ce4-XmT*9xGqVRUyI1IFf{>8{b@+!#@VbpGHSfS5en85h>lSCl~boJy{pA$Es+$O(G+E+neN_$hx@MOR$LM+SKg2?$jC#%KW!Q~Snx7+Vwj zGMM&>k``AP=<#9a{$%0O*#DGu5^|{2CZ`KxKGLv8A@0GwvU%uIPNyw;3 zq}p1Ge;e!H6(7*EZZ|7Zvd&@aXf%PCTm_g4WXRE~9S)OKR^hnN40)#;pBfBGog+S) zVK#Mvg8wqRnEkh#3W`Y58oeQ2GbF6Sw5g^MqMbFmHWnD%H>)xpi`_q~GfQPk)%dSh zN-N%a#jSb4BfYeO53&fmJi-OsWHZ{g#V!yp62)TwnT1SjK)^y8Np&ptlyjP`^|}Hy zy9lI@9S_+AwTxh$&l?hT1D8nwQ}OUQS};WC*3kbN+4f%}JAQj>WIcAG zISC4lfhFJtqrTrsHQK&C=KH$H(fM+BOR(y5NAhysV(eAu^(Ogt^#w{R z<^}Kj_Un1*t+wdvd0tV%-ka{ao6a{B32tOpvrB%#px78y_CN+Yg!cb(+kGv=)U;el zw-;Geu||Bf6B}0;9r^_s*td25FS%>~k_-3OsEX1wNrL=;6^K;%ufXR2De(P;J-k1N zHAd)d3Uu=%IfHeOD$U%`>9p^VMN;}`H$2TlSD!ObD*2LS+5}u82p`o0C^%@F2V4+L z;JP6bKo1Dl4QVQD8l*}^zDCOCosCN@Q}&l7!1*r1m%(o=FL12_Cix}Zxmp2)Tmt;p z)Us%FFSOi|gxu#0b1Z!+;iA7C0|>jRICn$uaI6@@s5U0%Y|1OJXb60J@Zh)r=L`wl zCQ|1NNzQ#bVWMVkOnqSs6Grgi*Z7})3LvkZBm6kaOxr{KaVEY}_Iihep^MLU87KWP zLhH56`Kjk`B;*1F?uyYLXEy4I2Rj<2Hb@FJHl1?UZd8fPjoj62#Tt;g&s zc>yUQM{RrKvf8FnZ5fbwfbetlTbUYst3YD`vu1Ikk*-FG8i%8`IV4D^>yh_Tsq!NwXj2gC5jhb@PMTr9DUU_3( z+!6$qu0}Fy%`QL%e_#$ZSoK*}h4?Ps=RCoXLCq#QlX}1>?%-U4TGQHsQUaC8WDUKuSpw z5TqOFE(vLANs$KW7@GgJ2JidvexCPzkNw}r-rx2I*P2=Dy3Y8WzcXf>VU}pyw9=|y z+#1H=i62!>!*;O!BJ(ikDU0|UCZ%+p`PV5!F@{Fh4H%TJxcZZFM>1x4{YAuiAg7{0@-|Cf(1$eK_W`UEP8(qL19w1FDkz5}3R!>I?n^t3;=<1o z{JDFvSrV_JvZ%x(kH%zGnk<7!&$t{)NIXJcr^r7OlBkopjvD+xNWuu6sHjq@Om3?D zXL_f?1*CN^v^)Zl5B&9?JvPPHs5ZvWNmXz}6s62!k2Uq>>lKnbRpB3svS zUGk2~*X~p*IpMt&Fb7zdVT#$P7^l1L7><$!1SYw9m??H*d6^}Bw0ypbWd9y?(4r4$%b=x zGEg%@ zT@U*!XVin&Sg#Hl+Nd@#-`Ff${%{vEcn6opT=z|Qj>Z3U^N)HnZNanme;&bIZxc9LGX?rBWAKU zrbg#VDZ?JpvRy&*+7Qfw=bPkm5P0|Z0N+KQ{6`Sg9$5x?e@p1|3mX_$fPY zjcrxJ)*j1a6k^xrnEfxKu}bffJspsKgpy;vseeH8gA2v?`8@`I(zK6yIk{I~{P?Ju zgQQ#)>W zMx-!GWMfyP01eG>TQ zhRB6&DBVn1d2~SCcF5Ig}KvNE&VKbm=&nZ!~4Cw^Nmn zVzan$M3E~aUNDnGf6mw(;^? ze(E>TE#i#st;pIe?1f1ZfVDvAf$i^kSg|=yfEM@!)3rEO4->noOh3BtMfGZd7tIqg z+$q1bS@}nUrOlerJg0kxRs+_>cKE}}ci=W(A5D3Z-kwT$!l&Y68qK3sy}*%gDaMF1 z%1^AwRw`~y;=yN%{8si3(v8sYv*vTdkNeLCtgHNG`3K$wYm-9wk4;Av!tzh&du6B;ZElUV%%wC<*pM$rJZvVWas3BEGJ#ET&Iii>Y$IY zd~9VGlygcH8vNGr!apj1{p}* z*nWSU?qgNumixnIUxPM`ZHC1zQJejSM#x!>Q$yDy(_C)94BAHpA8bEPAya75^7WKA zmQpq7D~Xzf+%o(=%a@@^BsO>JU2I?6{Aeu8Yv*{$Zn-!?X0d$m2|iNr3BI^kfiFzE z$ed%Ju=RDwUW+T^arPLZaMoQ3Abpt{Kx&!i6W2Z>&vT9EOFw1xS9x#qsm$y8bVU8& z)3d2G0TdLhX!_%T8L0YWcj>=4`SXcACb9@jM$#wvR_G1h}N*4RQE%v+i8GWZ_!MDXe zc4}J=>o{B0r5fWp+i84ZmW(fGQAJ^CC$XR&+(bAhu|P#zp|X7#x{tGSFVKXU{~k&@ zY0s(c3j6DEF!KU5O+_ zw80lc6yRJKdtO5^{jeH z3<4rj=zFVwe%qO5xH3GgR6P3C)v>f$a;|H{s;yh0diHoX-+kH|dp?}vHbLVaBSuWl zSE)F=2-@MrGr=0luaRq*4Z%ftdh+jDPdVw31+~u{%@3O^nq8igN8FXH@ma5Mq49#X@A74(6i}z{Nsn2XtPCC%Pw^V zQ{As$9+7*u7tggWq(y6 z3;xhD;oH|+nW7svs_ycz+L(77-GYlWmv>l5eqghKgCB^l8rRLR52{WytkdQC!2Qi% zo0_Wu!&+|P%+A{Ld&@0*!9JJp71)IZ0}!>~-3O1|F%Z8I9$V{{+wEE`8_~*i*9HUr zM14L(x29tX1!$jmn8<1~x+$tNUohiY)M4Q%^lYB*vuWYVt+a=15*qUkPu1rSGWGHv zZg^bN)1KEiW;|OxBW~Brn7TzG-QR}Z*Q7CC4eX0F ze*L`v(SXx+)uPzRN%V&87Q?~8=s_2$a-I9m!HmSo?m?eN_P5N@g@&`luBh{Bs?a9# zv55+gng`VE3PKdSI*)1=f&vY~azt1a8jh{OPb~@wQrPZ|AHWAWYbuK1cpkF%Ee1DK zqcKfkK@qCaltil0XNu(Ju$A8NFN+El#*aN(*jw-Us1j3^SJBC4o(XL&|FU>9Q=fA> zD4i>NVxSH~TNzo!opdYBsl}V2tZK>`@V5xGe4-kCqiTw);;Vbj^$O8MidyH*9qW^^ zZ#g?6jo))pOZZ(^*T$^{ZCs7uPIJg^d62_ z#V*gm{28sMSxhT(zAyzP>E83UbtV2;BmN4@N?ePrL6u+%#gXCQM4@>i*`rkxe^VE3 zF`D{ZC);V@6MiLd(g?on8TGCUUmtM-CJqARv7-gRzt;~UI;R5 zTUcr=-b%A)kr)*mx~QLMrm7D;IHiK)yc?JLFwe&kt#hhzc5$8dY%eUL;Dw*vUB{=D zF`u63uui=DIaT)N@*00uLkxdjO-!TRUGEhQl)`Cx zcVD=2l-I;uAGq9Bx{gl^0}^R(r>&9FYPV4mWre%2I($!}8Q`@HN3&Wo{#k=!A4~P1 zRocYfJ1o_@8oouoT~Pcf>(GN%`@65zn@yr`t@YCD=W9U`YzMg5B(6gxGF=Bz5ANU3 zNDFbhSYspRexgbxm6ARBoXC@#%H6>Fs$C?!1lM5s=k!H&P3850)+zC`R{2jH8@Uy~`kPyaFyiZS?0u?JOp?}mp#}5n5H2A9v*Wm{6z?|# z)z=P`E(j0ST26EwM-P19%oI|y!*bG!+=c7zA}3b!WmA3kyQS^P`Bzmc09wLRHF76) zf_EvCg_r8XY;_5(@9m!zx@O$-b|LjwCYM&k7(J*jEV^hb!p^qbRBX2=uVAsWxD9kx z`$irJlJ=I>UFevU%!8ACA5nO3fvxG$cj@PIyG*M;#;M$I7p{AZ6TVqvoI2*sibQMt=WYYMfJxgc>^Y?u z4;QrNPVizKLcfWcoyAy(l3-4?Fkw!8%JMaLOYURSy;?S=NL0w_SzV{_la1akRKc@4 z{Y-&>iL5=DgW&3Q7dkuoy$3Q^NZJP|yJr-=zMSqks*GQR*~GQakmysz`V)<&cApve|lk?N;tT z(W5F$_`|Cpf#F*;oT9K0=Lik0cC7BIvoI#kr2|14#36ru(ql$)*0W5Uj7_-(S*h0` z3hWgCxPWH_wj2JNDUEIs0bN7ZUSB?t;UX?8l|d`ZlFcf)WLom)_J(nnw~_m!`w3Hw zCD{FRuYWZ{)dUg;EKisFwoQjNK7kB zJhApFEl=KPi54fbq-4xnpA3|YvgvgPb_>8EHzoroB;9-0XmBdR2Dvfz4w05+mxKDb zQ%EEbH32e&87vHfR{wE0S`pErOq(5fCDB`j7sv#Bh2Yru9SVT)eF)?K3dpPjak2s> zC=#~RxDh#!fhxc%)U*%4%3*|+^B`o3otGGb;MqLEsR)$l1%AtdXb3EcAh7*gp8|Y# z6*8X?tb;7M+yNG5224oOF8T6+pGXGM5j6Qba=XenYCxdpYrnq_ zAbrEXS-S+?jhAfUl>f*qU>^#Jt>U2wTo$L0hv)oNfs6{;s89+m;her7;~9e1jbh5 zP@b###&&|uv9dDVv*`o`yWH%sO-9ldH_FUWYcHw_s|jgsEaB@e40{sG(fyhj`@`oP zm$6qg{5NW!suQ7OFgN(zczs!cq z!ta{WXtuA!qq=-R`Uh36EP`E+ zfe|3ye*yw5r~0$D{6|J3HeDk0@Aet}X5#ay5a=t-Z&~{{1W| z6}X71e)S)WK(s9&53%LHt!ejOgMec~(i_mlG3D=;@^>`oqWq_QIqoFHad-pPB!7Z_$!yVKYjeVFWQBv7_mP{^Z~2f3 zc9}l^kw?Q&Q9u6RSl6-Nq)@-l3iO|jES3~Ti9SCa%sK)WsJ2A})bI-aij$7~ zM}7in$~YAcY~)YZO@a^XQRo&G4gXohO^wS<*9&-jfEO+T2$TNk3^Nb?&491{^$!KY zZ^`{9`_^A`-C9x$D~4C1u-aGb}Kg$;vDyg z00Y+;ENJ8?7QXr^%GM?OWnVKBCjn40To$CrNV<)dwTl>h8Uz!eWkgd5JF1zZNBor*?VMNh?AvYd?@p|LA~*n*?AftQ zZ$)UNgVgCKqf3B>0o@`1RsaHpxsz3AMSzM69x(hi9T?D#7YwL!!egfhB_3E$NW&Sf z^cX4vCp-xLlr_Ji-Y8XQ;mJ~H;d`=q>yx<;L=XkkPf=GI3T(NKr8<63li>o%=2>251NmGJP^K1 zut2mO{|3q!(B{oQ%Jgb z2=(t81|b9hTn9a}d)Jy9QQm~`q-6x4NqrbXp}McHcF6f@a)1T+S@x^d46lD@wgBYk z0)>tlhW`itQ0^a|yntTFe;Wg#g8)`dqXd<0U5gi89`_HkG#^Lb4vuQ z|5pv#Qo_2kRFefw2q44bp$vB((#~=CE5U}K3bY7Spt3|n1)5ocQsZw+;j^F&bR){Z zp1EK(gNgqqL}xMmeFmuspB)ha^g$#~9HjiO`~h7QDibgVIV(1o3&VK?7>vP&MC06jotdkds6Ic#GoV z;^?mu^xr`R-1;v|kSSC~5Ex!|p38Cz^{mSZgSa&)_X29Khq{)obb3Qe(4w<>K` z{C!TmEFr{UP^=(EgEt!xVM_;R$U#sHNShFmEVo*Vz6KR`0Yq|L`v2$ct6+A4P#AK5 z!X6E^SnFiG9Z=++qoGX@z6URPXJ^WPo$ z01T(VdqqUILL^WA@5Tk4fAjJ(eTv*Q3k{(@4NZ^;j6~h3AcLUE6+{xz5`Oy*F!)z` zdGH5=-jhxocG)voD4-6O60)iW%|ib*IG5JaExJ)%rWa@u2=+oF-QURvy^8}y`f~O_ zbhQI8w9T&l4|GG+tV`ejmgoUqOI-A`c2J+65B7PU^^H|Yd!p6|7UU+nKvH=GRoJl_kX_JCK2dce=#uwlu%M(I=!-qhwd-B!0QPDIaUtvt_?V@{8X zkef3x1jo6Lf9VAlu3YTtNnfydxDq$We1&bLNF`j>+h# zBp&&%WyLN9UG6F5wbYaE$m3Uo>X21drjc?it&m`){9ZX@N8dxYW+|?F*PGz28MKaLI(=0f(cEZ z+MAWpW7E&(dK&Y;98?oop#veYj!xVhEZYM*(X-t@2BtfH;OMFTOs}JEOz?gd6ziZd zb$NCezdTotz84qFTEhXt1(Q}FK@RHu2+ceR{HQ>SI5R@*oYcs*aqpW5#m{gMmn;Mk zr=_tv$c&_%a-;sFhy%!YVc|7|NvxR&5e9w;ANs1CxuKiKFM2)-*Um#KU8C9%y6)g2 zL>XfvJbG+pj^5LVkR%X~*joP{5|j{+@N{w436gUpFmg?!MHjM2^W+&~e{UvY^>hfd zT2oEN9KE33#?;~}!oc^-2=)6`yAYCV42zJ7BNLtPz1NDhw89q#$Zj|j0jSq)5k|bP zLTD+wu??1|f+ZSPu|j;HGaLn>%yGpPGNbN0KokT@c&_)_jZuSVTH!BDH{TsF#YI<^ zR*<`bSiCZ2AK5noQ5cv$T?I-XfK}sbLU*wX+CP`Z%DEtUtS&w-TctF03JI z#jNWOb*Qd@IGCp+%+j%$M?l+22^mpM)it1#udiq=9FtzR+=4KKk`N)nN@xr6Q_$0@ zr*U5$vTQuXEZhfJI#h^=inlVtjk$1Wxg8KdXhjfIQb1R6~H?iZB~E z_h{q&vJ0!64a>KE^%#edR%SXN`mJUVa0YDt32r$cZvBElWBrcU_W6(7kWU)|F|EKR zI0dvm#5L^2E8&<{;lBhxDu-B*9>8b)75C1=xz zxD3|JyC5!KF8lplxc#kGIDOTU`oDJn>p7f4&PF(9KIu=P|DzJ18`}NvO8?iD{N4?e z{%PyK#QtBsp&d?NLnY@R9P`VC_4~g1=e1(PQG>5Q`Tx7|KSBcN8oX9aG-`0Cpj}BT zJiU@i4saH*_y67apCQo>Pp_tuvlot8bzvReSI=21Rv9(O1|a^w8~-CDc)D8e9^Q@< zrsMVb&LMw0P8)i_1s=FV4|u?XMCbt@cu+@2U0>-CB2{EQz^lcBQNy6!_0Sf2qK$Ym zars1ts=l%pEE;_@>iUi1m;HdfE)RxlqTLxuPm>O#Hpb#?hf{zHflILU|LhSmAPUwDaMPspcYF^z0;D^xW-ix6ku@@B$SH z>EZ$jIv9p)V>gRk^DF#3kED9_R+ObUb}F9F53CVB3lj6shM#_}YhO^iB^=2Zz1{H} zFbJI^m2WXtx+5UtDdpG(~ zUiH|C2PLf(lWK))GS+39Nc~bevwIuR3U85S31m$46)0j(7O@l?O{K%g4&0}oiFX~c zt|_}QE+UVc!S2ut9=cP||B6!XAaOhWU| z%b6-5%f^EZca<1CF7n|lOH9Z)cWn=dka_m-+pR4x;iV5Z`{G&$6?vwU?)1FS{Me5d z(XPQPH*JZ%x7)sE7$9UJqxn{Vk@l$0)GdBbH?w|({RrygvOJf1WSx^1 z6TR(y6V5r4A=+;Hc)7za;X;zDbD+y4XV534VF|NB<;z*Rpym+OtfoiwKWOwFq!`(jrOx~G3 zx1)fw@AFZQoHF=-&r|S$r4kMw(tzR3oh|=uc?-RpMk`Oq@3h?I27+I)&}{$6`&YH zCTVV%#ihB4q$lkqDmO@%Am8pc6XgSAywdO<`Q}59IJEewdcoj`$`)@*>qiHey$l1J zU+G6`g2#q`h$5JUIOMsThts!*E;yo|;{}m5MtFT!d@-#Cle;Sh(_XDE%8QxU$xCld zr76u>Ku@!@5PgZ~aL~X$*NRESMHO95y_bcF?t4>QDoKtjF1haHg-Tg zVPmGQ(o7w{ougJwOe}f(Wxt+t8B?1XqOO(79bGy5JB1i2@$?iM1-fBI3yZ)WA zc;SBeugZl-CIZ$i@+Or(0@#aZ@9<6Pw-lQk`cb`4b`$vePLR!m_^8R)$y&ZxCfHoQ zIFd-=&9lYCw5np0gSU%aVkO^6PI&q-9_{fEEF@Nk-gV9l8!;s5md@k8(~8B@{mR*` zd_TvZ<->99PMxP55Bu50`B`8ETr^4EYExH4q-I>G`h5k)&z)d9_^;g(#&%<4&%@bR zUC}e28zSoBjqdq0cd}lSHa(Tu*+sDm2u)*j^lO^hRafAD$Yt3hSf5;CHjzf)VB2HomnRf)c(wvDM^+ zl#e^0tQ;*=fco;GNj~ll9W6TLd@iGGOCxS1vbt=YL1@<1^k&EEWVU%6>%nrT?K7S=ziy?S) zsBAuWW;^`sa6@Q7M7x4fK$|kwuDW?*g?S(Lq}V!Xpz{QkNY_HYNK|ZBvsp5babd{% zblR_e6?ruyiIVTIeW^3dN8^29y5{InZ_y`bjWo)hXh{z1txV3bZ*QcN`F}(wtjLY9qWa zjGSbx^|lRlyjs>>k_^wcuvM>cI~HlNGrLL0QeuWV6c1Zv*r`yQp4r;9_%V6*ww&bL z9NNe2ko4{MQ9N$SPZrO6$*7n8do9)H>gM~^Oxy@=GO5q`dJ%^zto4wEBjD=C?LSP< z-CrvptkV%CXL(uXdKN}oPvdC3Jqc6Cyd4Nr6%l}G-VVUDGjrc4x*dUO z7Dm=-dH&8sQl}twqm`O-JAJm0lV^d_OhjkP4|C3YSwdd1j0=;?iP-MBDk3INVGDKG zDV>`cbt*^Nk_!OO9YMJT-aFZc^&h&=5@90!SJS6TI$gh}6h1wo<9b@uiGj?*oIH{M zqawE~p1t>x>f=sLdFQ4Jv%;!1O0=Wa+fHBC4d#8EY@uuQH++3NKN*yNAZJ}<*vnTs z`X~;IhBNyyHzeaKEx>W2!wJ1QH}6J|rltK1wBdp~sve24M;$aWZ_)?WODw$W5Nl$l zM$5}`)38!?ep%TXFz4k0HcT)#Y-XRjc@QMRU%nmim0JiF3@oLR((U>tzK+}|bbZkG z`{b8iSTLxaIfputPq*;~{Z&pSCAWcdhZu6(ym#&#KZNp&#p5GMj%!meLftl`E*Pj| z5@Ek*UT;INU5v`szQfE9&IOtx#;}LJ7n(2H3_@Td`sappm19FIsA*LypY2UMa4HAHk)xj4IZoF;su8* zKBGl)`DL&~)@tSS%hWl#Wx7n>_ImXG16XT?+twEqmim>v4^gmae0GJrAu%2w}uCJ6{Nu^A9t+JQ&Ccm4y=wUXJwT z5Q}~>dN-+*FYrNC<_+Z76IX;|_bweH22vcu`(dYp4~&<%9^5x@i-C~5U20RQc6vp! zR03&ly1kb-cxG#QaEE!R&OBl9)`PX6oM5Y?xu9%-)+^C>p+VV6J)9D2#>2tXw@M#b zW{*&)u+T{brya_V3bQ+?x)G5Y0z>i(e+rlY&jQ~EauAOrwW8Eza9coW`rfwb`=P761$x49BUO+IzHaz z)M5#g?ordrj1sHbRttD(dWBraZ6;SZKG2j6r5teNC`LCaW9Yrr{ViiIF3#Z+fj0AJ z*4Z_*ItlY_^{2ZdcC&<=X-5_$^}(ZUIIL&)ne_!zZ!7JRQ@O$Yw0j(pO9-_{m|HTO zF6PasUUw!2eo$JTp%IOd?x+3Kd62-^snw_=h_d-?9DTep;g9VAaC9nTrPC~145_nb}v#b2j zX-*_Yiok@aGJ2Y}{kpr4SnRvXmle#DPhm3iW{$p`hJp8HviPx zg~1eqnrE9fKBb z^uQ{|Zgr0PtbrH?ifX)a$Q*|FH}kk+(#=_unmKNaiu63p8p}Kvbg(x7YTZ01)Vq;; zdDvQq>eC;e@`uvQ>rrb3K?u3})EH5rAVvHzQ*Q*DKTWn&Z>XUPJ zp$iXUW4ju;T>J`RFs{VBIxM50dUIv>bzIvl$2D$HaoawxkcDJ&ylE{{kh^Z^usRpC z*7nv|ng7a515S(xQ`RMYvl%6wn?-M4V0jzgAPn_CzDl7g6y$V)Pdvw=FvxY|nt31)iqm^xD10~lewu2urLr;Zs=hE#9DSEAV#m!luxnR9^Mt?yFN>rcK7avt?=8OzHp-I&FhTnaABMG`25j5ci1KjUMIM=KSq_Dv~fBWD17-T z3JH}evL%P)YrQ#nQgac`sK{OGo8JjXEpGQ^6mX7}KgYE$FTSpP60;-X8&th>Hox~+ zX-xokqj&M=qljROmci1Ol2fq7e0{ai*9SlR0}3qeHC30tde2l@Sl;B%#DU#gXHf2~ zXe}T#j&5{{g~dTfAgK1eE#+U@%ztaMypPZpQ$!4D>-04xKe}b>!jQdB!R%PBD1@a{ zY~l1i#v)6urxte8@CsQhT9UavZ3phY&IfcpyK7bt?e2C2&6Ir{^c#%jiVIb6Y^^i6 z;Wuk1Afz6_^-&2a?=|sFp)s%eqhwFB$*`?Dy?X@~8o~G#jGu8BY}wzm@=IX0(%CT- z6Dl9Y=+OyD|r886)cDrtV12Zc&(S7>v^j~MU=bVo>FAD6AXM{*nm^E_N=mRfijdKQg z`lKH5WYioTAN35b9PRI4SpTX&Tr^9Gsa<6vzTO}2<_L$MBzuBaE73hB^V$^l(s*Z^ ziw37B58A~NSN7HV3NG$Vd2A0S&K>NXpYf0Cp1nHSSwFit>IkjAIGS>IFLFW30pCSO zp3E8)Y5YLlNGy^oihMU=0yXCb{Ct?bN}XaEy!EceuB-e)uxwOUq~XXmv2HD$oN}qR zWGTOud*D9tu;A+8QA6)iTg=(Y_jd_FCcW^D{mJPRnVOlf5V4$lckhN)9mqMzU%YBq zAKw*Z*3gAhFY%h@d-H2@RkscC>x!PNRm`03Ppn)JZ2!t%T>V z%5ZNx^P(?ggkvM*n=>2wqAB?!g7Ge*{bJ^L(Pu`l+`ccp6V=lo-*1h5B6s@vVlv5+ z`~FlxvB~r5dResl@LU#C-#pUzzSFfOyYV`w*|7UU;{zv1^5KnAZU#>FpTifAKNYI|J_XqV?7cYhSv$Ht;AYev*-gQ1xP#E!J1@ z{;JaOUo+o7{+hbIl2UO;-NazOUPak``-LRWg%S*JUgO<(LfJjxN;7dvg{STO1qtHv z8S*j=6_|%gJm%d$1qH?E_1dWJe;q`k!%{fIr_jGj-z2TfBt^mEm!lu@MGh%gza5)s zRx_RU)jNNZW`Zl%UizXbe3L+@_eRE;zxEng!fLHGoanH;Z;eKG`xT2??WkPXLYJ1U z+cG)Dy&vX+3NPz&Lv)Pg7p{&w&T8JQY|16AjNY8_N$^;?k=T~NXQ}E@7gM8K`?JNW zbBm$p?Yu4fUS_P(S2WXRECLeM+ANgtE#_-VHNI%=(jSui)SH?bx=x);9iMwx3Dm3A z=l&!_?+Nc(#Lw42ZDuxw?UzWehlPi;Csd;7qN6Xk()VtJw>8$e`FH3}wm{RODPuQ)ZGuR8OF5T9eexKA8M}=Ed+iJ)bExPFsvW{}&tiR~K zz#lz@>1SJb!bU1)eiZsRvwB7g^l5lT8>#N9VSUv&XMXhBnsh&Hv2b7zb_#R3-=!O! zcRY!Q@8)2_j&rG)!S`?%oKqT@*W>oodK^1-iQhAyGpoMIX)vo_ zJIsx1JWwO%COv0fT|dl4^Pes39A~<{XUQ@OK)QXH>ote%3H#c#r50_3R!nboZTbOB z?9Le0gGg)_IOVPNLS_rXQ&`%Mq=c11*~IdOPK%f=wFO@cPm<3K%(6ab{tdzLG&m=@ zsZ%++nbS{q#q~RWbTi+L*&+S5Ie{BEUno&?wITOi19RMK7l{Kkddg9vY25`in5gT4 z+KW0RmLF#@%R!>e`NH5#x_$EaTkY5RyBR!N+wZ=ZDjB+qTlry;pvt(V%18YW^hqH( zrywm{yd?U(B$_LYg`5So51yD$FySt{+Gh|hIFOLE3o8znq?w;PyR1Ls3PEMV;EXQu zQa?_(5__MNEePr!#`oh}k%Js}Sb0NG+Y*^Nn{r|_ElrvHF6Qao9(RXKBdf}htKX$B z3NF1;6nqymPpJeeZ<4-=swkD75=r$H8BSgd1}cjr)0MnciRi}F6p1pg=q3L~fIXUO z2)b%YHcFmJ(0%X5bd0>XMs(HIYv@I()3`+hMCe5Tckk$lPW#4S0q{p`!&tlk>`1EV zH%;|m8iZ&lkLY=en5)1O8&tjM%J@cR`|(DAHj--X2|lKf-)`IU_e@w+c~^?`8Dv@- znaA_*e;{NH<_kF!z>jC# zEn!h`rXh|xPSoef#?BnkH3<*PTvytf9@EuOC%$WWMbnt@Fl3fI{#${rdSy*YeiBHv z#8iT#e!s|CjZK|l+s{V%?mkSxQ&730TAh)XIojCCDpI5MI{U+wFA8!_Z1)XGR)grO z(mibMMoQ?X$u#CXbBiHKkaWmda4?i)ZZsR*Rks*#G*d>&mC;1X9rI~q=1pkq)Mna5 zW~mWWqv>R8yQ>Mty!0B8&M^;#*A)sfqY8*}FMka7p!@DwrUV|fv0r=hFT z^W)^nS|a5U@Dr-1KOtAI>LF-krWSHy{oD=_`XBff1@oDA;0vpM{X*4Ai_B75v!(H< z5kX~i)kp2T{urtrpcWhJMeoag-2}nqX%$4yb&^%}8pgzi@U^1yhE-G^E%KCQ3z4I% zswV`ywtEqeWV~%bEo%N8D1nqmLjZncCRgf}tprU@WtDkCOjqrGQWkceU5|}Ip?CDN zNw+E@Wr3@&b=h~cc#5#gGT%-riB@f>KrhSmhFL9pLlV7-RX_h57T!noj;4)5QMFHz)!ToXqS4s7E1?(d@E9dG|B}G!oH>nV z6aQzy#Q55Wui@SuDm)b+d^*}HB|37)%L=;h2)=q9-SGN~UDi)BZ zlMI!h= z(-P~Its&=XldG@G>VYDyN302GX+)@AH2@RVdnkARZ~o$|gA%O=BgsKi#UswSk|)HD zrfS+wS2S*_2dZ;pF!3ksJO^RDRy4jM(9pby_Z_^VKXQ1%Mx;QwQ7u4K?Y{0sY^{Zy zCyR?-#M~o;nmh0wNj*~543vjKKx*_x=2zU_u+>sPI#%Soou=D5zwB854djrs546M< zBN4PHxrX|93lUz#(9|+T;=BCZPZ$@PS4fZ>CQKw7#JRD@s`=5zkFd=&L zMzfFaKclIRz~gTft$KVgwSE7-A_)hTCC?eWU($$eKHWKstp1$Wo)#&F`3(Z%iN}6A zLlyB5#KAoXh?BK;Ac$v-#=G^IjggBB@|RM*VOgdL^D)O?srBxHF##>_{fyDi*4{>0 zcQ1QHeV9R2J>e@Fk8NZgxY5X5PE#b?!%$>nkLTLROdrlCD}Lk;4=hDj1ziwLHQ*_> z`mjH`@ji9d1vK9E1T=0qs}PWPx9bb=CLWPq zn&#B=-~YC-g_O6|MGlIDEjd&q+A=SeA1;?Pb=`kcU@=bQ|5aF#Sbc^4*x3aquUp~5 z;s&DGp-$O;Yh)f0Rj`peo5yn_0dIo=5-VJ6BS^d@43XG=896uZv6!PQiZJhpMF+z=4rDl52 z6mj_}HRiCXVC8`k@2a}94rbm!*dsmrl)qXab5Zp&G7CeIH;mI4IWMaMH4n`nIqx%{ ztlmPo4P}vj7*ZaX?m)!=g~e2gOg(x8tua_d2{rd^0@MbPRD%+*@{}@h@+OV2^rG>o zgl^nafB2}V0ZFwR&6HIAVNI(C?iHy7Uc=Xo%<*HA0(5%*4kS7(Sn5{@6%{%fnO7<^ zwi-JNb36{N<$czcS1S>IxKvUDFKtLpR)L zO}k{XRt4@?o1{g}3fy03pJShz#p5G=p0UzjBGV)O++^O^39x6Y{=nBd8i$!-tx<`t z8d)PGJr@`hH2%EEtC1&V5S|~`S;0|+eLD>|fSuhrlBnosAsaEl+%gz{{CM@!>&w4% z^-;&%gt}t&FXY@VzM^VYZ&=!0FECf@MZcHVvll?hlfgpwf_;!eWpP=>K>2Tmx>z!G z{|xLR{njj$+%BpjeH3zaFikfGy9hSQJ|%5rHor}UY3@yIi>9{_^~uZZpHm$Yi_#-# z+5p&3BB|3`G8D-s@&T0SynJuF0=E zeC^*w&Rek4Pct$3@HLA}HvB@Y@}X@`QF^l`PLph7w5qvQktVW&31<*YBC1+&tjiRO}O^@ zzQvIRQa6j1{&N_?-SsXedX4ut^*Ay!q&UC5O;MCDHGIABfKaj~$z(O3h{#@$ktKL> z5KEy?ONl4g7wv_-qLJ@|sw|UIGy5=G`F^J%Qkw_&Zd?mJcjCZf0~7bnX-TbTJY!)l zPXi3|j^EP_-PpgHH%jCCSz>fZ*>5$~@+$EOTGt1pjSKTiR`CzdwfOi&v?bY-6owxp z*Shca^@)D+l($+jzn^*J5Ng~~{9sEO3KLh0)o8~oa{O$CITWT^hJykLqr}3|xa7i= zQoBPB9L8AlhS8UvO$=@{ZSM2DuJzZHGB2X6bssNja&cXqOcz-UA9LC+=GNs%!)l?H zY3|57q9oUWQ>dxT6yN-wK*qH;`f8KdCN_F9RB5A3V`E)^Lvna>EqZW@G5V~+pAtJe z_KB`yzk62diQXeP#?_GrMh-Bz>@&yQ0@s?N6R{U?4^y~~1^me?xcBPD)Xv86@kT>R zqib3736^Xv+^p6yxHi@(po4W-r;qw7TX*Y46j#Kv+(FhUg~jlan|^9WtaNa~v-{Nv5| zc-V~aBQc}uUp2bEDDkk>`kH9Wj>p6vj=yfkm$5X2dy!_HPBWiP=bzOJ$gey01w`H) z@c@m~FraK^Vauz#=%5B)F97W{VXOu_zAU$)PlTS*-6(35ZLNXu*_5%7s#oUqfWGcL z8@t|Vv4B|l3ib-T4sjUJC$A2MTxH+aCk zn)u|+VRug1Xi$@{yU}g>S#lq&@R~I!y+XbK~D2ki*tgBx3*tOZ}^kHEL^yU6PuHG^zj_+*(#R(83 z!QB!pXmEFT4;UFqmr9p(Ndr}I6TN>j$Li##dQ+8C)Wmw8+1X0R=+wFMvjHrK zi|HX)3KTUjW(MhbtO$#Mq|7|1E?L5EAC?lj&dCLGpV~ZmJ-)3}Fe$(G{9C53w_+<3 z=!XY1OOhMO!rwA2qfDt^z$2=N&i^{0f85tdG3PI#sFBL>C@etwXsw+JX#BTK$2zmH zl!9H;R>&Hjq9(cE*zfl9<@W9cb8L#9edf21A8Qy!utlXnTKyhWbTKJ9PQG7}so8V) z1R~8%LGc-Gn5nTTI&Ld*2&M&SqxYP2F*^BYEneUKhctFQ`T(CbUp>6~25UM)CnW4v zIto@+_gSeiG7XvDX>@y?Vsz=jD?q_sCd7h}T=n36pcg!}aJge%3IkP0xlAG)KGvyJ$HgOevPTp!QN12Q8~z zyz?VY2{XP3YmxvZI9`O+1`bJ~PBhn%ih`#1j{mH7{Jd&m8AnyMsYSoLVax*WY4tu_c zTKk`hBj(Kg|9os&ng$sE3{}qPjz0L@m-6b{m`pL~UECk^TFc^fPcW z^y`rQ^RHbogozdSa6_Nkg`UIs5bml*v(tA)QCFuc^Y5Mzd(F516z%o(VlJRItsgc! z2#Xd2O_A=;A)g{1{2ZZ5wbZJnefF-})r+WVSO1Cn`Rc;k)|94Xo_6mokY@9=6R3b$ zEsmXy5mGb<`>=zMscT|OuFyLXK6+IeDw=|{>UW^<0Iho33Ba4$4YWvtrZdIhW3D_v zW85RsP_B=q)4vO2OJjA)2L#W)1P$@I9L+~D{4G=61>zuJXrb;Xc$w;>wN~@aF2i4i z>E_V|ide#oOx{#W%@*1~APn9gzl6bdD}UcDur9g~`WtHpldO6C5(j%LFLAKu^%4gO z$1ibk(fSexR*;uCz-@ntgHp(Uad39+)bI$s;Zj$ zbKI2HR=?Yu15mSvbB)vZvUc>St9e$|t&EJ^XTEb@h1tc(r{k1R{_RNNckfFdx<~2SRsuNUm4&v@Ck3cvVk+jUJC#qeR!vCc+1<78&(D_;09kS~Ip7dzgDcb1kS<;@dUJ z6AfRP=zC=ZfLn&eWWjmmwupJ=ou1)V7a&3p;{3cHfiHXBPuJ{xu@%Glb~=}(;i&DE z&W6w@>iPA}`OsyrpOL+Lt@o4oezzMJ;}6=QKbM7B7s}6}qsK?*lT(fM>9u2T5=(B_ z@bF>Hg(`+5Sy*YQos!V5oGm)P?Tt^?8iu-i>nMM`-E`-k4<}z)mX6z~^S-!;K+o2@ zmz(de-M~T*cWY2-JT$k8gWHB#x6xl&28z*ztgDB@D=qg1mGw_)EZGTCxaDF44tApl z$CdL=8Rkchopv6b6D(aO$GDpi7>Ub&$ty7U4k&ARta}tKwR*;?)*86*w0Bmjo?nu>yLE}fX$0Q9U2Scho4+VL7_kU1&uwyW7_F#kYQ+Cs zXsc=>_?9cm%EyBxsw&D#@c?66Qejv3d+x&T_6GFnnRE5OCdupz!51=d(Rz*JSv!ZZhI2Ze^YG^k*gA11D;jevx!H*z0*6ar?2iQXy1c1)zt<)M z6kF1ARc4L{^FlC&r*XN7t-?E-JH20h!?Mya5cx1yd|4c5B@ZgT^ZaUA7%{!R=WJVu4 zW2viA8}T*rT*REbk8Q@ouz&&FU@YfG_LVW&@I>m@$IEk%)#ss^AHRAT+M)B7##(g_ ze6NSUIfGeKr$=S+YLJYMASTkLsCQ++xuHoGvJiAg2$Spb9Oi>RnRFS_DEx;HzXUMv zQXC44JL;J}RN7X-5no4TAb$!_#E9O3_1#vJ^WW(dNvPO64wkY?=f+7Oekmv}(_5|) z_>6PBzE3*=DHIL)MHP&H>d~ua?a2rT9j8Wj0{l=d_et3CCa4vKFc)MU;r}O^FJe0K z;(!Mhed$i8zkoZL&6>d6!cKs)XXR*+EmWYx*ro4HY3F&zKo8w$kgrg$<=&$^82d@T zqe*y)-<8a8nVeT36Zyu4i!xxKPi7iK1g9|?BqbICj4bxev(>_BUq)v6=6PfpiBiNquDA6TfTp8Az3Z8HYmf3@BQ`nP{al%LbY5G~>yW>n+*UZ=-uP)YA`@PC?h zo*N?XbdCsNdKV1~VY&jEp;3|kry1O*Ok^nCs%43yjd;Jm%AIfcG|g|f1Az`JY)ALM zqiQGFI3kF!$f!i0`Z}?{L%HCDbBNc4+8h=Vr^yBI@9F43bU`=12qXx&YSni^=_7Rr z!p3A&kvuqQhQNaTJJB7mUSBsuLpbuYUL#{A#VnVb1PS=+2x!adk+VA=s(iNXl8-!cjFE;!H8~v`= zA30Ssp8CXKH%=H0+_@gK{-m`o@q-ZEYqT*iwftEmDPj1gO?HC(IGS;7Zl=T=j1Y0c z7{Lpk%q|~Tzij$`HA1ZChKeakYhkfmfo}8hLc?1bg6RCXjw-fq#nE`@l2IRHFBr1RH|r9uA!PE`tH9_OErKp4>Z%!8pI~ z8$mAIYr?g0|M3F5Ne|}qc!nkEeu2fjReOO|HM`CK87i;wKUgxVXV@pU3a@%NmoT|; z60e1~fep>K;||9UO!2Jt^g#{4V^$8GgBrrdFjnp^E!$0-wy0eTWrMG6CgefLDm&l3 zLWj^o4F=abTTVWR1LxPs-tcRuXm_*i&ludA`E1mF_`w3Fv)uApxYXPxIcfLDa>n3p z)Tk>Pw$M=7$F<@`55rI1M*34a$=cs%C{WV0CrJnQGl%8Px;_BA%1o9d6E3%_%r{V--Hv&UFQ(L{D(0l4|})Fr@Z>9~00 z{NZk*XVTOtx}sP$>)z`wqgvT*w&nkEtprp5^qECfimR^rfKB6?T;17fqUBFd?D)F@ z?&0u6;uVbjE{*H2>cG|Evd;n6pr5!T1$u8jJ1_J~I_J2`{!=eGlqNV1q>E^AtXmw| z{flZ`BDKw2$75>sRsZ2NeI!#EMStYRJgV3(Bo(&^Gxki$R3c9eR|+7#I#wSj{tR7I z`2ic(HMywc89EHr(Y+FG$OH!t=1WspMrj#^JA0|tYHNxGBL3vBAp(kw?ZDs=+&_e? zdRWWpw_fj*EYZ~_ZZm*9*mM&mpsM59q(ulBK;;pnydVyEWjv~d^`}fH;7*O?SfU;d zH=BGMuM%$m!&ER@{r&sBWy`MfO!Ozd-V=f60*CBuofsk}x6&eXu&DNpXljk!;MA#O zUou%icn$|fH{GlGs6MuRe5MR{9yHb5njTd~5waEJzaWkC^Ng{L;|<0@sP7;u)n_z> za)UksN8bVd*m9BJ{O2Nf+?iS!Auf-G94TSPU)ju|veFGdGZwW3cJsg@1w=Qgq#u6R?MfqTuR{> zKG3Wh>GIcWO=A4^BH_lUe?fw%^lU}pPM=xAK7L+)t$mJHsaOOAnIp+KNo|;ZOOw~F zrC+Lloq0D`0Ic;9X${KjPe5qUuo^NUsALU$7i?PeG{;RofnaZCd#ExP8+4Eg`g78EczeDXUPpz75DfRmR+dj`cS4~^>@MElt#C|3@?WxWpEoqVlbB}fpg6x41BSm z5-D4q9?*h#+5B|lFWq2L+XA*k&E(TpP(1g2v>7-}_<3NSL~6(B$i z$q0ri5pzD!Gsns3V8?~4i!kOtq`WwgicdI=JDWh@aSBkMMVvvS?5b=POkWaZVorZg$YA1J5Rc!WwH6P8wv*c3pJL9MA9zU(JDWh5h4=9R|Iycaue`0of!HsbZvY%_})@l z_QpAHUXtTFw38}T;nfL4;%E8gVn(w&{{8n@T8ya0W1lO@SAfZ(LMq=(OjSa?j8Mps zY~A-NSD;IsgzwznqUK6$dgoN$uw4FoYnmhn^u9W-i#3h+^?6Ti=sP4T8&h_qNTAs@x@J(MDl^DW;rDp!#I0)VmnwlW8WOFq5Wl)om5Y!4e)GirqQw2v ztKXrEj_d_;5_q-(>#Y+iDC3K|v^vIIHSf0vEirfB0vdDk8wK`$x&jp_9PB2E^1g@t zL1h-mW9c=>i@ipl#}t-_l1OG*-HNC)35z6Y?SWa{YV_mJ%kF0k9fH##H|uSs^*>9) z>2p~$PF*!dH624JN2Kg%L+LTyxjIELpT2b?*L*q=^E0g)VN6syLbxOr$_V~)8pAL8 z)ul$JMkGBs6}_hNTmP$ng#kkubNG$e4iOrA>HKdp;k?k&M<%Gz(DfH;X%8zKWiNQ*qP{Qh&0N;Y^!5<_LYQe7|z64ED#ZV)3=fU8kf!b zG;|RboPHW3B>ELVI=%&5%s71DvX;^eb!IqufOLzo-%fHUy`Lin5#5Sb$Vc$V_WgW}k3}{{wqVmv|%z z?Y4YNCy-`}hpdpjx2UdoY>4UvIYlw^$o$P(`}wu;JNFm%T%r|L+6?&82Myz!c!!wYzpDu zsbU#*GakGH5L1FvBpi~r;!W`+-y%9pfMVn5y3}QAuw-$bL#W1rM)idsFV6EM#y{}< zCGrhFx7Rpiab8NN`ck^L!6Zk+#=N226WElUf$up@j^%3p<*71)hnxs-L&^wy?d8(DbarE%d6sb@NVQnH-!UEo#D8!+K7K z@paLZtS9GhE``zpqa&H5J8JP6Rdis!bgB*BumI{xkPRL~q!_RYbe2w$q>VP--Bu-0 za+-%ccY^@xOE=^`cY`5WaExK6!1os+!vG;=sz?gp->JO_De<3>G7c0=G}!bQl2k8B zV$%akCg9^g=>W%UpmBw~Rl&cYoVWBi|8vSm`b0aLo;8k?7bQVzFG|t`KQ{q8{Z|Au zklLT;CP2wz0o`~vCSza;(RPLC%&j>+SB+3e7|Skh?Ogng5bZOw8v%h}4UacM=D(0%)1+cUi+Z{%_fNqARz8QLeBvFUbea)hrZO^22X>;phTi~oY;(Mha6&`D zi*N#(AY?qui3ODI)tHWfwL{YtVl?MqM`S`6LbxM@rZHMrnc7F`XYk^L(=d z0?>%1*hfgOvs*^G7rWjF0_zS{GBf-Pk?RR`XL2R%e?WROvyK7j?HUkZ2W;3zL~05~ zAb#!Kx8mYjwTsYH40+`Y{%eF9U`JK9D4B`~w>)Jt7c8mJUWL-sFLIsp%DInCt<))- zUjXq6Pv|ocXmiXz%clIE?)tP@D4(d00^E%Z5AGAW8QNLYki^A3#+bP>WUdQ{cdz<& z+Xa;uYmAyZWVo-R<`JcuwoWYY33l<`+OSTLdTB36(oVFpQ7;ppC5z>yy&`rsl5Vn$ zFvADs-HXgAN;P3h=B4rMUQ0$f1M@N;3)S*-OEg4^2 z-J8Q@NLM*r>5T%FKfb(8=0Bb4`uCp~L;h&=48E@m!kzwGEcITIffmD-l1D!ZJ47Vc zo21g6YMT6g66VjMmc0DA1boFMTsTAA))U?)1O1`swiah!gCvV~jkkv^Tx{cyH%U97 z;or%f8UF?b9L8MS&Ktndqu@-XUH+Y+#b8-ItHgWrGl)a}u}HgTMjNBw@Yg8#H+{;y z&^2=+v8Po5CG)d&qvO-tELxWSEGAwe_~q=UhxO9k+~}nzA80ud*^kGmdaGQGf_Z(9Wl_fgXG^K~uqZW7}7%^(;VDaN!D2*l?4SMB_WB_wIICi>3;D*GesM0hGF^5&l_Jm zgdfiK3(*zN`)0d9D43Xi%GpkL8WSjj-yfDtP8WoqYWiuJ5~{rAiBJTwl7wPC0Qqh+d)JgbAV5j23hQc9)k{ zJl+A13Ar8&$8=*^Y4N??D{M9pet0+!HBcmbq(x@R91f2VVLhu}YW2LX?;kv8jQr5% z6Ctp0VqewnUNkr1p6nRm{f(oZxrI~f@#=2#FwM{Rkq~O_d4Dqm`M}>Bgd0;!zu{RJ$*~b3UYkc3hdu&bGCBWjSM{-HHhUa|4d}b(4L1NM6HURe7x6{;b1*YBvALtKtv*vjdQ;dD~;3A zx8%saQj&L!ZkggbQOm7zz%{&vGx9B!6oY`zfk;Nc9 zkqPn}K*}<(O@4GE;Z4|9Y?Hx3&vlyeD~$52uG{naa5jX0cjJ>VROvPqdOKnL(`71) zX7Ge+dJ;uia9iEsdX>dqq3Fj(w`z14wHU&XY;?w9t`L}kgdTFOba#9h_vpoEA0AOs z=>g$ZzT-)N4H}Nqk3)8*r;YkHNlN&dH-RNwg2~tao>nbcBmH7m6i3rx!Ve;_8#GZS zwA;R)aRDKu6+{n=%lypOuDhPRAWKeA#N@QTCTl=jo_@iR?K(l*D6MqIlz!pyLRV;) zI!9=?p+}ZHb87RQvS(vVLKbW6U!h&24<*9J8jlQFF!NiyD)0(f7Z5jKgwwLhTnoIr z-2`Y;_gPyB2JcRJ-hjhqWc^bA%!i*5e>&$ac;$G#DjUrk=;+O}%Z4xa&3~5BcxNC^ z2(~n&LQ_vf?&j;r5|w4Ns{G_~$uZ?A&*GYumQ#M%*5+eJG=0#}7|*Hr428Od{b*Rw z2@fiHqSEa4aNcj>Qs7z+uh7Tq-W=tiG3{x=i;d)x28Ms4`rj;~fcMh#DiUO^$x82X z$lYC9bM;|e|J9Uq-iv(VDW3~Ryl?q{;nVO2bp=^zwH|e8;Y8?{YmdWwo~gCgfsyTQ z3i3O6&ZCQ*C+__pY4%%Rb?rKV$2|RVI+|n|SDvge^uKY&a#`kebl(3btmt?ndArtd zOEPKL=yme1Pv8@;5D7H-m{y{rRHDjhYy1g#22eX0zhiEzUqX-mq1PLU!qFj%-Y|3- zcIsh@s5%{67+UVGa35O}SaaJO<(TNK!rS&e>9g7>4@wbr#%dissD^N;o~c;@Ck8aE z#pPS(PjFmvs&8H-S9aodXDS9)4hBC$JY+6hIz?xCH+{SOmdjL_2(a!pcI~hb zoZ;~=dUSL;=V>`OIK%Bh>U5+J>X!7|_kivDT@F7PjN%YBGZLA%~a`{&|d61gmYXdd5*LX$;;^;2|;-8LcFyVD()GLj*NKEIYG|TP*oG-L_e|5 zy+u~DDAO(-C2!5UA=CckPUP$IcT8B}Z1%wIH#nR)bLD2}Xu_Ly;(p3*QCP||tHY{b z)vYhT*E-3G#{4yoRXsb`uPz(Zdc|KZAP!uDyUb}c5C#-F^lBgoC(gZxSIe>YI5`i zb&qJCpK!#5WtTJ+R2P3Y{B)#7wLhCs~(;k4Gi(y zL9r{xnw3zKyleV-5UOvtxmC-@3EIz`1sAaev19ZTT>Qw!f4#W%eviH$VR_ZE-{)Qu zYVT{#LSn|05)BpkbA@;yApdJU-Un?4D`JB6mgi8_JsNX(dJTFi=I&?e?sozFr{*3l zD77Z&917uNBVUpJ9(3}^^ZFQ|)^*>CcHHB>Q&pth?KNfM-VW~aVy)tjLOY z_r8XOp0C!yhrzjJ=m%Bg?%L=Fom92N+nMMATG(?NwbB8Co(JDM9-)|7E5exFo))%2 zo*FFHXQ!jfGj?r?(;yxeJz|5x{wWn9Eir=Vl85aDg;SYVesq*e$$J9WbyqO@bp&nX zVmHiEE`5Kwks45Qnyqd+h8G21FY?4TbToz>Mm$!aE*`UdJ-mLk2saX3NqT?L<$9CB zi@sQY%xF_FPwA1>P}L(rWP`|GIaofN@<*R_QaHrcuPHYr5TcevRPlN-j5M;_)l_%W z?0e?$NEtyrd7%+MHXC_8`Mpuv9;F0i5lvc$xZXtgq?o8aNYaAah@Tj)oW`clGP=w4 zVh`8o{`NdNtBpM5aBLyuut>kl^}>zLcxmb$8*0Pq856utA^Q}U4c7=O(~o! z*GRIJU|j80rCuFYeLk+Q!XN&F_V@y}v&hbJvAJJFLN@1InBA`4N@7NdSyvLrNpL$v z^_UU_%xS{H4Zf#g;&Q51w9Bl#WrlP!MPF-*tN2#pM^qCOS+lSf z3OeHwkEL!eDv|LSg{YcTlV#dH;lkdXH)Dx{3gpfHirFTCNIzg#IN71klvTUf(rOsrGiKlw(0SNdG3P(S0dYMWLt!tABeg%@O#2}A z6q=;m?n8tG1uA=Aqz~rhtTd!>S3|eGJBm1>1P7bK=T!0>)mm zUl&BI-%T%SkPG|WuHBxqR`zXkRTpBsuPtm3t!f=Nx39=ZE2L5`4!KStg7a1beFd9) zzWXzaUOWTZDQ+UIQ#FZ+PE#$lT~<9KT~`!O25WeyA1|F5WlQ&j;h?2rkLpMNDdZaC z#yn(Q;^tEv+!D zw%oGqa5D!R^of=qbxZqL+~>O4tsQ!yiq;yWo~7nRJmi%0cDTlnU}TXjVn^}1chJn3 z^XDk;o5>o!pr(|Q*dl%IEWVA5c3?AwRs_hb%C(mD^uYnVOYL=Qzy(7cR;Sbt8%?6qy5 zow|y4SUl$BR6p@jRNv6lF7t~uyJa7!8AtbA_C2syzPch{4CWR7;A{MtvB zi$$g^TF#xVFcf+M%<^A%a+Mb0uZO-ye?4hR;BZqsX4$E1imRPAc@<48ON`yTF^6Sm z2ch^Xo#Fecp}~)!t165mXNk0BubO6E)Er-_#){C(yCBp^kc-`vacrqHr%uyX1sYCkyLNq`G!bMStw!Z9dbcn@nt%OpWlz{gHM2Xyeh= zrqfa{$7W_L7Lv?M4MbYZzH?EaEx{CeI*c+v8gr|S@wLvrmPT=XmdmTWZjlCA36 zr{z~}rq`>AP?1cjR-91gOrNJp5WE3FK`&){Km|}QabNhXL-LInNQZfWf8B6P_f829 z$9yp<)PFMh$EUUI`HmzPbBAwfznm)UNcN7$g)HF>ywp4ildXOGpUW*$55#1V;PFU@||Oh@Q#an`$FlKrM)uaFl7rc=$;V zc={zXlE5_=Jgw^wkY}uR*?hyL;gxO1LtFWTH`b^xB=L~^^x)byh2C)Z0~q=nbu{kd z)hSnQl+RlL!vGX8G%!O0zcJps4U`Td_)U29#K8tWT*gbdsZO_`PUlAsL8!F&plKCg!(vC2F#rDbEln(bw_=JBx~{Xj|y|z#HmmL zk4nPy$^6Qp*paNeqroI$=;cnk_w5fnlVY;$QmDZ5%1Cef8NaWj5(`I#|k{8Qp{j!q3xS;V>lE?SwMI zowQnZCiXewX4abMj{^hbieJ#`UR2_~oXpPum1X;E_efV(RJ?8lg3H7FQn@h>C6+HI z_SC)d320P$CL@4P4>em!8r?%hT@dDzm+%76d}w=fqn&IT^opg1&xVRhEUFMpZjpe^rFwa=;0l% z%+uAR^8Mg7W_$cBxCzJKXU7e)-T8oG$^VVp?5Y7jsv2+Z^dsI6-7@MV4he&ht zz-k$WU&-s0O;!`Mim$|`s{iK)|5g@L0z*io{#?G%4e(sU>z zad2dm>b_~N0U6AQhV6&&X?w7LZkKhZ5|&6S8{eT!3PaV{?KRHOfUDQyx?uJ zW^@-Z;TCr;n_#IbeT*wIf`yr>8}v~QKKZ)C9h?ltcg&0~mCK$)VoDTCEg`x-3k5;u znuh*ni*Ee-cRMMBh3jN*VL0E)GI$Y!%G<6 z4=MAbNl#@t?I(2je(OVs!XN3XP>0hMc4?r2vahch*<&f$T`utrHt(-mf)q(!QD~uB zc&*V{2aw+L%Jkk*-FhOp(z6)9jEWqDn_r@x3YnAnH~3i_#>)W0+QHl&Cs?_U`H!-4 z-^zpQX@dA(<`fm?e(h}~IWxSM;z-uW2v^6Itlvx3X0nJW;1&y^jXF1f+LyfFSG!ay zcPtVtO#Is!IS_V>eV{$Gyi#Z)Sy|kh9nCTdg#j`3H{eHCEJT^}jz24%@BYGN@L7Iw@1tjfSXD>Nv7#XRR*z z!LTd;dhkE|crnSU&b*!Ovyn8&PYPF7rvlLz74=t5 z;e4wkDD|3G>Fem{S&@ul^DQ@yY+v46h5Gqv&c@ZZQx)>U{CZ#SdJs4=zBd1hOXd~# zJ*T%gn(}%3Sre7k{Enk`$@@?jYD~3Y858EZ;P;jqS8-vo;f{__ z5qbx{^yOQqXIbXP$5i3owIGVQ{h*r`jfd`};)Y_`LsC=+zOIE54WZ>MGdVoFkld)_i_R4IJ+7PaX9 zf`eP+YtyK5sT?ez5firo+GRMeRiWsQ1)FIyoeCjFfc*+=TLFC}s-XFx2vKd4*sW}0HzuE;<_u_=V^ zeEc|b=io-L6s$B@x)Z%P?(tuNJLq7VvB zzRyuNWbc&T>Z5w;XexL^b)Tq+I!!S#5~x&`Vm&XMAAQat76u>qGMwJFaFEy5sBbwi zy`EJ`(MMEC*HZXKmz3Am)&G^tX6?KVMKKfSvn)Ec4(y-Iv& zimsg&>wP-g8{PdqzgUf`9KUa{wRHqWB--lDE<<-z*kGA{RW39N{(w;ecKJ3DRcGMm zg+3L#N;4>>QX%{&6k(!9Ep9s|W$KtMI;-c?e$M=hAR;7SDLLIw&D8UpI zCYo=6rR=^=IsrmGI6MT0c2ay<8vA&0*WADEW#NK$+dIY zGy6ss{|tZ8%wenCxmrZ?ysbw_nJm(>WVklxEeIb6#Iol&Nqn&`GjXtd$2VJljCO0} z5c+$nR?>S=_s{VGoqPy;&$;x7wKSSw#HQT2$&aiHH%k$_7QPME_G@D; z%Yu=zr$z*1m#VdgQ{ok;&f|lz6pTgO;c!-?o zHOk%KuDK5EQ2q+zj$?soTK)uun4!Wdj_8dM^`@ryS6a8z z>FbK-!3L3>D;L_=`9C&>z0HIh^PomBv2%gS4eBlZ%2SNwm%ol?SI{%on199fd9Ium z4B5|?m3$cEYAyI(1N`a66Bp)&q}p7uJ8sC`cU}uPZcM-+x&4h~uj%;VZPkk87PsYo zizR>Btnk}fZ9Q-X%dK_VIZ|%vGHH4Acd|XcrrXkG;?i`wJ^tf{{`!`+D7$Tu>C$l0 z{G=lJ`SD5HV>Ud*_cEug0#a~&>2~U!_Vib}UWTddcj!)GLXxSPji2Fd{pSr_rtaM7 zCXq|38+f1R6;T$GyhhHq{E zH9<;Npw0Gm2e~Qm*P8jlPf$$XcdeJ_CJku^(OzjnZ?~2ju55D7J|TNYM!_u+FZOZM zB{_X@TG~yjWNh;0knga1Q%*515J-(HVD-M~A?-)V(?j%A_0#=!^YPvi2FX>SN_?ah zlSE5DK8qaBwlejh)StAy583&HoA+yAtS<&QEzJ(r($e?4#V9O2+hwHRC0L{KMn4C# zF~29zO!+J&bZ0Kb>bbSCf&TE&oxQ2kDD}w8`ko-%(YbD9{O#+_e~DK?2=Kg3mN4S1 zF}c>D0L*~mOQJxw+gC-4k(mC?3JAHf!|0#I1IO<}3RPuU@5t{*ekZ?@(pVm!xgRUs zmSFAjBS{_P9sn(<^dp!&IS#N!4+6pEc$LV%Eg&No*M1Ni*I1f8 z*C4QS0ZLnyqsX_wr`(8TVtYR`-|OXHH_ha^RFFd#JLy0$C&R@)Sq*~$S7*ZmY-s)} zahd3bkQlc2F!~-Mq-YGK?P?|}h~>NzO-TMymQ*aIYv9zttu?wp_~~rc?~$74&##hK zgf**+-g>rv%ezP;ffa|G=xyO=ManeMcM$@66TYlBRMC9shJh?+MZ=6ImRxoE*xs~R zW{9ZXKbFl<+Z6Yl$B2+1z#VTR2UZuK9y|f>d*|+vd3$B)Pp1chZ=$=6Z>^RTh#7cq zlrS;IdB4F5%_16PlnV18cx5G{wOy(_k%GqCR8JzCmRE^0ECay;EA2>-Uvkm6AUEFa zv~AaSH(I%YiqKWvK^&a-A0ZYJDk?Z3+%5*pgm{uXk$LC(?_4|X8!7YDza^H* ztBacdqdB=0#R{>~_&w>fO`LFrxbySRDskj1)YolSzVWIwL)=&Y5DfUIcy1iEl{?L` zy`yastAJskYNE8AB9y%K-pbNBu^lP33Ie+`^mWc&r6NHj?;Vst!Xt$D4nWqghC_Lt z{aHm0Y*Z=K%b&3hJl-t&AXv<^W0gdIld8u$@!WkLniJ+HhvYUcFaAtSV{KJBiCnZj z+tfQ@Qb#{rUQGjL&VtVCvF()3>TW3G%}VpC7xnPj}(yc^_v>TpX$|gIHLh_e2+}>yt9mC%r2-0z5!ZhsRHeXK>lOq~)l*4E zgg8%Dn6zQmtlqB%9tWYc{ohEbC@=~HYv<#8*ED}QQFP*e>s_k4rgR+y){uM7&8&jw z+{{I5+eW$!1Zw~l^Rf=@Z1AtLa}1_C3~kilnE41TKY>F8}{@ zozCJ={{i=0jn+amqJeNn?g-U(D$7;bypG}IXR9_V?0)ZAqS0_{Eu{rHR}i}?!qsU9D@QbGVA}KherM}~7``@c8{JxN z#t3!F;8vr2C`Dc+HzT?sW$>_(E72TjVroU;l(!c_wACWpPeEO7*PywRnELD$pPZ|! zZ~4?Sj2Zae_JCprMXh?qR--X{HrVRc@Wl_I`CSwAF{xmj57+GhIM>P|@-ckXeqEwg zO#xIHU@dOly%_~cvuhOv`n{jaSZVX<4nfOUFX+Tn&*+C(06J#u3%WQ$v;=^zhsy0L z|L26YHhU#l1FS893lXuniRq^oOzHxA9v?CF)Pe}Z(;7trh(Ix!8Se(?CYsNQ zQ1=JL+q@{#9)20c$@NKIV_Y@-w;PL2eavs#C3%n1`W@Ouqr5DIU(s*=E`(*wi`hIX zSR2KV8P*oH%G@5w?Ylx&Xx!oE8uxMk_etegtR!haGwL;bp1r7O2~D#bCXu>Vhz9Ml zUO9T+opgk3VN3ot%JJ4CH<*5#PaL5AWB-7HQ_)pv$3;^{PsYt|^tuV5STbcWt^Z4# z=(giCuqpEkaFb18z|z)~H*Vf`|DeFSb>Fv--@!I_XD9X*&zxC;bhwUz~nn)Js{qP>a!I%MN)z zCsEYVk-MC%dw4|Ws89Gk=1-eDz8T#xk038-a zo0Re!GPVmY-p~nI{K?qOs-%}Gl4$fonXmxR`lf379Y575E4m}VIV_}5zhF&v-jADW zTE){u#w8AYIv4oDeys&eG1NvAOBghIUom!io4;i8L9Z!s zm1sO?Jc`;qXTUKRl-owmAIGm^lxT<&O$K)U;3x{Vv~Gksdhu;-XMnIme~mJS>``M| zJ+>kvhRz1Tx3H+U@a&Wj86+)#a2HQg;$QXRcAR*>oYpCr=KPvF*DKsHo`7`EDYX#4 zWd7FI{BGd3xe6s@f;e=^?t6}>vzVQ5{|OSl#@}+;kbWe5R{2DuTG(>Mzr%5%N=9tw zB`GLbSJ)rohEOA{Lylu_ekzyjo%s3XieGlEeVt^iiIZnvJRauQCQ~NlKQ@nNmLWvj zm`VsehA{(ide&!2zdO%Q5pWAMT1PBf?GJ%g7{6}#qlH{ zSB<2oU|yUyNvIZ*MqdE-8JTe%S+3S`wJ<6AgE}O89;F5A}*Q&ftTjm~6JNM){B&u*O9Y25Ws{=z( zjIsIxW*{m(mnF=7L06wVdn7tNSMe>M%CM77y?)eiL41;KnhA9)TTv4)*WNg+rf}aj z9zITyRa9iiI*VPMxr&RU&D4T_NtOw923(0pl%k_QB5s_`_beh6ADVqury|hf4DS~5U>S?-3!+kbLpI*21C&$E7m7r@cDNJX8razu zL_QmjjG>r}ROK={p``~Au_V^|zG!tYL6=%#5R)J20e(k6VdG-T>z;XkRYmEiz2FaBT6Z8cC^;TiJV zmKMGc??#GF3o^3e$5d<`xfRTf)-}E$TgQ3w%EW(3vw;6hd^bBmrrrD~~U_Lvq z{>6Edw*NV=X_!l~Vg5_gurIhEn=jMONk881Me?Q>$@3PUC6BQ)DOf`rMAP7H*dS6F zKDX6aX+AGdy90JeG{mkDXe@gZU;YEE4R#7gL)GAfNQt|MXr9^rM8{yYZBtAU09>|i z8Y;gx)Icv}DWvYfTJQ@&#J5cZ2(kPpoH`) zbZgt=7o0WRTeEU17pagQVid$ffalROGC~(;KUTl^^3*?5)q~Uj~pxm2_L5 zytkviv>w={FD>8?)MH7r*xZNy441es#@wRKI9*S@TVzJwo(?Hz5n7YpX8p|o1CkQ zScV1vnI<_^zylHVmIqIy4(;pyNa{lc{)tiYjrO&2d~*52_x#E=^drn^#_gQ!3h$xR zgS%@MNr)bPM(N+_O@WaGC5v%M5_Pl{#wZ#UtPO(D)Ni|?{||X@8CKQSwhdDPN{J%f zjig9RDk&kM2oloWogyG19ZGknbeFQ|?(UH8?r+Y8?(M#xeLv6N?>OE+W6d?k9M?F{ ztJj1+G(9_ zy)v(}|1vR!kxk-u6Ns7>oWXWpkilzmpdQx7C~os*fv6bgbMdL@OEpw3w$xo7zd;d& z7>(%1SdDoDo8IPRiP(EjYVsLZ-_^>xF&-rZ&AQaAM6c8#aAwC@(5$R7-(0q;zw9&i zUaV;}PM@~gUEFD$c!V`=t_5Iecy8@YA>wkZNbgi*;Qob4gUxD3_GL^+DGd#I*n=L zz!%A)5f>yjHTY%G3uiV(QW>7tt^Fh=czQ3F&Oj!dgIbWTt2lb^{y9J63-gzHMuL=F zByB_YhdOu4xFX3~w5>fiT|B+#jGPGJ#!^fIV~;hyY@zMnle`f6NLJ8?9s=WSt|76( zQNHNqs4LxS@v5N#rf}!V`RVaM$qXfSMkqCmWaJ+3oUTD^k~`Y=Vdz0godJx}OD2w<0w7qSLLs#Fq2GroJ?m0sWGf$>BiIyQ5M4n#KD!uY4sN(I*Z!n?=LB6+i*H*x zL33owvr9DxRwkn6WK5h-W4#4<^tRxix3wbp;3+zRe_w*08StIAC_~`S??zmHdKb3n zp!8ELJ||zS3XWX z;`#VRsnWm-%YJsNT3awel3Q?lADz^BeUBJ?#(PI+dnF00BYL1 zVPY+et*mP$=ll=B?Gz$1*dWO$OX5&1t!GO3+Q^kQaFVi?%1Rogza~)p@9Wc<7DjjWl-mo{;I^Quj7&N?r^W~>TXd20oyr=Ey z%u%ISiMKlPfn$@n{sHXCnmohxP;hf1)`Qrg5#BKd>`X~AY`67RtsF6jaeyF!zqSC5 zh<2E90+qI#usYrRznPJOPP72dUD6mVxn5{rL1tFr8YSyUyQuZG~G|Q&o2)R zWrETyLJ6mtUQ*s$d~NmV)9AnlHY|$8;h_7^_qrL255g2to5zHs-Z6VEOmgy|=E{~H z&=Swqb35Sze_!3SIHkT|iOoVBnS5^1UDVW*|AP?=aqqMdCZ(|b+~4|J4hL~8J&S1h zNnX>UBG=l&LQ#!=cn~#lq?ymc-r@>M!yAENYW?5DSR_4r+~n^M~v`4p^U1UK`){UKPPeeztbS?%$Q^ zLhz~NJu}jL9`~8o`B@{zP;cam-IUsrNsf7AXV1%3fExmZ&_vMv@j_;$>$F97d8dh< zj-q9@G8wlIIb$Mcb@CkhwPwNZ`30`+P>b{Cv`ijsd^RsmD=`!Bjge#*?6ksR6WY~$~VTxIwPX{^OE{-a+1d!y%TUcD3>|rzHSAQI?#rF+Rsw4S`+rtgI z&|xUFJF{$MA&K*k0e%5LIMfTvkfE`nydSR=RtP?(Z)B5pMpj7drjBC$fks~U=vn3+ z?kF>)a1^ufg*#Ck@8F~O>tZ2?YtslBMV9D;BA=})xPuuPo}LYoikM?ic9eBWefT8C z`TWw<+UGUwQw$daiTw9BT334~;ZJ>zMVC6(jIY`$JAp4mK7J8v!yU&qq%et@*b7&p+H4Z-PXJ_ZmGgsvVWteRqe@^ z2MzE;%3BJ%EMDKHuFlip$=z3!?x`tPR9TK&SBRCY6l>8qGjS5NB|J@)Dqd-6^;whQ zP(bF7rR*aT;M%m4LsY|E8J$&}pk-@S&3rsi)9rtV((m8IS+@!=vcRJ*Ne`o*hLn!U zy--hEw#K0shuc{v9^o9ya6+!UEmAz?uTzE7Zp9q79N4B@PrI_j@!^K^-=@_mI|)Kd zT>4jTCQrA9mHx35n7fr}F5I&(lBjIHsE?-oOYC2BxBJy%DtGQ+yAC5Sjv*uUr`kR8 zzEj}jmO$&20l+1pb4p$v_KjQi$9}l8;3T_Y?W%lFm_Bezwc-Pk^jdu zK*^E9DuVeu-WkU&{(qypD%PQv7V*EySg^29;I9)9qU>y+CkdVZ)00lvIHG)a}$;>Sp%Ye z50#2bF7>{U>CitU{g#QrJvAvp$P}RMir&9?H-*M8f$m(eU(8RP)`^{bFltnJ!?Z2aBc59~p$BK==qC~XM@gjuh%5^Ur~Q$-*4x zf7MAH6~Kxgr1r-^VpVzZzvu)yw+QMZf?YNEx|4K)}A&7F7K=P}$Z* zprOF&6^QMv&_$OXTabb(xF@)LpL=xvmiqs>a$6$ef11I*!589X83#B}-@qWKfCM|h z_J^h60G^Xl<^_wBKehE+Z!ge)tpl|G@8(PRcRLV6o$QEPIGD!wpRtwKO9GuM0ZjI; z7_^%*2nRrHECR$X;kNt#Ch@!z?TVQ)e zD2D%32?n5&HN*dDb|28}i=Z1Z{v*D=J>pITGzl*I%kO?4QJ`mfe)^hxT#)Ea(E5Zw zb2aooqG-`NUcRQy>Q&-QYw~0)S?3<(S90Yb^K7hkD;LRh@rdC1^!59_A`zaD=H&S0 zIg6n%U;rj9xcqd^d?9Ov5Rr&Q6(hn4a1k(h8u2oep|#>QFuSUf(^IRW!_B1%%%Y=< zF@i%V1CmcFAeJi*9Y;l{O8<2uHy5FZp9LV4uF>(=B_x(yM9U>0DquCCNHHN{5IJ>?q}%wv-4>d!8bM!b1girOCGViw3dqa`x9RzppM85&gv0AX;) zb*M8bhu>Y~0%1!2kz1g_u;R}(_4(g};kB2>=Uxcc$jW^_v-^B&--&R zl@m9RgV`gjiI`AL-%|fsGPt=_>7m-;!I`lBJMaHKIw12IJku}+5>F*d=>d>#lBoW! zIs0TjlTiK;fLZBbsq<~b+~yfTapiwy7if*T3+7&M$Zwkm((Ys>5aAa82tOJ0Q9q!} za!rZe2EV8Ht7m{dohE=>KQIUc=Oi?6!IS@5rcD1W$N)pAgNFEby(B`DdyA8F14(-*r-RyXueP{F?&c3f=$I3A7Oy z7zB(DRCTYEMHJQ#3VZuMb!yRoWRalrAK}6s2dFzcr?hD5>0@Y41{4O?sshj#-vR9( zrjI21hrs3kScneDdV!APm-NkHg3r~dA^kk3`|}9aZSwxDs$W`?Uwgi2{i^tP+w+I1 zRbE$FNK!Su>m+kZ8+jhdK+1=ZX~0T>Cx576L1PArmvF9Um|A{ozqt5+9)U4@BFrIl{NosOD?F4F<^>ZgbUmZz6@*LMNFAr z)ko!ZrY1nb4|EoAJFqK*Zfnj{o$2~FSBvfJsNZug+s``o=Xs|7n~wg{9wk_3epwap z^;RA<(N5)h15hQP(MF+Q!M+a!y$?nY4`GJhCAJCD4{ce zKO01oPrtQJO!q(41BKecg9dayy*;YtNxSqPpA_t{eC^jNCguQ5Qu1CzW~+IZ@U4N z3J~j;8UL62aozeoU1KQJ>7kfZKONNm(zg-V8bV|Bm-|7@a2w*k9277R7=-0nGA{^Q z&*K1;N5cJ2MM!AR#rsi23Pg1%{&udv!wmG${}KoXw=U9YA5;Rfa_b}qDvtpzK+6d9 z^#bZ%^bGp^zvI_pyESZC^)`n8@Mo~40{!c+tOBI`U#2TsO#nNp*caUUj_OxL5|pRCWGtr436dX(N^ zGf?PNJ+XL~Ddc?AWs8w%i(mS-_tFNVB1;C60ldl9|K`kU;3K_Q$&vRFTo(cLq0InV!w#5>VMmr zPXkEq0M~jRuiqlFShYRs(hn}t@B)y=0{`3lw}$@4`0B(0aB&krZ?S)C<}X!cI#)^p zHMsZEDSUYRx9l>tSqK1jYuLD^-sf5VV4)h&97I(qtsnHY+OytT;OJHdeAccQ_U|$^ zfdoG97`NCkoM!Y~zh?UuqX~}Wa7IGa_Ph*`sUvw1>A_=w=|Q61)a?dOM}Jv#=Q8(Z zx3Zi$XRr`dlT)fR#>Amw?2O@{v#HZi28K^YZZz`*u*h3F#_8udF(A>PAfc-MpOy~U z0-%7lANtExp1zeF=0OAO-0RX0YQ9iHK>)xEbsquive%%;oJS|VTL;w)SQUyFs^RF3 zU%ULDE@+>vUAO?a3n(6HVG;>=0^qYy75J#P>ev4Ygtb5pK7&COQ>RSnow7B#SboBo zZ+h1Q#AY{U*UA@bJH79(FR%92D&Bv%+FzgCKH0gt-W$XaxH;K9JR2M&nYQD+s&~6u zeD8LB(EYxkewryA_S?hNpFh+m45xU^&VlMA9~e82x;^U-txkUaILEO#Tbt$;)aN5edK!<`H{Ol78lVSngIxm4W8Dv9 zZAeRyG^)-as82=kQEy>Nw~ah0nrn2m2-$$TC*6zzF6OiK5uTq0(~cH=pHy6Kni2xr z!xb$GY}oFmDg_@A!KapH4nmk+ri>;qz@?^0{-6~4AE1=C_=TVpSZDBJZtEcOD9<72 zRo;={I+-uU;Pja&blOymd~8LQm;gp^fnO|334!I|33nfa{9|-w@7@D!*sdm5^k-0U zp)goKTz>Q*0vpUKlzp++XXLR7+E~uZ$qc8}@VE~xc9H8j4N2zHGES-i+`bwIv^E6_C_P2dI!#8B9NWgzSzND^|3`WUcF zCNU+r?`s+zQ2f3l^wKUg5y3#+L>?{ZyHzNF4kl2kGR-6)sB8gG@}!nx1?}<7EaX_Y z?j|}*sLt--K;fOc0T&4yFq9tK}OqfqL{MU0s@IgMRSWaGRB2VtT>xuy zR?*m010(}j{_O*lw7)nM$vf0rBpmicNp!N>Mce_sprS~+psLT-0r7BC_yc6LhLlWt zo)^;rTF`a?d0W#4fN+9nLEiG(Me*N01D9k*iw8E_#r*Ry0N)=^?O}FNR6l#@KMv)z zpBORxWCNyf`C5S;0usOzqP<19?AWQ`mcYt>YX*SbDmQrIkkB7k;uHk%`Rj^5m#lyb zphEw33192NkWw7Jzk;@<5ra%`5f?jl<_dUX(3(LeusIugqGbWt1-Js(1vqiLBmuhM z_Z5FES>wjeZ23#*|6Fpr$KO`~+y0jF|A&*3vf6iz7=!|;vWgJcBa&Jk3@Lfw|G#&V zl071=C2UA33|~@STf&GzB9JP(=>NTwa@ur83?hN)Sw&dv5h*S5LrQ-5lK;=0oSK!> zS;N#|A0&p2*xta@-~$grH!(FtfCKC>;6NHY10K8?ym;2Z$OqRWagT`zzDMFEbo7Ic z9nkR}^NIaybti;c8F}Y5++7}tqjc@>8yQvA#}*_aS02Tk=7PmJ>smAOp(~oJ`^=PjI1O) z0u~G+3^G7~42IR)=u@i+3=EzeJPa;y#=(Ty-rUOA+CW#=#+n)W!o}oZY7+Ol-E5NO zejU!L0CKHLER}g7Vd>og#8oon>NrCqorh#1U(>V*L~i(A7)g9Y@W%WxqBK;?X-@2; z{+=iuIYE%%+qws(rW9OO^kc_5`nH0^itsyk1JZ3JymFFBX;_ww4$cP8lMYkI;m2U` zj1)rZ%DNx>p-y_HQNKnTI?a%OC+{EZgcB_a&&Vh4M;o}POi5QD(ONhVX_1w)fNF+i zOf^(a(NCHsa;4Wx@U&3E?rwbAd66l#R68PFxvGWpei~(niETyh*9;YRSCa66;<>E7 z@CAFGFMAv2k0p9aS#yfXSjFOhR%|h+>I#py9hTqt8-y_o>^4m!*2|`ognwD0czgbw z?M-K=$EE*;vBwk33Wo08>xX7xn%vpnk(vU1AJ}_iR`%X{l@fH zPajm$%|1R_wc3$&-TdSZ^YbTT5^h3L=S{?tLG;;%@tKcY06a#cI!@h@KK#YwC=ncU5yOgEB=(-?YqZ9MD;I54Lox5*cIC?@1WT|tbY88Qv;V6Z3v$nUxbCK zP`VZ=tmbJ@s&p_vakWvWyJ^-;YPHK|$BOpm!HOn-aHhIS=7JjGc2%q9rsdu3F+7-w zE!dvp8E-DtB}WdGu2%0^MlW-|2in1L8IffAd=GAxopfTnC9r$r_Vi0rbnD4mk{8J1 zX!fku)69O1sRXHfR8J(c{9rRu@8DeSvQ)8;_g5t4xtazOaen)G0{c^d@DvUQZ%%9Q z%}V}cIKrx#{S?w-r6*;{v-U_)vjv?1>A3Gj`rB}4dy=7Fgyn}ivxj`zD@FX8<@r`Z z{m9>tTpjnmEtuiEIG(OZbU8eZbTgm%aH-=|e6}@eK6{CH} z#&5f*FZXypB5bx<46oXg*B-&INN-Uz=C%IDx>eQ_pK0C4lNi=>OqwvrMpQOnt=REu zJwatZoW~KTM#^r83!YX{P^oZ#FP!LkXOP7gveTKmJMkpDi8q(WTe&-lCNuTt^NTc` zlbM`@+sKOQ@OFtV`%B|%^X+aQE)ELZ>b!qklaXS-3s_ds#VasH+=xEx6ub`7+0DH- zmUU`d;p)Vxh9JFb4A*eIc!WXXajW|1Fg?^<}V-hEQw=FsR#J$<#GThq&&7peK0Q^5}DtIiAAq|W8* zy~l|4mVy*sycK9C<@0PFfrH0uhTgNn4hT>A;D|H0jBd^rYZ^Yd?5zk~T~1%L?tE}O zfNYSExH;ZzkDlyw-M?Bc=s7jntzV~>jdMP4NSS`zkfK3#?T3moEv$Se|FFhAw3Wm! zon;u$jW!z1!q0)4+4O^+J!S5-EbyPsBg-vbEVYr`Niv-2!Z!;yLB5A)Hq-!Dv8w11 zYg$=>mgz1O2QfJ=cr_<;A6J0@R{;Z;MY%w*;Kxe@?`RjZ6cc3JjD!63fbW&8*0Hsv z?!!dw5iszHMX)V)CBxsNbm3vNW8Hc+$m?P=H<=Ku_lvJrU0UR|32XVpfeI#kpHa64QT3noV9VLo3`CFGs*T4MAfK zicJ-55dwZsF9;8BsKFy(Rq?s^t>)#}+PF$XEmz63tCjBH8&GROYI&z9=kIe#?Wj!0 z_G#(`>aXu3s_l9NRjPSlxC|kZM8--62B(_9xTxy6$ll!J4|{)?RHW0j-wGd3$}?1( zfTER2RPo+Zd4}K=!Jm8!dVY;$0Z}s*)ts75T_n9>K@VqZwdbpF9qrB=QKD5%zp)B? z1YKXu``r(78ijeTZS@r{t2aCrll4TT(@=-Vf2Osj2AIjSFnaNLJd_TxfhQW|ao1rBCvWHY5|^e;TC}G%9k0|R8t@gK zW9~=e9nw8G;)fc~KdH~-b!E(JE{qw6unWmIsfXuAOZcsBv{@KY8w&Gz_^VMX)5!2- z8>9z*phEjb~8&1miBVEA$2pg{y;S;oCYH>ebLo0UA zG~ehT)J#MP3YZ6~n;tsxQHEnQ-OlnHMlm29ONHrpK`n~R4p;(2&3U*G2hEVXEMy*; zEFI4VcUdeC+1g@A=~6P=hf%}GKk%@|;Zp`GiCYw*gxM}+hNEi9aCkt)Jb67$B*Z#N znq&1{R2Yg!SO>tv^*CUE2E-!{#Up40;z3To#lvumM|PcZG1^Z1hFYRkPz#b>{mfm5 z=_kRO`*f=w3X1H4h!{1Dmv43>3yBm2(j+uYYMhdWoJ0Ng=}U1Wb*F=YquTFAyD3#R zTR!3=pL1ncD-GZCn}yk+Qgf8&)I62)!xMAVcyAHW{8rPUjptvAk}f_mbx?0d&;|A@gh2P0NPVF^IjtapoQ9$6LXBn?uZOi97RKEKSCOKj zpoTl#=6O__!;jCHoro_pOJ5|gYSOYVZKp@7!Bw*Cjrh0LMCLqMit+m&l(>Y2S1;KKID&}`G6fcZRM618wtr)n|!=pK_ z?5#^f5Gg(IWNz$x-nPtlx&exG_+t@YGzQonRoI?ky$AE--=&2V*b(O}LO4290>b0E zz857=UOZo6V=d*#O+$&ZpjVsA`@%~PUw+)ZtjABUVO%r2zKuXwvk`97`1%dyPz&wq znZoc0Qjbefv`7F4423~XOGsji`y{P7Tqg3&KHul;90Tq^)O=~4H8`57mpEJ-2$uTM zcF%C|M&r|7g?AWuR<=6?9roJMi*swtMk-Z)vb1|NCwMQlJsB+~=Lw7$&?egx4j+{Pd$#-I0^6~(SxMYsbt7OAt5 z>ihWHkMQk<)C7RGT3`r6AH*^Ye^fwl44+&}uepV#48W?K(2cY8sFU3!m(MgUpp0m=RlEemL!Zuz z=IUq3*)R(9ClP3Ik}nc(5_@YYqZ}KeMbfwovb|x*gRp2&*kK-pE-V>kB*^?^83~>4 zZOuHHyf6DnE13}oW!xkGtnHBsM#cL}UC*1A8xtwbw*wdJhvU;BddfGp^vuW2(+Ay1 z!NCnKCqT^}cy*YwP=)tAkul0k@0E8{2L60KO#H4wFmGF_+6dJ+rB!mG@Jwj?PyL z&C@us{x?;~pN`ivGm88*wKdgUj|R;Ptgg}Do~P5KFn@R`H(itH-@Vg-^9tw3aLr^d zal*9M#bymQJLCd60&b!P2D@YTq)>53@Y}?X?;}6ozDvMuEa0nd`2D; zACz1-Bd0ZLhh1C^OXxKDlx?I2nRNIGc48Xs`V^(i3!{8Yyn7p)kD9_BrZ9FYjCZ-2 z4jeW0eqJI*yNg746=s2dZfhjLw70`dP$WSAWhm-}eYnlM4ZWLhP#6`Wwbyq)C|vLNQRTDdFQ;tDny2}j9TJ^H&G zGL68Bg77;eLW#wrVF34ag z3ZJ3}Q#ZoTd!*^PiuUy^5evyFwJjwiG^Bb4&yTw0cR6?=BRJ+MOxo<|?L+fS4PncxmCBPR|K}RdW zOVg}Q$aoX-)_{v=ZncI@bA}LcdJhx_e`L-WIn>BhKZ=oHGa1YevkCAvt^T?l#8z7tJ>LPVvft5o zhi!8>sw*;9IqlsKTF7>o0djA=zq)6h2&BEJ)LgA}Dwyki^1P|PcZDhb4F3PksMfT< za8=J>%+A_y>@hbRL&0~psr@nu$Rsh^dr|zB`F;e)Xu~L?!hI0YB8VhUn44Y?noU2uV5Ir!zIXvm{%)^UT?%^3kGRSh99EU$y7FX6f=Si}@NU z#^4cKfk$m4WU8bxD0YvEu>3fd7vM%5^h}o8AEg`k-!sCT5D3zXStbl1LHGa(!UsqY zj;DQ#no}w$H5NcLl`QmV5L?ps@qG8&EU)n8v>h3j$yKwq zpp|zQb9;^E?o%a5)fU66ij_(E_Q1(uuJWwI3HLsz>_ct)DUOV7&Y8wf6)_~NYCcCAke&-jp zP6+!IHAc8(w9g{(>vl*aBQf?gDh80v|6#1CioA7TJ7Z0+&yZAZ`faq7q51hzHG-PS zPdYGeE=xL|32v5O<3a*(=^T|zJ3=dlk66s57VdN&6;4oz#CLVF6BD0eef~M$>C`i! z%c-mtPu{WHUVQ0}uOb|srp;^OPit$xpsC`TOBiK>NhOK1%VJicOgv*+p7QYl@y1sp zWZtgkaG{Z<`4kJ*su)LyB)HN>NF{*+#k-lHY(F#%AZPfDqwWJa;{eDRywIHSx6wG0 zUlP|F?EwkU0Z4$3Kmz0i5+E;-0NWw8`fpY=r_@opydkN0tY+v?X734VaCqbF_1e8# zA%^-vwYye6^I|$95Tn^1C!$dxbtvYHf=S)MVGbe?<5RHC>oUANZ`%=EQG9N1jGfB~ zHQ1#RXt3qh4p`@ebs~@yQH0rN+~Z{%SXROsCKb4cEBAED=LL3Ng`0C*=AR<;`QDVV zqECfohcZ@4jcw+Aon zye8G9TSZE;D9rR>lP7b~C;OQ<3g4-#`P3qZTi068E>iQo7^N*}qPLhu%jMj?YsBh5 z>8&-E=aIGTD@bRu6e1$}DHTf_JMA@7#Bc&pjj9^sK?{|mI#c8@$78yq(N6fx<{127 z(fsKl#&QVc&h_b&Bm-&@rY@^vpaqSZz@A*&ZW<~dli`+i$&X5xjGCaYm~8Bcr>pSn z=Cl2<2~ixHWEb!ab?KB+a|ttUy1`edpx<_)vKQ%AD_fO$GhL-?A6Q-Ul8oqhH@bQv zwR=cpPc1biU+u$aRs#Y3cY^Hi2QPPHh%2J2-+Cb>1-^06#Un;m$hqUv22qyG?4A*{ zGb2+kB#W9TXrf4O8oG-R(*sF<`M4JKZ5}JTxoOyYDuvuYMfvroM`yzh`Bt@Nd^2|O zPP}a4Q4=GJKtrK0>BKu755A#8+SK%BP<=kM&FP?N{0e93$BCGZq>}uKAMg3TxKiu9 z9L2HooQQ<_K8F}550#@$PVe#hnrmLe>|2?marMCX_3*>$%yVJsl`%rcCj?lZ6TO13 z=WGYE`8%YGdYGIXjcrD4I_pNV`SnQg>xcA_H)ONkth}k)FkX&}U3$sLo@Ug=J)EhP z=VT)z(qNSnOk8Fmu>U$yemzd}%a?WQ;JVqC3%KkVanVDO*8RL-?lb;K8(Pi*PZaL_uRvp3|eM5TS~=n1Ah1F zEs_A6WRSb#BqqFy4Jy%NOn7BGsdvX?zE1O&RuExSc|0So9aI^r#e=5Cmp=;lyni0^ z3@MU`J)60(FS%B-E5-CozNf>IWZ2=4%f;Si8a%ntr;f+k)ow}jZiLK}rQk)~bDedf zpHG|w5wPlZuZGakXo%v~ zw8zpk&z*Jy>iid`LRMix;7jp#&_-W8qqrja*q5i+Ov*k^kJ?qlP5U0T?|yzd{$M1z ziZYttOi{&$dRG2>l0g;8p4)rwK2EW&=T*FE@YyL#6c6?A^F+41ne!C&x_UC}M~(-!%Gs!mQbX$5 ztVcn@TO*H=2*@?&aOlJ3@8O;fcO>b+BOY1l%E}0D4bgil?R?MHR~Yvom}h%9Vfvck z)pXeMG!Ip$0X1eB@HYknPg2UMI;)?7ZvZxNY}ia>Mg@9~C{-A59Xrq!SklCNBLs)4 z45Im2l&IEIjJO?R;SedVM}4c6%b{$rnV@V2bfIk2K{h=EKb!p~3f?2WFik0c)V0?^ zEXQdar7I>m^x{pIM$)Sx86xY+MGm=>m(j4Lp;?{p^zQ4W9Q#FQ+fy1<#Bh(@7v73| z8ZJ+6)R2Jpg+Xo(h9awC6HmHs->=ZSoKbPfc$i#xq(UwkJD z91y7_hmOMZp@!l09J_xc*nfbWiI-ybn(x(g@yaxhZZFg-&Y)E|Kq8duYmM7K3^BSQ zZIvCE6x8BT3?DL!e0^udRlw?x5f&Jb)9jBk8|kptdODh& zI^NC`6Q7?dG4P~zj0b-@eowwOOdLb1yn{$Z=@SlfN5iD4-M)ejEG7(DKi2L80b%a} zYIQ%Om?euA|6%T1VR~O2)_m|s+fQb*3tY!tZYYT${@o{|(|F9sg1F1>e8iz%{<{lz z2<&%T9zVDa?SOrrLO192^jcz~Npf$v=uc5wAr5O|yd!5#tuh}LwDn7Z!fjBQIX0B+ z^=rpG>AxTy6LMlRHTn}AaGBVVx8q{M-XCymeb)1g8sNy$ed=h%wb;BKCn`F;(CoYx z=CIb_kRN_g>94X(CZwxxO#+p6B4?k8tSrPl;J#2xS8l?P$_<}E#zKd63&r51=dMK^@Z)g!#*h|_Tsg>5KMp+)keuvDr>c)T6kzpO`tA&!*w-9MC{)wT8P?mQhE3jSEdT>+Ex>7QGzuM%kN zA1e9*Hyoqz^Vnwm`#PBvN5;vfTPb8i6*tih!-6!Mw?lw?jgOp7e5{hV%01I13m57i zshQeYy}+7-VHR=nw`o;L1H=kgH`deTjj0V@*uZ1*WrjXsS2C=9m>j8=muJ1d$)7NY zTUcB{(@VW}U(p2oP*A89j4g|fC5BRHb62sJGv%sTkJ-+!QPAABb4|0ihK<%F|Lqv3 z*P|Ls>qIkBZQVH?DbKGh7x$gUn>%6GSRS+5q%U5_2SZc{gjb`VE6TPu@sFQGt$JKWV8{MaNv0^gc(ag#d0{1eY_dbo1 z1{~0y)6~c+)A-dyJ{hVDTmbHizc#^oYfqCkHchkqF&{>I{y~~U=JvK`eJHF73`D2` zMxN^v0rB&Lsp%yZQNO^^862L>P)v65y&i;R96g(2|1Y)+70!5k)03yBzzx0T79d>+ z`>FNuDxi-Mnqo5v`PnnA66+D*<=kN*v_&EH@~oIAV|#@tU9X!qCcfpGY>kg6=ZUp5 z^xXZ+cDvVwEqR3jbv@IL=@N%TYls#_MfEeXW;0aazD5`=N+fCXvnmS=>p;{2I9w)B z8l)VSuDb*!+#HXtS%}fA$52NYO}^H87(u>TKX+^N^LR@1CoF;z;2v+$ zIdJbYy`_-~prAMjQKf*Czy-G!=Y#U{eP0d}%2w{2SO34FGKI)rDe*)!Bc1ZdHK&Rh?tzPEROjy z)(UQfY^i&j#6Fo^QumPTw|ZY1CyF@Sn2uAjmEdWqL}LJz(g&5|36+9q3OpnE>IF)< zV|v1}6_vyo_bEB%qnhwgxhs~a6*DB=cLE!*pir5`+9%VCnPx#$}DgatR&; zoXIOidz#9z%6zNudc}nnn5wmvTk~4hES4&?N^hhyeLRt;%IOuuo$;7N=F0nk`_?&L zk~CJ6%rVdM9#)Gyz01U51GuL}Q8ExYb6PJd0A05=Hi}s6J+JUFv}Q?Gp^a6LhQYzC zF&*uuI$>4y8#4tJ{Td}wX1Dx(HJ}TqCgt5aDju}4j zU6j0^H4i0X#bzDuHf#p*Lr6S&_1#@^k4lB7ex3F2?_kjKCEvzOs?pxS-9?${oo7TN zpBDjN!Xan{e5rPf>)UpZLy-{9vOC&Ru?1#>L+BKI7aw)lGa}oEb0VLtGW8fZt0MR0 zo2*cPWSI4?*2besfiuQgi6#c%r*6Uq+(h5iO0BAXw%F{g{soC6uCr0ZVQ--dDau8P z*S>m4`XdfzUwjPa^pbjuBxXM&Sl~b~YckVO+nVuFOfeD;MNg)|(h<0}z8w%reoX$< z-BdP`k)hEaXPEE%l6Fe<;8!!aTHnI$p@0qQ6IOMxum`jnX+6DJZ=C=tt3tPGkfitR$Hwa1M2za7T~!BP|(VO zhdt^hry`CTqs$DdK%K30{@C8Cx70{qF4NA}_GL;>#>|R&F&%jubZ)sahqdJ;yA7=1 z4Fvmssiw|;;D52(ATyU=S}vmxXi!GjP;lm(QFe$kyZb-cuf&5Y z-`$o{G;*M;S5G7aHv9z%m^6!Du#De@+HM|dJG7nkZQsbVMq;}h-oh0ID5%qI%Nasx z7yFqF>hJ!(J3ZZ(Q%mXz!G5Pq8@?_(gKdTHzT3dnT35*KRmyw>{QUbEjCoiPYzv}; ztvzA@+U{eF&20b^YzxXRvF7m;*qO7WSQr-a@6R~lYuoEkqsXNrZLu^E`QI494u0P4 znMU5Rj7MgUk@#4IIYUVV9}u{^zKx1YFh5KjwF#IFE&ykquklcuy!Jqj6IMg`lf9X! z1CRk&L_R^~)Mp#O4&L4CnZ6Imxet{?29<-h2bHt%hIov~2r6fRuklj*dF?^E8Qgc@ z`#V#pdw^SN_}ypTp#6^OGSv;2@o+J|=E=+=&l7dFa2RdvTA*LRC0GR9h=rpim$y)# z5zvrEE$$BHPZHqL0-J|0qD>AfdI3PN!74O4D2u`B%@HVIv&56`Orh-)kKWx+iAKOB zSOS9f`xt4#cF)HmA@yY;%LzEiNK(BG5yxN_*l5}vZ1qyxFDJAqwI=Du5jxt{z2T5E z#?LlbT3Q-4Pre~OnUsmLpF}%Y2z7M3gi&D&zpo7epn2mG`~;vq;poccrA1fMSR-$8 zu$-aj5~S{_@p@}Yw8H1dwNoAq>D-pSpXYqC7d}gC#S&{fVg0^Ss^>(GK5<@fh1@&S z8nKuMcHWee)TK&B5Vu=cNBVf{l=`zz(woDE;Va9z6ArCZwL&t@hy;{;oXlRC_k7pz z^vTUtbrvRATvhHj%c+~nZ#cuWR_o6MCvq$vINxFWI4U}k^5k8(mkAX;!qOUPSlqIKY|Kl-8nUV_5575KcV`)F&HL%{9idM|TS zpy9*G>3Ky(vsj^b_1q|2;u6OD^qN5JcQuj`u^8?UYv)hIXQ7|Ao5N8b*Tv4QOb*!8 z+nm<=h`Mwo9UY#%@ooC9U7yx^`SaqfKvO|kd+0+h8{(m6>b8E&)0xI=O7Kw~f}n0L z5+WJS$1nNu>Tn-ZB2jpOH{tojeV^iBsaug)lFj6<@II!+$-BLr8}qMZczfq%2B&NlsS8yATmoNjWBDZ-7sqQ8BBB=D@PrX@~;TRCKAv>MaRsg_&(mAA?8NK|R8>U-^hoChCbZ_W`i zNJ@szdHPCgl9nWKB=aSh%Cc&x$V`ad86_9xWYi4dpXRmcc6`Md#Nv4)r7-j^kw;dY zzla5K`<#xSB?LGb5+=H*rV%N%F(OISo{;JcrEMU}M&_#F)}xQr5$31xZFh6G216HMsTyn(V(LX)#L z1{bj&D{^g?*+0|cGh-7d$M5sR_8BYFeTfG*Z-gA?)R#rx2E*W_D+1e{xLl-bkiNFue$xoadVeeLF};HtUpd_S`=_l4$$ z?sh`DMiSzfXTf#a*JD+i()KEdK7HegHpq`UcJH%ulJjNBBKl@kjTWF{YBnea0H;YY z**Q~$vyvdfywr4ukdvGn>`?M!>CSj1x%w}`(Z{TWKT=Xe66ylzF`1r=`1IeEvU+Iu z$@QKn@C%t}ulkcuUodkK?T(=(`%<1`z4k+dU=$Gv_t&Y^*30}{Oy`ZWsVG9H z;P@(iLZe>sS)${P3PDSwmk?Ish`rz(d2HZpFdUVqa&JDp zH7Zqi`E2^hxnuWb@NfgQ_Z!#<{# z^%z#x@+DJK`jy+aT|kq?$g0BF7SHjO*XSg-XM6E;35vlFW1 zie6>5O%G5_{-0M;$*Nsh2=BQJxPPSsQq7 zR*cO_$%vzP1z@j|T*v)xwm8t#U!?^RHYjRV=Es8D9L%u`S5GdmKqMF)xN zJmS4aDc_1P)~$m)Cgv(QJ2Bg+ zA~^e_Sa6m~HD{3QnQMZL!fm2ta;oB3bj>livPr(kB#{JFcei7S&K7J$Ivw6FJ^Mfn zs1lxKe+np-Oull-2|FJnx0 zqG-4jor-4FSev8dHTs3RlF&2C#ci=BTwGof&DvNent09VY&#Ii9_T|2<4d!*&et*D zrbx!b3^t<9I)rUiXE&7qlQr^1KI7!b0NdMBGlOy%v+NdPEAu_AVq&Y^Nn)$dv|~US z|6ZR6^k0?#BQPAE9&eju*wb4sl*GbP# z^pIJ##8a5}hRX>3dgvBXG%2!-RneWbN=MKsg!o>A=>S{dO~nvj7L;tOH`6^^i8=THAg=ZTVB)MB%Be61q${4~W}$c!{rk-GUZ za7#=1*>Smz_vL}AHESk|+MfOntzrmwm>T_uh%tSXrYue>XW%=FXWfR5-+n}__nbXAs2su+j-0Ig{=S8;~Y0QIUQ z?|RzlsYmpF22=9qTMheOuBW@I4v#2PRe5Hr>8zt&EEy_qZ5+Mbpevs4_C0kceU3Ps zD!t!!v%PF@!{95o_(j{eCM(Mtp(5L6$%^m0les;7m~Oe zuT9mV)O75;T~%RhnK1HFbA9{GsvNsPY7qtsvW3-G!NSz{OTj)~9;BJYu0et&dC$&a zE|%*YPlv<#)?PmnVcyDVu5m#uYr6hc7?|K-m&{H=UI<(@tARU3RA*HV$*!CjP>akI z`I;nU#FIDlD*@kto~X~PgZNi-vXQyrOl7(JNE8dz`=H=sWXJ3%2;7|x&HU)Paz54- z$Dl}cHq=#!BYzPA54`6`Hn&oEm0M*;Vx{&ygQ4@N2X ze?~kjcBbQT9=klc8gDLd^YS?R^~<08R6t>e-0O#sHX_;wtsmxAQ+b(DD=G;tA=@fu z?cF^>`Fd-?YBNc_?Qh6%4NX}QUhB8p>_S0z;hd|m_CPq)86^dxxhLlQ zX5^5X_$5u#3-2AvYvv$Yr486jGGq8HP0z9l&(lxu_RE=UCM;`=BODPd%9Y;j86sN5 zxV%5B@ULy+A0(`+P-)bQcy6@ZSPlH{7%F30<1tK*lk5jVc?EV7fyO*GP~jjJ8CLCr zmSCJk^%JSk%XfK~B+i5FlM`$llo^Hg8-B)h2iL zWPGD;o%Km`J|ROnB{g$X!_Fc*BvO+Mb78jf1_R21X?Nm)BQr z?w_@x&3&pXF8QSRrDs(#HMqKMeaQh9>x}-o*2OusPwkU#j#Xf`J!M@x(jZw0qpF>`TYHWYRgIKds0q1fjWTVban~7O=;j)SgwR8gV6;*)j$r z9?hd)h74WS$G?Ex!U;>2Zr_;hG;V)#A0ig9U8VM_!qoEo8Gg!j19?i<2Y*q6YpxH0 z_C)bP)d`7e3-<>vTuqM31-i#xT*l`Z7%X&(Bu73&$Wg5A;zu%GEm@amx~DohtfIj1 zLlM|XL8moMVo+N%Lr2UqhTVBX?`B#wRIjpZo^KLbGEME=s<>7bL+>oJB3MLKnX zvGY1uY`Z+m*Y*0efg&b)vj*A=b{Ti1^$>1!Zo+c>wK&Pu6=q7o*kEaEfR1_>U}c-V zFW3G~bIw%j)npi*_SuUw6ozyPD(e&xTry-AxRj*X?qG`->Y1^MsV#5PC8#v^8*@{g zkojky^AGYrt6UK{Ik+^zBe3@-y%xX4NL*RuLrxVVWKG2oq^vmXau?W7i}tFO<;6+r z6{tJalH`Fi)Ev&e#)!1yjd%Kj?NI4}8#zxi50B79p)evUM=oNw+Qa`CLP zOevVF2Cso924YZ)_k6mKSK||q#_w5Bd4x? zRIA$>>4x&1Sr>l6Xes7^$@sDQoO;6SL(ZloxhO_T=aIU1+Kaom_tsu$tj&qPwAki* z@}36Og1yti7Wx0c=4qFK@5nRYsLX#06^VkblK!9Ni9I2b2gooRd|(Pdb(g zQo+@&z72rZ-arxoeP%R(dgf`?u1pYnM#V<4pXGp?)f&+&%lw4F_!%*A$JY-UY@}J7 zpir#Ypt_lt!_^yRr})W$KDwO^Ns=U-aqLlQpD(X#YEsHb-IgRSqqAEh=4eEm+wBl3 zf0X%|#`^2G2RI8)b3PtrL+*M`ECS;BT!P6lE5-`ZR6Z}uEbS2GNG?7ks1H&a|cvw(9v8 z6NFU#5b}-En4Jl|dQ&~YuDqrq0i>0pLSp&rmEGPP4c;q3S6%Eh3s4Nb{9`6RwoyFRzq!E2H%br2FlQr(f!AaoBAs@!`?eq274tUqhjp!_-2Z zdN8eoNo3E5gpOA|!_~jIZhJ-Iq7-Vv4{t9`&Fou^ISzGH&(E>IzzsV&Gt*G>pr#1hFYGnwiA2lzY$eUvvad+ zZ9POn_14l_c6q*|TXV=gj2U=dh>Wt~18=}oA zZ=I9v(P1mE5-H!;j7qtvaHm$!Z{_Ty_?k3NnjxX3?dg~(DY_7Hye|7Pyid4+FT~VE zxPcir&W4x8#z|SFqHTi-N;wQ*`Ua?A=Q6TpT2Vi6_~6Wtwx>e5dHSoxwAy}q-${0U zPnP4{=p|2&6$2e->RtdPkQ+Q80yzU8uzA_hU+w2!S(dJC11KDaNQmEBItJWG%!EWL zxTn6guV!{Dzi9li|4Bnyv2Y+@qlBI33pdWNQxC?8n~P4(2B#xCZ~k2wC56x3;jMe0 z-<#$%`^ueQASH&o%JSI+To{~q)g@OFlV@M|aHY++4&k10ZRnRXuOjrRe5;<_%_09H z&$B&&=#AGSzryL7z6jfB2A{UKqGRI>LE=TZ>G+H1s3P^$-nqwq+s5^4XeZt!mHcy5 zC-k)Xt~itEh`klf$MuJgj+CnV_4{MWvwq<_BMz@_nB>P>$6aA(J=esda#640@qw|L zrKD9xib&;uTz`)VMYMj1_RRmMSIf^K0gK(1YT$bYWpbnNmz47Qp^7kzNwW`h+ifE< z6xvkWl!nv4yeq|e`!q95;>&TzxQSwq2W(~Go+B|O)7a4@z5})(2*sHn6&2?WgNVUz zsI#+6&dt8k2agV#Pjy%MwQC3|*HVc1UeF%-aJXjh8g)n#ohr|EM8WvcZUdHP8tJt4 zrNNDRNsoMl@dpG3Z={>E_bMNDvN>L5ZfjhNtCd2LxwH4#C=#|s@8b{695x9xQ%MPO z^eiSV4{y6lDd;|}@`+!r-}Mru-!9fN9dmy7{PgLGVhn6O6(*Xr%mSyB!gqP8dejKs z`J@YHDyV_!;rqBQ?>@s`{lTyNq^}eUXM=fg2rZOoLhndx*9x(V+_}^ll;ALbpg53$ z2pnF@e=w>&85WYkgvO>SiGSRr;_xmba7!u}=s~BDhbdO;<}OHO4WBM>%NAYd#LHJ7 z(hPj}7cUvUcI6m?LN1zBC?;vk(8Y@gRw!DLCLb*l9V}{*k{p$w#~UcF�e^I@jwV zUO&V2qu<`#*I3{fhNwWLBf2?wTG{3 zW6JC2T>f<^2E2~A9QlM2i8W?Y&sdU#ye@DzQB_WfKH(g(8Y)}@elty}z%NJcQO+Sb zQaZZ&g>U_=qFW*!V+X;g%42LVSOmXSsrKXZjjO|gRT*+W8`h{#GX3z0S*5M#6^9RR)4N=vb&mSd4TG79jcZww z1LwFjl7^7k1X9-gkubZht3Uck@8>60mySIvnzIHBv?F+|h$`E5FMI|~G@A4@KZd6i zD*V+)Jml%}nr?iV;h(%E3tR|f3IJd{nC3#cd2wy7pC*r^S0c@XM6X$eL^COr%!^6} zx++D8zV&OPsULX~+pe^`8VyYk?-?7V$;8Pu$rOA|+(dMWbVB=?C|?;WUT|`Om5Cz% zB?rFtjzn7IO7|se9iLueO(+)4l`iGPa)ip)%xAQv^2(3a>LfD0?W9x+(W6t%_>fMJ z`bNiMW}@JCz9ms|Zg)WB&el{mzN|8ZuCR?G;rVjLNA2DcB!5VigqLZJD71zVHIn;5 zz8@ppL&$3D(vOSj?q%kRBTJ^@TYqAO0{GY@jjJSig?8+10Wb>lnQ6a}t6Hog4izdi znnl{^my6=-n<{Piz{1}U&ILumaE!zLc(bG3LKBd9dP>2!!AI9@nq;RSNZ_mU~O z-Gs=CA1SbAx;1Z=FWy|;5roHjtp%puKl~gUi~H{CE39)pIp z_JlPv%PUO&0s7hRn*`m);JAh7h*$`nj&Y)ADpH8Mxdu+eU}uK3pf;9)Ar-l^>Rzh$H3hIXd8{#3mBo1c zif#YiWc)ZpKD5L_MbWS6)ec_ds_`dF5_ZGlF-9G1dVzuztJD%Dct@(hS;`5|Q2Fzx znOR)uG>%IA%$9h>6LD#B1!O;U(P?zV0SL-)Nd8Ikg@w80@K~o7ej!2tGl3*~xcT~~ zz@uCu&V%T35qNhyXAQ@iOqcGEEbq?@x747+T7FZ|?T2@-jYh-kC0YyL1gd8uSSA%&dDyp~==Hzb3`m`<$^m;O9=>(WvO=QD?*8tTMX?XVtq| ze&SxE z+$^7MR}w2Ji3{b1Z<_?jJocOYf8iB;>;YD9^a0s@GJI@#ItV$_IA$%z8l&hv473)B zl9GW?*gXSWEMYt8L{t&EOu@qC>tOk<-2{;W`8SiKO15L4$dyjoWeb{AW8_t7Jd%`_ z$Lpv(q>coI=n>L?0L38dS1?cv80b8%?n_d&BWUXr{q94SX?0(kXlyf*p)4^k{;;&X zaDiUL4fyGyMXvJ$#p!&}rZSm~by0lcBymNQZ3aCsFqc8$C3df>RFezqpkQDcN|!RD zH%t~hE0GJ=sbZ@9^m3|r3BlB}F)1a#8s@{;PEp3@=O%mlJZ-!B_&*uCUFU=DuNb=L zevL77-;7}qq@NL3ySw&2jk{mi?T~5qVbE5!zk(`NolM~q;A(Z;dtB4_17o;{mkJ$;g>!<3kc;WH!uJvJ^u)2pjV{jy1UGU~y1HlpqauX(XdSn6 z&lEa>h#a3TRzvOMU4a<6M9-$zyzg!Ub-k{n`9hh}oYr6ZYB$-f zkyo5H#m00vq--a3u*FxmP*jKoCN!;}jXw)akS#yJP}^NnIq#;oaVL3&uiqDj;M;nO zHoo>kBb=++0V$ah+B26T-{4L8+~5a6X@i{%#4u3_Jdi!Beqm)OPG*Wo9HSuT0cgCI ze%i3Em1T`Jm303g2s-O?u{;!LGp( zaVt;00PT7o@|r>G&7Jr>y%BVc)y&>c$x`Png&INbjhm)3%(4Yr=dI$)kvWG=%XjNRI?PA2pQcQAv{Wrqx%GGEwoX%p zI;R@v1gTkeQ~OI1GFv?lwAu*C5o9#i!q?Ut9mXZ#B~3Tx?aQ^80k4?a_C)!0%SgB{ zOibjN6l_k7gPODt|l&DGlW*7S$sXKpJ00AA5X zWs(|RcMS%u6youegS{Z3aqKLE#zHD>Xhk9PSy$Cj+H-HPTjqjEGHva<)7V)N_JChj z@fht^2TULSp)+upG=gVUyBSi7EpA!M0TFH<1s2|l4HjO1Q2QOnTqM)XqN{SwGHQRF ziUfYI1+)?y%K6F^o}OX?9Zz_N*Tx)kc5;Gi(Z?2hmbUTqtozfn-xSq{{SdgTAh@fO zE7?qv4?_f&{!^`;2)fqFaC>{WCmL9^VyNPxLp@A>vW|695<=YhBaP|XePW-s$ZOyv zO_7ezS_&0RRmWSB(KgJMroEANBi5V5M(4(cFMFV}8pn6I{R2!HoaGV1c1&KwkCYG9 zo7h`S(!j|m%vB<7C=!&QM~@6`Y3=9J)NlZ%3IUdeKUn(tC&f4XLY}Ef-PCKc&@u(X z$`gBRJkn5z$nT^Ok*2m*xo~!NiO91!q@D_L_?S z$U+)YLEm65uFPuzU5dwrIdb6SG9*5Kd%OL~;tm}z2CO9QXRn~CYK*TnFOLVn(Ov=T z_MPHt1*Z2@(Y}Pe4{>4w;^ZGtjSt~H|b z^jaT@9zTe!egAL7)@^WTCXAL*Jl5tIi3|Cub-O+1&9OH^g$tq7AEp`-Kgi5zcHt>i zMH-3k6`)ak3nV@#?)O_If51wfGzT8C5*G!{J0z}QZR8| zLqft#?}0)K#C{d1gCw}$!S#w4cawn-v;~C7h$*tD=QBW2Sr|KhWpId4;lp}6fI{Ns zsPo?!C!ZK2P53)NCDMNd2n&eKuSkHKyRL7uN5GIJU=&m1i-EL^@iq9*3_{Zg1R&2M z0R8VIVVXjF1Q+2s0>*Vr>fUKhe6fApH*dr$t@#{tjS>hyK5fHN!ZrVvwx zuP)B)o#E0Ch#TRp1i+xvNAzLqXK@D&GlZEUHL-wfXR1(P4CaS{>4Fk&7(y9QHMi5K z7z8|tZ2$$Jh9ZXF`x)cgIcd0r77dMjQ#4|C&D;N?=RZ@E6A1oqN2)Oj2997pMp`Bm z0ciLTn13&>Y2=LZ@q@6?ktP@O)mAn(?}6H}O#x<&(JzXLZyZy8E`OdYLYsXN<7?C2 ztT)0^A$LL~NwJ7`x#zrgU;as|yxd-WKeMR3;fm4oH5wGTr?v}Y{0e{m2bvz?Q{t`R z`#bu1!b>}tliW4CXiO9S_S^lh3KMgk^^2+ZdC@k6FLI%!`AuwXu|bvZZ>@Q=t9giq z^hIISwbZ!#JE^{%cC#!c_pdZX0sU=%uuE!neWtKoyQDpr$HEbYLb{i1?x>8mbt`u+ z8}zc5B;BcOvQhCb>A%Ob@f_--clKmv)41Tb#<^>D4q^iK-Ya7f*rbXO(ftx?x)>ml z^A;L@-Rlx9czd6x<4~5$a?KhhTJ)o9@;&Dqm^)FL#F@Sm6uk;5WpVXfoxSIZ+YY`s zT^r=Q;5loWV)L$)wh5cMj{wC$&vTO}0YzsUIoNncaO#ChKTvdRY_#rm7rvJ>ZtoFW zS&F$JfUzpzG>gI~ual7W)-rJ$I2hA>DHlri;TcC!A z>HFlSA3IZg7zFl+(*V8dUA379q*2L9|JLj z0RJUaS6;OG9L6V%yyq3MaH0P9OBg@Bk?wgI`uY~j5vGVH>3(FLdh;+L-!RmMZ zG@bJA){T^+{5W~Ti?qQ*@uF{9 zG470Co^JQ5_paW#u2%?p@6nh+37_vCsCII4#k$CCV#L z-0o55!Rgg-afy4XF!Q7hLK{BL!}$}X>yssT9`g%02`Jw78k$GZN8`sr4Gh;83p%zK zL^`j5fA_mAQj%BkPp=*O#P;3YJP%A@zu3%lav2f*dI1z|K5lpY=)_6Z^k&cj|J>bH z)+$A>1;*`q-pdA4hQM}ETTzyQ+9Ni(S^5a04Cw0o2xZ%{o|Ecd!xoG8_XtPci-^%_C0_4d>fn7 zZbo>D-fL$=#oziohk*7yD@Uh7?=&Cg&_PtZPRP(|hU%0SRa z=e9D;Q2pztQTIPERKC=S=0@kKx*Dk!@k=AEeRHNy_nYMS+_$oel-D_28#FbM zBy@Mn*Ew$Y@i%gf=zAI+h*vRJEr*;Z^18(&hgQhs-Wu=}CwLzLi6|RZ2`l+YVaRrA z;`zr2OWXE~ldJLyMD*)C($_|u?4ofos$yqj#M3t|+v@=X864`q={3WzKGxF$7=x;zooIc-D+UcQ!T`gbM+GKRJM8y(ifiNEsr!2gPOc+0U zgl?~~02X}oUbse1UltWsV!(j5FqIG`(wM`IL%?l4S;g0t43%Bvntc7_Js=PmN#o?j zC+4+xYj{}r7`TJ1c=-JIht$BQPAa{?d#ZALjR73Vz~oH`5{Tb^%k&thd1bS@OaX-LA&~!)xmW|i z8~hhud+-!OP078J_nK7yc@4l9AlCnG1RVIn*6rmyAQoGc1HgLI+(s~2)}0_^0k7f# z2P*3y&iRWl$3=n35KO-YvU|}XHbD3WHq&*oQwDIwn4BIVK`bODe~+`5O4SZS27B>G z_K-8Uh0gs5;ds&ANKdo`Amjv->+ku$CV}K4b)L5}EqYc1&9T=$DywHZLkAe!+ zr{!g!e(~Uwye@a;(2gDt0=jWbl|8n1;iy9gUW6VdSrE!j*Rtq`J2uqrbl?+)mwp3Y zA`?10f%2CWINnMU2D~rThF$;l9x&$Dd%uTqz!-)+Q{cVz9@neDKm%GpH5oZ%yk&ja zfmMiXeUz_Nw;2VfDua8#GM0Kk+y5859>2mzHKWz|?wkYr2?QfQQhVPHOo%wICe#+e|7CX1^ zxTSXA9meRkU7Yj-x$~-r3t#ikz^d}j$&jJepI{`2$GoillW4_+47`gJ;7YUAT;adBOr-tewQuC9KfZ24*ny}fLNEiam-7O7zO|pJMnST9@P9lw=)|44ebXw zKFv{xs{~%m>?7$O{A(T(N+_{wdMz@2pVeO=)pX z#tjEM=&wyD?XSE6GQJ5CR~|6HzcB!n9M}r%-N{g=M}c}>j|bKUE@!`YvZBD9-vw)H zc|;2E{$C@Iy$_t()3(4S@h?5#2>@HHGNUguA^TW5X9fu6&kO|@Z*CFs(>9={X#KIB z0r7{df(I)q{k@Ms_Bg<8#f1AK;1E9nAe;VO4JH8J0p28lnArhd_dwYml?UGd$m62V zkf(Iwy&fH#R-JGHN0z^s<+ffKn*bPS$gAhUyl z72gGPr+PRy0JAE0nE`{rV^M1;FMSp;mwp3# zXUq>d1*wSeAK7&Bp04$~3YcxuQ7zcO1|c6U2j27h(W}5)QzaZR#OJIu_0yS1DgQe3 zESdx1%mFHYIPeoy6`;7SF3X#|`PcpeoR>JTxeaK+*{0d2P%FT{bh1i6rT)QowyUClWDfGt?NUE0c)Dn-!{&U~6KcJKc0?V3ErVEN>0`+PCsA;rq z6%R4i&F*53ppgETIlytt;1&&%-kRH-HF|_HasMI)AfcxU8z}S2sMA0PD4-RWA4?~g z=*A5XcINv&*g0vo3ACaDGYV){1xex^mf!k%GW=%~bE_U!gSiY$EIld3zLy^;R^L|a z$#@E(BVa`;3}D4YAegT}L$L?H6MO{wT`fNo7!?AW!-Z^_YcfPvtC62+0kn(T%YTCh z7Pt>LkKsmqBC#1fVhT2E4cLu$0`-I*9VsSYaph_ z>z!#F&zlVSajRy17fHI(=Q*HXIdU0{be#j#M zSTwLzL4ucYCU*Uo+~0hFl%sL^hobOb!7y~!@EH1sMGs8fvX@0wEgc_W1$rNyz4aPW z|4&pJ_V~9{f=Dujoaal%A3*$OFoYCTkOMv7lRuaQ;b92mF$%!)2T34(2Q$F}AuT8$ zoC@hh2yheJG7k(d2E+U{IQ^6{ths@J-5(Qv>{%@;h3d#iNi?wWS&MkMwY0DoDyO0V?1Gr1PX6 z@cjGR_vSV=;Nn35emVsgD)1in;GCpDZWai8cJ;a|RST3-#^Hg7J)Vlh)}=XX+0(--}bH%RVe+52IfqV-kLy zQc4v5GW!EM7K!C^Qa>jh`)zvzzCG0|E{g*YyOeODRVP1Y?$d!x5h7wo{nG-Uua9T1 zpzNuFR#95^+kN^nG2;*1g_m!yVHetU1>R9@CFg{xxRBgIk61zbXIjP+4LHB_if`dx zYI8x(z0y{k!?8hmDZ7s+<;U`QdsRnk$r`vV#Y5OQ-wxXjToH4$r~1)Sb*3{!J4ri) z+J&{TF3$m48M5Wg*tTq*>z&`k_%;(a9Zpmf??V(K-7)CwUrlelHr1>M`r<}qy~Y;! zbq0Id(1L0*U9gLFWj?`C#yIyhw2)x)r1S(Kr8zO_EafWuD6GoZn%e;4WEACBbaE;p_Dl1 za)B7?H|i3tTm^sm;yl5Tzj$I*Uzd0Q9!@WY44?P2xv6r1ju7UBPlZ6jwwa~pWxr%W zwZNYtS!%|jnl}2@4mN+4Hb!kRtn>LQKRa00a(W8234TAeI=!jAY#A!8!1{UHQd29$ z+#HOSdJ3x)Jb<9)c(o%uo@wo{$ieK?^oV!A1y(E zSk2>(W>!Qhq}+L_M~uxpzpDBl(F7`L@ot&<*UJ$?&11_y4{445b;f993oW&A>#0w*Vm57Nc7JNeU9}hd)ZOsR#F?Avdc1zCq~WYTSA8zW z$k~`XfL_L(Me(+WvCKxCIMO@kmuQ=$chMI87%RtL5WecTg% z0Z!{>UiKB_^6@9+Qav#RHwOK#{IP2ARznf{Bh_H)yc4k{n%4wt$KXpUX|-6Ste-1E zgVdXR|CVRK#Y7cy>7jsJk}q1pA8O8*KFb-Lg(#YOXY&NmC#C|q5K2KV;d~}fdTI`b zcRG|-UR#YHiRsZCCa@v9lD&#`dGo@dDO@z3_uv z`h6iLF4T)f+PQ(psiDrnX8I387V1sE@Gbs^ndL_IJ~rWzw8ax@*Ap(_Eh#V9hPNK; zVI9i)QsofCC8JnBd_Hgi1LKSUOD)`tf?S?F+!23*s0yqUi>$%{t14WF*iiWB19)JI z&kKTU@7EOE+^4mKGDe6Y^C^2^9ZfwmU`rfEDy#|@L+zXkv7|HsG-GH+RxBvA#?N0>&nl<&2jNB+-=1-Lga&$c$J*dM(O_T=KU z4C@$Fb7MEy8W+@v_yAaIItfuCFafzd9|tZX;9+>N&=1L#CtIcvE4QAfK|o=qKrSwc zV3W4yKjq4qRPi7HfqzE{@yr)e$fc1Gd;x~}o9wdyDdJ$9V?^37n{cJQ9bz|)={$?H zZ6s$NOnED42R22C5CpbCsRZIiC9WU8O#y3(RVh6O8-9*2ePB%2>K>l!%pAAC+cO4$ z1%CkO02DNDK%mXrLq6E&j01e~*OK2efaz%v!<~o!Sn>%X@bBq=YDhD{o%>|;o;mKz zpc)K2aAQyRF}V^6&;b769KV0b81jL2H&X*{|I+X2!<9(j4>ta}?tW+2*QZ2*C zmjq+%CrS7P9kcPsrOP?dQhJXg%!xL|6tuV^mjv+xehTQRWQV`Y+h2}U?t+__7(>uV z4i`}fN8X%LCO#j5FA29|CRJn+s5D4P3?&myBd+f8q{mvYEx5+dO>i-Jn*O}4 zmo@CTy_fvCf?|K)MF+k^(qbGxavn6r<8jc{L00gXz$lI}?1dCoyPV=@WUWJ5^&{D; zLjhw@t}#6=;)y%wdvQh(%KQR@e2mhGv8*$us!t$kWCIqEBfK z={rs@|QVT|wRMbf9c zpxIr_(R60dD2rBUSTm--lv7E1Jl8oP_meJN#5SNTfB5Jm(aB$I>18RKA`+o##r%l6 z>x{h2lDUrx(FpMe2^6ER<&+7nKPzT0c6ST=VH}+-r+0aaLIZ(sU(>t3m>WKNWjkxV zq_>U&Th}A{s`7?P{P$P4$?OLQI<4NPz3JYUTSUpad~Lwlvi zdzX=|-23|UR?geq<#@mR{hI!9`}qFkj>+Qf;(W5MZu{ly+NPUxSMS5#blnZvv<)4; zwjb7vY{5qsz{he7_cuN5-bWk!Z45HjQZe&gME$WKJ0m&O{a<}i40AvIX`6l(w*3;) zbs52t-Tg{5E<7GHY~p$}hxmz<_acXIt}ekSR1>66t2xK%oOo6>*gCyV4DtxEs)J>d z8+Z5|rt?|MDvz))mhCO&fwAgD#Pf|DOp}p{x&9s;Zh3m%udy(F=XdcF>-0C5x5c^( z9?q4QYlEN&M(es^>%95br$-E1`(2bc&iU~;_gC9C{P$a~c)RuL2IE+h$EBON`=u~D z;r+QvcZ6oWMOD@rTIpIh{mu2>7yE-CXa2U!eN?KBJ?zy6mljUX+fniR8@c-rt6@2D z>BG`LCwAvSVdI_ccfaoBK%Belhil$mw`;edGFJyoO_M*jj^|cST&)k+19cbukTp%l z^-UVPl8M^g&sFMMs3Q#1<&i|J;sPbZWZE!KHHg&0SfvP=mf@%f8`RQQvP_ZFhs)dA z?pGA$$h78G^M^6SWCnOhx>52r(ApM{bl`mUmD+43^VA3OGN`BF}v&{_5RQbraj{%by0@hTQlFcBJ2rbgg0s7 z5+87HbnN%h4i7F$W2alhlYY5(6D=O3%@g&J4{}J(((gA}SIQTUQ}O3&8uE%*SF&w2 zcFh`(($5Z+XilVdS-XIA{(=P z=*Tz6&={iHj8NGMp{5tv0U5Rs~5;Q3bS}#}6mFSZ+Q{*>0=v9tM>I)co zHWBlo4bqQDuMW};P2iZ$2!7P8c8qa<#Z_@^jNk5L{CxPFmDx zYU}lX2FK}sB6zb>A)(XnZ*hIXOW#t>uM7>6d5gEO8P3dHq8GPB<%h_M=``BoQr+}P$*wfZcgu{CG23PYKA%9?1Zii7W z7ee4|D@z)(F2Ku(+^dU9`#GWWR_gX?nA7A9to<5G7TTNPYRt+clkKdybV_dicWF&I zVaVi}ih&azio5j_u8(=&nCIG2K9$D>FlKHTv-5_T^{uRVSjjT2>#8U6h@zg2`Q{dH zrYO+3%?!!H8|aSaOJjx^J^v!lt}L6`H~#YNncLg>4>hgrv9e@yEnGvc*SPE zj}VUT$|ueWi}ym4x5iyxp^qT@lCwyCC@`2U%S4MNXl;TKhJ!xIb0aAmajGs%J275( zqdpT-ckRC2n3&G_NJL1@%@lH4>H#_I-QOHRd zEY!>!N{OEcnY)`<@b)(p>}~XZHkLPj+_9xat zeWLkSmiv$z-XA)!absk7wmB`|0@rQCtZbefyZJsffGiX|T z!)le}EjmkRSp|Va?*wrk0BPLmO_B;HYpGdta}VF-!~-5P2%a372Rz9ScqEf$d7KMv z=h;OF#+_2RVs{Jns@416!?S#9JgE?xAGCJIo9Hwyni;>LRXo=#Cs1qJCfuz->=u}h zd1*YF&}6V*(^qIFGe2K?R%l!?+e+rh-uM>pIB)+4#U96$bpEr!$g71J>tP{=?Q7Su ze2n3D+w?Invck8TWizGDvJQ-2laY^rn0Cer%%BFn+}r9B&9Q6ie$^R$n0M0K+IFv) zW_bSCQ!Xz-)Zi+dbAl#6kJZx|=!2TnYknSnGQTR{Uvg-L8zV}ffK<4j+ImL!GplLC zV+t2V{7@;6&&r+|nS8Kg{m>_5C`Zak$r(8;lg+hy-m-s!PN!$?QN_=-pSK(PW`Pc# z%!euFR=D_X67vns2QGfZ3I>Q76eI&U``X-abR@WD*zxK@{Z%S6tgUnM@EMx5H*aIe zst{sq=`ngrzpiSDpNQvXRFNZY;3$T^+({UYar3t}9ar4Y3Fg8^ayU}1ir32+o?6?0 z6Zn3f`;oPGnz|y~15k=@X@#q|=spEq;<@8Pk?9zO@@S_)$Trcjro=KZ#mg_53S+c9_sKd~yC?oBf@Z%galeD~4hqSl?gQ-l6+Gv8(&J>=t zN1ImZV_)!g5+3h-pJsnM_=EI>Ao~qe;(eX^Yh;dV89% zEbyhm4rprPTu{_+yX?8$wT&<+~Glc^|_rM`)yx$q^GnOw&pgN8Ry^F`|7098<8jPn}JrrwPW0Kp@<53MBY zZ+gx>6k{!0>#1f2ooY?7o#43XP;JO)v)0Yy2J0Y=YBBH=EdioQaDJAF195~IRc|jD zfHerfO6bAvGLkNKa;WcPz|zHEGy>c>$diO0<(kmKGAP508WT^bKyV2&rRYBLxi=0cgz8^9tHdgyH{I%9TE!a$p8Rp9e{KU zKw7U9woP=c!Dv@@D!f>kV8jrpH(wuJ4I1bquQIbva@9-zRB0{x?ZoYtB}?h5;7eAo z;U$jDI*+7v!FS;<^OG&TtnkE7vUbu=EVu@*TQR=oe$3Yxz`4K0v0o+D1r4zFXlp*F zh5nFy3I%)_Ur1CdKU{YQ%^4M5HNt?cDrasP@I8(5O7#MgpjI;JSDe;($HwqOf>s5K zpTCvXTCE#UBRX9Fx;Y*`;I~-$tjIR8RDInH8Vf?mHQPsasB64g>^ERY?3OB;i7Tv_ zUGKwI$qvxvJlSKTCvZG8P`u$RfpPuap;V#hZhGsDP1oL(EVKT$0$jjW z!1H##+qFAs=BD?`5mp8(1|Zz?hL3D&NvTxIQ4AWnwI#3_X6uDZMG3YGLy5+cQ}&1x zl(Gdq)hwa#hg=6l#c@{=0aovmGW?TX&!27pLvq!&yBNbNxy8 znA!35Y6`3gll|wO64Y%BN4izhlwiZ2$n1B@LQvJbEhxs(-NPw&z0+*={)rRVI^W@C z@1dmGSD)m2KQTbFL!rV$^6Mk2k~{-c9{MTRc{$qSFmi0CLy>JB)Ge~ zySoK<2`<5%1YbbV;O@cQ-CY*$?(QDKon)VL-hO|WH1Mq&HA=dxdeV(Ah9B;TqffEO zJZ#C7k0O+KMAeJIsJ=I2fHPf7s%!N1F%g~sO610PHf(cosXt7)U6WpIGBt_{C)^Q+ zxWrLrn`nljrN~a0QT>I-ldT)^bFQ#4GHFd^epv9=c>Wd!+dcKxp)iG0@5KJWNZC}4 zMz$W-t*OYBeD0`(Rd7{P?V^*VTa(v(if#s;BtcNM) z&+EmeadY!Dxn&l#xuPGjj&*A|P9x}5tp*J%@Vt^&qPHwf_iJ*JUq z6GBbYhu*EK!+no*1j=g}&|Yu=hL4~5@k`-2V!2DWU562!1DAnKS#BAM-9vhYR05yMsVDW&bth)c7Sk9n$Hll?CI9DY3zHB)Zj| z&KtFa@Yx*L59PGEt5`>H=Ozk2DfRem>M^EMzl*O?axo*(>79Q{`;7I|?>-r@zYj`> z&Td?@G&eet*V^wb*X6d{{HPb#*cW$|wy99z{%7!b#f1R$w$Bn$)v?d##Y=$@3|T_J zSACXTd43iS;h3MRa#UQ~*)2}Z)fBWweMVSScPFH9+VO!>dYF24mwX7n*W&Bw;74}G zY0l1%3Rd{!Vsn_AJq@hVqXb+@KPIucHY;hk6FT_{9`-ualqDVhp}i95dh{_o^vvA& z({6~+s`ym?vscm{l~C^u>4L=@(ldt!FUhq5!yL=eyv5pi_`mqwgod&N-1DgoyHqCkH+^RTRXXdB@b~0J{)6 z^{v`&Q=uhe^&(T(6@$;3JmEOiCw&)qE}Ele`Spm{d~iLCV1=X1YTlUb zn*s?U)*^rcLgSXBsrT3qfr(nrU%?qWUDPJF)^lx{JwtT{ zhUYcS@Q4FUB zUq$pbeGDhmJu;8S>Pi0oLK22Y{vx5%-2XgNrhBg14bBa}fR=I5=~^-m$*JOG6uSrJ zM7yaoj<-DaEFgX``21N+5U7a+APCi2*Fx$ogYIK+D;A$?Pj%;?nX0#a$^kq6bB#4l zEUhTuM5XH2(!=3rP#4%X=-!A$a?N~$)OzY!cVKPbbMiTDAEhrL(`eyH6kQDeTHpyK z$W-z?7g-tRy|dBy^BY)|Nw?eE>pYGkyFUr(xt$yg#qoD85zsPnKDxB#@w7z!I9%Da zj12Hlc85%maI`LQnFU!i_sy_P*`CjX$jR5}Y)@mz-22o*obBIlM^eve($v}l@}E5q zo}3pAv6uJCkHfSTaqW?LVlvxdZIdNhV}2}nAtxF14X?3wJ`E?-X5d9wpqu32%1V)X zEew((dLt=%<_+~MYCLR`3=>4h5bCcXHD}*5M^sZDB`Ho(c@0GhNavmey=(S9^2sj0 zlx7$guzhsQYI{wOIBDfkdcNyIzzU+$j91itn(OB{O&H0ETn?^pST9rPO+d|kmXY6c zfBw7AVNt51FzStGZz?dlL?ylVME0HbD-kOO!J-NR+&5~>1MJv#?eeofw(4;8qlKO3FggYls$A33Q z?m=}p6YeT)Eaz-LMb6xm`&EVi97U6n;AKHykoWZZ&Xwn>Dp69fe%@V|Rv=e15_vZG z@-S*V@mnWLfC!MWW>T-8v5Q#t0j&eeSWXF9^=6cQ#5xROvCNcHoQR5rKy*9E=^_9kAZ zT_aP0(w6J@i-&$cTXcSyQYMtQ=s*lB_>>P$zHtv-SP6p5usL0z~1TtG}usHxQ0|4kwj-1J#k7x-6 zR>-EI7{<)2D{AWS#4z&2RfdM|dq0I3;1k9^*lNzbvj3JYC*!FM9VIpqSS3 z;I0SYxMGL2?iW`-ExlpgC)s)0GGXiA0vhh*@8|7|4-YN%hahZz4^4(wey&Q#k*%mj zSR|;@-;L)nNEp_)L~TIaKNs|Ffom?(mu57z1M%#{vptuYN>=1KEQ`EL@1X5v2R^_~ z@p&wgxM3R0lB5FNq~Va2BSs@^a{1@%y-bU2T!lwIepiFCX7*j^U~BAiMA1xMS^N`> z9nSGyJc7R$z@f$!@e079hW0xLfI|(I=#%^$QD8>cXq>LR(hwyaOvhob*dcCGg*c5j zrgF2QYnx(8@apx9*EsTikI-**iFn5M;|w3#`J62au(Q7Oyj8-|#!qMmvGPHU!w7OLuuuY)pVdsqAx?k)sXLggLtGz?l7rdxWROcnJIR;~4SxkI@9vhe`ock^x{hXPtoAY0^jc-p zCv{;4nVKm9ZH?Y31ns)7HXF&pkZq2zB&u#nbh@hJXA^LN)bA!>6AO$-~5h98zoFibIgJ!tN0&4&L z%cHQ4+QVIMbBTEKAV~4%Rt6TtxRPlo=%k6o;i|(95R1+k8&+mRmsamu&2h z%SHLyK^D=j>STBJAqyQ8RcsJT4VHde5$0_kwhSXPaFNK`c- zs%Woydsf#C$6Vq~H7-^_H6cP?bhLvo_&1x4&fz22OjU-l^{iK6e{69JvfW%ITIf(6 z6=vhgil)OMS}B#L1LjP#d_OEinvI{bD9L`*mojhW@|JcN)2hXG<_J?7fAfx7ON~wB z$DJJo(NqwR85GVE*`mYi(nkn}AKXs{p6xi-#ct7%|_DZ8WIRq`1O}Ar@cF0Qw#A4{kU8LhCQarss7aCTMbHk{a(?GfFPuU&81!o&wEL-o z1HV{vMI3;pUdAO*Kuv|u`_y&y`7-gER9l@7Afbd{);Da=hj5?~`gMje^c7jYAcr+?)m3Eqyzp?CDJC zo!7}uEk#n!kkKDin%5U!{GhdFUarZ4@A;Tp=R=KvCSbb)f~@O|kI$AWjG=-z<`K>+ zr;B_>+xWXrE^@anP@2`bN7h`?C_;pWKps!AhvVB*=C`?H ze}NYi9YeO_BT+TD4xovOWe5MMCHa*fd6)D^Zj`?_y#)x`o2SDC1U*um%I2=Kt>^h9 zn!zATpWaU>gk1Tg1@Mv8t%rojFZl9sw`xH6{qJcAq3`qJ>9+jiX!iR2VF{zSB++6fpt z!-aHtdT+L@YUpn1Fv8rr#O}l)MDcp>PQ`^5!M|72f&!0DPn75OClkL^L+q#uj?#FP z2k^qji)3BD(LMPbE5Kw$g#n$U0b?u9y-9w+Te6V^MF-I0?8OS&O<>`;Wac`n@^g^iH-ueDp54V6%Upm&)Pzh1Ema~u*Ke@ zbkxw3X&mbr>Yzc~j+JN%JpQY0{krr;-~2R`$IODqnsIRw%oZpMlcgvKU=U^f3U_^= zZ+pl774TS5cp3~KI>7$gL9y&iwYBvLi%G{Y=9 z-S}=OGPpq4Smd2g)^C*g&nZQNiRQbWH5FO!936?A zCi8E-m(sMfsHKr?Hn+e)>?Dgq82j-aNIluuOr3)W)S}lkUF@Pg#^1&a%drq5Frq%8 z(nq+s9a24d$_`u;A>Z*`cFYe#csUq)?z`BswB1kE*Ybd@?)mU-$K+FJ(ET9=&Q{_QLhPAs&6J;chEwbjI_mqJNS z^CJQSmnO5K1jaO}Q0yo0SaWb1)zz3eA5K0U4|W@^FF3BYm9J8dM{eSe2YCIkJ4lz` zCIGUqJI+1P;^YO}nJ`?|creBmP0zIhvgI$mcZ7dLnGJP?W9me7m|8cKei|boFqXN0 zjgR6N6kZvwYs}sE-|OLV9T-;#V~OFj@*y@ypIEr#I1_&a4}61jh~I3=3jZQyGog$n zOwJ4*M>->^qW`Q9?a`G4(IZQ1s5NN3o`t2rT_v^~tYJ@&7!|-+{4r)TISOftPpOv` z=&?KHBTk4KF!l5({$c4!O+<+DLD$65PpS0n{guYw!;8GN-HA#F9q~YP6uoKrR^Ni;t+-BOmzgsZg1?oP`g|F1DBhpKFbbYWZXRv~Zd;JSVo9 zt@~+OEa4^6C%7Sm3O|LkC3$E+9%;lhz4)16Z2i|l)Cf;jJ_ufBU`~J2yeA#d98Gxi z!c{hSAPi2rM^}u(*HU5BpHGoWEwn=!l>Yp6Y!%o4=Q8RVN@1FP}>Rz3_m8S z13X6lsjkF0dT~)xFnVzZNEZmCL1c{ZSic}MpSTzgsO1L9K;u}7&M@~(OW_V71#{{h zi={_*YOZyLly0DW^p-eBE-YSudGEa5wcz`JLg-7gBU2l zW8(nUCJDc*sAJnSGZc1VVcEFyQ8ctN!WELsIiQgglm8%F`a`+BqY1U`y5d2>=*QF4 z*G7~5Ih<|uMakGw?L%HHj(drGq)HK*81qEu7YhRIQC6n-n5L$kRVsW#wO^1V<%_WY@ zz9t(-TT#>opM^)+7sTryYB22I|C&9gWb-w?zGKEk3VIfs6=fQ%^{)ArEj@j^*I6a~ z>$OYiq8i^>#aIV;c%zvhwc2>T#JtNFg`mprof?4)RI%Fd&_Yr!MibMYGmIPDOG#w^ zoKM~|8eG_BLzu^A8K)BK)iol)mH(&LhmrT^7oIfeqK~W5iL+AVK)*>V;!EsF-$+U? z{eVoe+Y=n<5at^hLS1F+Vi3(3H9K%4{lYN)uUM%~UZ0#>dPSxZH_tbs0SHR@q5(7j zgsYEVLhZ_yYdOPdgiSr5iock}c1+_IPQ_Ml2&afXErHdbp2>JyW1%gPF6V=Lg;Rj- zbGuu=_{HZX6EBlwEWrnNK4d)DX5!xYjJPo{1Ngg&nG#NU2$&HwUxn{(ga$jLg92ZY} zP7Q*$?Y?T=p=mNF!YDRIU*ijR0vi-(QT41UVKMxg4-trf_HfR{U!=0uv*8`$F&;3q zR9M8~OfRi(fO`X1XossmBB6~g!QnWem`tI4@ee>MWq_BWW7owrbLbK-f;NMEsX&}6 z8 zLHgt&MR?YH2moFVc&k^+vZ7{^u{xYx`H-!knu%$_h1dX#eiCC+cgB!UjqTAwgb`G| zYU&%^W_zo9Nowb-%ZR2p=C9V~hLHFRa>hE9{t88yfKj^wMObJpDzW1*`L(-ab?TV#fr7L0;9grv@7Q0(qR zNd_i7|0mE`bMIwukeROL)rG#&A1Ro;ie6Lrw*|ZjQmLT?aWV!Q0z8l*gbX!RASU3r zg7aliwEVg%!F*s}jizom+;oXr@l;{LUKUnE=}Iyl1geo<7(*u$hu0oPf)kz3Q)IIF^MmEQrc(MjM!rAh1@M2{|Pr&yq}>B}w|sDg)0@Mwbu(7eSorme1jhL|pYllf}R~Kx(eD z>lw|8Is+IqGX&%3M=%8x%PKMj2(+4*MTd7Hj6>9MITrRQi_-rq`>co;!?7(2gQA5< zj{s-HZd3|?v~t=}3g-^iCR4G2l2wB5DjmyWhBk{BggN7JA8iymAOnjFhzPIflRgAsX(N>- zxTXvOIs#)s6Z5I06G0OW416)hteV3?@MgA9vVA;}mb(;An*#~(lA-xw;ksO_+6_i# zN@SolL^+1Ez3etz!+-Q;7(%_6K8&Kx_+h6}GW+aUZssb;0eiCu&c?vrEGszFlGyLj zQ!=}}DxfSid99#KDkHgH-Oh|BMubp}K2lQoy(91UnX1ADd*$IL)KRLAmKN zmsB%oHUB{*IkS|#?8W!>sIE%!mMcj0FX&gU%s~j!XUHL4!0wb z&Tv{%h620Fg(WAQW5o8;W@Hn@_S<-lBz>-xaiW-`OGpWhg9Ej$zqofyMu>BJRR+Y7 zl7S?~#CxzGJyNJh{q^qecDR8 znBvFIHkmu6TT|4_<*Vsx#+9-fMI=2=V!doGKmTrIhzu(s=1|<2+Rrj52VUA=O2v#= z9JT-^Q#TKF=3%9zXv67~^LZ}fAH-LiBiQN>2xX@NPlcgs?+RPt{ZGPt*=46{T<2ds z|Lz7O)=pd6W{=!Y0Y`m)oKQN@y=$2s;k!62N>$h;w#cbghzCVzNKv>Y=+kL^AnI2s zF=s5lUUL`usYhyjBB{=ojEqi8RX{;5*uP6Lt%F@sh{ZZ%%u>*$@7ON7ks!`^ZOAy$ z(#A)4vRkk`5^+GD@Oa5M(ed=X{7K)=w?fE90RPu_k2^-ed&YIsAg_Cl6grgRXLl-& zOix(KeKZptNw<~dJj1D+|4?n@Z;`b>4@h#zNz zyqF6{?e;!s_#0MGBQM~R&4dNzi$cZaioPNt9juN5nb z{tkN*=xQapt_`QSOeRpY8nkd2&KQ0@t<}`j`ptY?UfRJ-YfZJOsWCTLo{Oe?t3KDc ztf!@cZnRI2h2$hek5EtJr<0-vs~@2OCv?x&+(Pr7p@ycb1pc0-1a0G}ROW}BI=MT$ ze*8PVQkh|?nII?ut}@=R6aOXP$DB1ZmYfdz9UV09k3uga^eBw~c4`Ol*`kpP$OW-gsfPf$PTi)7m+EXMm|(S#1WYyRm-(^Qf8W zZy8~KhkSO`2Ly-qY$KHZj?MNY!hnRE&|U?QlwV6q-IBCS)MA9&dWt)AysCApsO#zZMlsg;j|SXx8vTc&OC&qX zEqwh56BKY;(Rn}b2FoQ<1;ffnFYm@tFKH>&Eo+z!S}5!ZLtl z`2bH#EXNu%bVx`}ca7Q+<1Y}Bee%6iwJ|xJCJ)w3DI#f#WWjGy62Zl?tW@E8gn`k?(lSn6Jg#8>`aB8-!#Who;UTkb zb=iQPGatz4v1OJO3ncYdyl%rzuiqb^x8K2?C7#YRM0O!N_fdc3E&uZ{5+cUq`}b?} z%;0N@A1UG=HF?ojazP0mM2`Xv?y18g+Mq_q9(EY#^&KIN%~!6m^#|yk&;?lMP#4(p z=#-m!Jss#t_~mk#Q9Z5<$c?QM7>R-RGpb2u#`|?JpW14&MM@E!JxZTa<7!}?m0nU^ zsjDDrRN;Luwp8(U$Y$F zIlo-dd$1*FKndQw9-^1UE3TK;%7}NR9$_6^w^>FLuX;}Swu3s#31NIqXK7qU^ViIh1Fd3zI+A zW9_3=ecDHJp&k!KI@$YjOcdtyOu`i9up_v zlD~U-5l%`rnXZ%o8T2j{Spk4(^fZ@_9Msm^g~#6BO0a9R-mK7i&ddZHQZfRs{A zKSDL0tT^^Yz{nc`fOOBTd@hZ~63!@2EQQ!%F!&H<<+}n!@azqboQZdUWWEm2h2hamTxt4iX4za91)?-MAjo z#BXB<%U^hPZ%J@3TuGOIC^XrB`zBkX8mh64D3s-;x*lQG`Bi`I;;6e#P70!YJQWu# zFVs`wzz5OnZc9t5oQoyE1zAGUl2xz4(VFUE@}G<`0Avh2AY;t4TP${eu60_Qlk@wt z)zUoj4Yx0Yk!&p^wRict4<(pS|6@SNAr#Zlar^Il%I{Wx{GTO4Iejnwh<0NMdI;zp zu{LNxgoJuLOoiBy3kEYf%~fhRb~sm_v7h!M8*oyS&8RjUv;vv4-Oh9K*o@iR!F9U_ z#|ynZQe2&&{o;oHmu?Uv&v%{F#?2B;(V~dv&G5+NiVu-_11G^1xS!fLQkmGjiCbI^ zzRkiLbS@(r+#0^98jNlvPfhUhn#$-kbK!kBK}q zGyelh9EH`sVbr`Sd)2&2%m1j_g9T(rgI2@dkU&O#X5(fy$z5oxcNZ65$A{s45e%Bg zZ!oaBHV9%G8N64YHjg=i0zEYe(mB}>y60^fy;m868OQCsHBF+r=hb53Lm2tkCdf1Z zWyj_z>>i56e_G|*J#=enKHtRyrf;{CfAB}9oxKP;S@P*pWAuJ+&*_bL5chls*}%35 zU(rttd9XI))`Rse`65UI>+EYc);E`KEU^4TcZmZ)0F1#`GOHim(7!L#OtEG#+b`@W zyz5dMuh)?cvS9hVJ=%mH{1fQCg?TBx)%q-%Uf-)#Zyvi6d#|QkxU_t3j~;+GxL{hn zAop0knEl>CX8?+?lx(y|Y2S!eExW#YzX|_j=|X#Bjt1g`@tRqerusuJ4%(E(0%4I@ z%$N`huzUMl?vA8-;kRxW!$IHD!p;nSWXNj_WhU#>Vjdg*lVBS0Va_Ec8k+8p#D}4h zZj4#V?RySeB~uDft4#|Uf=mdqvrp@_GV{V&ABtgB=QR(qt2n9-Q?PP=RAA*u+(-mb zH50=tou**1fUGFFVdQ(eKB%_LwL!zn^lk=|1oS+WxT(J;R1fWyO$g?zb;Hsr(klVCN>fQ)QU@XiqK(h5LdJMeNVe zrUz0)mkpH7N4f6F1Nz-)X_iLPAJo;f3rg3ESOPL(bi%P{b64E z7r6C~76L6$D(eU(84Ayen0=0dOiwlE>u->E{Kf+ai*%`6glsiBLbPQsh%rZd7D0r} zp%P`W+~vFr_^y#SwvbM&-dZ0-W(6B_QuKYjHbl-ZdT7{p2W9cBQzY+XA$i#j)T`A` zp{yv6>j=tIR{+gqcJo94OvM09k@yXZkcFXz49@8XOL+zoiD?UPiiKTK$wE&aWGI99 zRJr4%WGQNAh-f~8{F&g+5L6DQ? z8^*1Qm51egmILoNb2?u^IlQ}VF=`(^rhqFbQh^(s2%uJ%QC7_DCRdZKno3G|ppq!2 zYK>HrZyHxql__hnJl2qJA}CE!S@yV`FG(SJs=L&f6?53CnEo)j8s1^N;!icYl%&aL zL^rp}R)x_QJ_45HWDsl%3u~swC6~Y4`fc^e@;gce250zE3d=Wp%r1-u+yOOQ%rW-9 z@WW#H&=a#>-}Qs{GF2;lsZDXD?Fs&UKIePc1h@0=vXmF{)@e&WX1VCY7S@k@3Vlbv zVB30m^!%|(qKi?>vh-Q{XE<~eHJ`#-V2d7ca%4T~>bnVH_s%+T$O$9fb?IFfM2Sk)7 zkUTOk99U6{e0*uk67jaGY@nJPMI~>6p;X8f*4SnlXzawCQz;rx=t&Jjc{0-;&=_F)$-Vxw`)8+5ZF)B% z$lqK=C#Kr3Bu04opF z!!(P=VF!mvG3U6AVoNN+l?dtvr>9VufZ$r?)!dv#tqbIxlWqI;}NrHo6W5|sxYm0^E zS7wIG&ZNA-xahDpGUdczA0_%xEjPjIY*dBs!(oLsy|%J3M~2!}W8#%X#Ij(jw@(2M z9$3*!5zNj7;ydthK|~sgTGN={P$DTL!3%00e@+C13fQ=;!uE^j2qpe@_>nKnD! z_jvF4g!c_n@XwRPGAwzN3S<8>$KBv_!4WPI?R~qZPk?m!&mUp-gV0Q6jra7iV!&r& zx(i=VwVtbZAU%BO?77`s6#XE$5t3T)k$sqOe(Uce%HzJs=evozw#$i9(g8tQ4#&Eq zW|xLiot`*8rNpiW^L?Y1zl+Lc%&&a2I z$Eyf6C`dOb$Tv(4yjI&CHfi2%d_D0ZSa~ir3Wex9z~p~OE|%2|KSKLe&LF%aj9gwK zE9HB$(cBz}E}WQ1HRD3C@T*LEHh;Krrz=3jFNObVqp0=c;4nW| zLZV?TEo=4_T3x7Hr)BXjc_3K~^!)yj0l1Y7S>TJmvE(DDp2yS+Pc4c0oYnfA)oX1( zix0{n*~oegn&;}EpyK^GtI`;W&#$<47v+9K%lHASrH>`8toWN9n34~aK7pBo0Rkd~ zn~8r8NN-Smsr@}6Iv8hM1U}R&KGu^WeP6RIGk+L~kBrKapEI?zF|TA{c!U|Z6LDB7 zpb76Cl+0uO1K0x9JvdXkJT7_sVxFQrs?hwQFF;J7+gl-HFaHsg?esSzYB2SB_Yru{ zNx-k{1N80!4 zj(B}f=(t)OFeCWCVLI^`!Bn%DGjGEJ?U65sVvIUlb)oxoDzs;GVPsv^Ir0!rm`{zW zj+ko>Voq#>I$ArcB%5?d0ptF61jRM)BzEbhYUX|#;m2Mr{~y!{u5cbrMQv@ogtR`R zMXj_$Lp9*KsBf50qSFxq2Xr@+G_&uy!fAJr&a854-O@VP%VL$|o5!^};oDp=4_CjB z_a{3{74m_ZzG2?Xy}oKaHxtO(k&bjsfdx*(S2@qe7$fL~^k((+T54#!${=qjK3Cho zSJL;yx|;oXx%7I79|H9ZrmA%%O1PMk{c;#GOdI7wsK*Sys(d=A zTUIUDH(=Oz9L8oxqXF(i( z@ghZsIWp8|{EVZF8Sb8|Pgk!i34CceNL?ng6&_U3gOwjh=lmh>A5w!e0IA!LY^AMVg5u&PRSWI! zY5_jC{+rKg_J4f3UjqL?9k&+CAfDf(8FwP9%p-vrq^#c-Y=Mdyu8Qz9XN)R93=ql> z5NbgBzl7clhWEK*y*NG_qvBfWX@mzI6g6q48SY#gSFP#L%{_;UQ}VDNnWKdV?UA1U zgBe}=2GfiTE1!BNZrdULJp3SDjw=9!2Zw+d8=7_mj~(8tuU}Xv6KF+wfADR&0fJ5F zSZwx3of6U4PrSN}=FoVJl1{OGn&{BkVBuAGQf4OQ)F3t37jc{-c{u_YFXDmx9`g-ec{p}KdUe@8Z3 zGvKrWC-(2{rIg_#E`K`~&+UW62fE~hDUHd^73vUuD}f5v`C=-ZvgUGm!aHLuHqSi%;@h(~W6f~= zcgLAxIK3Nz%#CWKi1M3(>b#<8H6%e{YeWvlFh?16Z)#NJIOuEd6U&s}>yc1KnjDCC zqI?+_R^^@!5E;JR$;oa?EB33kuwXG)MhowU{hJ!WhJdtB?u{8uHZJ?6F1nvM;#0$# z4?j1VqdKBy1toE+YCiH-jxsB^>iuj^c3~RWk^v`nM2p9S0jGD5u7?6MLgSkIm<4JP zo;33cVTwqG@~0&oPRcZF*sVb3=yAf9n_T>7dXJ^gel}U4wACP_YO?9eUzEDVnltjrUIzL- z-R6m3;js-ly}8`cZJzM8m@Hx*@jt#uJOMoXjQ2$u4%T0x1>Bb;8-6u_j<5-D{KW$b zGpYf$P-aqhLj( z>;k6TYt8YnODAHlve+5d4DaV4@|p@1^O!hab&^e4X9FFE`eu6b6PKGet94{pR8!V2 zNs*cf!%bO$`Jt1+L)K{r<#iTm$@3BRIBu|+iO)YLWEuO-Z7g)y%6lJH$}_$AClUFw zemMQHP$AT;McHPheWOjV+>edm(nmNE7rvS^(VEyD6T_1{6e}fMtkt+9tPr=PPk6;b7D@xFpD>KvgLIo3?Uy(X4h(U3-XJM=gJfW!#CcBD4DVz8!02Pq3_d;EOR-eA1C8_UCe94;`e(`?qN{$BsTxW_T|uEAvJ{u2IP$--UKZtt#C@)}hi0&OT?3 zjT*~xlKtop#*3AVT~6*@Ns-1)>U5cIX~6=8m3)aKvts`0-0Qs=E2665`SxG8BpjXP zS!WdaD;^ik5ymo2={}p^bT&qs;b`-hw6ekAn|K^sDo z9}ZMSZ6Yx(>}T(-lQ0eh3Wj&Sau@H)jj|DRu)4pe-ePP)!b1`6{+*3*6mL(x?noG) zW#T$jqta9R>_&?H1(_lq5o&$tdVhUw%^Su123oEOFjMlR^|K9@MY{N~R#j+Ri3Cla zF6S!D#q3vjYR)f_(T;o@IidGG$cj?jnTKf5XOx9fW*uIB&{ey+mHLoNOWSy+fio zTg*~|g|U6?z}08@FX`0R!tbYjE?84Q4Ygn~9A7_*@llYE3xaZ;IMw4N;p?B<#72VQ zLQih4EuQf|-)YZh9HbE$P5PvGi`Bj3?{K-db}zH3WK*`(e*P3p#wPW$-Ru%ppWWM_ zwcT7S&-@uv8$`)TWK3qeIV3|Ok+E3ZFj=N= z^(qx+#wq9%zF2RND++fFcW{7|jV4qK84Kp4yE5?PnMxEUI|9y3iz5_=iYc^*jQRIt z7JsSMM(7wDYXr>2$d~hrUE^bw+k0MYu{#P6x~KrD+2pGhuJ$#Vo8f?1Vl7qxg6+6z(e20(>zLT#zy};*qwiW6-O%aBr4ipAJ$0NZ1RF zQ(HLCxg3ea@>u<_7>;DQXY1Asg<7tx4Z;kCyAG=aUu^3UbuM)<-d{>!i0oFnBh)4& z{(y*tp*CPJSzZ-S%(#aIL>7aJz9o(=7JDFN@L!7aSiOy2$6-h=w+O_l%a}DydG9)$ zP=+SfcWFQ;@?k_O{Fc1HYZy#x;tl61r>+-ztonn(d4J@E$q+kWNX*Rw5lHBP1CYhg z=563f=C?Ux!jjehj{)JG2N*OYlFJw~l*77RWa(QT5ICXZ^l6AlMCY#~1j*Z|l+1rH zv`qPwNMweKPCKhlZ$!Q0!hja^*}2hu#0Z5M4lfM1j7Wt?13IR*tioB1d*iOsy$xFo z?$Yl32ez1k?UXe%Dqo-PrzT~T(4$Ky%VuRdKIIviKVk5vfQ@kR0W_5eB+{mIOP4vo z(>aeZKx(D|usBtK6dHcr|Bn7+f0Q@-Ur_7_cW%GoQj6BMvIyG1CNe zNtoL&W&1+{N=rs%0oB5QbWo&MdgwtbkpWVDUrGa{PCD?#cJxk(ViP9~{z49KWEMSO zLB~8uv4U=vK7=Xuxu9gzXD#3U5)Q2Yu?HpgHqw&*7&CACzAuoh*fg3L6jzohp5N!q zau9Qw&_iTA(~kasE|6+|SbSA_YINzz3PLB@TYJw6N?WR3L?Uqy!xxi)BT?puigC`> zbk8Zo_@59ci~YY4IQ_2>&=Drnj}s;fja+&Qh_}&7fK)v@6v$@auNxA{<7101WK5eh z!N@j|iVMZqr0f59|DpVU*NgY3rgrqLjb51@JK`TR7(_C2RyMY z(lMebYuO8N8`$=#gpL20-rwn;={Md?e_a33LvAy@jDP zcD4ReKnf6>s$U0EfLJ|{0>+3`>YvZ>nF0oj&m2-8Y_Xhn46*-&LE-<7`uIVnIwn5`T~EI66UAnB zjHsb3rtVbnA^o$vEp$v_LV(m`s=pMDFRIx1C=9lkcD!W+QEc&)ov7p57#p}3cY1H8tiBw%X#Pxy_1uoDZ(>_ zA<6$Dq-+U^nj7oby2}Lm%pTVlp^ieGUJ@Wh1FzIv>_7OQ5SLlpdrNZCf;WGcO?r|r z{odz_FIYI32M!nf#7Jea+r0izpM_|DTkw;eIpf@ZcrdI?9{X|1&)j~Q>PUTf97^68 zsWwktZ`)Q{nmwX{{42M3yyEL+-}%Kv>h~b}>9$DwFvL@E^xcj9yrL)j z>EQ$-Ohp0zi&oLy5uN8@hA#rltN;>=yUXH;!53|P+c>_+20YI?n3lEn=-P2ji zbzdMbkKO`vxt^*doaedpY=ljU2d_8eUIPHCLlc%S^T6D{e7;gW{x-%E{XJ+J3VA0E_g z%{Y%80-Q@P^?HJb+_lg2oJx|| zX$chT!~_lxVmFMNJQeGI=T=^W`OO-bQb(Y;yr9#RKX5i8)$1gQ*G%8~+^0FFzo?Tg zt;ir-&o8=lu@A4U^>Q@2j_Dknl>d6=fQTf3Y>dPt-ng(!qw|#R6jt`{_;Y37F<^Xm zfByaD>^bxAYJJ!GThcU(+_kG2AUNwt} zoY(vcqi9t;&!GZkF4>u)p~7&CZ&LBAcKVp=o2OQHDh5^GY@JDuCFR0Z-df`?!6Uas z8FM?*eWT2zT#b%=TyDYhMiG;%BD9w5X8~?jok}ITdZmkY`eA`{g0<|EY=rgP8EpOU z!oGdm{HM0VPMqn4c`4#{BqqA1gTdM>;qD0=9@~m5=%-bAsP6X*?!40rQ}PluxVv0D zYb*9<26UbB$qHiX1_nGopqZ}`!nux9@^B!Db2WGV36ay&W@x#_K!qdPxD~0RQ}&&4 z7!d&jxguZ7KcQGF-}*!GhX*jlOik5&frUdm{Qf?}+FSN62?8I7tN53N#@58oi4nFA zBue^0e<>zSZJt!2?>#OC@jiI`Vo8d`=}BIVN{>Pczlj~m=kq|>_B_L4;cP9Yu}4BV zI;JUJWnGXNi_3IHRBZn0jm7$BV}npWfc!?MSmPLRmLPtA&T8$0mw-mG>MDsvP@^*u z!o-$@Q8`Rwk(SL@=Y%s)vihdrl#SyAgE-@HW_=fvMc(}fngj`2YxV)@AiakVuVdz z!z)0t!6}^^di;>ThvoD18`<_RhQmZzT1@=_J3^)lJgJxT{h27}TIJHF_xW8y{rZI6 zp1mZ;6!d?DZrUdEs*l3qXL1HS>-M-q-v^{TF1Lm`zQTkM0XwSg1^}fM3>R`9a={f5 zjf5PP=2AxYXFcYHNX#7rv-D>TX|FBpcZokgfhm1~{HIb3Kxux4GyNnex|0gASOr$ay6D$jm`fa0{VAD}qr!HD90zexZs*pkhOrcj!w@O(JrAf+=r+ zg@z}yZp1Xlm;Vh5Ew|_d9_z?ZoJLB9sl<f+lSDKGG(W)+X=P^ zW1nPx?h!Xq;|EG(Bp%%Er=Wdm^Q4WqYYo)x5{nSActVIk=#7a-ltiWEjxY5s__J@oAFO&9> ztfbgZRqVP;5@&@pt^ND@<1g(D&z?<2sbSD4W&?zPR0WfD@9Q}WSg%Mszo8_OttVNL7J6k$fs z1+nm5YHYr&L}*)*2AckOz!@1~M!mFJH@{?))#=?w4>RKJr>Yzk#0uL$ChU~rj68|Qt3V%=vWFjXdYBYb>a!95 zH9|dan4X^RO&Xi3U}PgBLm-36_lZt&>#;%x+2j!c^T0x|hK5K+o@GxbFGpDYpiTJU zw7n~3hX0elhl&DId!V&H0ieHmqDu^5W#RaaK($`tN)4}0XxK_c&|~0UVNlgaLK;}1a;xk@bwj-T?}~u{ z`iJ5r!N|FAN%o8`V<26eLbJjjjb*w~la67+5FWF?m~L130jEpx0&v%C*mD#s&*7bf zfp~)It-@Q3A%*i1Xj?B-_ndIlNY z{F0?HKuP%%W6Mg z^ftl>?wMgu0JXO?bt4XT!4Hba04*H-sXy?Q0^&(Koi-Az3nbv}0oDd5PD_L}JK9L2 zLD`|XW{L=-=VCzWZ1S%JQkTn%MUMALP!j}773m10j0Z?X5@FTYtIvZ8dP5^BL*&=UXL;Tlz6O@&I8yi@iZ|BE%q692FSjr2v7&D(5&D6m*q z<-Iu5zr{_6Sb_dRS_)wdsDz8|QZ$wH^eFD0tNa>z4>Tu#WI-cl_O!j znO@rFi3CYg&mra+YZU2dUU4Cc zl2?@0cdK_>6F^t)BjLVv4_@1U0)hJ7Mos)PJ0T-%ZJf_=Z6wuwZrqKz*q_PEUTB*R z_^Qr8INX=NC)$%(z$r>{!WCU!UCi%C@AGTOR`fAUAk2DXi}vx%);(=!O}d>(uk%eG z{^hU^d3p2uicI^D>))K;Jaw^;ab|hTh?Ss()OvV7#(t+vGE!vS#I1xttzsMD;ul%> z*RAGTD-|4=_Dl5{xF>er^k**BpTw^`&yHg3vh3%yaeCE{!qyL8A6TcL%h}9*wmp88 z6FwX$W0#$Y(5!{dw{#|5KNn6#*x@NEoiKfGjwe4A3;Gtie816Fra(HT)0W)k?A~J8 zY`|yw`b?W5=yGJW^7*qM=1lJ{rm}$|p~weHJl!eJ>gSTN52u=KD^|sD1J&YK9;3<* za?je*bwg%~45rvF2khUAAzwD5)UUQ+SBwb0ontB-F595HcsFid^mY^PV<8X?EV`Z8 zC&Gy{ua8ga9p$8z_tU;5E?So55A;UWXMAQ#B(UePOq8ZBtsU-S;*S30 zD)=bPX6y&+h2$_iTvsgH6UvqZJa$AS(;iL8n!U<%ZkL%h;}Med8FT(ZM1!Mgl2}YN z>uS%Th=6QbqK;6p)6Y3H#A{JGZ%;%$e>kS*vx%Z=S*uwJ42^BQ`CwbUAa&F`8Btd! zsv(N!z+)*X^AS`m$=#hyTlF7s0iUPI+t5o^)sngYs{MZi0#q@{`zM)#!{ zoOBLb4j(Z;f0}Y9asD=r#)Cdl^K)f4hP&l{<;mHe44)M0ag2MpPr6Me^CdLqF3%O| z&Kh&Sk)fUWlFj0D9i@;lXS}{dx9WjzynTH(v2dVHl~=$i5>JT%jKvm zvsSw1xIbwtnoCrP3^2$HVhl6Il{`tgQ@%Klr||%tVf=?uts|4EUR6=@mdlBFFL~Tn z&5mt`n^z-Ta7bxMOn;B)=b)6=pNYx5qdOwb;3b8jR%8Ki= zF~@AGJx4bJtmw1?bX|rwgCsZm)jFLv6&`<(wx#|`seAHWEH;rf4E2YNn&m>bLRq_z zN7aJe^KtL5h%x8A(bc_`pG&K0`hLuqFIf|YlRK5Nc;_ZqGqk+W$UqicfywkMyQYKbk@!dMza(R zacg7s4+RB1j@Ra9OS6sHXkX5)s01xqEoowNMF(?RECLZUT&{&)zF0Sk9uw=X(jV1s ztt~VGKh&kuFFaD%{}L0Okm)3T^j&{crSZGAJ$o!p+}59XBQNg&ubbNfKPZr>m7G0# zX8Uoqt3CjQ>EP%WRaS7OF%=1Jx0>VEo;K%S$Wk@HYoi+V)boi}6z4Rr^Ll{H){|}w z5T09zc~s;646weZFVhMj)9k2ADfpEFS#@xQG3UII@(EC3DFHa4yCqZe309k5cK zAmFHe^2)NaFnU8PDuJ@WDmQ!c`&O)qGk4lIwGBzq3Z6{vy}Swi<~doCc&b+i{9jeX zqY}Qpao$ESXJRZ{F?+1Y zRO7;UR=dF2n=V)Q>lG5C;QXm_sVJk-aNsI-%$Iu;t6i^77Y-A8pBUVs`PTo-2Y+_| zZdZrI3)%gwlk@)2Szbb88ID|D759-gHA_MSn>t*3>u`wcbc`AZ4v z!YSYE8(2z^pFa)WZIuaT%`RPq4~8R&6BMD$F^P(nV-8C&BP>ifd!wSB=de?t9SnSk zv(cXE-BSD(9p>oEzF%XM#%}2)XBopuf4QlN(9K6DOR3(+H=&uzxbty}*r^RA+7gp- zj8Z*M99+nkUMmGG+ENMrxRfv?n7X)lpEzYE@=9&t=y-iZi-dY?An)4yhnRs0QYmMEjHXi3fT7_FgVOx${hX8!8*rQQJ#2eVDK4Wani_};>vRi#s8~V# zZ_ywk-2}}e0OWLNJZyj%V5KAgX({UzL30FhG>2cd_|SeOwqNj;lrY_3v#(efqkDhy zeMWbKK}lR8RL~E<&o@i|+zr@W0rKQCX95`bZV9jm0nh^z2$(wEV&_1IhBu{HoWMqG z{#XBcKx4R;0YiHLLvP%(WK!?DHXHCT+NH^k1AwB@{+%g2YQf)QZ#F^z9TCWe;GP@#Ft+e*OhC_X6x~4IxGy8C0YKXOcLx~9G-ClJ z77-;LYakgz{nCea6oXX3GsQr#e^Eb-5bqa(xsUtX$iKMHm|p^;qUqYF->RA&UozY*GG#lto|gwovV{M`x+8qjp9YtTRdN~J;o^2=GTW9ToK z0rD#Y=c48Dnafhzw7nVsiH$vWGgAVqww0tt9wyFp-2922TN;h&`6Q?`b&1-&B78MM zd`IK(t+)c?Sx2%d1&l_9ztMPu5D?&7umJDj>iB2iFanOiWPSuA>W1RKpi^9n?Wgrm zc45g;GxUF<5zI5D9%nG6K%gkW(;IZy{{@}VYjl8wGKXB}+3y$vV%!oI<3J8kF##C` z%jKJ>#q|@V8Dus!N_F;GVszL4N90gLiK7?=Gyu_DI#>7w@vOu^d4uo*WwObR@!b-z zIiyKGdf27ndr1*+)AHtVpE-4eZYDJUE{g=lvE4Nt;D-#rJVpV2P`x+-kO7{eM10zM z%}Oj2_$Z4GsGU8|fW)R)Y(GPwet=7s0pU?;@`j-9T=1cP3YXypg`)rqLd9bNqSSpR zexLeC_5ON{kM8u$wagMISAfBg9#A=KExrS4a}vK;I@?&l-J1tss)5`F_ZLhz*^PV6 zcG`zz{MA)W)M(H)koPoL4MLMlMzVs8ydqRT{31@Ke%O)>)FWKVwUrnc5sYKxs36`q zWegUM01-Dg(|7FP&4r4Y5Nw}5?js7e~e?;*%EaUz|prYQ%^HTjC9Dfw5>!cHjDo0<5MlU2W1}gXvEDdfd zdgbW5C0ajJ9L;JV9hteAW=H;7S%Jb-0Qmc`WTth0Jd_w{aA?%-MuV?#U+WKI2R|-a z)d)yUOlh+u>pm6Gw$cpc3)HWy!~7c_yzznG+wCvW@jk0YAGq8o|HCVEr~Y&GzS%j0 z;Vxi}q-KG(*^PQ157kney`EKfsWQslx_4e zps`}SqzDk|YxoD~KrRC1+X`qVh_KXL+4)P)yJkX^BImIo%q$Ba3xQVnhgR5Lu=K-& z?ep&`3UXmBQ-r zAH_TmH**5$R63xTzxTfDkouds*K@&5r37}e0pRBS*;fAI%?PFWX)c(09c)1Rf08VT zTWdOqgez3I3cUB{D+M;kANao;`(K&>5QXKilmy8DY9mb7AKqX$w+>HSv)AzLIzMdULuAZ1eSO z1&Wo_D#C4>?n!G~ICakfI_N6vlWXF@K@8}WqfL{2_<6XUY&(wcXP=~()*24N2a{_2 ztxUnpN{2Ms-zx$u&10mH(wqESpsMtV24|_11HbDc1VaqS%mvXfbyPzjE?f^Kkc88l zg|EYj5zGQ$7$pf+Acrui>;A}S19yuO-?SNE(uL&-kUT)(+Iad0uizizJM^XP^WB3_ z9Bu%D83-^KEPVGwWWf=jeT5UvLmnPz0szGEh(JW2N#txnN%{oSApx-6m*~Kn)bx>^ zA{btP0$@GRAzo9NRG*SCe=!_rw*QNUys4(U?f9Yn=K4(PpaY>#?}Ie_VZik*5XFOd zzocQldzmDs&-{Spx&Mf=Ji9$&Z*;@H8w2$#{R|4?>p@95ce;;43Z|jxc>QdvkV-_2 z9mL1!Z^gk07jP1ok6|VwGXW!|eWr(ebHfT}0a*VR90=7>!TR<%{izu^ZUZNfpTL7R zhyZe7mWlx5-a=5y z0=2gstV{4MC-j-)12o|Z75vxP>aVhaI7@#EOdl{EV2}-iUjLi3C@_8kS*Q47xtFn5p^>NI^yW<$hjT6Wxji&=?;WS0{b9^4VwRW z?m~P3grq;)%KwMS*UbOU3E1(v{D9<&-T!M;z;uH*55YKr(ewZ2&JBXF=X|h`uoO6e z`O`FMvp+Y_hbT1a{AY%Valy`Wd^6fAmH)^goc_4`KxplT6vR6KF%Kr_CAujPQ;z)U z6s0MQzywyDa0rf=^MF8u1sAp(oDjeiv*`Jc$@xdT!qPRz7kn-V=17k-&|`oc z0%!Q&!J`;*T@?Z>-p}j)$ahfiV}_9X-TuxM2%_;JB%pg5VvA)}ZNW>7s3KEo ziiyA$%vYFvO;p%mT`)a4Y=^VL`SbX6gQfmzll_v`h^GGPXhqNS?7W@K6Ds?_^VhO4 zOS!P;74ZLIH}?D!>#yd>o_m}VebhUjcbTm}1wPz!&d!zgevB8jSvTYUJQUd@IHoDlfk?13>V3MF{u1vpc+hcqrr z_E#d*)s#Uy=T%Kd$NAb`dI8F67NZfx4E*x7)kNEAvsnW8bkb@W#TO`p8jLb30` zF3#fli>r72v5ViFbK&ytEc9qM3zae_Oyp#E;^2%V)CcKm?q%;-AaB_Hj~Pdgc?25QqP5|R#sq0r3hKSuavX+ z$If3D^xBWkyP}GGrJT}cEo4&#)pulym~(j}}aHRdD+G5g7&cV%^YzLt}^mEUr& zEvW3+j0*0#3uvexiO#Oml|CdF%VK~8ZhEU#plw8nt;&?rW`m|yGOtH%B;PDVjnb9& z(QAc9l6U#>3jtYLUjXfEdCt-}2EQYR zR(-BD0*yWS?I&e{li3-qLM?vJfe=VX}BX){z1l z^bg(K?ND2U_2B#BTv0ih^zO%V?BPm@){*j>&NE>+dI;I|wP^ipKLHiL4W3_rsvmv= zTK}YX7pCD}6HM<%c)j~I9Bf8Vz<4)zJ$S%cte-Fq9m40}UW%~|m@73|F!lDad89r) zDKHlv3BmTJ_QOmM&)NqCi)wa^c!&4wfu>XRFTnOXgu_R+6>>D__A@ z&h?a>LGOS5sxi=_3h;N@y>;k3vjz8Dm6F>ZcmM>-uGjY0QmEap z;fwwZs&z8YKGa^9L)o}+~jpQY5;D-6n5@|jzX?Jz#Qeqy^b+#7{-93?;(02-3Wlz8aLBq zo_6+`8je9=t1S$L_j8->V}bx?Ftc81!rbH~y++rc3&#B1sy?U`+yv^2FIhjk2LLlz z9cFw8Y}|Pq4ZC#?lL0;g==yJNY{Rzy-gUDEJpBE}Z*hQvYlXje{JwFcXWK9iFrxGG zpNDgGT0q?X%?-f1{pIUNZVrFH0f>WbzS;HX(tq6eztr=4*WXS0Pgnn~x&QBC{*#LT z-}fc}cmdA;_wYXgLF;Ej4Iqa9_wYXg!3cmZ5WD|-_#c6wdrFN?!}I(=&+B9^rXBe8 zg?5%pVK_Lrt1H+aqmZX}n^-Z#^RbrUMkT}^nm@VQ8sZ0oAT?C8J(JFu}byINbtM?DLhWX15?i8>==oRyyU zK#I^wlT}n(Ps%!@I5Htd%6T^bof|dV;_4Nh{B5aM6v1y^zH?hnh#M=Y66WG^UzS0g zSdQf-m8dZ;da%XZF6?E6`$%GPpe(i2$}Lo{qV3p)OgJZ0NoY-I1@TtW2;U6RFq4j2 zv5;+svr)U&Nor(P5+d_R-$=rINr|3?#n^GpxOIlv-V^mKE&QS^gayk^^n13waEdkG z5DzzMR}aN3$C)bpveHG%^^4Zv3UNwVS#X0Co1??3Rq3m8leV!@9*NT3Q6ST8{Ma_* z^&t~ePMV2f0d9hXvz|%Vfg`4fW6k=42O_mff5~`uOZWNZId#Np&pu1R&xC>#w2i5> zXe7nu6TOPiCZwWAxYE(Nco0RO;HIk@4G&6j+}5{xsT$Cr9o4iqD90)kt=YtQMyLL+ zU;KYmN0kn+G=`m7guLIZ+wT(Gt=cX}LXoJIE?0Vd^ooq45=pz)vd_Jm{O(-b{c|4b zpvE;XYvxzC+@>9pH;z6!8s=U+ONvxGeExZ7|HL==$4moX5DAva*!}n8Pl+btU7kp~ z%QAJxaE+nWpsf=NuXh_3`4R7i5)P8d>{1F%xIRdmSmAZTnm2xm1u0pYv=U3S@7jGe zE-Eq9@Wxydu_Ypc*OTz+VEDc&vfQ8ud7YLNFFSeYdsk<+ujA`)c-gN49Adzwj@R{z#FM*Op<#?S)IncYXX07ygf0eCSc)oSw@SSA5Oj zRV}{9v2gw60hyQA$^L>~a$9iY6^VS^#rFN#tNLR-&x`GD1<3dAE5c`b9vAI9{MlaX zJ)TDf(DhbwDbIVm^>v=7?Xy=K8^V{D0*Y>0%APD80wObXMu+?2qm_6@>fyG?r%yWI zDL6zPW9>ie$ROUprcm$^#Ac^6dfE{gjzeK7!tG;)GJ#n{xA>$ZBK(7dCz**toJh)) zTvFer8jFM>m#-hIFL6|airY%Y``oTqJ5QQ3RjOQ~wsVGfq|Kq4iTk@zDre6>?#FwQ z8!eM=m2w?M_z7X{2Zqy$d|A?W`qYo2fl)+lB;N5U{2qmth_lZo3Ll0&^*~^QStIHR$MZ%86gct?TKK0OcKa}Ig=I@6BZ=uf8&Fwz>RJ7IuEGHAb zWIgEx@I2W|XPLdCO=zxuDHw&9h<7luT<(1$37!3#bnIMqx@CKHe03H^O{&hYzmnKu zCcAYoJavAYh*!MQxYF-+br7@Tb-9<`pID21MlyaiO;T%q)NH`5_rnWW;%fgO?CNBx zThAjU;cXx0&o}z+yNO=sD_-~gT((4g96V2k(`^wG--WOMABd7Y&@P%6O+Ohv7QP%v zKed^0qja6C_R?NQE>ti*Q`Pobj_I&Cih;9T)I(ONM%!FQz2qkuB_249(V0>17p6tS ztaz=t4?njlZ#P@8E%{UNR&V`J)Jm;hosyYp7Tq%2FVudoXy185gyK?{W*&@O?jVlf zqaT^n@pHuO8rN|2i&yj2=1#|rh~J{+(1TO>5qec3Tvfl(Q!~!@*lDgyvoU|);m8%Scx5~C=xBuiej`An%PnyCZ8(yMNpzRtL;R50hU6p`e8FER z!bd2HV(McU{XRYaN_}xw?6ir>U|etZUG?d@-lDcF%3P`@;viHcZGz8@FUuNkAG{t4 z_l3_9*#0oUOl&6YAbi?q>;W_b+E=QJ}zEVpKW(?g9V-W;~O zKPKxp_rLMyFcd|NR^7fpm&9`63d3Er(1Cb;D&7c!TvZw1t2JBP8Tb7^CI?lwX98+_i-JdSSWglNh)q#*p3c(U(@<+DT6~N$wGm{ah&_9Gxnb#EC*zWG zZl9b|7}4&X(l{O&SG5;`^x*>dFgrfF_1@R`xcNrjx<>D#x|K1cH4*n2!UuQ!k+$ws z2=b0zA`9}C398o`s+$47HBSPc8i%x?;w^XZvty}IUuRE$5B-XsWl;RF$LlxUW&iQbkGIpv+G&#&9sl<{U>2$b>a zlsPkOoSd0ru>d!6K6_bDzXjTDVnGV>0t&Q+zC5LA0*JW-i8J&?MsXuIGBN#zLD8}Y z{J7-#AaVrqxy0kZ=a>}#ffWqM@#7`L#7)2jC>+P@q&6lj?{Mze6D_qUw`_GJ#PjZ z(dMa7!i1bp_}m_MH#4OOi~})b#e>&Mn3OHVAE|3Xk%za&shct-eTEwoj5(ZEs4!{I z1Cc+l5l>Qz@NtOyy!7x!-U!*jhD7lMu+sC2nXxp`Gzn~lJ@IjgM$UFYyZ1wdQVu9R zv`wxf#bn}Qk#OpE{w#Ci^IY)k_sUBG?>%36h{jR4jkq0cC54gz*< zcDst=stzKMflTlLGXXOxK8~`9x9+LWQQL7~K^Ku2J`OQu3EoevIR?;yd`3*w9ehG} zmA^5NAnVguMcHHz)Xpg6gCm}Rf}TPVpPMuYz?eU2udBQ;^O5p-O_eB?0l3CTfhrR1 zlY^{*T|{9d+YuTrM1dp{>J!gt5MXz*&n<_)WkT=68CWjviiy{>>f-E3DH;&JBQ80P zF@C6sfjs@OxOV6}Y#D4{pf#ui=yTI^yRO8ht|7t8~QAVc=&}3p0Jb#;WJ# zjlMz6;L$MvFUk>{AQFf%DEzB$SCTC)BEK@UE&NFi zNBz}~fzBt+GhH@cL|Z&gHOS|)WWv{EFEKFd9q>zH z5*6_Kg+_wU&+f<`zSNv2zl!S-yB?NG8jwX+d`Kxm+_dW=$|1-`+4B83dAMU1XHDh( z_y=43ZDJXo&4R|=w4^eLG6?ZZ+Pb7ni+1xv>*vY6oIUAtFAVg)K=|PycN4K{8ASzO z#$frgG~R>!fT$Nn7~_{1oQm)TKyt}(bQc+$$zQarni4pVGH{$}_(@ABu{lmF;z{`P~omY z#j8i~h0TbfDswndn%S-Kb!v$%w(gRS)*^Y zM~oN_z7rKT6ZPB|88VH5AsQ0W()=|lb5L3kO({u2UJ#94Jj8PzVp^+|lIR-i=tI~~ zO*$H^IrVY@dcc!q)agWIQD_Suw&i_tt8!3HYs0XzNc&*5BSbdf)b8oLOtIZ3}M;}e)y_xs!G$&IdzW@ zi_`njqs0JY24~ItkcnNhRLY0r%{yokX$J3l=-x0s)s(_-Y_ptX2 zb$4KPYi#avh7^1ecO+a3rmPJjel>&#Fa7+Nf&V?ftS>b5r5$YPmpHP1#IiFaktxr# zd%R!UZ^~-Dr#c5H(Ufau=Zl7i#5e;<;SYtyx)X!_Msoa3p{DEv8$DT@vEPy*lJ87dX?#fv>%>d;O(oQM1U17J;TpEKGP0Y9sw(W()7cc>2f3DY>+QZ%Z7 z!ALg{UWSr6uL_%eN!A)Qi>8JjJr6aE)NKtFdKCJW=3#STvxuc+vwa9cJ8z9gZrfqo zLu-%Rvd)lGP7mizS!+4df%DQyS*sT8<9bzpa)6d-3O^E}z>ud5#VH@g@l%^Z+)VQ9ZrS?u!HIqkph-7b3~%j+xsNT3`n-V<73Epsz5W zE~s8ir4rJkVc9qknS>*1>Bo&`O)$w;V!GNe5RvrZEu(;Q;9R+W`$s$G&44skl1Hul zaoyvX!4O!GJ=S#8>mmhH6$&R>*b1MdT(}hu9LVK6#YYnFGhvVEVp{ ze_zw$#S!1qn~aD~Zh9Z#=Xsr~0-r)tEu4lLv3{;PUBX>)cBn49$7cFk5xDD{sZ!Jy z0YA$<*j0|gXi1ujuU2;9omixvYxSR|1uI+S5{@Bp0nwbvM?i(Z?RMVW6)P(_4f;+> zUDRq4ZZOARM3Mj)J(pu8;K8cQC779R@UxV5BHDXtJDhn!A{TdJ^gzYvGvLgleZ~pe z;w?3VrAcU1t_$SxL>(LRMu%z?G#rVkRQiX45MJ?9v7)F>?rH=kv!apEZ&Z(pM*3bJ zvQLh8kbcq_*6fe9BugDoPrvi&-{jJk22=9K>1>;rg% z$vK4clqv_AekiyD*T25FndT{g#5d?IBKaWSjSgpzXsZ-I(K3?9_?hcpLlKhgKUj4) z+9S!tSf!{2TWy@u7xku(Z%VjDTYZ@DEb8U&>l&?Qjj@ts3F)r#T*`_J5H!nRGK=ng z-gQfn>Vvg2N*C9Jh2(I=g9(cjUiUbwC@)PT*(EWu^~GExSzt(*7bz<#{8ahOPUY~S z1T^MlV$K63VdFwttvoh^f1MGGUZoJG*eoCk;Ynktl47NF*^+)`cbaUOVzzkMkq6Gi@(U~H8bR5zPAlOF6B2)`TGWG1?#(EO zI;v z@It!-*D_j+A!fcYYjrTl+}LuPO&eQisqvFlrAgqwchjv9i|D5ObZ~RfVNn#5^_+#w zmm$t3O&2~fssrWJv52ih#tDgg{$O;yvv$7WgYMbi`N;Z%5A+FlyyXwp;{olX{2}@b zqzg}Ft(A7ZM_BWbTNoAfGC!@P)!H)SkEGPvB9>(Nkh`xCY?WEHCYn$aWtCZGhWJ8z z8!P8+Q8@}TkR!1jqu-y*{RArA2d1$nh5tI>6xAx;Qyw?biC`Lig0p696wLM9xx#~- zs*LLnS!^dgZJyy&b+Hu@7jfCvZX+`HL15RjGA5+%EqeFW%E z5|kxTm0{r{t|IPE016>t9!B^a6%Z*$)$<-_&B^L~opB1_!y4p+#2etl8pscx=P}km zepmzfQ3mD*ntQZ0kRN5e{OD5vAH`cO6*-1l<0>7l1NNVljhw8s&;tnLtczuz=S{$h z*0`!b`(U?KHgwoPE35wOIi0PsR;K4&qtT_YmRAM=!My}M?iBir(?u?Q$f)HxvB={O zY+%G-v*OwOJ2AKG6z4{z@N7Z~?6QHn3<_u-=A^vj;-Y7Lw%yuP-(Mem@j}6L@Zp`A zt%61=97b`P7~9~z*?U20?gtVb3*+wcP5EvG&AHO$amto0@*>vJ@QL$*=YsrPHmk16 zBi01@>TQu#x%LOl^YRzv~FDxWH>$M)V;t7R3nLpv$ z%gzS|eI0+=rk#qqtJGt4i4fbe{+(oK_v{%uJHHpkQQnM@6y4Q+xn6xqErn_JW0`6{ ze&9d5)Lrc%l^m9xs4$*xo81rY+YOx{r4+`xTui)Udml|$sNc`SnC0^1oUAH6X1Cep zAoFwSh*H(?VNW2kT#SABJ^j!{EjU^U9|$)-k^5aUqIH*i?vwUW(OrXiNJ1i);(KUp z7u?MBOAkI?nFEE?S|9$oF^uxF5?1dwRI+3_T@P}hn}I5Es&cYq*n7K4E5Q6COP1GV z^skjoHjzlhIMh*P89AFh_^>GLzN+!$oH-$+vud@2@!c`eF=egA+VHRlubh_!#Wch_ zB1_`EOm3P2J88`0aS`57OUBn$sB<2KmqY3KzIMbDA7;KR)f}?XZL_@Ieow@&t0W%R z#t^NM`jCT!sF=a~p2nFS>KyqCS+aUxyMfNJY?d#5NW#$E2Wc-_!VbgK z+z5S0m+&nGaDsNk7}B7m`$|1FhM`RmeO>T7={s4flf6m!k)ez}zh6Tg%uhr@kr_k$ z+}NVkhL&s`qa`9BuI8N39$BhRHk57#bwV5>SCc`%YEF95%^@lDDRsiusd|Ai4@-Zq zh2F#%iB2pTK$a_t)6h_cgQcapQ8hxx5VCBM_48()yI}wYR4*b!yc75JYdPm5t^Rca zt>&y!l>Q|ZV-!|ET`k3;MF^2DBl+?T^H(-TLQO*(eWRspQS-g;!ytYeP=lk!KH@nHu)xUpGwaI}AmXiwD6u`W`3egt-X*1Z6|R=*HEgXR!DY~A>I!sR@#R(fkMd%R#z)~aGJ8?A6p){k>u z4H`o2X$;ScY7do(ex5b2wuiNzdV;gxthtBk$rY$K&fCC#Kko-wF8+er)z5TB)xF>( zKGADxYcS?bJ(*eTcYJ1(bEo6?$(0!skI+8#=Q^LKmIF$uFTd3P0H0301 zXf3ju-1Axd35_{~xPIQr4*H3AFMIOMiHgRsxh7{{J%Mz|YQ?`7NO`xs>%pLS0%+)|i+?ZxY9K8-OyrhcRx zKx?ne(}PtqZ(0X*AQ|XdSqKbpX6C=}!Q)*oXRVG5vv3+zdW1_!M_9cuMO(qVx;+$5b;0@3)wMnePOU zu(|u7zToBORVio_;gbkmoO*ZXV&n(1)f$fD`c}4fQCRSM3_B)@U=Hn=U^>m6GSKt@ zac#>JY?Q_0=~k`rkt3jAFXRVfo9Kccvu7qZ&Y%xjJ@xCa#4Y>slOjClsK)f3r_~xh z4$t?xXL~7OpnMjGfr49g4N5&D2#Sk5G_r<1RF8(P$y24;;Uvdj%fdfr*_-h)CRF>k@ciqoStS>MOFecUZ5Y_~0%P<=PICSxQzHG<%*NRJ2Z}Xka zC`Z8WeW9ULgf1>9f#l0PUJZo@3x7zK3=EK8L@10h=OG{<(#eIhQpCDn>h0ET5aUODw zg)KDF}SfD%vvB(FKsFQ`bUPc~4{#l=J&P{;S%CHT*zN81ypa?lpiF~{d zZGkrLqAs08G0q7-ze%L^>B%6yC4c3;4IFMrVUM@vu_VK{6XQ<>Kd&pTO;gjq7FwXR zd@6YFgdNSs4FR5Y0;L5~2<8!w53I}zF3biWW}QS0p-gY-H*FmemcLsoXdL%+S93$% zg+{$^Z;v(V6!aSL@aa#4y&){M6tI`E3&lY?-^-?DtT^>o+4Q;!vhNe-q}y)KFNDFw z66K2N35`5_YabWwG9>YR;^5(ny=>n5PRdYvyd5AiyT*1Lrg@x9MowCZ6!kc-9(qnt ze`O6M_pEiEkD;!&gVOV1aswA%{@ZpWGbH&5zK|TjD~Y&1lICO9iAs$R|07Q)8|&8m zebMz3Uu$djgYWnUW}V209z{w4W(ro@asQ$EijIcxPrP@c`^@HC1VAK$>s$mt)X`K1 zNv5JeCEWlkO@|BtLT>m`8;XW4qTzX|P8$7_4w*K?4w-1Vj;u$>7)6Wm?}}1;+8aGP zviR=WbYvL_8;SGzGdj$Bc6`F;aioytN<}eJt~KZsV@FJuz>8C)Ppp}zNs;r-nHMb5 z6?TgXc5$ROTH3JnWwa4|L8oP&Y6sNdaN`5dch%%ZwJ$}Y7pv_$=*=;>!3)*WTNFS` zq5xVF1<;ZxfR-ep+Ib-5(14;5xsSP2_L!xY1E(k`W|v2vBHO`|!6<50)t}J{;bWYn zKVvmZ^+n{bP9+?K5<2eVo`LwJe|rI)Vnd?VtF7v|AOF?WgEeCc)K^#IbB~N5J7j~M zcXr32k}YE@4aY851a*$dqpYb9$HO+C=4#wYL=W%!`GE_&vS~n-q9$H5L}$&4Fm0Dh zv@t{%vKeP^lJQfyc?xxxO1(p;P^%)$nt^;E#T~_e0McuFg!S?JdCNKifAHi64Sx|`j-qMIeW%-_1tzZq zPR_T77A7!~{f0j@TX!i6Sgd|?CfO>Vw6A#0HyOgGnZVcb{ybha>>ebyoKNzs(cU4{ zLmOHt{B;{zfXlA) zQL?JQM9c9Zl7?TF5dWgRVtg~9%NjBanPJS2j_M5ZUyCy!OzVd}TLbYuKq8;ch}&WL4yVN!Cgae z_rW1Za6%w>kT>w%_x}5;?oIxxuEuJHUVE**dY|q-XB;wStxF~#lu_TDF-#FZLkZFN zs|ke5xPY#kqS1J9&E`_6@u#&k0Lo*HsM&yy0(6k?VvMbCK_zsm0WM4;6Iy8}WkyQ^ zmE%T#0g`;7d=fq)$iZoD@n4p8<+Re4iqxfQ({x;-)|B^b9^;}ON3g%uJI8t^3L${1b)i?8bpdNkrN(eq@^4r9SZnBZQPCHJ%u1jjO!Pg$mL~!EngHgA&RMd_|@$ z<63mj8`x<5Z~)p=M(Ugb+A+rdEG@W*IY!G_9HJ~rDC8>qB=vH?a?9-(vJ4i~bHU?F zEZuvwMGq5KmG@}KDD4n!dhvn3n9%z}NfH5?=Ab@&es`D&y+`ABhnY~>dnAmBf%j-S z?qQeBmC)5L;~lPJ{19E_-(12)TwSSq8x&A$Es*O8@&Z28)6>Iwp^cTIwDlN^y`kny zr5WoNKOhQ#eUMU5s|HOlA;?S7`Ll;Nz!(Z>JN za%7U=t%k{8vuTdf)pJY{bV+wsFU|S_#B-DJkWX*VAM&ZPCN!)91#}A$4AHlXU2}dD zfMC(mB2}q0IMkhr1{y&mV^{Ih*|$8Nu)GMVW3c;BCz*`V_=LMmUY{`bL*?5lAE7`@ zZe`)3?~-JW#MpL$u&CIcVSeB%yJ{0^hAS%M>X?^O8B_$BH~UP_YkY<_F7`<{fx8Gz zUORNeexqJNk=ES~u9F;!ee=}=2zq-f9Y5p&+z0(uMw)=#YsC)sjl8iLIlRGC8=Oj= zx~2>}n@U~%otyTVzU++i-k(ev2IRi~Ag?Rca#!^Ih%|+aP*u~PHV)80+n%4Q>i4KY_r(b(^t9Xnwi z46L`G<^7y-8U0XpsKxg8v1UKzHOE4n?CQq_$?m;++A)|1;WDr`O3Xg8alpZp}OqwKbw3@4I ztM8S(zmSY<)Y<`@ZK*NX;uVq+hfn60IK-Sn{@X6;SI*(?V0ft3?CsFnEt1@caHLs^A zqp*~g`S_>23uE=-jL|0?N@3Uq*GL8^?OH-=5Sa@7{SUJ#1T=6`srtWvq$zrcEc|#D z*!kxvQrojlx#2_jkEA!9w$EYfqHRVE@cgJZ;0WuE=ktY`xm&3tI^3`RNDtT5h4kI`3;czQVq zPWA3qPmVr$SCP(u8)LLHGxiDv7@~h`QkAE!QDI))V~F^o?dwn%MmugR$hQcXsNXht zH+wp&V~ZtUvDKbEQ<`XG*^wTWv;QZ-eV-*tJXdtKyoZqX0IiUuKtQ^o1Q-MONDO% zcn7&+mq>>6E&!EIiC zmg(ip7*GZnY%rG3?BTLrvF7nRNbal^{UvUQ>4w-$$<5v;zo3i`lPvA_^Q7$Urewhk>yE^Z)`b z?h!;9-2;fhs0R>WvqumGBWnKwK`7L`P;wf6z4M~I`iA~<-Lz?L>rY17u@AZUzGpS& zfk|tc!ag*XuY3iQg*RR?bv*rg{p1(t@jj83tbiJ1u%g_fEOeART)*QSDz?~Sg-m2wU>eu2ou;$VJwqFm#DXs(;7UQ_aN+bPeR%M?Dxw8qCU;gZDbu5C>iW3fzy#s`W&?S8 zB5Dj>75LpYQg`81TTe$MFun@XYo3%H_Gycre5j}YDq0Cw4?gUO5LcE0bCDYW&b0NH zvTSWyp4E2+1zqJQGT%{tK0ix5lO|VFPf3fqu{3WVb`jaF~2Y2j?V12kn}BtyK1FIEV{y zl63H2Hw{Cm3b{*uMY+muy@7h*?wV4CyJW(St^jm{B4UK)e@I*(Rfx9e)#E}pO*Mb{%^)q6h&G#A0z8j_1}>|CP@!|2eu14^DP~e*L*r6( zIm=t&|1BJVQ;Imh@+T_>Z$_6O7B*Yi2dW3btPAEoStOa#SQmmXGkQb4Kk7??1y_$- zS|Wrtr0m~JP&+C^0N|@Bw>mSxkX5wBpxNoN8HJd~QTw4H$Odu7YY+ zD;6HCCJ{8ys0dc!)MA~j*0lPp$3haEN=5Yf5HykH@C>Lz<*}9PlVOuc<-uwXP3`1- z1@4X>JyDybn%4<5JBp@&W>vNQ$+4&hh-R|n&$cF2-4}dx^6)-Vq5GMK(t^7ce&3AMcBk5n3* z^K0Q$RShjWoI=Hsr+naptDKc(^;1#7z@Xw1GZ`y+@Gx0+DVHqxuHiH(#M%6<=D9 ztzRCG(bqKoSM;m%1ZKDZ=SkG_UdCZA0PCYatug>kBwYZiddZwU&3UieqNu7^2GA9$ z!ZW@~6dvp8!Zv43#>|g@jOJIYV-m}$%d4n>V8RFMJ_uhpjMj!~0J?2I@q>C`C3daH zUkrTy%o|Ls{h*p)X{cxtLOyyiEb1J96Z4<;$ns!cj-aeO7y#tV1a?5CrJ0hs4mDtf zFS*X_jeIbbLwwfb$Z_!=Mm{6)*OAXisOsr)_Uz?6j=Z`5VdVM8Fx5QA*nn*##Zaj> zN3_)Fxoxkk(TF~b-&FZw{CpzUKR%XegUbk5J-LHTZ~*KvcCGPcyli*;0}OWFjr6GeC*s>wWT}Koxnl*r0Ve@bRQ_5up0=BYGBTLnJnFz8oxpMSEm% zN@^frs-v+%*q(pEJ8+88r$+^0QFz%!Rf>oGRYBqwC9)q1v|c|dC<%Ff&0+7G*AQ%7 z`G4S`%fwR|qeuK0SzR8jKvY#H#lh@YG{(xW*V{mi6)8M((Fg}75sib5iS`AiXSXieJ(z#(V!s+cx4~Y0<$U4 zjyP2KX7OyAfpsah$=Jo7=P@cY0|%kFfD_kvmuDJaDhPp`Dg|H(ol?<79^BT$cfNxE zz6yQuPs=FU;8x|TQ8m1Mxhkzf*j_V$2?{$E2rz;)?H~izg-#w7_dt;)?bVMEAC8ng z$TeSH8+h2Ox-Z~(Z5f=`k>Ner+jj^JImuauVQYGW2K!?PC13&NC*Wk%lPWH+WE5b& z9iNA@Jv~%+khsE%Gn=gxpVv|2&4VEi?s;wj$bVugTq_OcW-Y_61XEd#7^c1e81=|! z?xj+BHGHkP=tX9TD@PWb3>Mg;+s!%l7ugdTdD$@2-6ppHL;@`;;mvG{gmfB!aamcWFi9a5~|x8 z^OBNp2;HyIk0=jD-BsznSlXD7o(>L9E)EFv|N7NXljsqbdg|!M`s)Y&-t*R~Paczl zr9)0FpJoZP4AfLcM&LjrhI=oZj0hAm?^Aib+;nQVhmnWu{|xEP_Hy)~ea^CO2uBZl zI?N4tt5EyU6^Fx3d2-@EVe2?VT*_<-XoiVFcqr>W$l){fSX#$rOmjJ{g>^_yDzn3% zUicpT^1xpY%+9>PWh8@<^UKG~N7#>k0hK@Bjk8OJ>p?{v!~>M<4;i zmV+LWT9sXYE_QkC)GD0{QCxpi8p2Y=NP+ln^nniq{s$zCuHxR*PMP%cYx2I7bx}xe zO0`o9TinH!+oB(nJ%$|bD+^nzaV59$Jco@hS(l2jLPYmV4PFLjSNW#8&%AmtZeqt!SLQ!rCl zlF;bZWZ(Y8N4g^QR%O=29w|`(l3^0xY&NP!2tPbuz7?=+(xZ>z1P#nUbjpP60CXlj zhl@d;d%bmE(#7`EzoaWoPc5ju-BI6?3#}ghv=E|(mo@#S&|q$gM2w@*U_QR~1uRsD z1K4UDw8`hw9>7mi^Wzp#g8stQS5l4CalGG?1%T~L>Abz?dWiN*i)`@?+70;NXu6o{_aNk=V zgK(tKg;(shc13e@s>QT8U1TdpV?SGWHE?zM_}$V)x*O#qtlg=F2F?dq$u>=FhX^Wd zVGrcg{XVyW{#Dd;>gtVKE}%`!-5a!-EHhiBDJvk z6ROa69v-^eSXuTsVi~?@O5^O)yLeBjA@4HGOZ@jx%ccj^MasB>iW#TF)kQq+Kzj#} zXVu)p_@(}TW=CZ^y2Ss7^Q&#bG zbaeH_s}#!${1Jp z*D*=!Z>-$=D$-E)hw*d{r?T()&VfiICC#b_Rx48kOmtMSHJd3j$9YYW3D*ldFh_ua zG7$$Cp6(yLr^5$Ob$CV0?GZjTpIC6#lY1O$=}!#wk}vgSbGRW=3}$mQASM zfdbGnOz@gFi%Q3x5i%x-@(x#XoF<7j`G*}&5gpn=Nw!+ern@ouUP&5E5N%Jx-H-XS zNtxOUm9;KlsqKJP(LyMZGhv%(oin$yq+MKx?l?iRvrJqLM{`h~yQ1^xTo7)tu!V!K zGa>3bD%GB~Sv+SCL0y5K)*ikcpUE`LV zs56tx{RC)Yca9Xa%)6(V;T8m7Vjsu5^IcYhHg`YIyTXg@u9Df$9i9$1>-%`Q`8tXv z-p6)+cZ(JGSLdhRH}?iO8YI#8YB#Odu@6oi?4|H)BICcBf-+F3gJq4#~P!RvGUk z7V|gqY|g*j%7!#6>~;7B+&S?3orZ_TcW7=`aCof!<>I_E!`U|+n>Wz0p;qp00~Cp_~`;!Do9VTa|(h>Rejd z?iE^XpLYaO{bCn*HK@n&o19NG6sxIUQxpow`g}}JPvJc+Xqz%z;BfgqZ!YKMSgKXN z$yA3g%gn2jI4L+xJFh_iNC4MBL+`{6gadr1fQFQ`Y3Dq944irt<`0-C3y-jl;}6t! zG17me<`X5^YBwA2X6C<=1tpPcd7A8o=bIKe87=TN zj6P?p*|tDykUJbbVR|<@sthbl;rV|+JWL;f=no7O2rl(}wZ^D%EelyCd=h zyS{h_iACqtK`Glb*#+mr(mFVOqPFmGbvQbh1+#xwc0&mBFIWaVU{F4t9b`z3=`$}! zr%%*uv*J1SB1~iDZAKLc(yzp)a}>0h`WE17H1~+r4XZRXqP_$y{D=ax#W}4TGQT}c z#1V9?cd;dL98EnB*&Z2yB{!Lq5kptnxx&U35K=Bs5oM{k$CRY$7~_|$wb%bC4W_S{ z^d`#+@fo)5D9ehvFOmvx4;`k}Et=nrS}aVR+YRj6czjGR=lp@)2|LEw{Kv#TImpl+ zThTr}n3>GzCt&s4|4+mB9EYAl+Q~Ta>pGt8Q&f|Qv%>0PS^W19Jb~7qd(C=!_G3mH*$nF1E zjwjXZ$;^cIn?s69MFp>-#Qz)m&2;udwBxBw>!)q3;(}9|0+GW`P=OT>$NJMmI7h^X z*egmJFT}$>eNje1C>zDiVRKmCE6nksr!E0I_14ZlWH8xekFsX=?hD=x3O(4gz}v>m z3Z6>r^?A*+%q7dsv|R1nHz_E~m;_}KtUT?X#Fianve8=L8;JiUlG(MT z;>|T5Gho?_l46vO1H(vw&1a6I?&nFx=5`*Q&bR_FD~g};Jf|`yH(#v@b$`7*?Vu-i z!^vwd=tV8@b_cgliEzJ=5;bjG7yGHpZ(sfRp1`L@1Jitpvdg!HJv9~FC5?n%`?)o zJBHv541^b>+RgK$B*7+w%&6XK+6s~(M&9}A&=wxYtt3HlURd9Tr9QxGJU@kKRX=AL zU2PjSH2F`q&TpKq!mOq*eRLe}e^}#CcZpC;fXqBdl$tEo1@z|;aD^+f|#9jsE0tC^< ziu(L8m#H?!c+d*TqgF`%(MnYz+B7(x#0!!E9T|8GdLL=wJ&SX=w1VF=t=faX7eD_V za_7g8k3WWd=P~5i85}e@rdF?k`otLs*qG0L@6@gk4d9Q@b7N9Glx?qJW!nTV=rsd9 zyE8206X8v$cCYzRXkM#ol1BH6Q$2*7Z(jUE3y<>_&1-R9Sf7KXKEZ4JdJ@rUVt^(G zszAgCnx6B4&zKPJ-t9oqdz~|t7Pbzv_oF{fRTCcMcoUyoFf%0Zl$n>&GA1N8S@E1D z@jk*o=i4xoJ<4|%b|xKb3{%Q%42!8crD+U%IVVxLl;;in7)6@#(u?J_&pX{LDcfY6 zj8_?AH&lG`BHKjD;nL#-2Cx#2hNCrdhp914PS1mr5bxs>LlPsO?5l2-$We`aXN($_ zVs%NZ{GGD1fRu?*B3JRyLymtgK*hEj zpMS0JyZe4oq0e+z+ilY4cMo^Je=3Yii+6tC#&dn_=XVc#5{&EB?si8ECTq;y>iXuG z@ZE0V{r!)rBVpfb1kJXa*zb&n2YtD#?ViV;!=-O?YAh&A@>{Yw7Q$}62aZ}$g2^S! z1%As$T!?Q+Mep#`VUidh%2#4iRK_ZRD8W%rGkl0J*Efo4@^-SFMkP6^aNJMF=W8$r zYWh2#k`PT0m~pg5?=a0hM8uGQ=piDS&ehS#ZVo%cHsWE`xuY5cr&J@7YJpEC(fR5E z)`!qM$Bx+DQEhI;aO=WCJN4_Kx=)D+8}njix47D_5;pl2;LBL`#2YZTTg-Mt@^zAa zXf>N#_DrVcBPEe)dm8P2%14vcq4oGe+Hd1*yDS;m*tjFlyb@mNe5>PkJLkU6W^zO& ziA)rmpQwT{=Utfbt0#v4aQe%eH;E+DwOS3%6Zf_mobX#eqeXkbI5TUQ*Woo3Hc6VX zb@J7;c?GCW{D-xvhc)~F!rqP+b>!GE)4~kBdnSw8N%Xyr@U{-kvP;+EWy`+0(mU#| z4s^in1?#x5ZL9QS-TH3(i05B*>-CXr^VH~trm!wVSm=VgYSMo^UtH)J;exTHHJ@3P z+x2>X!FPD=3wy-~*^tlPG_sQ=-<2x+5~KpmN$MoI)_SfSQQdK6q^YwJiB3;O1;Cmf$m5e@BhNSe`Mn==Z1@WUJo zqxuo(IiItjRNx73bKRJ!bkAEY_6czD`ThcgdFc0-WC~?Rs=m+A`MtVs>RdIwP7=yK z(YszjrlTh?ca+h+<6Gtn-e^l0wPA2?znS{oGf?>wrR9Z@SCO-3=dbVO#w2J5Q7(Cn zF)o`O9@04;1+K5071iBdm01ZvC%RRQNiOQ2x!h_Fw|?u^Dl|(W+3)VZD-S$$8E7LR z8^yT$%53rEQj%lrR@;jFkU{IS{Jp*aLuDec4_@QIz^IR};O;kGca_3ruA+c0{{DxO zwAS$$mtmK!hSP2>a}I9ke7DEpiQ*FCeIU_lO4yYmJTntS?0(1%Tm82&iH8a|lz^<9 zAKLkf!#D$Xf@D96VppqBAP#-S3U<^(g!w9!uo7`p20%)&<>UPOu?lxo2pHzqE%x#wF)?*ubEdZ$glQt(llI z#^pvi`2G?NaK|n*;&*@5peVfi4e^l6dKY*->WbdJNZhVN-lH|fIp2*j;z(<%4p_Xd zquJ@w%$)9Y8=eeiEl&xsi`@C@h6-3CGAQ~b=Clj4`cT1^)02u)gw2?GYpg6Dbo79A zt>y5`>_Iul*9It>@W6STz??D&hg*1X8aj+)MHSo9_Lfy^tI?Gr6q6|6s_5mCb@D!`cSGy1&8$g~6H zmFxhHDk;tA{_QKo68u<==*-mJDZz5xy|8cF-d!yBU(mlc8j+88+`_!?mxY5>Z{}fY z(^dOGbc=PWcWe%iIj2^gOu=Oj6CH&j15voZ#sc}xNh zyw+X=!~eo3+?9yNx)X?6zcnhR5!gx@mrFfrVBk;eLxM#q60@y;JJq((&kCjE$?%VNh0!N;SN8UAG}rWd4hr? zy=VGmaGTgLjB(NLV;I=RH3Xb~6yO*Y(6EzpZ|lm(!_6PStI^PUia>8|oL!C3`xgpP z;}pNX*%Y&w{W>$w&7z|Q=UB(KcsgNL_=qd(0T*Aw-*KUTciLBi;gW25#5MJZYx(s9 zu9kJ_-FA_c(Psph^l=SvanZSDr?%pX^2(P1d3iDR9|YKBKR#`u+8a|HhVv*2y^Dyu zwq?h1!c3ppMY~*mZY0jwfj)!Gl<1eyN{8rhZ5H%*ZII)Ia2DvsRK!!D+7wj zwsnE2?;ZJ+h4+^CAFFc#3PR!YFurh7&cEful`rBYwR991FHr@$on%f9Sm~8;A15>*ilQ#?pN9 zmxEU#$cCylF40%AxYOvs<*azMem4 z?u>V(L1m?i3z7(1di6;w-_rCh8HPdLr6m1d-A*c1S2xzp+Jx=@TvUV}1(Z!~L;2d= z3DErO+@&rhk+M44za;B2jlLkf*#C(7`|HIBvG?lcPan8E{4||_t~C0~Bz}5t*#+cP zZtS0lv@SnMYMj?18O^>ezHa_WBBpZLi?{dXVt95M*8=9`Wy>*N#v z6n6JZDBl)8?wizQ{I>QQii@$2%~7evS;!R;=q=I%W%o%H`j{ z_bCyM%>La$ew{UO8L;YugOwuPKCpTqFP|Z_9}AFpz!O~cGW+E@8(g+$1RcQ~(JlbT zIDygU{t(9-#!fr6&4;7K=a+-=e3voW%|Clyas0Hw)VqwKp!eQDarx%;Uc}pwy(7ZC3^DLe zW-jUEuCeQg;5V>9s-|2W5F_`A)sg)D_Rlp9@1;KR4o*K?#X&APt2Yz~|hBrO; zy`!b%+v8JWT9jmj$=Vw(xb0RhCUhdYP=C@rquHt~$4VZ(t>^c4n4YX_*R8c4oE1p> zQm_9xOCzTx>+Jh;GmwZsQ-=srC0@IN2@=P;$iRz`~s%IrJAm z9z~@6)jn%Xi;?c5+RQ6xCCAqdch~GW(S>Kyau_8m<_*6WRxe7=Mr_DR@_9sDaAI*$ zj9Hl-=+zcU+Ig&Yfr>0ZMD<_R&t^P*o~eibcsG+ws|0!awB+U)uNvMP@B$w}R`VN4 z6$2?!(=Z~NyhD98q2U?mMWG5rSToHVqnJb!PkUMkp~m=E*SKnP@mK=W= zaKoBnifY_MPxJwiz&47$@VVZ4}U@y9-UIkqG%MB((g|I4qtm(RHvUDDjDG9x_rJ7 zyewBq11y_XiJ3awo*8B~ZYbpPvz&&rzY~i7(TF=^nA!C38wLKn;Hy0T(Ti`U&V7Hm z)C;`|SaQG{C20uz@h~|J=kmi$+>mtH0c*;k53sx4b(1!fcC>oNrXK6KA*!1tMI{D?qg%t1ZvSUkyNp`eaajlkk;y;rUNYQ&l z^O0U_M6aEPonFTem(94;M?3%|`*B=-qs1NV>2m`e@h8^juSvSU&YP8*iMTQA_gBj@iuIy<`O#26%2^yYaxZDsT6a9#c$?J0OYzAJ1RVq zRQPWx0=lkHT%=KD(;&qkyL%^bK`dVsiEYkfaM&v69XqmMha?K0f16x$r-Q)c?-D(8joh9MPzR)#^UAILe!PLp4iwqT)z%pB`;XV=qF&@1 z3&9-a%sCDa+#}=#3*BF{c;k{Asokdq0d0!gPNIy9O=Qt&NHO=@JB5mVS69i3!na<# z(zP3{{a->IAeIO47BKg&rM7{$X+LVEX&@R)3*8T_KV-VU^?$leR?dsSqBm}qHnxal z#X9|zxy-7*KysY06j;{e&*e}u&#xj5$80AS>oxnzJ(Wt2IfO?~2X8Orb5R*C$NO)# z7`1gC43|REUand4W!A^Ui>0m^2+SiBRwalF0I}2~y&((fjnFnIBcYewf8RJlIt)Oy z#2byny#FtzC)#)s*$B!-lMO6NBXzl#;+1!io9Iv$DdZQ`2KuORAAW6~Q}xC#V~@{Y#u0ZHAEE)F1WQ5 z*E(KmaEEzU!x!a^;TIS;m9w6~2#}>5Km)PMe_lHbIv3fhK`|GK^ulQ??%@x7n>u!L zhEO})Qk8QBcBLeHNMxIW*rB{Rf6mTSBp~n8+{#j*S}W% zexGU{xMmG_i1VB6212dtX9ylbn41YZq9r;&liLXli}l{8x% zUQ!VjStR>GgSXS75aagvG`=F2_@26AIM~!{u?s(jF_}qXfgK4HC_jK{Q&e`}kxLy8 z!eKW#9l#j9O@8wQ!wYgd5vT#y8V5V~;jR3qWoZix6V4WU$(qKC@idqXTI5c^F1bXA zqRp_T=0C{E2;cwK+HEmKw|`bk%WDz(Ny?aW$^=^#>AS*UKKLz6fw4VViL^b`UGuD- zT~FCt2~2z%KJhNpk7(f4x&$#lv+>SGw|LL_4{;-p#7zv}Rng@HxR$9iTx3C9hTR-t zeS8nsxYg~ci0rnHuLX1c$OMgR?XODsJBHfR6Vt==_7KYwM4&kXih)S`MH?fj_}G{y z1W#*pkc7z`(7b_i^dI&DV`_M!kz2gUzR8V)8=D7lC)A;XZsInziNWx}bpd@xoJBRA zDY!?ni|m*@qKlfmHle#x8?20+Z+^wXo}qi#A$0q}r*W^cb_rmqGby=H50EH;2o&cY zrsT`&)QCa91e)a3OE_EVxQ)GDfR%#dxaAx=s+2a-`%F+>!?ep$P6q8~8tLYQPfk=2 z6&D}sTB$`Kx3+FB1gaQXU*H4%v>@IxeEs#<13yT=2g=eNokmw{@~SDDNMb8wy)p9L zN%!m-R?xC|i+pX1c#C4KdJY8pkYa)q`;dMj6Wb==C?E#ipB~%fwb4JDNr5xeQbo|B9E^}jY9*&}nz9UoSPokAhMQnkE zsMf;M3KmcrD#Dnm1WvP^Gz*b8Jx@FH{!7z9K^BU8kG8$U125GFWL(AUoT$ddib9U* zsD1OoH6*363Pxb$H+B!6fNu^PCBowuEOOc`(W(&gufy8xfiTPLgk6sO)NXEyrr91? zt}fNE8-41Q{>jM#Qx86tf<6#d^S(sA_yj4&?CkY{O$tvG)6MH&(B)9LmtinmAeTR= z6V}7j2@kq;#?*~AM0^-*ILV=a_x6)O4xM?A8!!}10N-NUjhxAV7??jtk-|xy!Wk6^ zfcsN};J)-GPa{C*bwG|0s?lht49uNiqM}2NQQ$z^vt}*m`Te?4j!}W!eW^VHGiqQs z-y!{#c*?w-q&CojWLvNI$8=hm)6s!LD?mZ`G?E%b5h`p<=A6iHY*Z5Vu(S)T z+U$Z(hZ$~&!R*AJR)I5GMzXUfvfwEvW|eiM7$=QhzduihQQ5;1hhBfy*_4ERT{HoF zJR&^pR^6{Rj7ae2G_}7jqaoBB$gV7$l9h}xzd5HBc3v_iH-;lm`Wybal|E=QA*9QO zIB-MT8saSlFQo&NR(eV7V@XJbj1D<$d!%mmfx429m{A0y`D}%WD>el@1fAa%BEEs& zzP>av!gUL((w$+@}fr z&T^g~`7JPP}^qk!`KMPRO=e9-h;OdvJ> zO$G0?iDKDvWXjiPMQHpE%maC57wbmoL(3)eS$Q#3l4`3(1sDffx|vl+Szi+NP@_X@ zYe*y5Xuh*`XodD`aTzh%P_bXl$WbFc;p<9WN_ZFb(WuPu#ZOgiNb{AMt!>VXGVUA= zt&Hxf-1~*HHFoX!FW)!I>QU|_lQWuJJ6Cr&Kdn_e6|yDkIV@#mpUd@`Hg!9E;-QbADe~`*_=x^P_c_@%D-+O~S~S(q2bLW1 zpPwfOl|qa`X{U7qa9%92;n%t=oeR)+*DLkUorv1BLWi^rU|=@c7Z-ulh|fIzbeiac z@mXlm8>o4gtXzJL2qc3@OanrOfQrk<>@7=j{Nxw9;nT_n8A?^cai z_-S>QTC?>J8<~=MSmF`?(sY>ZuS7<<(>*pCiN}l{k$A2?AhGa$M8XV1l6sHEZx~J1 zO_SbBg0y6mf8Q60`-Ak}UB=qiROvSv6e)^7P&IylmafxfJE<+^fS*P3`Kq7L5WM;T$&5 zsN?~<&|^oV$d+#v9`nW4csE>%@t=;Xoq8Wx+J9t;{p%WtG;IS5O}BvOzmoMx6Z_yA z4{_gjcR3x#)sI6H40u>LEK(Kei1f)~8&8w(xmuQtpsb-`-lWDURMdUMIfab}f==M( zGsn)I1dsyRoRh}_H@7ZF-*=L9Cu(`2SW#9e0V@WhvRr<&F3qp>;%*UK-nGwEI=WEs=ikxS#!r7<9BOmEy_xx_YbHC#mSTc;$`+tC>|-Oh{D z5t}Y0Ngkj=VyQ`HnfPKF0hbK;FAahVdytm_$>@-SZVYW>-3dt(afS{Hrt8gS>}*p74|s_&xoOwk2J;ML#j0Vy7AWI974u^q`6Hy%{r$C zhP6btdY57=7#<~j`sMRqe_#&1_lPL2{W!E)$B~Gyv^(tTsQQ9USK+{Qs6I)eap`!G zVw|;=?#S=z`nTO>F>$gvv0K3iAxk_OhOXJv@__8!kL2|4t|#D*-yaWIPMNo=Yrglu zfhupJiD5TU#v#6`xnh}kVip0H0{AZtventjlYn6-wcyO8Kpj;o(k z(w)RKd@CE%X~&;qeeeuWiA>jOPl_@8NEla)QW&XONl)Yh=F?_h3PklhA6E4h@G%rN z%yixSwEU&naHTU|b8-{T%(H6L-$Sd`h`|P)WBvqY9q@bxnQ92Z_-|s*-aTFGGU!Wf zu$EQ*@QuVy|2Zez7O#^&s0MAgOwVeuSL)u+`)vK9Dk!}*55q4TNgChhva}5%Z*ti# zVTi65yW|11l^QNXLsE^_nD{qN;RnTV-42Wmc)|#!cngkQCqUOzs^z^ z))8M#l^6}@yxM3AtDLacv=i@v(>!Y{Rsz|eN+&mwzd?9vH*REuxoocqKs7&D&4~z_TM5xcF`JY8NSIaLdbE$O7_l`KU}bhvHQUbcF&$g~rvIRy4!MpQ}$l7aFdPwqswL z^M2f4!#IX0*VAGq_LeJA4Ak!VJ_;=tx>6F1#UBhEn0evJn>!=ujs#J|6e-o7USpt% zQ;f1ZQ!myUPc4)A!i);!*SUV(9|hzu#gvJQ0&Z)(md2ibOEV06RDuQb2=9lUpkSQ_ zwp{3`3~*S7Kb@d1!lg7621~I31`F+ffeD8D0oEJC2Uzpj7StDu?}psO8JkwA0>nTT zl_@V@`T;ypf$8KuUfC{2@1OArG0Wg{X3gNQ^cIlbQjH>p_A4%ue;--jmw0vWF>O`z0FuX zg#?AJlUu0w$zDZCAl3&b9ffJIR|1~30&k;U9rB8lYKgx9dU%M^ub@D%Wl_eDEwwwd zoU`ib4YcdgGHLq<(I?769cxJ)H$f(-`Ulfi6 zX=i}lA{?Lpv@uu|WUl=r5XPG9vj@7&li@Dk(pW@qKL^R4`A6xL8cq1S5^-3K*jDD{ z>o`-7?|CBS&b;cIGWXXwF@a^&|Drvlm-R~|(b80n7r=p_`p5Jl<$OplQqJdlhpUW_ zME%lt_Fiamg9&gu>zx_~q`AZ9fhfBf{$9k|^S8UqRjL*lOPQMg4oIDi=BVuDOCoKb z8GqYaka7E zyz46B(tlnXfmFgx@hxJ*gF}RIzQkW+@_*4vVTPy>5|pLxLyG`0q13Usim{+3`b1^_ z(8K<(rGfqQmU>IH zD9DqVzcd-usc&Cel##bH-xxYdHzFm!tp(CxiFXqUgScGiGjZ$E`4+U(3OH_YS$N#_{H75 zf6J%>hTct*+K5l3?N(Xl9(oW?22Klzy0j=FB*Vt(xY8#0%Ti_&B$~ia#PWvDifDWq z{e6~pSCqNoKuys?;xH0J75-V)Zp20{To$05S|pzH?`_J8G<8Uz;S$-yUPY6 z_}dz)OdF3u6<-~aEr6@Zh->k-UZ``&sE8YxWzM(+S!7DBCnXY=Legp z$3<#1C=duNpxpg|CIWm7LpC5|wA3=ab>!Cs5}XzxTl8Yuz(^TQ-@<_tF4oo1b)JoD zG3JJ$n>xmM!Dg)%`SLc|+TY?j)C+tQq*#Y+6PZ|tyc2K3>(7AxTiL{FvfEjF&-J&t zc{sk;NT#xN>d1e~0&J%Z=rwyS$Xw}9r!S1-E+@Iwko4sCgu5x9omVl_hXicEZfM({ zo1bs5*W(?R*_mH%)W|7B%$U-FLg5Ee?~U9i@%oW6Y2T<_@ile&@r$Xur2)H(a~YO% zalbeJ5T4J%&39e%yJd~-Un8~gu(AU!VCBo+yWH!W$k?bumI=T~qyhDFA)o7#@xjnH z95+#jU3NP6R$Yp#1Us_vtT7yo*H$8;XsrUt2Z~*Ks91yvs zQHl{7l{~7d0tyug?hV;GH@{rlR$f0gUqM;Y(c7D-=OUAiaIz}I;k(SrN1P=sXb_Wm zjC_vF;%QEVnsI==yi0v139{*-l*81#$_iWlU?OgQTbtQ;p?JECCDVEuX{9}btRR&V z>?}_FB2WII*X22!iyFA!BPP4Wf>k0XW5TT(Lq#q7B-C?o@||=B>Rrv1fWTU*Vpqzb zNkTJa8L~qV5(nKYH^uGbR^4n|e0FKeCZYszI5HhIT9C@5zslqr*mwW!hdQ9hZsnJI zaysVGr`lGY?+}agVJ5G_E)94VtKujPP;=YXqF=?xpCYB7pPRXj>Ji=$DRu*#xkkc3 z9Z1$HTGJn8PanP1F+wW(Isex2GazBKDSvRQ`nk+4inEf8%d-T}E;Tm}t#0*%q-!if5k5gd*G`iCQ|mppzMRiO}dXnw*EtF8&Bi z9FUO1Y2pz}sdVm^rf_)5ce*@`Q|C{x)7_HeNz|HzbBN>%*!KJ8mZAJ!b@rNvBtgMu zn_-OYa92|Y_Rys_asT3MnkcXNcLR*G+MBT_L+i+;M~eBl`6Thv_838vF|sA%^fKGl zDv;$*%9b{fi1`chs4_nB%&Pf)*`^yvzO7iQ`RgmY+0(CBcQ0AnmSD)<{RI{b_dm#P z9*`lzkUgoJJ|U6HH}MCrp?4~o9)bR&RPEy}scpuUr=5r0l$XM=L92%Ob0m~Cczc}TWy8~!l zEe#y$5LYgnoOopP_cT=@-hIUW-Q!I@XS@2q`9LCW8$tjzx4vnAalgqHT9>E{EtsC&Z1T7 zZo8F>{Q}TsiWU4-?ELp^!4ZuSlPAJ(OhY=!ZeN6{)vS~k*hJAT-q0O3X2~SvIFBOE zEM$mUT9%SNat2C~pr1c^$TOFW0Oh@iWas`QlWynif^JltPyTNh9`oy;Ec?&>W15LP zq#5J=t9%oCpw(3j9d%GVRVAHXdtO}*R(|ee9D?xAA>)J4Nz2%&*BrdehCg_ZS!lam z-1a$KDFEA2`Fe%eIU6xP*!qPOo{r_tqlao(R8IMK2z+$;d{1TC)&{1P{ogwY3^1xT z`MMJRE6ZpFA|)*Q&eR^p7}TBVn+Q*WsRF*5&BQw ze^lN-x_r>z&?!uR)prKUu($cg2;V&Tg}x@kTX>I{IE36umG%em$wdx#*ZO;GcekXx zoRui9f&=iyPL{_%pTNw=)-Ry&#L9QFEdY~?{*US`*j;c8=ZNJ`2Gz>xNd83*%_BK8 z|Bypt=|-Ag$DFEM?1~+vvT9M7K1q&qS&Mp*wl?|fM+i{#!L zPR>4ipWV;i-(b;yyfF-c98A5MyH51-1@V7>-CRB)CH*+lLRs5Jh0ECL4Q?x0t33=FgiQeY{al-O{}FT-SC&ab3!P*-|mt z%DynrCB}R;us|{2IYo-S*C<7bqt`LThT3N4op0NPxWv%Jo+;Y6M9X#C6CwKsh7SiX zQjM!C&M0yyUSXuDI`_IT)H7P%NzBXe@S~`v)gh$&SikDS8C#fL6;o_8B#PVTdQQ;jSI}Ix40Vz=f_;wjFdSu zgI%E!>v;;Wh{hL=&)Dypaq=8}a>B&4ZkK6v?I)|X;)DXB=b{FjrzNvXGxyo+m@;aF zzgTWWg7&^_F^v^7uwqQ%iW4)lI<=45bc3$WryiCfPApKC3GAn%H}ZsV`-xv5M`-9w zbR3HoO-kcJUMH=LLjQr1F8P=^lo% zn`xV(df-)4|I_-W?!lN?v01&_p%MJ?6toqP?l(b<3eLMs{YjF0eMqkg zVIw~UeRvXAAE#CnWMWziyMLmgG1TYv#VJw8W*C6D5CJPK!Nv|-!`P|#48EvMrFVV| zrjf_U8rdoEFB?&DP6JL0{Xco7b?y=fc(6)lV0x=HyOBM$Ehl=uPMQCd!mbwO+tjDj zKj1#Edp9OXms-RzJc;HTD_xS~sB*528)s%$n275UI(1B3*)e)XqA}s@DTWv-`jtePl+Nc7+c%(+YPJLfxdOZ@X4xmn~ai42WBa;5fK@;3p0n!*xP*>=CX=FM@ z?fvu`fH+eMf%b&fx&V9AQfgRJy*r6%Bq{zSoUrd3(!QeZ2Y=fw0ZQDD_T$St-LGL9 z$u_0g;A+e%7Kx+7SzBHJ90zthI4XL&i7#Ag_B5@HU=LG|y%lxQ^lGAS+(3l!^a;KkvB*)~>sgJ;suqd6sxNJGAYVdGy{H2ncDWC~9I!Vd<#~ELKgJ~caXm~K*ARVs2h=29o=~B9< z+~)gdueW=QDY>Vp?ltCK)QeDPPBr2gJQO!78M)i--L&NGny7*WA)SO>V`3?_bTUm! z>)v$!_Lzuxo$6aPE{VeuAi%uSuoMINgz~C>SO>G=W`e(1(JVzZh&-xrRj()lJNZEm&#cDmYjy)iPeF69P z;?#*KW;sAm@u#!MH8dLJ-;W=E;!1xkD@fVsV}uhZPAA|H4iIKJ93T_SavZWtd+K24 z%!H$+ch`NPWVGmY5PSzV8jy0$8E?3436B${_ap5v8e$(_JI#fsf)&Zb-^C%C*5MX0)_Z<g(s@R~w}6i*Vl(W{?{nmoQ_Avt}<@-(r;GlrZ`ZLBpVST<}*Y{ungc1w3do0B9^1 zzJV6{91j}sh6Ank<2TUg0nq46EL{Q6LZ9P7qY(KD8gPjRjr<#EM*kBu`fs4oe+RAh z%2&|Hzk){p4YadA295q3X!^f^ruW}K3vC3;&ytr&FE%wlLnFyc+&3lUIVJqMXsqSN zx5lQ!&};|Ou^BVBarbJmh`Lg+*~d<6vyV5R`g3-!q|U(MT`?s2ZM8y{I6C0+i?{JW zj)1w?Msvh^W}<95jk4T0YM(ZJoOYDlxQp4xJ0UJ?i@^KFWA{x-el7{WjngA_r4WHv zsWlPq24)|pfR)_rYJS!?XDgqEnkgRaqkAa>eYq$yZcPpVSHcoEG5=ukNn9_Gs~Bfb z7GBHaqhB5Ix-5=))x~h06Xk8l%89Z!Oy)$n8|rbQoUNb{?j4lR!0{~Ss1U?X%WJD4 zjhKC)6*J~6te*`4sc%zyv22%Xxc!pY0D9+1G07{a{lx(qS)Ji zW-uuuy)U>CSxNb9xw~s@hNs6Y?UW=T`BBJ7G&%+6G_n_)8@3r;_&f?)`Z8(D7^*kv zM2T`LR9pYTx`?u%iqRMF*m&RWHL`Ki?M|F;`b7PO3GNO!pk{W=+yLAnc^9J1z{{n) zs%7ym{>hm+X#-*%2Gc!rWoYE*A(D6xlu)o54tv=mS_OXy3Fwvyd$q4yt-~A>#2V&tc>$JAY(1z{~f~H%Qy%xAtzqf>du2F zYGIDkIo)9JJ?H7g>AICyL8~6=*~9b69;^dWn=!S#yo2+ZVe@H&3QS~h+xeBcsl&|D z4awg0s_y8-l40xPp?bsOw03G|>mx}iz=&Uob=dgW=NYH zkGIeS)+G{3(8_HX39g?`iNG@ z3?^)#(2uXFOe}m+LbrSL4sq+2he|X{#kVb+l{L@w&?G9`w%FVI>q$ECH<{JWjc=^# z(wkwX*tC{!VXb_YVXd>z3uVq~Z)O)_!}vTGR(PMK>8-M`=5MB+MTgnf1|(pOmJLo{ zK=M{MQJsj{GU{JJs&ePkZM7$2r`8vJHVb|9Zng>!`gCJ2mu=PXG|gbBoYKRl2a!Wf z^j!iv zGN8A$fY@3zV}mIQ1>=2sy0jPznilW&w?U*bv>3m>tk;#!MSZ{cQ2;X)u$W&sm}i#Q?`~b*=KPe>EH1b`KCDPo zZB<^Gbox%6ZAx?U#|Lp9cHoy;X44Dh6lm^3CZib%k>KPAw&>U5+EgGJz4m?~lt8A2 zm8*?uEf1YB*z1gHSG;sU{Uf1UErTj><9<)S%%~^*&Yt>FPjrk`Zf4+~jASR!49Kdv(Gb?Hq{U@ZM^GzD!!2>I&>Ez~D&0C$=%dhNwmn)_h&9wJFUF{3=!q~9jbnCRVxC3`xuo=|;5V z#{qAqE}v$NrSy`6qE^yc3;-NVJ&( z8S}n+5A3TZ&u%VhyYUe!Yu8kd-hCasv}a(ZcM>v6O{!44t;CQ%x?zmEw|njQRg*WU zvJRD^Yp5%rJ$znYvi6-Vy;ikC6*PY)tW7?>CHD+ff@(3#3l@8OdwmRbz}eo`hO#)H z5i893IZ#T2hU5B;uEO-#%mYY(D-&-}^))z3oeK~NLFi=l=ieR_8s2nvGxG4r3tq8L zpO{6Ri<{GAJhQKJ##PpQ^}9nPuvPl~=Qql3o@**hx>9l}Wt;DGz&hmn13#CK%>0V&K;P za5<+vd9k+TOFC;!`+#?9lC!X^h~AX=`G7oS)5#`z?NXY4*0aSlER;PVt?K}SFJp7d zu6Fx5xp4<#p7b?ktu(RMv;gguVQlb~&x^}K{W?Z6?H=!3aM*Q_E$E&Y7Bz{wHFDT0 zAqiIPZ|{+2zq(&$WchB$wdO(5YQ}WUk;7VBRUeHL3`4GE0L7J5b81d@eS2W_^`>~Q zZNeEQtI&Hw8W(SLeGpzQjqAa0Bf~sl( zjWs9LCM!iTGblx!u=XJvPLzhNNNJbIQ&Co-^@^=8q)Zber9x$1d4bDkm%;6Qh4Dq} z#_4Y-G@MGrSSV+JeVcB54nJ>XPfr)?!WoS5yu9!gF)b2Wt7nE3*R9vl7ozSy61tK@ zdaCPOHRCJIZx1rQ-kdgv-Yr4Ki5Wjj5+2D2dV-e8><>c$I)&Y{Ikg3I*L&B*sY+#Z zR(B_sQx=e9=~WNPXbt+5kJ#Pip_((b`~vS(i)Xn@x3wR!-q?`zzTLtWCPf$5)DoX< znwU5vue!QtU?m2Y)#A7wu(mSPpYh4NVwqw6T0BXu8LY7`*?;wkX0!cPjEO{u`1Hml zuZfn*)P~IQ4NrHZXQuzmcu)6)gyd?^*@mccuPr*Wp_7G8HIscc&8rbjm5vyA=GZus zAq0&2PDsvv6bn0#+N%pQ_qeqO)2vQ za@n<(Z-0y6*5jt~iWQQ=)Nl%i?_i8&?@^IE_6?LDz?V8JHW}1lx4au5uPX6C6od5Gf>a4hyZi?q+ zvrXO?WaGt;=P1r()7`UlJMn_}$OG9wngo6r9y=zfsXqW! zuFnPa`4yeFPV$uY^^@$g3X%Mhwdm}J>KrGSo!h%3QA?C z{uH_(2moE7?T`N(k8a!}l!u{njr|Y4B;1>oH&#d<;8c?>_=mXu13Z6QbUdc0=Z+=j z=xYBNwtqqU??2$EF8U7DRPf61pa0e$pa_D;bnbodWwQ*rKV8pXR^)dddd#8C(Hx&H zh#Qp^{Q*t>;je$&CUO8;PY;3G7-p(}u+;y#(SE-OxH~v>nCx2(Z`S0^`U9H&<1L9_ zy1dqcL=0RVMpY!eIJZjNo0^rRPnCB(VmYuZ7SRxhk?)qHdZoYy5o#?*vEyKT#?I zXw<|0kD1Aj7xderhZM|M->Q^)Ai*V-cR5 zFFsQAeV#wYs7kS$gwK#WW?LRvLr-&;2#)Lc%BXjdyTFj)~y$v4Br*8zau0F9PFFu z`Pazl9S~|$$mtd`jPz%x;n{f-PL#P}7#GUe5T=Zrs`5@mQGz`vS}EGg7d5H4eNpdiShhCwgrJQQ zY%ah=+8J&1ZK^lx9k1d3d6Im2jqOW%muf&6<<4vt&HDS6iR!CLQbSf(>8c`E1IwNwW&+FN5PgAV@d$LFS1h77 z(CaB;BG4-i(VdBR2ZqI(tpa{0x0eKiiQw48S>!ulFwG*je&ZVDo?Wa;QbxuEN+lw) zX~4ocgPbT&LtajlgCR@}*;%ElhHR=DP(}7v4X7dERnn@+_9|&LWJ6WC?N>iZl_a#~ z|2IkhJC8LGHy{Y-|cgD~#$RNXKHE7CqZ|4+-FP(zW=#lK5BD zLIQpL3+M}t&F>M(JzDhSQUy%6OG&u_R3lqE59 z->RY+@@J!11%2@5Ew34w&n?xpKE9|?-q|Vr7E-V@BB(-_5@iYL_A6sR&g##Tf@Kf^ z71ER_3rLHf7Xxxee~=U{jR>porbJmm2B~HztyPLd2J(FJ=w!B(-U>ATX(0GF5d4O; zXI-2MI6rYG=KOSA&{p2es1UIIr4aEI1C%IR$f}% z34ItT8uKxBWX^$?E^mh}0YRP&2y#}yL@NF>0{n5}RUUz=aOo0+Rlu(T$OYA% ziS?DCW5p8pM#=ZKS0quOJRx*`Wz5J<{cJL@0HUvAfCA+Wq4M)$Mz-rGlcD($-4*2& zC@%=BABGv(tq)`E#c6hSrDi@kbTZyRzR1K+WM;bHmDDHAh@Vb)D@@H38q%E#{^@i` z!W3{~?w_ysK37Q}~!gzK}Cp#>2W73Jh8XNaAj z7b~(>Uxo}VgqRP&yLg!9dj<(&9B`NsRAijna9gVYi1F;5%ywVm$3yzXlor#jO?JuXOG#vH&bi-7 z!}#&L)L_S)-`S}UajjW*GoQo~vd#4c7pjlC1Lm%N{Zv36T)=nNyA&l#@V}-VIrfP| zIX}^0^I(V|y-()OHP9dY)Q^Ldzm$^5>nv!_+P8Xn8@YYGT|GiWplyVOZsOr!+eSv7 zrIuOueejE)59Djv%pjlM3EM{Q)LWZG9h$j_ZG_j}W#(B`N^K*pFtfnfMWsl78wnAe zNv^2X*WmZbRCcRGvtuDHA_xpF--!NuCfta=+J6rV72*L|ltIUrtyPEIG%Njyyp-zF>u|@VY#;g13z)tf`Aah z?!>JC{?Jq=sx%Lquwzya;C_b{wN3}SejoprANubf{!;?}u%6|g+fvs51a19aAwvHF zrkm6}61H>dC5#}(|Mv~qf5p}S#Q5OOS>vqW#UQ54|1bo8b1d>td1e8@$Ac4L1gU}d zzW3%e+hUz3K?_(`Z*MBxk+f~NFG;X@eLz|}jQ&4OR03uG)fK=iR|LxZN}0>RG4pBA z!UVie>KxepZ9j#J43N(b`sKu=D5Cwpo-%L2`-0UrTeg}2!{;W!@F6(nx2w+ph7U}& zpJdC^4N7LtYxfRXF^5ZMhkri+1R?`7BK!5{$0fQOAGhm4LGTO(U}B z-w`&ONW?hqoYiB%>uvwGlVScR&X^N2d2l^O2(bZtPnDbCfgYd#YV}~v^BhM@9jrrA zu6=mpp>U&QTH>nIC5tT*ccxPlTbi{Gpu32z$bzX>apBAVSr!gN2Ao81$JILWveE*I zvPmr_Ng45aZx#OB*-9wj=G3SPkU`T)?Z7&N<$7TjN?Yf;TFu<7vl>6I8 zN}vl69NS(>U{--MP^51=It!532-LpXMoJ*G*TxJhg)b>H3zU>uEJQf~G4$_=9lvOw zXu!MlyJP5KxWXM4I5o5!zZ6MsEn9%R-?RfN!2c!>=dZf>{w3>4*jzwH-wtf9zUD2l zouf-Y+!OdEfnV+bzf>`E^uX%1EwVu}B-R^eY0Gerw`02%_f z+8J*34^RbcCD7fkaYeZ7fFfK$60<+7q50S7axn=LRJOLBNKi1ham-)`WZ*x5s&+)d zl>SAK+o%7yB%C*JD(H6+p%I|c5fCy0YQx##)qSq7HL+psKUaI0V7A~?ae|tS&n3`+ z&LU;fam9yAF+j9(E@kdAB_Pe;aPUBjx^Z_kbhE;!D*%bpER{LF7i&|X26+v8y*Fn5TT&>j16Y}!xy<-yFq)Jyq+ehQq+{yRm=cf$L)ZOhB0uP5&suJ-T%P}UKUccrCo%HtY4(4_a{dz{ zCI0~BaNA+C*@8T56227>iuGApQM>Ms8dCx3#PHvDTd@cF009TkfeuxLcx=$j_xKRR z__pJ3{|2hselWJ*1=X^1Ru7O2M_`x#+kxeO17Xjm<(chZv_}e!bF2R?W#-o!Mg+Tu zVE24K!<`4%J*ezo^~;uRx-WSF_hk#g@YzOLDuSAgKWxznL?Ksy735~yvwP4$P3&c} z-@4V2Sc^P6>3Tw#gy>$8KEcSmw%UDAD;D1ilpSgqXoU51=|%)bfoBwizS#I4sS@ax9b}h4ekOrk61uH# zdvD=doe%6ByVN7FOW=e8_cm%H5QN4z?Go$+lyaZ1t_8xBUm|{@&$$#L`InA=Yy`6W zKTDQCaPO=7^}{X)h=z*4p4_+t1}wlYYYTxaI9<<8GIKRnixyI_G$N?thhd@L9ZUn_ z=Rh>b594l*=i9)sG*f~Y|Leu|e{?X4VEf^+2xf6&ybMShUd1;$-?$7GMl4t8lK=Q{ z+K)>kfRHU0@Xca@M(4OVrDWS*-&puUp5JQ4LGh-O;x<|b5PG`cyP5nOI@?H1A{VjR zfPRS$V%;Jm|GCD!6u7}k(!zX8(hK~$RkarOTd5x|% zpeFrKR`^%$5cbx0cB!|6>=H=pAh63-f|86YDYC6q0NAD1&aq3}F$)5_%-+W79|F7l z&MswkkX;54*yVN^#lOLt-oAnhuuJgHu}i$0h@f2(*d8&H8K(3icOU7UId>no!W!9}E(LC#6HfW96|RKR zh%@+;>9}f#f9u1)q%>lCa}ut5?-ss$uVlL|8BjSJS5yY*{t@V{EP6#TXK32=(x zM;(NL)_s4q)PE)_A740o5MMYu$gFo3=*)tzDzp0g!i7JG4FyyH1vOVXe$yv)U4YOq zXd6QR4^aC3tiqqu?B>?Bor4aEI1C)Q-R+`EWIFdf|`g>!RWI&P+ znmgA(|E^j@==A+fizKvt|JwFF$ptk5v>Ny($eCtcAkeRwM?fPCDwHXt(65XMiP2{z zMT`Ef2p3Qi8?FyjAoloL+xWd^WIk=u!jSwMA^|2GwOTq|SHRB&0*-(LYdW&W?~ zhhMeXf5g^EPsEG?4TDzkjira>pe#W1czk&{Z%DUa83S_m&%3MfAx89JN%&@xxW>{C zfFr*lH_b}_wz>`x|3|FGwmXX8O~CDxY6nW|WNoWd`~Pv%>D$(rwJ`IMa;93t49$Xo z+8wRiGst~Rc)h(-3F;+5z1*(U0MyIDol`Fd3F@U;_qKXE5TwR0>gDRrsh6$<^>Vw6 zqL0uy5Z5;eP%lSzPQ3&&H3{nFwmMr7)JvSJRtr!sTXs&23lP{PfnDA-+kx0XdSZXV zFJZ_}=7oO!6!>#MKyCK_Sx@tK9Ryl%UD275-PiD#cqP$q+OK>J3yPeKNJ$MnfBDW>?PI2loKDsU zmkTN`ye!#Y9me`nyk5pT`i-8BXLq58aHt1OKOe_ltjSyvLi)URU)Dy3^5S{ zaL3J>*VWF!%F*1!#L1Bt|91B588;j2gvYnSdif644sx$ZXnJ$4?m3>}>sxY__05~w zJbPxy!;uc*m^a?5iLv)}0t0fnIpWr02RCa4>c32#wsbO9bnF>LxJm|VUNEVTw+Z#x z(hTDd&OfH2VA%s<){CuC%WFwa<9dzqsEw69XYLg0T9Z%H-RV@jyEWAM776#0>-XsC z-(S&0;%3Unw7m5ZqlY_gnv1zX_R%a+S2eGY+&&wm7pwZ#l93& zfXl^~=EONeLLzhrsxN=6UoMDvWNlf8M#|q$$-BqxE5TfeSchJ|ca7s+Mlgx->YH_G zOpb)hzOsn9WuLtx@>z!R1GEdYw4Tb5tb>{r+^08>o-VE^8Mzuo!t1!{8j&%weo94d z*@Q7H&gGtebVDo&9c3mH3XzEKrQE3QQGmJ2 z%N6L|GKtQ}g7zESQ}0e?I=R|EVD@m9_-5YI)-0`q#E!<@7;YK=`zx$WA1IH8f)9K_ zdF?GJNW`c-kGwH@C4PSC%Y(()=J#fYjV@C4Ubc_FOEM{LepPpW+R6Mguk7y?DFu9B zj9s{R&vo!+9=wMu;B2WJt;eVQ8vMJUV(k~q&^u>T-3&ZsAs@o zQ84!&BvIh5+OX15to(HEhjKij;s0cKX@#+fWX++8mRXOK-VGs#*tgx7>6%s8^@V5d zf&C}hNHMd>7&#Y1v*0MiU85Ex$!IO>qZjOvDQ9$E2hJUER7(u+ z;GidV3*92^zKR-*cTJX#OS1Mxub@R>6|f{-$)3$+sZArS@iIJMZ~%rGn;V-+hK$vZ z`=s@+%1B}svHhi+vjH)7=Vp*TO=zxUucZro4h$Kd8^%ztT;h7WkDJ*o&C=^@dcc!K zstkwfQ&28e#|EK7Q5~dYkNODt zGfiTHiVx{(E_-<-D%JfzgRzuOx1H+DW!*nb4Vf!CGIAXMZ`&Nxrd__rwH$&ZEB>BJ_-;hUog?;IT?YBPehH);; z$mqg0CTnA|bz$!7Bl4r4SB_vjm+m-kjPv@eFDGyLRWU{C<~+uhj>=@-7Hm@w>Z*Jv zJg`zR*B~NO?!9uKOr-?9B2uWAbc+}M$~Fy2d8*$3*}0eo%*YLL&kCId^vWI(-hySz_tqE;@8<>PGjQ7z?zD@?c$Bm?-mp;`g#djm4 zjXUWc=u(vCKVUj8Uw+s(&0WB%NG12!3F9Jl?EX(FTKjAZhMI*FNJ;G}^Lk*?eiE|! z$~OASQu^2G(>&O8^9R-F8|2EWN3jP8cV{35T-nY+WLWA`= zj>9u9Wv5v0Wk_3oH?3U9M^h70T0q>zQy+blgf&;T#yhXO4pC2fu11>8Z$l&eP`_dw zgu=C8NRaOlDFalP-$lweA^RSFpv_%4@Qm@`9fLR0i!Ak`=%~LBWZ?L*4$%M%bnFKM zp@sQTQpWFJWxi*qP`v2B&f!dJa-ohdG5dzud4CKAPqvM(vr;Zc-TMIRaQjcpLj07u z#Nqahb^A^(RDE^FPt@q(@W;(u)x4CSbvc1d}~PPQ+I$mucV zkP&}>cGM#Ca8je7Ln;g3;;kcRh#u07#x@Jn?0#W*`k)*`iuIcz@ALXL();;?KXjfu zPr@c^s5KY4d`Or}3S{CGbRor~eS>ooi`zn4uC!F!~F^Is==l)eLhL(ILw1$E> zDK(R7Xa7ES$FqZ%sgTmbTAIGpyyE=CCoU?}`mgIV&T&z`A-zSzap{Us@l*Bl;tQ!F zygICOniRT%F{zzTILkc!NPg}r5G@e2&eoSq|(GOSStAy`ElhTrm)>V_Ndy8e*J z>LWj}((;;74|=H*j#qvViT7E;)7WB%aofYl-E>f6YC~7>=6i zqjpP*hup@%k-jI-XR}?f8nP&M3Z{>4`yo96B%fvK1riVDst`Z5H4#$59k!@N%? z8Wk6r(5V3wrvocg7wv;aU;92>ZZh7LBYRCK<*72A1qqi}+^*b94LYq3j10Hqh1&M0 z7Ckw0r)ytBGyiFco+9hWP~uurQ)ky*su7@*ED)Ldi1*Z=8)-jlTXP;tqWE-J@P-i) zC7DHPX|-s5JvlQ|Ng213DloS^#gg~?3fuNHE7s@n>s$F0Yd3}MNA%8hmq-xT&TX(K z^4*}__wMZejkVX7GbCoxeT~QEn0yZb!_}#cytjEQa`)P9yY-~1>ovSG6|c%sUc#HppHM?>3eOrdsN?)yzAEm%LNwf&btQDncd*$ zh)XY2`}FPbD+YFU)n%ruv*7rU`+%cP?0R@!e-tbmW!f32zOamKRbt!}IzYITOE) za}7VveZTdj(Nh6V=amU?zTc>QHi+GlS%m6`jG%otw1YlsA>_(Bu~ z?abW$v|Y-XpR|M*G#NLRu%1I46^-bo)5oi2m4tR5w0|Lb>lN{v9v+)kK->H+!EewqSMpK9b1K!`lXb-nTiJMkDbz5pMP-E zR!>`33g)#oyfg!|0fD?RtGv8}n@bowY;kV03iY>`VwBj}P73G$FUccZtayxi>*s@~)`S6^J zxIfB6K2WFcR^2q|ok^RPkDBwxeXrMQdPb(aa*PtCc>PY!_(VpY#z7_3hXtqAOa!p+ z6uN1$Y3ijIsVPM_IEDnj%ydL*53lkv5?76K{&jfAoz>%{=Cu(Ti_5T*kuIV6J^N2R3%>%I6#LkpN4%mgmaIZ3H>9nB60JH2mp ztuIR(WOsEq870AFU+3jv9uA!}t?PGjtnWW1HhL!e{pi5bJB7LS3jv>~i0SVp+PeuJ z0_~+^7n%{c=fb(V_fh3}&eboQEG(XllY6lDAmaX?;5B9&A^Og2#qCX6uQ^@UB`rs# zuRIKxcy*=Brzl9A!d2k&gfsQUkIMTm_wbjpv!oitA5DSMQ1qQXKIY3)Z8UW6;Jp}P z8CH?J%anJ?h=}c54?;c!9+U0*WWgPIKJu;DeZKJitIvmuFTow-{mm}G%^RK@2>S^t zcem&7U)oP0PsZ#O<8QU0!pIrJPmy;hz<=ThMUbt(zl}(Ye`e$b_|kr5IFDYupyaCg z8odR5fc&+tv+aBm`eSkaY$x^~i1Tk>c6B;Vk*Zo;LwW2Yb6kb%Yel$xiOKagnC_Hw zhv4aC`4E4y$X-DTunDJu5R2z@rhnng3$5pI7vaMFrxa?<5ouaebC=;-@eEna5RUBA z+UMZ9A@!c+ahKlE2J<7&1o|(0DxMUoyDgZ&tc32m)X@KMnU-;&z}&4bZ7B1(LH^iB zzIa*2v>A)rd)y!Rr;>!0E5U^@oD@+?asE9IFTneL3{mN9>w^0W17?s)_yq7pV(u0} zW?6O3I>Ce_SSpPLy|W^tbfF+~q{FGVL(3Q8PRl6Er~YHhuRbp9HM3wu?Jth?hu+Zc zbB?5IRZcO8FO7X+BxoH)=j;kxoXKS7lk{$=+#`s*Vc$d-e~bOhuFlGvnWqF{$zm2~ z>z)c~UytU}Xt#8$THjAGe_OEBs(qpPBVVtBd2G{BiuM)3%zLHh;jP5-gD;1kdPn)! zzf^`>S3Mun3G%-rasgftuLQqY|J=ZRPufs)whH6Giuu~{Ha^O*w2UBSIMVlt8Dr?P z6Q_+CRa*vI0|kS{IVkir87UR+&@z@^7E~6o%TBYerdzbL8yJ<9LVv3|0)mTK%s@3ojJXYm|&x6xc`*L)0?uo&xa;`Q|H_6sK6B9 zqgT@mgoi&alwX3U#6LIaYkFz$cJw2pbXWVGhHg%Zc?m)Cg;4|mPRi->9ZwUhi1!_R$5_)gS0@b5gBsA1wpwV3Jn!na>8<)b0{C1;^il zicrrOcTqXYd4&tP7fC)Xk&G8Fkn|3tEHwP2%r@#ZInMmF2AxB&ca3c&9ss#Mi_xTR8PY3352ol;8sr91Sx@=fq1_YOC=XN;GZ zAsVwSlAm~12D7fE-!pAD*kyAI)fv> zuRtAmGdg5sC3U)l0aVbh4JuHiq-x;iqbl^YS>l`5l=aStT2WjWT>;Q$T300W5W(Zf zLDc(uz@F!8*tEUYk+9;;3YZ$tyuJ+a1POsaYr^-&4dx{&#)sw%82g+*lz&tnHqb%= z>|D~iq1?$8xG;ai9E-GIJgxH{UessW{Ib82jQV0d-RBi;q213Mi#2d4JF%jeWeSW| za^XRMy+E2=ekl_G8c6O}&~O;TgC?onZnwl&{McP|PWFkU=fJQ*YtsT`c6s(tTrpemP17i#5Ig(uhPH0t-&Ka7YB z=uBgF*V3U{u3^`OXj8q_x!O@*sy#AvS1rOEB%M8xk?0!5(RDI~Jo$73>#Lkgj}^pg z-~|t_x^jUEItxGCtv{lk>qJa7;u1eL)NjhY|HM#^?koTIaBWEjV-?Vu{ajIR;{wP| zo#U1ahMpBl8JmrLgIEA~h8w^$r~sakeXq0<&ojn;MH&r&w4ftY080-5Sb9KaBphJr zjX0Jr*$BSr462!Z_ud+S?AXXS9y0X19B>8P-7MPLO)|k{yzT(6E4}XVJkU+FOV>;h zC@sG5Y8eRFXf<#W)~!}aPxXnRpfgn2*St%gbi%aqG|Lp*&VmZYYD***Av`iSDG|%p z?QWI$224Sml&T=S=?B7x5Y9c+v7#DB^C+yNMa930>?LksipvJ`KAdWpqe z;=tbio6d+(?^^+#OVi?`mtqq}644-$DTWd`cMjdVXj{#)yJ}aWZhaCy3^%2{=q$fm z(SR-BH2-ntm-Kl@UpnMuppb~MY0Ef~Gxf_3#TfeVVV{uKeYCD+kO{kd<(JuMWj&yIZEDaUcIGmPRNp#sro-6Tt zJaSWYu2Majyi1%oJjC-l@pxH5txd{Y=M=Fyn|jOxkE4wjXKzfa&-;eFceZ`43pw_% zH@lPV<;4!~9MFkdDK{njo_0FE1FhYle%BkwF@e5_ne-@otqvjM?bSPQZ*8r=&&LO~ zZ_{j<@|APqBPqeChrKtE0D$U!kEHrp0zJ&QQIAQ4x%?g|J?!P~>8l(_KGWl8M^qnu zuA|sAtbFSl+w`c`ZFM>xSGKM0n;lJWr0!(0pdrrSkI$*m;ZMLXOsL+!>Yn2eAy-dV z%(~;il#pG+mHI%Vo_El1Tv)wtSGjpD+qCJvWTbhZ$E$}_Tq07U%5_)m=$nqYhd#^B-(pMEP&c-a?jpUg2kYYViyH|)@Pocx|ZS==Z zj_E_H0y$xF3WFV)Q+=7&+5=3f)%%{7v$L>SYPF|BX@CpqF<+Hl{UPcU)T508h?rYM zI-0DC2WcS`dOuP=MDPN~zGc-8mir+^k=ave=2(swddItp^B#IHZR-Gz#X27cCA z&jEhWc|iTt!(QG6k_$E|1svXsA3*9NL7T?%N*xzWy!D@{b*Mhq>l+bPU$w*#Blp=!mPwEn%Oj9-mh4=H5CdcIe%;B{IXZm{&D#pMkM8-ceCD^IC$R3jQKWA*KML6n?@LEda-^V?cFERLJC|`Dd`zP*ap~?+;fqpNXhkb6{9iGd++9dn zInO%Nv1iU$=W}z{9>7bX9*=VdP_H1E5}Ux41&2@=F^%~z3s?W zu3!5+z4k8A`XzO`>fG3ZygG~KWP(SkB3JEPftuRHvGP3=t@A7OIZ&QNxDIxMl64;o zEe396@t84rp#nX>%RaI4RpO>^OY;#qfW8mf7(AX+J(n-^O5_6x_~GdTbi}QF-2+YW ziJRVP^p@|_%=e!Q)|;2L;ARmlj=5`oAZ>1cVtd`Ix#gkUhjeyEv$FxKFmE^Pp?av> zt#n@_F4)t&ygkec;{J46@1H{jbRTK@etDndQh(&gP<5YfpN)vbdS{aFUf*!@{ceGS zNLdRS-b)Pf4x-uoLA-Zg<* zsf`mDWr-aaETh@N_&Sensd+$^lFV?9>g@s5q`R;@3wIo#@zLo3pw=dZOYcEWRh5_A z?2SMHO{&I2$AF26pS7zEbZ562ez_J2b`Tw@o(3GFox|1WR*uCs?9e+^hmU7$p9Cyl zaS;|fp-{VE80F{W`Y4?C%W;+yl*R@J!m1mZFoQ6AA6FI;33qYVEA2cGk0InU>r~X+ zw{?_?1Evs703qS~A^?Qeo4VYjnsk)>%3W5u4do%039kF;9~;+9201sE2C0sjjNWn(F?eY%783lrLUF|P zkVjAT2XToP;FW48=!K^*j5Kp3UX(}}RCm4OCVN!k5`CuP5&G?Cbj{ zt$dVOc7yWpyTa2t_h{$oTDPq8=%9iI&k9S%oM00=jE4)lxPjpw^%oT@iG=6y-*HL+ zX196}KRf&3vS6Bdn*>pXT8QCD6@GSPr^p^{oWsp-)yiDP26bGSnbad)i-?<;qy-bp**4(16-1{TF+lFpE&gx zSUm0l-shOoo(2eyzDYK2s5%O@=k7?WC7x>gplE2ym>~ZP(o-SHvXjPir)DnNuk!ns z6siM5`8^6520X#EP&D9|UAvd}Tmf&9)^3cZUE$g1fuBy9T%5E{(efLU4C?cPF?z!QI{6rpb5T%$vFQ z&9CMFXVuz!t-Y(dt4|G2!OYk(hr)EOaB8 z;nl2;L|HSNq^?NYQEHxrCCm(FX*S&$HmnL=_HYSmvBYi|1~dSR2@AIl`1v^V0~*3csBRyCgH#7!j;YdBz80#Tg08(tmedbsShSkN{d zs_d6Z@chI7PFUJjD{7qj%o=~mtlZf(a3(d;qL-Bv%)APM+bm<04z&{1OKE)ct`vbF@lMIf9+X9rWX<-s5n_YFb7H}T_Zm>zzyS%%gw$_$Ld9q1*y>M5<&^bNz@#$iz07^4rA zspXzF&ZGlc^z$Mh3iNtIsmos!e47vDRp1ikKpOP~?7orv1GUn&0%w;T*f1n+YT@oS zZmHVD+!gdo^s5~#jN5vdiloC+j`W?w;u4bnO2QY2lg?LVq8JYxIk>?ank6L6p@Ck|L4bHPI4d? z?hG*JZ3{^iXXCDvhV)Em3y^@tZlX3<#Z@pFKC%*SoddG2aOh*Xu_hY_`tAJCV@#kU z73*CO!JP|jzTa2Lea9LjXmqzi-);~b(>w6*x+f5WDNXjhIWTwvp1zsYtY9$grK`8XXbK--|3-EUI!FF*UAhiz=ff3 zYYX>wpO{`8l=EwMH|YzLNA+J~4ctBSR(Q+2p$l|c#T%r}i4XZ^&D5H5#JLui(?3qf zR~OFg(-;1xyL$C+x=;V6+Z&kfTR1qZ%|5s@eEq9x?B)wJt->Ar?@~6*BT9w|9Qz{NQY*T$!f=Z58NHdbSpzLtU$WYnx}=$S5Zh^B2H(;<+OQ+KOlqugbaoa^7DU;Isa zunWMYcf`{KiCYza!4dN>DbITj+h1fI+~)wa4bfhgeG_k>dK2QJo{0dFj(hX(-)Qx@ zK-ZeJid?nHyMXD|xAFz18^j2#t%Vz`AJR1*%Gm|T31l0>HIm^u3FO>!QWoSh%0_xB z=o+vy$wU{7aKSQwtzXsp9*Vf`+XUV>$pr#AbuB=DY>o7bxdL1ue@0wbAj#YTvklrG zet~cB#E7!?Sdzpg!MvxDl3gu2)Sy8?@ZK{PZGfUXbO;r$(S=Evpu>gRL&^w0DulD^f9 zYrw6>pAnb9ZN1O9+rSLfeq@M2_vbzIbtLd#v07k2hz;8unfp^$Mtms^+sbl5m@iN; z;gaN{T+SffB9Fn{rer?-M7RR3X7#P2)Ll%w76>b^vN){$@}-e$Z*$tjlYC|3T;TZY z0CD#eIc-+?chp1uPMM@3*OesGilIOJPWzj1dabw()~wk_!^QVrFTt#)WQ2YqTmvBu zt&)I{y$cKI#{;i0&&7@QC{@j={`g@}2MX5HQ_iiY-f8SzaUd4n};{{G& znYh?tpYXoUU-!fy)bROspmKdTX#IFFM_ZyE>6E^|t1AXT2r=Ns%hqVChUUC%Na)4Z zZDc;L4%7XVRZ~AB4We}8;776Z$+xE7krtF=Y6K!Bin(j&0fcOpwuB!nDo*)G9_EV& zO5$#bz|f5t6~I!1xl8cicP5t_Ad$SeX`Ju&50sND%f%+;)n+pv57)Tr_@YVWdZ3Z# zsS_3=k&nE+WW z=Z5eejrL}ak=@iVq%3ddn#c~A%L}S;53gI6LOwH>j&U-klp#x*R_dhQ0N@L4(epOW z%pa6hGprLfCh5d-#!kR|5*iIT-1M^=`&Q{dYQW9+K{e|L$=0D;RipZpvC0YC+Gl_I4jx{oZG8PuERg7Y zYQ~XVi*-p3s)7~rNCERzWadECJ z8p96RX1o@sg5b`4HsH2`?Q%UJTx?aHV&T#GUzXEGqlr8(Cs(!?xc4G?6WR}LMmCVS zmctOUg|P8+_QXaZF@`}_6->ZN?fz_ z(L1u_4P_BYrZabFjz^=bSNiCHqZ`MelL_-;jBC`qHC5`Fe47ngY#dwz+s`1l01CeH zbKfpeHr)4N*t!aSJa8Xr&G!b`W0olCZHnGu+!e!~cPqnWZ>P$v+w`!!D8H=`CN?D6 z;i;8vGp~&mQ2qoV?OpEWEP(5$uXbDamVL^en&gh?4WKOk7=?y5ext0a^7y?pxi*y(shiJ4v z8(nI6A-&Kl$#G7ieA59+^p;Terjt5nPKZ^*wQ$y}vFAT`Pc^w!%e9DS2w=JAP>U>H zh(xS^D3cp!`<9MAYz7zYMGOx7d$J{jwx?R5H-Z{@5YyhY5ipQky5KoCXw>il4~b|@ zhsDA4$?$>hOIe9PJ!1fPIBbWC2A(Q&X>8B9Vf%yb7W94GR3d(TbP_zn`;}tF<$36!#AN}g!Bj|xv zUQlg`O)mtDX|S|b{UE1XbJR3F_fKyPQrmtE1xAWiOhs&8LBSc&K;)W3`qqfn;UD!wM?(w@Y{B;2Ia zZxQ9;nG2dpT-^ctLJrY>(Y}Jq<>54nKV{K#4H`!$&8PiDowWkKHN!9G`9n)Bw$xoU za(ENXJe1~KwE%2j0WCE!2;Y-W)76}4g|Jrp8B1SMC)P!FP2|7_a6C$}6CpQq1Yl^c zCmPaY#oVce)K$Vx^GQt?oZZFu{`opBW)w+$`mO9{ft7X}+q<(}Tf$PC4fx8=4=SD(=bPb#hn9XaIr8HxlJ3_;w*vyGpNX$L{Jm@IqMYtoH zW340Me@*hQtK`b_QjNM(O{@bpfF)OY*=b+{$ZMCQ#Zyz>S?SJUvB)|&{^>w}v4~Nx zSi&FOz&j<;tgutmYgkW8eQKFlH{q8lN{ViORd17*8a;(pqpD?I=+I2cNi~l*-9abu ztR2G!Xsje@K#XR?@%Unn#DngVA0da4CtD7X5^)n;nq4{s26bl<#WoB#UGQhT9(KB4 z7hzhgnaCRd$6$|V_|b&S(uWdxf0dA3f<};B%3$?YM>o&S5MDyz;HZ;8l}p)@N4v z_OK9tm#DX@x7rft1$sh*m@X{38c4Vka8Q#Dt5fUa9`U+}rlB`rjD}@uG#98iQA`#` zrbHQEld31PUlNw&<8^=6sn;?WIIUkFUS26N7sz5*56veP&UxU!m$kyWE@pAeIUzr$ zhBCZ7Ym1g%!sk!V{7#bCdlI|MVJfN;uud)a_@eE4VzT z0g-Pg_f`Ig@xH8bKh_BO5Us8X z?J9Er>WgZ}q0{;G6`#W~(u+gxrjeg&Dzmbn&Nm2cW8#Z))^ypI$Ep>20=w=so2?hr z^YoC^^SK%9^RDs7!#14rp>$yt+29wit&RN8wPW83k35BQHB)UBEcS6-39|?YBn~Vx z43O__eKW1K=F=UwBENP`A_-T$-f~9AXj=y-h zAH|yW`P~P)2gW(|^t`>F#~P8?@9*`RnUQAeC3oa9ijE2YPY_V3s(@&6cEih*-JaV*6Oe{nq?DB6RLU z0;W(@Y)HZ8G3#vHTlpz|A}V__8g|;AfPnU3-K((#156K3FbPCOOD$7% zMt<2~Y8mg22%6EKMq8+cRBr@GML-pz2Yp3G*!rWrfHWn7O{Qs!J^ zTrbJP;kHntxtd9aq@`A>T?O^C=At@wVBh6_!gj?R43(Q)5UHpr6*)^=G4*t|AS~Kl z)3k)Jr(W_?e%}ql%uQ75o;qtif*g$5QMGdSwxxNjmLb!iHGVQ#aT17wR&9t^i9wxq zi~Jq<)PBPrD|mAuK3zFEC0a|<@jClfa4&(u7~Kl8&me0n+X-Qo?99W4WWLFd%L(xG zx-S-Vi0=g1aDroIty04j7)~-7vp+bFEn($c6uz$4=!HAaQ-=3#h%PxMS!q}SS5y_W z;d8G)oUJv=9Dd`^jC2o7pWV(Q>8*O7UeV3=%H=%8vjA{EMN%6E<>OozxOemua*mE9 zSk6js`Fk|>w&yr{-#Tm)KIc>q)SPcy8r16fdyD1{IBC#8e`9HQhK3#Y(ncIN6ztBa z_QDhFX^tG}(HIq>Ie)*8Xk&g<-!MFkc#*EDW;{2@85@9xP%2*9y7!0SEam(;dLGE9 z`RBXe zS=D>;iiZ4(B?ztK;pu^x+uiVy{ribF;u`V?DxMem++Cm~8 z0$Za~_qz+$bD>LBp@4Ww_xrXzh_ykk{cjbv8mC3>6Ff~mS%n3TAE;tD7s#xvfC#jC)*2z|bS}4KzDR|-6?UTdAOquS4Z%At|G$`c)C+TnOJAK2z}t)mW( zRYs7}Ur%=zu&-B-eGoF|QHkIbYZbm{blUC;goG4!2W zc+o`2^pP;ZnyQXbK)<1RvL7xL0k3al~foAamhMj>fqVsOxIo7CQi~^wz8Wb9oc6AXJA|E5^wWOPb>W>mB0Y{4eI}#o2 z$4HGkpi>PnYIwww)HdIH%Fa!H88fK3sam6?6Jbl1(7{*WtDpl)@Y9TIxVIe?!EMSS@}EKUt2!UIBJw-xww44(qLCm$lmB<%?pZN*7| zJUUlAy5zVPd1CQzo2f4UFj;`A-{)RcWyY+#zQtHcfcuS*n;u4nN$Bt>(bMme78E_X zarLMM&zv`&$fj=seL7x@t3P*Go9GK4>zN!qgV(v<{Pgw4(bFX@+7p=#pB3RK&MgOy zc2B&|K9B2ZAMUC=H`lIClR z$(_L~CO0n(AsB1bU__TSI20RF=fQF>Zi4I@GB;ZJyP51*8Tn94yto?d??i%LjE84W zPzs?nT2D^|9BonhZz`H)w8=9bzh<2cByIY(#9x#lTBo0`kpYEwZAeY+2iaUavk@Z= z+V?{f#C3IcVKs#w8QrZgc>w4W5!J5!vGR`LbdNkVRKd_;1I-YZ1KeI(-Ld`V3^IK) z)*otKSUEYhLFBbE^{DOaTzmy*Nn5Q)&6va7w`$}7%FtE2y3GO!J>eY7Ohw5PnWp?h zZ_D{{adjn4SfOBHC9T^Q3>QhUHC6fgVe_E9yLR;ooQHmGGmi3RaKb$ttQYd#-cF#*15* zIRTB_o1=;G7hf8itJa(va5J3J#WxnuTyekxO~5m zWZ#!=)53M++s276v`^eEzykLT=VRkZGMbC=9Lu&BSC7*SDjn(WxP&XRtVDTA$K<3? z%ii#1D)uJDrg|w`KZ{zlXWLk0>8u=|%3X~2)vlg{wFm>9NA?0crDoxF5CHjWT6TO2mbb!4I}a;dB%vn;-pUL#1E@qy)W`D3?I5 z(|#gTk`6tjV+Vh($JFkdWuJO^-> z(0gwP+&)K;&_k88n zRX4*DrG(ypsK9*XAOd8V?^9{u>T53*ir}^Sru9C(LRxz!7y~66ukVCdm zR+n=Y?jj-^EZ8yzbV7)^w52@n`lMr zV$**r2KLqL8xQ7+OalX`)il4Bpyyae3kA+&zxNp-biqc`5vqq`iNc~#7h`O76${5> zXBOcsAz z+9WE@-=~ie>-R}Kqn9Ib#p8`uP!4KRG{cv+Bog%cxEkrmkWg6Xjig7c{`f&BQ{N3M)IZsSIra@@ua+?yodLu~7yz7bfM zLO48|no=N_or!#q!s=-Wt(A=RZR)o=kOdAS1bjP>)G%IMks{Zah-blPyG4J6#|siC zN``9pvEl6~Pa*5W$3QNoH`44a086%#a?piB5lnoF=F=XdTBLNCZ~+X)={z(>P>Mov zaSanzA*vTTy^GlQp?kmHAMbndoO=9?sqt=X8hnRr*|4TL^b3MZfOl2c7!ENMPHh%!4J^G&ojdi=X+hZJoMqKYQiX&m%iiSQbiOIg zK?Bs0sY+}=6&2;Wk5!rL>*eL|qa6)CBnF1fPX$WJVtf+*8{(m*kmxH;c8&rX6>I&; zzb+WwclJF*Yj&Oo-%W&ekN2I0ix$5><}FjJY|4m)HwuZelFdHYdYvF!4b6Ng7lT?3 zGbg<-5h#`X<#2#IFQX1xb;oNk^X0%NT>((JC;t{-Q$ZdNXs4~Ii1oZ6_lX9KL8514 zYRs4AK?4l_uo4c9eO?r@8C1*HYopNgRp4Ca(kMnfQb4SiFM7tzK7$hy1&{!%OqbaT zhj2C_L%xW3TMv~=R~*P%6&n7pwXP- zk*fJ!bm~*!@ZsB#RJ=k+%!8K@Zyofl0#Fm;Y$fsA6oVO%?1mdpAw2B&7==r&kD3wE zr*{bUq`Gx1)%@d z6uSP^6h7)mtmvPJp8s_*8aR9(25bn??_+_(^Ao4R3bh|i4n~zD0Hgw#8piB?AFO|s zjcN>;%K1x@NRgAX43P>&fdxtlhq)Lk)km4EmP!^;WAMqAT$pR2^N~IhW@84)TM3|8 zC_eN`g(+ZR@`1*z0 zNge=H1J){=(n^9Vi~YCRDG8FO-?zv2SBdeMw8w;%DH8%z5)#&}igDmm`CmgSJ9yuJ z>3r9l@p*fCyr+MUZl|CWTk^mM)sk*j0vS0}gVkSVg|I0)YGIyK!jmu3B0YlABFbs7IJ79Vw{nwa zKZ?L7v!-wq&GQA8JH=FLq83mPq=m?9wNt}DG<8T@qQ?TcB2dOE%D~Lp7RDWwY0Y}( zoMYJXDn!I`V!xWbUCWhlHpQ#!ahU_;XmP1idMu@-Qs#9Wb zNPoc@f#Bm8f58F4BugLQ6J}_RR({TtO5s@vnlg2>IkVh?x%rr=0s&%{w0ZHLtlu@^ zB#R8hS!l|WZVbbdQiZWV>spo!i5Z~)I9VFP2$SD5J#0!Ktj)?v!Nee}d$by{nHvPS zB?O`Jv&fYu^VeW-D9vCd{W0mxg5@6=U(W55ke>YL%b-5 zghn0*28$BrUxsiWh;A(0jYvR(;hrVvevqP!=H@69#nYl7<(hCmW*{Q!gPb(Sa;qEu z0fS8Yi5NPdjv#mq=XWhAMA%oH6^%>*bdLnI1PH{^kG-ip)#rn_93A4N64WF@5VCUc zEf}R1=qy$8sELRpGWlG&PH}JIm`^HBt#$4{&^ZvwyN1j_ojl=F^x)HwP{AnWK&{Cb z6^^{J7D46*Aq5Qy)6DQ?KQfr==LsK+H)UexyLj@cAScpHY1Fs(Fv4us+_&GvHwXVu5Td4gf7@+%%m<2>Z#%dAPec9GRGEJXGZp3(S%%M}(fx$8XgN29~ z6)1M`7c&v~D3yN&3Yz9n%a$VuHo64gOYHTbtBJst69Mp@H$hf4b{3KE-eQK80B(w3 z6g!goB-^NOoeM7)5YE&X(u4`@L)m1|j|yr30<4gRb@&atWY)=;K37Mm| zRDgQ^A7;QD{1w#zusjZrz+lOYEFU=q^l%F3hlj^NbfAFDHkyku>$0(-`{A>;jV51A zHaw%SCG4qy!AZ5F0f~K-zlp$KuYrDXthxII`4=e?@c%*Tb<_=xly&LHwW$DV7G!+*mn97q`kV>O7Qv(BGVFObE zpVYO192aJ`V>1E4Bk(6X<(=EQADk?B=9NE2k(hd(J6-Ap`MPEKVofFJRwEEO&Zx z-+VZzX7{UQh@2j4YTq})gFrC+D&swhBYTp@S0nP?pSL+pBDL>)>1b!^6$BwuZ+@~Eg3(dWMAY@ zdwrS+<28~h=%23E_ zW(_i$lxxo8?}fOJ=JAcp3l?!EHpL^Twp%Qz5;|+&KqvEk+1I{oG*_PTh@FijHOeP6 z$_G@_LX}NOwFsr(>2pbd<#F65OB&YBa=Q^%7lVNnNf;!NEx>&k(` zp^OVd+>;55cFVfYO9TJ5`x`z9N&%^$JUF>_6ejI$E-Osswb=U&6fu1XF|^AILi|0} zAX0~`1N-`LWa)~|r|SNnQp!3>^troq14j-6bb>9q{GuDbbh?+?S+@=NucKePr6j|b zzKc4fZ(m-#?QQS5auDR9E2VMa$B@w8>Yfb796`ghnv=PamM?9}g*h9zcy&sxT7vvB zo4&bdo;QZ!y3A|l6Fp)SfAx+O-O0l!I&e16uk$yt>A2tvNK6PYy?E^>e(+9h3RvlG zlX2Yl`(7y%phHzmKSj;jP^n+8e0GJi0 zvd;$=eEJcbvKeKoT43p4vOAKutaZmV2a+{p@v%9_jgvbpwRXX*m!=dd>YrQl_;Q9i zbBaf!xnn)A1xtwfiit^w=9SKO6HZEh5w1+Le>cx>T0NwirfqB1+`WS$TzXIkih$N= zsK5M8$7b={+@Ekfh(c8{?? zl&e_wpIpY=UDy+|-$-kw=)^H?!wT9aw zr{Ax5KBJfZc~DIbjEP>fA!u@0OljKq#|qI*B@ z5r;%oGcGW#DnY=wm%n(ib6^$b<(B;fkbVKa}DQ;^XkX z|M%29bqg_ZUf=6aQqZJCv2dU4}+cWUllXR~kVE161-7x*Q)Lun?31A{NHdZ)l0uKO60QO<}0#g(C11f(Bvql zlm#D8dB*(Odq1?&lv>$rpx(-&I=JW1>o*!UnX&PGli+xgXEfipH#)7*asAEXMZ!aY zeEJ>vS0WgVK(YUuL>2pcqw?}+NoQvM0d=3%u?u=}siFtnp!K^4w4DaThaUK z<(c+eCnAUa7{krS-pv8CeT*Q3FQWK?Uegm_??o)ffV&bLw%jN*V8cq0|yK-oF z|HI?1hWWPBUC9Hg@NWZq0(YM$ymR^Z=ku_tCPI|zssMhETJ6dlK~o59zPzfFI}=*n zgC8+u5;ioy#+){Oc?nYg8RNM9l+prwaI)jc_ zHFLpGQ^s@5vGfIMw@UZYzfOht+N2(lO@}a#xkd zcp5hI^bkYrFE|=}`}a$8yo>7?-xK-Kzju05tZ~jm7@K@`vVPK@>dyc%vXo(b>@fJU zSKrgOpCwQh@rf~8U{-TQR(b10=$V|JGOk5XpIrJC1t zTF_za^&6tsQ^7OTfpU+nFJHV(`;!QQ*Z-Z&BEH8F%i$+w4c(W=BJY>#QY<(%dQO5O z_aS?=+ZZpl+mhClBh}TVQr&`c%^aKxT%GkS-O+MgX9F}?`mh2udWCJxf$V&6dAuW4 z+)EC0T(ixiUHS~{nh4TIFu$*Nkk4ADD#k z)fqkTp+MvTQj`i=3O=wY+%6FHOLnh-L<%9a#+Ov+&0k*7lz%9M*5U}E^KAl8oL~Y` z@v=pPp*3NJet=~!g$m~aam5F5nf;?Mli;#@0~8EJDL7$;G;jm;8_$j7aG>q6Hlg!5 zgo^#5SOk%4IM`6S@t%>D$`k|JCgo=Za>(B$0poHpCLd2^5Fn>j{ zn}C0%Wxx_DhRU7|Q*cKQ+`#5_O>Lt_9{z_Y)0gbg|40|G&H@NkaP7^2vOXeD zv;8udp>>sgqkt_jMMrl*(N*AW%W@YJltjzR0+y#gFko1zYB9LsRMfmIz81J)UCW#- zcXz?tI)DEJB?Vq_!8x(EKp++b7J7shUhwsl0?%%R>@){P;_7fUM;bxKIR6AaRx}Sz zP7C^sg9 zy|0KI*XdgdOPLDIQ{#=p`jvIblSf8iK0><`;zGx3zJW~YV#lW$4lNZMLK1RX=^={E z?KF-SHu!3*#waD^MpYh3Um7BgM0B~gn%QC?PNU2;Pkoh|M@VxS@9j&@FsGUd_LtJ| z?Z1*_sXZ&IoN*5Njy4{ZaPws04&1DKo&o!~!x};1@rgW_QP1vQcl7`34tfg}zMtW~ z6t811RYT8ZHo2xJNg36QypxDO#Jo)Q@`&|JhfIGn;ru}+InT|ZP5D8b@&g5-PB=%A zVBx}SCm@uD?OGKiuIu%{B;4dE)Wkvr%vz5n{fW5c9rS-s4lEyQ4gq-4N~RqUH58Qm znfCAscmKgWX2JA879v-7Ed%FwFW2|`uw=2iQ2>m53U9Z!OR#>L^a$OPtvvGC7G0%S z5JR-JQy@dQYkazVu*vNxqbIB>>-qXQaN|FGt-&rdG9=)Y|aK}uJ=dhw;d zUTs4Cr!~i0*80P~3hr~o(g-Q;$>uzzz7@XVVq> z0cb0AE#;;-fS~cx@P3KPtXo`$>_Q=NYRHOk^y*K-K%lTOZ3#hKpIxFjyZCdGbP8O8 zzev>6+`K|4Ydbp;ec!_luCS!kFYgl++$Rh5OW;mhXRB#cPeGm7KxcmzK8GoH7qK#? zUNsI>$`QG1IIi1V#`MYzNP=@Gc7iLN|@vh6PiLl8Xwn`~G}%Zr1D zS+!^<&|Fto6fX+G?2W?czH|sI_KNRKx?0ag{Ih6*YRH~%>|I$|lFGQa4qu$L7xKqz zzL1{KC8EcgMZ8m3zvie0lA58If*-ic{l@=)&d422w~Sn6YbfYMVt5xUg2X|z z?>Su0r=|VX?zJa`Aj9kOZI!?EUQhQ1YqhfT<>I>X=ADmQ*XjM}p1299A zk>BUxYHR5IGa}YRhimK=pL}v>+rlXwm(*iC;``gl5LV{f+ex_mx{QXdjK&>Srkr?1 z0ddIg;H~R-jsoILCEkQ#c-nZ$WXIRUmYWjk5Fx+ji>!@;BG&CC34g*+~g?{7Cf&&!>9PUp7g9c`}F&nJDmXjD5Hkf&RVeYf-L zz)3X3=jH0r(PCN$hl+~`w!;u&UpZ6c8Sv{>G0wqA<$SR(^X%OF?fF!PU2V%E@z~+= z>DX4!=Xp+@-d6YZ{{4rSH zAW&4lWaN&z%g%XrBy`t|^*KfE>k{C8VZHA2X=}me&h@ytoil$=EbW=;IWDz*e;O-2 zv%eoaZa$mf_kQ4coj>JsTk%27*gRGTKJByneu96ynz^oo{E8KyS|EMDqgN=elI?gs z{eUs|M^zimxcwW7a{JE*M$$+f{N;M1x2u=kW5x|l1R>ISo|?z?@I&_`(}NLp_I2KB zvH}T)J)`kznW9H}zUOJ<#_!2*$jr1*&Xn^kg-Q*VPBVV_RPmg|r6;oS^*olrMM`Bq zqK_yF0u-g!3etSIa?AYLcPQ6K>Ob>MI}+jQd&4~sxAFoe^g7xe-{y|bJKlniNa-54 zV4Hjf=nv;@*Iqqc-nWlkfam({HX^O^uf6m~vc%mSpN7;V-A*JdwY9%)@|McjXJw}$ zoqNAro?2@lb5AQwN4BXRXP$b!jPSo-9-O_N`iS*JyVLGIzlJn+u8LtRi&AWR;;pa8 zGjHtKR@!tlcQn5(xK)iSu=Tw+&v-ysn1K-=FKgJG@_4 zMs~w!$obX#vOhA2@()TrynLHr!t*JbL60@%702gX{gpLQXz4Wa7|Wk1bHD$94>}f6 z#Mt)$xwrrg@fb!oPEbu{y-J%Q01($(nuQv$RG;pnvQ?7q(bgcV8*^3)K^(;>n2>032 z8}4~*|Bg&dA5mV>>fQ!)ct6IBID8ZYbxNFuF~Z zjCtawK|=snwb4e?fj(lGE=(UztvXnGm-=eTJ}}c{ac(|Gr#AL{RHCtap+2Vk$C#Fh zw&PFFUdiGw_w3w<5;v(#^)XB54vUQ1u~HNAb=4^utGTl0{2B|o3FNYr2!{aGS{>`P zOHYJ)-2$VE=G>9^SQMo46xIEdQWM^qvl7nA_nqxDCuJJcG}Y@ClJUplMTshx;ds_eJ%a&+Pn;U;0}U+lw;x;_8Ew=~3(y5#m&IREX;ZG3Nw0H*#<& zid%~MpE;fc_>sf`ioB*)nktRsU`8m)YLl<{wt{M^j3l`# zmX9mwsEj~=SEM!C60M)HxVGT{4?oH_P{g});^Z7a3l2ZRZv!ez6mHSRVW${@^-V{` zmQCg5j>x2g9si}tW&N{mYh##wf6_m?3i~K}nQ5pLj$Y?zdSbsB$^~G~5j})K?2Fzi zR~P-^yve~S63Seoet6Y*yw!ahw5C-F12@gCsSujB$k7h|sV6zJ^j)1!WtyO0$oN31 zyG3CU5E%~EY*tNE)q$#eC98)k4i|5qyh*Dv9K0U_f90`0OJ|f#gh}5f>yWLaW>6ah z%Rn4#EcRJG395l=QIH{ykr93lyM!SQ1sdL1241*uZcoPytIKX4q^GKIB=y9#8#x#Z zS{O$jJlNHq5dQL0DZ`3Y5eIzV=zV_x!M%RdwE@TYXS85xjPZR@h&tDuT3@fezfGI1Sg$Rjo z?X{W%JT`gKPE{0}kJu;{M=>CM8$^4<2Xlxka>x=y&#JSW9483;+&6o)lq*01_cmN9voo z>k&Q{l*1Gu!U&Z(%NLEksi=71>51R}%`wEen=t>`F@?Uth5yYlJpTV5$B_SDj;WHj zfmn%)c9`HnPZihQ$x$K#7eVpr%M~XItHi2|;KBJJ!3s~d*V@|GOZ3}d3$_isBE}UC zjb56pfFGVLqb072>9Xb@*T?`J&uCAQG9aQB*3&B;@WVg0O*ZC-F$S9v5fiBpa4P_v z{wu|B(&w-vcvXsFXz(y5vf!MLp5%lra9INyW+0!)zI++@6v@J372?kI`9D?gx!1|C0#-tQg0cF5bfltR_TicbJ#PULN7|=c zxFys6a9faz_mVMskC{?LT-9&H%i-4|RbSF9SrI8*^t@4^(}CF^XZR>4iQu+}h$Y0E zuL!1h5-^+uQ{XLTtXz+{#o$_>6p;@Fjg%O>_UtUg!(8NqZwOfQhxPqr+6Cy*`ff#V z)n3n&aD%0WiOmU{$rUusiT(8Y@^F5tPk`Qr<>9E90bkQjIMsL`dXr+GGRbu7QKj+C zo%ylBxT-Gfu#ygvK4r?mpU!I-%5k9eo;KA3YEf$pU35py3e+N}&te9rPHoH2(cm6`HoHMc&avf1Qq9Ssa_nczppOFf6R zs1o&u?78Ihamio;i;P7)a8XtJtWt4|SLE?8c?mR_+I;?)NDRce_~vbE)X=!}r{nZU z1gw~u+lnShoyiaRXSxSxFx*^uW=W5YR(J3ByA0Gg1?5Iqv8ae5rd;iQaqj8hoH3Ng zLke4NIHBt0mv zr&wC?4<-_HbtN$x3urk=Xavt43}#G&VnGc0^atECsZk)fyuxVI{k?{zPNI*FLK==~ z5cnqzoS_+zN1Hw|V-x&u4~ISzH_0Z-spRrW=aETVH_3r8lh~UYne%;O*<(;@8-#>p zqE^;zJ`K`lSazJM5fiKCG0-b5D7TuOFpx*Pu`=z(!$&)1fpa3IKq4oYDTL!|i9Hgy z->_9Rf{I8n^s*o8vwP_@&f+KjrqM#$I=tF6q*|~_M63cLwQUUnMeq>zWP;O00U^Ab z2IotPD-v5b4ICH>O$8b0>e<)83ji2b#O)q2_nE7j%$b=yP2DHB)A4Y21K~e81YhIp z6mF#!((e(c+m_JId$S>p7ziQNW!mhd$7#+Vp2Aw1iw-cDDH?(7eD*7Jp^>-4z@pk` z?BIPz85(=EL)w}-Iu`ZN{McvO^5V(Y)ynk8SKeE8#R2~`JT$??=5Q*~L!DyUIzDH| z3~6a|D^vCcUio}XiVRZG8DnO_9NJ1*&0mKZtzY|rD3|7xbxYJdsLh z2;V_b7-+6u#Ay0iIRrdSMgi-j_}-bAVzM$y9l0!Gutggf1{NZ4hYj_i#IB?OlfoP8 zlk??#Y;b4zIKd)CaaqyzVJ=AZnL#}ec8b>>$qOu{#1!EE@CYkG%qcT7fI@=vvLJ9?G3kI4F0v z1aQA-NGT1pe*fS6XiDh&e|{J={Hz81n8G<-_(~8liL+Y9?`|wPz$z_2!Kt#SB1Iv1 zPD!}6H_bV*IME_5_f$st_eOH_;*a|+e0Fp?u#SxKn$TCXX&zc5k&nV@#$06_YU+9BuZv_!Jo zcl)2{33>}JS58k+;|>gW~po> zXz)Eu=nM!_Cius=jtC3W06%7G)kSkZ9W;k4KzhGXf6TF*U|Nw90Xr^eA5zJW9=FHVUkXnv>?oiI7Z?0H9CWae za8pApO%)e>3ee?et<5_mFZ;x`OYjvWZRrctZ2a}pQ=GV|Xj|y+pq|!crgnN=4F}2M( zk8#(xdJg}N=xOgbeHL83hkHU)=_B7;Sl({PWrKV`%ze~u?(iV7_emjdVkl{8fa#;R zcSUo0=T1i1WkUh>ot`tNe`rq4d`m(_#15j;`T=oG8&BTvA;b_3_y!RNsgO$t=C5+= zpQQmWYX1C(7sluLt{*QQGQqI^U(DY~FkS3}$E;-g_L$w@2>TUPf9)joM!$p8dU>l1%`FY@#a-e~u`tgr{CsBt$r-z>)*kc7`CO;k zgPC^5v}X*{o=~p+9m|G@R6t$>J6FP1ZkonruI#1@gQI~-7F9#}NKGl-|8LngknWn|MwYrpLb1?>)r^d+f(L}z;w zi9dYO1kab>BJ8#D)@9KbTGd%lhwQ~AZ157RS2}gnUfvC#G6QngCbj%5jO4%UAil4* zfM{owv-2;981FDg*^-~Qa)gWb*j`m#QVeovP=XFID*UCme;QR)OlYTWPk6@nzib0Ra(8Hsh3e`%pw z=+QkX{ZG5~jnTWI3%4Z|?JqCBm!yW1sm?VLpiVVaPJsORD8-bFyt9+(EX?R|+bN3i zx2pV$7tNKk5@1YeeJwJ*OlhQndQ)cqk2g~LbN|IMOLkIp-%0&k zwpWCg^r5QWB^7+4Mw2mr(zuu}Q!KnMQ{K_G4QF+Z+J1-ooBry@E^+M6feXVNtF)oM z!a5Jyfr93po+^reB|tLEN1D5LIT^6LRAOe`jvEB`lWNp5M%_U(hIBIPE88DL$}d;F z5D@+0$#6e+c3guI(mMS`*So`$qy1`hNhg|y!g-Qk7l|#!13Px-RQUH^={vckDqzQU zYQtbMK#K_K6ducW8vec~L@{w`;Zc--`9di#`*3>udq}6b3SJde zOI+tvx;a3rG~FbfZYqg&S9Cd7cLBUZLV9*Kh!ZKII|Srk$r#qDrLSOAA28|9%EgRP zqKirj|870nz=jFCh}2lemL0dq>DZ+?NAu26I3%Pq*dglOdOrJ!183FWCC@Cy>m|?9 zh>q)jWMMBaVe_7}$iW6G3kP{&Kc7Rn&9os`7Y6vQqgJpRD>?kbIS+Cd6JGC$o9I^B zep_fEW_qT|8->O+gdaE_K7BzSNSm-ejo(^o>kV{SL z8({XeLWVwlI{WfYEW0$?h#Bo$H38Aqe1%ciy38t1-T{L(`hr7ifs-B@LM;+w*3u`0 zvoCGrRaOLDWN~@jPI;~clb)xChgppM1JFhDhqGlKdH9Fd`&r>?yF4=4(}~fW+6P%) zf5MDxhWWTi{y5wSfbBN%H`0m){wQV;2Nc7Tc8#9!B!_>8>v~SO0Yhic0@%>zq5V5M zi56g?OBn#Z7^>nLV83`%8}t^bYnML{APwW3h>D?p%s-@g07w&1*-YF8kmlhXLk_IF z1VEb8_h%BUh#@-gmWbUIq-vmdO%e6=NNEWFH9S{V(blr$lqaC!5xZam+r zUkG)|r`5G|SqOrq+B_?VPJf3e&58uxp6}diS9jeD9$f^uCGaU4U=%-`Akr?SU;8PQ zcZ$!drDDxPNI!NvFqI;0rq=m!1WG!wW5KpP^m;IVlhS>fTkYt2{PE%8&liK1_S<-n zLYwWjeYz2%{A}jmF5WMW>*oTV7frx9tNyxv;KL~M+c$%91k(q9$84Uazw}Pa=1cmR zF5VND&1$On*8et9g7@3;O2_+{D>0r~^K>&X-__YR;)K^35O{BQv(3M~hpl)pZ_}#O zlq~Ii5b*cOmbR@kbz!w@Bv*Fle0#woPN-ED0?a0pwK#KHg;%oqyU5h8Y+BDdyzSq? zu6!7*WEdvU~8*i zSR#^uxgZ>ixqm=%!j=e`so%Jp8pGvx<6ETt7oi0e%lG>1H#vqBY>k)Y%~-A`8!l)c zs2T~7R|1yN(4Fchf^yx3W-mn7#MCKjmMz^qBEc3LdRb)_?KsD6giQTLdPr4L(J#_c z6YOfO&wZBlzGLTh2HyOzGMadDJLzgC&eZ=Ta8prF{5>s)JypZrhRNWQu%Eu39A0gL zRiK9ah{r6A;;Refo?B;Mo0iU(SuWEe66~xQw$6+WeTP$ZCobZ(U+HE|p#<@_iFy$I zqn26!RWg9uFTPC5K&tbrd6|@IXk}_@%FyZG>*JA6)!`#QI+uz+3tt{Kw|%nS_a(as@H#_>6BMvxubiJp9;qwV9l%w>EO$ zUlhKmh}*ZoTg6bg5VU<`wmjw9f;Iu(^)9y2@yYR|vEIK`#k&?u%^Cl7m71e|-3Ye2 zNN!Ba89_h0Zu;?wL*#v-fWdp8aj<4ujsxb3HeuzNEW7l@t;K-UZ>Z<+6;6kga5`x@5@~qR;8y~lMkHJf4&;B- z4S#FOv|k@C?7Y8N#>y>zYLzZn%%OLVk2MA0x-<{?N$>iQgKZ&n_+HT%_|qnD+;i!% z$j9BOoNZHMP=l*}sKB>I!vs~Cis$)O#se?V^d?W#s(MM6qTD@rmF>aJ|$k3?mkPBzh{^{>t+8PGy-Llm{WXmA>2AB-sJM+&I43z3} zF(9WihlDvA z(JkVEa?*h#Co>G~#a%oTHwH?KK}wd}=M(w^cW50IE;Zs-zIMORvQsuYJXsWnp+1fl zw41NFeT-EYM%nYl+->C*;Fa$W6P>pzfi;kV5!L2=InkjdExP_*H0|8{UjW0?q{O*dGnYyVU&aLH~KW592Mn1g-jSx_}}xZv_Cp!7sWlD^OoW z1Amts=)+KBzDBs$Z5|mEVEh3>I3qdwzhn9hM(|4e^g!bP^kNU+qJxI_#vb9)t645j zS<}_Xd)TTsD92LjXchu=oOx8DdCHF@upMtUtSTq2ggJtg$X?;(Xvp`(q1z4Um+ zW8io@Yx*xw+ZIdl@%BbxJGjXwnCgJDmx+D)1SqV66C)sGQ7d+J`Mi2A;XL_uz)xgB zR}uD%CPYEt)F_WiAnVX^cZP)o56&PrAIXgX7RI12O!P*N0`}1w)&P{Vjg}p9iRRzb zn%jpaGS3X>Bdq_ML3dL08CJ$TD69dJ!Q;ONc4%+zf^w1Fc(Ks)racHy_8Jyn22ol= zYzh|F^VLIMT#9mwDC%FNtZSIpi077>o-nbpMINAa$Z~fu^G*wuW*Dk*=E;xoU{M9L z1)2^Gn!$7!a4V+04=@>l@o`>3y1VOt59&h@oR&L5uXOuIsy?zs!aVb}n3r|KuoH{S zwzzv0=vaGdFDuIjgU1bf-*Y*=a5Dzf`4&*8`{e(Q zRGoN$IyL@Noj$0`2iaCtP~u9|h+~b;mJXuqCA4IkZW8z;wfJafmU~X= zcNCe5rtR25sruJ8DPaJ{r>!}Yt?8jB^`Crn^|?tS8r6-VY>lMg0Do~i3~ui-Q3lv8 z%_#OPQsDFIwP)xibV(>Dw&i`EGmlKiziB$OsZXR*Y&n#Uy?2Msn^%qkvj+l_(EI_) zUK-&9cvBlLI|MziI>Z+CQokBy@9YC-p0@t1H@R3Ie9i%so<;?tR?(Jtdsnb;fhWo- ziA9Ukf?np$TSmb6Z1k*ov)Rji2&QbVVH$nJ6d@pi6>%|9-WFfa=WD6)1i$coWv~EE zw);Iho3s<#?5f1x=y^@$HTy0j?Diz0?6J$DM(bYk;B--|gTw6nPNjtBq{AMS9I+!f z7i_2{03+xtr3eS)99RR}Dt7{biA6gv`5lK~OoeciJ!OENa)cxF z%Fp#+{zXpoJ%W38N@?u9pxaj9*kn&xHIIA09`*8nxGCR_Jz-Zb0V7glcOu;On!Z^S z>-Q4=4!lUCowBAgWs5v=yVLv{?_z`N@iv&>X8xI%ZLgucJX(TgR)ufC#W;a`TKVNP z)``>88=tDn#)h?NyEN2TgwLpr_m^o?c}M9cLQi0$n8RE*0dSsR2a_6Q!F`Vom1vk2 zPsxksHz~WN6FN+kix^{#6%5jCm-h8?Ds!xo%YzRw3u~@j`5bId3SzzawtK~{a z&fdu9V#vAMKyvXdd+3#anmXFtv^?E*zTa#6LZ3K2<;C~*E;v8r&vcx;mHS5AvaaO( z^t4Qw=io1B%tiPdjyUqO(4uv#f2dk?po!^JhnUX!Dq`t6*=(20gDUtsT<~{R`(0wL+`b)EU&L5GL%fs}_Y+sI4O%9U}y-F36`jj4xTbsEK* z`pqE+v|K5f*1tI)A#kXw>l|WlVt#ZH+E070#yKb7MUF+K%l_yB90*@gZKoZIeACa^ zs5s0pt>U9_71~K32_&hYYRyus$ysA(!lIuWAzGlUe9P^Ab!61#E%l=av=ui`-$Aw# z#P>$A@(>4kb^OD`kgdy{JnCw)ulgMA1&#i^>sumT(uH4Z<$38>cjTIL<=A0YAV$lM z`OEmL)R5-W$}6g|9=t20v)n`& z!T%s8_YYzz&xmQYJ|k8)^$%ilP3)C!LN?%M#F#0dh*i32QI6fk)lFUHq*f_>n7dL? znEztgO2Iw7-4)~h*g3+4c(`Age6C{J;deClem>NtwN&`z-bYfoiTl#6E;H+DN_hZO zJIU>59uQu!JIrm%^9+q)ZsD*GK}d}uVqe8gCS~2)`HX6{rjAqe0pqBd|E$J5KtUZN z?O9bD>O)R#19@-iLo!<(3xEHOA7&y2<%eQM2L6dCbI3idHaVmfHy_>cx9Z&u7B5K=3S}Y^A5K4rc2+wvLSc&1oSR4f%QAPk zZ`|<(x$O5rQdqsA;kRQ2Y}BXjkk71if#AhQRSW;55l5re-`BvS zOGTy?X>3B2IlAj_6O0zfGOnf1-aTQc;hbSVZI9hN9lpO%^vf{a2pAQo zw^nX}jE=I|ZG2B{4Z*MpjybCRqB5>Prb@XU(^FXiI z3_X~*`!dfL=<9wlb~ScY7*|qkD5;lH@fh-l>p-!Kx^sMDX%}y?CQb2|pn7 zmYpx-PXvy@!?CCGU*RYQm+hvuG^WjfpxUaKy{5KphlvO43l$>EB|opTzGBa7W&hYb z6QR5)gND8@6x-{O+4W&f`a%#7*M`D}W$T52d)nel)w;N>a$}dJ&W#nq-~gg+!j3ja zf?-d)JEoCR{ts7({L=4VARL=jN`-q?j14HVM8M%O8n7QOM2fklNd%)N4>MHT1Tw#H%A0Z)72$ZykB5728Cfc%t=Qb9?0F z_4U`Xfz*+g#+ko6jK(RMhn@B2! zcm2wfv`>M(6l&wv_RCdwrdER8va$&KqRa26aNJZ_YM3I zK2|X^(*O!yvBF>rUs#rzeOeM)))ceLc7B5riqa>`md3aONuuHka;)O>D~s|n^5Wl! z7MgLa&S(lr#KnH)-#gj%$-fM|9QBJwjb%2F<~gXJ(Jlrd^^``JZOqtp`M-}<2%Yi7 z;QxG|y&AyWIA$X%ng!Q6HV3DgRUqUCiH&h?-EKzBLLyWsE2|g0Voe9m<9KR}tLAs$ zN5^1_6$wZEZN9C@zt{l|5;gQVy#Iu$Us+-%k^1mE%p32Ncdxk6stadT6_L{_WN}gK ztWB6aL-Ik+DL*A*PVgna#e2(uhg0vno~mX4^Je|``1Gy(QjKfBx5;|6GzFA0NY!V} zH3-0KZ`mvQxc75O~RegVH9E;vVZ?I_>~SG>0nIkfTSHwJk! zkMQ5#wFNN&#Uvi5h8hP@8gBX9(RL>n6@Y%dhWmN?YMfbe$n;pbA3%YFlY{2%_fu^7 zquRkO^m@-UH zz)!zu29-^Sy7|3~YQZOUYxpSqH+q@`4kL5J`xRxB?|M4t>k>vabH4OrHhT`^i76s~Tg_G@#?RlkAXf~$RB zw|e6oLk+8zbL(!otCQ=-A`&4KEP!nAZL2Egmi>_smz(K$go-_C9ep;)(5dKu85WE`d z*Qv-K>TAEB<{!^VFqDw+quMl6*xo6LN1v4f3nsQA%jvI|rQX&qxB$nv4fg2(j@in+ zdWl69#Wt~i^To@qGkVEc}=;qibdhA7L!Ddxn4wAx?GFT~7-nin?L*vy-ncaz9HV@rws zbz!G(b;G4c;94hh>KJ$s!#3JU zzPeI4GxNx!i)Uc8$xSMxevZYXz9?k0xN-Eji9Im9NyiS;K#8eD*5j>*brqwi;;+XQ zus<7bev>PB)roa3pP~MKNX}kb(bzI<2A`dO?lGXnCM#2c+Db(|x3G0i<0T5Oriy}M z_5L+0KW^fYwz^SvrgL0W6Ow5H;_#|(nyI~m2ll(Y>6*F7qZq=gKKeahBX0%bG*;|T+A@w=sJJ~f)ZVXu$R z5;NP)8Z1r7(PA=f%4NZyFNbp0tMX+zGXr07lGyhVfC-sD&+oR-fx0`NcfCb1soHN@ zQHzmJxxl5<1;bnwYuh4Tm}(%;W=>{Rt@c?2Iph;NxQS1JhIq#G`N z)`}W#t%R!-ETENHs8*ud)qLXx3mSAHGDqLhG1pS?{!qo));qT_Ta`3N>YMrH6stBr z*ERqDP%)?!y%cX4uiu^^E8ndt*U+(;q^yGk%_PA+}gJBFk*@z zo=?5xM#MWrV$8HycGyWRsWbvJ+=p=J8#iVymF!gN3rI;L z;EEWGNo`rMigs`eFt`_EA3JtZp$W@6+`2it0a8s;K%AQyY#I4e-1hae{h9d^r6htf zW6$>6hI@HIAP>hEOM~_EGxkmBU}kEk@R|}`I{q0JkCdVi1zWD(iEkX}+k((z1_spd zh5VKR7~T;dX(8nWHtg%RwSxDp4~0alNrBmKn2vvcP54ES3qho#><4n-7e!L6aK%{g-T)hBo`pg>>w@=dZ%cE z_j8k$7kn@`Xr@wcz>r)O)K1b?h{jbqBq@$8L6>|8Y%3v|zi>>SMbC0b zp_+6Ar#fQ}_Oesl$JV=>E@V(gsceysag-i&eGqF&&9Zj)k0-%bzfj9A1SZObsHh|M z&CJY3myl$HVwMP$tZn^PdXIzr85}%=&@T3QJ9wsDvUF%h;5Ba(IhWX&D5+%ck;-%$ zl4?xX9D0%1zf*4_5`~=2gqU0?H1(>H0ypZma)p(^jk;wUH=_ZpH+PuS81TreWo{)b@?$ZV52Vka|W#jFZ#SimXTm)}zI9-SDrQ1Xv>4EK@w z@YTZVYNh)weTp1PLnHrtV920*T-(DEb-5qH56(g-Ax5EZ{u*|&A&`)4C;k-r$XPR? zpqz5lgWM0TCOOm;1hg~!@+tX(NWmqsWja{x*ULA*28Ug&6A(4;vYqj35LKP2WyB0r zKtCLOT>IJwlPL8;PlivAPWT!KA?-{c(9`DwAFs?5OK2WkN&(+9wgRM zVtFuUWJDZGN}Df@MYAeFeLTVBOGjBSQImz$q4b2dGm)b@+tH zwIVdO^h>k{d7-74xNVw$ZgQ3=H0I2>Q)!auQjwiMVm6R3ewivSL6Zk+NEV=ml-Jbw z2sXSw@^$%To8Q^n^>;>O@GiR+-x(!8I)|rwkdUB^3dPE#uQpJXzLE~`quy=A8IJ`+ zSbQcMQ{F!gKnJ>b?!&l^ZIYz-bbP`vr)YuaOjuGVUsArQ)9?w45k``KJ5D>(Mw1V; zUuiBWDo(9on0@L-KC2MFgZIs0clkgaEHBIO9TR*g?}+X^4=z!%22Hxo*C~CN2dApY zXrp?Pa<$~NUQHAF;>rMCek;I= z1#wiIhno6Mv;lx%uk~wwta~a@%ZGr24I=wjOiG=IfOG{ctUF#)89O4eIMltMkZ+q% zUHS;@=3wY<9>+qko?}Snjh-5iWl-XIC2kQtpvFdgpx8T+KoWj#G}r1jzg?69mR3Wr zm52hnv_+1nX>jqR?A75AoM6GDNKRaag?EhIHxhXmYMvL&SV$$=d&Rc;p>IE(>h1NUd4 zV5(j61A~2)jGwh%7itn^tb8J3M}?A~>U3I9T-3g);bPTF+@kMs8)}H~G)_Hr;wNBH zu-;B+)I9nF_Sb!Vpg%g&@u>{>}FX$!EU5#ewquLGs^x&)w6xi;A66 ze&%}s4RA`d^fu+oyUz+p3U8HEX4=9FxcWkwJn^p}MSFvEQn&0cAOnDAIq2nagp!Rx zo>|QtQX*37QEUo0>XVaP1Vd#m=^#y<@&OMHk$KG-*T)wPLk@r{2nz5HIGwMRmx@>gQp^Gz;b^VPG>x&q^nsX}@VAlw|Rx%(cs9er;lO~OX!{wNwcegs0!0famq2)PLm z@^m2N3P8yDDh7!q{O4h&o7YJcV3SniqC=)&B$%he;Z)OK}#h*Dg#S|9r+ zE|Gcr8CPBO|1;z?B>xUMN-Pla6eer_{|fogKOuK{4*Af(Lry0kn3_n-ROeq?WXh3} zNK5(Vo5m5RMP}xtW_3(!Lv(vr$Nl-w9k1KPF^eS=->2=qP2gox=v$%;0q#WJKL%#c zxSo6y*3J_SX!$;g=_RC9U9DG4PdHb35^t5L57`IB@f%`~W2ex4O zUL7U^BSBAI{vbAyOs^J4q<>#-F)4F4p6af)#miJ4zt0_EOR&&kUVln#PfCi7JH(L6ua(v56wkL|k2sCebN`9z4 z@syb6DTji}&TS^_x)fJr;sG6=+Hf3uUfW<}droqM)Ob#&3vpZ>8Q^dA0*gxM zIhi6Aq?o~1dt79>Ep}?H0m_nVHYiIRlU{S}pD@Ko>u|VV8Auqc^M3Hx{;S@byx$hP z?MXtf0IdNy=>3VH`Gil^n^|4!78_FA`6+Gd+su^bb3*Z-Pxjw3G8Sc!{R4jL=9Q6F zSO*t^IA*O%do}t*pGE3()a0a-(D~`E3Krtr#hng!$3}{c4aw^)2aDoEFx)G8p&LI3 z#-#zz4yJ;?KT+Qw=;EJ57-W;wd8l#F7OS@YZ28@@<;Q^KBpiq{3WN#oNr>v&8@$QKAY_RC25&lCH6ET9(9fSJL>QzcX{G1LZ1iE$ zrx(DnL*s9smJ-fHb1J9{$F8f{$dyflwm+EcZToXCOlB?2g4jDhln z11MkCYD#?7B-EEq-nKs;r9O5e(!U10xWR=?%l3Yr;)x+vn1-RPE^PV_SI8mfnI8t; z(RoebfPQ@3=ZR1Vp4W>*PX7X{@CCuJSZ%{S5w4n^AhZ+BR2VtVW203=GZ!3>u4 zR;23uWNiVCZKUdNJYL!9-F$jN!!KAIeDLY7N!pdb-wx?841pVYb(_$I(-bU|;n$_s=`?87N#N7x)Pq*dbU()-0{r#|0^I*|gF<8f_Xfq- zZcQwf9)eb#3f)&{YB8Zlz}-A5UeCFQzz~{yRJ@*Z&ln6u5v^Li^i)vx<9uQ?)LgGW z2*8>Ps$YD=|0~!B{}t>orsbjnlmCu&FMc}RnVDggc)|Zw56Emv{ktCcI3ILS3)BN~ z-ehQ!CQB;j6p;6^UxI7^5RTo95188-`y+sbUiBD2@~7NJ=7Xp$q@ELCN?D^YnEhi1 z?c#eh8B~>0tj`6wr72}-FX0qtkU-QnDM;RA)Z7ohWLia)+ z6$}UsC2Tf%RbEuPSASM0{YZqVY%a&zo-T%-LAsK`&qcu6P6+l*5rr)D*nQLU!Wisf z{yUJcU-roWF(c$7ku93JZNsT}lJ*cjg&NRU#T7CcS7K>%9=f&K(804;%mWx-%3pS?zm3raFv{(5l z3KXvPN&5`WwB}{N_jlkjh6xR^X_HEU&zRq#ZRaE4a@Y030Dqhp9S`c%xmg-a*7Mpt zm4wXnd?NWCU;1q&oK}4j)@IT}RL>Z>=#P^-kEJN4%-P#mg#k7X0&_G>nG&Y>(pgwk zMMHXZHyJR4`X~6QZUO4aQd6!<^7yG!#iadRL2A~TBy|0jD24J8q>Q=hDTZlKza&Ic zBUAx=xcjz-2boSs2sz{6Fm`ZeBM5}=!j(Nl0x*S@0!g8Xexnp38OxNu4B4bWfFoUalif&r4UmW6| ztOWUabwQ<*36EQmovlFjFYoqa%x&F7&*^v)OJ7+eDey&;y;SdmMdctG)bJ1uAm&g|q^AwME(lCIG|mKszoeOqtM)ps&B% z7Bu6T0N){^5G`an9`6(dcVxOOX&Uu$*eE4}B%AG^jrB?S}#mOKgkB7mg%^;-AAq8z-525Q^*^dqbXb zZOhGH!jS5p)hup5l$DhO{QR#E?$eYL>;Kw%-lf3vQ?I$7RJFdUNk08^x_S5ayz#}? zsYj3N`_Q|yBC{oL{{Dnt>R0)E=fSY~ z)cIh_rFRa_T`%xEe``#?(;z5xdwVrBvXx{O&}q`Qmb?DACPMB8K9x^BI5b@{K*q~; zq>IkQW8CzZRn4KK!E%`OPH#j&Lr>I;GBbfK)&B7z zM!sytZJn+3!~OkPd=9*kSYk_2neXC^P>KfmpX-O~^D!-=z=dDdS8gZP=!sas$fx@K z2*u_^-#Z)nw4Set@3Cys^aW5`ew{OV4r%UZBuWgur;osGl#9)1Ed2!+kttWTs}l6C z;TPn${m{4UpeqTC1BgtRJR4Y5j_sq|i^!cxwiXvV$F^U2ba}t_Y$gflGUQ`@{%)_e z{({hq9H0HF=jPYR2-5!`Dqe{8D>)kx*RPpelrV}Tp6N53Ia*4PZFxJ1g@+VKG>EKSk%v;cy$j#nNz9{FuHU-q7WXmcqR=v z+_6Fo^ILZvvO!KbSx@UK>LGMG5vyF^Y|(J_LI&zwmwy{O-YNKBABo_?GPd_cv}dn7 z!Oc@eh6`Tyhu4nbtN6|DiKv5C*wE^ z;el=W`R~yD=5zo5IcNhjUo~ifkm!>bht01|x2l~1b&%3+nuISXLfki)E=9t%8gFQ=qUWjtok&lUWBSEu8H`%D zTP61(+_b(KsNhABWF|*^h?GTlasOvFUd(sWys^X1FGuvVG-5|O3}uc$SnL-(?v#pq z&LEMx8M6r=J<~YlBN78!teDt%wU$@r885*u%EwpYwsXEdTBpD`s}xY8^2xNHu@^OR zmE3ZfGA3d9O!0jT+bZ%qX_?Yfyt+{%Z`I9LH$E?Uncs>qKZa>hs7XES`yXJTr%^i` zz7^03n<<9*%!Y^p{r{@sgIp4F^m!|XA7?6HuPRXR_1t9$NJ?(@MLG0CzE&b^8{??u z65@BM4Y#!{-LxbT&Zu)TLaj1Yfm)>%>Z65;Rw-B%O+9mu|B{$ZY-ujcr3R%`m0+pU z*Vo%S&@Uh`;Lm@IrIL*O2AzH;8A$&NzCucprR~L360-7R$Sh>JuT^&n|66sFW?7SW zFCF)e7;Xu~gm|-GUF{RS;DxJLNxc`Sy!Cre#!o6whI>&W_LmSGq=TL5qn#jX&dYMG zaVpQa4;GpM6*EarvV==7-9}q`^y?lRWQx%jtr8hJ2Y=!O)2pdfCnWWa7W^z6_t&&% z9d3DK^Q&7K$dOqk``@OcIi;5^=D@?iqyWP`@qpo4UiR#6))o#H|NP4dor^ZAJ>;2g38xYdE#ZGANs3@n?P9D? z5NQW;?X0T5oX%o@{HD8p!-#dxv3)l6bme+sv*W9VLy4Q}+ImSTMLnb}To1@xict>O|lehgsS}BYFn09Tp5ej>vQ`B+O&w!!Z%D#7G@w+rO!= zu|=K9wKw#YJPcuGa}v{(CpkJO=N=z-&Xg_c0uy)I_7nkiWwE>_-Locr|1?D-CE6Vn zq*sYX&KhSuO%)dt?88MJ6R!7a3!Kubm!++Fr^A(D0PDX;Vu8pb_k(x7aCy3o8+=VA zCq!4_;wr0SkscqPI&0&Z6-cn6-jKtWD0t}xDx02|NFQGlw{xIDUh8f?!jJLAk`Huw z6J9PM8V#lj4(>725fiC$ zN=ht^CFU6VlDMaho)7uGx6?0CH*IrLDIS%^-*YI}QV2o4WYv2Q(bKtDbKDmqgB^-J z$W8;-KaqoR$&`@=gH1pLUrCe3I0#Y`c&|Js(&d(qnney8P?&MmJn)xCF~}9aLPDJ^ zrx&)VgO$)$Zt8H3O;?SLR@{}FY&*zCc)sN9H%A|5u3FxCD6W~#@~B3n)H=5N4)q`I zq|A%udw4{pH3fXqt526u33{0l}u+L3&zV!OT!M4%!B)tC~u#B3*Xi5T%UN)hD zfx-Ak&aQ6W_7<*CA^+BUA6NJqKcIT%Dah*wTt+;G>Yyz*Nl{9pCOAXR-@Th|jx;ic zTfXri@T4|)LtlpaWxaZ-H!AUc*2zj7Mv}6wWP|poTH^OAM}H1?jDY~$c(46~z)r7@ zgeow3A8dhajDi0r^~dSUc_Rj@YKsbU8tJ${lHaXlGs7O>CwLP%=-#{uKO~L~eu&0Z>5NUZAhQfq zzK$`FwK3*+kPExL+^178&9M!rixMElvu6TR1b#|7seP66&6?9eP&UxIIZjW4+M9Ufd;msC~YMrs90yn~^tVvxoNV;F5cqEN@lfdR*#6&)9;s)$8jG}NK z+jnZPL#Z#cZ-mwVR%xsuxf$v;_}ltuO&MT+mTdn2 z*n8`!I)Y_i7zq~K-Gc>}1cwlUI|O%kcXxLQ?(XgyAh^4`yE~ix?c~V4-@WHtS?j$& z-dbl(k5o^0P0g>ns(0;a`T5fUVkt-;%iSgqbAfT?(>n=-Q051H&WoN?3PJTUYj*7z z%7k|ieb;h`a$>r+dZV&FVJ?;s$1x%~gDpFY<6pke;}Y^7#;oj&-yt_EB6IB-rTMpf z#1Dl`-}*ThEWg`!eC5?1)vy?lg_lfM3}S=Il%DGQl2?Ak)&$lnr4vO*flHEO{4#hxV>B zWDzNfDX8mbR#bZj3}~s~!H`<{?@sNUhe$KNXm(VXUK~I_2}0>EjFjM;wEn#|hoaPP zDhA&MtN03URSkN&dP-%2J(2^}+C$qzynUY`J=+dzM`wTN>Z}4MH6wNp-15f?! zF*WJooe_>@dBJ`{U}`88LsxH6E18>g6sp%8ptOZqx{>kw9#b~;E0bEiQ+ z)Sh#Ql+^KoE`Bi4oRlGt^x37dbrMjoIT_;u%S+;TA$$})7s#Sf?MEHYFyr#IH1#U0 zKoj=zsS5>^BTq2Lo3g^6M9wn*bZ_m2+UjDh_v%iGV2i~X7o)cuDG9LK<+JQXhh0sF z!@<};){hf*AH_EMH1D7tO7{qGV}of;;VwZ+qP?cmF_u>gm(kGAiO+MA?SOiCDf z+O9ns2xDI;I)1p*T#_8LQ}qeZE~qAX*oRsv@!dO7Pu{Ls2iIcTU~{a^o;VA%Ss^J|HNJQXX@>lK9K&pj`ixUIVwD{pbEH)Rtial`4BrR^TnvSg zM@MYNh;oK5a|bVHP@8TGWt9OL*4GvK+OY7ya)!#J3xJQ2lu0-2woqVOZ|}J-M8O;Q zg9V!iK8>8`lqoNCZTVP`+1%>Q6YqZ7iVFb6X!ohZnp1y%s=flG_DDcJE_{w?e%_F& ziynU+I(ZP@x0uD}(P=wataF_p;u+t!pJ0C3-{BvA0Au$+B;nWgVTCqllBV%s{rO%O z{&He2xr~;b)5G-}c(vjwXwbA*BYoWgZ?cj#)3>~JlSiEgo|WT?VE?7~v!(Y=FT+*P zlD)Op7s&5i+(*R%XhJ2_e_+Xrbc@=!3&ZBs2grHivjDLF(N7|PCgT)<5DZMR9SjWP zuQt>~*Ur#D!NJbd%J`2dP1iKH#vh0S5Rm|NH^F=n4XW4#c~8?gurVm8z8Q$;9R9l2 z6ELwHMkP~Fixsy62R@!vo*z|KD$AV1;OlifGat-4EU*P{08Xl8n#PFBg2%?zp7-MK ziQ8mS=bk~+IHuhVB+0DPX#o~)sK$)k8{TXj-J7&JJgzV1_J_JUf!E;|pVKUNJQmWD zWV}|aE`Tj{b*{jb}q9ps@5e}S?pb)>0bM`cRiHR z8snxITu^8%UtNOOaZa9$7AaZmyi3 z`0&0Z&Jma$WvcLzy{o0A^inN=i<6sVV0`%A>#m>pK;6~R5;8)Hz-XmDN?j}rb6cFi zC<@-MQ#EL2K~oggbkNBRg|)nY%cS>v{}3wv4mJ5+apZk^^h}D4bqd@=;=enIon5mr zWxzdj;>tkG;7)+gq{Kj^%i@K`fTb6(Vfns|$3+@-hwvN6v15yj>?~m1k?ciqr2y^v zlPI-@7eG5UmDaE_Xioy|{j-d1scCn?bK3PA+}u`#&faxKWmR=&)@3kFUo^BgJUl#_ zui@E^ST#4Qq3}kO=w!}Lo6~6OpZ2h|JykR}%9SJI(?_+U8NKk>+q`)Us5I303^sSk`_d)jTH;hlwv8NCnGHU3y{69RV|vG{WkZ(N>u`B~plb{K zc-zR)>%k|5#%v2iLzrP{rKm5QaX;L%SL1)YWP8-CCe6V#K2Iv~H_b6xIO0>5t!Xzd z2lU~x()HAiV(CKAhcku8L1pW{*(2k_fJ3Kcj|HVu#9GORx!W^mGA>^4rBjq& zJ;^z<=$q$04V^HLJnDDKZ$8vL8PrAyBu$1UT8~F9THb{)sy?=cGJY73)^J#VnuMx) zuW3V`uV6cRao?`s;UMy=MF^9wj(;^z$us?}`Q%3NUD{RdC+E-y7yVN{4%B%x3n$Y} zPhAXWv>kFw)-AOLr6Tsdvd=_#*`2A17_>7=Ca z`RaJ9m)5&?3W32Z#iaCR?zy**v2>@4Jv{B9t8BbVabP5TNYAUZ#G6;kr1a_Q*~!p% z#W62e%LeCHxANBKzBHBtsxA!;tzto*6q#|Yi{;~aCFe#rgR%#UyUs!_NlLS(4C%AF znG!-R$=PuRN;45`^t^Z&Hz4w-xkr_baW04`$GMiMe$%3_kfrc?zWJE6A1YMHO#AS} zs1iN7TF%L_ytrzFr$Y;}q{{&g+lySb78x9k(gZ7_ps)%M!RP^VVH~KCfb^evM~{{!P%IDbg`V<0Q2|u_%FRY$4;`zDhncfZmKlAN!mv|e29a_Y`s+ubs>562mgNtj9Ik$xsa z)p8B1K^j>S8dreVH%8UZ`>3f8sG0jzG)(PhqOxIM22dx}^&S*>V@&f{Zg_aM0p@`# zp8LuXptXT5j?7=5-Oy4^z=+>Wf4-EBl`a8{RWhFKX4c5dCA&uj`xdmvDR1)j4R^4s z)8=}KozsBp0AlyK_vgZm5?gbbg->6isdV_%J`-245Kqb@r2V0o5M`Db7WjnhG}69ZuBPCs^+=FFV=S`?>^**|#C zqaFT^!&pZAX{s!iyY`!4`$Ke_vV#?ALKXdv!c2F9v{_cP0o^z%_M3_IRdBPRC$JVY zZc0REw}NSYK9nAAL06MW8re{4dMJZ=uywnay154pC|u7hKbTllg$B~~8c)duf|I9# z%k-jlBg^beofdGLJe2z?U|ebo-cGzuGZ4|9YVIpEA@MwQKk!8tDraVmVaLssT^*S^ zv^oXf^kA4spPw+DRdSo{A%SBNj(LV+c`A!8Bx`QCS!46#<9j-{-?R$E2Oz!a(h$G~ z==p{_+DmmzuH(BlU^3PV3TbKfnU7W_r2Vupkh|E5J=_})zPBeo-oeUF4xMmmT`qiF z{6RdhH$aZe!sj{}GSxoWhmbxgI4gigukQApjQc^(EeeM|z!1%*J(z}0-MW(5Wqcz& zvy+pNNPC@seVuO|oA2p8>LzB?w=|29b?1+@F$uEJG@ zaNDPf5p#(Tt`=7QV)VJqO3@U1o=wxu4{pRg^8Zdnb_hDvZ}*8JYe63gOo$SLoOPU| z?hz8+L-^@|ltWdbU=@$i{OF92_35`QsN!z3?ZR$gNR%BI^n!HpM5mI|+Df9{L!uWy zHAy`$V?~hx%wpQlNFM-g?~gWYr@QJzfzqS^?(o0JB9ZwQSx~2oDnUP7ZcEsEMUgF8 zr(sH@X(mA@)4uRnqIQI7|IAoEQCdspY5ybvw@K{$Xx6D44y2mLWHDlHMH9{=d-8WtXe2g~|lT9rsDc!hPHP7*Sz!UH+byPtn6t)renDyblvPz^OZe&%sEl zW3d?m+igtup^6lpz>Ty}RyVJk8AEeCzZ^2;yb!Iynz-sRQWU=+8v%)jabckzQ zO9WA^5KY}X9};YM2vG`5dY06%G2c{dFc%YN*$MchhW5?DU1ayo_Dx;w71BdjQiP>- z@>dbpElqmHcJymMdzLUrY1#v*BBptGKYR_bhcnrFMUPGNhKABA#L9e8rM6MxRN>r z?m^9Btng)@=2u{YN%g%6jKS-KeMY%!zpPBeCP*>Sx~#6UB)e@#G3s3x2FawWK|>Vr z#Gq$E5m*z4-mfISDIJ4~WFrhqNC6)R8HXYdQrQ-7(GJ{1q-@JZcUXB(IV874ct22m zX90J?g?~3$$Abc@@G4kfjQX}<&tx#aQVyHIY(x46(!unK-qUX|>*jCxkHHoe~wztR~E0oC~}P@NBhnIw+CE4cV6)gu>pE0TUIf^`&)F-@$Re;{om zgv5L#C<2#)40ogelIGv*UJ=HBqkFCd|DEm;D~fvm`p>$T|MeM;3h;{z@QoC7wlYrX)JPH7uZk;Nf$pDUmvon zYUD=Tj zEIdJXXDF>4)_Hl33B0)ds_NI5cU`3U$j3kC&~n71D_ z1;P*Ua*rIw?kO}C7%^Jyx;|<$Ueo$0PLttFYMy>X!@-xu)6Wn!8o{lU!l#yk`9hr* zy$!c!*yt$}us$a${p?#T{Ryoh1TmL)4&hRm#>XW*)Mqi<;maq;W#JNEmvA`0#b0dQ zMyK|@g}$L4+d70sWa;1X`&mEysx*az`ibLaEiyKFXBxQpaR^Gaga&#k`gG)7y{EtxA&s-63u?Nro3}!sT1%DYiBXA6UOyCBATp z4)#&o9}oRAS4c!8m-rGj7H3)W&(mlKQ#oun;v43UTIJDl>(*1T$fg$EZyFyGIO66) zT18D>NUn{DV>?tM55ohTxI=y}i5S=@iM-#r^0vAhyri1YTg88cyGah1z>aDxW5#7d zYc1>_*17&ZZuCCM-&cG;Ti7BB+>whsI&Pwc_I(bNOyrc*bHCIp0O_h&bC#ZpKgzf+ zUP1Cy>k}VeCi|g;-`fp4qU~!T+yPl?(YL9`q&2q7#;`}s&htz zs`XLIZ1uHPYr^Z|bI%CG_8WnyFxcT-H~Amd>!g}rt;u!AwHCDN7ukNATH_8V^pm9+ zTXUWd2$QppxQHD}-h{k8Z-yJ@*Q`rJ*+*mEjD2~hTH#x+B%;(-AM=BNrZ(=Ypwfyq zT!PI`bouVm16KqchN7@i*l^5V|CF`@qUulzDLkk7;4)+E+yEKJV$tAmY>HuMIhz9! zGdZnBIah7IHFWUJ&=uO^#VpC-F@k|3S1lL1>QF2hEe)GNi@%)sxE;M2C%n*)*dMtp z206uewQ;P1Sa$O=07R%%vpG&rJKf~fsyElDznhdYRO zG>DfnC?18ODwacPo=-N?P)z!dxT*Ywo9KVyCU!CPle6ra2+^;c7gE)ot9Etxr;0I! zNLYFPWXz9wic_nQd9qupklf)xaXH*t+3$aUX*aDuJTKG9Xhny zhoh-_()sygW2kbn)X~NM2pT6hG6)P;6iK`tCyXc`=5~gyMM5wjJRG#6g@pVYj0KKx zf>>(dvLN_aK!0ZkfjA2)*%=Lf9e-cjx&~rdjs`Oxc8X|kV5CY$i7NV=A`Mj_A8KHcCMoNhPICI`Bn%32ZbEQXxAf*>DLS&?$;+<282ri)pldTv{)dv{ z)lT=bkQ9PS+~;#jM}}W{JK{Ma`LxU55nT=fA!?22%l7@(Z3 z0i^I1Le!wb!BwUCD2NqSN=nPgYCvj?sA{T@>oWqloPEKiCpt-P-Np8n_`?m10C{QfNxj3UN1?<+j)~TDYdwj($W79o1ih z{&x9PM`t~^M;qwc!J^GLhTq^?FRH6jrhE{2{TlP!E|*=Ue8{bqlO%CF9zl1hULkxT z2{)fW))5_A{kd6On|?-lU00&U2=iDyPyWKeNK3)|jeH@7ySm_o5~Mfwaji-C zZ2d^Gykzc$;Co-HR@XyCsY;pBWrnlI?yrj+NVCVKj19pP#n-6sR|;$pBuf1v`bLEx zs%Qc|7TCtk1!!v8+O*;0)+GpVb-v%Ix20dqF1uBzO*(fjD~N8ChBcT; z@x$z^;LFZUoD-PewR(XDg45uEqtKq_F|#W8eJZHGNbOg_S6ji>zS7n?yHI>slaatx zVLg7S(A;!3Lo}a5>$*{_F~WGVkH1X&*u$AYkgRX{C4;}szI=`rKv;5HWb*Dy`Rs); z*L8RbS~*Rh*8*Gr@}ybUqXG)l{HdFFYao$~@ud_Es+m?OvX5_#OC>tn?RP5JKGuw| zCspn+?G^F0k41AOFZ;II$#NUi=e{*ezS#K>Qe>|bu?|YL%DJGy;HvkB?~JV(GdE6u z=<~GN)cjf~yt_Z#HA2G#hy~Ant#&bEjlQ#wABY9sgZ{otn%sCSH>wJbXroMFyrb*qx(gpWmUvf188vR?N2SpIzC;^l z@0k)8ijM)P&5OgB;UuecPBJ`og`)qf+$g%ZbRHd7fyK=wVpnBSi?U1q1 zwDzNHcIxA|z%p=Q-#zTC$*}8U@>{i4hL&sX%4)wGz3+L!e zg2At&Ur07l1A#0sJe#fs=i9I+s^`;zDV|sJL7y$yfgbVA#vArGH}{@Cg4#_ov){rU z>DRrOBgYI1*-W(*FKBx}Qeamo11Ze=g${kj`?{W5`4^BpLIroWLsqeGlDrN*r!Zv( z8NmfCEF(Xrw3S3{fR-yDV;dRs5A@I`*m}`>X4>q8jZ6Z`0QK@mhD6UHq3VTZ*x|Tv z0fRoq7TEh`kW`)n_RLY3E?A(_jC$x>^h!i$*pGq2mXpB4juqR$4h`4AYFPx*13aRm zbt~iqEkCyBVlT5^gcrx{^#``E0=^#T9epy0e9uTe-`p(HoV*b%)pA&>lpg+6u{h2H z{E&p-ZgAd=qdkNO-Q&s3j*P{EZJ(!uQP&N|@O6g*+h4Ss?@tjL{zmT;gWsRBz4|MH z`=87RXfNra$bp0{I4cu&{~oTY&R;@I;ToqvrRHMd@jJwX2O$^{^T@D|p2>g8vS0y) zp$FdQ6T>;^jhtl_7+On-4)naxKkeoI5y=0HlGY)772Ezsht!^#{k?E+3#`=dBKxOs z;bBjy=K?(c4wpv6nK9><9+IjJYD2y)YRau=Y%{D;Y&c-!J@(zsXs2&nI8qcAwj2e9 zJt|kWea$UikC2OFRev93Pv7ga@vzVXPm=xBmx?vf{iyIOs9CGpuT8N3J9#A1c(Hd> ze2r}ho-PLeY3Wti$nk@n<5RaBZkpJlW?&9z1Rx!1&~*gapsp8}*I?&<-XdV~Oj?Z1`JKd(>7p_S;b@W^j`+H%Xw>b@VYEj!ok znp1SpSXoSbT2AxgS)d&eUQ^I6lXHk`nl84LpJ`Z*6Onq`Em7SN9^f)ZTrqT1Q?A0C z51tzYur(PWG81izQ^0ytjuBi{`;o9&U`c|;Jzl{ij0OcO@@MPXJ0Ffi?P*J0-6$*( z3%_*Qm`x43%wFJ=nd^Exbc6CZ(nl<|Uo`FZZz!F=PI*m+jD1*$qgzm#)~F|*txl;` zi>q4}pANhC$NM~^Byp{zE~YW%CEAV?}@SYsEaCuBMH!!M19nv^= zh+VR&C-yszO=%GZF@j`r>V;g;2yg1~&utqx1MJ)%ZC3!03R-sYk>JPu%~eXqHt;+n z6X$T<>}~6LyejzS-ka5{yobos-DNJnvTwVxUw(A0xZ0GneBJhFO;3Nz*Df;A(WbL@ zu;rQ4e!;&rL7D2s5vm_VR9^|x@i0Q(*?yEHhK{)Lv(oW)X?AZf>Iv@~;;aLGWK2Oo zNTOoJ+k9PESiLuR8^Mis1AQ9|2yY^c1JCY0(bSXO{y>5m+89%YB-KpG2rNVVsvL1 zI#VH~rNu)BVpK5UYXapy0C0M}el68R!Ii}D?JtRix-tzth2u|_mzr5#Ys1ttN;h24 z?RqNvbMeZnzMV#S67yK)b&ZQ&PXvf@#^~_nigFGLon8Cr37k0JXPSE=y(_dF9l5!O z`$q_%|Dr?h`JW*0XKDApAz;?ag!1ho@YR3O{R4NfY#4>MIOzf<08B`0CHG$3q>19` ze%KL=mUMnJdaWsCYIK0D?f|KH2%1050NWbj{uw)LHUBFKo}2 z0~hx{f`ILJN38!p1ipVDpbC`t+tc_;vhW!Irl>VS_8WqNr>Avim7&z!}^ ziVCGWb%cCBRKzD=ed*P9s`Uj_3)T`~LA79O){^~0K$QrQt`clMBN6|Ip3bS}~jA(|NS2GxRrKM=SI z#=6CnE&upk3qGkIPytZkBo|WqZqEPVI=h02sCoY*2tNH&2onAuhrr;5jqHB}!RLPp z!Q}tr5J;+hbo(0wAO1^g_)m>N5sX6Eo`yKdZ)2eN7h}Lq`u1}8H%%D3VwO3MN)h}3 z52NY(^|}V0P35sQ^WHjJg}~7&EC373fTOW3X&;@6s^FKtXn9!RVh?rP`d>6*AmFp!gr!Hw@mS^~aQT0Vo9 zwkHam{+P6qxOteX`5Z_TJkYMYJoCU)!bnGeuDW;vjS(l~nXj`2a9Zl{(X*Xxqd`@3 zA?Ynyv07G6PoG7LX09v6(u2K7X83n$6~t~dqF1Q7|9hV0s=3<-RHB^!~e-GF8rQrB4=Av{vUTV`cVIhgcu5u?k@a za^7$Jo^b(p!Qj#*xw%H=G}ci)b3|54cPRJmm!kW0-#)ttFA-EC4+rCcgYL?a>H^mF z`wB+a`$p0QcRBp5%;SaVHb&8vw>Slrywps0jjwrP&wJ4a>UXE3 z)0f7)ZAn8xOYhACUNiSc(;OKejfSMLXo4lX+joVqIqi70xmMMC9u>FwyrrM-lbkF_ zIdPGg;SrJhLi^e?_L%E#>yAPvWEhAs##&->mYaBE43kbR)f(C}tEA zwE&bQ+JsEZrQ1fh%B2xO!-YjN*9>MJai+>QyjPEN{uu+#bcwSr`n5c9o{ILpS=UK# zyy1+{xYg^}7TT6fHQv%2wq>}?OBT||Qr@2k=51(I^!GZ|YGr%M1L#HC#Y^oKo-;;f zZoJ!SJgCbax#@vV-Bjac&TaR5Ygz_ZCr8R>DOl0zDP#%yQ4&@)dRMxtEEG`}cj>oH zO~_j3d*=`EMtiX5ZP^6HyAAi-(J{>=ne6SEJXPaI(uRN+m%Hg%^7i5Tn~yH=L(pfA@y>DT1S*-|(y3z4S_we5ZqM9?;&p5~A|$q7`40 zRzHH@Q_TK(hxF3yyexAKu|XPQ0F7^gwTgSLUr&G1j&G}Nr6F)+rW~4w364cimT|1F6$HcY-9Pj_7!-Tb0-)<8~F`RX?EO!Fi*j zZ@v7c+%#O}Dd$ywAe^4XxKEL9eod_sC3Y{b&8gKIH`sgQ0}-j5snguYs@(-62o1Af z{0069&D;$7v&^CiO7F`I|P@c+8ZQ&*?5D=OY{$s({SI za=)y3MDI5AOqMoEwTaF_j+5mQFnF4UUb9Z&?P)Qytx;iZB$jenl%ZqoMs?kOqWQWC z^h91!Ri*3NMe9AK0`I8_!}N>~cIFpY-pN_**~(u& zbhIWqpG}O(u9>75%hKz00prV{MogCR5q+mna1eb_u^>Qg&i|2SiS=L2(!ZLee>F@0 zYL@=hEd8rl`oGmIiAqpFN&K(8CAQzq(rKb9$E+vD0B}a7Unx-lH?IcWtkw{>*0?nG zgZ@~j5ppQ$N{CXVK}SM;3Ut|e2p*n)t`aZS6tc;cDG+9@;W@bBdx=J&{2i3+y@m8H8e1HMyT&Q z^n6JO!Z1l^WdlqvlN^?2CGM$cB^ocz0L6@c#zomDtc=OcS zz%XVit$pkhvzKUFHFPQ?iD|1yeU`7fUjG>ibHPDZo6t32D2))+XDx*#$YSHyM!RSI ziH(klarypq6{B!j%982A9Wz+9Xy3%`!;`@@GE`7|exQ_kU-nsP5F%9yN)lQPYqTaq ziMl}G(bhnx@?n*DqPad7rMkL@77ytjwdXXQ^QIA4_FX|vj~h3pq29Fovd@#n0BV_& z%;S~28bsd+n(eH#R_93(b81pxt(A1)GQ~xXXN*GpeMVsXt09X_^XGv`GDaQT4s`R; zE%$w0^R?{_%9#L{RiYq2-nL|Vp%YF>E&Gp=P$P5B-_d?KZ5QW%|_=zJ7K zyJ8b26+v~KvSWtTr*x$}=EF*>7Jf&9==by_AJrtO4XMQPX~VQ&KGM;k@kZSqK;oU? zc1GPxe9$u34`O6XGB?gYaro#ojMumq6*C}}NbmC*`e?&ad{{C-nDh$j-T_#9#5i6(X&kK?sk?z7%+w}|&xtt1ZY zj95+AZ;{hhHZeB#>q2tQX+pmaJf0mwTMcP2iJXgBJL2$Z#p#rc8e6}7U!7XNUh6s@ zMY?-;mh^E;Tj17*ufbY!3DK??5p9J_Zb?P4{Bs2B>H=lm5*VgqO zmmOICe2qM#bDbR2QowjYm4=Y}t8~X5bce~Z3Z|*>((rVdd~WNz#3ZPwU(YwQg=0dg zX?y%KjW`fx@Z5L&LRUk2>vDvjy)TYC;R9c5s=_QsDS!TbyCjCQ*tlojJX_(7n#7kB zd|%jXR~hYN-ga62giq60@R@OobIN8;hQU8ChFwv@Sm$dZ=G($2Q5Z`6)GPhS2-0(d zxug7Gy#rIy*nR*_T*tN@?Umpj?2FHiS;JB?^1oF%(Xjja+Os9Feu@qM{EGlG)$S(o3qbRoI(iH_~jg}$WhhH4_g7c zFlyIJQh;_Z+4C0$b3(WqC8&s2j!{8ycqMIf@Q)~yKKO=_uzKjmjC^?(t7UY0=jn05y~Kmc);O;h9!Mgy}d4^OSVUA z%bkQuURXM(RNyd=-!j*K#hyQ6b5GuyrHG8{AU?^vKe1z3r8aAg=&cI5Mr`dKR5{$* zSF|TYx0fTr|1CG^T79BJ_J8Fj zeg3PP#Dn1ma+CD!D)dWo3=#D4DI!iK=;i2Gpcfj`TB{NUjdkUjyl=kbAoh0-Mfdk2X& z`A&c&Rk;S5w4E-bNbYAw5o&wX48KAf7}$#oCht1@5}2$cNvGVk2m}Viw=c2DnbnLw zV5FOrVBioun4407RG&)=pwq$7#Op?l#0nbK`97_H%WdI}v5YW;&taVW0=9Ax!Y|;e z#tyreqj&*#2)wGvYDr9Nep~~&X|3Qww{8dKV(UQ}-U`07D5Q)miY4nuvHJY;wkzqQ zt4C$M5~Ki5K61slorljCxjgU%v09(jgx52^a*BfH##_wa<^v#lbe^i`{f(h+iVThkkR8Ks%o`OYJ%=xAifIaMf@eKCeamC%8CRNh$A$ZNL!qC~M z=i6;{6a59Un!F({r)Ma=Q*~fn&AwwnFWY%y>kd|RG(<|R0=>R3WMahdcB<#XqyZeg z9-30iLY;WBK^UK!#L&3+3y)m&xXA>8pxg2{njL$7s93iOisY}-DN_fPjIUSaxsY1; zTy5}KF=q)$3>TzIrSa=L?V+u=H02p_%~^>RbzI@qA)knrTADS=fr43H7O9(y)Erwp z`;iVrsk}f^S)bv-1HO7g=hz*fg(9}B+@cO4wH=Si8=Hv0zEy3DYy|>UdX&g&60{wkNRX9I>Sop$lOvys-aC2nlqXHC zxDNZRH*O1YHfR>JI(gFTu_3yM>%oq!jh4|jbpbNVcxIbCzxvqA!R0eHw zW2j+F`z|?KGP1tZ?%3F&2r`Xzs-3vn9)~+};#xXmh19tFA-*ForJNlQd`fo8LV1j< z3?^J3PPSc|0MEbn&Ye?1@Kl+juCAk*RG-!z5lkzJ~WTq@?Lg)M2;RD42>z^CVZ6 z;VPygMm4+_K1#&cPWwm{zH%X}@~ah&SQgtpD@@sA6O%wIsp#fcCCW3Odqah|M1HZ6 z@_qpreT2GWj4yTBfl*iFb>BhWdzdi3y3rlx0J56~QJ_|?lz|UXKMw=fh{`pTMb){v z+7rBQee#@GLv#GzymPt`Rst&%bY%S+K9|XEK7`>*vNdt^O+w1@f?d1eEn*v0=$$(wy=^?qThC zk+aGCpP9&3m9Li2Ni7wKVhSYsBxiZW2`!0;FvRDR#Y>YS&5%PE7t+WUI#dG**+oTK zponJ6KUPO$IE@aYZ&3TA$n#nruo{z4gq@3)r`#^8K=W>$eI;t)Woq%r2Cw>by|U2W z)-&%PW?Hxl56%}hY2PqmGhad^(iV$WUGHmV^PZcp=6r ze~MpTB$^l;?2JBF38F4&R_J}L7urRkjhza6CBMK3(G~Ois`u^HY?M1Q;;~Xk42&=DC*tB_wuWLK#o1pEV`bw4XfY3Hj z=RZ2k|7lML_CJkM!kGAuET~a3eJvi>ql2|FV#ZL`!kd~O?`q3Xyh{;|@{rPJ) zC52QhF0Q~n{V$l5Jvz;2usSCSJ|BF*#v<7`2F9=UR z5S*;7$p_RAPNT(P$;CRela#k5T{io7jCgFLo3H+{Rx{5bfbU^$`~~(5Jvc2djslj| zQb!mc1AZVLq`%tQk3EGVioMKiZpjoum~G-99dkEFW$@7=z*mY~CRE2A@4#OEnMUf}^Cktn{3xWJ)#>x?M(B`82a|$iP+IS{= z)^hg={4neM23bctuv*iqsi*8jFA@G&6+}@jL^)%--mI3DQ2P6cDm&b*ry2~-#W&xn z!g1qC-v#)fpg?^60t*XHO7d@nuPrPO*gx`>{TM#doC<@1F*bmMp@33=rcl(^wa^zd z(KWUD-M_~nW3AG%DK_H*a+eTct*FBBmUwaPCztzphceg(1v1H^_=*obI~}>`I-iB@ zciZotyOBuW-DB#EFo&Ks)4N`pfGxV3FVBd~*=j%2*Kj3ws3wXrH z4}7`kdejEqyjgE}U!`fkJ?%_*KVMaO1D}dO5kRl!y>RcB1>m!`*TVoY@Ofau`|S#p z%V_lShOrB{Jpp_@@P2*Rc)L&He|swG0z8g%y#n~Xo?Tz}ynz5>@0Y8r9dF>(MHgU? z|Ltlf+WUELf*)`@(FM3`%IbW*UfFoFl)UWgdOMHqdK$RsYUYbH1{gA3&0%*voje|d zZ|oC$h46nkD(gP{#W3xkFY_UC>E&mY*mF?6wb*l1zDIB$b_+0d)m!Ski}E4s^4G*h z_#C5xR#q2wne_A*s!&BxAP0~rWqkNc5a1T`b3$tY`mO@MoO_cz@W;GdT>T2isJ8L- zheyzGc?%rSMuxp``{J?y+0zD^y5;rYqh?$yk-@9LII#ghV4c|DP2ikA_C;p*4ZQ{U z?eCY-nAUM2_B~>|eA2LjoMaWIcwVh?y!gf)N|@uB9Z32K@WnhpfJ!K8@BarSZ9pY{3ebbLZO!53BzIaKQQ<7H%~*506Cph4;u>i8}Tof8=eey#8**ypNn`6fxIozE(80|e=l;I zz1J`2daW5gx1PygcA#}k|rQeQX|cw?Mcg_oF6mWA2WI&3kW^7Y&;a zIwDgduM^=5zAmb45ANRb${z*%17Hwoy(USv z1bV}~y=@LUZzkK0CRernThfrm2$_%2)}(^>3*qlPzLB&DBjLScH$l0~-a5o(qdt8K zQCZ9qxQ9l9AY!A|n;4D3ZwJHwWaw-?u8Kf65W_bY=1EWz|E;s6|jA4^RR6sX9ie zJSVAm=coWnR2}OF53}758sfKgS#qA$kkNcE@tJ`5H(Bb-GJQyl7MI$)F%&FomqPB;1>mMTOGeL{4J-#NEWyu|~PDk=#H`(Mf5cVOC;ymLH z$>R^YyyAu`i^RTIyS%fcyY2sCeR|W+V_kmJ&tYwG)6Zs2chk>geR|zbXI*~XPi<{+ z-T%Rw?z*4E`t+)wz`FdZAII9_svpCej#)qKpdZP4^s@iGb;M;qw6)}AKZG^H<@j6A zgy(trMgOCf#r$}|iR13pR!n`3GJaiKjZ$)05wGgTsmf??9hyZ^QP;52(GfS?r-0jA z!a%&9vE!Nl5C~zCuKNB{?7vS$SlFi(GFO!L&jWWvR|iU&4EvveE4Hjr&c9*XjvID& zkoMmN?uZn45vtIO<@FJp6WCiQ7=(kZeG$N=(Lmo=RCpR8Haj;?Et!>@T z_J4IF((R-z>Z#nPQ^Gqud&V6#ze6bI8cU#6JwP@?&R{))4BrH!#vG#>UyT(32Pp#= znl88>ixR^K3Idju+CvQjU)v*kisA1Z&!+|m4F%g zBZ3~bWrhQ7ha{q}OZKFTF~~Vh9psx%PO1;OEzkY?QmmdSR*dESE&(SED0S@GZ;4!4 zeqY+Mj`kN)6R2g=m2!j{QLqF>S4ZiToJkZSa}#A{IU1Ie&muw_t9gv$>W)9Z)V{A3V#PeR`kbS ze+QT6g+FmHMK483TQ_osE-^?ljCY4LQ9{E-(PH;98wqtImru82mrupkkLTeDGQ`1i zZ%2lY9^Y|^^0{~xu8dYJ<~=sTTI#u-&N>=S=7}1#F$}l5HtSEY&LWEjM8R)&Y{Zp=m+KNLUW26LQnQ1h@G(h;yh=K`Rp}7X5P2M zoLkD`j}TOq5D1A}n*>S$jV#uSz@oqBnq6Uq$d00mIWl8-FybNBJHt*%sW;CexXmP( z8fB=Li=b#EN?^2D-fx33i~#zem(oKPJof*!_ts%mMq9rqh;#`qx}_E^ol?@>A>Gp5 zp>zm~TBvk`fHcw|A>APe(p}OZ?R}Sff5*K!e*1j)&->i7^qKFRbBytuC!17b5nyrJP3iMRtf%9K z6IC2*Q79!Z*AsWzvp5Fg39LEk$Ha3pavFz1hyWbiHH)yJnR=(VPRn)4?vg>YIi~OA z=nk%oQWb5SEKkrg18a^*+E$AQ`CB+TH#GF?Spy>i`!Q0#);qm7sV1hT*tWGEd)jHq zE%i{_lCP}0H~wuMpg8c#snzTpo1x*WHqpkPV2Yz7lk>b4aJdN$&&`KaGy++P=+oX2 zLbW5Jvlm4>&Wcj}xr4CGfAAgJPK_z~)J(<~gN2OK0bS|MClUKGNPJtIyxzpLKqTb7 z->jk%xfgaIOl^Zr$)?ToUIBV>Hvr_Jl;~nzfSeL7p}7oidrX}g?5!kqK43-pgIW-U zm(%#RbU}Pkcg(RKs4hBc&pJy&A<}8{Q}ElmwiHrMAZiX8z|cuF3tQzUx{U>Dh`+(f z|Cz*o_26r6elNbVzO7PbPGdztD`9gt)3-zwN;`ZL+qSWCb@$#79@R8EV5R^O8w(te63jj!=2mg{#K*` zXDb^ZkVR*M2MCbnR!$}Nm^Kp>i=;0rXsF+87aG&qu%Ejn>`U4x$8H!>Kt6f1X;2J@ z5+detueJb%Y8#y5lrK*|Ia}6uS6w+?F4QC#>b=|7aX&!+nhDYTNiNCvN?@8!_2-kb za3^~y&ze$*lVqve9n=xT0l(S zaZGDjS){aX3kiS)xB@OFly_MKv|x0Y2I{OYVD+NTO00LYt?!QhHG|y0ktZ$B z7N&6HRyX?wK@s+5@tbo~ihvjHW29??u3uqL+6FbE*AvPmto^iiZe@+3JIVl)K$OUB z&5l+d%>?l7JsthU?>;UIT|hLGG?{ff8+IVHNs5vd>MHzG>OAY9gfcUBi?1>X-av$w zc6LkQ09Ie8tws59ZZNBV87zQQ!Avq=5CMBWH_%eaNX_Ygaz^BRQ`vv)%>1Fk$^G%3Qk5 zn!ME#hG>HD6*5wZ`zu2_Z2DZ)MRoJ&E)_3B@^*EEW+r82d=gG)p$amM5X8q*QW>c( zeNWEnHhj!(*96|lRXwOG-ljCz6zHR)Z7E719q3K@ zhInroFm>J}#qv9p=!}EvO5U`AH=h-yHrl?Ltk(%t7AeT|#KXZ7+03{+HQ3-+`7z(H zRllK>&tJyJT0i0Qoksm|xMvjKu^H74`=AN+>EYZ2$M*|wLSM$#vA$I_!H4*{m2Gc^`;n`ur`wHV-sfn& z=Z(WK&RbVxh;2k`|0nA=*{;{E1CdoPn)^zsot!HnoMk=>q-@N{kQ@P!2((U?GqH}0 znvgG~)+8k9?2TsN8{N&+hV!38qWGNqiq4iJL|Thp2*mtXy3+-3!ZNlbr!R7@1K2a_ zc`(hR>-PWHe|*3tu-K1pm)=+8BkAN)OHjTX?eWWiv z?X^6@n$Ykw3Ymq~USK1Iy*Q<^%pw>$7tVG71~xolx!{X$t&p58GiegWK}aI_`Y9T0 z?#}T5=KZNJz=lc38(0UJgkj)WMF7-ZX8x$E*u8hTKy(xqWzNZd0+iM->{1Am`@9QG z|1P7js4}oP5O%o?iwX(^1i?0Z0C&e5KoGbQ9EjQ^W#`{JCx$Nfb3;BZ4A5DTOR{Iyx5Kp?9q65_zqH;&3LaOBuv}wPjO82fv}Rj>++2bux0C>Su}DY@ei>z zgoU4fhmQ~HV^oJ1yYc6wC`g*pepbG%B=MIhDp}&WiU|6L^vLBkD+KD%ZOS4hDAQGW=b z&O0_jb%2xS0B89(IpDPMY^rCR$>_J}2}~5&9O7OhBHK1Pw7Bc9eMQG?@&k$jG(D`L z0NyC;j1acNiUBrLu_%SoSeOgGlOf=b>L|QUt6Km( zysUWdmI5~0Qgs8GQ%eZUx|<`a&}Rr~&1X|c96J4aj(~Ng2T}m0mn^Ozi;)U;$Cgil z7-A<=dVo#G_+iUQ8+4f9k6xJI^=3B@r|ei$;XEA1M_S-^C->kQIwTBg3&8H>_=lM>vfCSH~)|pB#!pjBHQ`46>>f@8%apg^H zna!zO*e=qM-1M>^lyF^@a6OgAO;%{^rRmoN%})><{f2_)kdDv42?4El-`nU%V%@B; z_s<`RylcYVu@2;G-474e02bhl9N`0w%a-UJK>^1L%k+-)0moRY^o|0+AQHcu@$-7) zY@H`=v3LlH4XDHB5^ljFKT1y)$MD}u70fiZ&Z!Durc2D6AkERDJ;Gw1H&mUg@sYs=m6TKISeglABJF;<+hlVM_-;jr*)#P4_% zENsDqfff@Z`i`a+lOZX}O{83Lka~|M+fYMyClR(nsHMG;S@yG^6`zyV{ z1#9Di$6556)&OIIII1+cTV4u;DskK`?@@O=GFj1swccO|NPz!1i<+Am7KYjZFfyfT zurND^8e2du@hvQj><8Glcd(z+5gdBaad{j$VeseWUKmd3RG6wk{fQoJn zA-}aws|5(-EVwY%^afZM=?oL_YXI^)6wkHQu9~QyYE2sdB!r&VRu7j|e|=I#`H*|HOGuN;q3>WDob9Y8fE)P%BS{d~ z`U3`35Z9Nba}Bar)yN^UFGGXHDY0KUt|0c^M^LI$fjGmIu>eCE2k&uMp;y#)hgt36 zG+OBAG4{=eYwWJ@YwUN3$Apsb-ci{CPu-?kP9TDp{$!rVV1a$}5`ld;G>LT zrM=+N9EpHAljcj|1H%f{4LA?R9OK~0N)APcB5s8`6(R|ZvF|Ndq^`{~v5)aY$-us% z#e;hT6W42Ny*?1=YU;9~;gs-#yvprJsNYl)*0+>>)E8O?ftHrA2T@ep6r-yG+ANS| z{5+s{jFz3*K9=)sR{WElE<5Ya7$tvq=`EB~Pg|SF+6al7$BRwB zHud_i*BTBZZcwO42E+Hw-e5en+L3r=@1KQ0QR zDQu&A(i>@)86)0?`_o4NDF9DA`X%UGwIUJ)EyL-S`n%OhTTHB7rkQc|xU8d3-t!D7 zBxFbqxrN%Kdi>de%(stj!?4zFa02;aDBsiUJJqtx#cGhpi~9LV`mr$mW4yxp$mM+o z8`Ff9_qi9`MdpGsickHh>A;X9+zlZ~c?G33Q`!P377scjns}lh$gM)#?fTSXUVfX+ zze|5Gklws)!QV4H39Oi(-<# z^+D`P%H;~roix{$fwsKZK#QuYg=IsBoX}{1h#94)1t%#&5mV|i zVXyuSMvv%9za^p63`U{o+)lm=Mo8%bxJPty$K3_vVd-3`3G|Z_+S#v-lrL%sIIgJ{7khj7;7K5`q<;Dqol)BPuE~*i2!So15j28#wsBCJ54Mr zsmvpnk5%~Es!IX_KN95(tQYXA`NF0weCoqgKQ4n(@MpVXo}ZOe@0{2v2s|ap9cMRA zrZ=GIxSht)$1_$`I=s@AoR$&0aRA73mbhsV3@Qez%VXBWcjxSK$UxV ziK(8?t|Cg#*uEnGYTVyY1=^BkENxvvfNN21GzbFnMn3}vxlPH3g*;uVFu% zO3Q)Fq*GW_wmgf{m%klp9Gf-mLHjN;2om`1EEuInbn7Y*u!762ar;x3p!5gcC3%~K zGJ3SndPJufxA~D0v}8wsYD_ck{6M)0R3jo!kLWPtdw#$I@PhyW?L}Dp<2`_o&j2HE z!wB2G06|U+u*&*F5-D2JLV(c62M{8=*yA_{o#upBa@$~#qYnM39)P7fVC^6YpLAmV zhN_Nm;dPa)t(_lkOz$1!=!}zcUEw=0v)v(nboRptarLgb5ds-k-%{JT7HGxq=FiSOW%8ji@%dDc>&7ckm5F^s^jL_jOvZ2K zjm$?^0kGWoOmTs44k+Es35ik6>V1r@_;;nAkhlJ;qjx)9*VS9l(c%f(Y{i4e!Dde} z0@_)Xa5+jQ9OoOqgH znr3AK_rqAuXt^6NHW)U+h*Y5xGfXH9|HxK7M-zt`_0h_IM^ICVYYBRUz<}b6_OP7t z3;Uy{phtkM(Zop+;+as`qk|q5iY~xX)=VhQ80Mt_OI!_%Wf)ByBbV|ELtOPgQ?Skn zu&jNg{PGk{9M-x1nF4J5uPpz-1jPSK0E3fMEF$*7$Ugy>bd$Y+m4(F$FdN~yFe^Ny zIz$46@EtGlf?W@KgQwxDNsRQmC-6ePrO9qXyxwU(q)MwU|B50Wu~!vC8PeNYON~NR zwfiLK(UWV#hy%jMGe6xQQc0YPD@3_lhCqlw$4 zPdrn7v_hB`29{Z48)<5`{Y{-P!rIwl6NDL(zi!t# z><&A_*>57zewdh~x7F$BCyr0Ov6TiKmEz^BNk^tCx1G;!n+;1}Tq_kf~aH{lJB(T`vjU|pi;{l=A5q!Boa*TWZ}@Mhdh$aD^LKPZmHJrOCMp zE{5Zg{fiI=;*sqc$ZPUThnWkFPl`DQ*uOPKA!Fvkl8e8SpLPaaFwQ>;RFejil?(%a zwMFiR29a~O_nrRxHn{cG|%Fs>eDnM@|H0|UaphLD&@xjNkv@yHCc$ zCYCzNQU`|fU;qmb8#cxZ)j!3-UQy5#+Uo7>EA$$T4|l~TSNRg`)tDoa%E@s3j~oY$ zFTs8SgHWITh>&6=CukZUrONqb#$EVOWuykt<@qU(Z1QD#FdFl9w0j$?bE2x>GFYjKRIeN(K27 zTPG`&j8|lV6S0FUhUd}9J+^zR?JnWhemL~o=D?njBb001NaiFI&Dtg_ZbKe#+^-Kn`tO1zJz)btBNNboQtN;QBV6&#F3r1ckE-*9N!U(b@U)BH%QiYmm zn7RPdGmKybBk=!&KugyN&V$X{|2qLTa4=xx;wAzH{3DS}A*d>|oZH5UStyQ1k}u2) z%mh2GuE1a-%nOqs17=%mR%@0sGwjsxS~Uo4TTW^Zj1v6Az+}vo;NoQuQp^j$+9v#n z*-!&%pN*5>CEOEhs0o{SFExu#EcN0oY;K<38p%=3)6AC5Q{4Wqky;z^TkOcRKaTZH z-G$|ZvCqMHnWHe)p5G@-54mjPV2#a~4|aTK>wu#X2kV%|-1(-+keHKh!67^=|wk zu-?&Q{lwBEU}M9{+O0n{7Ddwjd*(vE&yl)p{W|qj(){<=^7v+-_$-BORmBG&+XUbc zB+Ov>htGwDN9HE(J}NahQJHG=-%7nJB1;XQ)>sKk)DamT5mHOb1W3tdlNad}y^nbN z^y}woJ?cg{r>j3}7wXq*u&2DbZQ1DCI{3=KD_rgwm>~H$RbU6q;|VPz&41J@Q%}E- zw2t8U-5|?+tniS_Q`aP`WG!IJ>Jr_3m8S_EiXF<%!^?03TJ<943dcrS$kNB2o8Yrd z*=#tOH`?zQ@*>#ZZxXv~^A9Ef>ozkTciXJIqwgsZWxC*6!|V?o;aXE=nE&nqv~};16NX02^2S4TP`Hw#0T=Pbl3Bz2h3c-}q2=6Xxwt zVypeUL5}?RWSRU+0KGPy5e)5y?_);_^u>7ewVwb1HKG1{(pTr8N_(`vsBcshxb6+IPvrEOB`cYwC zMs-dsViOGot_VnaxMkI2##xhr9T?2*k)w7&L`zhJFJJ6KT4FKs)U!m1sCz{HUG_;4 z*847&2G6j^@o?m^kt+zbczrp7Tkngoo0XTYagO*nho0Q@ju^=g zv>+dY3~47;LkKpj2#WjUSESn^MRk3tHW6x85ir@jO!$$4JCF})S9*vB(tag|beZ3c zM-r-VDv$XTHdxER7QvYOKr}w|RncXS)Yy{=jtYge$jAP(2x-puuCu5XjMJ9-B5EFTh1Vb~CAZ=mu=u=i ztJ$&|8_IbX+DR#hoN5-e&`EHG-zi?s6H+r8%B86$GhqrEU;7xh@q{t2=q+%5$BXi@b?vY+y9Jbe`>ucYz?r z*)|}Jz@WjEQRusmF!m*5-&;(TZ>AgXXqr%F-<|kvLp{ytAP*N;?E4%l)|aPCF`sI5 z4fW3j-uU^P;sLmT4I4HAqe6Whz+7Kipp`fMi2SzExF!>jcgM(zbhVwv{!!E`DErqS%kJv z_)(W@tMxa;RjWpWC&pB)032*YO>AS=5qaqn(6?Em`tmLCa07-#Ry1H(-05}#qGeb> z^d;Y`qtOwqL80x@Z$9=}0m{(++t zR$I}Q#l*~(vBHH?gDkXV9ckUaHFp?SsMk(SE|kl1F8K@o$0xQMon6UI_|j&!%e2~A z-g04n{daPf0@ZOFP59#=87jphym62{l_DLQHDgg+0Uf$^@psw!NjEQ2byQ$&aQasAoBq@NfhW zKQgttVGzE{-5{)B2_IoMegVlfaYDX8_k8_%E$<5a5s$wK(k>T2u}8S4%AW;kzYG#= zGjgG{1MS1T>casRu)wcufF&y_(B+0*DlmcpYCXaYt<|u!*su#483O-617HDW`mewi z1tvmO3+Q!2+cOIjasz}eKs`WV(rv~kOIU{l0L$|4M=WKJRan~kYhb<7EzM~NybGyt zYWNf`pw~+#XFx%t0k1KYaiwvE6?q~yV%a(PyAHCY<*RS0D_Dn4*`&dr0@=(%nl^H` z-i;RJXp2vXH`P0Tn5CWVtb_}_>+SwP9uw5ivl%df$)Zg2^Fqq8FmxpKW)owroqkR$hqmTr0aWlJBDK?$xh7Q`YS7KyZc{w8?U`sB=J;PJc{ z+bLdaFs@Qzm3@-71K1*>Kc5I|WG;+nHShVb( z)`js6BD5A0%UV((W{iC&7jBK|&{i{YlRQkCJUsFzKUCli0bBTtk6vaS#4j=%^!cTckn{vgC1Not(#=Q4)LoT0Iyg2uqw;J}_9#Wor)_q0*hM=+l*`Kt#5l7np9mw1%gc%6Xs=FC#GLQVUGGR^tN1Ff31s^w zg!h2(Fu2^lm3o5wbJQo#9(eprLw1ZPfA8K>w9Q);9?x4+uer1d-^a+-J9gaUkibN) zJG}tX8_4T*G7&c7-RAFo5nuZI5A^t79jy`Xql*L-Y1Y16e0~5fSQ|O>D>Bu_#A*Yb zCV4+JgU?SnY92z`375DNC~sCYipF_)eZqqTx@HZaHeQJyj8*=6Ik>3IGWs2K=(*do zqpl$JzM9aawFHN5K`u*Oj7eLcE@+-kq?1gZ_=qGGHJV`=_ zOWK$}(`2keFPU?fv=P`xT-3!)m69E8$_8J!cO^DBtIa3;dciq!yB^fJ$x)@(nzbR! zkaro?TF<3THDq5cvrSWP6n?(vmVst7tSRGa4;lyQQn}l&l_G|T`+At;kaBh{feu5i z6FaZZRgF=8%p6_&k%XS_U9dEpZH#S#j)kywjLK%L=UGQ0GerpYgxu3Z&`&wxJV3M5 z(xTJJO{0qB1TViSY^}76Ui&UT*g|jVCAdmrJLNLkifMInJ_#M(L!V|c+5&wZH44aX zx)t|44rN_HZ~5#z^F|iqwx6I;iOsFRkR(*>rwS$O^5;>3fb8|_j`RfrhX*5TI=bHe zEwT0S10*by1P)WJht=8Wikk!u7@wUceujo!E4;yL^*uS15ox!Sc<~Wq4|$ldekP8D z=rn96x?;fl*(GD1cNYFQv@!9JWuW;}R@R0KL!JXw)lcB$HU!rhn1GKgj&F3K*iaPo z$b$&B0xL6TqHq4WdsqzM6lFgzo>%yq<|3MUGOqB1sEe-x`kL*{ccctBSn?Ru>6f3s zVVDR?(Fcx@t*OSURZ{A*wh$Q8P6;}GjvF!Fkf1E0#+uJ}m@75MUG)#8d5O6zt~sxP zf1HZ1oa!_r`<@404DXRmM>A^}dT7Y_`^PpjH}v$Zb80qi^b@O4onfYGBjaf--fZK7 zG_1JQKOuhQmBP=#2#p=+DV3%p_M;Pa`2^X{L3=gyRPH-}J_Y8onE;Ypn;|IC{e(yqQrPm_giaA7Sw>f4sWED?aV&Li8Q4&O9kbO3*`L{x&0zJM%87-1gKYD! zIWc48a&IJC*-wiH>E}{4W>L<3D8&bvleo7A1-W$|xPyw(S8oDe=VIn!ghb?W7iLke z)f)oG$Q$8Ta-_7LpW`ZWsHb2jTCIw}DYZZvaB%rqjJ!GN4du zA6HooGOKtBnz@+Z$M%{clN9Fk($Zh=*Aje1SSsW!<}6l1@FA-{>#Meg zivB2?A13Xa15gE}?%y@2iUOkF5q?wGB(}rc ztDKtmJO>WTzSoxr!M-pA(?};$)iobmv4+!}c{>-kNZz?~vc-bWm>eo5^~kH2;Az*l zoaP4Kh`Zmo*ab^o3i>?Z)!9*O7{z?+qfW4nB;S%Bxa;zo-B0fvM<)etow*NTV0S>k z%y5T=sklwevC#1KMPOQapL#g_d>mEyM1UFR7ZuNIFj?*+cSuaD20^Z!U0xC|h;Q;Eg_#+?6w-hmWaRTLLpl{?a zxSjM^0xI4X@UZEBtjlwwffnFf2vL;H>#1F(eS2A)=cM#OUX$=i_D46B>xpc}TTr5_ zxav0HPyTE=ZXG8jFay~!554|Rn5bKx3w#D7ZkdI_UujEb2%PpOxWV-`!>FHw)d@k7Hq(m?im5S29$-D9{u{1R9A1IblwFlO1kKDED7VA zUvxeDbtqA9Jo>diu=Jc;s$ES~#&S^213F)w(VeSW(yB=p3Q2Cz;B$Cry%GSv=7a<> zMCH}+bCOgB&{xz+^Nv6Ev_vx9OF#ORb9%BS6|*`F7Luk?AQy?W{mkFM*=ms6=#c@w zjRu8oSiAJfaIZT>8}L$%1}NR!tR3z?Zk)QltdPYLCYcYs_2c65C9Umg*IV8AHtf0m z@KpT5ybD~VtdwlZ5#{%wFzb-z)d2fTsyGqg>k(n)8hI84E>j{}wFibJ+A9OH0w`&D z>J1oa<8JU3)v9le1CQTUi0@z`c+0=fb>krz*Eg0@i!%iwQnLyjMjA%Ed+;c;@Qu){ zjo(JAf}x6mA5FJahTa0h$?LOZLE19(I#rkL^znD*Tw{Dl2ej|LXACR*T0E|;BU)-= zo(VBfQMV4|@&=CM`^8hfHv%UK%y|q&;wifWO?;y`fd>=P*so(BAY7~{-yn5JFK=Hw zP`zR7xPDHF>*pKbb~c!_`Z={bz5eot)N_Whb!dZH8pqc)XkUVQK|&gbp^dIw~P>M0uko(rU2-oNexZi3xi`5-RAt>WK@STGl`2 z4Uk{XrL>~O1x`1e=^biTzJURGmS+GFZ4}sOGA(%w&W$L+Sbuh;*AoB$nU7`$(ah6> z&X_w72z!Y=pS7M#ua;dLWRT9FrObw|eo@Bw#uQ43e4vx#|uDe43o^q9buCgwga z3Y;JmCnDL%Rb~lTXBC*E|4uYz32dJ{Ux><1X_)1SHyFiJ(1MVsLN9 zUm_#eH;^mYaZ%NCN=%Ri_Wvp3AFxEwq?~{hRfTMw1->SWtm-*v?a_zsKqQJ*2v%1^ z!E85{HW+*r7s65wmR zbGZ{8SG}lFH4M^L@&BxIr8KsTptVHi}W;w|V!<<7rGW`y`vGUewAp2n*m%>?CH z7vfd>h+he`yF2Je(^j0b-wuULTt1*>6*y77Jv!iXUESa$2@O6W3pbym`;kkjPa5vb zpBlU4d)m=X;3<6#j=-ZBZaQpexj@X7C8s!kLpa3l#nxp6X*X>{Mx(x~QoR^m4vqcP zbKfB4|E-Ns6?|IXFuz`K2@$O9Z zB>x9;c$s z{_=gYw;xD@KA-(KQ_p4uG_L&crUrpTK>Q4HF>MX- zEeWv@dU1J(Nmm8mN|TKRrLJa#w#vyVGfnaH_>}C!fnOKnwPsoVbBK?OLJw7!WN>24 z3d&7El8kR~e@gHpJ$PsDj$zIuze6aaZjf& z#UQ-{WsT`g5kMl=&>Q__wX5&qUSvYqO!Ecleb#V;Rojx$1Jeh%roW!&q%s!nl^4EU z9qx24w(pT8CnUR6O+@A_aJ@Me%DT{9h9azHR||W&LFf?y=e(AO6)!MsNd1_$srAJ4 z))E!SqYY$<`hvMNXC;qCH`nPg$nlRw% zeMKRj*6rAO&34LNHWSL&n}n$@3cml>mLp!1ZhI4g?!-p>*ki;ZNhiqwX0#_8)mUx2eqL)MKQR!k;yzR&e~Iowd)sDTyAm1fH~cPTZoR`9)0{V^>DT3-a_gn{^=f4i##;*KC5RGlGfPru zE4KD=lsLHk(&uN~tzR+Nzv~7N$>FN{vY4maKNC zNzIbZ6;(x349qdkp(Be>gN&gQUy#@13Xxi22F)vg(71N0%lb3ra#7*4pdcGFiQ|Sp8__P{1!x;SKt+sj}AEGfc1==A5Xc9qQw#n-f8V zT-m8mgwlzx;cM;RLiJbl#93wAcTkc-%vDJF6!^EY(;WJqf0sj-JrSP1rRKs(5W7S% zq8XW77)iCh@s?WDq6np7>k{jS3iX^N%U(yBNu~B3CGTdnS#l+lW?GYjwxj71S2;KJ zvPWKW@C&<&-L;`9c372tqj-qvno)QK_9G@sC8fyNtoJ$BfRAEq&?JasTOU+|?iZtX zz1xgt_a1(q;NtThI?;|DY$agXQQ(}oH;haHVL~-d6u-R-pPNwODYlBwb$o$y~_4pcw8`g(jBcF`Bt|c zi=x4C3BNgm0JKCZIhuI#RXxfqae=2Lw$LMpiuy)H;9?wl9^wKqX_-PF(P;|( zK87CF_9}_Lq6k!Cqc)d4jM=P$t-qWb7sh{^ z;3@5BJ;6MpY#U^ol-KznQ|Z)JR-ElZk18M1QF3S1Z!h65%3WEUyFiD!dqAI=h%SkL zPNO<++}9R#G9KSN2VAPlDC-duE zkkCy(f?^-G$)CC(vTBN-eElS%Zv)Mp_kELcss;|!B+?1>-bLYh(B(lO-1DrT<*Mp= zrH$rbAsrkd6kkq*Ws>RK_h$oHv5SF@%MQLAkHhuzPDHQzLQFxpjs~g{#t|~ssU}AE z`G5&K&C4R=2em7{0s$dE=yYz{s>QLMA;lUsHPJ|)C!n(J6P6cJ8=RyU)pm5suBh7y z<0YUI4xe73|mb>5QkoF0*E zy-$g})UNteT;RIGnJnKi&y1M_^>Xm@6LcR>5ND`4!!O)0slLr*XmXgQ>m!BU+VA;~ zh9iRe?oMggU+JVWzONyuCaN0tShBKY`N5h-9G`9=#(~${!yFYD_SYgC?h>H;s13RWlx)b$^KjuJ(!$N3yfFe7b$w zL}wE`M6lE!j3C)~-VX1kdUnvSkb6Ft!Ej-j7h%nN)OvusqEPUzow9KoeQBC=eU(e7 z;BZO!5PTh_C~&cK@G6p#O5f<3KKC0ZZloM{x9qgow$_ov zAt~iQYsd#*SN~9dnjRBhO1LbYB9YW#ZS;I_u24dqBH+=?V?80C{a+Jtw2#w4DB6mt zOJglVSy_W>Eh)3&2pD!88m6x#_FN?(Y3}1W2ooZ$&+8J`#?h=bEi?7Cp7^hDMjMyB ztwmAQ><)cYcqOiXB=%(-E#UJydgPJ2V56xqhGWx92|4ld(4!Pe8t#j4gWTeisFg}a z>I!<%_3zWX>@BQ%?HxCXb}mes5;2L=aX0$iQ=jQXkM(cmO=Tsqz78{&=<%#Gf{=fS zpeh<(;NjV$O|NMWsc*D@RR#y4UsECe$=j(+^2LuPNJT&Wh|T%Ilh+b=KG_)Uxh;5~ z;p@{(M5M~7J!;GFKNSIgt(zJhHV?enin)wxvm=bQYhJDK`2OeI-j zg04^T=N_@2MoD%&D~ci9z;3%EeZ_AmF@Kh+ zTAa^To%~5}ux7~4WMcDBig@a4e9%N}EY;>D_V)sgq4XOB??sEioMh!bQsIF5i-U+= zRpAB~db7(*4%apFNw$rd2xlL)3$^x_3KL1&o#+{Ro}V9vbUqg#JSh=KTA0* zab-+gTSz2s_@cQ)_E{kJpX6zZW!7SVI&H{7g{<~t_AKN@c4DL)+NE4N2-48O_+2Ns}>`dBc6A^^0wWy zliHC9^}zgM=8v-BXtZqgQt2`7vNra1(oW2$lh1I-;(~t4 z+&c8*Q}Tu3GR6&?a!_7K@3v{2j|A4b=6pn}n--pE-)GP}ESo9utlbKAH^AP>`?P%f z_$Fadq*k?4oTqN(b(MxwKjzayg<1`xOvd-@>Wn0Vp2MQ;L1~vIvZ*VNOs@j@^lIn;SG~oG&|*(wf@8d6LB`tm~6+?tc&9_HiK#*4WShqq_cl z(CrTqdG(}73-9HcF{v%p&>Ra+N%AINW-mb zb!_5?$T>|#ypXdt;atL5Z%_qFTZT`}mefR5};=nXsX(gOzRogW!6*`4al2)IdT zd700WDRDUuvGb;pDj|E$~mfSNLas1y)?fyT0sU7?S7B~2$a6$azKO@3FV|vdW0bh;|Zblm3P8O~PurX6b{@(#UX+EVs z1=tmU*&o38m(LF1L-!w!k$-!_y)PJFYBj3@u$Tghz?@6|`CtQ{XMyYWVE&a&9UX1| zRw@G=S*#|Y_9oz}nD~z*5Q|3pE&Pvy{}tk|N(BC(!hNIx2M53V0FLnAaHuf^Hu&8<+oSV`zR-9<{s!kH{}LAtNyz#qd?AI zP=5Ory^n$*^ebzl7!K|;1L8dtoQ1!l{PtCRALZ z4vt9mzKzoC5dNkM-``Mvh>ERo1;fF`_T5KGp7|>Z|KCu~8d{DQt>NM7G|}OR{;ky^ z7(D!&F6>YL2D2@;TK`K44zB(d{vHfb58_{8emf_>U%%QmQqs?WPN>KP)Xu+Yql}OA zSD3#x-@B~Ei%kVMxbim-?!k1D{~hM9?bq>r@k|CVEF@vwACQ)9f5W)Fw6F*6Y=(t@ zeI3*!uqhED9GuA$I5?mW|I4Ss@i&00o41{X>)$H$)_`s7mJArnn&E&U@?SrvZvPN{ zY2spGuI>i7xV8E#!hJXKe=w*M?^nWKoyOlc&V8@ze*kHr{{iri+vWR!_kEcE0R$)g z2f#lb&F=%=_Xz$6km>Dz0Q}=0{664)|Jr{5S>OE!z(3x$?*rcVR{aN%{r!IcWdH9g z@xJfpKZxAP{|WJTi~s9Hbl;KkA4Gwa--!3zDF4;1^8FY8??K11{wJWnonqbxz3;^A zkESmR|0kfoU7Fno{qHrsDE*&+{`O0AAN0N-fj^qY*8EREe|r_U4|;#e{0Ee#>3;(H z`&Q`tp!Y8q{uj`e-=P0?)$o1ke?NfvBMS#7{16%Le>;x3FaGblwxrHkT zxJ!Nh{H97&`}(625%0onVw!&te$)g>qO-!h{`f06Ae>B^M$n4^*qU=-pu?|Y#dYlP zopbdL3A2BA$f$E}?fla#``mVo2q(>n&atAzZfX5DA+@C~QO6y8pCb-G=so@H91vHL zO*8%xAQ}2tf0j+o7y|TR58g4LAukC5W)k$dd_W$0OGCbawq-L|oxEHwK7=|xjRJ4}nDUNK=$=;^ zD_BsQORA+|^V+u7EZbF>_Or2tL(gBCjBY%L5BvMfVRc$Q+#8+=xgq-8OF#WazCUAG zpT7&D^j8d@jRZzfm9GDfO9CuAr`m%90PIi!04%68o(`NI&aU=m&d&DFM`5A1X>7hQ zKIAdsnhJS?gb9{~WQ}@1Crc3B?f}>D-2a*X1c^5kJlbik)??-&hs{TCtDX6 z>u#*q#*weI*O4cf6h&Ctc{M`{X`*b}!KE8ka8*StX+5^V<|zqZ?%wlUDqc^BgFT|V zIY_*<{HcEkAIgSTRUGNH(xChVFQyc7HJH8Wg>Cn#vNm`ROmalVc~_Ycy0wo|T-I(4 zyk#eMXv(KS(f!K!iohH9y&0Q?Z*$(t@o-9T%Ow5R?%xLN79)gADSXA-ov*Z#U%68) zFzN(m{aNmmQ@ttlDekUCAY%afjIB%o`xrJgwZ5jD1uhLvSlR- zvbgD%ZU1D{dQFh(Mk_t&+(1*SeLz4Ic>PYGW7?{G?VccJ#K+kP!MR06C_XJxi+(U| zUrsZwv_K$l?9(p?|GkwD@6EsRQ>;jouU8$v`8^r1>Rm_uW+3o}jliTS=whQuYvjb4 z_^WPOoS)k$$}FZXax)w|rqQ?YL0yNW%pr<7526j8#jWie>`E4!bavQgMRUZDjWSPeYL6W-QDOYOuxZX9_GCSt$ygC*!Rr7K}r%` zlG=KuvDkLAp6{f=`KeT0u?|C5@xMJg1FUXA#z#&1#lKgq;L=hKTJC=2)RKT(Y5Ln1 z$rIShM9L9JI@3wFwuOSw1xu#h4Pxz_P5rvefBh4ZM3yqNl$l`ksXpkKWq?4H>Qp}jJj9n&s#^%o|wzBnp|-|onJ*4x@06)ZCdK#rVQ=Zz>vSufi2#jDy;dIi>)xQlf>-E^lSEX(<#tNKj9(x zZcq+Sr=H?F(U9omJXF{m?9RYPk^j{F{4E8f(;U=q!{54$MSl4ExX_(3V7zbZz!;|F z>?eLAS#Qv7jKq^IAK6+s#g#SZM36!6dMS}-%TDLW_j|FUCy=4k6IZVAFVaVjFKG+0 zH4$r1(2f6p4^CzPMXVMyE%s0V08#)l3^Wt|IXnL|8UF7%3In|6{4s&u*<-_q z3=}vpxE~#%H%>b_iXT(WbLH##S+@Z>Yc|9oCNw$=u*A{bz0xJcnk63mamM^tfz7z? ziQ&`m>vB@z2;P~XE0LnQEcf+Bg3}`5QB+UdA?6l8^I9K#-en?^hWoxf@l3Cr+o#21 zHZp_>S&)0~S~C8_*dpCL;3raYGi+*IZ^*;9hV0K~gEjr(pG`=)OMp@{aaaYBia1r`?{yz@oN*g)=PZIzj+=B%WLqGAagUZdu($d|H^W`7z=MyV4 z(b0LC3wvloW!WSAAzKLLoqxEhmZn4Um09`K*|HF3UG2`e00Q4h$7v=bi<(v=vQKZ< zJ!HZob$9I@>S>y7zgAYkBv#yzT{-H9Q`d{XLsmR;*>!~+;i~*&Q)wjbEq4#LpEbRl zSq3YSf|q}l);EuE2{f7|5F7JXh9;`pzGHis6LBE@AwPxqE}(!~zV6jGSqhq&7A{Ra z*HKD*QF-kZ%=|QJ!gE0a=W&U|3&PA-UVb(Vnj?tV1{|%TEvmoXrHg{?ibk}1I#o=S zNmO+8pu8hGTcO|R(D1Ch7p>M8P! zGbw&VSx=PzCSyHGM}YyODAi|7RjGUL-61c-m|);Vx7+?1&w=@dnYifk2if=bO}N9d z+GBNRVDc~OWBrJYZ?y#91nQ`UOvww?0z+pQKR%4!RM!L1J1$Hr6Lv6X`!O`NGpWAj zagD@fihq2qN-u$}t>Stu+ee+CVIP~dXy%Wx4bt4ha`5Vlqj+tblQ$0(`DxAm8`>B6zZo|UgniaL#y72Ec&vZ6Sv$aytHIJ3_ z6h~ZJPBBQjCdz+>0fO|LaxYU=nPn79E?8fDiUoX>cEkdj7$>dWYRy&EA(U3o$JX*D zn0)@^xP}}!TaQp_DNU74(j)F0)H{JJ8y6ok8`55{I}-hBr>t`Pn*R33kTDo6w$^ob zarh`m<$J#X?r$OL9{}&1)~x#l>s)^!>M$1Tjk>LHXlAC6ntvyyuY~vi~5|MR~&3V3f36$V;PEWd{CMhz(f`6Tk%`%e)xSP4)*(dd2|+^ zaTb5OeRTGd`CCJ)M^~u7y5^3oTASAyxrQnnTKVI5d2yF=aqcOV)jO4*rvoNl$oKv` zJT%Dnf;&8#Wgz&do5yBVaLaRZ;*u?j2?XO2%) z;B{Yb7v8lF5-a(N*i&i)4zTg6n6K9#@fu$Uqy{S&W2605fQRl6Ms;4w`(aW;p({vK z_c!nR#~*7eS>ipmeLIE^*M1O$b)W0UFP+`@dx_+)YI1bUO=mE!9qwB{}J zvnvB}p8+{paN+6U;h<&%Obw=Z@P-`HIZt?ZeNXmny}!8azh5Kj?s|MU-|JA}^t*pJ zxSq)A%7vWog8d{v8b1=ek8hd&DfkW~zUEjk!MmGn1-9CF=Ef z7RKrE_4m!jd&n$D<8G>PxzI6PDoV!R+)`oQEZ9#`gs)kXV6XJ*JXCKc^@B}_&r=J= z{<2qlR%hSr4p);1)+yb(UKob~r}|IDeS2v{cCI%F?jMgdV>dcm{&ucN-yDXF@jZEE zCf5v|bv<5w^>}3*d+T_6q*ks2@p1=|cQqN+%y72N-kRTD?h72&4AtFV+U%G0Lf+i& zblt08Obu@+1)XHr?)&hPz>tZ;Jz{&FKDMWOU1(aVQ@s8?av;hD({ZjG*CRlP^vwJRj8P+m?2By%bM(uKeM}w z*wj0o(MBI0ihFY%$zv(LV8GCSVVtPD55hSX8d6Oguj@$I#7KVfr6pRaOTK%XmvXn` zbm~>Gp%OFe(VgAgy4dbzcG!?nk)dm)0BZglaeVCTz6d(1%JZeUHku)5Q{feAIxzg* zwNmQl2makfBaw2Sm~fxSeqHh&Oa`maCVs!_;b#bjgFCk7)@&BLF3|=Ph3JD-Iy#SH ze8u@)Hy}65wAV(W+}BIyK~R#>e@NVN)}l5@4~bki_>JQ4`GPbuI4r>(F~ZlWPEc5j zHgVQA@fBA;@UJeK+@$-c3DEV>t{7L3D;0}D&OP+eC`yX`dT(w0QnovXw9T(c4cy^n z25vwy6RaCgx_8*aTUy!^>%i*ZpXL13W#3MFZHrhUAez*6DsZ?e?(VjMO+5yAI|3O< zxmRSo#(*hW6~Fmc8En^i^_Okkjjr8Hv#x$iCq~W}_hs?-3uL=p6^y^dykWiY#+2G7 zK8eL=fxv&|mP7ACRy~w;eu@3qoGl*Wxn7gax*z(d20vBTCzCOV^uHMH{u_gz&91Ln z>F%Rxi$~|wX^AWtE0v61TpPb3NA#)vT}bhTwRg_`y4cf_V{g?iGAy7Pf(o!9EeY*p zfdP{719Xf4Qo-hb8DXV2OR0g4G{9qO6Whk`J;~NR5Epa+S~QH#iWl-1cH~GYjKJrP z7jEdVBMabZbxIr}2wlnlwh9knKweyDY;OtkU!z*p|I$O<3VHzLIkvIuEw^*vKuKU1 zK=A17s@VQhvlC8hE070|oWr7Sn#`of1u+PO%BG0rKCk}c(kbn1LQcxNw%C{k57Bsa z#=4&uGF=vf>b$Vh}WpXXCMfetN7gk>rhXXNe z*xE;yB+u~+mL-+GRN<{SG7*5Ng!##PG=x4g=?Uod0rS!?uZ#sYFi*maX0BoPrNs|2!W?0p;)EKyLRkL|GAO&ksrB*LX$h5_r;klW#n+&b0g8crIxT_?_0 zem?7$3r1|Amzca3)Rij4mdAQD%49(HiiNOmSs>>#_B@3Yms3+01CIAiYNxUvI(Tg* zCO?B?Ax%SFBiQ?*bAcwTSsYJx9SuM&ZESdg6 zc9_7fNJo@-DQac_$9p{Z&b_A;AP>Cc0Of0OS{t37?HYS#@%ut zkLIekW_ib!3LAx;oFgyqsyU=eA9%m7N{F7A6DfIkZwkVc61>RlI0##>>G@FQ-eE^- z;&FkAZWfD@(mS76gK(v-F4*kZ-tJN-lDypW+f{H))ZYj)Xi(!REkc+cwxZs{5O__^ zx-M;e-pmJw$$0K7gf9PUg!(g-_6>>tG4@(J(CaZi^$AT`ORZM_?`Dq-;ITQgFlvZe@VM%$r{r$7tYpPtSLy1rtiKpH@Xs(Pdz$EKq#* z?Ke|Y(_q6Tnd$7QKkRIh-dJEo^ScUVmLt)jZWCJ~4C&>!R+Q7DOuH%*eD}Xv)F8p{ zBqGa=HbD8MtJZD^40)5hEU|_AdQH@jrw2g&A3xT>M~TVk=Y84xj>REFj%rI6p75;)b>mUVYD)T^o+Dqp5!Wy>`&2G^DFFnMt{ODs9m`Y^ZswKf*q zVHwFf_08|_R&6~Pbw#!>)e<~9WVoN(>KQ}FiJnU=%o0nD z&hsYImDrCauwFlMD33ggHB#iL85_?&fZMZr1D7f0gF`@lGMjix{e$igrYRDGpNLPc zdSY7Hoy>HCR#OvSzcCAS<-%IdOVZ?@GL8K;H_nEVAlbZ-^z*%t1mPBX3GH&}O2b<= z8B*OBiCXo;qF(J%db0%OUz?#NRTX+?YS6~S?@fbP_#qdh6`%DEUC!wQUGy+%Vzx>p z^xReVx!f(uy^Q;y*m7+^dL(}lR?Jl_)h|9c#MdWZ_hNh+O??Lj$rlNz zw_XQ;!SBi>^qfJSSAI`w(cvxzqjT}469o<+;`{lq53Iozbh=bl*SUa7tcByl#U`=n zEj<3$E~70QPnY(Y(QLlD*@qY_1y(biYt?HYTAdL_4MSdJs%88ff^FmIlDoS0<;>0U zDda-S=^%G#JTS+N%*+(LUDy5{Tt^;0;oRV)UKaDl={@wQIBz`|c18Xa5opC0y3@)Y z@+RLiwqDTm*c*?H=EI&M9^$LwE-vyC__34HlE-xJ8=$(_) zi0?pDFJr%Kv-bysHFEAJ*}_USx`}~sG3Ds3BoRNO4WtgQ*I-kyZ4VXUoD4J9W^*oQ zjd#$9gE#?CW^h_%-OG5J<+g>s)?YCY>xRUJ%WAGwST9@7VU&un{Qc-R3e`0Z|E{UH zd*s~tY_pHi9L{ovE9U6&hzlmz-p4^ncQKE)MUPf!lu4tHn(Uuz6_)loa#pvAm$(iza=Zuj zt(8W__{_PR2OURR+VG|VT@>X({eiHd+PP(%KfdigQ%I^n_?IF0jouGY7@9?oc5CY| z{-5Ff+yCb)&Ya3F*L{TjW!dai)kKq5dxr`L{8&$(|2WSnn*%MNK!qV6yqywv2Z~vL z>Fyvqk+tAutk+?U+D=LC;J@Uv{&|rV)NMnXEf7B6GB0fNYURd7JIQ@!{yjA!uq13J+oJ6+3+vpPYSH!Jrk}P~OqKD4}&& zGoNR~A2Z82nzVPP!&M@jrD=4U^DJLfW%v6b-a@v)dr>(7T{BPpLu^5=^(A=1WE6z=a9aOFOz(8;$0eLpOe@9DT-R{4H^-6*qGuPO-; zwvRP3Jt!uGGZ<;tU_N^9Gya*SiMz+rsJ+A5f2=)48o8ch<|Bcr2W=mX6N>o#eP1=b z{GdPI6s=DXCZes*!Y6hY3&g-?k++U5*``x-E!hFZ?e=jVrf=zwBgg&MmDv%Sr#(v4 zH?ms0G87!qfuK|{m}K*=dKViOPIEJ4Y37iC-SpE`1XFk`J=dg;C%YsMB7TI&zWui# zj&uF(VRZO-4_7}5-%I$Y>aI)lMvL{ln!i%y-v6LuApWij{!q!p&OR8ju4!lPkJjn# zVPW!Hs^$g%AY^350x>*EXrzC*q-)k5C4oEFrc>JZn8LjY>WUS0X(!M(JHX5LtE!_^`|8cb(~KDtBE&CjB35tjkM&Z*P+OMeGUDWafvw4*25dP%Ztbt)xjHiH4jqOCv~hma9)B< z#ES}dZxw<1*0B@q*$T?&XQwxK&)`M>fM1Ou+5RQ=(o} z^w56I%jP2P20TfKYf~*ah>|Sno@($ zJ4NH7m|Iwbr)Zi`w7b_D-QM2p^AP;Fda<(>Chi+0jj=tHthEbyjRqG`o9ltT5q$Vp zPqD;;Fo;@o$HbM2$WQ8s#qf0$mUbcLgK5z=x|mp!=qIn=YAWG`u?8qJZp=y(a|%a@ z{P@Vx_Emo&DrKJ>98}1SIe(@24hw7q+K;+YxUFi3)1B|JVbSDZ*r$0c_hCWOtcmaN zx-$@kudKgBxgE)es_4d}Q#n&Ji?T>Bl1_}ixq8$PPOuMlwfW%p`Mc>+R|Ctd1uXrc z$aMLudFt!DV{TTS1h2uyxK#zN9L3&MqshnCrymP7r+z_W)2oHkgV#C{uXM%_9$`if ztq!9999A=r(T}(oNG1%|H?U<)fRv#MnO8aZda2MX@<42~TEN}<1M z9&YnS*MRpE>Cc}}c762YAOkI#O6}!8W(757U&2Pdl?w8l0Wn1A zjp;5h?Q!ao7r%(N&-C+iG?%E;;TSrW+#}Jp4$Zq_M})hoxh*`5?nkCEwYAc}5#C1w z7dLOpgxhDB*D}zO#xBjHmt_YXfAQmv57~35_~>D*_Lp?ZV0G1Fg;InbFV90aD!i)j zx-DtlnxnHsePzdrqjP2rvh({8)s&cL+_M#QH$gQ@@3dCz3ZhO2v#I(!%>dGT)LqjO)yYoC1C-6)~U9_Ji!$m6Ys*F51Tn`)~-M>@9d&Gl0% z6oYnNP&2*UIfZg9oJ2;y7FtjRhjzsYKsQ#Fffb)9qhILiD`lFZ=tojR4ud5a=*6ID z`;)(>-A=*^%sx0<(KoA}Txzr45JZ%&RTuI@#(I!_i)F3_PB#!9_s3cEhP>Y6By}ffBIzRttC`x zoVWHOo##dRJ0U)=XL#R$q6;*(Rn9mCN1?N&P3SW`lGvB;uE;Q9u8tpUv1*QE~ZL(o^ zk}ITd_fFHUKOmN_q{Ey1CJq-GzvQD@UU|F8jD~19AD*4zoHGdgB@~W!*{mjt*KkXD4q?7)@1YF>cj_KBfr)i!z^G zcjA7*-hIY?{gyDleLKZp+L)mQ>Ux|NfeVR+9`gdI@~_3nb6ah8(f(z;FVy%;^Rkvf z_W$f^mJjpC^N^!oWwW7hsUrvAaJcU7)+TbPo;<@}gy~vo))q7gtWGFG7yPcz*4P%~ zgaujV8C=&fML1Xr!d(P!Ww=6FDTxkDCtT2Au zTijQ!PedyfeWnnp{pxH&%q$cIpYD@79Ue@t*e2kj0;RFSXP>QePnM>wo?Vyrj-i0D zofK(#9`c!?rq>FD`L5e302yQImS8;;muWV74wOP$g;qqc_=36F5BFb+am5g0^n&z; zp{(B|W|_j)5#mwJ@uPl-;4&i}OOA^#_CS|Kh3vt|{5PGz&%(*et()h3Yin-3yS8IA zuQ*!8s*q>V;ze8(H}g4F4f-luRSE1WWY%U%+0}N*j&jvF-xXAsaJvv>_r5hKY95~D zN<{he{Eis8XXW02i@KK?eY21~6gRA5JN?L|B4 zV&^;6IJCIhIyW97uc4;aMTI`GB;2b2#l^DOL4?%W18_DPhp7Q3jY}_|gCk`UT)fPS z*=EmXPii{Yvf#%@Wq)~b#r;@%wl2h0%`n6oIHg(djaNWTlxu1JZ&Ol0Oijmd3-uah zF=*A6Gi&itTj^s2DdzGfT>RduzmDN>lPsJls_!uSF(V4HFdt^JGRg&s2dcYW342?)Ap*cv`>zFV2Ti z0_Sb6?XPg@t`iAm?Aqt!EBAuXT7Taf=lH+r_;et1##(yth8TSwPJUFh*zhrMdZz9Y zp(*)#Q`HL#bJZJqei*B+dPCol7^^0KwV0gPB4fs^QT`S?4&q|z|BEH_eULriy6e7Y znlRHN{2e8sIO)(pY%0Zd0CY~hfmGz%J)Yq;?e2nWNd1{ZukrW>iy^sebKooL6w#~q zveKt*h@?YR$4I(rja1~V5bEUR$;~Ucc5jKGqjxFh;Wk`weWk?Mm@-4q7tS$VFunNJ z!+kxN$&9|>BlY4l%1KjjI8$(L{H4~- zAGLwU>Z8HOI?dUT-wVKNWRhe22<0Lj`WY)q7D!(njF?HkjQwET8W1Q@QBA5$ z7U(-?bB8V45AX`NjO|REw7Gaz?gLdG2K*)VqWu0vxtRR4D>@FwZyDlbwF@~~o1GMY z*^LO3$i#xY*Eq5}LU(n0GPN?vQ^@aw&E07wGPG>?vXF&Im09~1^Yxs=PdeIbZ`AxMJ~e7&o) zmVF_x3O47Xdm;GoOd!~|nDz#D3LpskPiqND4cc(N6p?KWuOUNETSO1K$u&6A)fki4 zq2Y)PbkUI%Tk@KYtGJWzCnu6%qVeKw7B(V`+yd!l7)>BtKxV3sST3T)*jr)=(U zWc#VTU#yv$^sWvW)bs~F2kYIG~>DxH$$_u4@ z34VF6MMkQOEJCRRpc;Ca@+ zJ3lw{-9v%eHkCJS_p>8$H?eBlVb7|+^es%;ly4PCVubyN>Y`98MgE83xwGdfuh@D< z*6C*-iktlUl~jz`?k3)*92y~0I{nHnJbcs)dgmF@b~m#c{p@O%e1W9C(RM=Lb@E)Y zNyYf*&gwNa`f2`aM_V;}o_}ir-e5tr75)*H3TmBXE!Y4SL2ft7;XHyGdi7qXs}~cheCs$)DWYETv{fmY%4K8 zlq#Ya8tkMX{?+I8)97a`AQiiu1wvytCO4F-fE3ela0*C}O>?WP%>Ru|YYM(9mmx|dyn@i>FWt=La|Az1Lg(A zQ{q_=XA-gAZP}2*@sO+>K_$Ezu0CvT1h;l&rOvUmmZP?>-AcN-P*3DhNno-pXS42- zLQ6Nx$NQ~>ibN<6YAWNwV>SUtFLa_B&I23HrOZQy4T0&Xte}W#e20NiwB%$WS?v!O zx)Bf?bNbSxN!*BJqRX0|OWdxBzeJAOk!Fzgb2FsMR$mrf+Y7U(%qT=n<}2AwfAT+IyK$<2otv}ltfx9Ue84|iq}PxE#2i(_rpsD4=PoI1ceBtx zZY7|ll`SG;=wd|5Ag;*0eHRjHV+PD0r7y0rPVcMo`|@sZ`>dfK^@ob6 za~*x-Hj$nxe;)TaXZ^DAF^kb{Elsx0o?sdZ>AsqOC|k#gVATCqJ+Hx}1O20M^7a#O zg#M?dLvW~lrn?^&#)1pmkg9L8*5o(UJQ_Qa%u-lo;{(1BgC~xeyw9c~zuyw2^Ur{# z$-cA3c;oo0piEYJz|HSKSfGs$B34Zi&{);t11EPb98UheKNJI}H)# zGu)~pmk#|6)1CY|cWo4#0OP%eWO0pudSF%D=iK$tH(by^`w$)jUQTg7iC+VqXRjY~ zyOQ-zv5~c!Y(JZ{o%n6)xS$Rr@1;JT0TM)}96*O)|U`H#_< zkYutU)U?u7XF~D8(GL!F^~o-q<$RdvsmX8bh#reuwLAGnneOZk3a@CcPkjQk2qFglw+Oa^+y`5Jw` zg3M%urQxs63eiZbZs8NWzv~ZE4j|0DDLrH~zwu4QdC&~QR+Jey0TGL!I|71l_HW?0 zb#_L*y({Glf(R61V?opsp+{+f(X!o5!;7QxK;>w7II1_9k&YH;5EXYn6+|i;+t-MU zJ6nILvc<+MHjAYOC6wV?nUND5=t-8ZYCNdAIz4Sr8>#!{v=ReOJw|#|E{DTAtrK)M z@gXy2K3fG9!@8Wy=5I+!DphIwk?N^xt$9eQeC^}wk`4Wof87O)U6w7%Bc>i5Jjx?d zdHdNvv)u;CVfo!0?4Hb&Y*>p$3i2zIZi+C~Lnc#ClqHFhlIrFv@r#ViA}6j|_2{?y z-yu1zM)9miW?%C7s$~tv-QYwN^6+g&DBQKCo$APAwRkQoOm{ORJoeB-G#!3LDBeLw z0x$J~eQ5KI=-tXp_l8vhP{TYNwKs@%uYunNI>V9zoTo=1O@2|Ri)0U)v0t^Mx(s-% z_MBM%gv3^xS$0Op64)lyN=0B%A;(D~_^h%GGu>Cc9n^*u)5n}y8|guK&~$hegm&}n zA<-F>$s#km`{8lxZ*=I!{9>-xX>Rzn0|jY(O!77exgxZm$o=4q>S(J@q1l6V$n(u= z6t>C0kk{1uLLp3_BE6Ipn?G{$kxPR_;c*ust-;9Uf=o44t6@%LOgOMD8+?kh<=VMR zOdgMRTm z@0ZP#x<7I4MBMF>)0Z3ps>z|YT5K+){V=L!Zvld6sxgECM^$XFx@ui1E>RLJ0)eCK zu+R`;X+eg@ZjgTT@*j*!^c51sa^{`l3#B|~Y%T=vVeLlZRM`lwPhq{pc9YC{yJ*0u zWlx3GC}N|xBVGp3T~vN&O*=-6sVXH3Q}t+X^t1UK-Vjfvr$-b9IzcGc@RJZx`c*vW z?Mdm~Rsob@$p*2UVW(K;-3FcsYIDAf>r`-f%tC@%iA6G5PZe;7*@e@rLMsUxRM729 zaDPT# z9_5IHF0vkchqn=YotEK?@*{;B^`l6eDII^3T8ZlBSQO^(0a99y3c@o6gFt`WLpYmD z+P!xVFV( z*mdyd7S`gp$c!5s zME{1E+F4#>vm#aqU@LgJ(Vd|?8iL%Ysv}W>meB}}a{oWMJx2MKzqy?*w2B8VT5^;nQd==-7u4*()4ioZ1LgqP%fd zs){W;8L4OIx|-dKhok=h*k_R@5BnI{4M<>2n3(cHL||Oo;t8D)OrFai`lpQM=Q7;W z`sFcTTA8P&sWzOWn)BbL^YR8e6z-NoD^TnqW`}|5H&7n)(vc{wP*${_A1B6|l4QBJyX9SI|$dPn(b!Vhvn@4HB^ z$Nan`F^H|zHRlo4>1k2_;WYZELzc~PMg#Z*;>XY*oX_jlybhJ$Ec~riv)+i_bLc~~+9a>7iRA2&RS~EWFc`VvLQFDr zZ2gim7PAPX$<)V4iXM`Roh5!mYHq17zZqAz~6@ZEpk6MFd2s%K(Oeu@PrCU_q&oAemZ z3VD=g^(}NMd#Oji`=y@ciOg{X0ZlMfvgwmU9w`agSnCrhnb8?l@BllMW#k{0zaACi zP?iDqe^^?eEbe~KET~UV7HBC)c0tV-%E5k>%!+BrXE~!WIvEN#B?O)hEL$6{_y`#a zw@5Q5;yJ5gJ{RXpJB${5xAJm{&>lI@mOiCuv(-i% zb{hmRn9&VCRln5M1!YACOlJ9Gd;~Ol)kplW!t@Ui0u+zJ#Em*Go}s?y5+m?KNNKP# z)WQUesR;?R#O5R^&h(@NqE(wDc4q)JdP3M8=ss9_x!l1B0)KLCTYcgwFfiMcms^#v zbsko}llNF$M$q2XUs_nwx9s8n3Uu3D2U8A#N_mAiuH63~s1?swMFgq5>O%{!@(SNe z_dZde#xA{@UCENUXNDJ;^6kMN5!cX1nJskZ-RqUeMAF!OBfl%Fz`7?{np=3$?no$Y9u$T;`@GM0#%GpQ6L zY;CahpZW|4qd+oI6_>1-NH=l#&FDWspvc7{F3BPosCJ7Yg#aHts$%jw5+M6$6JuG2 zOr2Ma5ynZugg6tvScsW;8cvX?5+Sr2BG;LdLco3NXV8*yo;Ar#vXB6H>r*m2Ecop>-V0Sf+NV`L!r8 z&f)J}9480FepcXOag%s1APw%N0P=qdI7467@dgU0F_Q?=bDz||Dzvb&2noTnwG{w=T`;pxZh`KZEC?$ud&2nP9#5-?GJ}j2AsjBS2CDGUID=Fq!#X>GbR%-B(r#vhm8y*8J}Shw^6>b zs6Z`DQ2Pukg%BJ)3cct=O2~4@Awp;1Ew36Uz)8X4BJ8oBYh}(tUfKpaVm#ID7P{Na z!{Gw{Bi;TC6(hRhXB%1XgQ9;@G5t*yD@;vcXRd=qJH9vpbFpVPCKYTTZ*MpD2x=vVJk<_tg!G8VjgpjY*Gh9ie%tKstW6=A5O zQAp!bQbR0jeI}ayrv%MC3HF~DD(y$_l#)NLCJ}Qp9Tm%y(4{vz&CGXfw=)+8#+O!4 zs2LIc`lz#aXFohSyMO`PLG}>Xslhe9-@!na!F)`owz#KYs9>eHBM z;SuuO;+zX7FTs+FhS_)O`V3mjXeO3>lZ2(P>Yq-iWhSpsPu#GV*B%~y{EI67qRZ;5 z-%l?Pu) z5KVmXNuw|t=PfWbv<11lsXd|NMReQ5;{cxEir>JnUjF^0`r4S(?h*&4eeXImvF(LX zV*C&H>-c@JTTw@eD;-@jn35$oTC=ZXmkXCp^Rtdz`!h&{`Gb@MEHdh1`r@`;fcjYEyBe|am+hHk$#)Nj!tuU;M zA_#ObUG_ZnX{6$~{Jzz*H=0fsh3Y%f2=sJx#s%cyC3c<`;Kch&&#&AcD7X1FBq;^y zWzhq_F{=-T=MQ5syz||+J1>qymCX+qyC+gvmANONvo710R+QyLN+Z{CU?E4DX9Hbzc3dkWVUc3&B|JD6uPxJ`- z=ReM50Vxhf4_?SJF-wl*VvxPsEB;1%U!~-VT@ZY%wx3WWc!laPC3Jc^&A&gC&w=L{M7_B=rtCA6Mq^p6uu%}@7Qj-g`CgQD% zsEt10_}>d0mYRmNv#2Bfxdm%W2FOxw4RlbuoA3ibT+GMPI%Y2n^q*cB>i%J<#{wn4 zFz|>#8InK??O&8KMviqg%q+?*t~8y@gLQy`+^NaqV&@-618~MFFD^gAGirrZoON7# zIF&MIJc;qvt7cIMhTO*wW;Ye>QW)tYc^Ey!}nzH^KcBPgW{+a@^e-3>!-L1YbrWZopPY>Z>W< zOR|a9$nV`FMQ^p5G%2tM#|9bprR}@8+jg9_sYi-7^7dygggvpr(hU^tQGS}B;%^nU zY~&8=awEAg8l~ncTuBlV^s)XHfwo($G-;Ujrfiubg9YK*d7yroyq`OTH7kJq_S7y8% zaLq?9KyylL`;*7yt5uKkdBnfRT#t&u45Z6)B+Vkoqpn9Kg^(1lP+w0jYZk0eWg_N# z%RMT!>-HRox>QQ>JhJ#l{Wj?iCdc|zO3wjs)Q?+<cyUQCHs zJ;+(ExpN-MvH}faO5g8lHRr>g7qwn27?p``4q1K7^p$MsWdJ*$st=Lct&bWZi!S;+ z(sK|D+;OE>Vwo@8nLOu!KGmlCAMQwlmRz$!TaaoE9s5!LVvY}h7Djge7_K#qsvzzq z4K7V-=fjHX#R{K8?Aa}nGDJUpOge6P-2pEO08O>LP#qtkF*b9dYe5)Rp`qgtzR$}4RiLpV!pVO=oD-U*5o*#YIl{f;& z4rHQ;jK6@xlEXQQ3m^4g6p5Fn|27IPv%32W^8aD)EyJSv-nQYNqJk(ONQX!X(x9Y- zlyr9v(vlK`(n`04bR#)1zyJdR(w#$hNq2X?d&YnK?)$j!|MR{d-{W|`%*@`i_FCt4 zp67L~wfAN=qv)EeB&UBy5d908osJmuW{rX1fv+E4ZK92Sr)<~!J5@2qjsF;7^FDs4 z(q=P&oY3dE5&xyJI7}$?1;7SeC|;D2IA|0dnVLWt;M7K`?hE!4C{F*^1`N0ms(ZhG zbdN-i%o9@&3<9NhjGI2lLO*=bK#0yjoG}_80Yvx!@DETdjXa3uM+0D19_+}{0>$}Q zor>FdF~1?;6B!GHrAwKP_7#Y{q1PL?;Q0M)&&3xmQ=r3t*~k~S&huj1kT0|az|hcg z)^!cMGY22P|C^CYg+l+hHPXW4%g}M?A9_N|0sZGL{-VGD0!BmDE-22S*(iG9OAd!T zB>Xmv;`w_%@2xhQwXm?@ z2Kglr$6&J2Tel)ExYJ3gl5xxW*1xB(KA|}N%Z}CdpCl?(L6MNVKf@zjR_xbbXg!Zt zY<|!8*nBB~vJ8DKfYOxz`SUZSYL(00MC{M?C&&H7@0Alizj)5E_>1eC92Cv*e&&no z)jo>*^^Mn$0;?2yj}K08ge{-NmWs>BU>NS|(wdr-)h3cuB|rq@ASa)-y{yPq%yIBm zw-cB$HsZ!#zph+@JU*pSi_}%XsEf0 zNmd59EA;VP+|Ea@o#!k3G-Dy1a|I;Yu~H-t@4S5%<)?6ECh~E@pf_|{PApXx%jH+$ zFRA?LGYV~&NQ?VaGzI3jvCVtC9bQ89E-shft_0UB;kz;m7GIyLa}LeFlYtQ?km$k& zWK7K-@I3LolR&aiROVP4x>+z-_sS*zdo~quhg#`D;2bk2+`8T@$2MoFFFWdufkt?` znr+W;7p^!HMuLvu*GlqtJ;UbAs%ak*WCTP$X3FG{3W&TMrB=l{tcpt@72tb<{J!aQ z&6R`Ta7+7@YKRJ#YFgE<+Cuk!l0;7I_E^tw@6mA8uxfjES6p;gSc1;EgT?*${6($v zH!K0a6E3bM7UOd3Z+DX+zp+>}gLu#t)H~IEc<3c`mmsFh?)#5ke>Q&pxMPI)^EJHM zVB|6Q!-Nij>^kYz$=&Z~XzIUyz0B(SY~_?&^KGW4bLZ&J z^!gqdmuu_H+wscN`twDh8(XN}>!T-BKbUyT*do|VysvD*+c#Gy9K9Bw#kwsPvc9${ zaZb)>Ne>W`)LODS^1A-Ybzo~szyQ^6a&;(aGX2O1n?yr15{MXR8Cc*639aDQS?T>Q zRrpeff{cwxQkKz9P?7wqmgR-D>4yw1Utg%*HOr5Zgw|P}P1V#AMYu0r1tG5{-FvKx zSSJOErlLe6^6+O*M{6<6scE-dMc9W&6vlI7eLXfjIiI)%%`xMRTCz2Q1-V_4L%5cG zp<8tM(}^W9^}eHD9=>6Vakk|PKTG<}ciFk8C#$)@{`KL&<`trYt>WRIZ z(V7D5iBrcWHW>9^zL{^maXCB{RfgQ?ecn-t`6+N^775XaYcEaU58zr>gX%p4x`)K{ z`i#!k>z+ec*rNtHITJi8g`O$0rKR1ZI&%HWpkso$hQ^hSpv~?I_sI+pc24qrE%EN> z{7K;3RH7U&@>5U5B1qPAmB1HLsnD-tpOW#*JK_<)Krxuj=#5%^to}4pwD54Ysh2u) zwpS?nK^iYFfZ|pIy}fiI-MH}Os@L+o)bi+6F*A9&f5h#G4@S5BnI;$a<~CaFZ6!|m z6+L(OzDk8XkV;qI#NZ)UmCT@&(PC%GhYvRmd|%<#LB}2$W)zt<%?erERs`<9ZNhuw zhaxgpi#xipB7R(q-o(guM*v3 zp8Is6ET?aGi<%vU6$3O{GnRnffQzKzOePozZ|+u$_JuXWT>8&g z(Hu&i?3ULUM(cXPEwArk*Ar)ozY!OC4EmYA*&-l`tNQdQ_JD#M5gP3af>s@yQMsO8 zaae0NANrWX8T_xRjydlo#@UODX1m+!Tdb?f%fB4mn3IB@X$@5p(c<0S6Ry7>iEjs! z;&#icJqv)*;@uF6tNd!Ep4hTqUZBj3lseOWBE3%-Vp7&F7vjY)O8whTgtk@pbyTxi zg;8P9iuCd5Lp|#?x0cV^w9DI6ddZ$&=dPNsVv^!7k5|8?d0rmdecJVG<6(2YeYT=m zyjy#Y*q&)0`?UMpCk`aPM?)au@)v8mduT)7t@-v=q*Ij*Lp8x}!?QlgD_U%U*}%K% zd~qkB7Zclzc%L5^`rx;I`?Aljxh?c-3!gN`x};r)AKJs^@A&-#k_wuuwpKtwJJ0Tn-R;1(l^$oQ&ze?rqeb)Rmw9N z)6$S0)#@az2@s{LX)Bc}ZIc-t7sO|r;EGj`;?gK>+sP=yo8clID1Gi-!2O#h8vDlnv`U+VV{g=S&$ z83WOqj)k!wwkBU5(OPZQF&_Q1pH#gxW4N60m_i0U07^ZB-juXJ+gR1&Xz7C73ONA3 zTa>6U$Zc&aCSLer&!5hP%Oz$B1l~}@EcGLBF=Ny|Y?TnVp2GNEGgb+< zV=qc-D@L^mCGFaf#!SC##vPpceH5_7I$yQTr8HwsPk4wa9J%bfXd!76LH+Zjs0s1;Y_fEA+( z+QJ=`)CD^cFssAE`Y&z_NZ09(jw7`bYOg>+=ab(3=lFAWop$u(I!GU-8IOIcki8L} zzii$45p^W=4-_ZYtOv@{qvIax$UK-UMm+nMCr+;0R#9J#Xm{>&$sHBVUq>w%NMl}? z0|^BnK6L|2(w*}GwnS|m>im66O!)6xj*ODX1Xa(7;tcZ;*0EQMN<(dxu8yA${q?u+ z*bIdkQP~&s{lk`9@A2QDb^Cq;(s`$#PbS>zQ)FA6X2niSR=?sDPy~QZ+1dpDcHs5= z-wvEw4M!a)N@q%XIUDM%hDs$A=GgonQH8Ke2$JEtN(_pB$6iab@+TG5fRx*vdG>dV zHoT~z_?h^2*x!;~Chnff{7a`gv(3MC`C{g88+C1e+jv*;?+vpw&2FJ$8WgEphn6p2 z-#8cT8prKImY@LrXF=#QvH&9%SS9Lrnk`W3qi$%(oW;?}NzN2j?0KKm8X z_K#ki6t)iZV~%Jqf9agKP@uf?LUpYEUmH8vMeUcPDr>74en8$kfBJY`3{aq%rm0(3 zkjU4$idl-->^zmFu5#DpiZNM<@i5rlIJE5kq^>G0q#5C1pjZbw&D!GQPN;61Q}7J0 zz4$c=Km$sk^@)q%x#vVQCn_593qH|R(Efji0)Ui7){F`0at&l%+RR{Lb)-nBSYzeT z)tNs*v(yuCDuRG{PF-HH6d6&?#V?%%#O4H0W9ylI{@Rb7; z+%iOgzJ~#{XZ3i?sZSc9pg_Tt>Cgqfb=Z}W_BW0ht1OX3^#DzP@AyT5GL3)%Xpn^q z0t4b5iY`QM{}Uai*Bfo)Vxi&+fEQqb0LBHFu(VD<6qu%IVu$gey88zY@B&0Z%=xd> zls>*rpJaLOER#S-q6mV}DT+BVvU-@R)m%vFwGG==?Br>t zyT@Dzq_vL7BL~>C6w5%gUz9qC&bHaLA)b7kzce%yA(I?6D<6?m={9UVXe-aZ&qD**7O}DSd!=nzVKb z>{*vW?FkAzXg*KMy;1T6I`*YNcKqxk&G{$oe(m1{ z_Na29_ITe%4IYw?9IEp%s$*giU?^m-Imm^6TjgOC$7AT4shPEje(4q>6g7fi@~zql}w!`WG&0-B0IHjnUfU-1yh zLbbAehH8b5j%>A?EQ0LxQXka=vKbab9+IaDTvV$GG*n*$Z-G`KH~R^vauF9)w`V1sNLGLma!eD3an9S#UB4oC z41Eegs#Bqf?C2;u>I!J_{Ps+)oel!*aN{g+KtyD#Y^@fgCc!`qY;2Y3Y+T7gR+e?5WJAG7>PjsjzWZ3_10*oehiyZU6 zyxt5@-L6G=Ij#LKuN}htf5x~*jr8|dQ~+W(0~xnJ{>Rrp9RnR4c{%;J*MGtexIu#d zA6@~JC}jP&NPK^LebOO(?*QlPm00?%*z?;bYq!W97pQ$V$lbucKP^yOe{Y03>d)7I zYyYRkKRf-`(SPgc{|_JiuEeNrl{$p+4{-kP$3HyyTs1$xW$zGve1P+RKmOq%;HsJG z_G5=I`2o)V{fOe>Td~*Mzc{%KLFv!Pu38n-Z?C`IUfo=#-QH{?=5EeGsOKl5Uc?oq zFumVCxsEXvdVWZC*WPb0Kj8V=BW?(5sndh??`He|wN9C+b0>L$cqJ*q{70@0NXo-u;Pv z1tz1^!T3nNrV?W5_NnJd;hBidYBuDy)}LV_#vw?fsi|!ti9~=oRZ%7rO^ZIXh&}9S z=v&7j%v$JPaoVPZf8?QDr5q_1fsju#q8pJ$C~5qu2z`$MV^aO+sVBoj`(Nm-de#s6 z-{-#4;Gm3kmYp{I3Llb{iFz%a8fYZC7@{;O`FIHIEoOXX@b!eK#oI(^Y1ftGXF<*x zO|p@5B_*}(@RPu>h^91pe45toF(`MejY;06xMSNur#}-GO^ts->YRj%x9+0c>f-Zg z*}l_dL}xO)XY|gdS6~Jo?BkQgJ9WzI?JAkAy)ttpTR!7MSY*O+ET@^!y}6@o?d)^L zpgI#L!sWvSxE!D}+rzaQ9*==`kBNY!8Qa5jy)zY|o5O*LPoUfLwVL9&VQNLo$m^BO zi%#(MQoq*$_=A(J%T&Ju$a!sZ`eQC>1zkmH%dwV`Th+$30$~+N$d*jps`CkvWuW4W zDC7-dS`;E#X`7L)XjIXal{=QtcKNZ4l28gUETM_YE2~$ zkD~LO!1{?PkGqQ|cf-oS%F202F9>vdvOd+G{mJeU%$AmySlpgisaeojqjdO&aD4+W z6e>J-3^*t!Kl>-_`T>teb6j zca$Iq*+L@R^4#u{y#6vh=kr;5ZK|TzFR$D7++&@vwAbO5>k7gQ!*MmI4vvD?V`-_L zUWZ33<1Ftg7A(i6Zf_6&Rq_-bwOjz1T zbHMl;-!eYEjJ$Vrb^F?b($n+QS@qh_^r|~8_2%P?3OAy`>9WRYXWew)6J}~cH}3dq zli@GLEq9~vk2{T5^awLK_41FgHya^DCU9`~Cn2&WP^hR3%p!leaO7

qoKT82i=g|mhgZwEbp4nCadQ26%Kh0rGONpya$H)D3V%D9C!?+;xmFTHsdTPU2 zo_jqW6E6)lL@uJ&NipKvpH#V5k{B6Xrx?E`5Gn(Nu@hVM}5w(TSbDJz=`h%veW~$B)ilH|IyV7=#~J9uL<=NrebG{Kp^N#@(LF`N!p zg5H_7w(k%)Y4+)wMr)2d50(fZiG9lXZD5Jtggb4zNEnyuFoViur(1!ltUBz*q&gNe zA!h&Bf?0HhiGcH)#K(^5_9gw>?B58<8;=0!mo?V=$~MhZmO2q(U2T2TKR8Fg>Q~iq+{O^<88AlE=?w!J=mM zSLU0?12D>G;;YYy1N$_Y#d}N01H;|5#fIG-YHq~e9{swL=`ryz)9u)2#fjy7zjBjZZyEu%3tbGY^AzRPjf+lQVPtA~Gkb#Q<0@G2h8EU@|jE)Cy4rW1GH|SeJn+ zt_kI=u}Tk=QgY(=YQ|+*)HOw9S_7UE3En{qhN$|Ciozc-RJY?(T>e&e+WDHX=H99@ z{J1+~ts{<0qL;pMQ}Ld}rCZ8GyUIoBQwf~l%po|w1d5`UkW|;7B;Cnx2Wr#Ts3ed8 z0A5}Kyr6Iy4*LSUr~tfV0=%dodGQSwz8sosIFSyHy^hGRsH>)xI3)1LH$`fua`Z$= zErqn45W@9#04-;29Oql6BhF)qRi@ZXGc9Zh$-2UqmO@qfUepXa&&p*~%h}#2AL%JO zRmW!Lan?NxqmvlfHQ_N%c*@}V1Yb~5S#9cLa3Y~-uw}?&2{=|R12IQ;28-A z_fDH^BIAkfQ{#;gykpL?r{4c#u8m{{ufXF&$q^>AS0kC<8^8 z%J;z-9m=6@;%p-6?|?`m9{`bL0Ff9_B4r+NzRmxKf3xF=vyFuXzV`{TGo%!2eNTMP z#{m7JT{i6L#3U5;+GcP&jP#fClN?VuuR(bt)z|8yV%E7R*$VTF zzWK)9+8ZN^${WPuv|u@Qsr@f^Bw=@27}g>r2l5$wEy~|+9=f!W@T?|`DA2OyvHv2d+xVXP(RQO?J zwo!{H8;fxSzYF6FW+s-J5xNs~(Ejcb;h8A(o29n+#nqLPw#o3}@NQ*)HoNQp`(L3{yO%$jV&=qAOAE-42>5k;OWd1Nw zjH|t_Qt+YK1k1EguD#j-XNH=ZDY_Jog$cKeldFIvRZ^qC9D0Py!K7C1%n~)4v6p=B zU5L(V0bi-5wiQ>L$wznVC3lPbkm+-E=5_Klz6Tmu8=(3PpZ%z>F-e-Rv`!Zy0U5fP>)0;FC&U0dQs|| zX@F*(jFg?5Mt9WsqyR2PDxO4+Xwi090u&A8acD>0rzx1Cf2(oRlh3mrU-XLW6d2c3^=(>Kq1LX zHHon21q5P2Du6-`dA87ijq>M~b%`_uvEu5EBBRhz@e$GXXmz2SvDVByhlo%tx&j+2 z>H?Tl#K^c(X{NGqDfOdw8kLG)3a|Lo>;^fs(Ugakw4(|iDy!*&`AW^w#8@u5sG0OF z?=VwSLbjij;_0h#JTQqVE8zF(42COrpTkeJll)g_uu3lSWGL-<{$k9kCJY)@`dmkr zE}?QbLaq&$gCxq9+V*aLiTiLJEJhGpXwF7? zG9Zmu0il|@V~_@Pr`S)S|4wqP>qTvkLrS!|i?bfie1-VSHzo|u7etYS6YnRfLtIDy zvPWZr;O?0jyPRcvDYsnJ7msf5F^>-z1^c8#7+}@Psqnt6w=CckS#WV4yv};vXMLY5 zEWRU>xPZp8&;e^&GU64K-)EP`P-1it%Z>7@MQQLvsp;=S9gP_Ee7YT)xB8IaBu$__kQK)9k>a)W8r{Lmpido-w?}x!eLHXY9RnRVm=WPmCv0BQmYT;< zm72E)$(eaSNzhWJ{&C|1`-l^iFQ8aT%96ud`|$o)zh#t@G=ZjWj5KwnIw>CCB&H=P zMfhdT8RYNS1;^ zvyEhVm?ML<3ghVltw)RqY&MCt-D!iSkBYkBI&#AA_e`d;2!~e2M)dHs&Drw&6rLX_ zP%hXM5^v(f{%0(g0G7=mT|!s5;mxC8{u^gYJsFV+YfJ(g4`X&tshFQdHAd&sES1j|n&xA&5BDH$`xL#@@#GQZP0gmhWg zXe8M5Ci(biEmMQ-3T1-5(>#(qVzzFj@?d&*Lc_OXD0aV{c z{YB8U#s{e-3#PmeE#la7zgrC!;0BbyT*2w~jmRaE$R(P{Ek^U*hz2eoow^N*8Hi1d z2HXY?0dUZiYQWVUkGoSv4mx*_`FV1APi@%{;WU7k#Q`si0A7v+y!;&SGVPBWDq6*5 zm*6Q2j@C|vU$<5kTtQ1qZyF{ca@1AO!6%&q8cIWfk>s_w*0M_j=4F&sJu8nu$8n!czHZDStNfsfv!@{!NEgop5qnpazu2Hmf`OnWRwU#`06i z)Ug9#GTHw#7|65*$9-8mwx?t|^3;6iqOc0aXerx**WwQ41jDb5XeEn@rtm2As~$vz zf}L6)(2#7d#oB7oKBds-kbOR}vBn6$7nKoiJC*r^3=<(W%3pnMiQTCqso6^xg%zn7 zHE_LGe=D&vIMc?-k9ZJ0Zu3=Tyetr7Yr^m%N*V0{?~#=LF#Wfms@hUhA2aSz-zAv= zris#rB>KAGhfNjgQtPBFKs}Tjm3o)^ryf=VmoS{NSw2e=cdx}h*RAa_j1bh5oNu{@yX##{q45MEyGRu<7F}RF=0Vs z87RH-*mzl9@eX2a_x2~*W|9zROqi*b&9!*kq`&P*Jvi-RztP8SQ12=YIE6nyb6#sG zKzsr{6Ckf1@KUQjf}{oUt1nJ_TzZkMEYGwz&L|#F1@$51^C4-ZY9qYDpdGDM4W`+j z4GFDDUW?=Ir^mXtTzjE=7Ir7xeg4eoVOxy@9SXLB!>+|C3nZ~(;K6sLivw=-94~4m zW9>V`V41_Ox3Oj74xy|H?F3hl<3dh3U++C|&=ld!uF_}h`|zDlb%~FFx5~tBB_(sU zJiqWO2LnR!6}j2AQV_!5-@C$(0sl2&kW&A6ztWR1(g5!cZ$EF_w6_c$(cS@%=)%RH zUs5p2`g=c|u+s%sDX}Nv|JoX3z|WF}=3oVQM{a2X&m?+QErE}TH&IMp?#}yHw`bfl z{tUx+CuEr`hci%LI)qc@t7}dsN6Ii+6F)DDq5N)mEB*&JA z!<6i~>e$r;ELnHx)b1U6i?-6NJn#!P^1M>QwLxS1>j=F`Cb8kGe{erqgc9sfv=tXI zzbT_Q4#Dz zEByIG+^sQZ4IG^f`b%k{yD%hAj8Q}_T_W8|xb@V|e3J@!@tu+pqP=?#3Br^Ux_5)%gcr}iP4b8_5p^2oc|cU|&^{&QUccg*b@C>7|9+iD9ibtac`gHb!?+U2N;l9Q z3X?k1F&6V+A>}%OcX*%cR4O)%9h@3`jt=**iEuH>V_vs*8e^SmIEGiVZTO1URoF%yD?VSK+3z_k zqC4$S`g{WCKkabmTD1c2L|U?XK>HAyk0^GnmP4p3>}MmrH30Nb8>$0%8})CiFsx&^ z#qjtT^`jLl;LHTnJ?Fb1&wm0JQHaba%_^2(ditS&b=9iOPW0s^*8$uq|GulUV+%Q3J*8h2)jJ9$ z6z8}@x$BEo2FDn+x8+%!eig?QV^6e_m|_A;(PMapU&k0}h;K0$_wX37Kn8^{#}@brCIl-abfMZLReDk(%!nK!sBmI@ho2(6(>IUHV3*0B9L6 zRB(7--ErLttk4Ub5`mcJ=*mJI?-Kwk+YKw5N0G(ADi>sBomVXJqpglmn;o=y^6*UO zrj*uh5LS$J@E2ALU5YU^x)QMV2PJuEt4tI}76Ye6QlfZ^!_I-lbS_@O9D8uyT}4U-242?18`c)SgKo{bFv~bh()V*ZAbU*0m`9X7U+0wY!)Uch0TYaH!+H zJSi*%(Ex(zMEGV20B0~DSx$Ze<9Vy)El8gsDC8AC%j($0WX^AwI%nUR{XZ^a19a)5 zKY_P)?86re`RY#AetZJejfS@G!w2HYLAveP?%SnUdZ2>KKT3ob|50MmsS9z6;IA}j3f8pZT=TJuPwK%BJUrbjG`{||}pTQ|DoSOaD4I)t-yPB|MlWnAYd3YQFZ zPNCw7u0+Mdk8+k9org_wB{Us4jr`w>7`ACb@iKDiiioz+YRqDjT{5;p=6-Q$okkXo zuBZI72=<#;IpjIr30xVwf}*ogqv#GO#Ib~cY|F|XyCRzmh>6^~Rn89&Nc{Jou1-;z zQhNZDe|>Bm7oHEt@sCfgEeub^C+*kkLX?KpOG*D91>wU^P!8kRrF z&TB8>UoKu>3JaaTdo;du*|7TcRqmr2K_O-uY{}%b;^A1QnyPyqEXT`Nwz6RZae8%2 zmK!CjVGc*@s`tjkD=~&EvW2!>?8EDTNDuo~r(K>fNB>~E|LlZ?h_!X0QO&>Zx6|i3 z9vPp}n57TlhZF(pymK%s$&|)Rhk7%q@JpQE9*PO*p=>KkETiFmd3%l=nb{-tm9N7^ZEB|J6H?+mEEBjVDps3VC zP^%6ynq8zQR5?t{Z&;0t4=tSY$DjBD$=N$YH70e!bh2u+s^3%WMX6d~;HyjGfjlIE z=ZB3DQPLgER31jj#=Ji{YXo_^F}2@W+)}Z3ecAD~>X4p}u}tiM{Nrn8#GM+FoY*i< z^e26>`Y*;OSUkvmq9Qfu>AwHm%u-benu>aF$+I$)hplBE4_t^LFX>}f@6ARVCCRbO zcuHQ<(@-Xx9lsHZ`>CNKtp5&KbSN74yXiYWGM=J`%H^Rs*Z7ftjNffj5b{iA?Bi0m zl;!WyE6tC+h?@IC=8B5Sn~8Q#jgPi*_ZRTa@!&Ld`CdWayj=rzXRK2L@7%CMUy5Br zg1hR=y?(ofJq8Z+Ez@MkD;e^Vq}2SP%u}qhvsa%%b6;Lb=T=*2rJ^|xDL|clF0taX zQ*`8MoEo^d)n%QgO-U zH*TRQu>lTiqh0(G1_WiX)^dmD>Bg5CTPk$&7mcv!ZxkPszd!)@HB>!TV>zay_$Y=W zhAtPUcP0>(olhRsa3`8pt(BP9FxeL}ZipTlt;7;A;fZETntHfshbb_8r};+sVA!L~1_IyeEg5^a1U&KG(w9vGZ7(!J${@Rj z%UC@%vELJSHucmFN0QM-tMVXKP7VA->MTy)Xt5+l&iN*4DI5#f;}y94hQ?9$4Q+vM z3|~7fe2IJrZm_M4K*N5uINsTg&D$q~RAOFF2LdR8{WBvV11(3Em7HCAMh#nf{)@C3 z#ON_Od!L-TbqQKqLVj$sHO0rFJppugOEbowVe57c2DT9XA1!xkf|55FU9nLTVDm<& zLPGqP`3!kPMoN|4(R=XJpg91Lq;$vy%P!eRS#QYiTDEAk(K&^*9!*tjtt619N6sfPRZ zmpC88-GNxE={uXMS&SzXC5eWnXcQl}L*t4p*Zu7qY?=?r_wv^v^V~VuN_VJlX3I-1%E*P*O?%uNE*^Pq=a-x= zse449>&-2_dBNqatGu$kD0$>rTd!3AAT4LsBD=ebzJCyYQV=-T5J<9nkAJZ+?8R*1 z7)yCLc=Uyn=PL?jdi8tvEDttZbRRTYZ@;UD)=Y+w>o|Pe9^?CY!jC@Y&PBwxMy@xa z_YOPd{FpzQBzMYvyS~Rmi}0LbK}ex_S@(XVj}2Wod8j<21G|RE(w8;_HM&VN4SJeU4uNWB26XYi=UQ7FxKyVO8h-CmOajcIJs{AwLCKR2Kc8! z*Qw%!$2zQ~d4Ad^93$;CA?n{U-J%axkbQ z4rC7h{X9HJ!{%#QV&yS)$gxO7eOILk`Bd?%@NIA#?A(&Iw4bCMQWebHgE&YKcq>pE zffKm1m}TrU1Vm}_UN?y5k#Te|bEx_g?ezV!j=K|k9ZlOLq0DDPup8?6Idt#WCh%$# zlSnD?QJwePr5!@q1}FC9+Wpx?o~cWl5SGXe?<^Xow)xb13X&SuA5FdvMY7OOy(0t` zht!XvKWu0(6V>Zh|Cn>pYunpx*(sX@`+ZsEUrEN@Ei>VE6eN;ehi}mTZ1mJMAGuVR zj;gn+@0){S#*2%X-OsqUW^kw@N)x zY$@B~7`bH7O8l8MdAeZS5aAc?2EcYL0+xfR-AgvE8t35PRR@x0!MMu^M}4aKs&GE@ z7DpDBCOt$eo(c5gq2QQn=JKbaSZl3IFn3{XpFbC<*M&6&t00jHkqrW=$)+5X@W{nbrREP`2@vA_L=Bt*-naH-PJ~|Wv$%PnsEr4)L@RdZU zm@Ldy>9qkQ2vO*1Vtg(#?jzaPlZ|2-bA&cpy?|s_s z?U;6JYy4Qw<4!iOWZhD{KGY>1>ha&IaK$YU9mZH~HAaSSuC(4>NejA=t%4lFN~R8` z(ha(~f|6scd_4%s_&;j*+;e3fXF@~jCGOvKz1r^FQCT6GzJuL4(G@(Ab&u=?OFNaYS1+B%vVA-3h?a zixcI<6oAVY-dnuA3i&vWgt-&i)%FW}$g zdku5d{FSJ(3;9TR|HEW;#JiRWwTo@bP+oHzGAi>hY5%geKu1EXl#hf7N`2KcqRGpO zkw2rqA)F%QO$%8%C&am9+AgA!<%RR<4ua2;vt?QHBnQK`epoYRzqOTj3R%Pb7$u+W z+(zJtm?=rNAx&-9j;31FHXYzk1@3J2RnYeGhFZ=?mZ8%HyKsW!?KO}yYNz&fYy&W( z_H}^{aO?*|Z`es_`n0Fsb!Zz${VwEKNR|+zPnLM`z09`qiTU{}oSmiSSNa-`aCYtw zZCbkFW!HUyQD(14foou&D0iOyy8P+X{ISC3^D}dKYG3mh3GcE^m8de7DqQT%X$^CH@D~XU1rzqM;rl`M;JOXby@M((K|y102C^e3Q9eko1uP)V+3U(l!z0+jM?p zAA6g+r69Co{hX2#i6rBhT_IcN#MUb^(_Me0e7v&dBXFuFZE&z!>z6VI?-;BV=Gbty zfC&fSV#_mgsMD`fsgHykmN+cclNozQZ^lJ7ErFY@eU|z*NLT0AAt`a2HP_LuvuuG( z{zvHonvPu1>WnP8nlB%$cA6vw_{KU%*h6 zNsw&NX3k>ajxW=anqr&SpqOpP0mva3)F6D=S0vl{xkBQ;t5(5V9G(08NOKpwEvT9= ztP65eeU#EL@u+h`3vJTQ!?=adY6^qTN{%xbc&bd9#hPzfhp)rvHsQjSQoKWKaXhd5 z*CR*0E?T0eT?oM4`&$yDPw!PLep(cLf~&vu-a7DOY==+?pi?YRJ$kg6FPY6wUkQ9G z(>T!vM0&&(572H@$G7dc3c;-bo6MzFaeAg@L%a2-bDO?a&U z;|%maG>?3^TsXzjGLgZ)%nagaoOqkZ%W4``_AtfB*h9L{z>JS94}T`?k%+jOdjJg3 zh+2iY?MshsTL| ztvbT}8LaR7jHG9P8;M?jypmM}c*R*?W|qfdz=vYgwZv!C2Uuh#kGPgtvho!i8^Zfv z^51`n@n-4X`xMwh7JRu?Ow@z%=olSzY~D0!qGbiW3%g4yoB@56xGzK;#}pq+IMMt4 zk*9?dmn){;c-a1X8GDtdT_q~|cvaFLv}FCHS1Qy?0Rn`=VL62tFX ziN!0mC^W3u!7zSnz6pA4#E&BN0CmoX8=~NGmk@qy1_8-R9SYzSSXr~68Bq!BP8 znyaK~8HX+H5)Z@7v(gQ^Z`AfeLf@D`i6|^hnP}qUMzx@rvTa;M(0=yQ;oh~DQqDrp zZzj(QS;VA_^zzg8*i2Z|+lI4ci*s-+9lEXW4b$nsj2`EOz>QiTs1jMV#zx!Z%VvFa z{)`P~@*maVxEz3 zw0<8PR1Qgw|57c^rxAJwyzlli1S^Nt6X(>Slm!gjr&k_hY-daug%zDisZ>hvIoD}~ zr&ukIyK_nC+j#2t(t+U)K$-EYR*`c|jSdF`Ll@c5xg_NY{5bRm(94eKlTc|0rBTO1ydlu_SO)$E0p zejSFU>>pLj@;nAlA;D~PFecmsXM}J4l91%aPc@oxgwmiW0h=Hx+3Y}3lFhZsN2P6E zcz0t`!)Svv2_GD${#O6B=R19q=KRf*$0|I8-zOv*hUFQ$WWdrJFX&8J2+Z>T$;evZ z)*nXHk&M6~h2w@BM(Pv)A_UTf!T6xqsKon*$*#)s` z9BXYlEAD&Xyhtg|q9>Rmopm&xfJ{!mkV99YBHI=?VcpOP)253~XC01DskG?vZ+ZoW zw^`RE{wNxa2mXd*W=BT&yRK}Cw|;&NA0oep-346*!~iZbo#+m?uMsX@u^_Ox6{W z3}=80V}OhXR^@bn48u5v{$P#)u~{Eyw&+)nH%RpLUSHIv6rw75di@ zNvoX6{OQw+Yl4;UGG~*IT(D-0`VjHglru(EX=ZpuYo4T;*c;=}u2Br3zo6!cZ(et0 zPe043)nj?Zgr1VlL%NImlpTBVnF!ydwLE)R?cy|WXLCw&?)tpL)%&;qkMFgqtG-=; zl-~AJGUTCTNowr2h2DnbVQKdlJN(fXZ4rj-&mP5YQ_mX;WN5LD(E03VnN$JwhJCib zotHRQmd)FqdXt6z1x8ztWfifHA$dJU`S`pcc|mMkw2jX`a30n8Q=MfjPvhRA65M?@ zQ|B2bqVcB&3qsQo`KIYe5K8t^a)m4QvUiNQM)zfoAfhuCO3+?3BonA_72Q|_Ul{jW zq#yU=#;@^2JaKLxRI4CoPMLovTA>G#HR5@xYn#s=G!x4xwsnxLIfTC0?qCGid%^)} z@6u(Yy-mB3_NIeazY)Nx(WuZnrz?46+D*h#x}32Ws?VaETD($HVA?&R_g>SA&+?_` zW`eP1Fb~49dKvnkEM93%bVsu0;fw>yU$y`#f3rC5Ni5RhYq24KzeZVzkQUc9_+xSM zEse)eaQDd%-Tg?Ve*N;b*Z`!GQlB366Icw<`HF->)h}eO12dCzm^@}p8)E}7Gc^M<(>O3Q!N{26wy7H| zDw&zC=?d$+L6C0c(m9%!Tij~#Va{ZbP?&6-CsyOK+BitFi|g6;22D2O$q#+5_O1s; zmCkLK+8@^a8*PD`Vp}@P4yYQy3Myxa3usa;cgu(Y0FgVx9jX$Uwl*{$jHu)qYHskb zISl@1m8t=ijCrW^0qeq&zOz=U#kbmuQ5tUzW)o%6OwOXrvW_y#Aj&M+D6{;jh5ALv zS~$2ILb!f_s)ek8YsW_hmn~UKY6MlOj^$CM=*uB>uKp}(!Cy5MF~l`(FZ_V@gCVef zcn_=}wyFhv#>3#<&baK(PbZgwMNEzKwu7vn_7?XMM;oiY>sNj19Uy%gSO-{%jKAm? z>a%ha*J#!JO12J}0g`7NKDjLO;;Vk1ex1btD~_M}mgV+=J6C`{RKI8ivqq;z4>>Ws zod4DFA+8co1DLGafXVtjFjIIS|uAr)^Xq0sfDFr4ko5SRPmZAnFMaCZ~hX0Ec<8%vuq}WDDF^Q4_{%Xs-gFv3w*h|&44R#;?2T0uFV0BHpk zCZrXz{~yxcGODho*&4;&Ef6GlNN@=55;SOVcXxMpNs!S8_ehjDO1HxtsnyuBOc^y<-hnDl8R*Wn z87id>DyhHhWRob|ZeMQU9>0{XlBt*OT>8?Tl_9MW;04^kooo0H8aDqE4M368%>$)V zZvRS=N$I+9B*(NWR)sCpZi(+3l2PjCZ1;@+S*D2hsmgx}(9Kt-?}Gw-0IcfWYGrJB z<_TKmdYo&tS%0XN&VRM*l@w)ioX=M#Mp2kMzU@r)`~s ztrCV*Tc3vdVv0&Zx%MF1@ZunSI)=OFa?hsMCQ1J=SHp*Te~HqpRVRABg`KfHmHF*{ zg)9EF-neE*#Rc%eF>>@-(dA1h{w6}B8+KM!GLB258V|2_Ys9DnEnQZgs<3&7f9j~% zZNO-k*3bp16l0O<=mZZ%qeV5F+^#>h*qxIiqMjNrqkQQqN%ZFpZILmmJZI{by?fY> zk;_+)C7vw7F0|dK98c^lc;Tbs-mI#;b}Q|pd|yY^F4S&m_Ru)&Qy9~m^3HJhtgm`~ zc%;o4J4(O_qj#)pT6@&I&l&m76&-|_X${ePM?b#h);A3OnP2$m62>mFk5&o8d;i$u zLNGT1K}fTv-X2>^ij z%e&)ztOV{;r{yy&ZIkOilA5Ote{BDkE0L-vKGnRAI%Con_YhkToz}u&)0eN)Iut1bnKbw@H52e2SB0-c)>3}= z^KJ-R_r)x(9EruWPHwv}MDNjl@iXtbVN%$st+*w+KR9doyJ)d-+nNrR8O3MDDM(h<;c{_InElR=)OP5vo zQuznmim)NjFv0eUqK9F_Ox#FHV#N$)f)%r7*bH`S#jQwG$vwRgcf8NG^)0y4pBC|UkW2kN8XvJ zIU`3JB<~t%r}ZZ0`7cO7SuQ@L?>s0bJT$WDc>9fTOM_Akv5Vx)7ddv}^rwS0j;)jLrIgK{i+U zAF}cx1Ae~_EaN%n&=P+=WY2gA=XTjg9&WsBg27Eoahxi*%kL?v-;{H`K36e_4p;kSb0v+<#a!!%I zo9~PG$L#P0szVO)%4&?ux}C6>+)sX!Pp6gD5O)9c+K(1GORz1|7@0z+WbW@?kwd&0y-%@9JtTEi;n0Q zC)KDx`WngWupixHT!g_8hD@gIYCw}55s}AxR`!vU8&B`#gSG3L56_@+B}N4}p zP}AUM|Ekc_eYAF3V)LPqBY9nqco?G+HC1`U-~fggPb#wTb|;Ea+SSN4w@^C(_q$XQ|nxq|i{v7gG%{NN{Hlfh??QMX5YE@obx zT9ytS-3QS09dKFw%DC5kl5=FXPk&F2gZr8F1s~7gbRh>tch>AF+z13XR%pDbG@w+MXESH^ON`ft))uc)FL<)LLn--Kb+K(SkoU1_ zS}%-5YfB3?3(slb`-tu6}#TnDR z2_XSiGKu(7+Qq7)VI;_=*4|0`aa0+_ZL6!1al!WR0$-`OkW4G@URGD#alwOH+c(=i zIkNhhkl(EfMFtE_E0gpow+Lki}y5y$&%)Qqdp3xK5OT9}?TRJ-shI3*s_1pN#=y!c$x*3;2tx2zb z&nKpS|2X2yQHD{RDjwauJ3I*aQ4Wfc{*l^B!26C?NfW+BV?>~Z!1`4$wY+R(>MyNr zBOJ&d4zw1ZU@C)Bf1SShA|3WuEFVYjuoI_9Yzo=hY z2dgyQ&de@)b-X2hAN8jZ#{O!f1V9I@$hgk4GQp|8qMGSD#6Phmce4%>hCso85dEy1 z*SUNvnb6#th*7v()%Pg6yxfMxv25w;!|0OG zx>%ZHXzcp%v$#Tc>m)N7=VVlCdnv0SdWkd>`QRj1b?xNg$w7Dr`A?oHUD||1CJlg^em)8ohF+N4M}fU#2GEsyp*w-DBXA}TFI9?e++55r$}*)>zOVrA5WezNpS^ma)Dt#g|CM0BgjN*H6-S?>4=|T zbWqgSL^Sgy*ct3cZ%!|U?Kksf*ya9}{mGYR);l)oM0oKd_l?FnE7DSyKXqCw-@c;P ziIooN!O2eOz`U`$`bv)a$(+B}iak*g;yA?I#ZOv%4yQ00(ogf^x^PNk=_0^N?0@8FMi9++2i7~B3|Br(S3WQR)0#@ zgs33827dTFxU?d@JK?OosiWM)RsDH1yBU;RLA1>g)+;?~XJ0;P#xUz_r=ad2ph~`+ zEuYDn#5;JLCEL^#>uerlQsWlC=&U94Q@}dO*?We`$=iXpWHDGRaPi_ke0fDt(80S) z3&kNhv}pcAk*a(P$Zu8r_5-k*YXx0YEYd%IdWh?Xd^C6v)3c3TnxFb72_ECr%YM0Y z0x6H_DXV{^4%$xN1Rt>gce?dk1h8!$O%-0~zhZIlekwJwJN@pw|Fe=eW#pLAI=_Z_YXk#XBdXM!opG z=lJlVsv)yQB$D?^6sq@16^i%%r_P!bEqp`f6MZsp$TA< z&G9ub7t~y7kQ0KxG^`yd%^gyY$5$tp)tIyIjX1F#&ExU5!jgh*FtR{1z-F*QWN%l3 zEJUI>6Bbj_<%89cE3@i3i@zz$9r$e5Aa8xPFu8MOsl^ZsaF{9}D4 znm6a?KPSTB0vTl%)vipA0n%ze>IS0->@|uokQR)b5IxwLF5z_<>Jh(BLI>-QCj_lK z2Yr*|e>lR1OJLerKQ&Y|#iAon4bB+SqCT#}j+57(`YRpYnXFD54b@J4q!UE0Va8OK z!L0vw*6MBm*OVy%oK4%=whx;YZ6;K};S?UubyPDsP-HA*d90{*+KDc)t` zp3maphk(2~UEtxSx5Rrm95R?S7)-U(*%?XiwMYFQZd9l>q zxuy!IRvF+UZ7w6jt~Wmt!PoH`54YI?PDbK;r@d9*_a18@lM!%o2&d)ni7=vQMuREf zWUO=(c>0Vc({q3w+JX^G9v2mC9v1_wAulO6R*{)1c}y!33`OF5N)6((&WYGsiO=@ekB{D|FPn2-dI<(aJ9Z1V8 zJ;HnSKacn)1J7``90!}k{x7O2!#bFwWbobcY_D#EexQVKW&r61n$HXzBc7Q~r>Btx<- zN&(F@3tQljRM=Fd^b#irvRFhThpfb)g+N5G@3JPGnywniazcp|^2saGz*d<2dqR7J zEGO24roNWot?=CbJ6xo5nmkyFp$JOta+DCd^XOFbKrCuMYp;LfMm-9 zb59^f2-EX$2_)p-5a~0Z%>F+@?f`@w3#s%I%SHlvh|BxbWCcMiH?JW$Q6K3&;fT7f zftfNGiXjB59Zm8nb~|r4n7pAdW3t#F8x~xgKLtwfiAM}lh7dOWiE}1AuAL5kS^PJ$ zM20(F4q!U0Mz(H-_f#XjrXf5-fCEX}^uvOqzndpg+X&geNq+7&4IygKBSI4Lxqs_S zcA{Jyj2!zHim(YN02a#d?c;QqUKV@Oono|>HL|Vv@GT%GFUlW!ETO`hzl%fDS_1CB zKHr_^NxSa-{!qai=oV&kNs91ZOy@VNy&5(!0CmD zvSP0Ppzl`CfMns9`bXc5uXM&+bd*tHYZei-V~;bQebH4?{lF+o&p4=de?zskF_A#B zP3^6#m9Q>cdo7!iY%=8~;QgB?Q#LD6oXOB0Zl3suQtfO8*3p$j9B6;s8C*mg0dj1@ z0dI)OuP^QT>kL?_9Tk4PT&_k70+ITYc=M6bgEweq@x(Q`P1xRp^G&F%bal$#c`MZc zZ7dZesSg7N#8Ag2#aTBgTYKG{ZD>!=)tB#NtfONWQ;=y=JsitQVgYVhA}p9WoVWhs zr*rU&u}WCHoc=u zvV7D4{<)AA*O?vM0!fDyuj&`2r0aL!8R=a$~6Tf>r1d; zf_H?R?hM|M52$j0U-k=BosQLxdS$C_BmQE?6k&NQEx@ym&7n>(Mc{kvKus`>$dT4G zagD@*L>5A`^rApxS7_eanlJ=OG;14ma4%s>4p--#vn z4(5Ch_QDMUtsvELk$R1;Ou^N1ov3x|`FN3MdUvjfK6W%4&&$$1XFPF(CyG6{7AohW zQ*`RD=aBydk1HSBL;O;!K33NNa|Cbo{2xAqJ>{a@4zpkt8UxY|sBODSUq){%wBgnO$lW+RkgvO6?2#rb67aF(Y zJ%uwO!w46EP(_IGy+O!bdO(meFa*r)t%Bx=-RTXPpJF7quLD4#eV)$!bt&UqT#t@N zg+i88vv$3DZCmLsQj`4YqDLRo%^-pK@Y@I;a&`WUcyx@;ZepKn2`sqg?sdj$nrJ#e zlXiZtM;lvBl01WYZ#zgaK6qz6xV>c0ECN%*r5a}{SI`mqLdo2r91_@zYGB1>kH`Bn z?yr@f+Q{DLO(fmTh)0Yj4H88IjPiSq2zBQLoL9v+{6o@U-rik@-1$SioR`#5UeUK| zDE`+<#YA~Y9Xg(uxZs<=#ATE0-;_EZO&weC?w8*8CA^CmkZ|)mwE*DC!{yq!vce(; zMi~12k4`^$&(28hG%Z~CRO1qn0reznz=3=G$d$53>G0}^!*iCop;Pf+`omG}-r)q= z8})o`=Zh&b1&Phw=A5j*p=i}|6v$(c!#iHX;X~+L^sgYJ?Alim@VzKCz;ze+GQ=XW z*{_u>m9Yhs=S8mQyWcfUh1S|hRmTS|wvs&kdWUO|Y(O>P)mtBY8{GSwGZFr5 z?=c*NSMR2c{dq#KU_w#2o^WBVtwZ89$MqGk!b!rleJg}@7(kTgO9Wk|i0?A#iL${B ztwVS6QZ}@}ZEb2Y0hAyK`kG#<^QmXw<-4>lLoi=Fs}q;dF? z79Db>+S(l1nv{;=qGJE<4(%_s;Y&D<%apoYaH2(lfZuta9?Ucn1`c%%zl$PAZDyO& zRbAQj4$U(OGAhOxX(_mMND$(=lO)ic{A5syNg-pZWvoz)5w~Z{B8uvI)!2)YtKn;? zgUY;vfeHC%Ba1Mid~PhzG0SJV(U11lvX_n1f@D%US$oHHZc&S@Ls6>lQa$=l|hai3_0Z74qxR6zfvue!4LaRT3Sbmykd zlt+r;^pd8~M4eAqFHkzBx^#%L-W}90@K;TLf;HbAc`X>bl6$i!8?XTg3lH)2Pf|0K z-ev?lTg$b^1>9bFSod#rnL z7(?x7b@5Z}Gai-n(w@>oz{Y>jNce{awVkc>#tRLc7a9pKG%Pn>Xt3qc(?r!voBb;q z8~@O7CCSOXd!aFH^PekMH$X`^;ROsCG8VYZAf#+P3%%l~<7hpjtA;ONeC0$6h3R7ytOdEwWYZS7VjFuAa3%7!M4lwX~M%Ne=e(X0i~lY7fBw# zC&k1VXi<;N8{rb$KqCLzlR-Wpun$!t`JtRYx5z>VRwL})zk!bWOdPTC)0`+u)=;+w z0jjs5PX3{mZs)rzV>opbpD!eT^$G|FM@`05=p+t!S;rL7rd*BSAy?;cM7k4nc5%nt zszt*h#mw@h&h(lqs~C({v=q46e8%&oT%Cca;5m|OVZ*|;in&^q4Y}Gyxk#+ z3Y?R#fC8>|CudN-AVUedm9DFYh0$m5?|i>WoUgL7HciuliayRptp%B4wXSD=M1U)n zn>Un>ujuq*7fvKfk74K|HcFCEdIQk|H#$-Bx!?GI*;qozl{0p;GeckccqvWeg{Y(q^K^dnIeXtAPC8)-cehwft{`W2IU3@h{UaM(=!Hg9O$2 z?>ChAhl6I_diFPimc>IUqF@`AG3s|)jjl389A$0a<{0}9HMluj0o(u=Ekd+%qH|u7 zTyRtTMzG!cwnk@W)lZ}9TK@UwWczqno%tEO*{}cj#O!~&>HjqA{(OF%(|!*g%K<&y z-TOZruF@b?Ec)wx%Rf@Oxi2{5bA<&nFnhN(*m@1~tQ_HQd5@|0K4v%ZleJl`Byyj> z*SCDw`^pkUAD{B!SLRQo9Eu$#b;59+0v)Np-uY1qIb{@-cD`jr2K?TSg{ZIS(Y@^Y z9N~VAQ&zuPnxs~2NuDer!g$Afn}FWeJ6VyBSvBplLUlZR>UVKozWTVTE~qDU5<0!7 zYX41zucrI@T!enxx2?(WWD|tn{#BtL^JMcgvB#S?*9@&+nF|-DhxYlp?-svrd*Q>+T^_l^>i}$@4d&F@5KDro?v!@)u}t^ zAU-P5ewZprr_9$d)klH?ejGiZoiq*U7^Ua$A z8U|wJH#+dYw==(hjVXlue|kq5h=9JBi{rdhSqs6pLn2l3Jt-s+m}K!b3!5$w6?J49 zj;n@d`x?^o34N`I&q+6Yb;9YD zFB2dk#N$&MDsclULbX@H_l5F*RS{J9G=d*K7BE=fx@07atX5+q^!_J}Sw->JW@%p! z_Bj)*$^rQm(Mc#D|0z)X#^&yE=F-YFg4O%NL)4LJy8XxZg_jCBEeNTQrCaxZ|u& zSw6e>HmlrEBv{!u?CRD+L;`d#6>muQQa*m^UV2v&(hchWszjE$y_855?Uxb>sP(^; zNXt}HNQqRog_Owe3y=~C_~GA6B>D6Tq(uG?x+n$z|Mr4X%!iTx;ss?}NT*Of{?ASU zaRJ?E;X+EXiZ`T7d|!C!64PWrX$1VB!WU>%pbk<}KA!%U=|NfnE$qlRP2kTE#Z&4w zOcA*u{|1s9vvd-#&F0yGcB!I0!j1=9+Nc2yT)|80&{5t!Xi6kf4eqJ$@OG7tt!2wV zkRG9Y3@Lz+G=1G$o@n(Ivb?)2!yN+$5adl`xT7AWP)?F%>fxgz@?Xh9T(} z%mGDLRk*P6^&{*5t;k-f9)^EcWS9~8Gy#18aLwl97k0Ey#g1}!5a?*U=kN0u6xsem%DP}tH;IL zV3R!GQ}Rf)1@{(sB*VX@dw?u9m5)iy#@u@kxPmu;(0mq9fTXFCJfw7l!v-6@ohF-> z&z+O{vZ8F&`Y)Fe3rs-KsM1Jo5NECYe_7466TZJt$|Lk8RIQA)=J?2}yckQ?ONU_9 z+I&xi_t~nIROg_ITXC_}3!#^>VfiW#zqx(M)TaE=?ea}>L8fS}Gr4>3SA-Mfb3f1P zzZWy3fBUlN$)@3YDNF7TtNpyL|MoAdd<(s|*GKFa%t2~i*G3|t?`DxIu|Ff6@~o%H-wnfrjSOSNklGq zM7NO_)`!1t)x71yCJo89w@kQ6cN`38d$KBtrY}u?USv6$!kG(B+nZ(l81>Q18S|;K z&%`;Pd;7NMU0xV0JJHE8xTNSU6}KzL!9G2ekgKb0R?C9b7=4c=_7^87woC#;ZpFmf zD)~IVvi(7%QGpmQFSftVn6op@;g#S_H22pxbPBY_!wA%wj~h+?8g|zp`uPCC6dPff zI02$xs!YL*n>`5l?m8Yn49tcj_arz3w7bd&l@!L*o~-^ZcyTmOXV-6I9FcCXP24_2 z)|_;%K-h<8P(@#U{)w!If#wd_OMz{g84i50XR-s~PMSu9F=e7-eV8Ly8?~gBFj0KHj6I zjqQ%rv5<)_Sr@E#ehNe70=$dn&UbgkcCbGGyYb@5GoW;u{M4Q*$jn5$-ZSB5NnEdv>9;Kc0!HBa zb24$=UdjLBV%7gdh^X)w zG+ngV+oCyv*Hzu5TGr&*L(RS;f>TmtNVwkjSvi`9_rh7Eq~7CwdCRZvw2e3JwD-cV zm??^|5e{}Hk9PvdSue}gM&G!9bud-+tC&i(mnK-Ca2aXo)~S22l`2M?H&38#AK1VS zq)}F`j!*0z$=@g#^;NZD9BO`K@~K-!-GPALIUVgKuP_IVnYW0 zC%p^me>%^A{pCD^#Nnt#7QC?Q(DvZ*6{W4k5459k@;JQXAK!s0@Nc;Z;u+MHnZ)*6 zujeST18uqkOo5lmk?hYtoZEch3Az|+q}fh8&?UFxPjkt4+U=dFwnmMzT>+r010 zYx|oUo8h;EEg*X+7!lD!*@cjC{20&q0Bk=aJ`2a9#?goX-6rF9XYw+`#6Jw#^3GoSLNzsDIB&XIFFj zG~7zQx{z5%zt+S?bd^qN)3{(Lv|)Wiaw*$2*kPGy&|0k+{&u`YKg;CXCE2o8>*=gu z0T{2A?8Cqcqqu=<$nf3U>}`unq2Q@;5mHVRkgfhluHgC(9%T_m3|^n6V&+^oxlZ$t zg}-aT9GggF!l$|UUYda^7P>KJ377Ly<=Bz_MtFiEOIE);OBBjbodP;_wzVEy6AW+zJKtUu5Mv| zemXmRb=y(AsCs>&e*5P3wEy|(@0I@Z!{j6LvxAVP>+_<$ppVbp7<=%Yc{p05mf!>O0!n3IQcB5bPOzI~S_UGyQ3mmO3=np$VH}}sv z^@+RXvG;uErzEx~%(qwdIv0bFr(-oj|)p*smEG<<% zZT1K~KjtuR&pv;6zTJMib&Hn047&dH{%iEz*p{v2YLAZ&vs%af{?jCL$BO&Y&hDSy z8kA=rqNipQir(nc6*>EvWgOD8w#E1O+`YT zTebm;kCw&1CoNw+)qx&NBhL_!!~ONBmfU5}gf;Y-R#$_~-^Q~DI2K!!Q+|pa8=u1# z#94osxx7wmtCaG1+5}$=A2q%5G$(1HK@o1S4zzN^QL^2Ge`Tv$QgTl8`raK`;77{C zin!NbPWtj%?QSSF=bXor)43z+y8M*OcMD}2N}KE-z!iJ@ZCls0Q;AKQnzk)8Xa=qp zUBFP9jBn^uFahpS_#A>_#$!?0^|F5UPpMuRNz;w=J`TNquCL4IrAFvsA7OlwR zRvH}Y8QMp%XPv^{p112kL2VRagP^gsLQM8g*_Iud6(RV7(7ElM;}&fg5d%5p=N0oM z3RpE|8m;n(tEq>~OlG5!V#L!R=r|H2397pGVM-A*IdL(}vOrU@x*1ku+koG`T*j_Y z&<;EJF%o8Cv#(r)SH+RInWZgj@qm|gnlT{MG@JK1LBXt{F%ZU%^i?sNfG>WE1lNY} zcb)JwyI-e9&aiG?l4W?CWv&%l@5~aJ8+BQjH15~w!{z*@J-#F}tZ8AeWdwLO)5pE*?0`avuNkczaAE8>CV(?%QU38td4;oLW ze)P@uyih;>R^d9%ecrzVo$keZfu!PPrtm~FKj;2}F?sgQ4!X{KerrwoK@DndNzB+1 z8TzbKi$&}6!qxr0Ysw=Vx8R~U5?X!A<&_CdT!rhB28zMO_`Jsv0nD0+w*3#ML(--o z62kNW=v^8|V}Tb0mVxt_T&(A=R|tE~DWFE@g8mHI zZvMod>KYd(S< z7p#Y{WEoIq? z}n{GkR`n!bPb_0&%H>EO*mb| z3|kCr@^JvVF{%JvR^z0A-=y{N{et9BqYFWQ25gS%x?nsw`)N_SJf%l8D5$MT+0~Hd zme`FyqCh+J5ddZ~?C45@Yk{qidX(%ZaK$E-Mt#4>0K}%W0#ZPIgTV*3MK?|Axv>R? z4?{^^CCRVTzCm*djSc@^I_u0wlTgdwPuEm(%!drs$`lQk#-Rjn+#X_Xq6)TZz zUSY_TSOb0wuoEa@LHUXo0c`l(j71P*OuVUDnW``@pFLGb)?kXB`TlUeiO{oRrq$1VGgh={IRuqNtVQ?X}kC!uQc?b$Uuq zX`ljhIA&nxmOdLZLP482w+Aj1{1RriCPlR}m=s6nW{!Ma9%xco&}Rje!DmIR28#uy zps&znb!=_SMPP=;DR&7_Dyby{G+|YNSkqkG=LKXk^3gku$|=re4Mn&N+Ne%oJJ(OD z%!G!h*IYuz&I+;k&~UkK_;BS(3ys4@fo;Z<;?i7GOaN*1)>3pO@ijcoSP~?&O?Xo3T|#f*9EtdH_~nxz_uc2kO0%?BtV?wH~4(o z7!JmO!!)z0^Ulr1T(T=VT@hMq`|eJB7;IA6({~4zfoQ|O7Kl9#Wyg|UYuh3xLT;0e z1h-3LXdDRGnbROQxCn^t=O>3D(?*qG=e$iI!0RrG6m`(U;Z#E!)C!Nq2ZVeZeqf^q zdt*9vAZGOnDP>WpBk|M%7%2lXlE}+QR$jt#?6eqkjzCyZH@l{Qa8w6W7Yt<#fl%J zW?`HX3KQAi2vI%G2Q|b&EyUPqK&j&%A?Pq`X{81~L=$5@;B9Mc^U;Acj%^UBn-ST3 z2WxYZcMe62Agn3LqLpXcYHNu9r|~zz20!y^9h<{-YW$3du_>U|56OA^>DJDlyDUN* z59?Op-i*<<7-X1lYtO(#EV)8+x{u$0+ykLJoZb^wj)Qf<8RS1`>k+i))JDq4H4k%Z z-**CZWfhSE%!`Bmpd63eqNW2g0;I8@)tCN)poJh%0Yvc&V$K#d3P4~(+(HkCC%7*P z;+6^|awsy9^q}d?<*HU&5!|D63m8b4)-QTm0GQfTpp!#!NaI(S z**NJ*ijW?qm%I$&`Z5Hmfpd7JkkbSL_LbqUbhm(wla+;`Lt>?^Pn8mc;KB{~6Au^pDk*n0>DW4VeP z*X^aA|9q+Ec943$R^-Grhx1#M;wPPx^X|S}YtLk<`*8MlNR7yw)<(XyX6y4+dftW6 zSok-sx*{e==@DqVG!*9X@fEHEnkInyb+&ykPO+)hvXVbLoExZd^qy(9(xhUJofAct8g;ejtt(_TGBVKZJ8Hv@_Q@oYje3!oV$Wb5&O#+7iWCIceeuvE|OiDrz1WI5|eN52^g1z^&qCK9{OBxnH zVsjC^hCt#CBMjE0BMdm47hUdyCg!-5UXRLd^vO_Z9{#MI=-m0TShLfRf(3nwlM^&O zV!L>Zstk~^f{>Aog^*E(kYV5e=$1j~W{}`&#J#?!RemvK1u>Kz4e_rmdIb66_MW;F zVtLwP`{FBtcgGo0=#W-l3b<%V!^+^IGqw;xytAKDuFGo2Z4V4zT5C_q0dY*>i(^V5 zj!AxvCDORadf61!^R;Rl)NiLhj(Sh)1@y8d4Q7b78B}0e#vmx{vlT!Wm5;VM?)O1@ z+#mj+LgwW~0hyN`gwP>;M8LJaJYZ|)KM`9q&It}OJMSIJ9*GwDoaTK3z44f_V3=c2 zB~Y8xxrCP5yq^m)&ziY|N3O@kS-F`}dE|W)n-fTO+vir|H*cd+!-VOjgZ{{$*o#)h z-IJwTAnck_^bgvzsV8h6y;}5k%KRmQ)F#eEc)az*w1qN%nipy1phw`8`9$kX!!zn% z3wqmcNfOfeo`dks`H!LXxj99 zh+_Cy&_GhoI^ zsFDEJBs4K^g)jX96mZ$3s1kh5^}rZC{j`*jG0yiqAroG|7}patFO5*+Bw9-}L<&q? zH~10feE|l4KyK<@yRD6k0E#V_-k_Vz4zFFA1XSa-z!%9t3b@`%qcPaX$NiJ#V`84O zc5;d@a?~Lgbq>bJ@gqq~8lnc?{jtTgOoT9iaDQAjwWj!|t~?$;ZiB&<ND`%nJPr&L3C%bpvH+^9HY5OR%6im(q9(xm_HMg;QAj4R zL-{tq7#AL}x}_lkSmjZ}np;UUh7Y7Ti>}IVf9*@o&r?eExs1ZWhLSupC6oj;!la72 z9|i^x1Oqua+*Lw3_s9MB&CThbM1)B)kdPpvfuT&JAFK`N1ZR_=A|Z)@c8=Jw+Q+2j z(v;r?8skF07!!sVBX}_e4NY;TD9y64>a46ut6h$0+|8!3R766oBC@9`db2oUL%&`d zMvjj*xhmqH~HwVQnY zo0#II*GK#C$(;Ee;>2@j;BNn4qh^bp{_>cD>CscV2NV>szWBwnVJ@xfwoJL3kKW7I z!N3+s2*n`{CZ|Oh4Ri5&(%j7Kv}gHCxTeyR#<0J3Z8dU865cc-1jJjNxF!v?I$KB+ zuuMrxZy3479lyz75Bzk>5JcK7Dzk!n;taD#ipFqSL#{gj#)H#z7r&so%cc9OYzRZ7 zZzqP;$a7}IwIBRPZyr(8Ck|F2Zo1zoo@(HZD*cU!LzR_gYIj`x4kw&Bmvr!19Tx@R zaT1(n2n44(0KxH6131NRQl%DwF+5xpNQG(MdQfkZz7!~zQkQ%iNV*$GEEH!!q4{Vf zBd-6(1DjF#y&?JLs4Y?ufs!iPgYCg;aM>3TmpBC^(r*N}5?vPeQ+?Yz4L)JA4QM83 z&FK7Clx3NL9kI}43U=a%JZ%Lyl$a@Bs!BOwE-R!t86d)pL16y;I;t&26+gnbQj(Y$5)=+<5zfq$VLWmL;6x-B^+XoOL8Q<=7|WUfQ&)sQ5go@+eA|6dyx5vWx~>e z&OiQI^E?1)tcYVSu=4@~DtqF!qPte??KEEY%-2e^nuaU(fh2k${sex;JeOz8D z;!7h-5UW%cOI|Q;dluL?AcOL&9nl$oHIu;zapJlym?URm(w?+jjoFWpri)XO4@v6iTW7TrNJ8?bz8s-L?(r##) z&dbgo%9PsEai-N*{PVeFu5e8rn$d;Ei8bc~2gZuH<^s`aZ0H~9iGt^|ODk%j1Jm(Af(V1%>1Qf7^b7L9J)t7rjH;W$4nT;o5zqI`=}sKcPKmk$^@xJ z?iuzmK8Z2najZyaF7Q&QQV76>>XU`>mNKMAKRlFrIi-=5@1p1q)Or;NswpsaI$up- zs`=Ec{5}+!k}Zu1jxlV?!#toV_s7~_Otz|p%{wJEI8`;CR^-smawo{*pYxXFHBh*T z^m?c25@&b>L=9Auj{ykg01&f~fCAf@Qs;#C1k`5&9@w+DqPOCl0=K;W+O5BPvo zygB!a+k?8#d0iW3wQ%rIzxQiM0WdrojAquf9$pv76$$~BhHB+8aQ+1jNmSI-&I%?d zsQHU~rTqSud~+TMgw22z&9CbmIS@nx)g>u5yCMVac_U4{n2fx&5MbF8x!A%BFp3t4 z*i|=1$SVF-w>kXqJu{|QRy4tHHNSj48B=l-l~!~iMP|*b5I`n+K>S9tt=5gTgR{s1&d)MDdPfNcHi=qcY&ub8cK4f=R zEwR-c(frNZQgivZ!sl(n66eYM`MGC_KW_?^vDqq?!}P0!rf$prKBQlUJCQ$h25RT0 zzfs3+@4zJ3`y$A2v+_8%-L*#Pt3G>oFG-fm4~_#Cz4zIcvB^%rHv%~0A3DM3l{+J$;aKx|5oHC zsgbT(bO!xSuZl11XsUK#?1Oba3DAqMZc1rT*UKuK%G=dzMM4CLzpN6kt1skF71=b! zM9Fdi$3BR;U21HZPmm4;p1~r18S8|F{kuHSGyXWH&G>kF^85GwMfo#MK%r@nEsDo* z4L6iZ_q8@h+j2mbk3NQi0_8++3fkP@+QosBbE}h>3-j{8eKAj7Vh;K|w)u$yb%@9U zT(=bk#jnyvmTA1ZA~Igw_SPk&_3k`twvFW-eB^X;z7htvKPZ-U=fO@GxeHw`g=^QH z#)uOi3j!QV8@zsjrWZb*GBv@}IJg9%d2&G`xi(FID|Bg%`c1_n+z`00b#Cvx|x3-|91rPG9>v_AV73!96THJ&#a>@4gJ_S)jVD-i9r|P(uyH zO^r)u#`?q4$%70O0fx~9JJRZNe3;Xc)u=MBLGP3dhGOI;yez#Zc7dfru{~M#q;m>?)`mr3Z}kL+s%JDyIDL|38k9_ zOT4=72-+qXFYi0_zB?wiYa-sH-Mr2DofgF%*C}hyTqyN~6wj-l7wrcD2w9JsSSYZ1 zazd|dGHst+&AHxK{>9mC5H31PYb-_$8eyHTX!ErVcQ97fdr$KhGa+~sDNvK1rJwE&J^7u?e+dhK@&oAf4bHD>xr?4H}_jE1Q z!ynLUn^;sE3kJn@w!jy$p1^K`FQ!jj1o4Ynn$UoK?FE~u&A%(M|Xo#r} zX1E6WJ^GORRy1I+l%Z7VL2)rbSY{OR(>O|6Nlj-Zh7vPIQPE!9Q8KakP0gBTr3tI> zzL2KYp?o&pl7p%cQ5u`Zkw21p9sPjN$rm-e?7jSaaK857>&18r+KA8_x!>B8_0nFb zS=3(jwvsA?1axXT4&ImF>Eb^4YjMdWCIz%%a#MZawz#1=Q}8D8_ba64nI0+`3hN|s zWz{bh`nrRi2RrHd#Pw&5VZx?g7j{f#@LsfgGmxGqvG9~S1I?sLhj;aFo$&L?4m;n#mqJS|F;wBkiXI;+%bt^NA@)Hb?vsG9V zZbKZfn~~YSwQpjYqURW*=T5WS#XzqZE(IcP8)rnAKYafG?3B9n9Wq$A&D1R_UuQG!b43}u> zlVZD6nm;;jAa}T9OGho~oQZ75e|JNH8ml)Lvh7GKW~W^=r<5@`pr2ndu+YMj?RFnB z?Q;9-q3Lpyr}^IEsYCi|)8zeel&dSv?zB#MGoekv_)aCpkY zv`L1#cB@ivJ%VknRtBD%dPrF5Z5Qb^i+AoNJkeao+#N9y3>--KX*%>UW#Oy)N$$|o z%F_g{-Bu!w`z;1ntJH#z#?VjD$#CU0C7bv!iQn0aO_IsGc^iKS>nK&&8HEZdC zu^8B@zg`F`)bF{(M4B+!q7d1x%tDtxkn8Nz}r%!xXXK zZ{#4Uo~p1Eb(0oXH2wn#gz3i0BeN8)w?1=9@K+{h3uhuT*NHm!{SSqb?uTiIhc3>} zmS?$#L7)b|S__fJD^&AFd-Fy`o@ST3HP@??#|{u`>0u+PMXM*d+f(BcqCX?Sw3%HZ z&e8&|o6T{npS?W~Pm|;I`N`qRnxDu<=$xy@yxZOC&4FEk;&05%$NB*ZZOKa%{Y7u3U{jYf-9A8&&ls zQ_@&5uDrE3SqF@-ARiY)QnER#pb4k7H_bbR8T8sSFi4TrsZ)AlR&UnDM(KeP5R|q@ zPLDA|3vn#?92=mewO#s3o58)6B;-LtrxYR1!JsCz3Bh(#Yy_FRF7CVg8TPceJFt*EKo9 zIVyrS>PeVigo(+lH7&w;%44qFqvy;5;VB6H@owqkeIwMSulwH`j{8j3JD(>D41sI? z(H-T2LRXIuti>y>VZ;cxJE$TSnAY({UZu zd>S}bc)X21-`{;3Y=4>#Vb(ycd!;?+-|oJj>ityi{WJnx7Q$0G2>TI^`(CwMcsgeD zkw5s@T&ZwnsVw@v!J}(iYNI;Y2S9Mq+of4=4CZvRn!Q*`` zZyV>Oq}N5po4pt8lK}Q25pE>_dwBFSc1=^I!nWBL?2`a?&B1@LYXoX?PyV_vfZc<9 zY?j_+e;PChnk&7|XaHbqHuD$mp0K^0bn~un!(%f;nXDUiYvY{neOENoa0IYUUlbr= zTt>9o?(|zjsWG+5&9%&~IZJcUt%_UHR-!F|rR772K$%`CWt@WvYe*^oLXsvSbRlk$ ztD0_`(+s_#jruaQzoj^4(a)!kN+9tvl!wa0B2B_O?KY=$IOG0l_{gz&us>Q6vN4Mi ze$BX>K^rGG@NlP>l)yY7j#h+oq1nv%%T_mXk;*#BU1MSO66sZ=FXBr1t(x1D1_6a! z>hR;E>tkW7d+Jl*(b5XVt|jNh1olK{4#$rkp$o?5yssSJk^s!?gNwsMvg)!)dLf{1 zYwvP#=hRor>&qzr4hD>qx)>v%B&&-a*twf?(s81%e{J(Lbi0e^xFj#o}^d0IV_`Y$}M4{vUdJ{YJBb7 z2~T?(YI3|J4l_4CYoBX^rOR;g+KU;*G6C_^$u!*n7|^#RXQ$lfA9vx9)$<0`@jngi zFz*&8f!(5yqDdNY?1Z=a3(CMnbgiC?g^kCSqY-D5tM~ODEm#ofnbRDM_wfu8P}s#Qa7yI?r~xm@CS=x|X4j`|IqUZ)dza z11{(Y`TNTj5J*9QgmqbH5OA{efshK^w8nCk2DRGfg`Rri4tdrthWl8){Z9kmOk1Xoh_(%A3n6I3T&r5EpRUOy=zqNbd04nrZqMCi`R@}ncw_d z!{`cbmLS$nvi`VF2Y<^gcyoJD1w1lI;#4U~95*8@t)bBcam{3V6CQ}YG$p3KY-k@S zaB}wZ_Ugb8X(8Jhy@IvD3FBfvE$zs8Vbx^feT+mMJ9!CAC* zfR!P`BHywo2~CBQUX<41!O7{$iIS|)XIxg7cAKH$52@+yhXjp5JB}rXCL^S1#)ADrnoBP-n1PC z%tVk&tf4D8^s(MWnb>8lv&MSowg0|QE-5OJp{N^oMFM)tSWMskm-Ilo!UDl#}0nxs#*o=Knl;>|A=_TT3uEr#-c8_NNz`AsH z2G};NCzR$b8F|5Rr0Hd@AeNamzG-mYSOq@KRoRq^F76afzi)LQ#ys(dg76Sr7ZJIo zvg!;}RodmCZ^KuDqnjiJ$Li8E-9lIl)xj~JGsJ|9-hTcjt8)2HaHNGwzYAd*T3l|l zDpo2r17S+#md}>UI6>%G>Q|*!L8kHqzgN(KMjfJ=ZO6=y+jL>9a&j7;3v~I;oV?ih zzDzM8gB_wULV0uqF}W4;xqZn1nqJ?mCW{$k6i>B`>a9fO`ws_uP%X(mtf;*k_$n14 z0t{0NT@c*f;_bs_YQu^~B9FkDDt3S)sOArf7>j(a{0umYH+;4O2GFbkh+x2v!dTs& z{|SOrabK@b68QPPzF~YkK|R()vNIQ}6^1Z^l_TIm+3+9}DywAdt5-=uK2zLFvm^X`=m}x|Qa6lt!SKvuo{uiB z98N6>!}&MVLLfUFQB=<04pjcPgTo@FHq+Gg!xluC2I<2Tkq;y4xM`zu49n@hxE*qS z!38Ov;v?zC%C!wEWLj-2@d*SCScaj_+N?I?nDiqX&u;N#s7N2N z^=f|2i-Y*NetE0OJY0`-Y-3e_mWyAp2!Oz!{Yml_GHM3t*m1QOgr1iMo%ai^g2fyq zj18`bTTB?jHW#$#;q0rB9J^OfECcUzICbQ(VAQ-&)cYGIknOE09;DJ~tA;HXqmRy~ zGIYk7SU7BGPm!)VO}2BWRnq#!Yi3fR)pZ2Y_tsV6JQzlIEm=&KK1>RXY&a>+a`DEQ zGxoFYg3h(>Ic^Kq8Vk*HnKnIryfk0YMRhl{d`rLk;CE53%NVGW6>&kqJg(g<3HRf@ zcJ3Ihti}xjRQ`N27}-DqQzt&8o&0c3*85;`*Wp3q@U={Y>wDzK*GEj^@pe;o!fbZ4UI-cn6XT zo=AMpD2wkSKHpP0lCe;%xwIYy`@mj5B6<8zzSpbbZE57gaI81#9sa4e9u!$jHM4>q z=t2rfd??`7lqQl?w@5Lb3m?{Xta9XS`6d!dxXfeUgR=R-{kLFCtyH-C?8UdVEu~TA zNPafMsP7ZK z{}&8900!UJ+L@{WgLq~G^qWIy({;of^-EI61}yR~YWxwBAI;7p!pO~jvH$!y!D{){ z-0f5NCe)2uV5(_VYSqsTf^`r@#1TE_x`2^JEb-Da7k!qI_e}3sT*~@-hcl(upD|=B zM(B3)yEO-RGF400b-HpP(#x$Y3L5|dX$kM%n2`wwWm(#YvBI0FYuW>Io$2|c;BV^{ zI50Q!dVZ!86E;XZW=wUI|;jKw89zj)ZP);y= z*2Tx3`i6c@%o{4OJy8hh5)S?~O>zymn ze;p768>nhk!ihacj?mlF zuODAK?Q5ZoC`R#KVIz$6m}$O^PbR0fvBuNaW%wnXmN_us$c$hEHu;l(PJ<3s;w@$S z#GB2E5LXwbpYDTj4uO~Wn$L@4RLiA`FoI7}_TBT-TN`^0))Aj>`n9xI$#eT<$S|Cv zb%Su6lXb{yYnx#-1`4^Sn>baDZ#b7qB15XO;LEL0MyCF;kF)S6@`h7fW_y!)Xj>IF zlUGF9^~?ZsyJgx#c1J!-yv#$xT-!s;6qCV{c$gm%YdZ!l!9~WCq0`c_Cc4_C%<_v& zfBf(Jn9oVQpFR!h8u|2DEHlia!11%kc}lfI)y`<)1tIb{N4f|ME zIl{w{;%UNNa|D5NFAtU%ZrHAVLrlYS>cFKDG;VgBP`c9P9wz_eypVmHkyo6l*Dq^f7 z6x_w(jx^a+i4PmsrDkJLjxR)TtdL&Eq>!}IJy6Pe9;ITq4LR_2AUf;L8#?^M1HCwg zH7halW*u2v-YH|-V~e4OgZSFGZ4iGNZBTxV5!+w9yJT!I^$QclRymG}0sjxGOD1^v z{R0bu`M}?FgqC?Q-OL$pO??IY$G&^Xep+qw3Rx!Y^e(ldJ4U93`cP(@^l^PBCLY%W zx;==j>8ls61p26e%YAy-v7h!Dv13Jg9a742&;EfNJglnw&JD%!=)3M|YtcU$Min77 z2zrz^*-8a2PjJxd0}6|1jNVVjz4brOmkah45lQxk8R8TX%_=)s&nH$H+aIC&ci~dT zxu$BGRV=i4Oo=q;uVV>TUk%q_(CRm-$W zbgj&A;b10qRxS#k7Tu+(FD^FqPz;x}XFHQM6oi}wl{@HQ|H?`o zEoB(5gVNxNj8g`QlIV(d;_iL!X0Dg`h~n$m>h6x%1E7sT_2cj*ziL`<&?S1$#r6H< zSZZs<^MsL0D8}z6TZ&)*@B4HWuB0TXeR-mq{X#Cac^WQ)FES4Ai7Ey=@^II*7Qb(3 znPnX_5|Nx*3{KIYqRMhLb#o<|W9atUuB>dsmx8#GC<3y5KhsQZp2w3*_|;L;~< zSBJIIf5NCb=fbu#@G50%1<=w7`O>U#qH_zu4Q_2GREi_L!q9TR*e1&|A^q8`#Tc@I zcw!|fOekpFj&;eWJl8lD&_0!clCn2{tb6EL*quBwP2(j$e1& z4K5`n7Z&*x{n?-8e#<~m4<|S@7_>rN;DXzD;-cKWjykd0zwWJFdYY{Z-soRdSm~dR zXpcJ%H*FCdd=Ea=qXAoy`G8K~BS6M23O80stNj=QaW|~eW*pQmxP&VgKA`cBXxx}B z-d~wpyrmJqPWXLslu4ik3dCO^$x~y7|Kn|& zX9W@#d&~DkURN9ha5r+Ai%QPMi7R-=yZ6&?c53?rT%b9zsyWf4LiyL)HJpF#jF$yEF84?%k8UqSa^#T19 zK>)XVm))SV{B-F{%y;Pv!EEUy6KpBEQQ7G4!UU&iw+z$Bn>tdSr|4sgSuI4n3tuLX(CGfemfod+ifgrOxz<$0DJYruS(ovh1@A+RD|9-=b6 zZ}E1czr!Sx=!Dhi@zg%WIPp4?tu<}%HTZNbCEztzzrhO=beVsIRbod^>hMP|4fTZ( zJkYzVY-jCBZqRqfk23E6=r8f>)5I^0;~NX={@&%v-b9AMQEi6DncoyHOFkFa5HBa> z&sz6MQ&01ak5b{6er#t7rraK(LWus)z3t+!Bh6>nu#NQy3oaNM)9ViPX3z7 zF6)^5J8>dN`g3<&Q#>SY{@aQ;7yo*HLa99PC&%O-&^uwLrlj-Gtjg|~|DlQjYrb+( zmmSkLU@yvj=c2jQ+%xj&oTKs;Ap25*SGTlJbOrQ~hvHP6mVgK`Tl$XV1L~ULY1i`; zrvejE-2Cy6LJj7+;Vm&;6L)JtF(tZ=q$D6kIZh5Jw}J&L$lO8W8|J(AwBSpRK>=(K zkY{9F_Q|a6ck+0UOuvs7pc;A zc`FI9LG}4LK(g-PSYg54liEe+mcS|jp$WHtB5e40(-RFCNVQ-JTckPocNBGlaXuRjtYn@@NohRK?Fu>Mz166=ct0!^08Cit5rg zZi5Er@by56;}?kbrb?^bSU)99fGtCga3~OyT`ilL@P(ehP%h{dadAVk&&qd~c+$8z zoRayt6)WgAEmcK80eYVBhye-hhTQ)}1XCnF+%SoA(6t0}qEseWz6bIt2*{_P{@>BV zO}_=qn$N<%gx6@7wty*e>;DxyQGr6I z?m9BJCH*;a*6li>DBd>!#pRlb%DU*owk-$yy9NgyJ2HsF>oRr{n8lANQ=2p~%&|WQ zY}N`5PgTHKpXK)hd|NQ$3mT9h61FLk55D3C7oLH{!lOYCZt>(_LqTVz8S{~Ug%|k`Wuf+QTE0gKo=aViAv({`iUMKu zf3osD@N6TXx%8}aUNSNu{WzPQT>4-6L?;~25;i|VKO9nR>e44En)S@ecgz1`<^7H= zM-m8U!5>`&itdM~XJ%M5Geq9V1s6m3#;7eWc8uauP+%_~66c#gBs<2g<~0-tl-#(N zk_!$LlmaF(TE4U1o$1C}Omi0lomUUqS@G2T9c+#c#R2Q>(+U38wSm~#Ga|Wvw=}!dY<1VUOC4a_m z#CxXeS4yNuZ;29H!NU1bSEBoSHYdURd;bK@FKZ5P%B+i{(OLGl^4NURBTBUAA>qv_ zBlV+<5Gu@rq}QApZxy7HvcJE({= zF>{e%`CUC_ zL9Vbrx6eGhuI7n1J@#OU0sY^jD!U+>DE`W5`V1+)-otR=3A9^@NY=`2tRR>>YZ3*`r;5%v>%Om=IXWPORiBz zjnXyfRQ44Hp7S+TQ%*a~B$x)%%9 z(Dd;Fe~xg3$RPXhQ8lWZCTU2L{N39(!o`oy(IfB@|Kz{Oq&PFdlwv2Os~BNJHSF15 z(n`8BVl$bZUnM|#6dv#3uS3Kniz;u0ireRHbr~O8=&Olt$dkx#nXEqXMlh!6>jkD@ z41u7jsJ}|ZJ3~YN0-~uITN(^B4;X6yW#8^r_DjS@Vf{KNZABJbG^A(+)zHp!6Tvnr z*9~Oh(`xw~GSV{-=h&7re)~xEfHYcm1#G3s#63Y_(pm)UeHC#+oh=jyv&^)7(lNaW z(5X}uiYFfLS;K`;-+A#^h5-kwP4^+zaHE@^>W+sWR(Xdd?}DqXr>j%A^QOk&Lehvb zc78d%d!LSeCF6Sv$442MmiO^p;4dk=>Q1iw&zC6~lxR#L$YQdU4}Y@X?;FJz0_;dO zW>nBh5}Y$X^Uf6Ml5~siq+mKt>{Q?&T z>rcYT>eW^J`JjV^>I5Ztw)LYDiF}{=eTvfV*~Y?1wY)=swcJxgC?&?m-M7Af^2!Qh zwR-s&T(&IUWaj`oUefFpxqGA-A^QcCxX@&eherCi&}#!FVhJQTmj(^3zFY$I=OokB zkp}Q-SBlBKt$hMmc3APg-h(J{@9fkGD8|E&D0K1gW`Z^xOH6+%rWpFOUhOw5$G?b# zQwWcD?s8IN4CdAmIIe%J8OLFMo0V>&q z1ynLU@o$ye>U2`ckocuPF@CWg1e-0PmY!J z6{4OZHzC@4EW3$QG>%>@J9!NB`mgUAcX0!}q=7@^XzwlUs;$vIE%g-1sUr}bqt)>% z(5pxMG^fN=G8Tu#qx~TJG-5RwIzao1_O~-7JlcJn+ zeUdIp?kKq!5NwVG?)=dmqu$_u2TDipDWPIRv&kqk7X5(2~ zl(rX9oyKvu3F?0^?Y!ej!6pvf3lfj?$^kp==8&LveN>pG)RI%-=<%tzto zb!kxKbR1S7QcsxIZfa!*ElL)zJB|xo2hw8c;WIoSqZTGu=#eoqu8DoAMXQo-J;N3a z(p0Pz0^;P2h@nl0dLebFg}_jWglH&13B`=OsI}Zx-B5{aeCR8>-|81~BARm3^8L2! z9~7tMCG6I3dG`zSzaR+5t6$iNXm-v_4B5Zwj#rQI7Gce<^VJ9EEww-uGb3u_zj{VqdLFf41!)p1VupuQ-n%p>bt z-&3~`)7ZA1SdZqfX1!qZ?Wdfrlpu7IM%jJ~A=SX#q)@#&q+N4~K~F>YL@TxbSp2OG z($AFiC3Ws6;#w>p=b||DE1@NNsn`-tk-&K-%8i}&j(6OMO4l17@N)n5@Nej?J&wo) zbgfQK4#wacGQ-FHJ(Mgnx205KbI4>sqGYnZ(Y#=JQ&=in#`(4lfnRD1#P)qz99OPt z*5ddg^YO?GF6hp$+78txg~s%1b&>k|&7ej)PUy9io&M5-je$<9uS_>|w_R+#z0=~( zc+NJ8LRe}Jz8&7M)_6(Q-C9`cBLdCE($nEYf7sQh!%gR#>#J7hv)!|Wo;ykVqpz(` z_d5}jK4eE*AclE_?I!0jA6R1G2{k9~mCkqWO#N%W%Z-w+O^|KAv$O zUB8?un4k(I)U~p3Lq95N*O0~CPY~u>uV|WL7{B6h!=O1gX zHJ@Mn+}q<#p+uSMd7cf@Ikd#9&0$YDwBXKib+eqvV)Qu(;5;do`zc!%lSZ9~$&8CK zU@t(EC%?7J>TP4rP7YY05^wwM02|V=nm{O$was{$0f#<5ANa8#4~?NO&^Xq$@XLxX zi$i92wXfi3G2s2sZz@38Q^I5=LgJrGSgt$PW_wp>^LkiHUyZNL8uYNF6zPw@QO2EO zHpSB@l|MI}_en&WtihT&nD1*`@W^ir_CKxQELE-T|Z9fCfktpLl65@c*g5J8$U9Ypl) zyESd(HYo`U$Lp4_=hUC(y%g-dYytPH89O|_kSYU*Jrygg78I+eW_;||Q%xRZEY4lx zIPr^UD%MVI?S__BB0R=YV*KZFox-S&1&&z;B72GD^ZJG50i*K@jsxi4>&R#L8RwBt z?%=OgX}YPh*Zh&AWjl`Ht>4tzXERU9?DG`d)->!9n@$!k_{BfuWEUSBAl)L`&m(|g z`6d=Yx?0|x9VZ=$LD$ls725r@4nf%qSmuknfownnimane>yji0L;k${$SnEx_k((Q zEA@@hoh-+ao^uo-RjJ1Fat?fSoZpPYUSpp)X3GidR1IIec~kb_>*yNW*rV_|uCXi~Ko%N-4O>72)DvkGh}9 zUM=7?-_a_jn_O@o1j26Icb>JVN?Xy3u}YlD@z$SK#LMS(GLKUighQ(2esd!w>NaZ1u=bDYZ4xfM=i6k~ z8=oK1I3aa?r7tMveV$RE|NR?`e81hQmY;YZy!a4PC{=R{5aLrYy&kv4yXgDj9~8>{ zK4^;5j||gNoA~}_6|duCg!)k8q^OAX#7EJIgIjbE=g-vU-smpgd$FQQZNeeG1J*r* zfwewJOseC&^_bg+GLgOb$Kx}-Djn;_?_UD>DbXRC%kGT~zoe)NTaVL*-bcrnyl46O znrAnRWjVk6PtAZlm1_5RNuCt;mq1_`CAG<#nBz#3rgmf5vGfxk;!@i#VVA}m|GdiN zbE*E+jgfFnKYLIPLXy`^$`D*W)csu5uB?oolf_|V#xa0m`TEB zzK7L@b4zOvYxK=ZIopgUwC?l504BswdX=FZ-M%lTuD%8tq81>Y2uF4HrvES0C9Q5z z((4UKkIPk3mHAD7x+*DOBwHr=tBtI7E+RDy9zsrBm!qiS=ox+U*kq?yCN z`byOm{45HT)|C7niMp+Icg~;s_Vhhw0nF@+!LhHRqd1vuGI%)x1^Pc=LUtuJ^FG6F z#LQQKKeHZVn8QBUA~SS(ROpuQ&pZ#-d@9(ln1+GNCJ8c0$c2W?LLF_Z&wO3yMpgXk z93XK0JRkssA&gny8QDpWBeXfoN@Xqm(eyBVU?~?A@cKUd>O~i_i-g!!KNsVI%mQ>M z|AFy==^4f@$ukTiCY`^yzfM*BDy%*>wo(DQczb9;4I52wjRlE40s7zQt_T-L6ig~a za?NorEUC$%6k(~F;nblHEUGh%j+&P_#Awva*J|2?%aMDptbsVGM+tvc=Nzm5>-+oX zm1s!J>pVh>DvZ3iezO47*VcMfZ_<*OJ<>5?AkxrEu<25)?ocu)wwG=N*X2N%XLm3wwLbT6yv0(}Vm2uB1Db<|F+U5#EbeERkzaWsgs;+kU$Ew}N zK1(y(yvosoX(^wVU|D3X`#DsTLiVI`2tymyY{gwp!#`(|Gm1p*(?2s&um}N|*aY!H z94i+kv3O$3J&7;qRO>KbLt-5ZX&+f78Z-EnlZ2wTcs(mdoLL5Cp>z*Af4tGX`#Z#? z=2^jhBlz5a0^#vjL!7Qg#j0Ad#Pk=FqVp&a9cl+c1n+X~x@VQ~BHlJDa>+zB^OQ7_ zW4N@nC1=5JQY*M*zy1{P;|<*@NXC+Y0`rqQ{20pgn@+xRhLP|d`-TtDo3PPUj}PRy zWvmB@3n$G$H%O}L-+CHM)%zT)hO}5@vyPtdvoW7vpLxK{sqI%|Jr4@XnmL2-`|YFF z!Qu>0zzBMJ^At48rJ2~@>i>Fm;E&Q5#5q}LM*8|r^w?=NDA-oz(M+6JL1=8h^yzLq zMmLMJo|Ix}*>yRTqF9sx=Gu`gNcD0gor&rtXAS)xtU0qu&(@N2eaTYS3A1DXl9_ac zVL~nXysQ)BU2g@KCT#7$a_I8c;14D~Fk0da@cq@M%bQ+|vs@mDi0uG~-U*(+F?C+5)|AaUxwh`t~Lb1gKt8a-$hF8Dfz(6R61c*BRfi{bviRWC!RGX8Qh(1 zidjw>36@7O>8q^sQ2p5a;*>Vm_oLGYLEQ>!%z#S&3<~|Ma(u;x6M_cU=}BL1hh0ah z^K&Y;5!!*gC%dGB_Vh<+^xV}yUthLKoflYt35a(l? zQOx=q+VHXFwVco`tox>IQ$E7X8!8;Z9lpg<-e~gY3PP-_H!z`no?G#{V`Qqpij63) z3#OZ@@l5RRH8^`^#z01f;(tb}eL!a+3E%e@gG@o7R$GjToyiLms;)fxJNIX3I)u8L zbhH%zLGW)GcY=A}lote$mj6b;FCVKf=(vGhPyy&Nz?ok`p-&+dj&6FBrsAc`3_R%A zhA1d0)~q&EsLlDBme6Jna@X9+K4P$*q-{Yel#IQ;WEFzxiNPE5QOzl(Zq+6OimAvK zE*JTn+3Aw*IC`Od?yAVc0s86?!tW0o&2hqC{mV$yb@ta2ykP;{e4fRd{1KZdQNc()l7g6Owj@v0xQkMzdRxte* z6zThthG^dviqZk=He_hJ1b*prkHvCv!u%l4r0>>>L=#195Vc@0 zHJ9I>YvWXoaDV?sldhp0-@%k5N&|Pzjf2ys(-jF}MpBO_69oWd;3FV2XFobXhy-K| z6Y(9!@UF#YJBZCoGv@Z2fk<26mx<36>A7QjaYFu! z6Goc924{`gM}3T;Wyl|>Hr?Kg6r1JBNTmJj5BGXFAIEqr-I-sG!yp5KMb{CZXXQa` zlb>hhBNQ_d(!TIb4z~vofjhm#gQX3AhS=PEdlZecw|K>f>CE1CO%Z<6=twdpuh*dL zKTRx#VumxnEXQ;LgiBNS-|2VzYjBQL2uloY$v^fJUhIoM+n20-u}?Fa5^HDQeU?MewxTnw~Fe)h!qpBLo>i?MTi9$IJ04Ruj<9Bu3v*e{`-vkUkXc~kj zo4LrD?1LgDUX&o#s83uL{p^d3|M7)MsVp=&+EW zYTbEn&1_I7rsG=>YppR|p|{yb`(HwQwG@Tk3fKvlTBN`EUlabwsrR9jzlKLSS_x}~ z89a0V%8;B*kf6)66oC(k7Y5`xrhAY!pb#5;3S^$Eve1>5T#Rv1ftt0vZi%S?o1*;K zCfWkm9_oqaa^JP~0T&=38aR65rG}%)?}{9B2G3dq003H42c%FuFbGbQad*)*+omyn z7UL-}rUk@UnmPBJ41{WX2jiZl&^tKAY)RfgsT1?db@~TUS(<7ujn8w7WdSyFlj(_ww1#K?W(-9iiICKka9pP;!BlA! zFg{tp_iS8&{y&UY8NC>nfcG1@|Qh{W}95GV+~-=5kRYH2EkM8*Yj@NcvB}susn<(H&!Jv%DmNML)E{ z;&LU^!7d{p5iF_|2`7p;SeN4g#A{b8eL-Es(5~jgC@j_@9O^XccuNoM@UtAxCi4$| zz{Dy$(&DA0RKqQj)98s#f~tp1m%fE4cGEv?hw-tnkNxkoH;ZbCcFFpp?UOk#0P+9; z#V-Ji{tZAH0H9zpIPnjF;uiqb&j5`60bo?kCkp@|8TxC~K~3*96F6Zs5&~_Wr4Y2n z=rGsHw{!Y=Tc{_>&Y3LJqTNsBu&ccKjV) zh+LyaFS!P7PNInMTnAQM-`CIL1$9lTl>i;b^5BM1m7_OXTp=2&FoR-Hb>%YmkKTzi z4ame~8M?kzHJTe`rd2gdY+<&RzZx6 zuN=F?SI01q&o_D=vp(&f^++Bqsx9%{Z;OXExSt2bl@dK2FU4IEgBMz13fEeLU$LZ0 z9Sqn#HaV}*c@ng+q?K-045t1-x0`zo6TvK(1t@pESH_$7%h6H>m~hdH-qysv`zNJ`q$ zUJ^MZQ_6-yOJJxKt@ONApEKB-J@w!~@c(B6Fdhs_rtz1yhMJV8D%+I8#C8t@cfPqh zkzNdR4Rjp#z8;7XrWA_p((}E0_D{5bD$j5c?^_#)4}lxVo1a#snZoH%aYoyCU@AwW zu{F%h+Ip{+HimQUsw^g=)^d zq$a)H*vH1!#ieFcMsnSj z`nZYmlepSWqF#SrYbOqqYC9>ZFDm+@I^C3jOTx9vYQn${EKHY^om;A^DsLxEKWdMr zm1#N?6456nM4F6XFB+<-G8W`^^c}>{a0O|>qtiHg@PBc1eY;y2G16L=(Gu7qfKAt8 zf-Y8w7Fj%hq>wUgs4)9bE#;AZ+0bF;qcUQL^#Wf4+%J?!SI5$&vKD?)VJb`0qDk*a zQAHAIQW1UHQKFI|(xjs&?bdZg;?RDlOZ{ZC3o~50-nM%(-W2I)t|U^1T@!1uJt6V7 zt0%b-R1VpN*~yI2xb4;mN0HspHQ3iRDxa|vk{t+hCP7kM#9D4!JQ!+elwPt5ZFD!9 zpW5sCrQwo;lL{AEK@@8bJlW)}Sz_F`Z(P$f!{UTF5l?7GcZIym;Y)Y~rG*$+)%+O1 zE01ImCNkd!h*PShzx7v1mZ++L&N#)CDz)@lxqEHxrAB%)F7a^{^9Dnb;H$sb*`^?M zIsNbH=823C3lO*DOz;gu{N+hH2>Ckqu`L@;Z;^uIov9^@ht;yNp?(vM$ zY-@Pi&7rvYbWMlt#A)4c4IWvmh)`RrCQmp;b^ox z1=L)D9d63eKp3*FzRU^`*va!Y9;bdHM6`?GE% zn!gVdi9I?1HI+-AtX?+Xi^j31Gc&g4Kt5%xZQ^KD`keSoRhgfNKC~weN8}BPpY`+1 zH}5u{U#+U+x&5R)8cVNt35)@@NP0Jk-;o}u&ng-mjX7TW+wV-rxx`&!%{HFvfKSzD zudIJqeUg*8xbdeb?-5I=V5$bXVlR_?UvY9DBKtAY}f=JB0;a z#ycwVO5)%t+Pc^hTc7H4dE1q0n_}9c?9x11W$~$kb`__B0$##;xr*2l`RC*E|2|$o zt1kYT#xyYy>u!z`0XUuVkH~LFqjcK|PH$D>NfL4v{hK7>rA++Dc9@D?K_$O3P~8WG z>~>CXapXx7-D%zr?uNJIh#K;7%6`33dE!B1CpE|6HHq`4B!x{~w(vMsv=Aw7C7Qm% zM*1$-_&+}e%)S%mxDldj!|jhUEyg*XnLMmY%*AoUx#Ct!DfhE=FZcvbd-?>fyDWn9 z42T`lWn4#J&nV}80PpZ`Tzx@|S@QEiD9^T8Am^cs<3q%Hgz`g-kpa^q;?R7h>X_>u z*&EwX|K?aKyU)MDs)d)b!-(9U%+t3}L5V~2NL5P@#-@2J$~E*tE&mwbgH6M;PcP@@ zffy4r`4Ni7y(|C;{({{e_p40eFKCVtb&35AY!()EbpPS9!)p@Nymgo{AwD|Nmyc7OD9(XI5zKZK|8;0K|z_+icBAWwgMJ5jiS5{4o!7QnN)p2 ziA{QY-d`M=0(9WqHWLPoyt1`2DeC+iexI`r{_L#7=s@!&WOq13tV=v>8gkp*5);O3 z;_uUifc2<6W7M6Dn@V@a2;unoI;ou)UVj32#udwSp5GtLFJjcI!gsm(Uqe80{O_}H zRceyvGHPAH*IIrxPwx!ASo#spYCt~B4lNLk*{NcW*%6!Wn64Ej*ElC$&32Dn&UJ#F za@Iif_Fo0X`%|(Gz6uA?gAE!{S2Yuse^QEV^1SEDr`=Y;t>z**&^Y*a2xP6CXm3vNdi z8js+rAyTmN{grXr31*Ls;Z@-4;~rTFyq4K4PbfqJrOrOLYU)c4Ljb(zxPYP(};wp16%` zbqm#gV?oRJImN=D)t36*j0B&4-P;xwb2DNWu+o(Bk#MWzto~y8kxhyWM%i`q-{|CF(Yp)U^aD@TiZsMh zM8|nW!3RrXOys7OH@wVUcE`p(WiD7XPOvSRkrT8gTS`UXm-Z3QZfYox$+yj1V}4o&l#9;5X3vRBXoM_9j&u+@;G zKe^bj@cz_n!n<}=LzcRVzRhEY2N&-J%_n0Y@FXuyf#^LEJ~~Qn|4JW}3!oiw~Y@aJg~tjIWy zN&4U<^y0|^QB|oet(C}8-wNf(0ivn}ANE`}FMHFcz=sIu%pniQBSJSP<|!6aiKseL z+;W413b=jcnJ*BpkQ^XhM*NM#c5wF;i!5bQWz?u(Ve;Zq)@N8zeK@kY9o{KaXs}4N zWOw(e`mv=5*R0HgQk4}gc*^EOv;pw~pZUEa#PyYigG-0xOtmOML8V3_h7@upcWaAt zn`S9T?>{3nfAJw=uYTqNx%f6h;>}aA2#HI4q&u&BNOP2){mPYVAKnms26sMOdHuy*azqJ2olo3+p2X?9kAjt6V>LF66EN$e584rF z2qhz$2_2>edFnlTjCUC%kbWFJ(MRbjvQ2F_CBFN1E?1};5^T~DSzoo({znSZ}c^c=-~3l zB+&=;omHw^RyZCi7qM=>{ZeSVHW8|u{ySzEKVv3(;~U23li5R-FMdH*WBmogaj#f%$Qvv>!Ce^k@u6c0`Y ze?G*LV&?1PwxjfC=5}2B;`->;PL@h^@4<+u7?A;DxCL;ai?-=!epi;w)AbYFE?o9W zTNJ4qTNLpEDgU^kDhAa`6_nkm&MYzJzPx**+TP{Mi^2~2CX$)Xp^LpoU=)4ohTNMs=ncB6Pvm%z8wsY(s;q>Ysaad#XwU~@8pPff|(MvEzW*hRDN8#d**okbK zDEzPpJKLH0m7Mf+8jiTuStDMj!X9}_mtW%?BK3o)%3iO>V+cd134AsQWC&AGj;x(G zKJTf%QVrLlb$w0oKhq(b(t~@@!(w<4XaF`dROU) zlev@ZWA5>=D5x?NEIrK!KXhtf6kS=yCNb^mB{^kCu6csr@SQ%P;9^&_ojq2G@k3~GiK}nU;I7|&PN?N)zwPh(He^z zc6pYgIITe&RjE`jyV3cGiu&fdj>xB~u@d?EuFcveBC6Ln%<_ipRrQZY@HT9D0y)55 zRd^fkhum0xh&`UHX6AKIgL~R@LRSYAr*l;3c!p06QLN_@E03xN%SqqFCe&x_I3v87 z+TGLeq^`I11QGBiTsZ_*HldZLRJUQ+u$f`mtnH#%)Un*RsB0=buvseqPx;rMKbJR} zubv6GKljqMg^4pIP_%lX|2PgmU|l;=oY}cpy`dpEyZcMgL5X- zyHk1}H!;cmxwr2PxqK5TZwS+rnC{TZhQ;UV3lN)0g3KKtEo@#HiGWl`N+AA@xKpf= z6vL-LUX(Xz;+tPNHvk*sz=npi@z3al)Z*O6%M0kVr)$*3rmZx5DvdPoKkWeN14M@@ zXD3WHrLsVl!iFuK?~`s+W!aL*w49}44xjMgX-use>qlV$n*^X4lb-gV-52EiwDXkpiH+3UGOeAt2dQXkTpfNWG8lLo8xFi1 zEfO8o_rB=Ot9c6cPjs|RU%?EBKg)zp_`a`C>J@UAD|V`<)#I@3d={88&%pLEsLE8X zjlSL-b*^6fuF!&H?A~gJvR%q%uxs!Aay@6Q*xiDBdnY}ujILAX2Ky&^6B*K{8qRL+ zMO(_tmm&Oji^eq=R0VYc7Db9A(no4hB|m}lTSv?d0;z_y#-fK`J&Oz%5;zNbI#53d zNp*EB`0S`8US7V!I5ji!juy|%mX^ZUwkCx2tlXH?E%8p~3nwn0r%P-oD z+_ASH585=%b4DBVmJhoiV59p$|K_4QR6G(*Dr7pyJloAOj8L_2S53CBCIl;?bJ?kS zT90FfKU#S~8v}cx^Na`^gMii5_j2Zlz(&u{la3PK6F_FY z1XSByhg&bpxG1rV?Nx}YR&K5rz#ynvjT2dyVk6{u_N$!(m3}E4w&5<>koY?ADP=ap z+|3CBl&$$>a{k@ESznJoCaX#K$MHz|%US+NrG6nISW@GJh_#S$ZTh19%G-(po3#nD zBB7nCCFajJfoptO;RdQDIB9x7(>kjkWG`1NQBA8yW!?FXs!|h zAA+o;nL((?gdJ4;MGSkPAb(#%dmDrkRs#sfU> za-0z4vnLX&dS9qo1#Pr}S83i25xk7LvyU1;R^*Sh0Hq09$j8VNu1ql*Lpuqaqpge( zb$lmL4O#48qV1e_=S*qfepw1ovoqW?t?`ffH)peIyk%L=`=Cc4bO|N4DGt zGn9S1ukTz*kzSOQIec+nk1>bUGW-1p8*-WnDK>8|CGL#xJ#<(*IaoG(h&P*2PFI;? z4F;vOKUhbG?H}L8e~9VLMeF(@KGA4hE7oakLiObSwdK?9QGRiN1$0IyMyRt<#GS)PP@vU0_8vGLXfv@fkcuLK=t5>T;B zvWn8xubW97nGlfR8Xi++y5%2_x z1#K%>$P0SftHg&J?9SI3?rhsbOeG}_)T;m+#dw0ffzLzt5?q^Ic$ z?oWF7(rnTtk27bQR`0;Z;)PCRr+@MTU!sf@UaY*)KvC9l6~GagcETo1G?M$y0o;Ph-ptbZG6#Y zfVT~CXqka5T?6Fg*C!WCU|L#&%A1n`;nGP0qY+U*hj!x{5Tx#_1L@S#%~9aZ`AQX- zZ1>`Z{EU1@rTdMJqfpc3Wk(>UQDf|}X67d~ncX(v+p=@XX~)02c$Gf&T+t$vb=Crr zUewi=+_^&RSKe*Qx;Y`9xc4?5bbf&ex)=bRy}K@bHTLq5o~7qHNR-Wv_zGN9a%~^c z)VX6&44m>~Mx0wUsX}rrnONs*2T!vb`*?9MYB<=LXV$-%jr~Ke>6g@Sy@@O&yv~0FDs2I-(vNA$WbENQ@y7QgV8E@TZFIwD7M_R{nMwqNHH$ehV=5sy=VU!ADE#M% z6|!VsowC}!KPh0~|lyMV$^>Jep!evxm$WQ-#C`PPo3L_o@Z5<_a3B(~kwLJ4`LH z=8_nQNzZc^@z?rCHBNPA_S%SD3MEE0hGK3^m(mY)1Rhtc+^;>4YW##^D|4D-YIs>u zCBItA`9y?Z?g8q$7^N2h{;-zkq(my&0L^3Hy#9<(|KlP$WP@*fwbGb(YX@mh2@MYK zZpcSSW;;Hr&4#50>;!OTXe9f&1~I+Yng!!Fn;1dGmiFMv2l0d>vf5D@XUf{-v%!^Q zfUKwAKWRu2*c};86FTYa+TywwpIek55s-TnuPNOP!xUO4!Sg>DLb73+ncC?6=z;d4 z=UeZc7jDzE&(S(4^vNJpFQ<1^f}hG*;Mc`!0JRhRc?RPOjs*P@Iu~@ zB4wZ?$ceQh@i%dlVH<6kis@jJ;R!AadWZYI4=Vz-p0BpF^j%~0^(l}QKdYT@`*4N# z%00#Ah?lM*RAx^hrtRajgsbkZyj$*ApzG#^qxKSMy#og7`1u{BN_?o$4*;B1k74&6 zE4Qrn7yYuvshTG_P0a{4gX`@!rG;FBvD)bdrll%%T{%LSFZ>KJH$Y7a4AC;<2- zZt;EmjnBC7z?dD`$`i-9U;RCUKbPf1c*#5OXLZptm9Jtj^&Ml8p7+NJ7QW$V{)qK7 zizln(W1@t17Ak*Xjl!Mqm2VP*+Fl6ZslvfrLjLa@o3)Snz77@_*>5o}a^Ze`KH@cB z>d4VdG{=piEl!@Rc>-L-La~`xmq=yia(JgLQW*XD;TXcf$J~o48F#GWce{^TwPOjS z*PMY<{Bk99EbOxkdB&d<2(2I=)LV(tB(yp4pTHZ3PbD&Gj|i!Dzj|A#6KkT7qEGN8 zEp^wpe*|vaUoFqeUd$qM0rsXp4H}ZEtXa4 zj&Xk(fXz?%7Mm0(42F#asyy1mmyC9!Nt!kw*EUy9 zyHCK}oFWC6o6669xnDa`DaE@ZOEXi9cRfnC^etYc{7M81aEMlT2_2BRTd>SEQP4H1 zRZ(q|PkKB)YMgO;8{p9rN+7_mzC2gB>Y}Otv@@Trtwui)pnX&v$b|`Ch~m2@REIZ? z&|OyIpzTOJbmZ_#eZVjRTDqoW5}qI^0Klu?ovdhOO0zm;H=)ibld2V-Q$n#9UtHq~ zN~?04<&UEe(-59O-9bFCTppm+bsb%qU5Qeg%@pf~km1YZ@-on*^f?Dpv1uv9QXQek z-c{>w9mIV<=rvQ0smis{tXUE{B+gvw5MH=EVeR)h5*!$GA;5BNsI1ufSFL+4OJgXJIbuk{ns4;;kCQrkIo_tJdnOk|B1s;;iMZD_+D+m;O!W|w4P3kk zSfCGzx~f*$chrBk?c8-Nk&N+1Dd;Ir5*B2;H^8yM9<1S2ba?svQWu}5jjp?8z(%62 zH$?>ZM}tWPe-@?wqI!p)QcSK*Lo$X8Zr0qTTE7ZB)hv+ zY#KWtEw`CwV+y@zgomIZw2#@C3g`K|snevbX-mrQ3@p&I#Iz{sKF`-7^!AOZjwHS( z99YrLk6~aeY$z`u=@EHN@*bD1&VA90v^XuDVHa1iBrW|BwY@#KVXwTFaL;L*a?TDMvYcNP()yp135b|D=^PqZTgoZnBrvVGLk&iUS^v2i> zPcUdXh+&Gj+E(5E$`lrSjWARqbR8G$wVR#e=XW|8Ve9Fj>KvwQ@-t~Nu?-SM?pOR6oO8vv+@u6u9zh3d8vm^-7#KR-Yx;%D+ z-RFcX@0lHz?jZA799rgdJ0Q;PwGr8r!k8*=iOCD^*5dB{siv=^-JS<=4?frtE{(OV z<-HU=xA4mbouJC#=q_C>QR@vDev(&e-?`r2e4qOgcj{^qpOFnd$DyF2O-b5)B062S zfd{7XY<0sh)eF4$JuDy$?|MHiCqMiVrYUi|gVfY}Ii(ho=lirZ37G?1JmiRQAYKBA zE54!JqS#>uI~So9YMm~h0>j{03p)6@O^dO0YfA#)!!_bWSvfFbd3o-Q@UX8c_VM`j zzann!tW#)VD9vSF6~Vp{TiU#TIZ*lhJa}-~A{g%=$)W2;iR&%8PTX5;y)OCl9W}AV zC*s#QG1Wqy-PGH)H??yMnnw@B_IQA6J%?X!&cQb~6T&xFYXjfAPs?tOsr$+f_*6)_ zRbLfjnIQ=us&MhU)8}_~9z4|#kJt&$FHsS~)XJg;(FylK+0IsywC3}%-gYSk-46*% z6`sHryD8~^eIOpY`dK>j=11<*Vi?_y3bxcu$` z9^a>3B=QV*XIigD^n~Yn@n&nZX(#E^r>Uw?IOs%BlhKEue1^9cB+RX#@vJ_HY*R)Zq5dz!=svY_xBjAy9m zxid_o1*dQu?>z!+zs`Crt3vU0Nzc+GZCQhg7a~v43D2~g1L9f1iS~9cjRrxC3*MT@ zX9Ifvy#B8(@7*g?IW{%@d`$M(V?2^S#Rt-iJlJKQfV_!3Abg!Dls4=7I0!F%ikdy^ zfDfj~DP4yFx-C(YJT%?d;w5prRBP3!+MSXd(isko+;i+TQj77*gOflRA`)4js*$Gg`K_6|d`;mp z<*u6puSVu9+z;KSJ)mGc&suhRu+qXZ*97OyMyEh}!-%TSoPZZHJy?$gveDVQN^{mc zw;@s@*F>Vel`5U!QTmur)qHgveqtNZlY!2!)^!uVRv*Dmmx_yt3)e=6?vq;^PJwA& z_)-54p#g6HaMvW?GsRp*Sz((D#*>)XJ<@l2+0&eua*Eubav$kO<|2)=u{Jz{Nw19@ zO3kz#94xgRDodUxBrmqI@bPgm^L=HViHSAvr(OFVpyx1-714A@!`Xm_k+*BIqhYIcd}7?$n{Q2KI`Qh z0d_w*#6-IHX=S@`#9@O;ZFjgrtRp8}&`Ymm%&2APaF@emI5EDUQ+?hxpz0CwdIQ6B zxFsQi?yjFF7R&rYY}%(!KiC{BY|*v*MPe#lSiC(?^MQ&XM!OneXV z%;sl<&OX6Tb_@Lqxo_e)?5-Mvd1SVDUrpIx%PUew$n>VE3;OfYEjB+s!}{7@-Wu4G z8!Dv3`}%DSCPv*L8xm%1^15_yH}H{?8QlhL3B|4g09gImb zsSU$SRHlFIsML=Qd|NLN-49plGuVAI7mG__HDI5bGCs~T)xm3t$*-9vGam$QND~Ee z5m)Ch_;prUSxFq%Mw@580*|i!K_8*wcILE&b)*oyM9yKqo`UKW`pg4FjzI0tT7tV~@M52NibeDLTv%B~oLgDePvi9&<(lXiLwg9&UO`Uq&Y6-p zK`i%XmEIprn9N)--H@I${BR=X{l4V4a!3VD_%;j3>?*9u;nND3 z)?%3)1GUd+QfCc3thM@SI1*~N09FMlxk4)H!V;gXg7eu=2%bUk(fyi@ya=Byf;p*M zkF=Z!8xJNNFd7ejan1#XalQtw#9IZk&zZci4r%Ii3!UmYm>}-Z%l4??0-aR#jTE)U zz(}u`yd}NLTo*fHM(&n$TcsrevI^m$jLTTmvg)6tw^PALZ)K{4kuJ4$OM3L>E$Qtk zf0Ew&cA76Pk9Bk(_EP z0pAFq`6s1SkhmRAXwL^&7@|SE439x(uTq+1jXosF3STw_G|65I&K^wca!{QnHsyDY z8WA37Jwdw*IyqPfZu%C6JYb~4`=!%Jjt2O(p&_scX0%OM1dJPP5{Q*uUI=8Azo;uWey>RO`FkfM+LxwnSw;pJ@EL>PAAVA{Eut0H& z{80Bnn7#oyOX-nc-1>^>&D)zAw{S<0x4`F-`B7#M^xqzzaQCBO&%{4a;Odz<&4lEFi7ZyGl-K zUEMP%hm_e^prR^&prjhDyo=Hd|6sX)8NSj%dt)s+K5*))X0we>f|4BCX`PTP56zqxvl;2*Ajjjn;CuyCQ?nAu_+$z>j)$=5_$OtpvaOCqs?W9fSb5({m{(>>C z$3nqk4=-u%(!`m~ZZk^EvBvPJBm-3(uSkqsF0b$%ocbXEJ;Tu*I2p^6PlWfP0Pygt zmJxRzan0GFB4nSwIP1+88=mlzK0g2AktK0grpOgfdXw2F`*Rp3T-}_4i6$39qDC3r z<6gIiFUH%D%gC5t4n=ab7McjQ7jn}IybQ>8J#k$Z)tyhG3Dn`Kt+nLR(n@I?(*WK@ zmjUmhLwO%3;(z&4T7>MXC36ZlsN0#KrNTXEoVxKPzbrJ0AVw%grl~Q1{Dn^_vo6}W zYHW)b<9mPMI88kfDn~--6VA>=6+KH&$5*W8_otP3-W8qc`B4@=`>2Vv8jIZOIh>UG zgs}Pvij`Blm|48>kNwbZChBx#V8#8(qKMqf$n0|MJ{|9{ z%GTY-Jtc zd@>cqNDK$v&6y#Ygwp!?*-9y;J##WD?GZL-=r zNV^fYklIJysJ)=uf46W@-;pvf?R`wiEuUO*pM~CfKZWu(z>M9-ZQ`n``7LQ+KERv$s1m@$~gYnNHoaLPODN zAr|t19#ijj&_0MPF6FIog_ZWloU3@1y_>=d2e^&&>-#pnCr>IIb44$_55@7x6@+eKbQc>5FD zxwM81E&ZnvS+O%ryU)J99%oEsmRqtX$z4%uTx@+!^7^^aYZW2WkJuQ?L9y)D2K#4~ z2hqv*QoH#^P?F08W6S($hz>WEG5EyR2bET&6&{e5!n2Phi6g0wQ#pyyo4_sSH&pB{?tGAm+av}y0xi*y`)IPQN{;ARLY z=nd@~Iw@q*+EpFP()Fmk)B>JB4DGXIBKjlj-q<`&6#nc}EK*hA{*LEP4B~#7H;hgU z76#Y~>px=6w+iVD%AL92ld>tg)(c)z^2;+sPUESqE9Z&}_YfBXU!)$lf{{!7C~{Is zjV#UYuzE$wAu#>v10+P!c#5%-e&nea-9r8tFK*8yzrrC-D}uP8$oON(g5)Ex_?_TN zM@@$)V=1)kFi4A$`M4BUsmD>(Ug0=N?@;n*k6#t}tWz{Khz4?#)oRnzH0XSKrtkwp z+-GkQuW>qyJhRQevnu>L0)ukHU?*(++>$8}gJ<|WHLUYY$lOy8O2Y4k1YU165wb8F zq6~7D=NzXvjN7JOFOJY?e2=c)ct*3);99j2kR53{tkGCOR5shD&C^dR4 zNfJp`5|@Lk^9cLnAJt_j1C1gSLuGaPowRV?V=l|5{DY!CO^}@`*W({IOOZ|9P~cKN zWJ&1;S~H)#X4*JiMv~FSPkChX!UzcTF%G}P2e6{Ux;^!Wz3wj0J-@!H6{Sq^sEZKz zPz=#8FFuwaegK=2iv^Z^a}D61_rN)stE=M_2jZA>L@V`HAWBjk3HaP}vF-aPFP75%H zjK$WcI~&CU`I)YIsI(iv1~2&+1{a=*&BtP2&LL&k^`=P#QXJzWJs|ac{`JWVbTK1X z90dp(#B=rpyWRJShF#HRo-Che>?v=^JwPXYJM5|e)(Kqv3y|iesv0g3$6r}UNIF%t z=QW=Zj#N<^q&lCcf;(vJx%H*V#dU9P79|h3c>$Fa;#Jd5x`PFJ#hA-FbXVuRWRX9(EOtR??Z2;PS?0LVIVoy-UW3Olm;0Mt8jvP$q6=0ao)xK-ObUwuc)4ArJ>fdzUvi`&Q zi_y>tzb(G#{rhPWNikd-F-i}%ly~a*EA~#81Ajcu0Pq_5h^M@_G+u}`H_nJ5;hmA* z@!+tWze+!~xrqINHQKn?>?@8eYzZi+0#MN1z>*o)0Ec;x;nO+2nmwWzWRmwY2_%&E z>kdYF-M->2yw7XwER*G>n9p*)(fo*-61SIzbxaugO%!hM~v=dPhKhodFEF=4fYstzgJRsq4HaS^shGU{tTQcQ0 zS)q2Og9{ub^A)!Qgp7t^cvq&65|tJ>AsHAfz4ls%9Z&X)B16qB5@gz2BmprkA}<8Oz-aczb@zr7KFl;#jgF@b@u987u%oGO}+8QFaIr>-JEUoYTu#z9mFC21baO z%q<~`g)l-gOm7MC%>ILr7A6W5l1xPo8f;$mg3x$;@s#CFrLro|FC?k70OsN7J7T2&fD(;gEDsewp~2qkU1Smz!#;P zJOsdW0bt;ez)tQ8KJa55K2}jOvZs{xguOIc46*g}3d;>~GG8czn?<{6y0PyDvc|su z$joax+`ifG10OH*sk0ksrk`!f-^IuiL*^}V@iEw4^d>O(zN52AJKTx#D0k>JkgG$(NWLw8#QhA8Q%9V zoMYxyX8ahL$DSH7m@MEZs`veu4WePNKd>am@DhhbZPYj6ao~tD%^L@*?j4ngX3^~$ zqvJL|=(UyI%Xvp+7+Fd_%|KIYUmYzSqqN1dx=#~C16+mVMTpMkE$*WXqEX;f6s37I z8Q5&h9P?B(dKp($La2nQTTMC>8!Q1R`Y}?e`HwpiG3pE-qLk01SM7y>9?hwpO6HFi zyM+=_+@?*`M|@OT5uIp&L{U6^x!Z!KirfoeiKu()%BX+R(SX1~M+`-JL>wLmR$YP|jp()xZMC!N+ z>Tt8`adiefXw;0#C3UDDaQvW$)mY@~fDO z$QW~&a6ZQNp&Zcdf_GT@fEYBN^6dGO{g0jCOf+sc~N>|2L zc674syh=#GNcHB?h8HSRgfZqZOiVo8b~H9mtt^(@2_huRA>A@$5t7F|bV}XEpWyxklBV3JC7Q z%PS&vcHD?QCrY~qzU1@AVrh7U_x#?XCDh#sV&9MugnOHlAOQ5WV-cbJOMH^|rB3bA z486Uth3LUCk%l@<4Vj}0sU{X9gn3&VWCn2_&fN!O8ag~t68qmP#JL=3_?|A7@VO<+ zz-^3r`eip;`?Y&!ik{;WbkzESR$&kQmhM*tPt%X1?7KAyyho8fHtwniA21D6r5e5w z3a)JS#A!HGkMUTUl`i%e_nkdqO+K->hy~Z%kALNl(lU&i4I1<6K8voSb*+bY32Bc9 zrP;X*E)q-IEBT{s7AqZ?j=24p7!j&v41C})BgJgZATQHLms>uY)xi^ezImDThMO-7 zbPMjzv(V8S3BSj>5+}CAB$mR=`L4O|q9!q!l$^pI%)6DRV?+*Rz9-BIuoKLXMEg!0 zgUmAgwqcFEI9yiCW+ZfI;t44aFV6Bq7CMnorTO{`2=Eot zB&_*xCIqiq5uG7Y@-|dTaqf4zMpv=KBkpWm)=DbeQyV>3XHXt#qnTy8^T|R}g5OoN zARD-K4t8%Jp+IJ}7GjJs5j*PU+~+TPR(jnwC6ZE0WH)sTq2F&6MkwM-^*V@AoazRP zCNHw1ryRaDQeG9l8Hr5tjto@eH8L&0x`Qeet02C_Jrg#^374(}o)3dF=M=f)q@R78)W7gtGg&L=vxhLdKv!FY_d%g-VllPcI7Gxv&Oa7My$ zu0C)Z-wC;E@=zM_tx5XWORk2|=y?V+wixib95Kct(2!XtLg(3AEZ{z{(NZ!5kwvYB%n;_S6s&UzPyPD2M@@rY1@BxS z!!4s22k^h6X|x8=!C~d~vlH@#s1y6&S*D(P#VLq<=a3y9%L0KRN^u-^pVM7wT`IV! zQ5el4nO)WB_!XDIR7(xU1`qq-XCdBA78pE4M>NBUfg5c8CVZLfX@($@5kd~aLBe^t zyB`>&F=QlOsETr&K@ch0y!pHQv*cMo4@_Hi=(c=BS3Suin1VFmK41w;I;cfO?;)SL z9+NJ3$C}u@ShP4KU4Yu23W$}-H&Ty6PDwN9+R?8p)J*(py{-j(ZCoG`>BRSCb+ilc z8u5v&8>T~AT>W20*)|N+5n4Cw@v30%y1jZIo0X!%%DO3kN$R5|ljahCnfAlu@KFQK zSaAJf_osuTY_jeVjhd?L?(;Z8gw|a#FeFSn2aA^qNaVLnKOQPwG ze3))`usO_sa>7bdzU1!0N|P>dZ-Xc5o(r$VD?vPOPt>&Lj{N#sF?;fE(xau^1CQpU zld&}=@Z8EsBT@RjQ_hb|o5d-KQxd7vC)Fu={r#SN_PMt=Gs|-=sVP7|lF>~Y!abfX z{o`ilRzj?tW1G)T-Xt+WM|U4J%(vAUsUGT?a_n5Qy(7N!S-Sn#m14PRoWfm>cg#&< zwY~|S`oKTLWkUARkbNO-)W{*3o+--|>(4SF9;7vH4fnrZ=t7x2FxD;#k$lqkWmF4M z5dyHpV(NNRC&C3Min?As^f1hwbgbz6UbgId%8c?>aNr}(#qf^W)9+7+i(idtD>E7o zR15~$e+#FqSaVUIa&% zSG5{*+XZ{8H0AhMgvsX|+|fiFR}04)@Yrcq#u+FpPtzBbL0bxc_sS=RAWg{YV#hVD z>CI6_tOZ}KnDiIIDuD_Iqwt^vscdD#jW?oFdhSeH17D;)&~e@yp3sQhO_PuYPA%fh ztZ$66?zZ+M9Gj;j4l z5UDn548#j@vQ+ZRYjc6rlLu&J-QPy@hsi$n8+gB2nSunn-(ZC69;NLb+{~dsR|a}l zt=P(nZkDu!{Ac!|J^c&UanAG%Y{fGW$lcxvSKp@k7S*ODkk_Wx_=1u5$ShJsoCS8O z!Fe41d4*in3Gh+>y;@CUX*Ux$jYf;P0yjnTOIrdy^JW*l!iTepKU{Shxe3<gD%>@=a5A zgh-cAsTKy|0b~5jrt9Zy-gTwZPXkSheE(&*-;*q2#Ni=b>kJ=X@Sp_#m*IX-GL!Kl z#AcA7#pdjypY8M!>g++zv*|N#i04?tklzrn#-XyI(4m5%q@lW@uW-P)UN1DSAd%4j zd)%1C^aojEH_JyW&w}u_H2x=MsGYW0_WI4c3Mqhv8}tGV1G;}(I1Fi`tm(=LaYk`rRr1X1nw?_%B%NyJFK-Ku*uC`v8g)T@gGeY_)C`nOcEf~$d%P0mt_8aUZ?zzzy6vF*uT#Ba%h*Tof()V zQL-)+s|+^GgB?~6^_Q=s>Yn^<&(En~L$QYfSY95C8eCGiPVPD;OJ>v&XLw{GWl3ex zXT8cI$kGDt@OI6Lgy;WeLcYv8?IjCpt z@nUQ$7-FW&UqI9}%V#CEZdYAs4trt>SXf9U4DSgej9{U^5e#EY8w^{iSf5El$Ss4~ zV5$x^*A2fJvpOZ2q20^^X#kT1jCdHh+YJE1FM_K8O4$I`z7zbxGHh4kU!!~g0Dk#7 z32f2-A#Z56RLblD5GP=mpLG7q@|9-I$YAtElrcEDQajllKR-4|BS`0c9U*(@tKC)=QNNce4ZUkcz05rZp7{S9h%kEbL!JHGo^-q| zDX*8n4DBKDb%Z6Ez&M5Gz^F{RKX;KR>kPe^2@t2K&tx)@>@^5Wyq)v!@Jb9jm{V)+ z8wCiP12EF6Sb^6r7669b0nGdl^dCCdcUuWqJsvRKLeBn;eLECb-|6kpZmX=GJKO0x zh2$rb1OS}dr*09#hWj}^gDYP;M<{@cjqR9Ov;FT+{GAKH@RCG#OJ~>CS;bsECw0BF z=GR-+ht|8-C)YdH$JYDTXV;hBMwGd6{wO|K|2U67c+)Nw@C&hspt0l*DvMApULN|EWtb(t*8yIhyVE&zkph z@Ayv(_?23vu=2d?@B*lyzh2`Hv+~<2ck9>NK;k?6T=%Vi{Mz~N`sVq^?*A0Y+ccTM z_{%`>|BHdl-5x>DM0Wn#UBb3w;50-VBd4f7Qr8R{68>_*px68#G~^An^QuOm9o$Pp?is z%ZFv;&j8($efxsjqTUGLs=5ul&JfTCbljQ@(5d{apTDhpGK(V=5ZU4UaX0@~dX~Q=aoc(SDP_PdNMW_P2LS7Yf7>JfCE(xQks!!e26S5g$I9hl ziyC68uu z1r(5!&Y=XPL6DN}=G`;sb$R{o>wbRkbHC4r_rvqWJu~~W7RnuXS?Zop>F%S zS!?cUZ!diA>a5P;>LAtVV!srp*ikSf40A{bny$6 zn}q6$CBgCwsNdt(pFs)qr0GObro=xB{9z{l+js!@5QzE-Xc%>j>1Cl>*w*ii0a*Jd zXKoVx5YNHyY4Wd`=ywnSg!ly)-~#|sSiAR|X@BB>qZG^z)qJM^;^KdC4bTC>lipu5 z(gtj51Y7~|*B7XEtE66Vzp(r&-T#3E&`@mVo+DJ&-1INi_m1Uo<)Y=(4`4SM zEBS+zf8;M%iTWvj@LS$zSOoqW)c-)_CSPZpt-`qnWA=lvL)L$0sK-OUoxI5@nw;@h zJ^0gi_i}&p7{~+wrT!e0{!UT9Vg_jAf&2WLV&O^fcUt;4%;D7m*kkw)(gQj7Q`{C> z-*>mnoVr^xGZ-@z5~LF35@Zq-4Wtd^4P*@zzIO(lh^s5V%L5t=b>GkmZu{8Z!!n@h zO+&Lvdd5}#Pcr?tn8O_Ni!%Qp{83>aut5MYxG&oqX3Ft@W#?aj12g+yQ#yPe`XkBw z!W$?LfQSE%0vJ30n(|?L1pmROf7}t?Xx&f+R*ce>|DIrh;R`P8cU3ql+yJ^6+0Mbr zfASwl41bshbKdY}fbR5`iz~_7y8pJN0rE6#Q2XuSzY@w{paZps1;?3$^8WP??Z0+| zekYw@8$169^S_~bce7*in+i8GGr(Th*2Uj##9zf1=s|8eD8RP3zdFx9G`i`44sOyk z>`l7zz+c@DycNA+A1uxM&j|jX!v1Sc`Dgb7+eN#{E(6m)_BNB;4}oFSk>tM}M!#E# zNlF?GWdcp)nA$aLO8bv#6xdDrJ&YQ-@?OGcQ_>jN07?jqY=2!)2@G>^J^@4OY5k#} zxWXT^EGcX@C*ru7UeSQfwum|dpf14YStDSK{lEpxd*5Iq;II4j0y~+VHN9}y|5Flt zzJ*1Pq)TG2o6kikaO2bZ=ek4ABu4H39Bt3xY63vOY7Af(Fe57g@UQ)&>iX*C{<{PW-(joqqoRgYR3JkC$T>H?&#zv`=zpGE{t;&FGg`0_8Hn|P ze-2Xrk?<)srhoS>TePn3|Gu{s`~A$*=Rb4VKgIpkW*l6@eEfIf_(whZe-p`DWvpyo z@WKyo_x@e`zcSh1x%D6V!21WF|NYgr{ny#{*SHI83d0Bh^WvX*`XBfD-9iB${wqoT zAX4sQsr5?Oe){h&=8xP6+clfWS!}FHca@@P-;|UGzy`|aztm1({|aXR8P`9%v_DGZ z?-uxfujK!O`tXwVt6gh9dzAT)x^%N${o9DYTe1J9yZF6*4C`27X#8&KU`YG{z2x)6 z!*?eG_f!08{qm;f+*L=){my?%UG6rG=cI7{WLX;;*#E$OdU|NEy}ELGY=5wSLBVw9 zc{I7YGU1V(xkBxAu&=Cru)lCo%Jf8T0C&YfB9+JU%B#!>{+U&+Ec~-3HZMP6|DVY! zL;J0#`U7hU8BH1G1eZR*XGQez&(yL*GpM0+UT4w=7minB4r$S_w`Y`V-TUL)<57N+ zX-$V>@i{B6_N)C?!{Fy;ir`l^aq)Rxok=7P4ZzNc8Q)z0G912!!}w;+DGOWycOr%X zqox(cvr|CEw%}{{8eig@HLW!8HQqnJ?3e$X+8i3N+IN34HyoLf*+2K(SC`MrPtbq- z@LB!p>BPm8@x+R3m@g8FRRX#BAJXU?1ypfOi5T;nUEXK<~W z&XqHouKJDP*!VLMOTgAR1i^1~B>}!!g8YS9aQ zg=<5qY~1mxY~kWb>uFuczB~5HHaT=oAg$^Bb&X-`Ddu^!?Kgje0{D8-;C+%K>TwqM zN!5iW|JJKTa^QnQyR)S^YLjcHCj)eFxV=!H!*y_Z1y?&mAXQun5CmJHHWuM`4S+U6 zcylU?1g`woDwt})mz~cg=vYrLfg69$z$Ap9Vo!o=z2g4>PJ#Wqo_>HvuoZr-z6a+p zXO(!u#W_?&!5y*LKD1wXn%Z(@rq|RcaB^Aj{yJ%_d?NzpfGR&Gvx5t}tNcUnlk63% zeWB91h6I>)`LIO}DPb_};8*G}om~PXYf@r>yYtwJegOA8ngv*SIE9!EcMJ9|Tr~$2 zd6;Ux1pKg-Cf7Wr+YJm&{@?tSf7YqOk)LybQN-xvs*~`DS_3!%ECP)EKlNte9DdV( z9{v{bOYFZM{??`OMx}oq{?>N;M(O`NRK35pHn|>ZxylK?l*gRAd2=kK_szd*=Q5i3 zh?-*q{sveEsQ2s5uQNW^@QcoWFFU!C2lz(ZcyqgLf7reMzUY^rf4}$ND*SafK!bni z_W#Qh0Hdgms3kU}yuSG#yuV%r>}b8pd37oOe^2}`A?X9y{pzyw&JnfCH~;_p=6{9( zyUF#3mzSNlkEoTt`TyTH|1%7xeJF@&rfI|i<0;JLK`ucXSladw%9bAN3XR9LGHzIG zLS0aVWz-3oW?&Ke$@0{Dj0My+`Vfm-O){ddO(FJPzgy85e4 z*jliMC3rSuPhbZ-Irw4Y=3pmp--!Ja-yX8{`r2A%uY}s~`tn$6_Ij&x?(*mw1Oi>( z{9_mWB&~O-#bwn_bv8zRf%BVT#^Lj1GbxQAX z;811&aj0!Ro8p18f8dwH8uwxEFv~X1{*-~?4<~*#wm-Os7?S8p_D;7@T{#q;AzqKK ze{k#vc%g^1(-n#FSxVmt`4+5MX&+O7Pr^2SV@qD=ss3T_0 zPBYrtbbC0JNc5PMxCX-5J85HoDE34S`)_wuW77}5?-=VEPIIx8Gb^W3Rrf&4$JS8^ zyeB11Wn0MVS;;XNy**HgvKPUiqVV$R<3MO%)~mx#+>)GOF%3RT31e&Jz^ArTcg*hF zGQQr`>LveH^d_OLrDWE0_{=YiZ87WQxCqJP(nP&C+7sv|m?g8k{DnK9)Eo0s$0PjR#QQ9vslvh^aM0YE zgLiCKa~jbDp1Ol{4&Pz~Ha#}q-|<(+1HVERqgh;)G#6w2TuCBiKi0|0rY~p?PZoaM41}06^)+9KMxPj<5spa{m=WS#;@&WCBNAor?@+0 zGH&O?|dR0R)m7ufimguQ3jE3M?6j1Za1iQ)=aL{**Mu@I+y zr{8_!)^4M!!EdX&pI)H*uDjZP3Y*Cb`GJ$_Ko*1F=CgGZG@rDl@2xM!(n@07i}MNw zOy_!;SFtAT$z}s@^im>Txwguq1;IPo0#6T)YC)?zMe>) zoCb$u)lVee{(e_espZru(MK(M(Kh&W)Ri$amF>Bi4{KkZrk^$5zaHXsPUqap%r+>E z`KczvmEtXB)Kug7{BmD{Yhkwq{j>XNYx`n>5&ss~mXu1!mi75TIM>z5E2-11kZ44I z-&;Y;U7XaH?;EVQCgde0ec!x!Ao2ZH#~qIcG%nk8xh~Jt8O^!57}r!Z5~dqoB;B8~ zBrP+#^w~GXZ4^)4XHrx1|2ClZahsTLgFICb<9pEwVQgS`pKfVR+R?V3DXs6F@xw`7 zX`Tm}-sV1D9vTa3FDy|p{o#<034Qy~TRt(zCmgxZN}>U5%k|J3OpEgvwtbe^fN^E*H9AAP<*)>pkt?SIjFokZ5?8AE7Xy;-f6 zX<)fz-6thf&Sf-v;kJJ@^P|76`uKaqN~d_^$<^9o_{?CT9LsEz?og}fxu7BTxzRFWRj z9;nO6&oel__UaNp6;pg%h+-^?;hP*h$<^P%RQvI9Hb=+Cm??sR>S|8AqTl*?h3yAl zSKGVW+jGV3&2@`QpKW~~c_%-{n#^Aemth;z7+52AZ6tMlGg5QT$%$%+x4a{E?pRGK z%=3Vn6ZL8>xt&HCn-jHSL0Qnw7s&{VaA}fr+d<cXK)=lLKdBUhl&J#L}@8^m$ls zC}BKIuuhxs;D>>2sv#Tmb!<7^L?ah2r+jdpXpimDF`m$Na#+^725!1m?ODRBRg{bbjkauRzje%DB zrvxWHrwQKnD*Jd(46kP{Z0_RnR(hW&#EtR^*j?ybholK_&E3AmA#9VBCD{!{*Ym8B1{0bj@eL3w0SxU+-O7=3UsL zKagX#fJVMUzpXp{n!-sfXUKH4|ECz9yH@A66G*(GuC*JRSLtxxk68WK~XF!i9*L+C@=pR?x_9}8N?pdATi?TFy#Y9!I zuQ<`l$1SqUS4UOenURD#bBCh=%HYywEk0VM_#uP5&trB(_29x%Y+Q*@f3J?9mqjwTw6KIb zCZy>F(V7T)S3#A#^JGBd>0OCiKN5w_U#c#P-wM22BDPCIgn<7;rWlE~BWPNX#`K*n zDwe4{I@N<*0hpU`;chyn;pI`y@tUtsX^1LMofF;O|xnP$j zbyY@OV*fV90SycmDi|y>04!*~VUg(iydg8Di+cmhL(-RfC81rn^7>xj-Nx6Q!^S8I z4Yej!r^Nptyz~hlKd~Uqgf3Ra9aWyznOA;`?32qICj9Bnw5ht=AKs_YM5@f*(s9K| zk4t+kwDOM6>4-hOJ6~iTY98mv$j$A}i1ubgI4)>a8E_OS+Nv@Pob=ZKILY(VSwfFE ztcoo#IpT3FG~Ad|-`!{No!Nim#hln8_i!PG=PcQUm0z-=mY_hLfclYYo}{E{T2JXB z-KKIKMeC82?I>-g^HK)SWYMiHGw5b|*a?x#3;x&7;tK|KH#Jp1MPpKg8!v#*w4rLPre$vhml7;%6r~eB5Au%Z!dM&ZCJ=Sfhe-rQzUg$a`991j+^?{BWh6CtP!-H}AztUX zS=YH)?<~c26x9+@I$hN}(cqsr<(3TMWx!3>AZ&!h3S}x-EIrd7iS^Bi0*joOOEwDR zw+M6TeG^_s{lM4~Kbf4W<&hpElqRzfPUe}GT)6Xer7(Nqo>F=XN$lPc(H;i1CL3$L z-NeFpG=`dWP0K(fTbYG-k} z7%l`ol?_hh5W6^gw1AGSbK>cyKe4Yo)Y^Ng{Y^}D;YSo3bc@JvtJV~;i=W9=_0h?_ zlo21s_#aizRFsYkL}>GNy6;%oDhE3mR=r>A!OkX{b@+^7>KObAoBZS?t))aoM_A|4 z!ssWqtRjt*d)Xt3$vP)ldXE+?dU2ZkG(GOM68U9B%5cmC5A~GFz$GrzK(`1DJ495I zK)h^daAf28G8Gtp*a67S$V7oze0Ukg$u&&UNI2|porA1{kEeoOkQywQupvlF7VJFr z#)E2UdVG|*WxWn~C9zU{nMkrwThn8rqP3iwC}YquIMWJKsrLx8ONAXSQIHt0u~8!_ zM3JTv%-up5$z>kX=dP|mKQ&fmP8Uw6PM)cJ_hW}P>543-nC>)<-r}Wd0uAc82iSLU z(S^L+tzzClHd4o1Hy~ei5z~_%fOWAoF_N51->s1L(IPtb_=)EygDUc#|BaMS{uEJ-4=Y7NVR1VJu|k5{p{d$5@xjVr%n4X zzP1dEIp^QstPhyTcOw6IjA*^i-w0WKUk({R*|Es!=uMz327d)G6_{OCv;uE_@Od{) zKNtn>`rK74rO#1~?&wy&>s(GdOux8ubs87zeV$k_hfBF9Kv?9`7*c7|o`E2AM+oG9 zOGrEzZAITq(j3{lIMI$udZMPH6B{`yfYRrP&UhBLy_*BUWcdZ7#EaMYs0%jW8XwFD zM8x=vCiBAO$;0&)$QX=Q^izY40@ZkWTV<v|Rh2iQJzU+D&Y7ttcL#{W02EM&H3B7R9_&5v_R=`SY{%>EnaI2 zz6X~Z#*O8Ij-rO=zGQiK>3i6AT-%uQ3+oDMY^3&XvJho#sg~M^kh?aYq%~|vwG#qe zG-O*JDwutJZA}`RU%)@jy{tg)&Tli_oy&6+rO)&A$Mdt0aMiY4AZ*uXKSRhl#HHNx zdY%q)-;r(Mw(}l&-K%xygJ8r7p$X}76j26vtBZrJtDQ({w(9nSxJzresha9!jG|ZT z-|i{pk$q#ry>rEq5~#?KgZh9EZm1=<8f&fDID3~SFW^?BWX0u;9S!{ngm`I2a^sf@ zm~CEzIDj-9n6x_aJ0Cs;0n*Sg1z*UjE~(=#efOf`I=YqJ?N^0F$Yh1aIv(Ld_VpQ1 z2HlJ^#T{SfS);MGMm)W}DLs7fCS>Z1IGLq;;%&oH2EM*;Vo)6OkmSlB%C09a%81E+ z0Z;|E_heN_@-gp`resjDWoVAlkB3b126e8w(y(ZB`#{}K%?U?4lj+^MAd z-hnSq6!O6|ZH${nEb@-Qny;HEkU6IB@9v72J)E#fE3w834Dpe0Z%V7(5uC=IdUk>B z^5|C0EkRcUs%>a=rsS+ZlR?8pxzhgj=y^3)D^VW!z;!B9lChE&?ey*SE_J_z3-*cw z^;KTdv*`sT7DyjUp4`P$>l4z0;}t#TeP#EZK0_k*iS*`3ffdU~kaL^sn%eq{!?Pc$ zKdTcHk29#KZDnR28VLqJ>MM<(dqzEhX%KsT(Mf&1GjVP1ZSgAaO1VMx`eg3vqW8Rf zGtuiL@w(pgI+4lW|6<8zKg*^G2T8cY|H^BBPn3tU`Fd&MxKmzA(v$erNw&?MMJr*| zT?skxQS0IeQzx!_L3E^RI>pBmMSuU3Y7M5S%T~I|2oz2_`9rn|o<55HeMPA>Nw*it z*ZOa@*?46~W0Pgx8M~+*tsUb=yA^2S7BlSM_j$yS+@O|^g&^PP>y)^*O)k|WXrP`|LxRtYA_>AaS%Fer7?0j{OhNDG=<4w% z=J7y7<7OTIigL03fw4hbx4gD*o#YK!#|4G2b`$&e!Mmm*-=sejAuGmTL~9acNnDJ#X%G+T!rG?puS$i&ZB`Qi!lF%Dbn1Kk9{ZrMvK-AAHyW6s#sn97UEb~3^ z9~~sxo4>}2k!hA0SLHGGNkjE(5HHJc3TPU2Su@ zI81pSR!H&|UwA_c`}jMSSU(KNXTJEryh7lYib2sJhNtoA@k_R8#}QH##D{L^&zA&G zXoHkL^_L}rjjw2J*k^BL${smc%di{WmSbw00>?ZxO}-j7@WOkgBiUDby>~Mk*6{bIlJZE+3xh?Ehcnp zv1acLK7n)sQ6QAXX}V>GbeXTHjt3T1aRgD|b|(`}{LUwQs+lROcP$Yvzf&s+)qk_0?KFE~9v$9I$dJkcrO1d0-Dll3J3&#gwo4PT zt>uA=r7l2;SF{MYIiSFAT^$K;XVoA%&B|OUlJM|A&tDgm2tv=V`^VFlHMS(7`imx- zX*wb)&S^prG2^%vMo~XSUF$TRsuePuv_$6n8FwjH+J&AM(hrm_)<1o*?_^lvGAT1- zkXGHG+~$dmLE>Z>-TUMv3;HHyP}Dx~Gpta|Xr&HM6(dn7rZO*dYVzqVzLo7612Uec zi}k8*o%~8^LO3KYR;O7Sxn-gImh>6qE0L{QZJvC*%8~o|me06D-oz{%In5r$c6z>c z<%HUPb$^g1WI|{h+znWw(ucpo;Gj;qqE+wG;feX;$6`H7J`bY~^~z<9#zXv-OU=3b z7P)PHsQ&xMAfh(UOHrFVJ zVwx50C?7vD7JkH*DUD~3nnF+|3q?ZGx{H(cSzt^qb~ATrv3Z^KHdbKAWj(AGisRTh zm?kZ>1UtSB5|d;rr(L_ZT_gOyKI~=XIdJesvq=N(!OqJ4Fk#-mi=or;*{~sV{EiWA z;wxcVA~aP)vZ-gJ1(8UtAL)Q*&(Hq{81Md3@MV2Fo0-YvYA}XL*>}HL{L1RKr`_-I zgVN@m5tl(;iHNI~UdYnN1j|{0pYz8DaOe|^E6ZmRe@>!Ezv^T__`Ifso&01Y|I8xdtt2qCL(fcBI~8W%vBOq$6d32Bwe?#)0~Dc&=F`}?x% zf?lBE(~?zuo(^oHCGCom<;|dmbXcq+4TpQ$bGo$7^Qe2ekR3%K4eu@ULbn1A?j`V8 zA$ECNXSwu*gtcfLpcWRDtOB!FOkKyF7{uZ3lGQq-4x2#!Y4v5)Aqv(DYzrV-zo1=} zk@@)OIW)BLwS0$ifGO~QcwXg56Ie}O9xVa>V zV1l(f5W#gZL@-kX;yZ5iT(oDVI5aA=x#VEBS&=|jnfKxlPVPvaS}&SQr-Cd*uz#_G zhDnY)MlL3?QXoIiv^Yet3n8G&NSQ&DMtYKfnZ_3{pz54G)(BzE_%s%RV6zuOMuTmf zg99!oo(4gni8V59q0)LEH#C*h^o1cAEBPZRb=I0=g>AD=(t5M5Jrfd;ghVqwgr$b( zgCZzk62)oKfI`LTZ=dq%s#8U2QF7xL>_6X!`TL@awBC$) zm`gDJ8c$_G0Do<8M>hm%xR($jI6@atmC0TGl4(U8DL3&pxOFjBdh#GIke^$DrlFpK zW)ooFFu*>V^w_&i#q#SIH0d!OtdOWyEznv7mPVlK(=k*M;8iu+uo6P^dwjQZAv_vO>{ztB$o7~FL8Hyfa`l7g{}a8&(=GTke09Q`cvi)M71Pv z16&(jsc1WH<^FiGCMG*FLX4BUQcLD5;~3TFAqJ`8$V%kmc&p(qX2PwAI%Q^ExvP8f#%uSurzrR zJw%Y}If-|9I_XDgQQm&UTn*kOokQ>wgj~McYAC}_H84y~SRtzYlk>FcK+=@CP*ac zRUrM@_yZxBptT>-Cj1TveBQ2^jf9vh5r{l&iCkmW`kz=H8Ru})rWf~MN{brBlHi*m z4_Dats15K}OW&5nAA?9Kdd17N}5_vw; zubgK(nV-bK$c-cNB;i=Bk|rGO(3Sdlx17=KJH1ShXHgw!ST#bAhBDa_ zVVH$%uf!|23<%oS1&C|H1}G3{7dH{O!19@647AJ9o2G$SIt9EEQ1xgIUs@DaaYpR^ zcVjoi8|26nzZw9t@t=K!VB_yI!R3Ex2IJvlY=*l?!%NsM(vv}vqBIRqBhhLomEeOm z(!i>Bm7g^DC7vxvdu8<4V(NK5yUSK?vMo%*!B+0%hMQ|qs>&Gft_mq#BcMuZ>sWSi zOWEbx=Hl6r)Kpi6*wzZGQZv!)If&aWdC9`_kJg`b+I4h7p?aeK%dpn0Sw=>fAu^_Wx z8tiB#L>vFlv07amzfPu0S;0lx#;I~DA zvI4xCLRyOi4L=Y?%Z)sX0u7_*fY_7~*JM(Ykic<5MX1AJ?y59T@Yr#4F_q1f%c#Kq z(=3Ic;mq|Z&2Oveh-)v})oE0)gm7~g>KlzjRWuc0bi9080w7?yfy({X=AW?*@DT^> zuqW*mhc;a7#%2nx|9Jo74I7_Ub6WrS8vJf149>^_|646=C?Q#s~*o zx9Eomrsl`=8^(cN4u$eZ^f)*evXd5|3_r{twXR&5*IQSr`m9QjlHiK~KJNrr!rC9^ zLKNtlRrDIXzn_4nOY-d;z<+Y@PfHXVc&A0xriXHF)5I4laPj~ z?7kwb1&Ko>yO3VNFTnb#d!lsPTrsv8XIv~SdnFC& z^o6<_f$z~t2)tO^7#FpSH_`|-WCY2$#-L;dUtH9usVq}tWGPAap84J-&FL{?{X%a? z|Jd@jtv>EU!5H1JFOcyfxv2v)&t=`-FN6=+z6P;4M)H2~YPU8-M8OIX~4IU1C?QTv87~uas)}L$!w!=tTy18ECUrCt=U4x0lI}y!@k;& zY;7Uyu$qqCjHc+tgn6C37?NEmbcZ~5VM9=N%-aM<*2~TK9M**Uu05CMN>H!kWN^Z0=_#RkUU>0 z7vd_X(7|EV=osMf8}is2fQUt8Uu}nc1b&KK*5ojHNdP2HcVG^p>MTK+Cu3nm+WGnw zn`@bj#S%1M{Eh;D5NRhSkCZ^rS&1MSB_M9R2yH&hQyXN6R|;yzG{{kQLR-O*SoILAtk3Sj!l!r8X~Zm~u1cvoN@GKBBQUbt$p z@D!Jcjl+vIL9>kv`ZdJ}Fo*rDRfIJFl=XVDA zL26%PkU%(g7y)ySJZ1NLG%&KPdJa@j=UG@VO8n`|0npwuA?*koVuJ?2JY)d{`Su<> zz$+wBqQz8Uh$l$0>}&Rl?c)UI$CjdqSC5K0hG7`G>y4Dt>mdZNC7Uu@yg^q5%~N}l zKLwpIo!=7>^sWZgn}5Lyh-PW9mXQO^zn%;qe0G#749ehav<^iCxo67L;$t_*{UGV* zz7v2uZiH;Ej^2!kLOSJxBKIH#KcEC7A}qgv11o@QrKou|1f7VKqymu+n0)4egOxkT zhlP!s7eP<=1-=&(!j3a`hoBbTdx1`h(<15n`3N2rIEyWJis|c#13E<`EJ?AOKj7sg z2ABB0Yr92j{wZr7>n=!#!^+I^5t5_dy|3UHl=)>+ImCdU&Jo<0e#vSB{x|_8u@RQ< zT8Q5~xD)}+H|K*+DB~@vOk3=uYPN9XoB4iR0z`X57(6N!I}X~37>q;kxKoZAV3nJM z)vTc*RG$RALI~(}cF=4U2T|)}5AElHPRt3C84y*M>!=F=}(?8@nnRI?&F8ez{c~koc3TAv_e&mSpq;TJiv{mxE`+*-csF0#+Vm9~h zMk0g8E$)~Qi-T@pQ;)KIhX`=4^f%{3P@SW;iN?3#FMUwTm5;*5@t((&?*2+<9S*0y3N@w|GGS zI+4!^AqQP`H$IH)pXC5?>2f2@n<+}@LGVEy*<*CBXaLoY{y{aW8>)H#q8jy-PrE#v zYGKhZs@(|~(AafSV3X|GIRL&dL7b1hOo9U@2?K2J2C)84L9KxIPXv^lj<_Ek4ZUZy zpD^6wGel}m{IEs$p1WUg=3#k9FRhppuE&Q1I_SfQfL>F`4bPm&1&l6+LNgKPKVQ)G zy+E5^I~_o9)I#JH=Wjq^c(jcJ67DL7u`IC46bPnd=NAB_6vJB9sk?1K9&)SQAn_<2 zq-H*KWz_kiA_~JkKJ`9OvxTQfu?bZ`G#mQbsXEA~;&mTlv({;IN?(j=22lXX12)hO z;y5!w8mL)nkN+!ZN9`#1sojx1f=BlYG7z-}?eL2TP&0u5?OQR>j%y6~J|U>)T>SQH zYfuI|flbH)$frh?o+eHaWXMc7vCJk5&u>~`ny}U!zw#E{cYd6^s8+gF1*a}w*2ZgQEU^Pp`U9fp>N!f?wBha7 zudAVaH986nMz;pGefLK(>yk5l1DOh=O<}1 z-h7_VM$qG=saRe?O@&PwtStF0q=Wf>Z0Q%>?{EC58(VotI*B`Lsdmqzv!)c`w2~bg zE4RWce@-->8Bd5t_~HGwE;2~*T(AoXHh9=Bkg+MP?net`W{&C`WtwH}w`OO2Y`eAb z*Ct3vE!ly2QQ?82;W~^m-U?3nRr@hzpC6CiNs~ zpfAPnkeZ|f5%VBw%(t!^UFuYL=dC_ECuj)ZzZdtpuo( zRQxj#P)8Y1CqE)lXej6lZ`@?1N-0f~1BDhXC*NMjCVZc&`i1A#yy37|P2wJo{RX8K z3UGkpXlJ#IZ4mD`G@e~fIW&GgJ4!8CE)8y_D~o}0@&!jusg`_&n#@hIcZZ0&`Gn|y*PSp_A7Ml9uIbV{=_fsrE+nPWFh#~N)F}!Ii3kPNiZJ;f zDSX$XvGG!DEj7--=7~{fi}>;yi_`9ew^p$8bih+|p*F95R&e+MpsjS~)1jSJ@Qq54)C`e4`b? z33_Z`3$7v}Lf)i3XtB%1)er`~ikeLgQJ+hAe7M+4K5-?_aH6BAN<`pbg~kS9c#(|E z8boGq&Uy>-@x?ui5u5m)w=mc_a}Zlz66KC0*>*e|N37|=Kpobe->wKlbYgpaP8sna zB8{kU>YcG^5fO}>U-e{IUxG`s@Z{c*$fqqHM{EB!w}d|7fc14=y&@vqT*Via=i-fe z7=<9#uvM{=krO5oDM^mDQlIKu`n4UF3JyVzIgUs)bm2*(A^YT)uTtr0F?AgM-J+Na&(UDkIiUxHP<^F8Ole3+G)Nip{Ma(oR;W)8dNVj3nqoc@s*!Br+ydldwy^RJV(l5aJVv2 zQfQJ>%DjYEgq%)F(pbEuCp=aN4^Ik}n zeb9};`Un#maq>Pv(kfREwVcVVS+$z*Hl3W8 zwTvv|26jv2M-yS+nHNi``2j6qFI%!v2Ta_4FU-dJiZo0b+KfRFg+t7@ROfFsb2|kD z*<$sN03XJgWN3AIMy}ttoWRY|nqx|ML|k?T(TSp6(lpA8cYRI>cdo^`VCi zFlcoR(<%$kSbH(~nDXv;#JG>hVjN(5E}ig8(Hx>~g6tXzG|)qTOMXS1>EB|e-`T}|Kk z0hAQQQMLH?VAnEOps=Ri7`hBM)Z9gfKlyX)gaI7iRJfsboCMPG9l^6UBBg;oWkuTw z;MJ7%8n&1rftRoAwJRjIdZZZ*DUD^FKU>mZpPH$UW43Jq^M)1&9^EUSd*8+6L@avA zpq5#{Q(@2S*|bulNM+tiQu=MtwA4PGC`!oq#Le~?u=aWD%eE~=Mz;^{X+&LZoL0x$ zGz4|ZAgxRsuL9jK51$I9PYLWQCQru;tf#3mj?}RQWtJGHSXxle()$$H|A1^x>YMlRRq3fB*EF@i@72-Silbk1#C)`^ zkKaI(4;kvmQ&ygnh9NA?URBuETIv^Zg;@cWy)yGy67SCBK;=DWHwRSS?q1}FTBcd< zDP&l=p3l=skAqb<)akvn@<`PZAKXV(*bU#)rXNi$CNeu4!ZILy!-YyepV%Mz zFDwuXDKy@~4fH=uFH&tt?AN0Y7%eTz;Iu*ISP`_8R&Ory)_{wPa^|B^nBVI!;@0TH zG9Nz1D&R{AEGQBP3KVx-nB~2g9m4u5V+Q*I!X9;>{>3;yetp7gW1yKp<;CxtXdvr) zz)c`MqmSA!(q~LV^v;3PWxe6)7%iFIErKRU+}ix}&e}*ah^yoJ5${N}>$-glSRP~nN-upW)@@x>Y`QPn}bBk>XfnjeNH>`pu6D)5) zF(&UPQyJf`;$_2X(B<2ye)Uf0SgqA*C#Y}p?$6P#srwLaUvKa#&bZghCi%@^Zz{(- z_V+4u7$@eBARnSdOt*=)5KSW0E4uF4{xL^!tL!FSPT2zOAm|r>5Tm zIRUgNcZfqjcN=*p+cAsB*awnZdENW*OZA(nB!upX)W9mTw%i7i&{Tx($ske@zK1s6 zX?519tj}=yKLXcQJM6#qzL*}uGEea<_{EC0%M`|~abBlrI4ib9#F7I07P!&%l0V#GL>}VwvC0tPCP6q{oTRinsA0 zH3gzy z9SC7jYU`){#x$98RF(v1g#>_kXMdUZ@+yV#V4U~ujd=$!^Ax{7L>KjxrU*$gN1c(D zn>%3QJxhNr6&}%e_p2qI9El}B&Vki(1vzSun(WSqMiTIm=>d6LS8`y_>f*F4@FwCj%B%owq?pH&H*l@Ngg($0Jm$L*~ShFA+3$l>s4fm>(^w@~>zH(;S7g;zoHm%;AM zgP~^x{s~sqcVG5>I&$kCnX*MH@=)|wQFHL7DqCGT`J}o=u~kFv0fQ9BadCR#DUd`5 z)ooGlGu7-@pDe6IS!VH`{qkV6z?_&^L{DmEWOu$4#gDLK_;sLEbcyflE>IrI3{yr2D|i4*WsiP3+T(YRC&C z8etC+1NNC8)LjVpoz&)#!9D}_LWF`mdCw?PhUU5=B;k+D4Xtb#qwbkg$7RK#eZI+C z2X#v^TlN!n4{qS}EcPC8wl_ni&vQT>w#3soGo-Nx-r$-pX(K&F&4UDUAHYx+UpPaD;S9y`gfZsft9oGQ!9rC(dvZl91q(n;MWbJ3faMZfWzE4{ zks4lh)?D1Uk&=gjAHL$v!-eO`@M(t1u9?phq3jj#_zSP+frMGb2+@bz!OW}df}0nP zWxCWSZ4u+Nl}%R2&I`AWxVG0SX4gfY@1d^wucT}qBg7wGAERpyPs-ta6JM~*iIWuu zyV-dURQZAe*_{*nXx&pS=_Vbz2BeD2Dx^Y9~w)Skyfg*sTNv;bs4tN65W(iw`&cU3V%)4_UP?^rf?LAVmoF!mf zBv!-7hA~a#G{Z>Oj7%lIjrskg_d(|5o@U%cYIF`@@(HZmO`7}|AQEuE!cxvvQWGNMwaRz&%G{+l=hh}ap3vNN~C1@;(&ouGJSM_fs_z&z`#nt zz+}p zz(3bp>yFF)#p)VQ+dpmyTt7`5DBrrim}45>E-N!4E52-Ek5K*W5{E0qA6Xak8s-Z$ z-Wb3aIOep;3hyDW%~#XS(ZT~CRII7d$C5Cvv)t|uc{n9Qn$8p}gsQdsU@wF|Ht?0L zmomL~pgC8EvP?u8SK~`#KytJGQz|r17a=Fkdl{VdE@H2P1Ir(1Ye?yfi2-Of!~WXkL{QCk_b&U=fbN- zid8`6;dKM?ji$VOBk^PN{#RaxQ)U&0_v>U((G;cm68^-%h<(~jC%KQ(E{`~F9xvwH zH&4U0?x>BA8KB#svfv84PTH?iW5zAciaBQKW>28ur0B(@pyT86!xrWhS|(y;=(kxFaG6KhvIikNTpD= zh@X-$X6~#$hIM0TdbGIN5kn5R4Ao=3zw~>(k2?q2xY7N78gHZHFYMiiC7BL}5SM#} zRxA5-Ivf$ll3)Rvpn z)lR3>h1=o6-uht)iBOY47i-;3{W#QEVA-8N2R#7yTGHXiwEYnSeShN=~dYO6Aa8OCHs63F#Ui zgD>dZbsha)`7aUCF&Q8`xd^+ewn+_y>TcI{Ue2E8{{rFyLdk&9^pcsE*f*>Q5OsPa(AtCr8I8mUsQUw6z|uPrT*w_yR2p<`6i7tv zGAMTYHmEz*9R%*_50EkjvD8Oa{6CDnbyywGwk?WFaCcikfZznzU_pcHBDe+%7Tn$4 z-3h_n-Q6{K(BN(XUX$P6=k9y%dH214_^Nx&syW7(qpJIBT3k@0&ls__MY=bf!jB-L zTWbltu}vkR^5;D>*gm`=B0`c0DA~GwZ0PFhipIPdB#G71fC0m~#lL@Vblb2$3T|ZH zwC}~sj`M3o*e5RBY(ywCM8}(A<<6E&K7(MAj!5VepMbNOdVc|K^hVhLO~iGJ%jt$T z24B9ljam8P8tF|=Uhwz72?OGnM*;%bZt}p@-9ywCi7immapa}jXQ~DwR*Y>anEmwN zFi*m6aiId+DS5cL=m;krA5ZBmkh6a{(l>XQy)3<3ZTwHLDr4`ZJ`aYxbtgOO%)8jO z!C1irAlv}2{ucRoy|S9JrT#}AI&4?4Q`Q{ifr4EWSYbb!+@=BOJRNj=F?U1GP))!<=MziQDi4lCgjzn4YfS!Z$m8sN_DrfOb?YCjD z219!|Xtc>T4{ItSjjq9K3z6@xxkcv-O7>I4>)Is|!OC7x&bwZSx)heDgM% z7m45GxoFL~p~aQ?DS0`KR6HGKyVEakg$oAZ)qrpOfTOSW?A%^>c&qm(s9!H>3T2u0 zyg;s=t)GmPjV}sJXN|Otr>{TSH}%DZkVkn5@6AqbXA5~Hp6^XC1isZu+%!$+#|a-B zy4#M8+AKxA5qSSm|IYL9z0y7c^^vCu+s>b+mv-f+rj$${Z^fiwd?~LJnkMx3@9yn~ zO7lL#dRZrDlx#n*)Hip6G7J;IT6SJ1MWAa|v3=UTiLs;!ss(rXU=p0CrXv#12n_y@SzI z*6X!P8!y3$p#*4GyMomut(z*he4!+_8=j8aJ-ZS%Ea6N;|M6mq1Yxgd<^HS}qbHsv z*HgxIg`%^jFLDo;IAlHd_KO`+zo^fe*1MyymjgPPJm1c|RNa)d#jboz^eRwCVz?6S zbW~k!Mmsk520jhAs?O+e>wNqKLP$Jf{b)#3&F=Sf>lTX~i?J77T53mV^XnbH5vyOg zDBA^$z5gCZmNA=e+~hDF|4Ro6e-MwQsl{nPO$^Ou0zsy|F-oQEnL7c&YSvHZIeZx} zFVApiovcu`_54J=+Q=ZtR@%rjV*Bm@%|ho)x2e9%`IupM{bsQtEij20!B&&ehm<@W z^e;RCd&vf^Lb`BgDwW3JdrN_rHY0EN_uNaIa0Ur8YsT{yLY&(_!OfRVbS?|*%*KIR zF(-I#spcn~$KxL-VdVzvx{=QREES{Q*LVj1A@E+@i87M#nD4WDL`03z9l*tm*LoxU zrOa=e2eE*bHd>1?^mGDYz(R0docsBxxBgGc$*?jGo{>}`iJ`L+ng3w%4{~lx!8b8` zpwNnK)^}%&hSq*qx%4|<5aKE&7M8G0!$=EErLl2%&k z2DQDyxwh=COI)_^JD-lkg8!s+a*o%JCX`G^>Jl(r}$0y~oUuIw8*-<}K(Y=EVV!R-@)u;V9^R)p%TEbpVeH%rB#en&>j ztVT4~kVeX?K9-B_FiTCrKCa4M;S^fsbeu_oWdDo{wZt-kI5_^zH9CXT?9Eb@HC{DO*tK?F4ct=c z<^DI2(bu>I*TYM&lRR}!1$KqM<2DHSEA~|#NZY7B z+^ljYxfGd5zqvV~(>473TD5gU%WI5|iZ5O6hIgX-Pi#-WrBu(>YeR@BlcG!DQ-X;SUul$! z7r*ycSyZ@9e%8X(J5jMuWS60%ZSZ|FH1TQD6|^YAcuk>r(HO1hoz(+|`=KFn zw))|DhY5ww#e0x}$%up2;soqXO*q*v>=MNbLXAR(~B*k`17K@;K_9y4V z0R(5ap~oSU#8ys&hn+-;&NOL(Gqvkl`tr6D$giq68^`}}JgfJ8(+Y6pz+$_Fe#^OW z-G(QMwQx@wk4bjNJMs#fNMDj0Z9d;J7hX zQwUi>V2sfENeJqzM>yn}c^lK2-S}BcC^v^BMXUsKNN39@+;iu7~M++8XMt0 zCSo%Dr?iV^E|3U0Ag zeNx)dmi)0|t7Ocm( zwdJw-bSVO{oL!M&LsuXc{iYfI zR8`fxO?gannxQ~%?ajMzt`bjU+(Onm3YPtw*V0X*KH-*Od?uQ!1iZ<+>_^cYLmuQ4 za~%@9S%jZX{b}0$h}cF>h{b=0--3`lO)*em<%$wvVF16gV*U`SBLAaW@0U*c;uswo zs8i13m;*I`!k9H%bECgiBP2L9-PoBO1das}wcRy7x6d=TWV-HzlobhaX(n`&Gt}a# zCNR3|{CUinAdjc*heY&)A2AYp4ukXbbaEZ14{T5yGRhQX2N+O$254PnzzOdBH7Np@ zvGAsjxaqV3Tc5tVlFuT+T?x$-YyCM3Evh`lM`jJ;7G`rwmil;!1w~;)Hsl^#>523p znfW5V{&fTX`Vg$s_yYD2_mDT`!rYY38D8HIra7w!rSU9K^q1#?xmPp4Ld<5QYUd~B z54=%CDW*P{Iuy%adwX!sL?v*-eNcs4A!aV;8h-s=$$r{!-`BrVef!JxNuI~eam_86 z&ZiSr<~ROxZ{Zf3!v}JSrg;Cr^l)5|cpxE?GOSN6P!>%bM3!49Wj1d-z8A5)-;GJ( z$*`ZnxvBUx-BdHLJ?`u@+EBIW)V(7n{`~ZGXu9tCxaDzJyvnVD^Cq&%Mnyh=S^J%y-Gl0V%5XR+Zl>a+Xi3T#PH9w~ z?SZ{5!6BP~FZah#8kd50!&bUD!4*+C_0&YVNlhKkyF)agm*a_@$co&>6UuLt{w<jz$!;7$}9Tk#r zM9hS7GB1}lLuD^-;kH|9hjV{wu{U$QWU0I5K zFk~F?(BP@L849~6&wqBw=c!k27C324ot&d?(Ok-4A*ORaGD^Te&y(1(LP0qa8gM_7 z0PTsHWL&_b?4-Gr5K?Kb$)k3xpB1JYU|b;R+Zd^(Ry}Q|$=ZPLxdv+LBWmnR+r_<0 zoy4nT#eGAVF@qEpaqPZ%;KAR6%ThDpycvT%8QOSU3!=-`p<&|xneV+8fIUf4t4o&6TkI-vBy!|Nk3#z`C7`^NxN)ztlV6N@^Oi;LkN$|W7Vq=)!C6gKLgZY9`M z7I`z`)ej{l(MPG#r89eM(vU-TLXiDzxTr&5!siQ=kVY3*!^AAFJ@f)^9|uF@)!m!e zRp{l$-pjkRuO-TLR^{%$6<+I_JI1*b=0xFUJFpa1=S;n9b7N4NH5FI`tSnTa9{M*1 znXNp|D{Wcjv<`-pGUUs~%($zh%Zu_hmM}|U?E&mjjBZm-5hga{Iu6=#c6dZX3x6Ue z18c^0Qc?t#ONVWaa>g*XZ_VuSb3R4>a=iV7yA|%o+VJy|H|8y+B7mBu) zSgGob-_`>mPJe-KX}~<159Op-k(gb{;`G)@i73KH(9=`S`7=KW942^$&3MX#K)lo|yY7(KKr5GY9qr1>T(37)GVU%SHtl%NjqH&*BsB z{4(0c=ICmh2=gMg!&SK~%z9o=O0!V}!3~Hj+m6e8uH%FjJM@r2GyUIv!nysW(W>y= zMZt7!==OH|mcBf6c7@3`{+pklHEwLfay^>T{RG>cjdQdg5&Ma^qwjI2E$fM^r@?#t z2{nVEz6OyVD$BQ~-aKPA#-VLWQ-`2t2**V3qM!^y=P%`&WDXAb)g@h^BO^cD#V^pa z0U5X_h|Er*iU@B{5F7#dp>gzRZk3}{5*c^1>>>E(CQW~hpJSg82Q|)oE+PG)a-}04 zB`mgB^JxuR&=D57WU*$iw^*$m)veLT&79m2tw^p<=gdl{;7a6ZXetizCVwNu01d?I zCb2LWHv&cHFK~n9FW{E1c#oS%*Ve%PV>;CUjUBiBlOp<&a1)>Q&NFgVkiC(&00Y!b z>2T9;E0;utq=8Jrclt+PxU_~62g>V17voUCl|?8Dcy3^C6WE(h_j3=^q6y<{sGC`d zV2yg@{qC#^=+GB@gD8Rr%cCa20D%RpqnO&9U8`>kc_6*05=j95Z*;*E%*r79An?8P z(dIUVIl2A>BL(q|Ks%lTs+*!Tb8jZGOp2cTn*!P!a;6$Q`6`(l1h*p^e79)&Z7oUV zWxIe2m9c9xwmtrw-0Vd|GI{1VNa!e4L2>W@0WVGYTYm!c?qX3HnkHP}9#m*;GjL+| z3SRkN;2TX)Zfe!d`h2y^``X(EN(>XKBm+nEW8=tmV4#n1CTW~OH=VPm@;sadXPQQX*^Kvo8ccV?)LviB_{jsNo74?O z9p0h-lvOkTOd7dYFOO>jmB63n!t^l zp7O?5&S>$rG&>_|J!=nP1jbFtTf7Q>Dz!~!3^0o?VUs0FfFrScG0qR9eN^Qv)thNK=__F6-Mlyh z;yC)hR(&s=<*pggJz;k~rc;fQy=oi@mWHN8zd&&(Li7=7_qmRm zSI)ADex!NBbYkd1=o`IF%$_!{t}X5$Jjt_)icK5BQQFO7#5H^+6@tr8p=Q8oSwLOr zy?FP;>zOU)Ft4ZRCY-pLr;6u>r(>at?P*G|f(uzaK++xKasS(rds#prK%%7x>qG1W z6bGJzHx(J&8!(LIPxQs}A%6(TQN6FgsuDtXH2VRLYPV9Ec|SdHby7&eP-x7M3}Y#Y zC6aB45m}TkS37H@eL#kN{bOoP%t$8v^dB^%n^_^nGw=9Eb{MM78m=_n54?S5^2`Bl zEx8WNauE5178oB=tMVV&4=l6ZNEQW8o3a+%cE_JwwT5fvOQSVTn@!ml6d4_`z1g!z zb}FJ9Ye6JOEN*JbhNjBlfMK4sYhq3gjcK3Ogcq--9Ll^( zk+IEn3J0^diun^G@O^CyU%udgOGm4wy;c4Y3HP{Jg}vk@)!vE_RDP#jy&wvtl=Jvl zA!;;}32)J(CKNeJ)A-0t>8C$2;Y z<1asd+=TkTJLI|+@nvFceTCkYLa+o^CywV8W8*~Qi68`KT$a|o^aq2R_Z-oXAqNw) zNN+zRZOK3$P{Fz`Xw=^{nWcS_>6DP1oIHV2%7Sat)oEzr#3Y9$WM4jnh}{$3dyes2 zBx;$SnJuCqN5pAfnuVP1Gun4BmV(HqAaQkBrXc@@IAsFpNJBfNAOs(sjJ5hBtPL?5 zu5`bx?XCp6MumuUiD^gtR1P!G$2qz_%h4X^ih z@pO~dHn|VIl?NeIY-K^(ClYdkD5q!ExRaO&#F_mG+KO)?DLM>Q{<^e**itjrl@Cp2 zrc;HtvS}yRK)v~^QG#d8rpT5GM}d0d9YxF86*(DR{Dmo-2wd;>;td9o7nELk3F=Z7 zopWO5p?{w_WdN)xg)m#?1Kh2VT`o;$C5At%_6j#&VecnAukbPTGbNR|nGgCGel%>lmhj<5U3M@1BX1aUxB?8>FDs_tdsO_h6# zLKHf0h>k&S)%#-&R_$6?W3JAfgxnVTwh^A+s_RdZw{?Iji7N&3Qt6c?zpL}*@itq9 z%DbdI&oDfTAe&o~<>0%S)B-$n_~J)ME9zPoC3Rh!`qu zs&h=kbB@?j6m$>D`k8HJb4xIsO`^cLIhN>&L?Y6;cal+ zh5asu)*50}#4Ri6PT%g{B%34{pWpphX`Jh2kF(30@MBGiAzds&aj!6NeU8z8s~UuM z_>j<9W8n)c=Jh-vzw*2_ZRI;lM8P=EdgR&GyRho0TBMV@nTI5l)O{C#(U`BDdT)H5 zzNYf7Z1`$Qx+@NEwz4iLhTL+aMBYo4B)P*M>ZLw2aU8*zrX*kR0Tl_`p(P&DghzFI zT*HAJS&Ic)`|!Zi-C@K|_>AJuTN{@;Z=`3s4ZB_rjywV_6Yo>}Rmf$}T86+zsDW6_ z?%iajo??4@=aC|B^_ElRHa+J{(}o0Rc(c<3_y!+2Et#@@`YqfZ6f%}38Mp8J%zSf-6B5hiLyuaJ$`4 zN<@-*@AaD%DG`Yy*bbhWX_UYCH5!OCM>7h)-3&(p#Ud@+(rHFD%^Bx!?! z<nd8 zI^4<`dEragvYXMl9M}oeIak*z+$jWZKRL2$qH8Nm$iHUgFvF7xn>K5zlG_j`haC zi&jY9w!!4wM_Q{s;6X3B{I z0r`kb!om$TX2+AJh?v=`)VyM*Ml;@&L}XEb7}&}|8D(66HNzG^8hv#t4{}wHK`%cxyR-q(BS|=>q zF;A>u=RG>AIkjSOVue3gN~IbOYF0W|X+Hp6zVr(7dq%Vz3z@%7^&mtYlMvk(#Mv9E zw}368YDe>D<>1Zj!Ab{6K0b<{&B+24THeilN2@!yq@w&TfIjt_(m@~VXgEnguUevhboP$+TH#Q97- zYp#>H0Q$a4%Zy~oj8+$$q&lK5QnqcZ2@PpZ%}jqKLd&7%ia0B`&whrHGtI#Ep-iSv z8VptE@h~d`vI{5OtRd5c(TDF#VWeve&h}| zQYKO|+4b_sypq~?t<*_#?a}mmz17orbPS5WWfcfTj(@0B3C@z5D!5VoCm{uy1kfxe zNYNh*!cf(E`#s?&n=*Fe4LhCbBF-W2_c9XP0*qO3k)0`=!q3r81tOUTg%*?L25l=V z#q7ix6v#SG{c*o#QsH6|tKGM%-vhn@)=QTC59{qt|FvF|!(Z!tZq^=PAm-Q71h0DIZb25Rb8$(8}tI9{Kvk;7)$*zAbP)Pj03UnGf@}}dA zE%|>jVl0C3b<5H81$A3g=_l&BQZ&QD3mPGkQpvD9jk}`qb3u55pM4KUU3JOKznUnx zi7KSUBh40;qh)i_-DD@e6aQ}IWc~4b0TNfq|1_nt=Xn$O-g_^bzy&UAOb0E;E;liG zD`;VV-@#VQQ%?V*!_|R%xO$+O!@0hvnS(o@B3#z;G$U%|8pt}^5BB)JGy3sE*{)D1 zg2G{~nR<)j^Dm}tAyTTBs>F(wIqBy-4)kob3o=pW?Gpw1HW+gnyr6E0?fFS@xbG+j zp_7>3k9BcfqnpoMWWLFE%mb5ZSL1b3b)-udDU=*U%$YE@DT>+fj5w!bnVinsrN~wd z7+2?Ve15w=obEB(qFnRf*)Cu6AlR?J`*?CQ=9#=}#i~YLVm_^xG0Y?}@I{1QZSUiL9vVWN>_wY_1F3)ZCh zOs$I-&@&a^TDkY&65FHkelizLr{JkW*QI~JXzN$UJ2L)~*Oq4HQgwUCrTgdCf^PKe zebLok$J5z}ypZR4uVmO`5jmp{V}3n#(_X)1Sb%7wm$~)xp6<&6*CGM%4l}RE=P0ko z!>s3vz0(@`DuaPB86x_X*6(n`xzWgYc~4P_L5baxti3E_=_}gyJa!knK}3|=Vy7eI z?6l6vAiIkQ%<~%xj8kdMbMt#%nmxD^+o5)IkEvPVm7&#r_d(+33|DQ?J}MhJI_ZAol{0GoRPi z_9u*pw$)Z5EN(9;j+8IEVvauzwBIG|WwL!+Jq{NYnwI}In=%8{1o9ZJ$oQrGv6!Vjke)H|ZMM5Oiijf65 zZ)|j&A(wxKWgi~Tbb4kf-WDS%RP4Db743+svsBrsq!Ll&EbZ{B%$b4?G2N4Ru1itrXE#(O|2kbOq5=4@i(>m54wl+4_`W*w^WUjy zztfakl?2++V`8CgN)C&&Pq{=oaD1cM0x?Ype9Oma6*=H04#|Rz>;-YhV#QEe_0q4v z>ue^Ry|K8LmcZ1>;Xo&m3J$0u>Sn0j3M2j^$2f~Lh>Hd(eD*FDY3FxU{=5@aF^Yuw zRrg7OAuV%c{4+?R+HKJ^$@&j9O)X z{x2IUPXlhuunkE$vB+8s3rjK$L-lULk{x;yDGkGUZ>RhxWtT487K&C@dQx7cH{>0i zeciepW{}%jNaQ2e3XeoBPo^R9PVdXjX`9S2W0FRWmGVvZg{_-;eA#h&{wSqCP~8d% zR4``!DK1Qf4p`OQcy5vo6TQv!Qlb`6x)mP5on3#%WU5M@d2kfaSx4P&Es;F(%WM_! z3AbueaH`0^0a>ul{h@)>+_~97mHL7LJJx|=HG}W+Xx-D9&SZ%nzpH9K{zb>%enB~% zGIhbAoNl}<+ftR;k(nmGni|~ML}6^v!Gc`B=mI}HpP*1beOg*%X$$SllM`R|r0fAp z&`gofXkpZ@-)L2$X;Z*sWwG$f>i9!@b7(K)elh)Zv6i|LQTgn5Ei)-y@!ZxU{At~7 z>4;Y2C;Uu(dbg1#Onb)-Y3X0AQ!Z|&X~pyy5vDF@#q?#_+q3ukpQY${a$(g8mF#Ya z6z!Dwj-UJ$?9A_n8T}OON_`rQC-FRd2&nRjEwo%n$QvDKn%T=0qnnZ!T>4s1E&9O0--9O@ukB`YdhlnqFXpPmV75oHJ)0_NFz0voY zx_Ff2_D7Vs4K+<@%W2QY*5p|^d+N=;*^7j7s#bgp^2TX7o$Eepg!lcS%=QI5TqX;Y z14o@UO`%8lue9%3|I)r=H7ouloj@MPCssa-&o&woWL!&Q+}%Jf*2%P1L$V zLC0uHjXfbEVp6;>J<92#{jq>i#in45u_V)ao+8`(m_y(8_@B>2SgQ5DQ3>>^{=s5np;WUKfk9>A;f zep@w~NGQaP7f@74gwHCIE);U2Zu?L*PO>Lm3OGO~+j%kAH+H$0s5MXFpVV)F)Y?)y zcLCN%0lo%(NlnusGT1E*w7%kY`4-ssHHiqbr;m7aqy?OxhqUvPU#LvKaM3w((|*_1 zrhDO8*_dm=)>_N~PgtGB`x}5wt2sU4xj+h3Z-{|`)U+!+O#fiHe!e=kzie$-(52g^GRDZ zDjDWvQwz}Nv|66=GGNE6sSkUhYSTrTeolxFR6_Z!MqT0}x2P{vkaH9gSj~Uupb8ci zEyn80NEpU;Ebj%CO3R6r*J7aTpqtT3CvWs( zi7C-wU4KhIg-u4jPC94WzwQf)rhd0CY3s*KcIOK zpt;L*dT{mWO4QXcsY< zrsE797bEbV%d{<_1375;VntaVEG$-h+3SM2uIhi6p`*JkzAZ(Bp@`}eY=;ec6?J z!0}~2TX+_7z{4c*@xRHz!91nSQ*V_>Zj^uYWPV2-v6mP40y~#8j(|blmlgshN#kK|V%f5mR#9jq5(o9Zb#TAu4uLkr~oc{qjFu@A_fC(mL zUkKfvuzF5qgA*BZ00E36II~Gxw<#5IQ0bnbB~Z*p@>lVhE#~QS0ly(_jg-!7stKR>~68MfixVcesdt*V)mdvimG&F zne0V8$rMi~a$*{BSGg!y8Fg<-3K@c+tBC&=Bs7dO|JNCnC$4j>PVMIFB&Z@T|07Q1 z)-JuvgZb0yXWejIK4hs>4&-ODo2-{=w|A#;B3%BirUmvAze^>vys{7lWj%YjN9jZaP|l+M`AAa`Urd1W!YzTVu+StE}&9fY-Cf-iYsf z|K557c(k%)CMRHD3?@jC$qz54$FkSB@#1sfld`s}^u2V@Q~?dU9x7!;1b|h~w7`^a zbReWBJDhm;*A|O)o6kpwwi5!ru(;zh2(+F+5^K*y*z7wGoo z9-SMukgbrdvhUEROD*M`J9MXyvyc_KX=T=Jykq6lE$n0BBxABIBSTKRHY@#akPA7z&6O-1`wzVe(e@Faf)0-N}QXxu*KBnq;RK7AfYSaBS@OGmQ5f!sJr3m?D zPKhaDUewgUf&`qY-r}0*TXwE!=_IGjvnE{@@TFQuhU8URS$S-6(GxEwo(p7LWCoSaxABShwpA=NH_+Xz z{0yCMZ1}np@8-qjbb7kj#_Dc=JI=9tGM0|f*uW+u26O8Ou3cIS*0kG6p#~&!ECnRe zT8ymn*=~0;ful6|-I7z{wD~c;$<^!OWbF3#bUos!g?946%E0-%AwTZw{?;bV;y{G~ z($GM}_5NWDp6OcNVQPF4)7>+&y6xKpJ>_zKER3$P2vatpzGV-lUsz_V@@c#K*cKCP z)`Qq@_cV8tI{V`7K%mCOXgj+)j2)`F88w9*;rWZMBe~mKayf^`Yx`)EW2ig6m36=S zc$7cL0WXhU&tF3RJFR~QX&oH9fto6}FUn7t1%Q0X~ zL@X31Bcc_-9$tay#W0{tKby&^5+&KgUg3elE}NMy%K4v&bH(f{!46s}NB*NMJvy3A zhq5H$`eg1I_twD`=8!6f$BZB-6|}EkrJQRZi|FcRvcb;vb?)^TQkVVF8o~8du%ZSi z^QPlcg2$2{bL&_Ijv-vGpKM8U(TdWaMAw&uI#q!WX|T`RJ3b;h-W)E9*f|=mJe0@O zn2uX1DwuK&SDa2vE+za@i8zQ97`A0A!%}=YZ%E|+!JH)(s_5aCc<;GC(-Q=|`9a8U zBD+Glq97m`L2mb5KjnZeWwWw*5l@POjm15f1`E~Nl7eSxPBGc9Fd;+M4yVjv-^j6K z>zuBh&saThLKnH7PvTKbg!|C9CjzGnBdE;E3iv)ch4@`#CnYfK2Ech;Y!Uyx<{xTl;HxklRP~MJ{F1em+x4#sVpv5!Cor4 zZ0dtsu68bk1n+m!m@6k}{}c>;HAKrLdSNF=n~=MEi|qsT_3HaakkyM4zz*Qay;ue@bBUj_No z9(Q|cLcZ>H`+PNN$(QFSa=9(X&k3pYt;Thq2^r+#%AF>GPKc~9?|swkD;*@?`u0U* zm%PD7o^d;_r_KgNL}=S8AR)8E*Yo*lyE(fcx)m#z#yN18BTVjUc$vzDO0W&z+{6O= zqxN1bxfxM`Tm=GnczPmnoy;{S_V@kK zB&`!O8&cdZ7Y!KTYfN^T5oX^GqQOzC?mT&IU~bzXCmYhuxj9|QkvN_xCd&-zChDnU^ZEQ%s@+QPFf*2}JajS8U%cmQpVs@t?MN@kW(s^6 zCCv&?O%Q;V5uENs8N14Q=?)g!s9@;+-3KDRsiw82{4@{lIl?4xlmv<*FLDe7}qIRT^WJ zl89YAB5ht216Db8c|1+YxWat3@V1%K4R{buP5ks<_aYUp&_1|j{L=b2bMU(or!x>z zA$!|fzkjjW&IAh{FQ)p&b#u{pcI9cV`65fFZ&I159Vo(67L zC4;ZNCQQ%oB`q|)X@jl6tr@kcrEsgecd`FRA*>p6-n^Us33&>yz~=+9c^BXM6d`TtxMk$FBg$@x8q ztfBXM8pv3u$CsQ$WQ|V*8MGRw+x+10n$zlpfgd)TlIY-LAUC~QRS>BWa zRfOfvyT`UZZzhrHK42&hFiJEpA!YluL0t4Oe5$~=6jU^*)b#H%!GKE>$G61Que{Eu z2O-yII*9vsk!CtnaPb}#Iwp4MaL?P7$uef3gi&-Ulc)%gEx?UnBK@qvwVVJgW{Ot| zgz32n5QZVtFXUAP>pgBx-MQxF*_xYLKH6orj^4OtmkaG#PJsW$;db3H_#R&~FoG6! zCZ<8Y$3dnChY{n`#Tiw{Bal~YKMxUGpVMmuEdIu6!u+fOhV5wx1~Rw<8OTW6zjE@r z7dZyjR}|nawa+sJdM<|S2ZZYU*iQ)6DcO$*UHh@05xQ2g&lBrVOO%B2x;iVaQw}I{ z0674M5E31T$AAFhO9Nbh26L`Uha${IVR~fCV>;M%sda%|*lKdj4Fxk8*Rnzw3J4^m z0{Q^V+u#segDpE0qc;k%s3z%=^XA>3y&hJd&SsY^Ol|U8tMQMjPl zPsqW^kc3X?7$)BRBx3#q*|zW)koSSML1__NsKptq7a74=cg~{l_jiloIJ!}nAgGH2 zTOBctZ&%#FiR4`=?9W4Bv-0VT+p8x1iIaQ0$g#g(*Zzz&^UVCG_1x4^?*GlysqB=sR;XQh<;v z;JC#6H|I72gIQX8Hu{f0c0~YPD^>)t>g4Xu$plxup6@)l`%9L8KiFE{U42;4HFpDJ zw5^2v4<;(!b(-G6w=3Yz#Otb>(ufKqMY&zCL)-nvozpejUJn^EsPIAA(@3we@~X{p!E5a})KheFOLD?I6QbrND> zG9p)2iva!A)PjRIx(Kl@Ko=Vk1|kjA_*-j%_Hv__+Ow%>XJK4%kfhqm(!4Ok~&X^ed8qo3}UwA%7!i@+h`G&U6xJi=SdBoQy;Ua?JWA*THF`9zF^DxR@MUTt<_Y^TF*?CL8Xzc*8r(o<{Ql-u+VF(s9Ex^~ zZV>?Ux!uqGV9EL)8EXhFAJvg7`-gv{wLs2mq?qY@bEv%qz3u^cn=m4uv8Xw=D3&tR z^*}Q?ZA+A4m7JdnK5fo82g~~pE6p~wkUpBIBUgWH`YqZhY{Cdp_pwO~CVQSXDHvjw za0e3u&INx5NIsmfyeXVWt3JzX%jOJd z_1iEt2>FU-_*;u&JUx(|QL+4cok_OSFQ0by*=sr!2P?py7Of?M!9-^BfL^UKuX;KC z)$6r?(0O@F#Fln338`6#lXw{ibQ>A!)sOn-^K$mdy3HAAZLi|K7O^Wknq2jFu4TDg z?_5iAo!+^=UPlQHD*oTQdf=m76|hzuP1SAUK$qE8Jdls&iTnGgrN#pDKw24K3I3%6 z6b*aGgsoPW~dyS!mk`Cp!1uRP1nnWuauEdI!dotZ^=g&>du zJD5RHYqZbb7DBvMB`@S=!S5#r&Ohi9LXVJY6X~!{62h0DZNa71ZA=luV`1=vf9ZjM z5r}2Q&i3_*kF4{!HOzwqz*~BX7J`#mr>6s2C#opdD@zT{2EiOqYF@s1obUogbng{aUZi!H&Q6-f{WbbOkQlPkzz+3yiFo zw?%|^2!c%+1`7scIS16PILrc(c;^X}D!mu;z8XkR@o*bmzJAFfS>KOB&@`%ywekUB zJd6YGEg0V*!Y2elw3L+v0{{TGE6(0a)Yo|;B0C(YVF2`-MVG%>Ncz|bJYiSUFn_1+ z0Rhar7hvA8SU?tXJX3=@Yx_IIV3JAuJ5D%5y$T!=3cpf61B({QnUSu?m!reWCmuKR z2)8+S8|YG7=BaLo8eBMy*IGbWtN@1C&|f*U&TCW$mI{q69Uvcs{LM^Kf9q?$qEH9`BHTd#R?U(8>+}7>Z+32uPOe{&?d<*6 z_wAg`2Hw=|bEMg>m7y%1nCnUya2i`$@46vm+-1b^Hx%8G$TC*VyhUq=;F5o7-7l!2 zp49|VsOxF-37|Pfl;i7#Sk#d@LNnMh&iTU2e3lVE1NIankTTeok%Q3I-j)YUBrVrz zM=pFDv1Oc2bvsK&sxD7Cxtr&yF>t0%o%38ksSvACLFyR+pXr8}6eB#-Pch(hc}Yw$ zxZB%Nz8qIJTl1tQcv%&^2#)sODt%0PT~K8hN(8)#^g@h_ap98d0Nf+5xD7M`+))Oa zcLr-8p^5iZ;U39Ke!FMjXN{#Hbhnf-$C) z9OS+BHa6k?gc+L0Kn%llD)d#_Q}ljKdBz&V-*u_CY8hCU61fx2^}VSh3xM+UR;l;{ zJJispAiiP^baUnGZ^^D4_JgR%tM`S)nN|Gbf?>i`VCbbQCB-X27Lf4N8u_4&4O$KV z(7MnYDBf7!vIa4pCPqS|m(z9U-Qt&m@ z{_WpT`5_?mI-UVEDlR}BhG4G_5*PgVm)>OiNmVlu)#boUbRgq*K@OfMIM2G$O)#`$p36^i5vArj5F~G zv;+feYr=vnXY?8W&p=HiQUU&!BTn9yd`AR4U<7b-n5!cOM(KA`JdCc;|7e!N(xXl= z-K8&bHhwovnyuwx*v-w<7V~c!1XsQ`VCa7@iHrTKS&duD4GhcmI_%bG?5QUmF|>EC zIk`#iTnlm+-nr)GHoS8!%DsK(ikur9c4z(jtvxGH1puene^2@!qXPLK0Zzpv)vpPG zdIGcn4gbv$P#;hLC|rv(#@H))x7VLY%U+q}y_Wxf57!f)@BU1jseMC~p{>Nn{{Msg z|1J6d!hshf@zud`=@3xk%d$Y_+P&N)&!V#|IHp#p+T=&W;8Yj?|U-m!sE0lOv&H?&+Ay=v?)$$ z;j}4Fx#0-FVQAXs)r|N!y-eH!7W*Gn{MXR7&W=2m4vtdClb`>OI{p_&eWq7FW=z%& zjy(H-LjSmpAN*=yi5lGhW;lI( zmhi*R?Yh{_Ef~#Qt}L$Xu57NHuB@&cuJ2vB9vVOV9mT>41N3+7dF6bwf45)rRAqwt zM4g&4wwZqM8si=_@%AzNlm0aU9)(iv-}J^&!whnENm>B98lbxY5GcYw_5ZN20@B^m@16mybME_n z{_p$Y`S3g+^z7Mt?ceWOYhA1MY|jAKljht4kqVeN52i&-(m7X`12-55BUeFcgOESn zdPsXGJDsmh+X|uZ`6?X-!s35y1P+WGnf{8@@8|a7FX(HM{(X`2vj~gPGz%so;kYY9 z627xm{=yHKZxNJaat0r`r=21SpT4^N&6#0;+T>KbMG&C(QV%q6R(ge_z<$qDac)Io zZfx$|T+dwF+~C}YxxTs1xzV{PG~_CSzoY$EeYD0GylQZ1KDY&H00w0b`UBZA>nUF2 zGvEI-+hjmREylW7Kf-0F*5wB{a_anT{GX0MvI20zpQ|A4f$-%kVAnrf^lOpdVVqj{ z%r1Xubk076ktP$nR+Ob}BWe@QocPQB#YsrKfO0Xyj39t5rGFb2LF`lIsstTlCpp@* zTO3(O#s8~q4Suobr{;eINXfvznB>f#XWIO}#^1(Wl|#DlcM%{akOV)CHh>6<2!)w{ zH`ZUlcp9p|ko+ww)Kja32*dv@k?u0b+D_+8+z(p4xmfFU7Ivpmk5mS5BK;7M6QG0u zZT~=fnhQ>2g+0iBrT2DqdsWvoGv??h#we*UkuZrcu`p>pQ9VgLaXqPr*6Vf+i^vhE zR#v+D_)+BV&OP-dGDDow&GZjN7C}ac7(2@kr#km8oyPJ{8vJHo5r-Hagp1*L+JA5K zD-Zy#lma;+?!R$G1rg1izX#bLsDb=tid0CbM+M_7HU5@5klY8%Yl%pdFyNEGhl5`s z@iRC1NZC5)3iU*eWDNe9hkr|ilPR_Nh@EEb2z^(qd{#mzf+<3hf|EjYf^|a1g2zHc zSU*iO7o1wx#JL9q`I)PK2jrZENODjhQ~s3+ep&c5Q>y-|2ER}s?=f2cr2Q3M$Tc`zPy=C4-`-T>#-nFp#GcCj$!3 z%g^sBVUI$QCFB-xha9qA?FMb*p9SjK#zGD;j;B7z!&&>g+WnFdL8b+z|5(prywVPk zkpislaGKfF<$spQ(_nevJb&s0fa08pZ2PDBr}b$ky8|d#^M7#s_pDY5kj4WE7)aW4 z`0`}{M}MnBXX&U`2@#Sqm1oZUb0Z{Au}3rH?P6>bIRGGu2877s@~fu*1sKU1pho=D zqkzZv|I!sQF`$?b% zu+zF&yLPZkDqt+cwyB8wfd79c7tip?YM5y0)Yg9CFwLiA&snea+ee#?UI#}pUcz2` zv!a*wcH&R8#*csO6?&bl9>t7{cDSypSpDU9ejkX8O4@kV?G{b#fx>x4@xvQa$C z1OS6u3VslSa-I22PuKdR&Yr~tkV+8N0zxN#Uix3N7NS@hsvQOcpobpH2X3E*<`7Vv z@GKDk&r_8D3Ww8&ZlENjc5VSJ_Me~;CIE^p2m<7#VkS=sAiG&+(*Ir=PHXO2#Y2G4 zJh%c1UDT=x`ZOy2ukE0AP5YTePd-bZ!~Z)E0uDd7#E^DbY!c9#{)*82te+JW(U>F6 z3giSMH$-wqrha4_`zy2lrQ>OJIIq*c><=Vy1TsKrp3lgl|FaQA?0s6)|3vkBD*O-I z0c=3@v_NBWZu#?u^-m8WQtUq~Auv=Nd{{pEaqh>zrSh|o@H-F;l-MVHv zSn8*j4G90ogg>uXKp8vbJJRaIz<4FpGpxBq3~Yp;)wu(Ir}X*c6ZG|ym%x=@0r7iq zAaV{RKomR+~Z-H?d3x|+oPiA{ylB8e)9cv8oK!=h5nC3i`4MvG!A?dk;%t1D({l|Uo8#}{1^Y8 z+X^wu|0n;RMJgib0jER5fQ1g$iGg%}mRWu=0gyZ!@BhdwzdPl(0qOL?0HE9~a#ron z_&KH{+aqMuygJKch&fD|T@9n$^)@dCs3<4U`M%KT|3t}=rRM}JC{z~ru z6Kf;6?wke36K>Nk^Go_Izn@pu^PrhLeHs8j`o;dg06|6)YaZHK)FiKoh5fhMiI~Ix zPD_8V?p!hT@rBb0_A|tOpF{xIz@sXJOa6?opU>5R^mEE=L~h~vyos1Z{>3Xl*D*#s z>_R>ZXk-P{KCb!l+at8!Q%N`SX$xXkM4R-BE&qeETHJ7O8b}CGzlt}4N=W~mg(M($ zs@=~EzuO!T0y2q|t=4R>w$F;({ap!ci7*LyiEarti9!i$iB$>8n{yl1TmS4-&b|6G z*Zo<>SI%MlA$OLSfo>UTfPX=a5dXc&`eo6dH45pgvmOPJCjabCbZ-Ji_0nEIJeI?F z`A4cinEHQb7kOS>5tjOVLq?w6*=i&_C<>A8p}Tm-P43SfDZcL+reJ{MBjx z!<4|dc>c)iw9`DU0iLb>ScJ&`X>vrQ|JJ^oN5_9C(7&g-zZ!Rhc7MP}JfM|#07lGz zl%8`l{|qdka=HMIc-8EklsxOZd~1nDiU0Ls*H!0g^4iHwjYGG@2*e|fpVQ>|6o(vA zfe~#P*&bK7_si%mh4BDmI(EeQjP}PU_e(D3bTmecAHcXq{|GSwY6C;Y*{te>?2Uk_ zHbVxO`jU~;@SoErFhC-}83XI@xy>WC%R-h`09prP733V;FTP^;46Yl4Y+R>VD<7$L z>)u2R*1$CQ=LFjU4CEuB+Uwx;om$Jnu34{>oddQLx8sd&;GMpM-SLgf3!?p%qMpZ# z<0tMX)0N%2o_^XM&igxTqKC`Wx{W70J7N9pCxbzjt6fI*C89b!$Mm{`l&d4h zr8kFGt2Ow7eLwLfJK5 zflgE7#pgB5dm_1uJ!^eXvHSgaxUx)A6u7oC`nBii{oZgxHy={Qc|ZawGuAtIJaK3_ zUKTszbr9V$H;a&oWkbqT7KwMJIgLnk;DusFoZ^OH|aeA_ZGYz8?b%T|WrhtVjmA9RWHDx*~O2)<1QuJ1s&G zu^A5*U7;wj@o;7PsgotvPYq8)j=Zd=Nhe?}1e09ocCin_>=7cXOfPg0=ZwFcuEu(*rLiKy z&Xqn#ttB2CtS(0~176I-S#MGiCoL#z0#*QLlz5;at>3PKP@))+wM#rY)@(X9ymAnB zYe_V^=tTYh$A`ni)*CyNGC%f^YprckA~2lp^Uw1Wvwv-OCVzgu`}Ef2zY+a;UKFVX zV)e7F&g9R|d!A}`2J9D_KhK{5{-ylCDgpp|G~iWMbYh}^($jRD=9_$a)Qvp%kE=(L zR}aDncPLqw{<`h|$P2}ON3A3~l;#6o`2ZpQ?}z_SHt2bOoaTQd2_yoF9ZKOPQMUoF zt)i1TfR6w7!hbbMznVU36M6|2l@^ueySL~i2D<(YTRx)_Vd-7$GS41@v4yP-V8=mYP9k-5q9ZsB}qM)3dpdkLT2wTN` zeix@%cY5IRM-Cbsc?@a}jOR(;;3{ETJL>(Zm8&IQlncWhVNfHU<#6+kVoP_&)OP`X z{Ez4T8C$^b&7!|^zVQ4ZAjh*#*$@&r`Z3M=N%X!SS)lN;hRXMJ25#niZJlYCB>Aha z+F7>=qt)lw8dp^msIjQ(e|5MKI{39y^XlG9*1P1=J~fr*pI{%~-J7F!g{#e=Le~NZ zQt@b09(vOg@~GZ-GkAZS6~5j-2Y#|bD%Q4wM1KKALFU3me3VNl7{F(0lzUCuk$m|m zC`mOJQHX#uE*5Og)^_IhCQzt@Jsa{rJghF3775Cl=EHaJJt>z&iRxQR$XjI}CUB6z zF-e1q+e>NMi(fo;jj%IZYFw3SNDuGziyM%P?sDeuwT<4T2R*;=*)K2it}Ri@Q*Py` zx+OuGBr`FD+tJ{>Jg`A;j(C*}~BqTb=kybJtOgV5p>?#O1JTqst) zGFZl7LdCk+l$$o=vh=e^26z!&-97RL1=bS^Djz_aOf@n2#pD4-&(+tg&Bo%M$@Xf_ z(e>1N2&RB5?iNoxA1pyAI*&n`+<)r8mL378o5> zn@_Zl(b(>!(0+D2;_Yb$eO-DximHb`MLXDUqHp=*IjNw>si5!U&+1N@5K`AY+9%xqFxVqRdRetxR~<_E3WrtL zSJg?jM$v56F8Qtyn$G)+X$9J7XcKR14jmIZUw=MvVL3q)aKU#Ip%A0=F!%a=uZ^+f z=FYu<@wzhZClaQwGWDoro|ft!6@(@ekAEeM){kBZQL#&Sc4Uhc9W%?#i7!A}=clB` zq=I&Ff>>&$LBZsq-NyPr0L!J4dv%hIdp5x$lm^LOH@l2Xc^XM&>t1-{ZSuVkX7xK- z(rUzzaz|;##p#+I)IN;HCt8QB$$zGeqzg{_u!R+*P}O>G$+ncMqr`Jqw|IeZo@d%% zM@4!GdqNaRE#zPM9-7wLt;I9$PY?aEE@6;;d)QQNO-IoFRJv!9f<9W()`;TLg(k^N zOVssgDLd9z9bU-`xeE&gGP-5W{(O_UxeafQ%{*#rYxbuq$3=ze+;_HX3q|*SbjqI$ z)VaDM=!q}xyO$gqK6rVaY{&asckx(LGj{d&SQ%39;WA&yFaz;#BQkaEiU+CByMlIgTX6X>=uN1YApK(r>NfRl7F_tf+hP zW35y2OH({K&(_j$`%SjS{n1M&Z%-^p-1@T$J$Gw$PZoIT#^xYDy5*}sMGqZi>FQWp zHx4{;@H(04%PaIc?p}5lZ9JZzXgxS6Qt4b+N%nGedkL1FA)oqU`B{6eWv0^0eYdp} zTDuh=!zOajv9(5VEq=7dwYu7Mj~)jY9+w|TG7*q+VYD6{CePlizkLtOImeH((e>!f zo5{FVk2R7Kk_P+XMlS3})0tiJ!TzxB!oh38!j@m3t$ulxZY+C&$T7`xvm}kIPU%UH zt3o$X2`01G-oj4%CXa-a#p`F-yfUVkrscDqD$?8+=5k`^CAej6Oudu)=~CyJ%__7* z+BAow1yXb3xTlEYg!F`o=B?wNX0T;QGsu>*n6ScK@E57Mzw#MC*Mjlg;)fUMO#PHc zyYSvWSt+^P6+Bh#VPj00U?g%oYc%pRVMEHiW(hR;P1de;BcOKHY~yhscA;mr*Y@YI z@rL7-<1F2=qr-N=DTwE8s|nb!bx8bmm3oWr=#k+QMbtF1)eXRX+I zP$4*xXuhuyRmu}pHA|89N;-2-b)`NTgJ7?dW`2yg?g>dQti^~CW7XONKmB1t8gSg(b^3rk@llub)p9Igt? zT+KtWwvQwl(^MPbBv`;H7YX=vn(}_>67O$TykufY(vwt6-hv0;xY$=Kp&R=B2MRh8 z3VxJ^lya|?sEOe-{U02oW$z6VjWZbfY((v?L)0wE-m$c)-itNT!GrT{Gs7z56a6}z zP@o0PcU?*ERYN)zGUr$MEaLEoG2sYo&+ID18PaU8!lg^EOlt$srnR4OY>PiLqgUYR z6mQ3byGn(W-;KT0Ekz8^sh5jL=@_-T%im4+tOV(R+cWjgHY%{EmoeZ0Tu;^>$uQDA zaJ42REwR9axBQSG{w!~~8NZ{UUAca-l1|eX8s{d_UVX!RTH9wD z%xxGua8HG3(gUMv&4`k178fih>b>9N21 zn3}o-_i(}W=u#E~;t)-Bxj0#7%7u3*VicIsIc%6Jm*16`vOZE(?|NXCkKT^(pt{_$ zV?;1?#py!3>+LJi%cl-p$BN$dU|y9}Z+LQzIqN=0bZ656;5>b#^O{N~db$^CmRnHT zRP|#sb@1BxcA2BG(aS99L%b%mxN!a`g7hY7-58e(aoLLgvrkh(U(@0HrvhtB0|eXJhHqD-e0}b8|DV zy2w`X6C!=$+xz}rF#w<1jk;$A+B1tRf~{ff`h!+G|FqH6%zeWdzPB7|21QSTi?ni# zm_Hw41KSq`10hY$Y^>SLK~h~DiJ z9&^R}&Y0uMy&F^?H!*K2o#^dW-fp2BDX}3)HAUmW4dMJmvu|LZ^U|LEE|;1Cjt4Gv z4W#qMZG4{>4cRy$2uNbanqpiel{kr9@h=(xE7`be;K+I?4%Fa_A*nQnpc0NOf=Y7; zD!l-xgu|jFO|_gfQca%~yJxN7(IdJ20jDnv&rZx%7$48zYeHcRbHe@d;)b5DK4$N8 zlLO>%79HA~b|tn;Keu-g@_;)pskl{C=NeyweHv?IB~X6a;%~J3i0L-p?9kCye6Wcz zBU9`p?$=tx;C0+^jlzH_CSf$T0*uz)%jnrmKDJ*Jil$yZ$iaG!@=EvRa3m@x`UBqT z9Jz2Rt(xKccRGidt~k51;(-kJyM*~WJGL?3QHU+jyVx+ z&7i|NeeFhA6%p&vL*BPypNnmg6*fWW>-+IhC$hi&ezq%L5_wtk9mu6O& zzk7RonwYTx=th$16sNerWhkjnPUpO##rr!d7nUeEulC=qE^WPLxLWb*b7?2UH!=ls z6Yl9vYzX-WdY@YTg?DOi;;i&0yjVN7S_RmYO4k1`YnjOqq7pA)iIfDy^_2s&GWC(uvg0&eA zj-X}h3Ou##)%!SbS1&#$5W{A)4F+^jy(=2aV02Vf=WSvRyGyan+ndn~DGzbk6b&Px z0HR_fq820~L*iT4rjJ`nI+D?#H`k{fD07S#5h%(O+P1Pe11v;N0vP2@PKq4AOBC0$^ z^zP6NA^W{E7pLDC4me(2y2Ke%bg4ZN%ZNy)vN0jaGMaJa zYE+H-PHnr%RI$ZQwEZ@9^yZ31a`lIuKvt}2Ve!bIhMXa1^G2H3 z6BfsTC~e&a!g;c2%P%oJ#>|3&+LdpYSqg&>pQA2Wu%vxiy{~O?4(I@m0OS;f1k`{8 z^yV7?DCHCo{ZBwL63T_QmFi@^3_R8-BC}%fmT0jnO1TDUDj8OgxMJv9l(IBg?;`ir ze1LV*+-S(0*?A}O^T4&@gh_~qkheIw6V#qYiw&=sZPsCl>5a)yHb5x#iV0v!wPKjn zO9*8%O>`A%Y&U?t&7P3zIC)_90PMA+}glL+tRu6fW)bq8nn(sVW#cb?-TlJxCo zrVv()$mfF3=mv;&HVHk50(K@$^ULaYu&jzm*b=U8L|-_;lG7~QF5Z9=bWyB777_Y|9rI|7>@>!dBDrSF-w zQ^t|ofzC7QuZI%xkwHbM^Qn=ZrUNWagavlEwJAY&L*9y~&&FF4T#T8aWZcyj%jqFs z4Au7GVeqeYXGODw=XZI0VtpPJ$C}FM)9nTbfY_XHhwZs_zR^^W-JyRlt98-jyN_%G zp7Q+m1!_&NrLl{_`t+;6Q$OKqZp2C%g+nq6e25gxaYE#Of` z7$;4Tg#ux{uHc{6(>}Kz^(w-8@5PzT>TbNvdt%iqizSEIA|ul5{2ZLECB}VNfo}`A zR{P?m8EI}FZ>7Zf+-q0AJd-A{R8@+Zl{GT4#bx~*@AvM`R~}wRo8Bia;zHopW2(1| zOP{&XB<`maI})3EJg<0zm8^zk(`F({B{{4=N25S%gFC-xWL{DZuumLdANAINIKV#q z`dOM!nN=@FE-%xl=giaO-v9B~4G`EMVMW`ho=0i4jOvlC$$6(;QnM#Vca!>==M~Pr zwP8pzU_fVFqBVM``b|aSPmJ$-?EqM$^5Z2su5s^zh4VzdU(10$=vrf#@YIYl?({nd zaOk2Quo1QF3X1Ha{lZf83|*^j*JLKE zt{2Nd6x6%-+%Kw{x%uSch>VW`0(E|p13Bwpmx3GbrFprdW$gIIuP~<2U?FkQz7E~R zAmV)`gtpr>6#s7NxWMMh)MG!m(}!y&O98tnl2WpiZa$I$B+X>y5siHkSb+{*v;*1q zEW0S)CABNE6ir-V)|$p;^`k)LMhgp1vaY!8NXED;d>>$)Z z6wjjKC{h5{wE_a5!U^0Rz^O@jTXwy&As-?Px)3fEx{q+_I!5-CFq$9b?Xb6}Awlsj zBQcWrk*7qsoPeDs>yx6!BoMy?n$G1%I}eXOS*KsWe$=z_k@K& zvam~g#73#*n>?G9$oPoIewO>4YOmw9mG*d1kA|bA&i7s(%G6Ce=z+fS8%IaG*j@*F z6Idg-5y903?nJpK7=kC1q&EKZ1d_WhWr9U_W8lrjx5mZD)xSDX^>Oz+n~MwQ$h?Cx zPyQB*aaHF;fmMOs9u(5NXzk@gsykA9yfnRhVzSF8J@Ng>b;zylX0#YyXclibeHAKn zzOF~K(Z#72HF48$QsaoXxu*5#37#IKRYl^0wUy1s-jj^-5YMA1yGNQUA*fA+cl&ep zcYUAaA+|=W_#+(gPfhQ zkq2=CeRQ^lRHDgCPT-;JZ}TZS!Az*+I4UoXV};+0MGA+gURhI>_~d3cl=Tg(s^khQ z-iKlA5K-(MP2ksKu%q2zzAuNSvQ&ANB2B8|HW>VyE4Fc2YJ=QZdaL{J-K8GJe>Mvg zUdJ>AU?ZWp zs638_*JOH(TUBX)*OQDXL3MJPAa<~pv&yV0GEHtiksaQr)UR~+55zegU>-}sl{bBaiU}H)S74fXEN0nLebF4_B6{T? zzTmy7@Y&ASwp{mhRMmvL?DY|D`i+?3+XUK_iwkcz<}L?Seh!|uA66)=fUWp3QEB9> zX@2?aB->G9d3D})*g{3yto&9bn~r50qx^%5Z#}ZU1`sVRY2i#1C8|t?D0@tvW zHS$Cb5EM7d^SV%`s`(UmTTL^%?BUqJ4e7&l9ZUUDvvS|$fxhTNJ}paW`lcFpQn4T- zHO)J+(>CS4nqRamuaHcuYU(j(@qjpPT_aT~tQe4}?juw#%469JneU699(z;qDXqmU z=wa}TS-YL6x+Si!OL;~vwYnwhyk5Du>BT%2D9?iM_!eXTn+mA_qw){1DueP2R={A= z^(uKR=+!&B&+;p5+(%b0XWsFl-G9IE(d?@H;kSOQHx+m4p7W%;2B@gd$~WeJoW99C zaAU(PD6#5sqMD{jXf*|(XcC>y1>QVcWsmW8GZ|O*0w2JiMVDQ1P`%S^0aR}=RlO=5b_oi$cd2e*nr zRcTs5wt;8)%_Ox6x3?c%l%fVpNi@~`a z5}nz-d0MU6>0sZCX9r*MPJWBdk3S_xjvp`DR3SF0Abui~`yBzL&tMD~8eO$iksM^JMz`gsH? z%F-S71~Y=klbv#VuaYlwEmPbQ#*L;4hG){>m?ujsnGY!A=g3X$ypd0$hj+Ee1}kmh z`-*>$WAyhV1y}{ZN)AqY*A;!wLoxKV~9xL;sd#OT#b7N~M%T0H0btcXvuI2YX z6tAdPHVj{DHTC<{%gG34|4u3s?W^cpeUP%$k^Ow+i0YQawB2r+53!1bj7)@;oHgoZXuPByO>w}uIEqHiecCjkVt+8&UFhZZ0~hUm@wI9<9JyO{$LrKbB@=lU-_qm= zh=-1*lzOl9>XpS5;VW}snH4Iw5inLehYTdH5HJoiabLRPl@KMnpI3a3c+f6NRh3A^ z#TOHnNUUPxizyYLSk0uY&=j2OYzS0ur}wkw`$nTJN$KZWu^Jx#bb5+$-4DC|PV> zF5d`Ll%`gdBqESMe9P8bK#A}}NA@qm3%UKj5nju#fLO&LmVh&NLRPg_Qra^h?qBDGlQE3uWLL~-=Gxv+; zhipu{zDf$ApgW8ds7!@KQTPUqK8owjm3A6wld)uF&xlo$(pEL^8!0Fs#CSB@=s#sg**FAzcew*1q=mt6 zUj-i0WR$c$FXvZebf11|_O$b$wTT;+Yo9{(ZCIP(Rg$HX%5y#C1qh>83e}Jc7|M#@ z(dQ3i9KZT13O~b4hvCJLFGPQp1eWWb^36)oFdXHhv{&&Z`JB1*1fcIH1QX~mU_gz* z1X>IjkW}TB`}bgXG8S|h7&fyM7~|o)Rz{)R3^ zbyPg-vb9C~a@c&DAS2>_ey9Rt(hpTuSfH`pr%Rd2uAvRqS7IT90WzNaN{n%a1^)MQ zHt5z#q;hP4vU@dyk*y^v97OQGK|JR+E7Kfbw9Wv?Ak!l;dhH$qysQ!%tc-<`MNF4>uNDL-wSd~Ia-~TzM<(a6zQAM( z6jj~NtwssSeIjhG3W4Ri7BZRL1pC&TE99=!7u3E1Cat@25uw~JVDT%x9)@it3b|`K zY7Bx(x!-iu!f#~Q?bf9FfK*O&)M7<_A%k0U&Ybr7_j2eU+#NPA(t3rLofVZBuLr$h z0O~FbsJkE)c%ncmA_IYe3?!8UWFRn*ffNxL2n=K(*&HAPW!y)X$r%XLy_QMbygMg% zpiR|orjUE1DVX6QG1{V*oBHIpvT^YlE%pqc2r~dh7zPw!7*K>|bATc&nUgN|AO|SI z3_uZnm;)5y491Url4`~ z*g>cut;l$-zrl4ciwjl7Q`@t^i?-wQoVnMIUfX6XBbeO z!9aC}E!aJW+$%K(5j0d%XG{`ugH%2N)F%lEWKgM9i zE;}Y=k?ltQmpGsh{%>(0;?Z;Cu51mQ_&5dB2NitQG`&`(>rvl*S%I-8_+rF#hWnG{ zBavF>#Ni*My9XxrxlKAhZVBX|-mW`}_BCf95Lc-bF(Oj2Wa#TNQq!Klz;%zcHZ<*X z^`&JyzHg5dbHOjuK7+CaQHgr{uB;dT4AOfuTs2dqzmYo~K>8u%c{p%ltBRV3Gaq$}J0e0*g z|52O!rvuE+9B^Onzl8))lwk{SrE~kk7R96^BQ2og1Day0x1Y5b_$ zlH$Fp3b{2tuOJy?j9`^;bKxKbMytY2AzuihDl;IfGQ>duQI#L&oL1!wpbZsr%RFsE zA;>lqf^0*<$Tn07(S|}~*RW-C3Wfj#QaKCp-6BsReY|1I9XEQnS!HG!qU!e_#^Ys_ zr~%*Mr78#29|ULQl{oIQiE7>{87j&}Zz|p1Hh%qe^yq?Xkt({pcfx3tncR@<#3*j% za~iOOnX=Ln=7-Ma(LtVdrUerwN8XmFyu^fJOKR_5uBltypGq<>`lw=}oJSB1Wg=F~ zqnWQY#dz~dop5I?=#|lQN|5b-Y)4Ls1JqioHa^xFD=Es1lJ4X?)d1nR?iVPN0!8a~ z@3iq2c>Sde3Ox6nxbb7|muUEpMB6Lp$U`Ha+T{&t-0c>|c7QQqnSUvIVed$y8d)Gz z(t9WQ3VytmsageRt@qjh{e=wUHx{osREFm7cKh$$6;FGKQk5l? zThvQpjUCM5Jkidzn~}H6?7c95OpDe89LGy)M zm7~$o#9EW3BbJQ60fOzM|g$sEe@L#%epWlSh4xI`Oa8w7J?Qy#q6;l)jMCA!a-@r!*(j9prw zDaW8{I&)ZF`ArC+RxVmOCrGBVBHH)8-L7VOhjt!KX+E)gj|19~HFo;WA}- zZhdUt5pG1e{A2Uh=1DtJrZBXVfs&-G@Dc`n_l-vcpvZoG8BjVic<_40$57fThePL2 zp%393&E<^mIecK~ro$;%_uSZJUzC*1zw}pd+Ob-b3CDd@Jv+ z=_0H(N-iD$?x?z>2O&QfiPY?;y3e=Dk!+REdPaZvK!uC|-Iw>2~uL zcu>o3cO;hw_`Eu1rY;4axlvc^w-;4%=YxAiDHHTwgtNkj!Vx>qq=@D({k@zoE}M>} zJniY^_ZC|<{bqLy7et!nCVy*74gRQY?48{0@s z!}pTvRK?+w>8r1mr8HpMU8Fhhu3!i4}4igc)+)MT+vq* z{$#_M%-bv@|K*Wz6g3m{Xls@8@I!cs+_CdoyLVKHMA&B-In8 zX5O&Q$Nuto263>?Y5(pwW|1Ya*Vf1J8+n<{+x?+NY zdRyoVRbFy{TB0F0Qcc!*qGC-6mh9m2X?8~sG;{ZT(a*21QHf;EDJ9YGEInQ zWgR)NDTjQOqDs!ig|w{X7DIU6>s|vbriWi{6rzDTUf;u}g7V8U6~G4RHVy*l3RF0* z#Ea>~k&QGD4?4>o5n##dx@WdJvIZ|pz? z1tAkK{P zpY(;HyH4Nhcp=wW;oJYdPZJc$uOb!O&MeBg`Y1i0F5Bv5$vvw*@mn$eFCEhJU+ReD z@kk9me7?t3m?=G|6}WdwbdGT((R({;{ahi0x8u5To`e!`g22>A-;$BxdE)?k{iW3k5qD4*CWvIvCIq^k|s7bYG%8`+;LrIFx90Rs$g z*X@0u8mhSAY9^@zx?0+O%5C6*FTm}KTS#sb∓u>2}I(Z;>c!fTcd3evL$suWk3S zJzd4%3tU@>ypq}99I(Xkb=#8$+kzU3_*N3IwCkMsW$9R1u~T*jcm_av*!(+nW>YVh zivU~pc&ijaW;T12XeXmMx{5-XpaZJ)kmzPvNVMfk*mg;4Shx7uuf>MGuCE0 zbB9XuGBfCENuRe_7_3d%v=D}c_w@n6QB+B8gh>W7J?Uyb3>0OOksnn~F;o!;laA&2 zbn+grKhKC8?TEdtCJ@9_Re?#qxa^AVcTAM=4$Ji~r&)oA-4je*~vK z({;h~6RG@h{*Cpxw`HTXm$-vvLLU*lnQ&cn;SSp>*c2qH$5U*Uemmr5G!RM{*$g}u z$s}5H56gN`OYx+wC*C^#t>7B%S0(vY<@da>#NokKuOB?F7k$$kM;Z>3*#wN^G^}hM z$nzd7L}RF0Tu3X(X}TcFbEgPyx)YQ6L%N$IZc)5AIEKMT)D7mUqR17t7%_?Q>?l>@ z_R-2jEp4vV{3;3g^*|E2uR{4|;g(nUeEMu2@pmwo*2ZMaD`7u4ls>e8yLx|(>@L|9 ziP*fuGjGvTe7vtqvJTw$n+Cp*ElJGa)Vm@D=7I-sovyzR%|j1 z#C4N8qUK0j!g?LS`LjwFE6O;ECh_c$weC;h|vHRNVSw zL#=*SkT&)};x+YSZVwW6Lb_|Ox4*;u*CPBs{diBs-Xh;vCvyRce^qf)+xq7H2YBH^ zb$WA+wV@t5qKfn)yJ3-DltFE_7Vhz0y6N^}pI(id*wZ}c`P{p{%BMxF=N&ZL$@&elV0NZq**5=-1J- ziL=FusqnqfN|cyw&}y=HqBTbJR9CR2wJo*2u+(JLlF;&H7r#WjxMqB*p~E{m;8ma; zCRY7K!zHrXrr7UY+C85;8^D>Jffrim!gPwYzY}#%=eG1Z)AiYfjur4E8Gr!DOoH& zV{fw*f8gY6{lQmlv+Kw@Qs3#z)XU#$Vn1PK?-XqHKn*(8*NA0R?c*3) zY`=v%4!m7@7YGK%TdYji$J+M^9$;VKHkR5V}NN z(-~fSq!aSc&N6`^#u8A4s408mv9@5#8pFje3S@>hglOLf*=ye8FyOWF@nOA;oM}il zEYnrMxXcr3+iw$`Kj;vQw_F@*YfLu9>J&`WKq}axJRW#oKfKGj zdiF5dVv(HoR#h-b5?NX^PR_lrq8a=K*(7pI-Jw0`bPx9WNG@VO2x6D(D1FL4#Kz$B zow&8inor`Zg+NQdj(TeqZ>TM$pv1M5Ao8h(Wg^S2?$5#IMWO70OL>4kqphJmUr+e^ zy`ntdEGGAcMXFqn(SnBb7)9aDCm5D#OqcNsO1QUWnLP_aN%*+Z=MbETbN6Cg5GpcW zq(cZUhxYiRmH_mUrP4D6zh`HB60d%j$7<9Z4^7CmVvEPUITFHjp zTBW3Cz}V$V?an!$TOedNq;_+RL%0$uf|rOq6!hTt=!0!>2>95$(OOL!U*ixOl1-&d z5NVXo6VVSDl25(kYk9Cl#2$RhDcHZluq^h6Nug2r@JE3bhMG*LU_~D+K?%*1*(Dyd zR&`^i=U!eXEAxYBjm^488#|-&q9ej}$Jdh+ERU;~8a=na$9oC8yBsV`NPZGHIlBG? zU-id)gWOVCWk4eEn$t~71A0rjmp!3uU$Jc1`SA7}qxBZ2i7(bWr=m+)JV#%fFw&*x zXo3u}7UyOJ;=j&np(g1oo23a^TL~AtXr`EVh+2_1an*bnB3YLGihEczk!{Q7Ded<< zxeUP}8AY9}>^7732hw)??}w(UqNvLZ<{YdlZr-9)cWnHCrL9Asl!?JE_94;Tj)eLd zuXABiLa1pxO6t3Uj+qq#^k*Tw&Km4vBOi{-+wZP3c&;jBQEDvn7vbwG^Bla8nicZz z6iMxDvsb^LL88ZNsqte>lCc-XX~#mE%;oxvjGR(SJ&;HD#IAYH+FScqqmN9*miRY} z^0H04-yP%~&)%BfEQu$o6q59c-+^FXew`c{23zm@k@1~YF|wy(gG@h8he1b3vP?Xv zP15eNW#@;U9bOZtTpPdI?svpnyHu#!*uL0$v^ZuNDlU2s1s>xsH7h(4xLX3 zL$*V2m&qGaBkwaU&Cp&|L#->_edRZ9DLnbUvq7Xf#LVOAfrlic5K7gcBTS+hrQ1C; zH4}Ag#Fp*|^IIn@Orum5t6<9pMQV>qFm^v#${}3XjAKX@C2W^ukIJ3+eu#n4$E5gW z@mP{AUJ|Gr!P8prCE!I^?~51Kx^zf)^naiihKUzkcJW}`(5u?ro~V}-f3!(zDTh+Y z3l6+K1HWVbfmsWEt&8FjiEgE@A2zQ)V@<@DeU#k;p2xaqgbyb zy!1q0n`zMaYJqlWQ{X?fHTl+`rtJ$VSu^P2DJ<;Wj<-4u-`+(Nzlc4kCFjJ4KHcT* zcnshgHjHpS2bP2z`U&UTHg5bjN}>D!+0vEx2hnnh4u}WISHA6da`wEV6(Rhle8TwD zdFOfWkD51BPpbHpi|x|CUalIyOp}N5&FH2S3GM|U>&X{!mt5>Gzt~~|UYGMKF(UmI zL~$JjBzY2tIY5=0))lfAY4UdBWJbhy?|j2?Bw%B;wS;H{uL ziRqKk=u09aWVx@{Ad449R*l0|P;5%$sY70%Chc;F$zBi&cyD6bTZl3?()uyZ@~QPU z;6#4qxQD`TK@b6?53zUeymmo#3IB@He9flP`&sI>wc|^E9XT85mHO2`jYT4YFqR|6 zn%mR<^~%ens82rj@;@EM&_g&;^07DoYHb&I;)}*-nd4h|H*@_1dHMb|W(2f>TL82K zbN2SlxIrqonr4t`UyYio70x6Metxv(fZEThes5v&(@QtcEs*ttDBLY-DtP}#yw@Rh;3>Omo3yOu<>~m2@{9?xV6F*dx-DFNzv&XkY0%_-4B!>MH#-V53 zUbhixqgHbUhTjfX*U!iXO%p{az5g4btivMd&?#y!i2L5(DIlJ0@X5Z`XxEOSkZQPw zz0}HY8<(2JkDfA^N<{*q8LzV`6|VEngCAmpr1_J_ZxiXbGPN>XEr^M2YfYF9=f3d& z!`iYA)rcDI#rj793;TbpHUdHVaKN~c#y62|xO~{_k~Sw>JC1hzpZFof9MJd?zxs@H zYeE!}{-o=4lo^0}{^nF{h6cG2uhS0c@Vn2e%e_U$w~J{O#bHSc2{Nlb@G4S@2i0MP z!x~a}c?(X6r~zWUj~l{gvIi1kA7d28~csK$Duxwt5-ePbS}XD91=ri^TL$R@ECzy(na{-_!e z5Q(__DhcJ=J%G|qC!AtExG~Hb?SZ!!{9gN&ZD@vdr>WVBPBYp=J_TP&DhxasZm1d^^Q!gT~sfPzFUx&XOHKV@rwiBM}_Vn7oXDoc%s1&Bi_g6 z3Q5vSycGrXt5za-sTTXTXV$G`slm#CHUDD1VoK_DS~`g|iVpI-{%f1XLfNmtb_J1# zjTZ1+^3vIm`A$0DNgmuzN=^$xmB-vzo&=u|0J(0sl{bcX&kIuIF|Mw*XEuO;mbf5Z z9sFt~vf}2&zG0pcxDTeSPzmQw>!3BeaAzj&r4~2DgSvUD$u>E1^oNkT3 zlP$}`d?VjLs#{{nC%YoByD2!|<%Y=+PS>}-%$T1Hy!X}lJ&Z5MC28PfpyyJ!OzeU4 z2I;~!bj1pe9Pd6LwDIz1`hW~#SdSX#MGP;E(l7PS25`@3`q@ivX+WFdAz6Jq z@atG6QPj!Qe`~a2Ui<;91)#@JZ@}j|&LqNJ9B=Tead(~v4-~X)GH!f_-cf02>hKYs zr*`siET`IWL&0H|U^Vh`VgitG!dRg`v&*76@9c}97gbO~uLlkNu!Vj0$t0QJg7v}& z&?l%CzoLjTU%{ptkOj+&&7s&i6j`;V@QWR-c( zuVbA=u@Ria_It-pk_D+wbl_ew1M0@Sgwroezjf3M`8#yY&U3i&Tsz|X2r@!HJ6r+y z`m+f1Z;oNOEC|@ROH*V;Mtm)~~OBvf7#S0$#$|*)t0I)x?S0#5so_ z!iPi_-WBsAKt<464*K4Oos@xS<9pBH-y}xdixxF%J!PqYwEmeYvh!;PMc3v;Nm#S39 zRXAO3QRQHyGh6eYyfQ0n+OB4Xb>N`6Fxx_9|IX$o%UUrktW)B5Kv5EE_uX zY(LT0@UOeXzOh>FJkO{pEq~QfdthwJ1kGhJA#LZkx6#vPe*2zVVCpU=0>`(yKR zdsSWemEB9y7!>=vAL%?>{4+0tu0eO|>~5n#dXAuLm1b3hXi-v)P4X1)w?-DU z0*wx6TMElhoabe(4gUsmsDshL@3sG-Sw8GUf&ZnLMcI^}SW$vYnCxlY*v zDa%zPA2Q)M$|)wY)$x17IUh1_^L6?>Qzl9xOkD(vrnE!i75pZ|!X}KIlfzIBOp?RO z7sffOQJ~CIOaf29I+|DGJg6)q=*EqE7u){UwjC$8CN|FhRJA~$n|wK^4L&EbedrUwy)D*`j^h#XNWtPgZH~Rv0 z-DR5pMYkF2G2niY7A41kl}`p+0y!M|V1T367=J2^B0M?$ub&U8jC}asygOe!9`ljW z{;JNW8QV9(5Eta16CfSfY5$5MY})iW9ukreW{(_oy|Qe&rR)* z8rS;zXTM=G<%)%t8+1=D?OHo=SJ&n6`}vROkJ&6W^hQOuO|Cim3)UBT+~dl2q}n8jdO_GniDH&o3d!}pr96e4iJnRS zcI5h`5^cO4gQ`;$aS{;xX8j2J+U-5yvR)@#e7%1;+!^hWcTEc{m;p$U^s=Q6vO&LB z@W37(vw;Gg%C4bm-iFFfq8j~0KOw9!XaExQb+l)1A9_@F20dMl#i4qH=6e2Msiubs9~WHNMke3cL=}4& z(}EP*puE8sVnBuly}DvJwDd7yS$QiIhsjNQgD=Qvc&CJ0`A50&PHFoLwslT=rN)^S z1W(zp%)aA_+%iVDgNFk@8RI1HZvgW`vGdQ?pGNUGsGt_g24huBpBj5$M~3+of>@CA z;Au5dQ&9Yic1Pe!b1*bWbFc!XCfFYL+enYqF5x5V4&E>ua-}-~(PT;(UEsP%lasO% z7lh*^dEkm&2xS9)4A!@Z0tArlV1?{{j=iK^oq*)J^hPnBjqNClyf)A`(UDV00P$&z zcYg+Jve$#zw zCKIxw8M%Yp6T^AlabF-@ZEetCRK9~y8?v3PZ`q9#MwVyu*RJ=3X|(MjkI3@v=n6Gv z7ab};elpH?CN$@y9&$<@#qN3%!KP7o(Ik=+jijzecY(rP_z8rQkPCd8I{z`9a~U zhAT1;_p!1?gQcF*ONPuG*BzUE;tAdn++4`Fv`1A}o4fw?fEzOSLXKkyR*106QXN(5z8ctNWS~faDPj02Z6t`a1=rOGF-L##|Y3-Ms zW9z4p*%*Ew`3H94DnG4ZR|E!Yh3)B^nFwl7Vas?7yGU+UQ}AYKrIqBnDeBfM&MkV? zaEqwFnGw^O=$z38KSNyfim?_PZDuQSqrS!3}xW`v`uMC3$Ej8`<6>C#r

RK|lht6-j-np(F57QESbN83k zMAluMT(&`8#*L}ZOL13;Xdr@`TG>+V>lj(L$&{WXyx##prD&GaKIjlFI+$229K$94Z zx3h`-lJq3K(k-vq8NI*gfkgI`#AJvC=iR=)D4AvOeL$YF^!COJ>7i-QiV@(kz98>> zk1AZ$MryBJ8}#w8z3Cj+yIyd@yYhfbWT7=LMt&mm30Z1AnenlHxs15z0J^7dWdhe5 z9QdcOyqIRSQSXWaYRQ2obt&?h$yTwkjIes1^Pb~aP0%U;{8W^aFW?b4@Z&BjPdU?O zzkT@U&>3jg`wU)+ytWeW#Yu`Botx{f&F?%YvY+GbyLmjSlP~4ra&mloMuhBR6>i#- z;a~cKr@i(R(BhHsUE8k-(8d9+x4y^PiWn=6w@Q}mWAp{-$j8S{2hqEyq|9IFK1zG- zyl3QhB}@-1AvGLbU{14Ziu7*P1G`nI zEN1FknNJtxbawJBJq#cUzbo+(xGPHk#|M5aI1EUpK1WwHI^ZAm&OgMaUw$a#_C8TE zTHE)T1W7z0aqnAkyXSNX_f;#c=fA97e`!kcjPj-o(4sJ%_<)2_J^4zSveZG3KlN(D zL`sGBDzwVQuoi@w`}(sY#;4+LwKWG;6o(Fa12BHZAOe($J@wD%6WU9&Jy#0 zE1$zL^y>qXoke7?onB91Q|2dX&^oCK%yqq-ib%N16tdMI)AYiKX-H>%PG$0DUlpqn zPN&qIVyp_XPd+pLBidM^9iAd~;u=&#r%$~ddPRrS3poTw+7&r{Xv+JZ?Q^sHQl>1{ za)hY#>vV4;IV9)hdtJ$8Y8^zsulwWUgf=;O`c>`Ae#H_A;n{V;UFGXFlIK;nt{5Kv zo0zg#$K(CB)=Q;P@DUC|Oai1-HTgc@TU_^nfzyt(7X5fkk#*mR`NQg#@K?arCisk?(n}KmnfShP)_Zat$hgY0b9{!FDb| z>Y%F`kt3n5WQh`u=i|?GaB7V4a_wuXaNLAzp>s${ep5$Gx{`l9)CsK76NGPhVIm8> zp-N2o8L!mehTP`Pw|~kP*RURmTS$n{W3L_+-e8q8(1qpJ!pZE`60KfcS{F-Qv6N^3Z9d4^4uYkSYT}mq{6*0_4f0i^lO1iBl z*+2weObl#Ho9Yg8f>W272K_b%$rLQ2(=qkHr&P`40ah%v%MT$MBxLR;bvWlc9F^tu zH(>*<&3~P{;MKlurU~D=_L{qP2oT8@JTD=S)#5Ly(Sc(X3|ScpGTE`D z=oP_tw~42HI=(V{*!r+;u0O)kO5wuw3}n#j@MQVNx@7tF_YM97gLL~G>Tjhx)fk1; z5PWXsl2-w4|6U!AEI_7VgQGOzk|6qkA!f1p&s}vyFTBXqr9_B~sGNBC_p4NN?5cMO zR2H1OWMG{(o5*452q7(py>P!lfz~1OlPCe2E;sd^_|>B8T^g?BKnn zfNkJ?6Qu})a%M_kgPF!|?$nzz8?+{oq`*fY$IDHBmEQP6T04P)^>HKX2ebeh9s4*M z-8PrRAlW3VxoFcUHo`@xaK`e+Av3S`*m(U)^19*f2dsn_&4?wl<8=i;^NU^Z@Cm9*14Z&NWTf1F$5(@PcDehDqJZ5S%>!ItXC~D-=?RH$xid)r0 zb9|_27+Cm4mlYq3Men5Dyqt&?% zHYxshw;eOHUvBif4;ut}*?@`TZAE-9Zejea7TBg=t$eV%ZB~`Ej3|LwXgZYubcJy5 z!B}*eC55$(Vk6vLi4y5AoVO~0(g_XxR=@0Jk{2C+3FR3G{-m4-Y7w+jt8-vQXWQAXl4Na?DseLPqFoG6pxoRR1WhR=a;vysypy^OwGq_0YbBKX!Q|#D#NdGG}OrmJ!gRVi~R+jBl%i%dMObNtzVBhehH%yV4u_4yW?=t;l*9i*o=xm zhkVa;kc>?K6EL*Up#Z4-G7?KSIe@!6)hpl&?Z9xWT(0L(3@EjV3M=ofN6J1IBL;4xZHnZUcC0h(ClU9LOHK!po76 zFWO@H_aw5n347%nbHw);UrEa(?AUmCHZSye5s6KT+^qC(=N0mns&Wvcg7|fyDm8;) z%WgPG*0&pbJo!(nx4D}hE=EuFNEZ9NM+S~)(Y(m(Sq?pJNyi&2S)3vx8)M>KUoywb zpGHJRFtphq_!exG^}R9Dg$=xNJc$}n$X5M_in)!_qnfDcF#C4BnWjfZ-7;v#7e3H=_haC|BY7b535kq4BXgkqNuCT@fC^>< zF6MLy6VvTv(SINd_WvG?Tx2b>-@@rd8nf00fPs(E3!b8DxT?&7#Tnr0Uk?zcVY3s% zktcSlTX17mcZFTyAu6b<5s%N3h5J*Gg9EO;S=eJt zuz6w}&2VExs_pVHbMloB(MX9@M?LPWb~wU5HGucE09`Z!{5pfdW-T$loDt|2Sx`Hc zI1UW&mGkdy$XdV(80=IFO_&L@T9f4y;l@mf#{|$`=ve4n=#cls4S-YNb`rMD@ty+a zm^kp?(*M5|$dBVz;_>W)C<5Om9+^Va((}?z!u

!Hq?h(8we655bZia_04CfrEBz z-#m!wIjI(&3FXvUuY*R(^LlSK^}uh9JRjgwar(xFANnijcLt%;)vy`1dEHtmnrWa& z>PjNKA}o|EAyTzGKBYBB=CM7_dJ8xeMm7J!k83Or6-^CWOr3AzFJLzKu1}rMG^-$` z)i6gXs|CItMk6&mzq6g%U)$efuQTJQEID_<)RF?R8t2|>a{#%fTnYf0{ud0KI)jg7 z)!dQg5{gGnUwS|EJ(`Wj3dqf}ui((mO8Wj#=zWp9j})lk8rWo?v?9E-}2XYYNVJK8exWICw@}rgWK-_y}(_Bf~~suRNw6HZL3MIUXU z4ga8DvmalvcH?|`>|sQ$q4ZJ2M`~xDMAS<3p z3`k*P2nn9dA@Nb7-9_<~7tpBGQtADtL{_w(_otoBjcaGwOQqpUcR?HPUnIVTJ5I~6 zDMbOuw>ihemUBDx9PhQ${lrD-ADu*8if75BZ5C(CB%BVHIEEQ{bV17&t z4;AgRF&1Z2Vo;waogcJR<59x8#X1&j!lu0bRfyLc>>1-S+XlJqp0>(GPA9n8N19kY?$7 zzoyv>^T(SI&0kDN7{=)Ec{Or(8>Ql^J>3cF&Q2fYDRB{c;&Th&_n^8)QUX6nTB=}* z6~zYzw-u1Pntc?mUW@$38vh2Z?l?SO9x(An*(by>u>S_$iTvjEiVmKWZ{P$d2z;+x zZ+ir}j0xzU$%gpA#%iXCEz}f}dNaVnJpZ94vtLR50-{wzPrETG}qp%=XH!uKf zldq~tiN|hBKEW{rI(ZcfImt>Aiq?!fdEZuCI$J`MmShs4q>}_?HP0K9czi}bjSde6 zRCg1e8?U(aNotgbg)$*vA3DaW#?{2=b2AQb6fanQ#=DmlQInT#F7hO>GQX(0Bgry3 z_vehr{IDq0+yc$8xI#K*^&=@Utf-)OmzFK4oHWwl41iQ5mv26Z`r~^zd$ByN_9Z*9 z`7F8VkXC7MLD|`6d}Vw(S9i1QZM0rO+xEtv?_l@4uNH;C?lWh%^*B>{As@$`pg-f? zf-058d>`$`dTGI&9;i4_P!x;Jf26_`@3(m%;wALx5cK)r$q~hDX5** zupE?GoLCT*9Ux!1Sn^T6IJBdAhoB_`3}ifzSD>C2n?-8 zY#wmF62{8W79P|yiN_42+@v$)v_Ow)#4w73&r@MgM?cu5{M?52<*%mVjGw5;0E)i( zY9MyPA63wvncwt}c-3DGoh$_6=OO(9;(Ho6OW*|2Ha>ecjD61F!yibEPlm_VP%N?kqUxSc8`&vo_oyws|=; z9Re3#PN!18K}URz94I&RJVg?pm@MVdfvi3C8GkkM)dShu^~Kr7IgY2~-)o4ffok(8U0kE| zBa1OiEx$d}TxO`zwe}#r-V4<(n~ESVn?weN*JWU|-DB9C`i2nWsAaw%^jITNKGZdZ z7e#8}o6cd@mzgYkU*Atgkm}{8pu@Z<1n-89E#kUn=4vlH@%~R8)*yfNc2tkUdNt5e z92dp!HYFyIV8tZzI8X5EWOn=OCO-f39ri)5uVgWu{=w0UeaG|T_PUYR)299Xh>Z3d ze`dSS+YsN|_4BgPn(q^|j>w}n|J4;b!7C^+o$x$bG~PM!9EP1-?udv2=DPY411joT`KUyL0f3o8RngC2mg9YkqBwz@lvbB#JQ^ z_A(|oMa3of++Z^~W2VEER^I7>+zQo0XN|Jm&xjHrtA0xNfg+mwlvQ5K80YH}Dhi4d zGF(sdGAZ1uT4~stg1*_nr?Pqwjn5c+%3pPr~-RzEdy5<$4WvNKOC`e29n0FA&Mt1+UUz&sAxxP*%-57uML7zEL{FMrw_Mi zv|l+^UP|Uo+hF@ST0cdB&xrY9MjXgy&BueY#P3yo$G%0NQwz}#!fS*LFk3yv8_2=E zq5B9Pu>NMJ-~s!?>?9d$z$=nyLkB_cSnTHyGuw&T4FV9oQS?WNCKBig9g=C=UH&;o z<9a>pH9GQ2hm%Vp@Uf;VxP49{l4}n8d@uUwhaA3nh^+soPPQ z0f+B&TLd;YHjHyodzmLQiTvOd1%H1Dq)0Tw^$+m*&Kes!6POD^i5moTgyoLq4W0bK z+GUQB#AOaBTl2LU7(x6#6?g1i9N`A?_CNI4`R7*896~3G&c=Fg7J{?YJl#7vo=j3! z)wWX6QK3kXr+_a-Tn^=@?L;IAQ7j!~#6pI%$v!Rif5_fzsHZPv*jN}t8nBz=cZ~y3 z@eht~q@q(3?Fu=L4q!IHAq;p?#GM9B)X&RL^l~f}r)?0NO@AN>P|Q|@#hEgX<#zbb zgG!1K$o&NWOYj!ws0nfO~+6gm|5!1$scpI@-*0To9GtwWYgynJ3zS#uQSCfQx@m z5>NU;2^=Hj-;muL~0Qmuceti-mNu(hr4HiFGTQdI$y(#|1MGQ6tmX-cI_uXY8!BwC02=1-;KTMgR zyh=BsGI^d(P}JtfM*SpJ2)?LWRZtVIs%R;K;q&FC@zdjHt$A~XYc$#84zR0`d8l6m zl-!N=rzmyvO@Bgj@Kmag#9EM%M?J~s={5M!gB~JB7MwQZT8Rk=>068IK#;hoMs>>B z*h_kKPLm?36zuBegD?^pyVQYkG&~lIydXfWygl#R|Gky$@g_-mFILNvpK}j?yvz9e z@3Z78$(Guz*i9MArv1pMYAQB)QFDVR|waWNil@T3Z{rGkIg1ELHmG{N<5uh#6b9DMDpdpu5 zbwl-}piZFt0Neb`W{_w{E3?8F*yFKHD7|S8eq$lflNMwUj-q6p?@B{M1!Dp;(Gd^& z_JJ#$0EqaYUzE2Y^%*$bP@Nu#j+(|0Gh>vjsHizUNf`45FT%Og2N0tHoSv#Kmypgw zLyUH0lvQ;T{ljJm%5*>o)>!dOG|U{<#=4XU%-Am&qo4?DJld*FcmqdWH`TiJ6i=cw ztSw+pCqcP2?swN>h|g=)WsRIVIX5nKnEUy#(m$Wk&c8#7LphH4{pjHYpVCS2PM!K= zYyjmyYRiAr`Ec*lF~t8-f7?(AL?c-mR|_SDIHv8@oPt*23u)x`@q5$+W=2s^Y*&Tr z^zrm;g=QvBd2mD#WlT&^l>6plCMii0_^3Gu(LNTFoy z#}Y^0lX4+bV3#g@G(Lhx5fAlr6^8u$r5Zz98mCs~k3T=T8v9Wq#&<21E)(!QgLFc0 zjpLKn$+i5(Pz3A{m}0MfdOA{;ck+s3;CCb0umSZU@w1T~M>?T~FJryzEQRDLYaz;0 zFtlOu#lhM5djT~rqI%lbWSh_34S_8)s^!Sq@5d^j+c%bvQh!^m>yENH^ntJw7Athx z1a1ZvUg4@Oy^8^zdqE)wQb?$l+fZY9jHd5M$_4W)1+|m7{(TrWmBb9XY~PZAZO1Fh z^oG#$bw|hR!?Hb%9v1gjJch|9d}K$9S_#h?rqJt6xO^p8M^6X}-98p*G_>Q;fMn!z zs5te7Nbwbp4-sV5z@iV)e7o9eg z^{B!UImMGwp{>U7e9w^+{j)zFG5d%rGB~^kaJG{t~FSU2k~%&CB!mFR!We zba|I96XVFCWLfZNQ7+^oS`m8o*!lN3)TBR)QC}t#I<$O91L!K2l;9M~(#uP7t(`QB zKSw*tRnBEkoj}%0JcHjWeDvXy-8GrFTinFXaD7BNUYT(JOwWg{fMwy+b=Rq+6iscI zc<4HSAWdyFnkvLDZ#7DVW!UlFM_W8 zn4r7)g7c~2*$djw#u>6rrxn%2;2ZABm6HISC-y!w9(@hYg=_4u+I8dV;=HCw>t>xu zPMmUV{0JqVzm?gncrB*Ch|~H^8Tcf=u5}&rMD%Uxn|?zv^n)db|7y~6nS>YaUY#l{ zpX0!c=cJ363hFbZWB6hEiCJ0z5%1E}k&<@PvEGftJ2SIC{JRL{-vH{rjzBHF`ak`} z6l$J%v;3L5(#4*S$+A`$LJ5(wPxsTuwNniu9|Y}?jycK%sc7@-Z?W=ae>qR$3-Dl+ z+=SG2kEUZX%*uw&@M>aPMNVwzayH@)Iw~J5j}Zu0>~jGrUB*MsKmArs*W?1Kej;=D zQL0HEwMaxtHE;oEafRD6g_}Z&gKhL3<g= z6%>>`JfzAKDuPtdZ0>BLO5Oqd@du!zX|~TxqDr%95iwyapijh71fc-urfSvvj?xVh zAt-;Z>KhP%!HxoZXz8HNz&W1GWepZ<(50K*NfGVj<%lLb?^J#eaEO*LoRR0CWV~sE*L>F$(;Pe z^ObS5AJHp*l!+JzmL8bq+WH=7xe7Ge7YG3>r7v)Sd0WI&)^Y$<(;yeBTz)If4j(yy z0qSfN%CE#Uttk%-q&36KV9pd}(g1uv9DXlMws;JrKGx5q{mlU?%{F5uC`^BQ-E&hB zXg_NNMGvjL3IAlw?DSvP8mGqLe=4C%%%@ItJkiLQ%hYS2!11(Bq{Jc0Jv-C`epKWH z9&S%yBHh`d=SF69dk!N8MW(9kkZ)RDX_1o^<06sf62Myo0^tyIb>`;+v8c6RopEwc z5aH?q17tbVb1|Qfp680roQR z86(hs$V@kci6c(Qk_2G?ARY~)u>0BpnOjVuUYm|3hf{0vQx>2!I9HjCB{!etLJiGO z;DA~IpPT5y)q1Xuz^%WMckgvi3w{S1Z6Rk_OBSd`7x1|S z@js(gxV4nlQ~(r$;B6XdU_8BF@Saev`C|5a$P0b?seB}Lcf9xFoY#nlw+VBFT?4Nc zFp%gW+5Rj1|FU}h7Gt=P!E5w?_dX`lef*5=y$rxv&#+&@*d{3IZ%Uv_`PZ+&Fw6@m z!6Vc@nqUABl{we^V_lF6Ah-TM!;3-7|KE&P9|MkwDIqCc4TisC$%Pv1!;KPyzwxyp z47D_YNPubPXTgpHe_b2a{Zte#cytsIX+IzLCsXG(3a`FAGUS2~j_k}S3P#7G<^oiP z%U5jpC=)keDPYkg28I!HRqoyAOv;52XeWA6|9MU_yrJkckU&M3C9@eHdEkg7kIL9*b3H@AokHJ zoX;yG77UdAGdiJK$2kQ#VWRy9ws$Of%cp@a{4EpoesXUZ0B`}G%Wk;r8=egh6kZFHM)5A&^m z1lwdkAB?Skm%Bh(fF!bqotLV6+T*i0FoWd{IJx zc?9>NCDZaGtArqaVeU(*>2yt^`;-i^)a{1Z1(Y8~$o0rieuCVL!xYpY=+0)bfR9F) zU&1Cgk6?^BkOlEL{8-d-Mr4WZaeX`>2f{ah=OnkDr@{GYdvGKc;HC6o6yV}(K+KP; zNYGLm<#t;D_xYT3))@lFfF2FmPh_a5`Jb~lOhJg$2tfEXL)?~uu)3H5Ob^?RS zyk0)(ek5gqGp(SnSU9^^(Fvr|GQQ|>Q;(V78L_-Vb(?d`64)Q(EcJh@_DPSaM`rs= z8u|y&#EXuxq3wzYBE8iRKomgJ^)_`$Z{-6*JOTRt8k$vqTzI)j5h{bufoTZBq)AU${1n8j6@`l(1{h_z2c<@YFI$e# z9+;5uc}u&8PW;ib$LPS%_N=1FY*QM} z9TO>8s|^~IT7CpY8FKhlDl95`r;~nkKth9TRq0C9t+4}~yTt{n153IigtM@0VAyK> zl=2Po+bnx3~UWn39p=KM050$}+eBJQL$bqX*evpA5=EAghxFD@Ew{;u#b$1Rf-a4~c zdIR$v(M_NcYFi2=wWlT;KO$6s&;W_ev`V82s&xUIdH2GUh^4P2f8Y_yOSli2n4M?Y zVwDy9F>nl}6(LtytsR>Uc!14k42Bh5vSe8O08tl4Cl{x$Xw@b}_7 z;DtXJFjjul<{u!UGn!>dFDoNc$ zip1wY=Sp^I)#+^+JWzAPlqB`X-RR3wfe*o-)`3^D7QQgWJk3dSL(hr|HmQv9HWtWsqKmD`5k*u`U(Wh{H>SW5XuPEBa zt)WvWI&+t%nBx@r@|#i`HSkQG5h8M~A^7SHLSGQb+^RAD97lFDwKhhwdUG{{)F%tT z8`)NbW@kI`?Y>*Upr{R>Kj+T~`PNSRv+V9orfe^y^V#RImwGvbmQ{z(O3$J0LEw)W zGGiAhLL2}$xbx|L zX1bca1V)+Wa;+8^u>2h6VpEDWL$-HGp>jf}L5&(3#J?DdQC0Q@S?lA+bZU}F)7-ma z@-wBnkr)(4)ik|E1;+JRf9PrWK@dCH`8b=qD@+ z^P3_ALe~!=k?Z3C0w(h@O&bEHi7dQSrRgC78O5L&jE*N@2$2A7`ra=98N)K`=NZu% z{*!$Q=93wh**tsbOMw@?JbbknpRul>b;hW>yTsW<)Ts6iK&p$H>bJApagY85dLN>x z-@=PI?VB;5Or!<~y$*{|GVw*7?ds&W+`aN=JdV$QeXFzy4Zm#p)|U6B7lAL0yOw;J z5Oocuyn0)(Ew8|!Mu+fYLNGPQgisj|oq9#kCg%*6LV-YMiy%;aW64*clqPRLpX5-0 z-GDEGu+REQ)$hY|=Ss-K$IFF5UEBnQG=<^e<1@yjKFW$L7CvZdio3=z`+Xp49)AX1 zoTjWbjq2*uE33Jx!Xyz{d|YU_6Pla2YW^A1tnd`hGl+o8h3}IR1~os--gE4C$|9jo$l}Z3W@rvPDtj_RJdV6UJ?UIvWYA!S)aoZ1 z_f+d5bS2?cVIir=m#f2Vi=F9(QSnHM?BuJTp_n_QzH!U6nyC&6pqj3DFcV-R`2pRFWIU0m@G%ieTcXo9SzaPs?oPQ*TRx34t(0 z5#gCp!jOcS-7(`^?#o66--CrmUjl=AT0>HRS{g^wOxKr5x46{Zjj%VCa(;6YHnRrD zeAcrt#Fr`Us1#jE=Rd-~N81*^W)~tU`dwnRz}v&#_wC^WjKrrlQvcf_XEWp_Yw)z; zsBdZ{3g6Zng8Q`fmFYKJ3xg?WWMSK7V?LB%DG@WkBd!QRo6&@m>nqBA37)*E3BJ7A zF7SCKg8^e(kbj4kU$%GFO9l@+Cv%>ldRfP_H7V3d5}A}^Aucx)1KKk?@y2HJq`Q50 z7kbFeO}97n$eJ+7EUNm82Y>HE;nC4pNm<61qQ$(sva*;IRc$jaXb%78Ps87-q*b(? zpk1RdXOs(x^}s)0x`%S4Xxpc?dO-7B)+K2Ntdel3x%14(VNjE)Nwy7QN)D9`jZ*b1 z7^2>8R|GO@hjNIO?Fs&KTw8M5F$!{*lmpA1Cy}vtaCg?2Iy7#mEH@LAdbq5*oVp)q zIMy>lB|W1(0?-J(bnw36oz=EiGWt)*N3f8f*>|hKr?bCX4Vqo?lZwpo9xZ%>by zkc{kmpgx48$)Rs|rH>7z;D4w=Kt5&>3!uT)`8wU+Ukp2E%wkV_!KVO>Aec^&t?f*I z=fl@Af(P4O+#`FSJaDzm9sj`?wGP*GXFtv_ib9&MD)^gpB%rFlCYk{G2hYD&F?ny5 z{vO=9)jdUA@xuG&L1BCIU>Gr06EblU`;P@P(m}Aj) z?M_Mp70N*~ry`_l7TPNa9yv_CgS2xFuo969rl`A-1gfS{7Ni__SYQA3O8=+#UJ3bH z-cZu-;Y5$dJ)wkY_I3z4Fk)F=o%Vx3!i;5C2$R~fya_UbfKs3c%r=g`u?6m9)|#~% zY8c*093#Cro`o??Y7r?2YuZrE3Cx`LM*cAO-pF({?~VLt8fNmFKLL1aw;wV{WKADR zNp<|+gb`DP_)QTSN6G;4PGee7$&4Mkvv|x_$NfLtf*N-bv;z1{uQD&M&}?+ zw#v94CT+IP9HbfLL*ixu1T~{*0Pe3TJ(|G1M9%?Y*{1K-pV(xZ;H`eYZd3EC>*9>c zB=51QpSkqV>>9Ey#eJKo<&G-m@cfRWDlx;S(@3ls4ZC-^{dZOOuG6xiC0^) z;ui$|g$G;$Z&JiWKz$Rh%Sderu`EYr1@Hf2?=9n^Y`gVgLMaiXq(MMhQc_A$x?@1; zP*S=Zq+1b?5D<_Y7(lv_PC>d;x~2QQuEE6t&Y3xDoyR)XvDRD; zGXxt;eX(XLscJ|TN{Q07?WuC6DjnUT6S9dIhZy5Vw8!LF-$V?PjmKETBvOhGc}32Cw^Nl^2bsN5f$fxN=*07= z8w;CAMSpDx_~pwYm4;C^Ss`ulxR4$+JwdESRmK@qqBH)dRL+6+qDS+qIceDfQo0tr^-_hcUWgF(DJ6Roe z-@4Tdh;sEOG9oP4ShveqzeQ6yiO4g#(fPvYF5q}nJ$SNW2a^>7n5;PT?0LCld*u1v zg6v&W_9fW(w68A^PmaYNp`yL^eN{Qp(AfLyq0zvzm*s~m2(pJeXZ6c^50Tm5utGYW zki`2kY>^%PaqM$4N!vcjEY9yC7{X+PjH(7{+Sw^Jwc)NG%7D9`_1g6raM!aEY_u_> zLtx-=4>B?&70(sr)YXbc@1Iyi!K?(*1bRQJR10w$+U;||Aalq8gDh1h1~ju1FcYB_ z>qRbVSk8lkm6yLjl>tDF4e7CO7(L5i#^F2}R7RGUhk1vmz40@H3 z-_7HsC2rz4R(u;4Wq;BhYXpl<5A+IkxB9mi7@p}6}g=wRSnxddly45>z>9ZZWoNZt3#0rvzOhhG#u0gQ zb^VR%oOtocwE40Xx^=;!=jzFK_vPg3F^RD4zn_48rl?x#N#gc}W7o+R?I-q`bSAFz z8+#sY$HVwnOo^rTnC;97C7}mAIUKvGf57##$%l6Sf`q7 z=4sdyT;Y=Cr7m!KF^#-@;#KQ;xOJjyX1Q$3JF}`Dhs-qX$FlBHz?QKje6_Ju&udA< zeu``3-Gz25U@i{N;H|-%92je~zOQ9YV_?rI$})doGVtlehp`3<|M>JG0^5(fQH=q_ z3 z(&!#L_-(28?zPot1YcIj&Y?Mu&$SZ*_nADa*@w_23O$2qCYAkZB-Tlr5wRqdoR*9@ z#6E{rW44e;)Xm0du#@nK%HKvIml$Wc@BfA-pX^d;K8Vm4DWbW%W{$q$9r+$Du&W)} zN#g=qSTTQuVz@S6+N<<>R0(_6=}jdxIewOC8#(kWoBMv5qbPUic_{NybUE#L=UqRC z9#d3MxLmYcR9E+2X(3DTS~KGUpPLKCP*^SFj*aVLWM8eXhDfnnb>R-BSFo=7-(cvp z?~c=tVwHP+>(q=mJFb;UmH!1VRjzekNZnK39LCqQwKpw&E?!SjXgo{A){5kr9KOz!EvSf_^+`iMkq6qwdr3`)-7)5Pn`=L zr#*DF^z_9!=1tdRWV0Y0-8_NN+uCD9z;6wx`#%gyRTVSgHWzp7Cgb|imm zjiSb+zQU+gjcOzxJ`p~9yq~_jh;n#nRuIpff%mm1Ut9XARC^O9yJ#=$uko>!FLvD- zVkrkq+&{asr{FRtSK0!xs!bvngXT5IW4e*XEQ;JxUHX^?mEfZ+0urueg*-$11j-uy z$@S$UyKyTN^v$N;24kkyJYJqGkIIkf7l&@5XRS2@!bc2Q7ixSaDRL~E@1>;9(ri6*!A2~>f+Ny@LNdWMBJ7FLTD(Dj<8;orY`Kx(yIt|HvP5iPbJf% z82ZPyi26E9XzAUkje3zxelDhWP~?Ofx!$8U?%yTSFAOHpuPDOMr_kj6&fbUi)M;gj z=O)x4McnV*j>!69Ux+9X@X5nFex^t7qOtt+%cId29LBuam2$~Fk^H1Sk8jn^J03|W zm*vec>xg*qdlew~F1odps=dC#^8V@=AWVJ3U+P5GFcXpPng7_`J9_dXRPDa`XnLZ! z6s#PoHPd3yFZdX&@sUcWbqUw6J zXRh^f9jon82Q;QC!p*`O`K2w(-uS(tpCc%nIn8J9q4>R1uSq`?+;%D;O!O~!C|&P% zTQ$Rg!{+_s!4I*-+vn@tS06X=Z0k=y>UG)ES;vpxZ~_ReA3PW z;qo-}@a6iZAK!U9LWGgkPD>Dfed_DhsvZ{)s_p^_Bhh~CSI1jYsjqLB{p?Uj^*Nz> zjVV&=9ZX{DYW(08dQGoyg3HB5+-uA_osC;{@++ix{pZ`$C-2EJ_m__cmUpx2<5KcU zPBq#L&XY5|Bi@Ws_**N~e0w_0En1Uh;WN!0@kHgTS_wYdSZRg*CCo;4ntQ9f+Noe$ zxWFcdln=I?qJNn4sn=5TeP!jx`JKyZQfX`D$^t`|iq_hDccN_qChAzk1e> zHqArIp&yn*Qzpa6-R{%Banm;w_=Ip_O8&%C<`tFASv|zZ+*>q^7LuUOQ4pc-y?3?M0bUky1LBF zaa1DxaB(%x`z0%pw!EHFq3CSkyLP{s6TMr#jK(JQ=OI>6jZH_z=bMLYd`@cBXT>`c z-!Q)AveqxXIJv;4BvadzsK|G8{<&~B!zpoU`<-XwWXjUjip0n&iPOa;;V|D#vV5D7 z?SsXsBo*yq=&0`Vg{^@WZuw*2?-;PXbQj7L?7y_GMpkoM-nwl*Nn%^qS{qrIZ!>Wx z%Y4$Ku$UWmSZ=DFYMG_JU5=S0V{bTO+_jB3so)}lGdXiuC_eSAaN5wd$Ls9=5x3={ z&-$6>NfB9SptMdMWU2N!ZJR;#aE0%-{PTrO-RjmUBrpB&39+O+z#tKw1=x&NVXK9g z;EM&GFQx@6)StP5vn~K{m8v_xpP(3+HzO^l<|}qt6sL6n>FH-_U&ZP%KJ=J z7t0MQjO84j)oEwTUMI8R8=H~(F?jpctEmErd*7=^X9BmsHOvZaXpcH#Ed3zgV6i!F zH}%5h%(%XPWzFHh%4?Y^qaKE8uv2!xvtF*bzq{5A`G+5Diq zy_kkWqQJyU1h3d_!S(8+pWnb?QMDMYsD>)_XR%kP{$j7Z8d_hdR^jm!bq#E;M$POz z0{SM_o=T`c2*;{nr~{hqamG53<}8tfVJlCNp~{uUAz z@^@qIR(cp(Qf^HgS)UDb*d!hWV3l`8+>JRx{C1ZhsbWk;_d~!0$Ao}y;e*M@$-;NO z;#D#|j+=97wgP$+m!5^$d2Qz9yy&^^s7B$)Vyfz@Z|aI~uvU;j?sQ^{CU5L=*1b=nhjvTA zaDsdzwg%0#BlK--4LN>n&6B|J*iGx^^2kgG;NdcA``V`$k<~04a}y@L+cq=oQWnip z=Ey3GEv5(c5`O!|0-{whIQ{vPPv+FH9$6K=?hSM*=lu2Br%Scz!YwtVf&3epn&`6S zobpgjVydZ5v{f~6$#Pp%e@*_CcYCkg$jYk0HNxInzVa(sxI;Dc($Aif=JNy*)l>^P zejK(dk>gl0X+ODTFQS#P(R?W40fA6Z2==$NOER%J!R@&)=i*T%RrjQ~mK$HgcFC!$ zMvk(lyaaIiYp0*g>0rAenT{ogOG?ncw~yTRntEl>`l7Rmp=9e(*nB}tI=;Lf;JQX-P^UINo{Fe93fl9~ZwnY9Ja|~;^xI1}HgOipz z6NOL4>aGqn$B_E-Ya>&$te;@v+i(5;D@Wb^Ige&>`;ZjdyW2a5}sepMfR@vH`x3 zM-`<w;rmvb7X@x<&T5Vq3@k!t z3>%IVV&s$K>BKJPM=1#qQZLL^_@w;^`_nYS^$xO9g~JrrTP38l{XSf zsO5(y;?v{U!lifpju#}$0TfHK>Ob^f9!1%hZ`V_g=eMNxJ487TJTE=s5QdHWX8UTo z-65FxYW{>T#NeQnQm(26r=Lamf;{H1K0Qp+{i?Fxl7r+~{(C>on#Z#g;!kElyXMc9 z$1==Q(F8)~S(dQNj<9VAajIIfL`M5BQ4?)K7qAIC{LqAOt8iVZKih^HuC90KDtJFT z-ycyKzjEaaYSSg4rl7)!d>bSo*-UeP9tU?9ZB>SV3TNg?t$4TL^o=^KfjXWern6Io zm3MtHeR!$HqHKOT=(P@t_k@?6B&Kt=9Sl|em>KNs_e@aq*McdROznoA1bIzu58OW3q_AbN8;5AbW%f9{$^a`XOtmKj&1Qu;c(kF)CQznyI`2spSZ%@PNR4LRMN zWi^4cXCE~;z2TRVTsx=-w*S?)R)%ufMHETmNF`wIE5I&!;8}C!c5NWiE=MN|a5o0m zhKctv{N)U=FT*o;vXf}B3~S)Sqfc$9kJUvL{F2dY@3_+L4?po}?E<^-f>bK0q?>al z5rX+*Nblif*-kw5IVM_EON%%?MUW)UvPJ$J1}v@I3JhUf$m+}wQ?guVr&>_84Ept& zs-<_d&6fXG>RZ5!{Ac7D;P^jHX|7bMgj)!7(ar;dpMC7S{TA337_&vQmHOB{%$8Y6 z;*af-?_ZCpc5`F6LzzA)jW2h7(0?^CdlJDE0vZTO0#*dRFR&7^Ki9KrSq(tSA+9jj zuJ^W5C*Kih_oN+g47*+n>;vKg!{~`evI=B<3&@|CQ|U!}{dCZ3ab4FxfrdbVf%oVC zamjMCbO^K63`8ehP9{wQ&I-a&xqR&k0OPg)3dq#KHimL(&=cQ;cpo!?1}f(OR=wo} ztpxfU;@$!-d&UT$31A2~uahrkf&zmWI5!jEjaMJt;Mo4&Ph`pt3OBzUa28<6^$c)e zrv;$t68 z>OU|EvQ_Cy-YHyB7p2Bp6qjsHokR=fizcPQ5mB);gK^R=jM`0zPZRnC8TN+1{mUhV zk=MbO=&4``-7B)r@VCiRsfsJ;=CZ7q853x-qY$@elr< zt5yoZBgKdBaFP!2@TeWl=P(c>&IlpEB+$j<%ru@DK(57aEm_&_0%nl$jhu@u1GX7@%UwMoN(qB;gZ>U}i0^J|$Tx;AP zLYK+WX+ci+!15ou^am(%V1(`dyOSpZG6LTw#uZ@V_2Ol4!LmrR{X>m_sHy{lbe~)V zVma^&5^$@WKebWS(k;99SP&${elwzwyf@4*8BGY!m1{DIK>a?JM2RmRHl{6fq zKcwKlyB-i?Ig^J#IEq*H0Biq6w*iz+BT|^kUEs1f18Uf+0NfM5q-Wx(M=RTJp}nyp zy%OB_FqKfWz;F5yT-I6tWkG5{Nm>81xDf*T0tyM|2_SP6>3~TV*f-~aS^mFs%5Qr7 zUXQ^6urFs2NFeYFsJ3nlF9Ef$R{WjV0CRrPadZ@sa%HqNn%`}q_e>VA9nKeQIG zh?{yNNW%1Q0g8wVkff}PU{8kpc2}Le_cK9hWFWt0xAtmGjt;q4|c9m{3Ea&$HQM~B!*(%lV1#wr-K9k zm&Kiw!1TsjCLa$EAI&UwY2qx+&SAzdxV=25L||^?BEk7BquIhFxeNmuzurTOFQw(RPKQ5*!dmK;TQZ>*^k}3lSxU` zgTRar4`=|S@TrGH8DZP3n9Xe)m8toD0Ja&*e+6iCA}th@MqVzDJ8(mte~UotH$2ee zM!mOLh_AU1rf$HOz}L(XWhl>R69q+%**#6affL#P_dqMsd`d_F2B?Ydy?G^zYY_u# zhkH1{#f`yU$>%suh_{68&Mrg#A5m2lh?Ks61)>k|wsl`IuCMMf5PqXieSmV0Z4ls5 zxDY;YU?9F_vHgRE@PC!g`?4$keaxxlSZgvK7M!!@4u^_yz$CE10+$4q2j+p`gxMNm z`=h_*1Ta5T)B}~Kl>#G7xfRg(I0_6rfcBvJfn7muw_@NASJFgV0cd~~0YH!bum%5D zAE;=++H{YpDQ?Dr>bQ~GznSLI%I^k-4X-UM-ByyegIF97$D!=7y#RICgp+c3|$#sH~B%5 z;P~DW18PdRqq1xTe&d8^40z}7r45o1z@`t6{xJ6!6XB$})Pyt*$pyVE9GbRAqpcfK~2BYM&TTzmD1cgQMlq@KdH#Wq_0b z64|dK0(C#QO;~>}1sgt?Lo)*#uh+ar9W2t}^#29UOL!Q-xdgmB0egVr8SXc@SD!Q} zf-kaNQyYi?mC7W5^=??isK65n?#6}){gn7_6+{<4Afz#{H3Sua?L zf<-YX96()3?dd40PcZ-xf$mP59a!9gFJhHP|1SK}CXGtij-@3tzR=IU97FW5oXnFVv)xy*034mJwa=@Bk1%}4BU@e2r zxM19Ap>u|X+0GX|!DHJFtOgWLV2yrV#70ll9Fh|~CUdi#X!p4;kKMq6x)-RAcONeD z6oBjrw4D&gYTo_$NAcXo;L(;k`G~>2EpeRqF`4CR7#-?qL>mK(C9tEZO_SZPlH7G3 z;8!<5>3>z~AAXIXwa)}|S$+w?H8Vl|dn;5P52tD}c+NI}1lLL6y7B_JZ3MoN1r_So z8-t1ra{M4{mv0tE*f&L~BbI-i{kkxo*?m}U4+lN->fM_NlwVUp*u*7?12xA1?BvFe z!N_XF1m4GAOBv`C;2jHCo6%YPiXYG@uu6dIE>?L7(3k1>m%hKpR`+#mZ3C_#$^b>` zy21bkO;D^o6b48M0ziTOx6lIX6(BxA%zm5lm$*vx_&Rb8%`e4;bEob)O97+=6b-l~ zQktO*&m};B$uByNKh@Vs#5{%q;rg29s2;9*zv0{Z3zyX$?78~p#o@sA|7w+UQnug< z@)911?8SimUB@ICo1LIO)xh-$RQs}yD%A6TC`>mPn{ZI|6Cd1(Bnn_^oN9Pg8$`fhdIgUx+w(ir=i8Qa)5% zNdpoVs5I~c;#}*;wMxUK-$rKasXoeQpgI6km8nhouT}s8Pe-AopaF2FK_6Y)0<>VB za{<*Eeq=zrkpkd?wZIPq{cp#B6%;__iI+a`VLPH8ZJ_)E+tw`@P6D>YAp+&|FRlBf z?Aym%jmgJ=Iz0q3^FIU#DE{F}`JaGcT(AcY#Yy30j>*$SLfIH00Fq&^UEiHlFrRCO9+371E8D!X+Dtj^rG+bUMC9{%SkXt zu;%K*izMJ6|9Z;;URV&n1v2v=<&43LKRJi7?PLXmdG*E&s5sX^>Ny_>$zo#kvu3J}mkfWRuy0$;c-=`=hE-^fw< z-uf+IjT<5YvDL7RHFJ;e`=2zlXQl+r^3qZ1McnFDkJdTQ zI@Tv9-sG=CW`+-PP1jwAiX3XqMyhlU%(M$yfL4SL=nEY_FuEuuBzv@1UVivuB=KNG zhse0cYFO9JBc8kdh1cdQjp1`(gt`F#Uik>u^@uq`_=wan_y}z}_y}I}=X-7kPNoG# z>`V0}Bec&)z-NI+`6sof)g|dahR<~_w8y_1nR^yovTpv!f9NG3X08qFBp_f4E+^0d z-&erQ2>xvGCA_)yqkBfa_&I18mh$sGpy8R!JLx$!$Bx$opHa9tE?GsgX@UbNEJ~Mn z*9(M9;On`y_9o2a)gRtTfLmGl!1(g;$S7) zoEB_o&c)9Q#?fqS~qR>9A7bE@?`bk*xY=2cM%A%|wl475I@_U>o`ynQ!(-Es~A z#}gU2dOq&Pp44k~N-5*UoDQE(?sM(9VYpd3u}j@RFSy?3?dQYG0Ft$l9dHO8@4@k^ zHv45)M(z9NlXGxa-j{Hn=zPO}>1MTpY$UneclQdWYdMJq$YBL1??0I-;I1Ux|03omfbht%>HahGjT-5^8&ig$so zFYvCH#h0>Ih8^%}QE&u*bpx+*^ulq9TZWJC-h&@>>Ew?Ez!AV|f>%Yr(gw*_&wo#O zCwoN`e<{Iv5&1ItN)o6_fVmy}B2g}v@RxhN?hn9U{x$6SIk51{Q_2p(tG~?t^ZBw! z)T-D0z4N~;`kyxe_6BDEbJPFECfBopP5)-=?`8j2J6@ksj_r$lS@n83aMcdrCwE1Y zcqzei5&3@|{}B>~%qu0?tMs@_34obE6aZWfS@psnxca}2{|t%QDdo_cCYt z0HWMgdcvgy_eJFYb^J$2oR1Ai?vXUCKh8$1xvK>{cmh1210RS24|u=_Pk{&G;Dcw! zJ1r%mT;7_&nZ#)dvubIkfh%|wF(xF`r#CEV6JmpeeSj{;pF1t~VqD(UbP099D?sz@ zx|zOiw%VHr2PnQHY$ceG+&{emG#b}U!gVu#-H^~?>&j+5L#{ASTa5v>0h-wB=EHRp zC+L2X_v+_a$|dlJ4qkPaC(9yNt5=8!2v=7K;N@kcHb&!POuvFJKM>SzQAb-o!AQe? zGmAdVV?k*CoFYKcNT8^3| zm;>pPeEAERQiLrZkEGp4%?Ui9or!lFv}1ojA(fQLc`H4ghlf=!gw6etG|%Q<&PJzg z7;>7L6WnlQ1VtI-8~6w)2x!1_DujGnrH_Vh5fIeqZy*o>uQSyox4>OsBJhM#wH zZYU3uf6ZIEipT?D z&p68H>4e+McM+c&V$>9s^`LXSZldM(F>^s?j_Hrma2_-_(C9H;ee#9QhREod^7q*Y zs*xk>>|ES15yrCjHAUpXOWdWiGq0bSe|sG@^^`tmdTSg<<;%^Gm~4L`7v-?~T_4uP zO{;QKw+y3|10qN~InLh~ho#gjMZGb7rTPk4k1lC>;-~RTaR$;j%k}zDI_cmgw>hjG zQG)tjWiE<}`CBi3%71x%&u$`PFNxvSIsHZfPILS1IR@EDYln-LP#4BoKW&KQUT#B5 znme(-R6vKpmgY*j zdPTJ2t?bX}bcuLl5&OZmd((RBO6yHke}-(Con^1-rj?L7hxgx;OXun~*y$^%%WfiM z9VWfi#op!E%EaH@a9M%U)ir>}i}{GO1|=98lS6Vt|Cw?HFFwh83J*bhgW`u{FKQ$l zPOQU(DGgFY&|4R{66I0w3g%~<1+fewLuUv2Dm@9_9wG!G-;0wkmfDZSC)!os$yj}7 zL-uU$flCuL{+7)hH?4#zUps$$H{0D)U9tJzSxPvo;FmlP^GJ%e{G}s=6YOyGJA4ge z3#*=155K&6{E)<4r@4r%g`d=|h=}NCJC0tLj+DG@;n-DO9x3$rtwa3q+1C#_21TQg zmj`=M4-T`oFFn1kE?1ql>(4d@%0;g1T+fbQ3nxxr{G3X3+V_fN?ai#O&$=2*l4JAo zIJ#U;vE0_Zn$`T4>D4o_ts{JTS)Vdp@8)t9kp1n-&hBt5i;X;zKB8lxxM%5gT7=W! zd1UW5k&9!>6pz#0E=gMgsWM~Aw%GO2FAK3*sf!J_c~j@!kP5d27>`7Cy|Sv9e5h+>hiidH~DmLee<+@4$aEY`n1EF8Y$bEBQ6F@ z>`6~_al`qMAO)ML_2l;0zqo*oSZ&o`F-SVs?!HN$@;Eqe8S#ocr@Yiv@!wiIKA^nZ znV30ewO5FeIp33dsX zp}?x{QGu21Nv8lpCtu3;UlK0cSX+zqTNo@l86P!!uvFup4@Dyd~H#tW}=Hr$zqWzM`>umFWP2Rb>6K zzwvAjPxrM!p@_(yK;uF{*5aV`>9k+n+R18WGCBKkn{j8@8?^-E49($_Z|vzV8lQ=K zVji+v?*wwheGj8gmXi)Bihf^NUrc;+%%AFkypEN)j_nF_H$yNc{%i3k4I#uC2SyJY z12kXrVVSf=mA4m&YtAhvH{x+#SaZ$A-SO-O=%pmYpp#i04tB`w-CBhW>btP-c#sk?}b5WA{Z8fpFign5n`>w~o{T#pC;& ziiM4+h|Cx%!-)hGq?ScL42rs9f&74fM?QFaVv;t z9~{qC08bJCPwroMQheI2E^FO(B~e)0nIqYbyC06)HVIiH?Z1XITq5!{KQB@D-_aBy z|J=GwdX1(g98K&$(e(NML9?9Ob7tW9n*+G>ra|W& zfX;K%u~u^*vW03y&}bl4d6}$Vrb5rMf;j>n>!2a|=q{ScCq1pgPA^zo`E=%On9LcD zGg%Xyggtzb)kb*xL;dzm^$hbwRv8Z}tg?EMhirq>yl=|uMUT&w<@e7y8HC>7%CFsj zl=3V9#_(yoWfc9zz^lTivH6)h`tRBJ$<_km<940d85~$+lBhLLT%x|a9-QlHbut~CGwe1XCGtKvI48N61ApCk$dyvG zNXpU_k4%L5zIe#zBRO6nHpgK%f=~!o8xFxcaFuEa;0unW-W0Kpu`fI7^ToQg?NcCs zv32fq!|cF7?9-(b7+LXX(p7*$Cl6p2388QE=yTU<7k%h6HMZr{FJ$THGF^q+g7Q)z z>mEVvbd?!ucKG>ki5P){B^|&ICaDHL*c!0PHbpA*h(5UE+bcc$*6ar$lC7^6tqYEB zp&0oitdvG3neW%lm1Ye=H z)8sqNhOrWj`)NWu~n2#mU*Z$FTy*ab_*N7l#kW;^Nj$$eM~h z)$)(21QUP6n)OhXiW+>D44K)V+%qt4QQv(bW=HlNCkI%i*3Az#pK|}Pzy~Ge{W2|^ z?YMcvw`y3CAq8*c8GUSL3NQ!zk$7s3>eQ>*u>p>l0vy?8@e-8FA(*kB?0soykh^Rb z*8gQz+2Lt4Pe-`N$%p*aD*9=u-3gc*K}I;~b60!SkB-kIKF{+C9&MplhiuQkr1a#^ z#*CeJcn@{Cch`v`N;1h8%dpheS6Ii0S?g?@k+bXD|PaV8*V4C8h;+#{DtB_;OW4 zM}c4@{OtL-(LWjIz;sVrvv~ z!)p9zVy*jxrWI6=1;esO-EqPaOi5ZBNt-04ODA(<7lIz?BYBOeP2xFOEZ)bN%Lqg3 zCBj{r=Ft2aS4c+jT5PK8!OaH6Coc;-)nZ}!&KONX6;WOeG3SInCLLgH7ikZW&`?W?{T4Q?+giKtGr47fSaqk z;Et9kqh$tI_qv{cYZ%?vBc|bRgaX@%4&lz|3kctUKKRNRiGm(jBt7eSF zP16XPHNSF{sm%$RvKzOcS9W?t%T zh(*gl$!js~XG{5=Woa;K8IP4r)6dJRTKq&sG4K8I32oennuaF@{J!3W5I>!{r^7BM zh4v}Lz`cQXUVB7M&|jY!=AkkBsE8gmA)PEYC0=OJLN@!_f9r17+e76^)+Ht7uD#m} z`?90Dqtd(gC0okoO#x&rN!vWSMYbYoI(?6DtE_P7pC7T305j$LT9s)NHCoOF{Yp#Ee%MoM znCVkw#V?qELU)3W&W?{OpdR0v`sZ#>$F6s?N|&=wcF!qO zNf2GR$kaI@)-?N8cMXJC|0cr>~FUR&v1Wwf8+ZHPQP$$ zrhZ!XG(sB6=)Y{z+OfTE0ls9Y z`M&+#B0QCoSUnm+Q8UM&RQk#yHt83D`suL7zI6qDqB(Ch6UMjq(>ReGmNZe?8vFDC zkE6%gk1jT=I+Gz%!|{ShuPPS~(bWR$N(|$oh^QYs$Gd_TXEQPKS8mJHsvndD$YAfn4DI=!d7r^eCbwDGOaS+KnoSeMsuXaD2m8*UY6Q6ET za@y~^(id*^lC{SejMwqnJwJ^c*nH2nMOJPMe7Ako<$Pqz_G0<7W11-i-DB!wcR;;6u@Q*7?>he_!g&w~J_(VW`L^Ol~J^$l${ z?KwUtc_Ay7w{ldCN8wdQ+xlpV`$pSuG!8iH%=4YTZz7F*P;qF4g^F zej0hEKaxD7^!>EziZ4>i{C3S))OYU8x|5$Ly7iZ91-c4XAA*dnxYZTvJvlDUcK5#v z@`u`8DVlw!6h86NDG9LA4f|%t!LBeN8P%tgnH>q~IPc&LUFZ@{IY%5A&!$fiVA<`u zG<2)#S+TEfP4izpWx`pRw1R!U{e|EJR7%#QiS^+cif`{CVZ&2v_|Nihc@`s|2`9udhWgkJQ<*XzT{ZvR%}`LwNj zfxCJOJ!S&shaM`8QWQT(f9{%bT4o}ctZ;W zS~S9cu-Ko0M5Ctvm?)xT$5Ic1(NV6ht&4q&kGqF}ynW6rrp- z_Xwd=``{~fpMyHV!?-P`9GQS>CY;f&+%M&euz770s_*+eQq445OrI<&pwVdDP6T)n z6;RCiglg#rrJJzM(?i59rnoj+_4vI!2X#{;Zl{>Hd5f?pzn}mm1+y(CA?+6JjI82G zNO0~lEXw}26J(ft6NY2~nSO{w1DIA~CW2h}YUW1C2&%LbWZHGWznOW?YYuAh-de~$ zbeU-i(&C%s$vOvuvR>DCjybaplY+a^$MsF;b@NE0$By~6y#l*wR+24d-V*X0qsRrcdi99L=~(G z=sefBwwS`jW2YFZXj^rq)U*)AjOw*iQQ%wnlL@P!{Si`5L+)9Vkkp)cm_bW+6?CaO zqB;cqwG)KHcMg^|9Z@Z#Uq= z%lkJ;kMHDsa!MiX-^%Uh`Km33u~iuloXfNtI%$ON1QB-LaiXe*rrjUat$@a%_ZL<( zjpv^_tlj3OydQx1EwA5zF%ajXZqr(Fi>ah~r}|MP^i6O!{YxiEzm4476vPv9P;3lf z%v_2zt-Z)2w=2Ju>nyEY|Bk_y%%qmwlvARm9?jk?+ zw#A*<=Z#V5$_VE_<~yMaB_-ho-gWBB{7M>5HrkVT5OSHS)|9M~2-;$zS=&1*{K!GC z>RwpqyqPm|jv_s?O@99Z^Q|*|n{qLc-ehpvG1RPbF*ZQ-cw3{9x2a}@T&uLiW=MHH zS5k8}cl1pK6L(@or#9Bc9Fs;rq835c_X;x?b{MChaz!qyYA}?7N%fYxi%t-Ty;iA- z7C{12MM!Km9*UN01pvGjq+4&6X>D_s>52X&GLX|@6hgk1}g@U9h- z!Tp5jt*Y`uZd76`gqF7f5}X(eRn7_r(bj6I#@26m%4bFPIXG(etHvyo(HpKXXxdb6 z6Mt%&N%3e(lXpimMJLr92(^Y(1yfv*t7t1ks*T&f?HXyVm;>pKZJU@0t`>ng0O(=s zp~r}%!O%R{V%FK^vMR#DiI1NSLA(By=x%BFH7y%jZ zgC?{XxfJp1WocMS@O*v)N`~Ci!$5 z0-*!s3rK(>hWd~{lg-dmf3rEJ-di@1agJap4~e>eCI-mvQ(!HvmK!`UCL?xhf&)kE zm{081kYRCPH8ofhq#MVYz*@@(DvgB#W9pGy$n8%+P=645_PZYNcd-EEi|{zH0%w2*kQ{h@+v%@EVJ`>=7dYXTFbhd|5zAA`G)%Yc4JSP>F` z@Ag8jN%@+!dsH)F(u>I%twd4h7LI*_@XX^uQ>k2Hnn5ak?mW}QZA^s%o0yZLu%61e5KKKh zk$~k&1}(8#j;~r?GYO}*WPRs#+)DSghR&a(usOCu)(o9#NR_`rswrUOr8YybW z49Y_|RNB%Tipz_qo*_@FUfF|N!9*!IUn}26{SS~wd&iW%8{H5d8heIK)Qmchrk6v<;i?ZQB)^0Y}hTC}dSm$h z!9~J-Eppmd7^mhz!^(K3oKggk>}+B#-vG(3qVs%k#s~*Yb}_v|gyB%pp}qU%stT8J zPE;JqAc+SluSq-&CvhMJEX3urk&FD%>%R-J7V#t?#0B(N$Dmd;_Wjpd@#t5w1GNI{ ze;wriu~x(!SA<;55d&IW&>^lhbP>I=bbn@W2f%rbmm3sgp!u=m4c+OI6-AJAuMbW# zw}wdGD5(AHLCrUt8)~ZJF77-1<0FoIY0ONW`$-d9fmfZ^(-E7Acx%GKohp)Pmx})lZKQ(9_CuS=IWC8i0NP!II6C{aIs%oGyR8s?Kh>{0 zwX|$ejga&F3{eBJBx}gq!T{(XZ>;mli5n-J?H`1+9L8E9AO22tR#a;O#;*vlkO7l_ z$cd0@_FdS|nmg(lUaZ%(YekVt zRfxOZDGn$a8*GK{SwCi;r_}@9r7Dd_m8} zlOvj%GX=wU6-FriC?7V65&n?4MRawSGN{Z%o}gIO8cOv%xV+yi{MK+D(HbQlm3jir z8~v+PL8QyUywHGvGL0ccwHVj2zCFt+#msDcEEc*Vra)yUR9F7+Z}-(U`|{G(YMyHg zMY|ZBC}y!x2GrLy(%w}={N7&|hLM&Lk9fn*%xv%u3o(h7#eKyi8Eqac4pm#``+yWK5l$uX%B4O$4tQm^;LE)~ zfAUOje|I9~>SQcyzhITcH&|L|mOFvWH=bk$u3#mJ{xwe5VBgiY9S z3F^`;Sh~ovO2l zFIS%mk*N;etTK02U=P_)KKOB|_cfuR8@8y!xMT^jv-)61nY}#CwlWP}nPyxSRvf6+ z9IVwCxJB8*IQ4nD)TQg>SkNb5P`F9UPv}i78*+c8`+)#{q*0yW5h~qNm z&&CXS6eH?Ux@`%TW>I%3gA*E^`s%v^vYMIO!lfAgJ8Se>-ky?^7 zHG_Bj3kFX=ROE;0s)FIhdPajG*XTc(2GNJMT%)g5;}!y-U+WArgr)@+&G9?JAFR}J82H}_ORoPIEYLco-ZnL@jL0C{~uRh85YGG zz6&TJ2uOD$-Q5TxAtfoD(%rFicStwV(hbsG(jBs-^hz%cXW)1K*NIOH!^Pb3#QVIu6KuK-C2KrmubCnj{?08_-Ax5tNH6QuSYBF_495l02M|E`8m zUzowx`KWme{y-hIbopzsZE2uh#uO{G08^)6=Z_lmP@TnOWvfhkTpZ2(+qTGEb`I~yCP z<=Binf~jPU$5k#tYTDe6undf8%bzy=K)6)3gR$0Pq%Jv}Ot&L~)CR`!SU-Fi)9CN# zPE9-aP-^a7VLSv=4X13-pdZ0}W=iiXw%+t}aX*5{@xkY|q3hz)I5IwwsOp>cBg*NA zy=5E52p8kT4AQIAw1!o(fqKP_!dud}qmrMecwb|69d!qA1C<(+ zeTD9qrWBVgt=(0w|2-T3!cVi9u6-pAm+dg6(2aPxt6V)bTe1?tv|;*U$O)D05WCn+ zuoR|F(!;a32!YKCuLRFEva4J(FT1!5hEuIT#Of7HUFznsf0|m+f2O(|yqNk$_}Nso z(ic+;4_-`-n0qm`!Slt`zXva->b1X^iah^fs#^Jrsj~C`nVNp-)MWkurT%m%obq~f zGRvjE{bSeLQ2pNX8Pbs`JB53FQzgW{AX%~f#Sphf@xlecOHws zW?_UkWd%%KyZ}^zR?<(i!CZ(PNDrc)CTs8HVCoQ2=3kqd3WLC+Fs729K$JE>Zpwp< zCSRFml|pSlY5^WEfE~lRWtE^^2O5jEbFCjoX08(N@Z;=_U z&NLd7T?sd;nsir=ikUjKpY}0LJqtuh2Q-7dmuA4Q+Uk^<@Km9EB^Hx-Z#UmUw$a@+ zTH>m>MUYDH_up!use$Qy>lHO@>VCkL4=S>O`cL=cY)T+bXW$w$gZWAiQ8*)*RPG4y z#A@l)N`h+pOEaDWy)@%XJ+!MXYmq@}P6}A?NK}@Z0TlW;w^f$`*_j#}|KzGKDzcL0 z?Yh%TPH(tBy349-$NSi6MhZ!Fdx(o8|B@Dfu&Q!>C$pKsj(Jw&pGB|k@XkQguf1mD zt4vFFy&V2OQjI^Su;=eWaiaUn(8CywSXI4K_2H~^m0^yKW@7b!l`#6g0;H6wJR#;QGVj1Wi7*bD96Xe&p>+Y5PNP>8}qB|U;Kq__Su zev?PJ-5-3qem%P$8J>(qjtc%TC%o(xDLJbN|h*j4s=ya>wB|x zF?IhHF>h6rZMow7`O~2Dnb}|VarKiJ$)(rKxOlK;B2}ZGj#+7`oKjGr*5=(|2UB(R z2BGd=nu;7ZZSK5FzmLJIQVClPUKhZy+Qr#ItJ~G_vCrcrFyQ6;t;U{rM9<6H`|AF- zf9}E^`4#waYuD`wWghB#K36wglBXukKMqNIfN+B<&qsAx7MWQ!ZpGY>+5_&1{7Ohk zW{B1)Stv5GC1Hbde7%oxk&(_T1RwTXXbdepd7+K8^gsXoI*}!kEp<9xe17@8u~8U3 zhnbE1=43$c$l6oI)vUgEUS_qqb~i<1bqS?nrm>`)^bHYhLq{XtpayLNjqC0iWzhw5 zzl_bFKPw@Ghd1=w^rOQ^;+_S=v@Yjo;33>250q>2z9y2@J3lJ-O5&jSTF-Yy0>`LX zLf?|YKnxRUOCo0XCU5UD(++pv&S#0nXpF&sUgSq>xsqt4{rURn*NKB)k{|F{JYU!6 zE=PAEG}T4Hxf>^*=qm}zP?tfmt-P?Wm@X>R^$II_D(!|Cjh&wLv5J|cH zn83IQeEV1j{h(VC`*B4I`79MWAm9nHfjdd@@yu*7uY{E8SMXzA`BqGH8362v3(oq` z`Ot9vL?gY4udxm8_%sd%VUuM=Vl+@m5!Fo{gYXTpTKCqe;hCCDV1F~?R&RrAwqQ^+ zMmA3QzI5X%iK~dWWegdvI!sC{LS@U(5@B=oPOh!2^~3A4H@$u0|x8g9{`!I)R&tuTQH*5 z^zXa2400R4UJi;=(T}f$k3_r#G#K{{(V+jhYou}cR+n7#igMT2Wc`(pYAZgps6TuM zyIWnN!CWqAcqsevG-Qa7i)R1-ZCV{%Od#-l=di@NErSoFLTHWl#MY3lu42K(!R|&M zVuSFOt+2Uu2Llts#6dAptS#y}pSJvPUnYYFvVSCkXw}QH#H6vW?nyJ^KA0F45OSiz zmJW(h;q(H``jMVftqbdgSxwk8GlikWNO}?hB>h2DKx#Zj>Em{BT#>>j%pQm%h4A$D zR&G`zdo}!kgP#;b|M@!K$%g9Ip!k2Dtvgf)ZW)-7A&LwEp0xs=nZ(7sc!qPw7#rww ze@x9y)A-}dhZ5J$enPB2g092{(Qo*Ls7>kZzaZ!K_`WiETRyW+5ARJxku!;kLAJ(c z^E(|qJJK5yn=^3=Bnmg~k4#VSAf~XZ6@bEy9?wJkS+4qek>C^R!v;F_X)Qe5RcFHo zblgOD+@`Z>k1j8^J@p1+sro{;SFE2_19w_MovG~;PbtUXHjo#ODCLi*$Lz;YpV7|y z%hkIa-6)D$?8CW->#3e~46P+)O-1-(j1k z&(FRM0oKUatYC~(_>(YUBC(m!@x$@q@Y28P4MB8?Gle0Iei#~sA)94gq9zMS3XX1; zc$Iy9ys+S`O)xuESF4JnI~&}6cIG>ntf89oZh{s7R%H7b_LJL4tK180O7#n@a7W@Z zY?%rGySs6K{U2<9$P28~=wWvB2i+`XuEFfapj?QpkMkeFuPE=4bw+?+(3S*Nb8RT= z0~>w3m#b23hr?E7FxQ1sE+Up-$A4{tDGqx!798EHS?){Y-oY?R_KmB}&)E;R{QXL* zxyA>H$c+4;-o(<|dq6-mZz5pqw(Hokb*?+=i_Teg?{?rij)$wSf#-rdpVY%8-7`Pu z+;`SucBp)F9I?Zf$4puheBI(3)rjG&8{e8hP2|a9{W{fpsNGo7Z#d*d{_CK3Fm}5G z<7$$V_7VW7kMuLBJBYlD$baMOMHDI(n{HgIrh=5@yOY$fPQ9;WR)>-5Uws!qp_1-? zWAVBM3E(~ui>h~J{aRt=kD$M=HC_5v7+^h@kiFgz%ea8d**J^0)nfmMTWVYH3$oxd zGE);XJdB&yk&el0)T<0_{lDJl(KD4{9Ei0o82DhWiA6TJnbSt?ZRc;VVPie0*zRp- zv!c2pS-CS+TtEMc4_bRIUrba5;(?P>`t>|eX9G)Rew}r%;vBtBP0!fMVfZbSp7D>M z>Fd;5%1}hAu5u>|7=ywLU}6U;fNDXG&F%2;q1i<1mtCgoCu{DwxoGln7~no;J;b-x zC&mlgR$!ZL=gRl3S#WMY`zTa``v=E2<>QE_qLH8=j3?0d8uf**LI{GW{hvmLkGc>=!dH<`XZ z$j@)XB0&53I`~;MUw!oYBmiANdo*$pL{dci0__<J6ek2 z&Pzks-Cxgm{#v^5m&gyp*A58oSQ1aBkJn){nt_R`KD5P7%s2AyLZsiLX} zfXNzI)1x=ACmAy}PDvPCA_9Z20r+p;$^rN?1_l5=jlaJIfX}6Uq-%!RK3U(g_ZKy| zEfqhr(mR`Z60!GV!WT00GK`rOKen`T-gd@Uvjd-44-^%sZn&rmKRwsw9BMhpuWA{C)O66G99-`#P(^Rvs-VEmN;w!E3nc8l zF5O>2oYxNUN`F`Cs;^ek`Tod&JGuspY1-`RMqf-#Mc*^mCu3YhT!p4cv4*L0IFk`X zP*X&3rkzJn8>7vZ<8-~AX4~>NdNX5yswGfzs`(6ywD5|`)A##c?e6y|qu42velP`L+A1DHl^?@g(m?mEJ@J*k$W%7oUy0?LgH&R%5%x6{y5Gx zQ2T~+uPx_q;y0{MlWBYw8AD3DC)k^x#PVe`*tW(c5^VB3j^Eq*yDOCpaUQEQhJQFG z&)5sfzBAziW@CjxEY?`~AYi01qieAa7-@tvo)Cvo3*m%T)`crvq?J}^^3-HN-}$<_ z{5jw;l*$EEVwt}6>>Q#WrisAka+v0c51ibfFOUzTcPT;%l8XpxmAJO1 z9Z-UlO1ij?Rd^y2w@+a5_ausTZOxZyXMIkhktTwp;Xcj)y%8HfJ-Ihu$v{F}n$6f= z;3bsKo;~cJmC*$g z9A_|~;c`^5EK!p5OH`=kmwo2}-F`M2SF6U(Bbx?O!W&ra{_mDQ1(R~*e9anO_e6+M z;1HrfdqHN_*K;NHa&!?U5!}6qqaXjU`Xovj zy7B8|IC38Y*o>VSc?J=aD(c}Nq8LK$`E3VYhY#gNOSTCTGLU*Y9TrHBn#S~b@k1zN z0+5JyOp9eE@qhmrl?WGpV4^Fg=2NEr{EpVfmS2TZD46SgJVW<1l{`-qxs^a?E)Vmu z7!R*pbo29)w@UGfD*J|I?2k-JYU>T=UBb4kJBu|=Dr(fkXI{841V zo6UkX9DWNx?W}t|*R$Hj2-E4;$FQA@s=uG_M%as~jZm2Hn;uIC(5zn2%3sh%(_hfI zp3yE}&^+<($J)Y!?@!$OJCk^8R9S8^Jg{)t+ZmDSlT=!gkN!p(7bxIe-9G^0ZYtT% zY0N{camL!-fCH^@4oW+LCjSDq+&A5x=*uUw9JKqreACYY*kXUf;k(yDi&ghOWuxd0 zSU592{#>?4t-xfu*;ku}7RM(R6zvwA#V2N5?iQTJ=fIbuLYhMs(FceFHQY`6t<>uAlROmKih{vR?%v-z->u=-@QKaFQ2DN=Cj zeN(IkEx;aj&@Jlr;VLeyFX!biyrc_~! z7bCrm*k@>yd!79*{xeeK#mE_2wAahuZu@>n=e#(13pn}nbo0CDb3129-^Xf0Tw+kY z4f>xw0sPTGw8k#e<=d7^ZvK#tavl90Xq_l)yRV83eQms z+(Cr1;V}213)p#9hL#>$97o6+u)`!g{jJO#VQh;uG0nAQKiMrp1tM85we*R$rQJDy zB{V^z30N6XqHKYcQP;p(8!gt=f64|(%P9ze#v(8U>5sByO__nsTLI8e1Y6{dnOfQM zR}ceiI9j~v@>cp}RzAhp0%!uPc`MIot>%(V0NR3^yEb23F>v?MNd9OZ7Fe%k1JWzg zvyzRH0Uy!?bZ;iMHlTagb)7WE83b+sXyZ&gStmS~L>mxPkIxis@Akoxi@$Sz#`Zi5I#u;7c{%j;x2Fx|L#qUQf3;)ZTr<@2XIu+}F+| z|2BOZ(Ke?;Pwy|nS_3<8t%w*N26EN`8!eP5J3y_bffu0G)c+Jvi?Fp)<5sBYytzWe z+0jn%mA7X{4!_;6K=( z)n5bGO{CU_I5Uvh&Y6#CwI{-2=nwb%x_MXmuKQ&+*Ry47vk7#|zy1;aCSrNtKzzL5 z9omgb0oS2wwA)*;8@ZJeqrdjRtV2~jGD;2SUeUJ`p8cLtJFh`rT28G^OIZ+KDLRuu zX}Z91a}rm4^DmzvBG*XhQv|K@gOcM7dBljUR)ns{Sf4J%h1wKKPSV{?|NY*%?Cy!n z&r8|&4Ua}xD!`NfJPhYUBKcRsE6d*@>bmjz-rZhr?kpvC7>u{+I?omw|MI1IidMhv zJ3r*z&p2I>+v9uZaIZXb>{~!_fj++FOv6eFCDp(8IQxFT^gW+_67{xYq`ny|?@Cb~Q4$Ex!&GR(huUm>4`>a-h1EH?v3{1x=9$Qu?ATW~nkD}+^+ zajhB`cV{mL-L5Vx91ahz8rl9KbcTy|o9Lk-C7(fb<(-Uue?cvftSl`{EY11FtxVZ< zvV^EL=KFYlOt(o?aw{O+uPSzWO;2+9dNErkpPbm=zZNJ~e4jO$KQtkXTlEkrn&CCA zOz^w7zMw!1Qk~ohHRSQpJZ1ed=Xlhv)a#8Pz#r@7IPI1;?sIjEqb>KKLSD6Ye|88G z!J^FS96z~Dx-0TlzFc&=n$z#R-mKDpfbxpA-(UXwJ7K5S{I2(Z?Vom^tH$Bq=SqrAen8d=)7)gRApuOSmp z_eUzX3m4GSv`!i5MyG{x5=M%tXpZqncus+n85_9r1UHbM*0D{>L}Po0e#RXmm(J%% zCvv1?|3|Ie$)L|-upJUHjwWqQ%~>za<>p-TtZiN`T^dugT*63rZ(ecI|pX9JW={d2bHBa7B&FJVgua56_oY zRSa>it#2);arA;^$aZAy!slgtzyIlpR28JnyhxSoUk&W+WRLwEgH9_<6NQAqhA!;d zsCe5}Y@g?~BDmMtfPQPY-^Psjvj^)wyqk(gxPR? z1Idx5PDU%yjwUL9*XFl zRqr@CONf(ly|wI6(x^BN}6R} zaNm4)KeV%YPx`L#?{%sn3NM-O=As)jNgw+re)Wm%+mdLb)l6qkz+^2+LwbzkOXs7^Cj8OZNjyz%f!scz{V>zpTTvZ_C=QOtUeG zCOP5mT*MTaq^uTkv$C@RzG z54%1iHhcMZXsRONiJE=`?{D$yj?<{m-+$c+WHb7IukFu_vvc0TR-r%m&W~3N#t<)! z`xZ_qdXv7j+6B81fzZg+l2qYir6B4=_;;W1FLeHNHJh>FZQXlSZ8H;`#*fb8lD#eo z5Tl`@`ntV5N>0VCM{vVAaUk_5u}a9L*xfWDCEq#esjVREWG05VqR>hLH^d6vR5DF= zCMcE+c4e@VZ`joXpI_r|@sb)revvuy|vhCYiS9+ejMhm{JesYc7A0%zhC2QG& zo$M1DJEnJqdt6}|RKyYyKef|sW*rcmkZfmOmJ-IiUtw58#LC!O)UdPF4+TqQxfV1v zb;|y$8Ot^BMY%v6H@7a|Jc9Rp$kX}gO0u^wRMQkUgMM+SSo{w!^zB10w(kf_=v|A~ z#(uQo9?KZwtM-Y##s}lvtMD>YWFILV%QjbLGy9Sc6sC;&TbQGH8rp>#co2+!yc!Ec zPwx7!&H~s^1A0R2ZJsj41bfCYZZ`OQS-P|PuW##9s@~R*3p?SZw58lTx#apbVePF= zaUXjDKjG~e$Li&xub#q~8;ML_VGH^{>hew&zae{b;l?tFx0Pj<560cgCw=vxi?bIP zKIUMZ%iC0iwU@6TIJvU2hI+BcuTtF!e@k2;$)BT9`LqV|*Au1k&ei|X_9E{z^w6Dt zmoGo3)?v4UWy-^I%Z)B^C(s{kr&Rqc?&l&PF2T&QjboBld5-oXz94>_eo~zX!Ke=; zs8c_2KURg%W)tdO8fxxi#Y$|#ofP}@Zf~E3zg@@9O9GdeLVL z4Vt{A7`at=vR5-c%CB8B^Az3~=v;xUt)K80YEp8u1J;T%5t=zFY0>6l591T!+v(fX z1@(;hym+Gy(<*P8A1g@~ev%qpXSLfW&N&D}UmY%QdR8MrLYmAz=Bo8y0;+UkNn0r^ zeV=*<-6mE`NVN`AN#}lhdfhuUG^AP7S#YMOR3=r;d~1{je-+1$ExrGvC4VaY+LsRF zPwIgXR>S;ty9K+aXwaT+lx0l3-CJ86%B!M{Egm~3UdyeERk&SdOS21KrCFaQtcEoT zOB6mqB|)ggC&&q-6Mloun$m1`E$f+xon9n8*CMQ|ft_|1Q#i9hk#E%UBa;*-d}p)> zP;w1eya!T{p@yLmY@sq#O?FFBw0zehLlH~S#(bW+k3k(xcrmpCmV-V9D%!JXxIb1U zAl69rr6nZAtC7o7WnU#AyNaSd_Z>tHAFW6l@;$?sPbX|=!Sw_UvI`>%7985M{}?GO zrPL%LmJx_~jg~rQTTwsfIc2P(mosql8tZ!$!`(w4q^7wfJJ_4m!j>~aVwc;-R!c~7 z62AEVE#~gNE9~-!Tt=jPn=(q~mItNEYxJwbYB0`GpGE5=4OLo!l1M;8=?9fVl^UZ% zA76u~z2dCysN7Y2y+^Nit2!T~0J-H#fZS6yZXbu)%H}VOrgr5cPOQOWp{QI+RqY@2 zW|-G{nWLN3KFax2<3-it7dPpx%Uf+T@Z@rjHDwDq_q@#?Fklv1ePrA`FK#-{@x9m2 z$r16n|3Os9m?faTpex%~8NAvI0daV?8ZsPbys?YF*FcoGY#}lhjN-@KP<-FRYa17N zuH+Vdu9q_Ph@IEY*~zchk(IR)HFSLGb$|S;>jQ>AD@_KbU zzt_XI_iGn67qJhw`k$BVuy2a3`F+De&5NhmX?;hWEktl{yq~02L?wMX|NfDKjTa?5 z6TZcmm-eW-R%JZ18y!7wvQsFw6ttYRl6p+9wfPXPjCZqAYLzHz5$oaIO&1yOdkFv7 zIM8AAN^8dJaQGwbsC|ZYXd3OB4#v$|r`P?M3hz$nyuh;5CFbr{&MH!;1!p6Ww`M@z zx&wLpHnubhJck|I2VwS@Njd z_Hz5GAbBV77_O6c4jTLNBG-K^BOk4Q&r)KpcF0_f!KJu`ZC|!pqEtn4Zne|cP5W6l z)2=MUywYpV6&t+dA5=AECbJWa;A5M65ziO^`Wx!X}@>P!oYX$CB1A{`ijI$^MST7D%l2y#w&KDZD>gSC$Vu=(O zfyHoJd#>3V>8K$l_NW3_Eg*~5>A5!IcXARzuuU)9J5CihiC(_PUNGYdN&$>E)Uu7tDdD z3zpDULlSM?$r$0a364-GTPa$2PtiqAwH_ciHXziGVRIGB5MkwFn`(|V<8^PDb}%Mu zP_{JK3r4NeN}kxD-n0r0D7=mp_QVj%2DPmEaj=thgCeq!ve9`fCKfrdL@>LXPz!!p zd3y7Q+T2N52}__K;}7{uCASR<=SWh{o2**1+%0cv9l zTb!%W2Q|Nt4++dyoAoZM{e>@&q@a=$O6EDW!57`u6v8*m1we+HUujF*JmD`t;3{*% zGo|fDo9H)xv(->xZ2Y?Yvl|)5yzC)gvxx*eR!BHI0e_wC8Md=5sHM+0ViZ($=WkYl zQB{isvDle^XC9npnl(i`TW<$k%|FCtYM5|RhkN4$Z6TDM!;#r;VpOD$O!(dwPMzGG z{)O22-bG=Fk~vM3pN#oxrA%^cjuMm~=VmA{UYrSiaIst$D0G%;VhC-b|a z%Gzdw4O8Sz{c>BK8%H+e+Wx%ktGA!b;N}6RhIg|uPb0>G&(rVYr?Umo-5Kn<&Bp#3 zkx%Sti)8QVt=oTlmhq3D7>*1Kv5gGKJq!#@d$D=lM8`M!zSZ|JF31Yd*BM_atVGri zq*^{_)b6tTLis7)^6R&Gl3-TS_G}P$@7MDJSKV1XKB0r3+w!C_X4#pWAwwgSaqqA? z&OFX1OM4bhMxom^Es0{7a~q7Fw!7p9DWNO+?bdOv;c;bKi#DuXg&{tEPRPA5yDmarP2>GK&vm|~5cL+nIjvxIBw44HJ}nMW}Vuel*=i`Er~ zKS%4gd6IaiFf3oC@b&yszK^c1DwZ`2r^@2HT-}}UeO#IFeYoeZ=v5Xb z|Jv$)fFh;Y-iL9=PdxBl!6W&0F3|Oyh+-i&SUq@$55hy{t)HoEIUs)ao%(C8hpsk< zdB?@14&kkNhnsojpk+r!tTh8{IxEP$=$&9AG|&%9B=iRc zW6CEqG%HvXoxVvgeE&M(mu4*;CHcJ(P0>Qm+MGgcxnPfT3pQI88s1rIk!M$xtJf^B zts$JL$@yqpB9)HY74XTNH+6i@?uVM8fI@5F{um?tEOz_1DV%D(1)aC$cAnKNsNNc) zd>RYJ4F=wOzjhV(GK6*3jAO|i04vy75I9I z6Z$}Ju+$m+ts%iuW2!@ne{9)6q+|Ax?Q`%UAB3gSy9XLNrevZokE`o{=z`I^e%ly& zI6c|lP~Ie3cv!RCJl>4|u-toh>x#b6bl05y{i%Wy0bxM|*2_vX%qj==9|BTyhuhTF z@OTfI?|1F0K9_rTfi9P8=Fd8Zp%CTwK2m*&YlZSU#j>yqZZ^7Yg5%bHC14ZH}4wx4BHahrBSfG?vF`-(G2ouaiPHu##EF43ho!yOHi+ zOML}M82G*xZ||ni!&Yw{#o@nm7*_zFG`AN%V}}S~&CvZeSKLRxs6U?XD~+=@U@Lp8 zlsC0R9a0!7cty|)kLXUAi3k07zn&NX9_=bv~B!9bj-|< z7o-!^El0V3p{Tt zf7^YFJ%kK8;VrBPc<}hPA^8BQb$4rszJUH5wf*A2TGUGK(zSV?cMBp56R7VTAPEnD zn7mr_Z96a*1%_z5Dq^iI>QzkVb6TWt5}<4rG`eVZHkVe#W7QwKYH_y?Bc(K>kH4h` znlcdp<3Hy3*w#C8JcyPq2XdL9t5t~N?LsS2=#$wL4nF!W;v!e#S>#f_4$txQnGJ0F zpJL%mvY#qls)@X7poU_Dzr~W z^^e4oaOw4-#}|6Y>9-AQ`w;4S6W#hM7ScG|?~`2QGwR6#D9nUAasQ?#Bly3Rt?l

e=o?L9Mc@O={4fi+1Pwk9_6@DgS5+vPy5?L4@40k^~U< zX=rUu`7KU4^!=Q35_b^7q^~qBGL%2GOvwHoTcGsj<%G=2$O~48#>HpQKq#g`OBM$U zlAeO1Hkv7?Ws!&l8TVYMiyu6*a&b|e-nkN3_7j)PNt5lA*r1ih#mwZ_&2vjjWv832 ze!TT5THfTG8#RZ_HI+HeDYOn-7Oz@!XVvlpB=l`gZ!G^KQT;-K!0LsB=6@ut020~& ziKO_Z7ZPb!FC^S-H1VL%BnIDK*7KFa5=mDjEaVxY_55A=;F;4fvygnjo=aEZbo{6g ztEiL|({fXOOGEnN&f+&s^!+)J6J{3Tgq!JxnaL2ur8NPW&QE_Bh`n?@Vo^tZbh zjkbm8wIE5FwX0v4^S9b1P4XmWZvDuMRh`D>hq9V*n}?rK);t#I@!;QPDxEyjD+D&b zTW0ljg~)|jYRw9ol$VnQ3ZJ8-*MUp@t|?)eOW{F*%&Y+i(dO7WY?`z|-xq{B9Y0U= z+f#Z?(K^8fZND|mM#_Hj!>z65iiK#Cjj)Y@__!s05&1*ZpT=pQxBEVRQdui_$@d2; z!^iO}rl$UdSF^YMAACI@AO=gq^)2tO)SzSgI)(M{6+G2V8)IMDb!T8(@~@Tf&hWHN z9HuIqYx&g9TM9)KNuw=F=jwl8n&M$gR_!~^FrI8)PaUm7Oe$@_f|`a7Qq8mV@4be# zd+Z>|_6-B8KUcR{r$wgoG)RIrG7#RsPS0QLWoOfRN{!ku_W@bi8!oiX2`9;%8t!Eu zDb+(}KUO_DPg&U)g`$~dVA;xztP;?>ZEy_wieJNG+it=i*q{3)wmK%AVD&(vCO+z5 z*&6=8rs1@l>9)x7f@3=;f*w29BeFyrnZSxLpxfZ#)BuKXN? zqNTgoFh9l3V7Q=XFS=zEpsT8DxS(bI)hR&tIu;b1a{L-_^1C6go`E87yJAQ0%5A%X z+uht9#Kt=XJipejXy`kHSTD`o(byVVnDq6Va=EYWO=HD(My;0J67Iouf6EG3M$FKi z(&fVx*Zvc;;j6zOa}z?ljL-s%kpl zm?!(GQE7?gdAEz!)1te>$xR|C5yDZ;@4zrW*JD1hXr%pXDchg3#(~Ce~Ql3gtRj5m~?$|&Zc^@ZM>mT`B(Tp{-ZjaC|+=K6$>Yk z-MgZzHeR>dCYyL_;kZoZQA)pMR+yXISFEdc=N?Ocj8OWOmINI$?P>E+Pew4DydX!7XIX_ zA4MZaFIw5zh(bB;TGs2Z(`LgH=*x+pY!+^HZqHeL?-oP@KOTLLh+~gvpL3hLZOXD; zr-Lr*^)3q1f^NUn7EcUivp^7yS!;`DU}&I}pyg3GG82_U?i#lfG4<50!9}&AMeX-; zh!wU+Hr|SJB~k4V^eQtQxf6ZS&}HqF*!Ix~*6VVkGMU!q&8VV*6`R-Ju7G z7bSYdy=Rf))-FS^u(^w|-62X-KwDaIbiF%o3Yn;J z+nu=rQ&em?_n{rnEnPhLe<&)Hp#{N0h z@Qy*Gk5;3Qc^Zt5)j#Lbu|p-P0^p3R+R023oddOMc%kNfdV;E=P{$l`@v563PwI!Y z0kHaKvG8{GjNCrG8#8QB*`L4{b!7jktLt6==8B(L)0etku3j9vA4BM%;Fd*Dt9Raz$bRLOU%LpQu8Ot03G_?M_gy%+c&vPN-Mnb09$?(=Z`d zMiZfF@Cpi_D;D~|-8C|vUmQ%Q8B~tA1(^%xqT4I#Vhbh~S461yqaxolSZGV7l47;b zWg6LC$G&n(v)o&aYPWC|Gfd^iC5t*VI$i~o{#pc?8QIlW4TAD*IiZqf>0PB3sf#PB z7X9EO7Cg|*pO_QySc!e{N*gajMdaA0@ETr13~YQ5Ny2!0b03? zs@fYK77uxK=wqiN6L;f!M^5c*DiXRsA4L}jBrP&NMH$(-glLd}dR3NU+Zz|?pdk|H zRcm-SAxo~Z2KuTNqWGX1Rt8i9BUb3AG|lzbwX>e`Mz4BgAGM-Elq+N*DRo)lmv$U0!L<9y5cUDCZ|^|3vz(V2F^EL zCnfO2=^oiO{2R6x6V4VlOGt62(NVn2XW3zG9vNw|JLlqSDDDrPSF*RP;EAuF@J~?C zyOmGSt+@rhpZYOjwKX66a_?jRhRurBsZ6j~XM#MwP@|2FW>bakyfCe()x<&jN@FAO zYGX1E(aOBzjK7VQDR#m?&0@<_gm?ywD82((}!ABo$e;&_{(O9^4T6w!;7$ zcPpv2J%nu3`oM2*u^t$3BU@ic7lFH_R!n{V2OAS{r%<{zpM% zM|s{lPC2^P|jgAgc1Q@b^&hgp)*(`22+5ElQUy_%&({BV(17fmu0 zR6<2Cj;7R$z3VKp5K@vwy?ZNEB`h&E{8dk`;|%_01c-iKTvaAQb(nZhZ59GYvdX#I zaf!nSN9=_bMV`=Rq`cNY(jA=HjN=k@aBYZ%T2<={cyp%bFJ8G}9osB$As8ob`Pc7h z`Y=LT)|5N_8j+m}aoI3|?@b5qxaD-@cMWX9mSuD+CdQUO&So;r_J8}K7ZAN>dQjVj@0ItrBvX)(|3WubAzeJ&~|C~eM-fZDZXPYZA8`rmQ1IJ5>VB_I@A$K&_D{ja3f%k z<*0aVU{UO^S~Dv|!)|E!UZ6+>|By=oSH4UZH!Iua1Vl%P8U}cfTS|QHM~2q^6BP9b_TG;_0f`*ZXn5s`Gw-SJW5G z_E-6tOW*A2Z2EcTY&zR$2z|jku%k#7x0EOBGD6N_9^=9-m@n8lWNUC*cRcSiDQx-E zOqBwHN54Fmor4fr^?c`Hn-g)pLBPW5!Mk!ra;U((Q{D%d0`0I#z3Cw&_x zlAdM(TU0Ie_G~-d#EZs4E}1?@b3Q{9fZhh6w_l*C7ha$pU!ciY0BGukXK3#6N=>ce zD3;HzziO7arw==e(-EUfrCzB(@+Ix;#SATfS5AG2zET~o4Cmp~`)an3IQ+5Lz|!lF z`Ev+ntRiw4BdNt-e3Te*{f9Olb8$7vwiQ zFUV0wMK$EzG~D{3KOI7%k$>^d(iwSAGGaRU?B|ooe)5{!}ISC#zzu zW{3<=q-?F`@z^_+!367Zr|LJZe@>V`*ZcE-*Ud!-oS_HWkG&1-W8&7Lwv{LW;GU>ilC|E2`wd7L=zC&I1| zBfit#)3AtYF8T19*gtPt^a1e^8jUMo2~?DOqsQ`IC@@9n46TTlW_@x9L_t>8#tja! z{80K$2~e+dknc9K{X>PEdpwU0ZIK*)N)~G5Jr0fE9c2CTHh~T|MWO~+R|;Zim2`Hf zm4XbB3vA;hl$K+~Mu6?-E7(+tjm|w}%)cjB)?423Glk0NFu115N^_JeE{0V~5 zx#@?jJo>{gIYx4cU-CUkhVt%hRwzHVS;|L%3`PM^doCCDQNI^dAtz z9qFcFpv=L<$Ur#owc|!|4xhsjN{Jf|jZ^;ITQT-y@!->8#rai^&+Yk|&*LGP@6A1b z;*RCcm+iBu9pUUXdP0hLF4S&BB=%KxPA4>VWA}B+Mk#&E3u+03ZMEpf8f*yPF zb1`bg#Dc@78)?y(OkL!DPpgnPfoySyv;=XCkl{G3doiKo`g~u}yHj~NIv-&5gS|-R zc;!WO(AC*pOwWn>?Y3~9b=O<;v9j}jk@uDXRc-CsFpZLebSe!}(j6ioAdPfLcXvpr zbV-ABOG$Twba!`mhvYZcLicv>=Q-#7`TaP5=2~lvIj(Wteb2dSHk<8&bh~5W11WR` zr99pqwmeaV%L}p9aS}Z7Bb2GY*D7wrne=e@UuB(e+qTlEC5zr-B4{fbJIpzLk@mU# zGN%}0MyEMBexfSf(dbcY5WO)69izZl6=rlg;c;tQfVIimDyXrPDQC%adE|JD=6*9b zo}GaEUb+KeMwz0{b2~ybn%xbO@UlW9-J9VVv%o7vJ}y|(Zr4HLh%c&*1a$mJgK2EO z(Zq^n3WbEmWkcb<1%o7ELJ~sM&sOvp(Dl*iaspkKS6nHiuqBN@>gUQlDitr?N%Mve zj8to&8xzc!=;M*=cs%DM>ai3%tU`AaYepp=KSfVdDz`gS_h*3<`}jG;&K1w zyna@5jMm*OKM8rTy!72hwqtVgo$LK=%rs$cx z!6kmDx$#0~y(F`51#Q2Uy@V9kjvfoD?YxM?c9CY{hbBp#;(@=vsZILK59@fByl{UT z>Ou8}p>b?kz2-@1A7;@B^0rRiw)G<|TN@Vov*%Pj_^asA=btWL(WeqVTS8oD2p^X; z>)1K&&JA9Qc5nPt2>dG%^Z9VPCi&B>Ft|(cn4`<9`9|R#&Z$;!J3-eW&%#ItQwT=1x7*;W-A(u^uDOXJVi<96Mv_ywl@eT^57aHB&Z~8oTplM%J zu`8qR7#G?gmRjKJuFGLs03VxfbJ>QJ!**Sw3M?$HNp5}9%al+1%JpkCD~zgk)>&Dt z%*ju@k9hJN&(KHls0l(+=k0NG@4I4HX83=G zRX-8XeOowBy~k32DxG%WB0@6fp4SfiW$%62_pr|!aGd_<=#N7?6WO1(VHJ*Y-8oM- z1Gi5nUJ@yJ!x52V(dO3u7_-l_AP!xVLkZ2R^XiCpsq;N=k*!#Id13n|05`xn+U+PR zLEQ9_2(?o$@J?pfPvSP&u~6}Kk6m8-Em1w^v&_ei3m2{0p$_n^Kl9!t>_p26sY=#vclExqBg)Ac2mRn^}DHV5%S}yPf z>L|ozax8=xJ)u`Da-3ykj+04Rh0}sGqrhAwHRmo7fq?eOW&-<|-|;$TUFy5+vmWBB z*hf#)^604p?DwY@RhJA>)NZSboCn2!%yiVt+!PZA@Y9eeZsj`{$x=zhyrR0BL}^n9 zJuCrzY7e8so!+ng$2gCK&vJNxDRMK_J1XGKS|6QcG%}M_VR4)H^D-~yIZPsnmZ9^O z#7d=u`FKAN$dgj<%B9D1ZV73}2ID>NDla1r{?TbuPWt(cTeYCL=5Rn5PCT6ajwV@y zbGmIIf*|)r%TZr^`i3TEpA<*`9yx&_WUDo9ZtysP`0gytRo&hbCj7=do-a2Ck2IVs7+Y z66YkVdR3(o=8jjeI!{<)#54^{eiJ4*H z!-`TNbXhs}moxIPblss*Hb~<;$Cp1xRxGb@dJyP;P!tng(lB%FROo)IR`4#Rbwn%8 zCX%tY1m5#SGq&f4kBBAJQ2Bh$Vr%-StmW;FvE$JC(|$fZ{_%zTz>|uD`-1H5)IFob z@9`N`P+45TtCsgyJz95XmEmMErfoHPtb$S%4jwaE=jY_PB1%WSS?II9oTyYtrLq)y z>Hu9&;qG$6=a5*$qT!0)oG(Y%J?_scm-*n)C$FeJxYT}co%s4{+03e#v$g&_Y>NmBDDS!z~^sEQduNx1LcxiDI%E)kkcme z^@pbk#A7~*!Lo~4!)Hb*!e>fbb^z!Ani)a5os`S0WWOe&#M`?`QR^A#E$cJ%2;!xo z;3poFvn0Yzz0k?Zayv1NiXJy}i*BjqXt*|4;vP)YHuVwS-GdZjDA@?*qlyr@^I6q0 zk-{?Td|2Yet847W<3{v1r%=5=V5J1aT7 zo7r6+@=QEgQ*VKfJkd5>=JK(|yw#mk$0@QN<;?hd_$iw;1T~kwwP?#KE@RYWp=IEA|;<#pHa9kF#dx5Ywp*6FTz-FfcMga7=w^4p75F= zYAbI{TMRrE9>A#2-h>urz^KOyV|MFDUp7~V&E-V_sHy$}|C_K9iQ#2JX6(%6i)oyH z<3Gq#_`3g)v(dtG#S;C06Xu4cI{5SO|Ax`KHy)AYNa?4?5r_YpDWMmc1XpSuE)3~_ zsd9$1mkwzqjVlhnY}J~H-S79IQgxMw&$oImyjqYfG~%BJ$GDk2f^{q(Ya&Y9PtiOe zsNV<0z=Vzs#!9t6kbYwx(c9L>x6ZaOj;}o7O?u{%wi%apf$qOxw1lV;JlAhE zkp5p-)`D3g{ZHF*|8Lv%ujp9}hIe$$KKtun5_WP)u1)TWI6#So;x4KjD=Tq#}fU#xKb zw-t!&0hOPA1BA^GP3$eesuul#Vq5#C*uND3_}Ifbkc-fPv^c zUtr*uzY!AvS4biMhfj}@Y#ed+?s@&e?KjK1o>`)G#!AMZ6Ob8JtqaLpL7oKO^pM`x zH5TO2{lNA{U=IIQiR&}KB%wfb{pCf#Gr;V;y&$u101;>OPtnUeo!wAu!OMO-&|jK- z$xiqvf3&oauZImqmq%)dR9G5=SN=394Hcta=G5eM`wEx2L&#DROMM{e#KkM06;ohPsYRdFEPKhTY7C)gsv+Xj+yw>HmyBL@yt;Y;r=FuD$jY)4YPZIL=AhB-=@ zfkipwtw-gNB)B1knZWG)gj}KqdxsTcC1|!cSd|Glkl>=MivX|yFLbsJAaXxjGqML@ z%r?zZ$yuHJI%Qthf-Bq*#Hz~*nAPKm#Ro_Mi-qkO*-33=KOoqSyu_n_t_GyqG%jG$ zWfVlJ1AK7pl@vwqJ*uLV1TS$0t^0lG^GoQ+W@IItLj-S|{^tSkx)D%{D(*#2 z6WvQX$hZqlK78Gqz}%Yz^N(V5JPVV;tX^!32OzCb%hm>=Co%`e@8mF zj{VAm-oFdlpINECXEqv~uRw$UHOSQdheXcvJMa9bUig1yWZ-icf8>F`w9^0I^NvFj zI7xugb2QI>`5&1Ts5TpaCsj~=dlOnS@mF@?{<8o8W&|rtI|0bIoI${pA=rDsiP)9y zp`ugT0_Elq$YpOq^&NxWR*#`&G_e?J3~D*eBUY}Mal*Zwy|-fc|@AICVgZ;$TI#OiX2ob12M zL4^_7|Ep3d1`@ObrBUH%3TNLr608B7Kh#>@i3@Z!nOC*#R{vTE7e;hOZ;Oa2PRX+k zWKcD^y^-xfsI+**fij|X}a#WSA_`5Oqo!o(_>dT?2%23rTUwXnTx8t8?7%(q? z>Xn8apc&lh!ZRv#btTFh^^OT-6Nx_}L(k%YS1Qg>Ei6b|!S8~A|-J#${4KzEJD~Ret*I zIs|Z~0yQD+$HH(Fpm60|m;gzfl2)8ZSsK`b+|?b^oo@=M}+JmMe(nZ@PL_2UMYe zdjPvO1A8d245se`lfO3ZX9Wl_s_x4sm#(+tAt1hHnw5V6KmyN4!@RtP9=3#B0b?KnQyGixpv_XEKgJ(W zwbq(i{1Oz@B7?UBy0C|B--%v)8&Cl@@b+fKph9owg^c(;*YQCVcV5FbUS3FB8yPl$ zi2C2%a`LYkJ-`kB(oz>-k7gsFHOvRe0Tl*ha4=a=3kV`j1acL<#hr96Q?Ty;ru1ti zs2c-RF97QJ|5Wbk(f-7+jNbc?9lW6~l_1Of)&o!+!3qLhD}eX>OG*%=mnx{&@g{+O z`Y;UE&jjv+3JaN;DlL$`^`(%#IfDB91caeMjt_F8-@5}>42Zw{^Or;XvF#4vm+PZ4 zeyz%(rGOtK{iD8{S^cd#P&NhoE?EEnGV?&!ZwCTB+5>t4%=JTiHodsSFuZx6xe zgW~B=o7S*mM02uYECW|uz)S&UKoYf!^bmZ2CY1{-3H~ggJ&+V>qCivjU=nbC_&5aa zq5mC%aT|cw0@`bki!bcp0E_Y9^rOS+51u`o4wN%MKQOJ}b3w)?3%V`_UAll=fvK)` zoh|!Ue1Ve)kWYSxpvK=*{|LSRrW}{i2j6l@4Ew`ku3+bxl=Zm|`AbP)e+Rr4bUrwc zehUh?E#N;K139Trd|wh}Z-%A)Q#mI@{NOpD$Mb~(3O2ZB1$xNvrA}LB;JO`S-9be7 zlOsmg3aGK>0lLV5RZ#D{dNe;Ve3F2NU=8&4`PH%#L>&`yzotNKo@?(OPd1Re+Hv=% zqItlr^$Mu_UI7}=H$E4!GtS^>V4f|dd+4n%fJ;zd^J7qTx1|*bHFW*XQ_sPJPN+k0(9#oL_pqI>ID)cuiQT`$$+M? z#h4-2V>9^aWgsizPb2gg<`sSbtNCRMiWaeKxG+Kk6cuN+R`p&#$ zW(Nw^8~Fw6AvyDH-}wGn;N0`=g{uBp2OxX^1o+v9(_`NA^FdvQ?DR^SQW+ICtZ>-ht?HpSw~QsK0UzDF;;zwh>uGz!BJU zI`05rSLV}_H8Dk)oP+F91p@eb#r_>6OG^D;2n{Q>%wPmSUGXl9V8YXR@V`!TSp;U~ z!@QvPFMp2a%4;k^Zxf~pU>#6Yzi0>rb+ zmb{og)r{ve8WA;j8O)N7&nopIW(J8K$a2n2mOL)KUGHoQ~?{3J->?RdxAgK``A1-}>!rAn^ZvmWIiy z$r9|7VD_WZ_P^W=^kffkJ}F^16r8_gU$B0#QF3wvvBedLm6=N-?`()ONb6X}+X@qL zzvTM`lhcrw`G*^VJte!wZ6izaLkCzFlc&@3M<7Q53BO;qr5QhOIs$Kg^-U6W`qX&D zj_pu_x$^AnhX1^0L3&`}&dup&<)U!FQp>*4!*XIk%l&Sz@wy|MA=JZurf+9$EZ(uv z?f!f~dSRhKRqFaY*>IqIqlTri>RdfWvqIhV`%h-;QJf8Jx6$hLFvrnqdfvP5w-;ZD z*99l+t!sB*6z(jej7}u&4DZaC4vaZ_Tvcnhx@~ZAHJsoRE^r2i9Po&AIPRydaBFoP zm8Mg2H6)jAUiJ&y@$@!M89iz9{mJe+n|jH3Z_vStLA<`ODJ_U^jqJm#wp#0D>Y$o7JT3g`SiI;JU_Sng<5Ij=3D=0mOZZrH@*)I+Q zf_5vEULM$3193SiW(INLs}}}wsZ0fN`6(CnBe@V|2;j1=#tdHY^D~Icffb0$$-76O zB@Kzsj(o2`C&49wc5h7qt+nO?o&OEZpC9Toh$h@8&_eMB&|J=oK+p@CY|x9B=;$8m zFoXaQ0(BaormTEo5bAb6NM~6Hc>bujx`|Ng;B`;DLF-(EK`*GIz=$n$WPGQgm{%QK zV;qBL!0hxB@Tm%5rF}R7F&g9_pCV3F=RXa#uUHoW$tN-dI%%o`2c)$4&G5@Xe#K4V z9kb|w?;sP6_=EP*AO$Pa_j$m;@j!~l zlMr*;B!;_fH9&h_;||!=9T_y7mjgC@1w8Nq{_KRNrP2!4{e?1-K?_E4W zz4FC%yA!-;{4@ZZV{iysl;VMNifRke1k(3=MqrZ((7>l1ek2fO(7-M5dtd#g=il-t%+4~|n*-yME}E8o^L(7@6as_)&> zAZS47-U`?SI79s&H1M!w0=(eY8GkMTXaNg;gZ}3d@E(7h0c`vCKEId!|2IgQ;sJ9S z>UoDY$PaZTDsca3lNj>$|K1?_mFTPcH=D$dZ%I=<$WB8)--QkG|DPL7Pw~Jw4gGj0 zJIIf4B`SDNwMh(n`+slH!txpLTb|0Wy?l@_ASWo_voc=8_-~$nfconHMCb~^h~gE>){B(5M}irJo(3djVGW=OVGGNYfYZmD z%xE=lv>-oFyut;}8F+0(`T_Pd?vefKIo$D^WKX`Q&%c~v4jPh>g*QN5y{*F%o9FrP z!OgAV{^sWA+&u&Y#QnoTFGK^OMF8n@VaY0l2_ngxO5h`N@PdahrtuYltSTk4N9W)9 z$KV$X_`>6;`>6;OIgo}%-JX|!5mIr>K{KPvFVT-`J`F8AS)=ec-eSn2eKqiTd#64& zTC6hI8y2S?zDz*+scbJA&1S=Pfinpxa=Ic&4+9{c`J2g5m$ zGEHI9@2eanQqclJ@4hf}9kVs#^mkp~tQWCU4tTxmL;bdk`Dkf28~5>Sq-CUwRYPU$ zhh21N$lg9Rfgzq(8~1c^se0>$p=(<0dIU~yc3C!q`SF#N9%Gt&*UK%VGVGxYXk!_u zgts|!k+x2_mfxdjq(0s+8CNFnAjFuI+$`bI{G{!~!Z=~IZK5y!KB@{Xyp}X1LK1a; zzxI8gm)WEFbS@9t?(6iuTZWb?+MW$;UG&1`qBSDliVpJ0BKjRA$Zr+!9AmDS%T{~? z4B;2Av`L8kD@3J6PQEyY{@|}Bip$bQXUICh@D2azXXNX5!Z>j4W8O50A3`Wlus}7r zH6(VOzZbtmy3kGecNFD+Fb^eU|Gs_!xz0~;35AWjs5A0zqhKZiX4ArP7JjAb6Im&D zSB!|ovR;s6LQ}EfKGe@6iLl7ma-%&tqrP2L!U1h^yk~EGN!}6Po)0J$&huWM&s8S7 zou0>dSkAlO=(&{q+?%jmxPiNOaXHgF8E`xdy^ZK|Jn(S6=oz>u)V%kjlV-bT-fOts z-@3Rzn95sda6N-7qraOt@1i9BfNiD@PfE-`Wsz(qaEQ-xzY`G{%6BsX%v=)Y%@%d< zclplR^w3?89tWw0 zKKBx#_fwD|OrPg#D^pIO?@p2z8a|u>qRc4qyWOlBT%Q_D6E=67LhMIKC-HFe^86gI z^td}KoM0U1hpBrNSnQTZyHeh#%p2j3+q4jdq?rQ|9H8YmlkGSnJP6ZBak#^;d4Je^ zQRwb;yFPY7{N+=n+UZHxO5avq|{fMvM&xwnlxQxKL*hAD#uh({{$n5?_jRlEXYX z$-s%cg*0{x?U1oe_IiML;r47LkpF&b<6xfO{h}wHSo8k!vgg{dvBAU8XOqFhzTNQC z#XEMd<=GJre+SdL*UfL-{E^`2UaP?7pH4S5t+?tuerw-;L1qitk2 z$`VdbhJ+eFZ#kOyL^P{al-z3fK5q8!|!S-9*nmC^1E>nDE z5ESDfF8=#nHg4pg0yBvByG)D#Ih>&a7^DYs=|-N#=Fqw`&?3rEx7zPvNYQW%a9y72 z3pFt&TD~)c@`FHFVg<=px7co19QOkMxOPqp?%VOkblv_9=W|7K{lqkj4I%}TDc12c@B6R{CFkhZP zDmlTF8au^uEaT}(24SF0teUKck*squC43dd8wy#}i4j%w50Rn~F0J9FUPx<~~BvN11`*5g9GD%x=UJgHUgTb!F zQ6ZPZV-q>yiwusU0MRK^aHI^Hbjq=5^5Ivmf*{qr)P;KE_k|kixSxgREdeuf357^N ztg#KNZie625Txw(H>7ar>bp96QQx-6gkmCspRgxjK9A!7J}v+s zc7TtsG?y z#^)qCjNR}fhm6)#tesz$)D^(YjB-&`l51ag?# z+&{Y)TO799bxS`2g7$6X+49kTrU?=!ImsyAs-z-yOM#m-I)iYNy`GUI2OY<-7z|`E zk;VGE*!a$4b8+fsQuwe+)E2rP`$b;lVH4DR=3y@|A*`$8-d?gA z<%%doY&|!hC8Lzbsd$J9A=A>=HC2x*huivSnkQA@bSd$JC5KqlMh9G;a~^7*n#rY)~N>lAXkuO(i$qHzFd=GN5q+5$|IRWLM?r>iMG*{#FM?G? z{8UCeoa7jeC+V?nL?)h9fRm*SH*~h&MMzMAr1lmRWz{rnKaI5(?ejNVXKedG>)ups ztu>eErOS>R1>eSyyQWgwfnenT;Pn5(F$Cj0V_b+(U-}}|so2S?iwbVh(CL%-keF>z_Tw;^L`0nrp0z? zc{9+CVMShFD3v^iY#eQ`S$V9ZHOsr;b_kSYN6UqVtD~criqE%pZj@+s8V?-C?+|aCW;nTi|bWIXS6pyw%zO ze)|I&uVrP)g_9R4K9qmHH@NohCa{*lvQVq8>RQM4h#%W)K=XE##o?tHZEtR&`_1&@BE?3y%)z3yf#|msGTJd(gM_ggE>Ccxu)3wm0gc_yjy2#z{OVF-WQ#0BL zYT`2xv(v(IyOEtgJNSsz%4xSELABH`8@gb3x)YChHR2m@jg}d!L}RM2TWL4U7t>_ zo_7HcorPuUpO#q%k!-lPF>Ytc4feOTYG;WE$87~CVe;tkN1o_e7?Pq?N{1p_V9y~{ z&REb_s*(H7tYOB^s5P)ve{k8gx_-{nE6{)Wg9Vl75jI(yq3K%O3@H@?V%*FU#co=l z=9kNOuP*|xE%$INlm@1^MJ%%8E9Lt3j-5xVfY0HgNK2&F+*tvCinni2H;|X%of3r+ zTte-=X|jnr>Ux^U6W)W_C-l?a<;T8(!o|`l7^F(wy=qI_PD&O#WvJCG|b!DiA9%?8L<>vF-e8v zV_MM{6%JkxQFuxEU;K;)Ur3+COELoShqbSz=w7S)rC!MAK5){_CiTHX?A1!+R`!CwMVl1CK z`eDBdj_WL~Do+>DtL}>?6c!y;w6)Bft2&v2#G>sr_~O0g@|7I;F3{4ZXZpc+Z__JD zEQ%N=#8Nb0?@Br>tT`k^z+Q-ey}SW?c?0%RahlOx>gjCZ;Q30-@E;;kmN0HdT8BvV zv^>Y994aZto@lWfvrk zp%q73^`;ihv2nNZIN=%+M!MbM+_YogIC;!Z`CTo-n9eq=1>Rs`zPGj1vLPNIA*R#$ zdQTyhFltDb(saI{B_Omq)xi3`^~*dW1X%Os%F1@kv}U!{v}RERSkX%Fu`GU0>n&-7 zdKZ!)t{fV**8p}zQFb<1dKA#|%3$gAhA^?S<(quTVU+&Tmm5XxrMxn%toTZ$5n9@0 z(O_?Ql=?y1-6#H(^}o21&(xj| zd!0$bh{R`#7d?v6x7L&*cU%s9b-fZrRc1B;Wue-#9=;~_OVZieCH@E0+~_*O7lq=xfc$# zF^9rQ?k#7zwqbopo_3A%i!m0EC;GrQxThFTa`S&Ou5xv1cZkwqC<`~5#BwFy!a<(V zVVFw%as>94+u2@(&XE<7&|KwFSW)t>du zIij`vq0r{zGZZb@9(m$4p5-mQK3>R-G&!2EI@3r z0I`J!#1$6MhL=ATx3YOf!;;C`PW$3b) zNl@B5rfI9$hWn>VjWGeb|>jxu?~(n}s8IG(YTrp{FT)z~Rzzw}jW z6`K5t%DjJ005UR=F?^!5F z#yc(Km44M{Yy?D-U#zvBWTGHv7fesqr!3V`OR&|ASxrZhGB_EV@xIK{F4s4-UonZb zm=`}Y0dgQ7GOF9O=*Z!_M4!SMmOAmFBgOF>i$1wC3b78rOoTi8uUjiNl{w#sO4aLb zLE&XF57D8vMkmm7`;3g~OFUavckE@m>9{pMrZddPB>ste)TmhRRr`|lJM6^t8GZ!^ zDwhHc$0T}`)u1qIqmSvkN1WA5XI9kJ^XX#UtL|0eRHLxrehzhVA%O;TqO)C4e3fkk z73o@i+U0dND9&i>>lGc64nE&yH6JT3M&o0dFFqYr$8tn!D^h`#9Yyn!o9xtH33?<- z-5xBKqfV2z$K_C6qqxp1aa^ZPn@6Z1w_O+wFXh9UNf?Y!o1>=VD~fQl#LPb=j-VFX zwksJPf>usfJTmA1&D=lHCgl?Sr9{k=awWY=Z%J->J@{*v?fgmLuUSe=-OovWM*G)X zZjSriv!-R$upcn`d3I{1YRDQZ(Ut2;ydJeE*2t|u5EWj9Cd|P1`Bv;JJsS0~RT)xmSiMQ1%Q8D^D8Q*_PG7^U1kF+EfjcABH9+oO5sWJHcu zUeF>j{4%ZLol^}r=!HDWWGkXd)#vOvhTWF$N%XCs27)@Hi&FaSold>N1O%Px{BFk` zW&L96`ci|Xo)aamme#wt5S#8_L`Aq&DCtuEB&**SOjN))9EW?&e z#+L2kqMX^Rtoo?{6x zGOW~^^~}mSQ<;(*lC6!pPxM&Fv)&$=!kbtZU*{mAFO^7r)O0sb>h+Dfjo%Adysi8u zFg~DJsABt=$tbEvCQA2J$XQIPA@+0WV4Bq&HJ>`QOeEZb4E=9(LQ=!Upoj4}YuuVr z{myR4c(e8vasV5}8Bqnf1_if4k3y}5i3OWvguU0KXK+;w0ULwvg7og-MfNd^L|Ah< zoAiv1-loiwu}a8W)#&UU*sd<*){z{ZC}^aQ*|%Ty7)RHQ)uIRrcaQ8!=~W!ccz6}! zkl?O(_C_fxc`Z)t3VCn^@SSV&rQx*KjSB_hTtt%`UPOLEMw>X3h!mr4v%kgDmnm8L z=n}?6)zQa}(-5Bh4qbe4%Zq6ZO^VriP9*Volulv3K<-<d#}2UCS=U^<$*sx?o?5 z$6O*V3YtwL*jvJBI!}LI!_1*38kcXATFo=tu{t)6Z%t)wEA1<%bG)-l%GYW@92*0$ zI4NLpqFKP=$l8L$p|Pf$7;)EN28(0%AkNH#I2K@Ww&NefSq6(U&H)x@6)euXey}*b zU~%mG!QyO!#Su4rf}cc0Wlyxk(mE2Xx{;%{3;5b3ZUI?RMO#16w2ou}f`st!YE0g; z?|J?7q(>Ye-)1;yxLiP;_hoSyF`(op^l{0hma)IFQm&Aj`Y5r#HYqB5tiGAxk}eLf zeNZ7S9rL^b7G9h9RB*DEZm(^OpRC>b=-Xzpw`BV0B_8g)2Sc$EFE zt-@PcI>s!<1&6K1n_kPT9*|5r3>}eW(}9K6+!lCn;1Hj9v#SgN^Xv@^Y}Jp@kkqor zF=;*&oC!-h_EMzjCQHk(IOOVAg6;20fWJEL(PZo42Qe$Xv3K+d(vWki{&9V|}-U&~e@qa>|FH;JK{w6z8! z&S0b*LGcy%CtOp)-898B^+5^y=DTcS9ba^GD{Hu)x9xLK!<)5XBgR0qaceoEMg${` zKw+WOzYVjD4H_a*2@g!@-BlV^b{vb&wcIOFi6#=7THP&84f-CB*7CTpfte+1P{z(b7hC2 zu?igZQ(_2gCCOH4k!uDjE+4Gc2Ty?E>J%L*QzrYKt$9i!=!4J=>EATpiBwU6nbGdUtNe{=iz6+-+1qx_a8OtmcBQ-`!1@DL3A9N@hGDhK>GobOAA zm8)Q==BZ6wV~zA=u!^iQ)gY({vXBLglhUKzdIYFZys7M@NJ&jRmlKc3JcoHVj2p#+ zunNdhCUMNeLm=DQjqDwv0)mHV;CpB7J6eRj*cn7>edF4H7%inxj={*F2~MAjNq5x; zVd6*BGXPMZOoS}w1(~5}flscXTkq3X=EOblG^6b2q=k;O*N08DDDNV`e!T#RoALXg12Q@;_~lCww9i?l?B-uM2~XtEY3vYm4kp7Eo1wgL|Vvb0r5#&CuPVRI2-+JK^6{tL#2j z%3oYd`o2r6G$L&}X zaGNFf^{X(@W?yZvFy&&=CqCI94PGKr^j}Jgg2Bdb1>~!m#QDD8Z&mypd(8`Zxx@-h zy^d-h(tzk`TOz&v(D?1vPBE}T;>xsJAh1y)=lFkZ!H*~E75F}MjFXvX;){S&(P88V_i9$%SxFe$Q zYB4s_$$UvY|8fAG8rw>|qbl*Y*ac)&ld%@zA=cA$za87ogT*=K}B|1l7IlvgS~ z{qc4`H^>15=i>557vlRd^(X>YdyC@V-0XR)L8*I`C#Ku0FJ=G_C1f6aSG7(XKaS=uAi$re%NoMTR_$M zRqf9P?ND4WX$Dk1;Jg?Da3&LLy#O39Fb;Gr7-tfUQ(?5QFSUs{0M=(#pX{M(HXh3$tH;s$?$!D@AkGI(gwD8Ar#3EETl(*xa}b}r+0f0(AmY0_ zwpq3uPi(kpxn(LFdcl7Nhe{Ve>9#mkzL4{ABeHf@v(d@g_QQ2$-@rn>$IaH+K;Z&! z!`+_wk#Sxs{Uve}=tDn3-->(=xUy@5byaI6qT@qdTWwuG6a5VPyx$gqL{lHXxG^(q z*PwM-=PTmYn{syg^WCH7Cf$aNj+^ysCH^0lMO|S}IqZl=+bBAR&@S&M_(${oCewBG z@ybYE$%RBY4|dx>RiF5z*aBbnzEiW&c`bN4xI}Kk^=9{~r?I*a!Yy@xndfI;>4MuH z`vT0Habhg4u{vHGH9i;nz-?GcjSc7O7+H;0YT!p}jj$|fUrE&!kX!pq^ugwCl0(p_ z@iIQDhR876J4J`Us8?TnTn&+6cIHX3ip0pt=lK|b7=R#Ki@cJD>d^e5Uri&!R39cj zr#g;g^~B{c8%2I@LyZ1=iFExLBq1WQn^S$dQF@Y`HW14W;~7)E3^^QkF%6vMOiW!e}^ z8a~gfzD~X?iXW|c90zA(BeTAi9zQQAiJLuIj&x)4%m~w?>VA~Pdx`N>{V1#Ts^O=9 zY2G);y!UaA$6%|3e0^dc-S*>{UbC~-j)>cdlk^uNq^VrGm&T~o4L>r3$?Lw(i|_0- z4ez^zGicRc5l zk;u6tzu2}be!n6JDYdj<@Ci+1@pBW4&(1QbK`64eg<818E$#&nXf%;%B*3trj9`bK z(_6V&--CDebSsW@VMeCktlu+KuLWXyLz|t=o;hm9V!E4 z(kr1OVFoI~!^z-ezq+3ovH@_dfs-LAoAY$4TI35yazy-G8j~;;WJDSE@y%J+PYY%~ zldXL$fYn`Uc@!|P&An(D_M@G@7%Fea5~_J2e5}!;lnZ%v_!)vuJ*F_V%7^S0D!r7; zsGvR}2^&DFJk*4ji|}%Oxo(E|`6$xQUQ6D%7raLps$3|*(0zDp_=48m}It9rpDB6OV~Ut^7b)XGDOW%)V&uaYRJvQ~9=dBtK|(;f zq`OPH;oUQ+zj*%l``qt+ydUom&an4h*IMg5S6tVC$E>78P&gNLbQ;dWx#;CrO8b{% zfmNrOGFNz+GRTHseC}5@DuF$?mfngd`8|tps`tY(dL9=t6;S6yMlk!a^&~mJ=32BQ z=bKc_u)Oj|9kWawHzeziu3i07VZ%+-5`^s~`0lyI!|M+!78w^a8zq;&WL-X7w0oo2 z9OV=~3}UF+kNwA6%^~CR;pg#7IwIc@U0Iz7 zmPJ~9G`PoT#0gwkaaO2Qv3f}{p2l0rUwsy$--?cm-AZCyAju>&dSxQMa}2bF^kXjh zz6WJkDP)AtKfQ+(bH6&+Bx$jk&H`;L(zosD#Ag;>RHf7AEA47^DMn=uU7S_$(r-x{vll+qkp889qB^2`AfC5qdlr)o9D)}b{rSkb6Xip z78{nc;ueGp7C;Ly?!e5lRh?T?Y91ffFcyx+O_T;OAR6lz-!smrpR+LA*2tJaJon(NV;jZG$sW+YQ(0qaJc^E>~E?Ovdh880@lZ~~po`j`gWPE8~t3OOh+$6KKorK|Rfm}<0e?se<<@g>Q!U_=t8 z)NpJ;xs`Tr<6RdVL^e>iPQD5Lcz<`pH0+(V9z*7z!7gcjxQk~<&(~S{8EXILY z^b!HF;KEO$;YiTf4EEoDU!Gez^xJb7D0A$@kOsWO5SzAf9?S^eGn|o>&*kIP$MRmqk>)qP%|Pr0;Ab=i!>M65S`~wyYuw6yPDcm?M%*X z_NR%e!bS7KhnfmlaXBgKiM>|WS9J$vOiwc<(Zm-1iK?H(aC%g z5}E$^WJz(gED2e&+|$M9s`IhBO2-JMDz3iBNBKT#l4uGA#F(;#S*g{$z&KC$i*C;* zo1pty&1SfoDiMMAO~~8LChONhDU9aQ}DEEw##SaocZ1}GGCF!wJt?X z^1PK*VA@-%GD2rs&m`K3j>>%7(h2G@_wS@QdIydtTMiJNI@-mz7Fq~<(RQD`mDt8* zz&8mzo2>DOKU1MRdLHBLu0(#K3g)xHikB_kZ#7;`jz}P8y_I|}yRmm%Pz;W;LyGCl z+!~9QRH4>vN*`idH(2OQ*0qjm)mIGI_RPN++MkUrq{ZEOphw5!NCUap&-d$V$i2%4 zLUR1v92i(jof_I`4NPpB%#|i*@n~>4qRmka^Kl*W(Jk>{RVyJns)w}Gs;N43L$Xy$ z&|*AyXRi07_$Pzy^Lp7?3M$X;WjQo@Q{Fk>3;0;H^88+DyvP*(oZsZ=h!vrGiT+)G zqh1L|(>)w5`)Yqhbf(oMHY+}H1>hY@$tpmJ@4LuAPReTMi+qVLTN$DUpVV7X1Nd7K zNv9rpe&ZCwcX-sFXnS7>N(MaUN@C{nch2L)g`xZEft*Mn)m4J%Ku$lN+&)fq-9FBB zG#Xo(@nY810)-A2?EG(nKFbDSUmy|-&72*hr5o2At3N(OrcmQt?Ia#7AAucp z-LFo!=I2oySG*NQCF;inwNV~o!f}br1h>yp2GG<3S z#AJyFt<~Oj_ejdOmg%pEaS}GOyA%t0nuySV=#F2vgN~FznlmMNuZZ4c`q05s?g?S` z>DyM1*&pzCd>MBNO^_jpqbL!*>)Q2!RmTQi&q!mcls%qvHX7O`1vDqid*HocVPf*9 zRRSZWky1QZ*L2S-aXc4BcC@lX*`lC(r(z4-&}+gczIDzG6n{Rjhf`UCE&JH`(jY9eaw+ z%KCysnB!<%Dvg@~ET>(e))GN?+FWBqMQC&Bfrd zHkEIZ@HnmM23sp(Tnn-k>x#6GTVbJvaYS#n`LNW&d)MmLhICsG;16TZF49YF$4@S4 zer(01>JF?iY2%>W!3o*sd;i{+IPOEaT6l?xg|1ltyPd`TcR0)#-4{3Rq`R-Lv1`;^ zNN*x7EWQK3f;(Um^j6BNI&FgvvqK|2kV-?3W|eqmx1zqPrPe%X*GwZFrS_ABTaD6e zK#1ACu@YICn^#k-K{8@9hQ=nzBElRK-KLV>X5=a$9~6=A(5wO}JJc#`^l-jfn1?vh z9pBaU@Vha5QJ!ZhtYj0CU!lBcu9<$qbC!hGu@WnDdUI`db4YZIwf0PrgXifXE%er_R3c`+aXpXfm zwR;*mJvjBCtA;|pT?Cy>*m^0BuZ4&?&bn0aaYq%;vhzN-tO#kA4nt@g-VlP`NYD3TD}EYNcAG%W=h zZZ4jhysO`ycbe1ZBoA#U4xk}$Nn-29J=bl{72Yj4N~uO4L2pS-`mk9-${M4}1>vZ4xAasqrs*r3;+y*zVzf5}eiK?yao@EHUV1;!1cgg3R z9rrBL?VhGKFqX+MlNt1qOh|e8vQ}6;>>m8gkJ*b{XejES2v>Vr;5MuQXHp)CG)5+L za6S%)7k$XsRPny(4%eOZN?kAAzDWM7dd4;y0Y`pp6l3;c1e2Im*2!J$e#2h43hBd_ z_a61f9lH+8n})sBUto}ogP*uC*kTd-_7*1%zJ-=9+mQ55yluT&8tU3Y-O2btg-xh5 z3LGf*@E{Ye2gMX+4Xbu;PF+J%6`uE~tveCk zB*E?N!$+y0V+j@HhoHr$^0g29XV^jDr*Cn~{V^Wtyiumd$LLS|(1HvSm`pld9k+#F zOEbV`WHTN;W)@?5l3Sl%65_)7~)!Xsj54-`^*dn zsy+&Vzf&u@sKJX!XM`2G`MJiC%7s zvE1gJ?_bOUrR|lyaa)xYAEX|)jR#7MI3Myk&!Q(A`FDIL*=Yt&&9l-nis4mm@z*S2 zHEO(V4Q_juXj#loyV+-1FKrEcb-Avs^=5mp;v~!(9GTx<6pTcjXzL$YI`CUOq+}>M zu*}n*8sAwMH0*U^-)1Xf64=e2?g)`QW!0to=*n#?PMb*g?B_8@D=dJj*PaxUf;EL z41IO)QQ*AX?D@XZ5tniDXdYt9n{ay!iW*TaautX_!V`E1tTeSI4Z>4OJ zn@}vsgttv)dWL*6PLO*YG9J&>JLxKB_mFaLhDiVHH8id(f8fIFpi@!JY0u71X}yw{ z0=k3rv=G6#vWau@O1k#@(|1+)iS2OB<2&y}$q`q*hvxCNwstIfpFdIDvXFU04O)C= zW^PMjKGG&y3VCWpMM?mea8)!SB~3iKrf^zq8Ml1*UI)E5sEPx;L$o?Pz4TF0XVlwv zYN`c!Xx!5F7Q-qGLk1K>2dHI~tEjhk=iVxTAXD2t<8S`ah5k<}zjCrxb7Y(ZCIw0N z=2Vioc3If=x+FZVx1F~*;e1t$v?{`#r0AG$yRmEkwriDmrUE?NQ8C7e>zd^BnR!lY z%iav(?&{m(s2H+DNG_p8!PoKW`NTJVwhRs&LJp}GA{_bjGLk3{v(jbke}b(ak|#!; zoPnRQ(|ea||Jan4`Pu7JKD~Um0WDFCsH)syXUA6NDn#aVphOT2S*iKM=ew(*(t*!Q z`kE)BUqJO`P8=AJf?6r$AtEok!=;9cnk#eJV zYUY)SuT1pifAajy{5;Gw`^v)1m9QotxWbLqI9{Z`YH_OX>sOzfRzDP`gP-sA@~5>3 zQtwH5^=TtIcIklr65AqRp4R%G(q`SVV4kms5%%!7hf-6FGfAzHJ>2*PJ z64sIOLlmc{GlnOcrt-Rm{85c4Uvn5!s%QeyU|Cs4wE?(#uxL^$c}_(ppl!IHcl_@1)XtV$$Wu zc;J|&uM`WsX*lnzOy7j#eXUA!Ct)E31N3ANK+^U-j{Bk9%zs zN7$VGA&;Om_KawnGhLzc-J>JmivGfd=#~4)VFO1i^an?0%%cOImXko+yVH0*gj@QS z=u*LUoTUYF6y225$zrWcQp()^)abfo#TDXmbcB(CSGj47Hqap{OJo3)n;OX1tVA~Sfj)O>^-so)my zj_3$ZRc6(>2%QF;c_R2;Uvic0%H3P9np5Pvy01-hTEWxvZFML% zxerXbsJlGpc=)n9icjsxP?QgH ztHZ9(dy02w=hfC{FG^N#PH-8ouOTEIy0bTjLl?T`4$a^-&m`G4HupU##U%SXVzvce z!89ZGnwhl=hP`t`BqK3UunO8xuq{feaFun+O+M0Rg%c+p>J@OK9Br)Xxz{tql3GV& z;JOX=jus$zB1h6+ub_Xv){qcsGYJT(52Y9x&u)&*&7Atw7cQm6jry+wbHp<2Fi+Irm?2D1P}zs zQu~o!+4yBf;iLoxqeJpUZZ_TWTv^IL|h!nBn%eiSRX_QAU z4EaDt;mFuk4N%mdYsNV3m6^cvEfZ`SWOadsJ`eGw>}a~xGM-|MM9Ai5xOA78ddX_K z@TG(Xdv=1I2z$W8O7o1jv1(jV94_9YMrKV>Q0)GF0R-#cVJmYR1o2__KJ!{M8@Zej zV_g|K-F+{+zDLU!qBJ1sJm9urh)K?uMV8(Q4nG=RP>ir4JHxsvKFHk}SsJpByrPWR zYNC(4igF8=4Kna#OFgX+KQ<yhcyMNCa4E&twrK*C46 zp7ACOkXVac@tgXDLjmp-^@ zM03OX8{{$2-?Y_s4sX=CBRzoISNnpBTrY<`(KX%*aoX~*j2@cvnMm`|ZM znZD8W)m`Rs<<0}_`~!z~&!s}S+6=H{OEaF3g<-BQD6=3D+H+y4)?GgJUm0@yzCJ8z z&!=7IxKrw&A|{?MhcOu1sv3&bu%(k&>AH7X=4u^Whr4QzaJ^ZFYde=U9dwpOYw9*( zRRdaX!&JL&7FR1a zl4J=U3>OdYC7Y|`HgMDRaZqpQmHk;?)6LIrSLxq? z4Gj+vgT6C;(*%L`Mqq}N7=bodLnC9;TZHObGRw2!pv#tlECQvavB@w7?Z$}ZoG8hT z5@XDMRb);=9hYSW96Jr_Du-I}()-kH$66oMvVXJ%$;xoXGV*d-jSaEVkCj=tN_3f< zjv67@sakmPy+t@&KT0z7O?YgJFv&7>m77IWH-u>Q2D!%5d*)@>wAR!e_hH{v{U7Ei z;?7m$2<}&rSaurDIL;#CfB0Iy_Lro_DxFT%=^?g)5y#+%cWqErgX=Ybd70i;9hh~@4@&{Pug0= zKHUyjG1)q3IvJgHWqgF!;VeGDg9q`1cz#P;33%@;z-_8o}JXX76);_#^s z9&)ePC`A}s%`(LmBLp~SquO-XbZgbBXMT(}Ugfnd)}nncL)*8&N4os9nrQn>PCr?D z+BJH2mt%FDwl1vd#JxV&xO4P`QF2Yk0g3L!gP=5G?eM&p=c{P?lmK8vB03|GXR)WBQtiK-e|q*d#5TF1j8@+j zqr=>J)aZkVsznLM+YfC3>(0KYI1ulbeI;K>#IT)@j|p+k?t}n}<*ezd)iUciV2btk zx{VFedP+F0!NM4Akket-8IwfN-K^kw{Reqnk&t(3VlcS%O?*qW0 zx;KO+v*DW)Pi&-^S7+g0EXhD4_{0Y4Y>g$(*v*ma!FK4BMjWy;1;UP+hE49E@&oF= z-efIHaJ+Hp(5+6;7L4a3Hp};r2xL9&s|Lty&f3HiY(Oc`2YG83cjM&doNqu@v>%n% zq!$C8Dwd9h2qt%a;)qod$rDx<>?$u;jhM_`dD;^=wf^=h*r*N0t1|i=#V5F2fsqlO zNh<_`i63w3r?THINO&sk_VqgiXoD7u#M!_}qG?E78WhTV6w(7yEQ<@AC7B z^^ok?)%d&RMUoq)(bZ7s+s+Ec7Cec2FYla7J_jF_PsxDzgupSzhX`=geS9XJ63;Jdgyz9&pc=$CLBPCHYh9HjwO^(Z!Wxi&n-x_~-iD(beKP zSD#)2&T=0-^boL2{mxvFvYbQG7o0%Cpo2YNzSo5A_z+GZ8MG5vvxAg6)Wv)b?-gzA z8an02Q|Gbb!TZQlV@$j)3{ZHDaQGjbG)#VTMF&k)2Yvy23x*zJjmupr{%6?R)X$g4 z$I-uSE8SSO$9OD1y@C_yD(4l85K7iQLa04T{R!mi9)itfQBwlw(o1L_>F_54ET>N4 zp*i)=hV+-#WqpR_&p0<1gXrQS_R#!4MzG-?;R&L>`sFMm@p%k7>*dT=(K);}M`muQ zZc5)VaScz!9zv{9@4-LeZ<+M{3Y65)oTJyR-Vw|Hq}MgH$meV;kGS9Gt9kBa&q!0k z1$sK+#3?*1vxsjq3muxQ_xPXPI-6SOgjEOxU-uk7_n|a2{{hm0{69qavM6E9)S}?G zZ_yW#9B!<7<;8Fczj1oRGr5aI@PE@O4F08)@AW@)3OS4N>-G8J-B{`XoX#QTERG#m zG!efuSwy1iNdzMP1=>;o@7U#502*MqbOnd~5|Y_haXK64AwV;w04*ruaA-kY!Tpp= z9zg$bkk-!gE0bchims=p01qes57b!Bqs{2wf*6Uxmd9+i2a2O*fvsnR2GD~i2^Zb=hVJ8S^0F^>N5r+5jonseI3e5k5 ztI^OLxCQTZ6mPo(WRu^!vFAY9z!LO;j^UcNZw(131NVC3cQqSG1n-GcLv{PguROk# zh7gyq97Gyx^E}(vsr$sgvS7lJdRAbfN6nLs+_Og@8A`Li72@%wdRF_9@x~9zbFrsU zjJ}u0b^ABnp9VKKU&m_ZWUFc&sJaZ?gUdXu{i)8-<}QP%80xp-J&bniq>HRkSV zDx1v^qA%=mwwt1miqBsfB_PVLO}YwsT$ge3AZ=Nmb~h55jin#0&kGzGIz4Qug+>o- zXA2&bF`VZ&9X+KL+c_`)VFbCU(cameX>R0cXx!{0!RxnErUR`;x9qEh(kN_%bYI;Z z&0n23-Z)!#ZA6RW-`IrEl`gwRpnjK@8aZ4D)_r<{E4-m@>sefD);rN_%IweEyN+ncn^lM{1i=;Tjg9q|b!>8=@j z5^wZcz5}i^PwN@QqSCF8+W$z5$OyD^U0k^FD^6)@x*GD-`d*!3W3F$!(vPWy$$%d} zS(W!x3saSuYz;Ig?d;0ZJF%Nmz3NEj2Zt`? zo3Z(Fhf;6OFB`tEx;<~r%$H+v%GbJ5V7#6`@st)jj)nI*Q|BXDC1t)6NNLlXBWvS%@Boi`*bqe_`yCtzl*fv6ju?NWDa4->67JlUvoL z;pMx%P3Db+GA3tegd2Ism!~U~F81~A5{ZKr zp7s+?q*vW9uejcP-Q;a(Jjq8WueNxTRDynLpPUg`+)HF@U^M=Hb?5j3z1p+(lXX;? zx&8^11O*2CMt}rPv7oya$rY?boBVNnli{`yyvzK!fg{crSv~xomnSFu*O$dj*NaxO ztMSa>)+ymaWyh*=mlX|n6_2ZZQZ~jSdevC!3pSPR!SBxPe)euI?p6~m+zguEOoMdK zIP=6Od3B`dLA#ChpQ_4V+AR_>5+6^;k=JB`j>Bxf463k#)@!^%24mS@YM)yOO*nAx z%5B-s(VEr;e?zC*1&R=3V~wv`oPmN(eYIXx};R^UAU zI?r`z*TG7M#C)eG>nkzkg^_J+1{+h=o)r$NbNrLVwAM>~{)R@|x54yOUrpu+kYs`f zcE0T&2gw%Sz}1DnnN@oE8m(7)elGJN3Qn&}-85xNLxp_L3m1;h#u0B0-*w4;UX}k3uH`EWb5zfXnj?W0mog9?QS_EQz}{ zMfV@JFH!G{x1Qm@LqS{sc~GOu?+5*|ox;iau(n`-}L?Nj1ECC!b_y9vT z2${cMCIPtk%WQHGc!fMg2>hTw?4^SWc>dQTOlv^RZ^eKFC=GDL20v#C?p9%#yrliD zM3s-^fQ+`m==YOA2}>H=ljAdoF6 zSpt9o&;9@If&v8o)&-)B=#5(m5R|IFX>$tx?d0FJY1!VYgsozMD923x5QWh9d{hU> zk&hn%+%Sdu0)45Hd-BVPKivFgX;%23wtkaHwvdnmBjOJnfLXEyCdphVCdmaw7!e*F z@Y6GJwWM~kYu^2&X_SI}h_F~a{uPS9VYW(#5t056B7lHk{)(XVA9i3jpJXZhiIV(p zihhOvPm~h=LvU}$*&a=$9$ub)(7CZ}M@1h^m+Ey^SMr?|)#0D=K8q?o;dR7n^9 z$0OF|?8#3WSi#x})c%ia$?e3}lKThHmDivbCm7jmB1|`1lJ!FfgsD z*ab<@mPN%|&AX)IrYoL@vQ}3v3lMaL$lu;hn*w^DG-Q1uhOM=9rK*YmSjHp?=(r!i z5sm*GqnMg~`ewkFBYJYe<{8>@I~9hX4Jp}zoaIO1`s^vYW?_8bXY+1vKsZAfP#X?2 zyBBXWgpCC97aKVA0C7GF1F8kkXsQCN%~U7sD)ee8m=T7o2fO~rqg%ijEP#4Q`qzt& zq9qsUv{7qDC=37|6b0Vi6Y@W1yQ)y3nevyt-_P=Z5SqLrupRtPtGzrMsS}^8^I87O%`ry4 zhBGZ)|EA6T68x*Zi@jOkmum<7z=ZdXS)8RI+3S;))30GEH_JCW9_L3LDc4y!j!oQa z!bf2#m-}sCT?c4XN2dUH0h0d|K2RD7KnpXacoa4WE&spwIN%veExl+W@EC&i!i!~L zFXXnDLRUK}L#8WWwFm@n^f^qWDNvROnLv*Mq4=mbgxCzZ$E29V|45|RfusIM&jK1( ze%E$3tR?|p9%cRR>Ok#=$&>uWh|IF@-zo*jN5Jg5q&H3!K$iqTKL}|p^q(y6!eSr* zFepz#^tXZrnB4sDJ%VzO`+KQsjOG}$R_+3o?2ozk1m@^%0#R$D&lLAKa~gsL`B{(S`>)-#4z2qoQC3GH3T^8E(;^3k~(KRZ71XJTLSQH zYr&X6_Gxb1JMTipe((>Ku_6Z1Fw&Zf;P?L37;x6~q0clE6r2bpD}J9>&TWAyXRu9A zjk3rex!eVR*%wdmPgz29M$JE19uI2KOoUb3z6g@`BIfQx0G=suxB@&Y#liuI0bnR4 zZpgh_<4w~Pbo{vUfcKFL*`e?n#H&k5H?ZfFH1s9gAFWX1=IbvcTl38=K{UN~R3AzH z5kWi@n8w%zTvSmWN!q_}Z6TGsK*v#DuENqZ5%~8ra!S~<(QIGA4m{+KERX?u#LUhR zOX_FRme9doJ|r}+EkRQXqjGCN7Gde(0Z|y0(~I`+U^i0%Yibmx_0x;o!^`BF21L|| ztF%Aj{FVT4`U+xTivq_zKu;(u7O<%RAgBNki}-H0s=>G-n7ET z!?|Su$^$v32hC7@ilk9}DnAcO0F&TE|FQQ2#{%k?b78boH+~N?%&*q zx&0?@erpAe^FUyr(fqFBA_=EwF5SSCb0gC>w(Es=Rgry8{fQL?Q6vR-*v{DpG0~isk z{`jxY4-#-^<-qX2|48(I&(yCR`%gSVQwo;XM}%SFjf>D?dusBN@DC%VHW{!u0TrNG z=_@#v?b|Z(`plI88I+y5K=*VVvGW zo&`Q_Kobr4c$QOj2(yAHy3YMi$B@KZA<#K|z)AmanhSw~f|laHTXE>Ag29)YP++>` z|4U*3=MQ<%pCX3Rk>(G4YNZ1FhIR)fO`u&t{e+(Ff7RN5SrD>j;O5&5g4PSra$r@F z1-ut(2&I_=Q>#GPO2BN+R9MzQ`GJxNeFx4&e{~Hg7Ffpx(hcZM)qi@%3+N{Ht1aN| zor*#?LzusR$oq%0KuR`bPoaU#s0wbP~VMu-3iVk~pcYy<1 z)v!}A2ej`1{d`P@ieLhmrdIARGLJ|;CklRX?R() z8HY|~_H0L9GQhQ`kq1izwLV!Gl94Pd&YNqR@YM$OCa7x9<&JYXTVoQ|aMZ-hfwY?A z*-eSd&EmehE*V~e$rd-~uDs0-xd_DzjHzXmZEdG2vQF&R-j0j7a%-KVQTr~KH(U+; za~r3VcaV9<8Caco13X_1KfdnCn_2dt+Oaut!35hKkqMr^&Qo-;hSZKlairx@CXVD+ zClLou_BJHXA?;5%ai%C06Z2z@g}L(169ip+VdWa(bb!35>m=x=ZAP!htoLehG_J$i zb*D(wx7M%Xi;`AalPKqmjWZ&K%cUGi;c3Gj9W`#zEI_YstM%&Y%dAnH*nF_6rnT?p znxnJtM#bQK?9#%CQ_YZ1sT`v-Rl9Zc(Uz|0m5OYht%Wse+1TUW(waCm-dyJnzXhGQ z#gu><`4Sg}k$x4dz`;K;2>FcWs; ztD}2aqEH=@^*Dq0pe~ds@#glHw)te~B)DVXNAFUR0a1S*}{n`#>*N&DeDmrb9c+r+Wr!(B%aF zIa@U7Ld+X<&o=7$wK3i{=pK|Fc`T{ic!?-qlZYSh_0GrG>A&w^RRCx9uenta;FpDpb?deLynoz1H>dH{Ww z=DU5LX1;yzp}k!rlDG=qCLFy0JieePfO>pPr3Q5fgi!)@Vt*!SmGbelOVel1&ZH{n z9h>(sGg_)p+vI*jQ0F?O?UGY0UTt0hcba-&cP7hV%OhYqEeKZ6I^9ZVpbGV1ck&Qn zut$nuQ1dcjP?sV&`eYmZq1Y5k@4>K{-GTY(I0>UsJAa2~_K-hxeZ~s*loky0Wk(q1 zS#8=F)bzTI+Ui;MjWx?vn11cu;SIp`^=k>3JPIaEzG$-?a4u!tlVFI@Lgq&LX7Q8d zUFa>{+Tbpj3Ntd8e2`1xYQlBL0Mw))PW}x*_U0>?|CZS>dTP0V;KX@0ta~1=|EwFh znK|S?x5Ju*-gD>jv*4ZWZsJQit4!Wq)=deW;_73+3WJH<8G*S~0fxo2QxaxPF&K)K z`6`Sr>A?2f>YUh}OVJpX0v<3<*H1se#36K0d;Q~V0!Gy8Rm8lOCf7T8K z0f-Ryob>@7W&FB;>b^FC0zb@sRu|RuOG%!ECRE9Y8;r#~0l@9=O-kr6GJlD5`EgxJ z-(;}&c^*RVtn#}I-K_N-5JQ3AiU965IA3Q#0rJ3nvr4{M``eOhF{lI}zH$boz~$f) zcH`F);0B=ZZ{q*304!-f{}2NT z1ITDm0Ic+l{{LS5&p3E_71nvkPcd}!2?)vmUi{BEV7m$%Kjb$8NCYzRe=q(=94xL( zYodnF-khHRzjfW-@tgHHT?B@X{h5~*@(Q`-#Uqho%oVs%QDG`m0pzw2KYuQXKvVE* z(fUSFe}<{66P(?Ir<`+M)Q0w19VEOaB`fCG8N2g89E4DMQi$yx2iw@2f?4xXoE!+U z$@4#6Crw$Rr8*&(TBaT8pQJL73EF1)@Azt&Aay;K@Uht^Yh3lGI!63Y)6eG8V@IBS zfP>3!`!A=Tao$cp)3lm+f#s1>ar5XbX^PS7zOr|k{e+P6_PzxHQo)3^5jP^scGK>U z2kV(K^m%s)Y}^`mx!H}aZ84`@(j3W(|)1T#&%-*#{?8;b?< zyjpR*5T&VKlslo8WZIKK=3{b;3JN}GlEVz9$~6SJ>7kt`>c;Y;7{ODJ4t1Xwrw0rQ z3{V;&oxa9yV$7n#hb$PEEhQP8i5pF3tq|r*9$q+9sk={1SyJv*{dhg793gF#|Bg2x zNEyp$z1Dwmo47)&h8LpR?X&gJ7_~t)dFSrKt@?B=BB{IiTpUC{uJsB?)fnDms4}Tx zOybB6)CyM*TuNd2GJI>h)H}>UBD|PoF1wO6FV9Y#{Au9JQ@6}bO}u?ZXh1yCN(FA+ zN$_jt8Q}AHY=}s9*lh~&V|t3xNOoMjHad-(lb_DIQ==|*9i_Yick<$Bh(+=%PjCP7 z;VUBkp~n9E^_fGWfddGrRrp-Rz4&<#v{1i|$XW>bFUgT#y1XB!MN0^g?Im($qAI7X z^GDC&BRc-l_JME#g}-~yO(R(15*LZok)s5G;k|bQNi-T<3F(&ot%7dyNQouEMWa&+YHCFaDxGVF$ z%eX}OQz8ZK=3(Tlk;f-7$NU5%lKHPRwv|>O%13YtV?IU9j6$S(4oHpBazg@A51*MB z8IgNjnv4CIui?@jUzKu9dg#YI7#cLR$FYB<+vIt5zCAr=)pY&yO4s9jbtMj+Av>t2 znBVhiv3R}McnmjTcQ%{<7&k$+>FWF#+{9n+aX_dA`EhAJ;eNF-&VJ)~az3V7?D@Ko z;l|Z!!K_4W{;S-@uovHt5e#vtnO4FVxw8KwcbUj z!#U{VTK`T2mv0bPXAK4Yyd^;URNuwO<>wgzdNQ{+Q|4;&u#5M+>IV`+LT@Eqf7qTRyu5v}8Xa~m3#6#Ba? z?~R5l^2#%u>&xp+T^&!`(zE5GYGSP^iJ>3CkObd1ej!Xws9zbC*A zV+S+NxbDv0Z1acLM-1;DIGZNMH=H>v9{x<>ufG~{K&x|hI|Kd%Rp(hMaic9-?ZV?8 znUKiWNe@g^+uSU9vuUBRMOO`c2NJtg;|RS~7wI@97J_`j@*4&HC`OTnQ6v@pkVwDR z9Cred7)HT0R2pAb4-Oc2_#1|Y?&Gqbtsi`pf6Oc^ZVg6~*eftmVS5@m^7%u-(KGF* zTbKC0pU6NT?pBaIZvvZnzc1q+V^ZwRnGg#>Vm$Oga-U~;y8+%VAJU?8myAvB(C%IG z^f)<|B_>v@vo;K*w=}Uus{!Xr1PCd%Kf) zE{v^UNkjiLU=4BT%ZJIKJ@FSGCe4coTdoM3DsAFV#2;Js)hu32mtP2d&Um^i?%Jk3 zMvG&1^mG|~7+B!TDB9qtVd3E*YcWTZ>Rkz+zJ&ab zm&th|2Z4`~37y)^_?EDbV375;6m?$REPmZWdDY%{6CZo2>ca1I!m14bVXT~M$gOyO zll938k@>XPyfS&ET4iRJ$TaPytH?HcfUG!13|mRq{H%WbCA}X-QEU`iXV%l>$*`+L z<+kh34_n9f>BYw?+@v(nB9RGaZ0L(ml<4DQ06H?4 z*IC!6D|s9hD&4?3sI(yQZtR0Xy>?vEqkA?TyM@6^M5gA$1a`vtXAb51W@yq{td!(s zW{ukKRuYwSo%N4K+>i!YS!W~SKV%99IBNB5@+t>quPpa^$B(_DU>(CHI`kRxlA&Uq zJsxqZ%Up3LJnqF8fJEi3m>Dl*5Bd&kG0h?yDcM#o)GwZ>sMv&6u$rN9rH{B(k2A9Z z=;EU=)mdlhb2yEa&1TfxS!X}kN%x#&t~|??Ti{haaFHEJ&vk~_rmonBOZ41woBCL? z#}SaE&pjLA90rh$Xn~5Rl_tXDX;(CxgUyO?C>$?mTn^BG1M{%e`wN(^oNaI3aDC~y znFri@d_1vu&ntzrR-~epBOs272R5q$J)6&>;y0l^!&HDWI)3-UtWj6tAQNGCr^l93 zxo0GHRXPhb7xK0d`+LrcOL4-irg|su;Ajr#n!n1y*OhO>1o1UyGLi-(mnEscNxZxd zkjNhiBQfm1CXxRTSd_Ukw9I)(;F23y#0IhS=g3?Syil>p$jfi*OsZ*k8FL}1m9dpd ztuY>!K%2eQ->U4OK%T$VfoQl|AUTeoU%aLIOk44oR>2`$DQ6#B^%%+_wJX5k7E4#= z_Da_Whz*`RYSzz=#uj2+>}wupjn}?!Nu;*}r(VZ!Wd4L1Ysok4BCNE=Y(4QgRq|=# zb~lP-IGb3h&2a_kRS@3a8D*4Pkj8EMrlkGiJl+HKJ*#xnJ?UaWWY)%_z+TH7ywvdR zs)+c-VI4)1E5r~7nWtQ|uuY1a|N@I;T(j!yIDf!ZM=NRgdH0ML+KM&dOg+l;3b3Zb z!U`eBX_jGEmPzXzA|E<(QJj7s-O%JCLptTg)$6QygEX{4Mmf50f4{w0={PrkD=1-Y zNIe{*ALSJ(3)}k~{jMVTN0Ef?wY~!P;SY^mo)^hElz&bhHkx^@J{DMZ;kpj_obuw1 zr0V#G5WD6lRIX)0Z-^KvUuPf`f1zBW<5I_tQlW9JEOOZWR-VAZ72kb-j_u@Q3ZUuu7AC?W#YU#k1T5M)UqqL5eLZ zLrU0q&m?zj;HS=#z4eI!ClM98=A(2BeEV6fwfuNr zBt?=_k5IbNQL$= z@&HJR4zFWWI9Us+>*}icMuKngD8ulON!{Xcy~QIDE5oCo>pjITOsMFP^de>}XRBPj zIgG;-`n^*2yGF z9;fdZk&}}3*5r4LKcU;I$4WX`|8!dbuo_NWz6kcoXIKB5x zAie#bfV7|%<5Zo)qbGu819S|`A7eEO%gkLMX_x}lW~N{YF#{}$J`IXce4oyW(6z8G z9zzM7UfN6?sdlCm@_FQje#@-h8ccgSthMNT1I9Fgl+5lhjMUIwDI{}+B1JudGpNzA ziI-n$Pl6HDF52Ox1s5L?-fg$`S$Mf<0{KBxr{o$DW_V{!rH3P)z}ve2bw5rcWM8i+ zQS?xZbRIW^w7b@Xz*wTUmxq&keTz=MBUlJ*OwNtx$7$4s*pJVb^?|jW38_7z*eW|7 zERw_B{t1p`mKm)^VwNLS!h|6G!xxSsc`YM?PmRlEQk7r=2G%_Xfnure8KOU*MOc3_ zVCX?@;Qd4k#<&`QI~Q5}re9@3u*zxD6IJVSvSQ?+prBelE9t<3hB}(Y=B#drraN|b zaVSoC@(aiQQIA$sojQ|QH=G(^QEwZV4f`NO$Zih5!!2NeZSfP+e77NPd&HWBdfVOp zLX9O88{zge#RkT%)>6Y5pnDDwqt@xNgwk!MTPKn~;5o2eE6)`ud1s-LbZ zkrC<^#+|jROhK*3oDSaBOPdK0iVx-QM`Ga#nv4m)Ot7PwVB-0$J$n&qHz7~qzv|Fi z+r==F9NBv4B(o&mz_JK6`6jZBg`M8!lR>GHmxzHdwj+Eo|671kyuO9h3K_h|_9p7A zo0+8s9pBRC1q9*TwQ3)YJ?Y?k5$fj7eDJlh(hzQ8_bF1zaR@^E$M)x3_k&3Zt70B3 zLkO!2%cK?`iCKPzt5s$W1yY580`l5+DEKQ`oYv(=g73 zF?8c4yj{K#p>*gsuGehwE7|IPouXk>;e1a^ObFFSMK(F4R9sfn*VT=)0=SF_xoGLf zgX~T0lEMWLLXoXQ>HuZFn(gC4Rh!J~#rdxyJ#HoDHq*+YI4d zeLXB!tdOUOMpgNV3L_6*v{>e8reL_GiWoh`(f`R=M5+pwwR!YB#bLFw=f#NFw- zlk$X^-CD8-&+O;k)ilUd7;%8*uZ)%^nGs<{EZoUUIXpQJk zemec((9XM)iW+M~DXE+pq#{qh32zebOjAQ+lvr(>tsZ$ab>}GH@x~rq&)YkY-iwaB ztm}+7_=yxIX)E{EFUODcOrk*O6o$vrxIx*5W7F2Xbo)zui>jBewSzf~U&VbVm}J@% zIuj-g;=t1;8E0BBp^JI+#o}QxLR{uNGuVBezkC&Gyc zf$bz{@1^n*6*wPMAR1Wd=D(MkXvpx_|3YpkcoLHB=X$+Bur(GBPg^U1v4@U+|2@p7q5RIjXW^nTp%E#CXqe` zvl(DVWQ#fCl`vvN{IC_pFims2_i3B@^R{V%CPlflF`sku|HITZhQ}Fo+s0|s*j8gS zW@DqVIk9cqwi?^EZCj0P^G^HSd!O%5&U0oav)5j0?|tyj`<|&%bD4~n=ilB{`@H65 z=vB+=r1V1V{$8m+PMSiX?@3g@9hPWzm7uEyX#4QqL9GLA1d zUx}l@m`DmgrUT+ZNgTJy9SYV0TknSFU=)ZKbF0qLb87Jk-|X-eU&P5{$|>-Yk(;FR zFzgloaHjUM#jMl#^f`*>qg{br~Me%-20fqR6PQtK%6H)bXzt22yU$FTX5>`$5iddc*V0s zfqlyZ?OtvtF+n;^62r5l@FxnGo|lZjM6vBxW$;rWcHNySFITX(1kXLT`i7$}S1PV} zf{gngHSM={xz!(dmL?w0xVP*pJfkt;c=~!D8B$5Mn0~2Cyx?Cd+FkR6i^eq>^JfUq zJ1FucBN3m(T+W!MX^cd5iekK>f>Inh>V!~xM03Ptl-qQzDCe7gpgm`8i~Xo}@RYS7 zRbzPRGk>ipi2?Of^AB8&Z}@q*DXK*Xr$34atkL@U4J znuivkJEwBx!jcp7=p#G{Q!G1We%8>1eZ^zSt)|`QTEFKmkFzSg3jC6p1-iKZ0__8z z+&RQWs_ikg^Y!`-zMjeBG7QYE340p$QFVB}UN9i-UHLDyqWs0uB5kL{CXa!wz0WBq zJK{>;(k+E=4s>E~zsiJwNiIEufA5C?Y!@>S6!g$Z^I=AmWrUr8m$!bQJ-7As&Im>}Fu)Il=R^Jyyf1 z?!KJzkOWe&32icX1efDC$XSO2?`G`#jtBbGsr3|SN|3h6pFEH`Av}#IlkR#0(Zjsx zRcH|M$P~JHw8^22C0Q!lbqi{F&d;z6SsQHv)z-=H>{axbV2AO%cqDQ&8bZPh+ zqcKRnApM>PGht>iU{VxpmW+#&z%xM{n&J56>tA-et!U{-GZlBt>MHo|-l*+(>r>Oq z(>xndfZ&6fMio^y-Xlw!tmcw)3|8uB{U(9K42!7_&R+)%r_!c@4)EDy-yV2C^3ED6 z^VaiIXGE{tO-vS9?g9Tl7Vpr$L4P0MBBIP|xs)DWZXBrHHab~XNd4b5`+jp0KeR_H zYOO?9&@%3MJ)|dTIzhy~l$~ch%)9=G!^@23g(Cq^VczWerNU0IT&Xm9=vG(3{+TZ@ z-3t~!V^wL(>xi-RD$j6twDaOC-=SQ6vyx+S)&R@+t|U{ER$nvmw~l4WB5~UBLJr9S zHZ!KWi{>J3bMVyvcYy%K2q#uUXV z9aaL`#hbi#f(NJ&kzV$Klaw&ikvALej}SB)OMUZ2W01Ye4~|;0^KPpyYg3_bckjky z%sUa_)tm0!Z}`fMnIID?PI>oxCWLvIC>yH8SSx)Z2&UWq&a*_)_^q9}2pBc@UqU<% z)t#ncJ0gHb_sI=u#tkk?Iys1AYtVyFC(2*KIz~#`&D@(dCHI}aSD6}YEr2XHP3bpp z3-*+1&dy@6G@9mVqT8&qMs&PWITAN&Vs5BV{SaMw{8`Em*r?SzxOFDE)l(J`|FJ~& zm5@;vQDf|ja)(cuHbgnA6bYR;aha!yV_Ftu#Y6Q%iLaA5V>2g95}hfQ7LR`CDA~Qw zbhy~jxmwKhG;9lLWB~a|isY=A$w(BPI7v?6m)3b{qRMMAd{j3Hjcz#DOx}cT&#mw7 z`P=E=#ZKts{Hn6V7IkA2oTd!PCTKx&%XyhYLhG{NZgsIgw;T9 z(pfGUKQA|;@>k2LN*kP3x#?`=yS9B4?U|O3tff+a0}|Yk`K?dpn?d^qC?Z#lL&pX- zh0}?>u#t>zO}eVvS$fm$^ssuj#IYiP^|uNaO&tFsQ#H-V%OIz@@tF}ilnTpy#&4#mvof2-vImhyeembVfI7FJyp^CvzMZiM7W71yWQuc zhSId8ql6olz2H1iQT~cGu!50AE~0}TjcXBA+DhPSy02P0!Bu7Qa-(n*VAe?Ml!a!< zN30l?cPgxE<$6p|o64q!?BVaqIRIY=<{<@CFsQQ(Z zb!WvGF2s9^U+nOWf5rw#`^yp$t@)vW@25!&c}7fFi4ditC8Uj!*34fi+hXCc6Lx6{ zW7>Zure?qdqy-y66t3Qc)S6Hqc@*O9Yu5YKebI1kpS+d<(*Q1wAh4IIR>ILzmW=3p zEC0y5sTx9%JA&+{p+=O_7$;uGV=UJLAUe$Gf>I3?VJ&-L8YxKY{Ny!KNt2YPsi*;9 zQ!rHXiIRwFz94P0+|1MrN{ONg!W#U>KXLwgSFS$u!YIfLp>+fNx=EVeZL*;ye@1*WE zpq`xyV%ewas5?~D4DQ7YmEt{A%ip})aL@x$yD$_pVJZlh#c1*9`~B)mh>^Uxgx*+y z)}|ptV>FudE+K^9hGF22q7QP^e68%U<zDiq_(2Wd zuKG*QNYif^Mv6n_uUx?WW|Gm|itIY!06RKhbbOI+gK--cC3D7}7Mf?Ip7tRhiNaYT zN3{VNm;0RUQ>fUc^KW1|!=bZsLYon?JcFwBU5f-8M#cFuyRktuf?fQHv=2Cm4k1TY zHv37G_T=e^l905)JL?&#byc zLrYq&XwIoIdRdmvJaL&9KBg*rb$qRouEX2x!rv!bY7N}baS$r;GG>FuH;}uZ0?kt#h_n8WbCY(4o`tXelFZ`5L zYvB2exztWpA~}gUF@FHgu}iC_mSI4~vDSdjy%>Q}M4vd-Ri(N;VU>FMmpyLD2^AirxaxDJKB@lz_xi*%j7&_fnl?Vm0*dbiid}Up zVES~WA8K~pUzV%P-#aEj{+UAfXDU7bXezGypQ#g|sjV|}$bY8JZV451?)|m!fzk01 zal^PUv`7DyTIu(qve=_ySK;yUImrTBst)#h<2+mH7806V+SbZ82qgx~CynbC&s6J$ z<7RR(Ag$`QGY*eMN6;tW%S*R9QKg)R!YJdn6TP}Bah)eDDz9G?NU1Mj1oQR@<-R*b z`zbW$^+O&&LukL1fre1K$d`bI2G~ZlvEK`y$XD8!1zjl2y1bn@6QZ|q_i~EgdAU*V z4~BkwyKDUPS6K5^3z5}P8r?1Oet+8S@_M=ae0Wsp;^}-j9IJsRnr17oGXTypN*rEj{CbetSkxfyuqE*6pM#Qd2+#)A_Eg+a<*6f z;OH?W@4H?B(hN4%vGyBX@K?f^gwl}M%v5lmNUu7k_-ukyB12J?d{6fN%e>PtBym$sT*2&`DqFv3TOfJ)3$Go`Vn74OYfivaDwtVaGsl5vy!f9lT zZB4i`Gs(Qk2c3)mJF^2ZgYE;C|<>br`y9(l#^T-nEM0k?2VOsBRAlf!(0!8V=38NfRb~Y)> zmA~N#;(Yb3$Hx+4e;&rN=fY2rA&jHCt$sZbjpqUGR#&o=jH;>4%^VBX+|-heU)P!W zWMNc0h5FmUsHs6^{f28bl##P)d-%#my@7N2dUA+UiP)OohWKRGMka)r?e?$mjv#eJ z$MFm1d4bxz4b$R4L_UHxO5k<6LjhX(k!qeHb#RtGJ`OIE@cu?!XS{X@0Kyp^t+(M! zm?xMfdte`O;+j@RLp>KlOEI#LlQA!~*e&pkMoo^$@x(^1Z}vTB2tWUfompwuay`uG zm^z#GzFf=LJ)B+8ut$Rpx#BWU`WFj275$yKt!56o03^<&&Ev&CWh&?Z!%(Q;H!(4C#E9B4gLqmQaV?{u7Z+h3$(fXn}p!BU3A zzTkWk%!8q=PeOeBqEXUm$c$RNO;UEfiECt~uC2~T3IW%^ZkiA!H)%B5#hwjZISk5(Wg}4lb8@EzG2ytG!v=12&zlC-qR3xB z+ya)18V?r+fB;8N8%&0{KkY+7QNv87jsn}_h-2j9Ndpt9Scw zmHNk&S;FlhP)Z;`bOf-;#yzsa)Lus@kANF%HywhS8--}N$ zl9t2W{P~3u2O;oPXn~(0q28my21I=B{-7I4JpPmamrX66l)SzMuu((?AY@p$J;qk& z3;L7g^v{mKXv&*ybEqLml_CqtEE2{KAEd>z4Cj-zjRzHHS`ef$n_9>N9UT!l%75$k z{LU32%b5Z38@wYXe&LA}xQtYbl#M$Z7)cAD6%|W;e1`EqhPEMHu4iapfuNY6{N4v5 zu{=r}8YlMW)g$*FUY4Qk(RC0PQyU23OMxI51rWj&IA5q$#ajJR7}ei6%T_ds>zcyx znT@O6o=Fva$(mLQdLm_Nj}tXUxPA=ipGjSPECX zO9(`Sl?+J)oMdZqQd5&oU!Dandpd?hj0qD>P+s@SiP=X8NaQa!C!JJ68(C^fZaH%2 zKjMT6a5AGJOVGfJX2%>Yw!$-2dR?PoJGvROso;+%&V|%!j@**i69h8TdkI{*pbH`1 z35aAP@dE=JG!h!h4|aRHf2^woFKl1pSO4=dPo_;ZK21 z`D&LU;j(ZC7YmAH1FNb#BWPw7D)N!@3NV(z>3EGdt)g&$Grb17^gweyW%M^zkDs6d z^u{}paOvfSld8B`JrE>lA_(QwR)NKB(;8UZz&$+>BHfrk{ihg#m31^XGCO)I6{E|* zi5pfK(v65@S``b(qVM1+Fm}OTY&v832!eo16_IT}!-I{36qd`0CY)i0$&aP+ZfH*3 zRNycIo>@y1!NK77HPAq0y88z(Z9zej#NoL~wsljf_^&GY^EM;8eGLE4J%7W40eWM+ zDNs#c?O|wUo4{g#NVYF^9A1QOr{c^3utxlxk_#z|=oYRVf1QXWQ8D^FRnrB>+mq1O zVDOXiMF$2@PlUh^5|d%H1XXNbzRG;aEF_yfiA2I5p#GXUuGyKDc7Y2FoRKEsjefii zhDJ7Vx;zf(m?N=$Vo}&40)JOW49Fwe<$Qf&0pKqgd_@zuNxGy%^(OHQaRC3=?EYC8@Q46luvXvyA`lVC+Z6DHOyW*p?S(0&bF2rh zX9+}qFj=xN{JE* ztI+*AN0icl#(Y4Cp0AYN?|_R_2u7BKO~-)eV7?Kg#!oN@WU#zjms0{q4?-z9OBcfP z*U-2Rx-VJ=gs$!0m+(ADRp6Kp!`v-Ui$Oj81(wKna2h!HP}_i@-!2>sgP_~PRg2{> z!z6t{_fym02OyLa(yozq?<{{or>L2?0jbW`IAtA&d0F^rGM|oS!ag8qN>ZMEGK*54 z9bKJ*bwX6_SBJXCZdcwTmxl+OWIamW0Q^vT1Fw>MPF{L+rpvfn%Q#bf@qBM;}iQ z%nRjJYC!=QaLvs5G92F{ni&P$3Pd|{s5hWj&YqhQ0KN5$63_xbYOoP>NV~^y6GT?5 zdpHmW8pW8rF9CYW$9))~dI&4l40vCbZ)PZJ6m4Up3xSSJz?Fi>Vx@R6PY5!BS&)op zQ_VGFS-ghsp6l;m%CB9*dHQRc#EX580`7A_a@x|Ygkv4`*Ti&tl;{0YN%c+V*eui% z%i`D^Ox+aA3+?lGs)?DrRbMG@uJ?ngZMbqZ#mrEzxk)M>|6~6S)Z9d0w4g;nV9Jp=%xIh?^6cTT{7)dcvi;9Bp9(nzy zJI)i%$I3hk00LHht>aM}rA$}G6(e94?cFRX-}t=p^Y*O{9>=6;ZdCx|xWG7v=xbKa zbjz7@QL^jyoB~_ssNl4aVI~z4PF0MQ6;+37EwJtvC{Jl?9!g&aAh(GmEJvFjQ7RywS3*#h`YL1 zj7`k^F}PT0*`DzrN}8?{Y3e+8naA5H%>e^VDWd0vKzBw61I@}EMotBGuLT8W5qcPM zk)20)@2h-b0jFywYQ!!a1zb;*rQpD@*>)_}PDC&i#URxX~#!@cbj|Pahg*8K;gh zp%>;P34z~)Heve^^%P-m+})I`_AS->IlXDe(|IsPPcP9>@ndOSv1JPC<#QXY3U1;9 z!l{uqi&^V@3~uvSFHR4cpG*%lGr8zZU#r?uQY-M5Q2+9SSKYu?tBtpUE~}3p6~c9F zmZwH0nC0nRcU!EsVV!4Zt@G%XE0&rrfat{uh1kTZbfheWHd)c^`LLAD=mPLUG#xe! z@mxoy(ojt{e<$zHd-|%bmgVl;^SrX>711S#)!*9k?}7K+&DC`0?SU+(xfN0_T~4Om z#XY^NrZv^oGJr)bRc}-D#b4z$bmg&HP-M*~wB^1{ZPk^_J(H4j8CyQH7#4D%P0ZoQ z?b!6FJ{P7A&T^odMsj{C7#D`w+4Ezt-EMlNoGS%KgZeq&&%g$d)pkx!o6t`IrSi zrsq053VXC0J&wPGmz{NOw~9gM0vXJE=Wwn6Iag~ggD)*=d*S#-f#8oXY>QCl8B8&0 zJ}sS$t>D6Pg~o+Hz*79{27tO`LS+Ufr%7TC>!^kLIU2pAQ!uP*8_2#f%@DGqbD#U9 z5-yifhx2=BIgf%DL(LUc)PpEqbHG>tbCDdOpCOVDse{!o1!&;~TK~I1ezR7E`Z-C# z&{t}*_Zqx28rj>t4OA2JAB3twBIu*ddFMVnn^c?Nza;hI z**Ny%O-ncTmDx6fwL&`^lA7`LK^57k7+}n!UtC#{uQ#MO-)?<#&i=~1?%KiM?4Lxt z&d>FIJ=NMbOXMvc-dTq>;IG+NGsbnI=tmhC**VYeiS1U+lF^%+;;zkOujMJ6??b^i zw5S(21N2cL-oZ};<{UD~*zg`oBmOHm@K8x_m|e^WajSf9v)NAqTB#k3Mc`wno>4Gp zD4O&w1cgNU^!{^PbVm-lO(@AxaO8U7-P{pGd@12oJD7R_iHL=%V!L;;-;$m~wnX_e z`@|mDY*4M#i(pLkvF7m#GoYPxSy6?jv8a>fCNn#1v#uG4q6DL)H zeQ6t=uGvr?9Lw}HG|^>Cy1qgFy`c`t%NE-6Th@v$nK1_*@RWIrmO=KN>dCsXC*rZ5 zYurYQ47MCq<_Bmlx=GS9;NitwdWD>c*?}0B3MIHV!i53n&j&g|7MY-F`pDgII8K$e zk|(e3d&QEr;d|}l>Hx!&Z6$l4Zd)ROn`i%pDgSFve-*WM6cQO@K% zITWXsWdWkfMI)r`#Tf1()d_*|v*f23HxidET@4*Sntc3bmiZ~6o7NhdZwu5A$rnuz zwC*ERA2*meDT_9Ay<9d{#gGPDx@aZuU^`Y@gcFZBbTTL1hvMzp$3@8X4R*F)zn8Z1 zg$~cdXG87TA)S8LK6ydm^4%s6PF^U2{!Sl0^l+*|esW7s#MFE{JniT3;BC+Kd#4GXp}3Vk@!d!@!xPf8 z(g8ovLzsH9xmJ411@O)fZX}l%HIyhh1CY`5EmOt-3tOr6dI+N@bBm-vG77hAF%Ep% za1KsFJHA`X2N|BR2uLRvHyJdwF>G}Yhj$-?W{Y*8E!MyGcP-t8Pt6iIr{KbUPpGe&E_lvnHx9T`qy zK8&6wBP@30Z#>PMk_!j8Eu(v~F~j99Nz=P+(1_4aT4|~RqH~vOhDY--@LLVz%8rDG ztjtl^+!jD78symAX8znLrNrK)Y#ccPaxpyK3q>zBq|Z(Hio z!rvj~r<*VN)zSVvzJv6llDkx<}AF177BWF1usm%^+ zzSRMgK5wZaRQu{{0d_}>mOFj(i7@^4xkwdArrlP@b`rVUp9S{ZFB|DER(GIuC>>WP zy&Y0_pp`Orpsk_WE-X>nd>Auj5kir&Pur*+VP}4;xfq)hLRC&E&L6Kcu*|-q^i^yj z+S9ed^d^TwRi*6kTR*cUSlu@0gsL=9I;=4AFm7CCVDSraI!LQ5ub>~{ zb1^ckN*A;iMd^?kqjPA&_9SD=;CaLyky*x_052FUBl%I)4@t-5mfR03Eww#L+q!?Nt z--Fjct?n-iR#@y21!fO3@Ez){gHVNYQb=Ufn4KH;=ZHe@MDE|_N_#b4JCn5< zqnb}DU>{?5mDTo{$+c#0z{d{hM;>$~zG0f*sbB;^x6V5e@vIL(!QD##kT*5A~lOm_+Jj>%K0NPi~SsU zR3S5i%!kD7QyOB8xaI95|Ye~OzLW|I14)Ra;?xK+T3ArkqPk{Dpy6#LAp zrpGu)hbDOv-zfR*5^G18w1veu2(luar(tx2m?<%Z#Ps(N8?-HUK!wNj{}B<(t%Y8x zbVZ6QCKISF`tY2?|1rQ%PW>87V$cQ_9#ac2wrWE{HpWU9;$g8IMv7DCK$7=+~jQ*dIwA zgFp5Sk?0V3{72}+2ILdD@( zY5^A>RqBGq+ukY_YT-NczN*rIodBI82-P+WuYqO={*(sB9GBi-s5Lv!gw!lxn?ziG{*IXuSyA8w&KV zY$Fz$)}f>9FQUWcb#r;X&eZIxS}ZIXGA*%1cm$gkY8DGF zCWaoWdKzY=td}dZcl(jm@|OX*AnIGNM7f1!XyU9RB7v_N@oq$HO$}?!aT*4^Zxs&w zZ*BEJtKl78VD1p*u8Je%;@eicELA#Q_UPl@S;_}d`17K!i;pnQf!J^=dVl@C}` zRPA4%ca0x^pX&On#M4*p%c(P=Siy`$vIU|;;r5MZ#Og;0$WVoW>fglp3(KWVQ)T@U zN40gIgC0207m^D;;kldrCNp2+38e=$LVjVvc)@T$?$&lBjK6&*l2w$GQuzpC)<2}VJ_PKI$&d*q=f!%#(E6=+iJn6b*G}lpjAp$?b<%E0L z#TXH=3RdeN^hWJoEJMUKE>CB`m#zLzO z4M(irwwmAyk|`&{+vda-(~YHLb?lyT3Zm&P7)BbWVzJ0yK<6fE8ve>>P8q$}{7y2mbXd|3vQggzuI1`K>_4fZ zvKjMsE^zI6~8#Xs3mDv%-oN12H}d28J)wcAhBZEFhpToZuBw z8!p!G8U$6eK>tT~O(DE?ZLgkkVkb#D{iZ$Q*~8SS9g^zbjVk%ya#&xolc$S*DM1~P z-!UqZ1@eZdkDTH{Sd^=Z#y;wvm@3Y*n_#lTta@JK3e(zSUt-ug?NVU7?@`RQC<3*H z;Z7bURl%12u3(O`B$vPIzP)Rfmz8HS$CuTs?N*$u{1n#i`Q2l{Yg%PmL}cUQi^w^3 zWuhlaGFHn0b@tzMRDVDdG_zPjc_lNh(Q!gQN7`~Qps0dS3wo`6BbT~JfOZKD%zuN7YsSzi)pGH<`V8z!G-jM zIOkH-0f`t@$v3WO>E$HdZ~A|z*w<)|)min`>@?3|eYI8WQ?{jdasq#-??el5Jf~HT zz?4eCuFzCQan=_^OqbZbRn!Y|s2nq^e3D&Hsb}3kGc1|<^5mSe^|q;xBDZeQ?uCCo zpk-`4g$?3AhkZ`1F5Roz;i!Ei20fVSoOQZddzo5*oRnUitY&I`wW7^t>xnVc@Ug^7 zs%HW_i{9$1k`loc*(`_YWG*EkNsW+%+%*`~L*%GiUUI7tdo3)@D#Pk1=nRvvub|+l z&UJ{OzH3%WCDtL;HE&0&d(O*BOcUJ-+JXEY1CQ_&Rx06 zPOFL#>-%=)ZLscNjq;?jp<#pSH61Tai(xl|)>UZt=k>~GO&aD9vrIKr_v*2%N{T!x zOm1VfsEG&aAQ!Ip2yyQEJ227$L+Uxg-DpKly7e}~PfnzZVf%aPHJ+gq=ECiARcIPX zBvoi@T6bgT=E4@mj#?FHxkU%+w)!eiRcK=!4f-uz%6EF*yNHZ6%0~c!$J6giFcZEi z@c9h_@!R3@y=a{G|3OOs07Qz@{VU{ZBr`X+M%lvpv!Wrl{cg=%*psUQ?e%<7-IrVX z%)CRHl+|Owo+YozK~m1N5{>LqJ|W6h_)o0LC82si!w#x-XM=LUl&F4%s%$0NT5?FO zazDje5<7aMyaLa(|He(txUG${=Ueb6kgoO<`L0Tz>4o61$OsOlA`V#|ilF5fp_93}V+{pqkMl=X8$npszn{ ze1V_-A;+Ryfg-lpkFazqBrPDbp)#jd6T?O=Ce84tmW8~WkobmIWPy6PBpy>kQdsMR zvO??Vu|<;-Rf(K*qcj;-x^d$&Psd1yUS5F~qCt1~B8_@5)F01vpt-%H$v|^+Q-|rr z#@MzxQk99>)v3$NZesdOZGlgniP^J}B9vvf-&8-+-{Z!jPPOh2icju@h?4n4acY%N zX>*3|B))?2rJXUcbV}u;dJlc|Ddzgs??e;(k z;5^M7lD;I?v&GfO9H)?d+O#uPtk>u`B9tklRxQX>_38=A~%y2`NCKI#20!z#yob(?W3H=H79=AH%pq};i09nwuR@cx{^htJ7 z>z&26OY-2miBgc$4bnZ^(tdtTCbJKtlTLLeR9_U%2^PU0?2^XgEdJ~nhRgkF*JkL( zTFr!9dIoY?Jy=3}0gRC>f=nDa3))Qjoq6S0@N|cS3Tzb@Y374v%NfaS4wGYAyx&JR zoz@##}jw?RR#NCYxms zQQ;Y$Iwg;A1$c`j2>V&`$Q=qV%2)&$Ih$l+(p=a^G8vcPh#iykfGU@nX5MdJp9L6) zW-|QhO0O@@^e=R}c$}eE=tyTC&NM0UWfJYU;5wGJiGheE(oLe#lhfftl z1DcKI*C*#aS@zLd>`%cq2gaGasyqm)WplNzN^~8XIzI^!?w1n#&oo3!dBE3Prr(_PivCwpuO@4 zZKzhj?}+Ta@2YdEcpkQs;~O8BIyh;Lca-BxQI)j0Lyb3V-yI`jj=f_BeSVOC;C;Hr zyL}YN3jh=>P>azcEue&k3!OFWEYWN^=26NT^Y&|Lq|xfc9ADHTewh5prSl8g;?6>> z*--u5OtEV&enCrmbWmxT<|N2{3dX|OoqYOU>>1_V>pl^!8e3G)@d_cQSd z!K*oXV@>(Ic2QPqV((zT?pzTkLgO6Hcb&uzi!I$W1=OA3 zv8!)>d9||8-z09Sq;J;KbU=d2h|5q9wog5w*+NHc^`SUw2Y9-(TPYZ_GS^Ykf>lx= zUt_A_;>DaoMd^-c-E`&Ql7+DHgZYGM-r$y=Ij78k&H^+2+g_r$Ew}{}tL4i54=WMp z<4R@zUiOT0u<0GXk7$ONry{sLKi~Rn0dBV@8c5+1huLD?kku{E&c*>JCsZje%*NC2 zat!CX!|?MIE(LgSYU0`3D2Iymatt+Jt~C5WY~W7~ma7pz*2;?!=~XG7C{C-a5@2sO zEIu0?Dn)usg9VOD{hDz)vfUU;EGV92f`AW^c}VhS&-tl42$X3wKzr@5neUY5*JPM< zwkC@_$bRdwh({Hj2472#9eBd79=dchftL&D=<{0=JH;P%OC+C0e>JKv1irP+(~zUz zH9@+Y6>TYXiCJlSgpjd%c(wCe%>6@)>481G2H@ZMrf#8jiofsa5^Jyb2sN^R1{$b? z!nZ`Xar=kPH-e+M$8#qQ>E@nDrGA4+zVQFuBh+31K|Xs0%V29Ha#jX_E~TX!iT-># ztm^8&{{^`))}yv)d+@2@S`Z~^=7K>jvdZ6}Us|s-j6@gxjZbYBwMxL?ZDbsA#dH^8 zvb>ZPT*q{G(&^nGBtMd?1q6xMbXP_hndqjUHP|VHbQU(~TR^h;N)gJ3d7xMxg(!I=i{mQqxb%Z@B=`{ik z$S|Vk{P=T`nhT4e)FVt{x_ZEHDlH?fpnl(vAkx^H!J%+qI}_U(K_u7ptd;*p@gqpc zlRBvX@5`}Bf;$5|K?WLt@?obl@8C;xjpWjnBo{?{u?bD z2uV(CkWPOL6O+JT40?k}I8mrl0#)wd1%79W5^g?cQ2)moqtNDp7b6$%Yyd#aBOgnU z)AC55WtlT*I;iseWdu_Ir_~OO_;0VARDU@1oc7{V^xvYc1Q%!Pn%ip7Rz>{?TdI0#QW!)?q}ZPr`5aOw zZ_khnNl?Zj#B2zWctCFgl;}d8^(pXEow1*=cR&LH5F$7IYu#iZX10YhD1XAEpltNB zF?ir~0#lyC8CXg&?aa)zxq`MSAKZr{feJ-$Nz6s+Z-nM5&#Gve48<^|AF>Da2N}YN z69XoqFo10?i6@p|ZYP@Hjxd&B+)?rW_5P#3$6x&qG2?!BjRC1n->c#F`c}dje_#?t z!MwoOX9pMBRNrY>@CSo&Z#*J~F<+QxU0+Ne&x&!+30IIRN*_;9|MMJ^_|j}Braj{0 zhQ1o&Q)<5x2thQBF@J7Q)`Pqf0B!lUUimwMsQ#LXjZh!h8JP`5 zZ}CJ!MLQeM9}&@nJBXOKSn&TLkj@3X9sscX7QU3unE#965g~rLTfY@0Vp5UI=IVNb` zDyjc);4UUIf$3n34300oKFL)gE2#B9>7g_JNe^lalwP|D3G+5qA{P=%Uu@-zrXo=I z;s9)GjtC+VctzVhG(lhqz>H&kO{y%#to>U824iYRoG*Q_1Z6BYEQb)e2cn2j24afw z0b;Fk;}VMIFuTtOKtnq!QltTX^IWGr*1b_!sNcRYrPd|!cy{GT*9|G(Y^Bk3CU zu3#hJlWQpE?M zbHGoTEiN*WK5Ru1-Bdck`Kr+axr{Y}JFaKsz6o(!#j=Fk`X@Fc_dl`Wrv8ZyU_T&9 z9EJbUA5%-zURmfn1V7^ zM>nE~T*B}KjlziJcm`t}@>HF3i_rx81D)VF>Q>SKViu}{F{D2h&s^kyE$3`9Bk73- zBdK-*um(h}{$Fn$AlAq-7;G{0;T%Qu{M@EF5Yr)!Kemf0??^r|;{+FK#u1dzMH!U; z|BStT^V|4s2x=1X9a z6MM;d+``8hsE1z1pzVbW=OR&L1(YvG*urk1SKnK>l(7NILr*-snM9N=EC+{^5pdnt zc;%YpotRA?>Vp;9-0-&wA}*}Q^ERgV#)wlVV8K-8EIaxMa(V0+x&QO3DoX1g@Q=}2Ale11XZG( zunUko)62?-D&^7MIu5BaS*yS8War{o>H9&Mu=ENUVf{*2mEcS@pHNxQ?BXQ4Oo z%ZGPxTvwABY@6IAMxQC#t8_BLyYMz)A@_| zP!5lEi!bNkwkGrQ$5lu?d9M4{DcASHrh`hhGn%%*5zWSqmDkOPxTYTa>XF{^*v!gH z_k)DPvnK4C17$Z=_sP!33b}&^a@MW}^K}8^$BefoEUP<;Zu@%ZKS7V%1~Zbq@Ki`| z`^ny~Jd3qm-k+z=Tc3CT!`@%URnfL>!#E*=bT`t1gp_niryxp+bSfa--Q7w_Nl14{ zcXyW((kVvX3d)8*kjwbJqDL+!Ub>7Vt4HZrFiwfdU%uG zOj(E7jnUdnyrb_U``R+|mcGyKI%91}Ic~<|i1-`QhYFvyIwvOC+~8b2RF1@%+*xMv zok`~Fooi;L;R(sXtM7w?0fRV;$}8O3Ur1BxUFrGr`Hj9~j?$et<(;D$E!Gn>L76*7#4t8;ZEX!Le_QDr58WH|u9*jY`f?A&A+{*4r9T{uT1a1wGbH?e$CCU;Hc9Oo^b? zsO8O%<)G5%9^2RrcDpAer^k=&5i@$NG0*b^Yc6y9`)sLCT8DGn(@xrw3^~7L+`Hfz zJ0ZdpWKP+0qx^OVx{kiX%}K`Z?=T2zez2ORkoH;31@+4_bDYEJY*@m~#(vk1FM8#M zWhr@Y7|S7n5O+7jxv3k!GD_d1`K|ao9isRx#+)@k2e(1)jQG{fnA)`&@=p`v%)5?q zG^J}~UCEpj&Ss#$k^I)MBh~>s@gUxxcH-&8HsfHWR|*!L3CEee*QP?`)p<^c6AoX` z8av8u=G@mk1IbybS~Mwi=25v7Bx#3^X8?oYhVXX*;70d;}kxEkrk01 z7PAb}p4oREzz~$IU$db&L4FLYIYfxz42<~v{sH{e&>P%|O~cjar?hGh1uN?*Jgwg; zI6wJ3I74S9|I*kgtp8{8^Uh?wL+9K#1#z!Hu8Z$UT`OrSu(^C5>RFzVjum;@4~AC) z8p5eng+v1S& z8c5Q2lnf&(;${?Rg-i5&BlfncJlq>~v^VqVkCBq4sSLkOdZ0yN&SF@$*H>f8hykXCYv&|}q zvyO`G5<|HoF7gu7GEq&z;8BFI1Xo^AhSAcJdpZJb)TLwmrMUZlN=1k@g#d(@tLqtm5IB` zW}RzM`CO`|X51pN8GX*}s!F@J&$N9SW#W)g{4us^tD$;dE>*H-R% zrP^Zu)Rd6MKo~k)k_H~KQEe}Prfve`*=l*uU7PCWnM)rMvHuxtH8g=GZ7isJW&ur9 zbIEz^{PODB0J+9<(t$;~T2rQC%zkj*B3il1z9D%l!M*wcGoq)(i-2HT-esGNu_M8e zQjPu3%{}z}_lZzH+02uCOSo3f^ZQ2q=KS=+eu^a8tXt4Sr?WY9gY(@RW#aT)Zl)mY zuTzw;RRntN4+&&X5DMdZS4mC+s+1TL?58R9HgxJu&9)=Qv?{13wj+0@Gs>6}?58M~ zy;V8l`GqMM5@_NC5VO(zw#WnBraF)`d-f#Z zV^^=5?lhm!!)Dgkap^7ApS~zI_v3G=<=U}~dmHES0#DU?NPxPTGiMMU0+zIGIHe`6 z9(qx+@dMJ4Y5p}-XCFW4nNA!u?%I_p;{twzs!fKFpkA2%cGpXvydWCd3Twz zW2E()HOGnMX3;^=C;n2~1fZ5xw?0hO@mOPa_7UAnWb^*Qw-&+An(gGu{F7^yczo`I zmQoS9mev#{>Y&uS+r%*ZKt4>;LzqEw&|fE1oV+fz7V80Y%#gTI-Eia|h9Nl4`pigc z3qc#)0EUaoz7r>J3Swvet{5QDKNQE7N%)DJbbZeK*j%MI$eqiT$(Lmq&c!DIL0G-_ z*g8eY7S_R47Ic^K0#dmT0&uL=+FR~huyq9Svz8COY`0fZX8|!3oyp}hY8*dE{GZeU z{^|~pJL|uwh}WJeStA~Q{WAI0pBNXeTuA-)G*Y58W-k$I8Kc))Z95WrCZq)LS0U$I zXWTISN9Gb*9*1*A%|BJb_$s5iFleBfw2+)2puqC^Pg7EPttApLtZ?7aY3LB}cJN{K z#5RWi8p1)Bh=^RP>!sPPY|#_CBG_>kS6V^l&Ti|37h*cyN%@E75fpp`JWOuKO_j` zzl-Y$B(5cQ-fn~59z{Yghm@p+BR_Jzry^T!=Py8Eru6pxANXE?d`kQzPzr_>ye!-b z1+)wd{pNUqC^4pPFEsz7NTFdMbxPI}v%+UCh9q>^h+OrlF1qZlsnjSh0F4d<&yFJV zm7L{pNznZEeLuI85;P6q)8BMyA4piVA0_f$VOZuJBwqja_6+ov-uR~L#1xV??mm7C z55B+$2ntgu21==cP3orW^BE=c&nfGHLkTn2Gs=?qe(Ohz;ii*=j$uF%d@~s@$cpX` z0k~D_tuv~er}BoG_7(j)!7DK`DQU)XKl+$8pTjTVst1e88{FdservK{{G-=oi9D%} zRe*mS`gt!3EEYhw_V%54i~oaLmW&*O52%DuTjZY0xd>G2=c#M@t_m;TwWb{)H5Z_H zQgM_yqhd%xnj``hPzbF9o<#w@IZ;Z6D0y@d-KQ)xD@eqGo%>#uuG0Vss%MpwOJ+}A4(zSB&-Y@DlQOW z9esCa@cxPh@3J%?+J$qIrbgC`l3O*uV~l%xxiP8LQqt}FR_Upptzd5FX@6yC6jQaY zdBf~(35*;mOmo2_bYyexA0M}9X8mBp-jda#P+MDZ`h2g8dbS5|l^}Sp@^R`TjYpN9 zRT~@;-_0n^a%VDYx~&pqe!kq{c>Fa3m9A(CruRhhrQ|F_ILE9XlI)Ng`sPLE zBa;V}4%ECqZe5&CXP0hAFsP+i@Q`TUt5D)~$9^)4Dw-}7=2ZEaX7*LxuxmD7;}OQ_ zi5z{=RNTA8{fv(_8uqO=q|XtdDD;w{0?}3?ac(Z9QX5APZL_}@ar=Qtm=#T~3Okjo` zNpCh~6{R#fpPk<3@IMY_kw7vicuA#2H~C2@N4>m0(7b3yYTm5<%bTAjJMw{b%E#*5 zW8zvL_{j>!Y=^N%zf|GFh2p9Q1uN()a2;gqyj%&TogthHDCX3FX*@q7QkXEMY&6Zh zR{MzavyteSoMgs$r1|sw@xD~5y5PmE*SEFZXH9*A4-v9b_yydff$vdQoz>3YaJ$HO zggo>NM_t62rVn&Ws_;>1h>AgXTa*tUWGwQ*XR9Atpli=m@e`LVLdFZPe>qoJSK2Up z(8F?Cand6ilIK)-^*+4=C)zNPKBF!T8-=AlDhKhY+Me_i8vrgouUY!&c}63xs?xL_ zyECzV^!S~+U0YWKq{>gl%yraJGj`VqP%|SjiR+4OQ6Cufvlf{gc^=$6bl%>@3wpuhL?l62FREMagQA^k@#E zc_A$cZ}daLI$xGxPf-UX8MRXpjUl8|v$50xfoT!j zt+oOE+q>`DiU8i)@=#25Gw@7-@AGcg zYcW4^D{hFWs}7iS7kgaluLCx9ji)8O+tqN~VoXg9!`<7CL40H=F1v9{-;DV8Aqlum+w^uav5X@v6umU9r6w$y#l+jK`ckD)YhYWu5@Q08IwtT!1t9f|_zgW> z|Ff!LRPQ%2$*Sg7PoD<($aaun%#>pLmdvtF%2YdR&cxyDRvCOTs9ITy?KC?-Tk(98 z8Qf_$?LWpc;Y)sBLk&esNiKrt1%Y6U5yGxljW7JTu-6wX37O{{Pz?30n_Y0W9VWEd zuLN%T#D$VrtP#u0V#bWC8*s)R!^lq5e3qLHd;P-bl`&6++p?$q2V<=5PbeH$^&jiF zOF5Zf)s(Qua@_r04L-lIa!27sHIt>+{9an>R*tyoa>$4S=edruYVfcte@Ocnf8|*V z%E<*$AqV`IhJICh%PO@^m5QI4u)TB3nmz3Hf;8{l>E2}&n#prcsy#Z@cmGaFNft5D zqUIbngEihF)0w8lBlp3%2iv64rm2O}PF{(ot%cono!@e0+9LExNvxpE{PZ;??u*4! zQ~7{lMyAgpCQnnTn1UK_x6f?T75Gokwnfl&3jG|3aa;3;KA+(WV4D@Y(yG6|c;T9` zBJ%mX&23yj@vVTmG?(kChxnz zvxM4Of#7F?fjmipKfvvVse`db?9TYo?^G%?oaX`JpBD?om=oDbsJs>u0}I4@_5=v} z71rXlt8kkw7`+zM?tu%fOM^w36F+EFND|D^y>}21Td`Lv-Cp zN&t3}ZWx10aMPsRKYIL9e&<4=7{28VvM@!6!;~5+jp`k`q%W7xK0y za3)iri;*K;*;d>v!xzJ7S)3w-3%uS&P(4n;zUUh9y{#)$6yH+ZjH)F7+#{}T(rh7a z2I2x={XAqw@?I;!Z_xlE%!!e2K*)v6umCaOO27y;q*qCiM1k5|l$B}#UYBH*Qz1u| znEdLJM_p;B3>QslG`Oz%!)54zA7qvBcT4}W8?ZYMj8oTpL%=}%0l*?a4@4kn>hom| zKwk*~`#4|;?qB>9hZsW%7}^gQ>T~B_)r8l=FSExf3>-+8IY76NLDwOY<2J#yIc5}< z)o511{nLT?2AWpLdR&@bHCc&Q}{wq4; z02!nI5#77wpl1Y$^WQasJRE6J1mhqJ07V79{e=$wzoD~phYm>NUwH;(4+Mqh%U@4G zjvD|5jDQ&h$>lrNnvruV-rKS46EhaaA4r48{ReYeIu#;I!xwyJUiKcFL$^MtE?973Ke6X5jM+?nCP@X`84+>CK{5*5k$ev zpBj4g_w#1JlWPF$Tfa0w-7nan2JBBoyN*CSWtNiM{{xLR1D4cZ3AUE>0*L84|)>xxHKwMTbRan3xI-uR5u{|EP@p9TF(>Sn7$?$nE$Q(7i}pxvFUepx!kRT0p^`2 z5WV|V3Gd2@apb2>*9fAZ#&rvEinBk$@T&{Wh?-?je>Z4@hz`9=ia*OmLKg~-Vl6(P zQMb1TD6j3IU>ZYeIFR5#gL+kuW<>o2Vcz`qc}n^3?T zO2&}Cv_7EfCUot5yDPY$QiwUf#sVIoPiJI0kuKXA{87E`n*Uw1`=_}OFn-Mrz)o>s z-lzqu@t-97)nb){GZrc#Jx&7Xaj^fXjN9q`haLy8a2ArWgh2ECJ*WKP>j4a5?*w zZssA&pS!9)7yuiAI09e+^T)5&3IS<&<2&=OHXyHH1i;aN0aVc?$|m0!a70SC{s3gb z@7d^XmLVdYV}SH*A`%;C4+U|1)UMd8dplt_mn`o zyUj^w2$0Q?yaYKz%G(VPi|q~J;J{WfFpH&oU);?QO5mUb5+Dx@0+mGFAciw+QpQP` z7%)-l4?E+!Y7b)t3zV+E4gg09q9jGQ*1KkU7QzZtzq|Yk@5NLD2ZqoA7)bxP8-2jc zM5EFL91omXtj2dE&GP2f2AKhjk^p27X34|rFyd>@W`i+IhsFIx(gHYA2&j;5hHvI( z9qf;6gKs$yb3lLyo08fDOin;@gOlJs0iv)BI2?5t(IUI}!2tC-WabPR4q{sV=2d?` zpNLKXWcSS~uqMNQoT-ReeLet;8n7OMU1rUBKjTBzp=OJ}Xej*Nve?lTI`~4H5g(|Q z4qeaS@AUmL;O-JQy&fX_rVbJy<`A62`2oudByj7EhJm(NvQ8PC>?`@iY(E0}HsJ8L z>4nhvp#Q&>BXc%Zw~O58!7of5uk{4>gR>!EX)&&NV&iZBQcNGGq%!XjATogX-uVY) z(cla8JKP6f-~%55tp*?j#3}ITH3SUC=b+aRWI*Vb*sxW>f(#seAS49d+{ffE21oUO zTpQ%%6cEw*0c`k%b3PncG*eQ^K#nzlmi-Zm-+=qD4a9r`)a^%jqAr90giMWi_^5;j zh?p7_b0XsksNE9aaF|01pjQCsga3(Tf0g|!06@3_9jV}b3F!5|IV%Ks-SP~We;{$p z2gY2;zKIsaJCLt}0h1swf@K}zFqk4BjK*!3WdFYo{~{QebD+OKO=ti1X9OUT0FCkn ztn>X_?CxTS0GZqV3;-pd!4sGYz@yOH$E~pC8^u*Dpdk=2pqL>s)nq0`0uwa-5BBi$Y&CX{{t9J0FnMfaM2(-A%O?#)}2uhc7Uw-Pm%uz5O+EF zJ2-a;LJ9z24sbIA!Bm?uf3xq7ad|b}kQ7!O=YG@ki;n06T;Tg++!g{OnSM5GKLH>+ z4Hb!vl7SdCakkv$B7}4aj(#meYskK1A*||4w6eCVU@-m>-DB=MvK}?1{ipnE4F4nl zei;W=r@!V8*k9lN%8mb!Bh40&`cVwr@BK=nSF=~ExM&3H04KtnIKkZfe@!X~x}ZaM zh=R8~U`c?~cfS@$4DZsZNe#g$WTx*oT2vmXSSZYkglamuzrx5o{wqg;Y4$EvewWF= zibtx}xJ*oq_=G|EALe)6wj$So7n1$7t?&H7`Y3D$6rFM)SD6zX%)qI_Yo^d9t(o`t z&<%{aRlnbBzI)tSOIArwq6O6oW(s6DuDF}RA>#n9Rc(jJ{h0*@_Vi4i9iX<#+Ct>3 zAyLXf?f|}}THqMb{#ZNTVgmly!+P_G>S5#U@fz?j(92FzH{f}zZYQgPOqGIex92H0 zTl@YgjkgP=FI+AYwv4o{eqM6kUR)b#WyXBmA=JMDh*}nfIYzoW|p5jvUnk^yNh#m`s|tDCHNa zx2pvx%GVT>C=Q>`M)yi1MQ%z}vd2g>q|?-Od{T-nO4}?ow{ZwvY3bc?bS!z*D3z3Z za_rOKs9B9!ik_1^rbXt;zrY?NgQe9k+^nKNJ2i==saLIR;iTzoW2~821clk6LaU4gRjC=M)|ZHTNlr(=C-4^`VsFeKx)#ghRO#t z*u2rJrr3%WMH9|&!c^{fa^@qGp(*8)tVmx1G1VkSv)VA{*TR7HXwkFhedcg!8Ciq& z4xwKN6V?L*_4F`$1P*;BRiBhOvIlEwiVe%mn*)|8rM8*tE>5XtmJFJ=%p+EzuZ%Mw zIpP?QYcxJk@skbhwQo|BxsYSfUq65DcG=)xn_BpyUv}%!6vzGfl=xMZtXoUl2%>w^T+ZSi!|c4m~NCcZ#&}V z3olu+G*0y%*8c3Av7HS+->eq=h+sL3*0)tdDmiZ3Xno_Wd%tjvcTH$JWM)dqQci0v>#|J9vnD!S-V1dQ^z-m_Ps*=6x`jj1lb)* zeYbn`2Y3qSSHE>WaE|A&p1cPCsA9_v*hQrYkyR`Uk@d{Nh9A%XGdr+<^@ePv`sZnX zbE&1m;Z_PaU0paF1voMbB5XGVxgNLy7t)TUAb3PCaT!;|8KVYkp zcN5*oNp>CGB-3ht0@g+(*?}5_t)?J*16A)_;fJV?&_3c5%z)DXUFfO=v;uo8S0JA7 zML`5xaU`$#%LYSC=f;QZB_>;jtSB>42jQ@Y3c6cK1+1(KfUNXqhuE?36dJMvyVM?H z!)x2Y!=&@@H?#*k5D9c+5UaBTw;`v9^^j9q)Gfybwp&Z1?+we%E_pH{pO-{I9yT;D>rs{(x=fH=#O%MO)_$=bV0wmC0+ohoq3zB-w>G zVDNV~AoeFkLsU++uY;%DhopK_7i$}hpxpO%cb6JhAuH>3?@n`9K;u|=z@>f5n;;!S zMeZ&|-Vth+2|P`K*hZUt1883A=e|um58q!+bO#J|upSUJy3s?1FLmw!V8939W!Z+a zJO*hSKL`=U<#`wSwFL-jGdM03_s-Ux&Y60K`Ey z|JwEE(tlj|U+Ve2>+dH0x3m9f?*IQ{{+o*b&)2s5-1`8O|L@`d2n36L?hF9B|M&2J z1cJ>z_j~}||9kj90>R3T2^Lx7^?4ES$cEk}Qup&EyjxNzsM}j8@I^mV2(g73U91Rm z6>36Ul=j^-#P(4C03NBJcUiLHbq(SHPiC%9ad#64xPN#&Hn9EDNx}cNc+~_aeRpBX zP6Vkxh1Ax5q@A-dggp<*!HzhSI?v}OX~qoovjbv@S?aOg>E|a@!q#5`e)_4uh3~`H91O)5MRxVF}FGey7nFs4=I|eT?Y71jAD4%A0AqPLVa%AyWCxao+~0 z(sOs`ygl_ZrhOu#h+zj#Q+mxOPK~BN(-eljc<&jAr``4@lWzDY($&(XU8Iga!+ZK~ z*)e!$@kB1}r#G_~8As{d7G@aeYOj8HSIqXDqVQTsg=X>0wR})}C&j3~S#QqM|8C`m zibxRIYb;i=+<`3rh!I(7(rZ6dSEBn3@3W`o*}hl(LN$v(Rqgv zF1J79OMShlGmp-!y}v2&A&%8%V(-BM(R0?HH}uqxneOi&hSN(_+sB zzLFGrohg@6HATvhm_FuxQ<7dHt@%?3%?Ya@cMXLTc?Rj+K|u@c70R;(JgMOnVP;bP zS_jN%er&G8k*BC5%*}5*LuZ3D^)S!ax5+8rX?xV^JtHQNVG3#?qhKRr=79G+TNPc5 zgtpYrC=2#1)p&?5asMe-?+A5wOl9T0)h$}|qK{O8qul7s(cVX^gqO+v<_vX;Byfw8 z57?N(y6XtmDB%`A%Ah-1(^KsAkZ#`(ew;8(Nr5-oqT6FAU{K0feZf%|y;!Sv^k-(| zyPAX(ON8y5BF)^s7=j5V&@N7QvXS{jLWD2%-Zp1kV|NX&*`$&m#?Z9&R6$##^G#6>r<2T@6o%B`; zUgO@J#t!cUH_yAH-PT@*4+l5f-(G*;6}&yXIR_r z(TV9+?`m;Ry92r3)Z0OVX;5B+FmA+WlrwA1CH^O#4 z+Yh+Wt;V`iT5TR%Kavg0>x&;4P+=0+V>j|+HX@FWRB~L)4k_qy-hI|elxMR>H>>u= zJZj{uLSSWqKJO@%c16lXzH5yCn~BLfC5kiIG8TEb4_|llW?eD{D~-NTS5yQJxrs1` zkLiPHj8dBAXI%=EhJJpJZKDakO`mVJQ;iVF^)m$foL&|Qt@)qLH@aVL9iB4XZxp!Q z8xO8rYOEuXgL!;&LOrw+T%=W(GN5^NS$TW4B6y3tx{gL7bN?PgBU{W;iH={rJYl+x zZc~}P6qgI|pA~t^inOl2$CBQ6Kf5{iXA=R6w$@o`zbiPHCGS0$a(k{dIDdPvk~Nr8k9C1Hbvr{+ z|L(Zeh3CzjD}uQD)k^OmVC_254zf)c6#TtWZ};2I-CJ(_xvyv#1Lrs9DGdZJh#bkc z`@oM*s+TUhW}S_mYPqeCx^QmsVbtx-4zBSCZ;!?|;7q2RQJ1P+Q#TQvKRup)(mIA%@Shw6RD3c8jyYDLa^IsJ!~dtPH%5$tKiYyhu8F~a!GI}{O2wY zTY>%N7l{Hclr5HL-}sjGWUM}^bl04 zc-Gh&*{0E-4p*%vIhC@yEUY`#7=hohQlxfZ%VNZZKRxadl;~tjVw-+l9wFIb@z#W# z+$a+l)6zwc9HZPB4^wGQRZDR)@qe8%sczp2t%r zszoJlStcsKlzLy$;zC@^mCb$RO<@WxcRg|iu382vFlmkB1sJIw?fp0_VN&M9Cl9$A z<2+FCF(w!43W?w*M-qh)L0CLzUtaAMB2R{ZXZ4#?kpB-P(%Ai1Vi`z95Cok#Bl*^0MrGiKam-ObT(%72O z$g`;HHll8P)b|)EiSZN-Tn$1l$Kq>v_cnx`=8&-A{Li-Gs@gawZV=iyzqYB=>%BEn z4`d>N&4@n(-NKshqHfUEz|h)9O%|eV$WBYHUU-n(S0e1kFY%Z6wjo|-u3kGx%w*71kPb}UME|2 zUu;ohvx`9(&MGCCv`O(TF6dQ)C;dC{l%lI!MCY`^?Jhoj2=Q2@WcpHFK@sfaM8aQv zwh^YWtjLzLF7xfkjBCa1gm;2rVJ%eEO-y_`CmJr3_4J7=RoD(9GI=@!^@{%rB?|zdJ)g0EIm2=V{gYy8fId-|2)ipoC3qrG$oGougQdp^E7@SIuYNe;px zwDlbIfGyLJ@H7-&4Df)5Vc`GuV&yREV|p zI|X0xmG%)YFHZ?+TgPb{QojK> zbPM6o704lX+bA3u{q^M3$9-}O&kzUN>L=DBva5bO#(Tmd!w&uO^>|3dDl#L! z8f&@k+x{WHR7MeAzY}B+CsOl_6V);KV-(E=|6M0|Z;JK@5j>YUZ45+u{2r>!~< zzgr#-I-)?_?!H8-MEr7XJEeU#V)2@CiwSktYMByVcR=eS2iK6{)yn7|cQMmEQnGc}$b~JwIqE`H=y{m_ubm#^>29QwBv+vaqXEG| zq#X&aDyG38Hnt1MpSfKKUy=obuQ-W#3Xn6scIVd({QxG z&=0@MfCr+(u`Pv$od0avlY|35*DE4>Ot&>rO@)DggTe8AmmdcUGunxYpX)nMOMOH5 z6qNdmrl$-{?|Pv^F6pFzv4b-(5;tbFnrYmty&&pVKk8eQ>7hsHtIYyLCtuJyBCk!?snIfZ z;!*w{k>zGcL>@vS@(>b{gS&|E-9-fLZxKNx(j5*+nh;T?0mxO7swjJAaz`#DjlTaz zF2@OwT*UynUPj%KOIFuE%aJWj!a#~ZKFg!pS9g(uXSuvSikY&Q!?v?Tn9`Y1dTmrup=|KeyevgjjqrI)^|9|4$ok8P>qH=u zSOKq(d5+i+dAFibuR~fgC~X`l(u)W3rTyR05%N&IMSS&g9i3iEl-`}l#}|wW$tP!B z1aHzq?dSfAK`eR&+#*PRF~|k@YHZ~?Z+nNrQu#&T{le~-+DuVvY5AhQ!mS)4pNK^+ zJL2PML&V}$Uyn$RrVi&zf>|Mav>|3Q^}!hbttTrAFN2N1)A9+)ry;GqoCdONAtN1} z1_}Cc@~v5|4cM(V_v`0B*54E1v%F2P3P9{Y(Mi==FOJm4FJ~p;dEh5RXVV3|X08v( zGjHds@ElJ z{hyELKKCzg#in@Qry^R7^d=wsEV`2Hmt<8uQ}&8M#f~v+tfw;!en=~+Hy})+O8$L) z$Lgff%XfDB+XDgyn>mH$9l@I|F1RSoqSg7A0w}h09o`(bkM^@{#<1nn#0Mq^8VP%B z2kgf7t#Dhp4V1;!h6pyEq_hhbY`3$%qOZlYNilM!F3ox77=%=-`yjafxnJ>~!+L$N zz%iQJ@&_l~w;eZqlQeh&Pd+O z)4W>?Fgv|(W;i$5XfkDKROanq%)ee{!fD0qgBbg^u)A>r%k~UcB2E{YT1^_QfZh*Dq@GjkX3xH&trJe(7r+i@+(iP{=#p= zHdIPDA5deUB#I8<&$5~eStna%8Mk|e_(et$H!A3HI|Gy(o@G{*xeYqB+>J==Z=a9fgiY?h%r>Yf4G1~dI z0Q905DgOJgk?hkI#0>T_Hq-3J6;l<-MY@wNLHz@PG}G+y?*)%zO%5ju=X}q%FFLC7 z^;DG9MIM%`Kf>WSR_}{J=vFqI+{P^bJgvn0DJ)}3iMMmOcl*2ihBiq6p z+f(1iPfS$u>o5xX3RRu-+S>|O9}>0v0Q(UAK3<(+=X$+?i?lT67$T@~V+ z0o2$&b@kd$!my@Iw75_7CikW6LJ3i8?as6_HZ5vu1?V^-uIT^Wm7gJ?D?3J$`Ahj4 z^+?v!wnrmX`CCH;#&%uae!X6X)4S=!=0*@dOYPAi>fwHGQ@ z9j407^%Q2X1CDG=c#yn^5 zp%eStm+XTGd5%Gr*L~jG#&mea-RY`TAsRG*iN;*pKvXccqp+hBw$)H$Y6WVx2`kjL z)dp2cOa$5u;k!O;f9g9aGnufQ8n0ze(P*_p|BCqb9`9oUG_@xmq(6sw_d+XBmYLW+ z=wYulmKcr1t~Flca*Ef8c30b$wiP7ZTrSw|0iNF2?yFJ4BUx@WOvK>*Fh6brh)Ap0 zklw@m>F7M~f3MxOnt435SL#8)=4{EqH?<=j>6ulu{Y3dh!0%SDJ`-~ysGUpHpUhq; zHt|OjFSeCcG%GdXR{hDaQED<~Tw=nn)n0gxouKhZzSM;E`(WYgP92rq78g5|gx;y# zGz?QFJ-)ZqvcN+Q>=+?=GEGf8xt&Y$T;k<+Zqm}aft}LLyAt|w4A<-rm8JAb`?5Mg zy&7KQ;wK!h8Wt_r^{R>W< z0^Or0>670-91*e;JMHW>BXDE~_B?lDgzw#<*Ki6|V{|H5%Ufp$vORi5%IUe`);W*D!K(k{j0`Wh+Wbkg+9mK`2kDWmik?{U8kcuID>7nE4?!U$ zPYz*tT?3-}i27dOY#1C}Y*N*Wqxfs`x-ffbSfp8f(ClrtvX_n3Oji!p+&ZUo>d%_m z{^%H``C;14shu4Q$3;Q@3Gt{rH z)Un#Z`+_JzUz{q%yC}z<HA}Fm zabB*F(e5CyX|eW{HkKcD)l`XS)uoSWl-1ne3ccJJ_2-$U6T)S*g>OS?ZgjsPH(%m& ziavoUTBE3?HELe#G@y;X1b)d-;P&kNko3jb&l_`jdHa+a)(R#;WJzK{Xt(2W?d;8| zA<;7u75kJU<)-ZY{?!eQkAk=9yJYF3@Cv)%XT5C>*4(d7W={MP3ofFz2{)Gq1zm4f z;LDG`o+&Y$|9p!UJg^rw{g6Ts^JX~(&KwO{kblt6#enJNVvV$B?ZaNH{b5c*#rVsb z(WAaV1ld@tN)+v|!)@QIud-x6)w7jc|*PKfO3F6tzuuq%XI#q~hV%~-l{ zb4ee{XVm-fEKH(TUX(NYdQh5>Bl6= zWLz-J=6VTXi!}JCt^##J@Y}+>Ic@f;^{#SH6v%`zUIt4S zRLITwHK?)@D}ASMySZ9o(sGj%da}9cmCQG#wRKc6_B`_&TFC1G6B6si8@08Gs#Hn} zrJJ{Px;dgfq`d}diW59DFFB`FOh_8Pm<@HmJHA-lKzI7I;Enlpqo}jBEHHS|=%$^XoUXY<59y$m-9xz!|f!AKKHN>@@eV;ASES}Qb-2qFy7hS< zs|5t7y#BWvwr#a_we~?ujVr#E#Wf0kb4H)`LGaFC3Q^eR0F$uy@ClZ-e)LTxS!A3cAtS@1VMG5 zGs+_x;cDy@Z&>#mU5R@LSylaWFC4@U-*MI(tCNg2ml= z%=ND$IxDn^OM%nDTiVGFdMOo^VosV(ElyUvd;Yo6lS zTaNxH;<K8;* zrPHIYMuM4`dY~HR*al6n2@juNf>oT0f}q;&hoY+6ilS-|fTGHpfl<6@P6bU*)bu(6 zR=L#YB~Ecr>A@30IFxxzhKvA8f8z$YtyvB%G$J=m(Mv^(&*~2a_uK&0$+0?>H6RC+^ z>_j*UPnghjS`z@_@4sq4;69iQ(8f~d3c<}iSB*ev!aD>cz+3MXL~3x85)(~c&6Ij%CNI|=&>3q;kgWe9fsUEa1$i-qv{ z>_%^!hoVw(L`?iRklz!0V<|UUZyFkY#-Xi|x7Dm_&)?LU0?jKVuyy zDz2-C-D{g2OkaxaKq1!-RXX*0OW|)RLM=q^mP-#Wlyi?^j+ZP%5xRGt_j8%%tLCeE z*r>33`B={IWARF`xVv0V6IbaT28Rz?sk}UFm+moir!RTnfTCtZ zmqI7P0l!w~ovsL%zeqhM1)XPY649p5a!Ia(*!YQ0M~CvkAJ}9f!GVPZz(ySNzhV>F zrpg(GuSXe3!Ox@(NZ{pzV=(o4!~K_2~5_=PgH;_-+9$mN}e_K)be7> zJkma|Qbtu2wt(GNWj|`G}VLtM&dTi=ihKS zE|Cm?ys72&v3>!7GfTc9*~C*)E0Xk@U3>p)F(h#~9y7>NAgET#HAU&uqN-9yHoFnj z+QKMTKttzEHEqnw)zFHVHbu2w$gAGLa`nZ!39Pj+%KMm`86M-+6*$E`XgMjx#hm^I z57plbsBNvahr8(-q&W=RIh2sf&`OelMC7cqG$#|dyl4Ka%x+7;Mp3qJ4 zJF3hhluKQjgH(B)T5>B+teISFaT`ke9{c;$HRr**GbudROY;o2brjXP8zP6r8?1>g zNaA#gKV5)lIA7I5)eU^KGn2qX0Ag`zeusrSB?OCGaR?Rz^>9w@rY(v;Clg`=kUPxWz*)&H$>GH ze?{mmoUgnkecr*x@bsA;2H%o?fHNCBgPDDcnzbJ;G9!T+OS$3O)}a{Smw}!AP?1Sc z^kF9|z9og&)_!35%KLca5C#{J(E6&$E7lECT=~Av2Ogz)L|Z}4>?pKc9}!lHZxlCA zxiP79-{13z4(WuC*6-%i8K;8Dj*GBH?1`erhrfi*GbE^b?WMF$qan(zA{&Qw3Og|c z0mwwkCW*9oIl+Bwy``G^(?`uH{%}^H9v;4sfXlbq4+ApDV2Okh%CQN|p(t!w{AJwG|J7Kc+An%)phmz@(2Q|lxhms#~6d{Dp(>KoGM&Ek6 zhu8DB4zxC*+(ajsfvP(7>=Bzh3LRQZh;|bVy)XJn*J?8UCzhxGR$Rn2@{IaaPeTaw z2IGJP64x2T=jCgs-R`31!A$=lbuE{H*PeYe-H4Mu$HlVQuWc$AnRf*fpwR6QqR<@` zsK9OxrTa1QRj7hxF=@K7t|w7??o_yf!T?K8VijrnqYe~}ke3BoFqeu&swWYHR|?*G ziaoS}Eqm9961n(Fi4qfAMtLAEZP_l@1^DfZnw$FcB*+7w+_BS5OXV!^+Oj$2LZYZ} z!W5|On>)Z0pz4YPRaYFSy5d096$h$r2wgY9J5(+f>4T?fGZWok95Zzl_c3oe9*f(W zy>HJx_`Zqn%V^JfxQ=gdN?57YD)2hj3*mo(Oz(iI{WO7IY!U>SSP}>_rIb9?2gKjE z1I|iE4sQf_TVv(o2>t3{E)Dpy*?R{^p>;DbO&$RiZXbqOviKf<^7Hij^_e(T3%O+z zTD}i)5?O7Wq20O=AJEvnIVgEwlTNHZonbc{*(+xGL@YcOc(`}4=9MITwoV>TvqDr= zv`q_XK~p>MZ}|7}J$p^+v34WwzC}?D#lOCVnV(91Ibfp7el6- zxnjZY{iW5?%*N0Z3Tf3j$iJ7YCbwZMII0LkSCQNGs#^Nmf(IIV3ubYVSuqN6aiFt+ z%g|l)9kkz$A}j9(mmz0hCzs)yY}F0Q1n2+q*Q#kQy8=`?y;&iH5E8|pqdG1>5=Edp zbryREtuJ%=F)E6>ye8%y7HNN1TmeEVmx9yKUPq;jM#n0UKDO9ij3BC|fO6SWoFVaq9Os`u$<&{vbm^VT` zs|k%R=Nq*t?ufITOXD4*l4u{>0}dolDQGgXXv0M_oTv!)8?DF9@U5z2N_1glOt)LF znL9E`#qpmgpfIj;DG$sm^bG1vqZO>NY`X8K$~6&o4!rAbvFvL&+{(le2zS(AX|vTN z&5AmC7Q-ze65qU5B5o4GoVMneKTJ%CW?c8`|Do(GprZQPwy!84A|OgAAp(NZ-KEk) z3Jl%d;m|1}4TAzRGzd6!$IvCEq;w1=NSAcOcZUD-zUx`vdLI40we~s#x?r8(zOMV; z_ugl7_V6@EE!SIpMo^Y?qQ<#;sj0=cw)CP*PBB%A_0^9z+i3bt#;Iw`W1uEk+nDVf zw1FkZf6hbnP=%rqB3iO81&)s2CHqL3{&16VqE`GURkQaB91_nvIW~aTUU$!H`sqZZ zkCB=@ihj7UeDHZR!X%F;NVD9jV1k0y(u88&Dr&&$NHhxUK?_~PCw$bofqC3-LTw}I z@nr!AMJq1wP3pcZ>BL%j|i0M2l16Plno0}zjtS|YMhg)=ij2^kMlD{FOn>bWUZ`HaMu)^v z*CUhS2q6DJjf(F9`G;czMlC1+H7dVHXh70=T4#2z!S!+L$7VyZ7VJuM3ROz3Ywx5! zenq~ZsWcX$SjPvw?v0Lrdc%p?6!{{`*{KKFr;J}lD4}v!5CrOcGJKklbcbe04Mg|LO2 zTqtk{>61qO>@~zFK1ca*zYkPdq8qiPut5%f{8WqQuEZ7jKRv>8YSoNc?PR+<=>Dv& zG;}kEFrs>!I6&Jzm%5YVCVdEmVj+v{RSuA5z?nkty7qpfte+vy^>-u;A_Y-vdykGr z_-z#5QUvT%Zxs;Mx9Kc~tk(m*P(&!jzfGL9$us!t?XK`CneFf^=konu9$#i@{HP#a zwzpxsK0Q`tgl(s1@v~-`NofqwgNliFRBr&1iGNZ|>MN%n8ER(HvYO|Am?lM78=GPAz(e!}OQ+l?r%gg+O zr$$F3`_dMr50LNlCo@D_**|w5< z9&F*)FjWW-=!Aa2+uBnIIJlGnIcoApsk^hstk2m8BB|)dkJDxP7gTM}4TGPHQVs@_ zslJZ%fEdre7TuIh4zGG()<@^e{>I^+L}_ofz>&PxZPA0FWeJ0(%Pfm)R*^E@Tyv?-aPhaPVr`P{xcs>}I`AGDDYxTXluS!YZ zXD->|`aBh(IDGTZ>~!)61dSx#F7?IQFr@~1%wi5dIV>o5+Tk=`+U~mw^4ld>e;x|7 zL>tr%-iL0&dv(;F;}*VqpaB2|b` z-ia~Qv66GDVv%zDp-MWTx>`+sK9fmZUBWc1Bvmy9_YZeT=O3=M@n_Sj9r%-Zo8hQh1Bkxm8%{`48i`>>Ya7ob;R`dRDqA&K|$O)G!FwlD|eQQIFL zNPX}u4BHMZI!-lgcl(qoouj#97mS;33^9IVZF@yCh^vt!!oafAn3W9wfKR`cANc}_ z!($QnBK&2JuW|Uw!*ryIPMNP*`XPOl+QTR5UjvUnkTu3mo^FSps@!cX`@k@pF?>yt zUHt(~0nxpt_)d3Cu{aOIYPuP8dSj29aE)A3cuJ!XlvCtUAl%0ns-J$S{sdKLedqb^ zx5GbG@Nnf~u&3|L zNlun!gy@bz?XB~(3G?Z_K(WxDxBPBnKh*pExUgDRo8Wi$tIDhwH24RNoB67^Ytz{m zoHHj6=q43ND&IZ_7rwX=yo-5!@3hPF8GDZPKx)KsuC)q=PL#jlC&?IpD_4*M zJg#QiJw}n-A5mEZ-PlfIq7?`;pz3g{8 zedekO9Ivsm+hU3M9(F?RQ)#X>aP_)aQK8g0za`T0sLc4nd)82Ld%;^IQewSOX|K3Y z8iOhCeV1vQg(O2xL1(Em%+rT-EM2+Wc%j^zC5Kz_wOkl+ITcxfriG5|oEdssm%OT0 zn6aQ`>e|}RI=4eV42IF=(uO|`FJ|pFBg@k(r}a3a%fLgZf{+6bS9fE{DeRZdWN9ei zNgC6kx81fq?dkZFmKF)pOvy@mrX_;mkwi1eDbBmx#fu&tIF_=d^Px)XE=aKY zuZu!0o4Z45nuJw{U8;KJ#tx-%4SYeGo9%y&3gTk$rb{NDe4{`1IIwC)!ZiQe4SoL` z!fb+H!;X7(zr>Xq_dnm;;>}=NBBYqgIfZ>0HElnK)o7O&toSi2O@0e2R9eiKu2bK* zP}aZ4Utr1BY}TF>H%dEHa-3r}HTo(j>b*AeVP0JL{1%?66XjhVrc;A&b+rW+5ci31SW$i$vIG?7F z+Lz^0no<0TpP|I1V>K(>qTb>Aoa!4VThr50`x8R%1IWRAvBQZ4@nXapHgMt#wi#J+ ztrM6k>3WOyPX{uFlHgqvN>eK(M&Gr?4E}N&zXJT=9|bFXSa(2)#1~2< zvJB<(p&d7_yM5E}e~i=q{n|K>qtM3bZ2hZoIw6_s?)D|nY~UH6WWhpd>q92vgqoE* zOkej7Qe@an+G8c>?Po@(^Qx*@6mMhm>$ohIzDN+;E3$R2>M@NH!LXR5Ff9t>6=_S2IgGno9q6y24kFR!Vra~TzW!e* z?UA9IL`?8Kw^&XlbFm7|Pi{2@4@*p!*txI0MK^oxt-_qrqmDaF)_?bwwY{@sFP{1^ z5jrsu^Ps)Od_qELBsmqXj}B}Qo>dvmrqt|oQ!zGQt>G8($%6PJm#A9{T|-607c8qW zyhX%1NrU08Z2xd9`AoQ=B0R}LiNgsE+sW5IHHYPWpnvSt^a{Ijw~|hvYY^;drmP$M zx;N}{Yk&HhMOto+-1$&EoY(`mUGOFoQ}ifNR&EK6{f$rAwdUM`l(GcQTSwNDvpp*O^YX_5dNV$|De?FIchvnp-fDHUA0&-Dm3^`?JCwGm2 zGDagzk_>#;n$n!2na3TfR#L0_4Mj~WkRhiU{ZHYesVG^!M2>E%^QY6}t~z*q7xDR_ z9pqA#<;bhBQor?0?{BgB7{KDPs_pkxRx7p==X=GEHtZevl-C9)eT7zFm6=snt{<1B z*Y@i)UGvEsze~C=vQBdh@0ONgx(#+IjbtCr6>*g`+J0GsdjZ*Zm^iQPeVp(W5BPBF zskuWuAxVA7A4k9RE|d*%y@Ytp+#(jPKClN1_<2$x;Wu<7^&yH`AX^27dEDGxwePr< zSrJu6GRiF(aUIA$Sv^%c`weEY!Z>IdLq&Sm%wSyOXzYpY=}`UjW=aF@&RERPhJb11 z4XkwoG9h8?1`upDxYRU<(Xg7w?2#SF@SH4u>roo;2G1DfC^9POG7@swCI z@ONNqW|1}OYe#HZRYbBqOji|XTua^#Djx^dMaFlxrPW+lc2=Dl_Hi#}8 zSjW`bV7v}-(k-H-hI zuKm_WjCi}RVN*)iFe9AP9Q%2L+s_j!?gHHx_x+)oD&1K3u!nYTndJ!dp~=S4)u&#u zW)^=nt2`?yO}4*_#0JS_YmpkRaT=8V5h?!Xv=S{!9;-^3YiRO{JJ%*p zUXuSMY_s<9_$~0pfwCD(q*Z;su$E8^ugZZstkyHjzUr=;Kt&&p8qOkDVWDz>KBCL{ zg&b_PUEJj+2+)L%dzynAe9FTuo3FeWN|Si4386wtHjFVv!Lwuh_7QE8-#Zpme#nwK>A;jRp#m_Gf@w+si7c;;hHT)wS}4jU?D%z_@EfUCa@!8_19L~* zKyGX7?%YMLL?sdnd?Q&HVNu(?A#e%8q4r0j||^4xifk2`>Y2x7dbO+<&##n;3y;GA6v zGldlY#d3V{qk9TQYgyQiwhm_;{eA~p*!DPIK&ozBU%SZuJVR9TDC|nq(bIy2!+3z% zJJ{GPlJd!N*L@+rCQ?KXOjCz;9=B#!!m0O1VbS9meEalz`WMK$gjEdk(mUN3}xlj54Ps+o=%c9ViCqd!-Y zu(7J7{b+GWhmiB5R^Q+x*DIDvlr>|%zpMg!|3S_ zT#?*$qFZ|I{k9pjJ6o+QNg{ZwZ~xx12KQU$B-fq=Q03elt3Rv;8~Y7##mSc7Q7@`? z^u*mLATsI0jy#o77}NaDnmlI_BT=Y#Ca z_tKBK`Ll5&Q%$R}!?nJB{AEVH9Ov9Y7-)=fI>$MGFa>yLlt|8g&YyZg0BSVe`9);_J-bySmC~UNyXoI=P~Vz_2QI%3JP?x<|E_k4G<=SxT4-9&i79OB6q6M~!ZKdLX1@!Up0&9^b<-H^|QZz1PVd4tz{I(dFUEt8X}^9Qgoe z1XmM~9elb>FY(7gEiiXcDQY9$p6A??hxb6lEL|)ZQ}UhD2N56*M!kIJ%)vsC8{>5T z{^!9=kkYHLTQNR03(y9kt@vrDLgy-foVtbiMPBw#fjup_Z92FO<$`d(R!aJ85v81| zqVWY~MU$wvBP|>g3-|eFhMK0n$mi-r62k6Fr$(KA;B_nse!?b@Fi-ks6$1-v{=uiu zgQMnA(o8NuPkM4v^Y6T{h$>HZ`uDrfK{IG% zOy<08e=??HC=GCNuhH`8iPNDLtj~^eBCz!{X|o3I)Y``X~Eo2jS;kec{nm`G7o zGZa+WX*DcuU5g15ZUrLz>IrP%MrY1FME&x6b+@d+8W1U?UY;{zuoA?_IGyL5J=g#u zU=+#QC;Af71q6d)z0lSNbTII#l?k!x+vohE#bD0Kh~9KkKbKbnVgR`ss)EW4cv#j+ z?HB>tW-KSefth$w%wxjju;mnXx^r|ZJO8=+UpZ54ziz-xfm;uI;e5#NWyk7}Gkh!S zU#|IAzmqX)Y&bPwx~k=gC}xVP4DqP#K31)~@KTeyMUlxFyPJxuJ)Hpha{^t23hiuF zKXmP^L?_U#YWI^VHKe!9g3kZd^F70di!C_l=#@ga!L%YjbnR%VhLEbUrttE#vt_;= zd7_c`O<9&LI`b`g%q_KOk-kO7j2{yV8n;xhiMr<@{i3=o-GpN28W_45Cn!nLjxoX@ zQG4@!i=WAto>61U2{lYvB_hgC?M8vonX|vepZ`f&z_pWFU%AHl_6Si^L>JgiHJx+&{x--hTOZ-!GpE>zDsTt8%SWZwEF+|tyv%O#9 z%nKA&DWlJqESnrtNV57Br3=mzFxEQ7cFpIJlw9Yc!9Y+Pqh79a;b0`Fig7yExp*)D z6vZfl$&m5ZV5a)vcBGJzgD%rF9&95rJPzo1a*J2Qz}MyT78!5b$*U9^oKQmn4|hAz z9(Q24_PE2f$7iaqBXkBBv4TLJpD1AQDIvfw+y%xfNg_dqN;pQ z*fhO-eH=*XCWuKFM_{phswf}_eO1jMW760Vtn~L(&(q7U8tUsJ;c=rfp+mV;oNnjH zu`^}r1p{6={j*oJYS^0kLXXyyOANAMTOFXo^|tOv*v44tQxiG|h5f#;w9c+p;wJpA zhfRId>TMqlu>Hl=Cl$ha+pQxCKJaU6X{FsK9rhuRBMy*UQ9Y+&(ra!mR;78MzKgEZ z&L#HOlRp}CE;5$=IC0rf*VWh3QfWq{!bA{n3958+p3{cr71*AmbzJpcz&qHtp`)BRkW$Z3|NGgBQ%8TufPKAK*rt+36*D5`aE}pwm z&|5Q4mlXf4{C>99=q-{xGgkhSN32+9M^Og0KHIjwJo;7IrlInYI3rb-HR4mw2`^7} z5@l7cl|T1>#io!o@H$Y$rQ0@)D1HbYK>rqLXZ@8nf~gOyP^;l!oSC)TZds+(QCKL9 z!a;TD>dsrkb$gsQP!umu-KEwK%RM7Z!w#wsCr6H>8OCHUJ4uJdSPe{1 zzqU@y+Wa2Vs&_n%~P#IsVXO&##Zh^4T`JH0#cVrLYE{yv6#Cu$xVLD*jxo&+f3kx5MPkjoD?{HQS zEBAnTvxPJ@kHG#M=yQFtsSi~=VPk$s-A$Zc0c&9`zA)WKQx%S? zb6c&PhroUk*UU-v^(0rXf+Kfz?v?Jz0Cul)eYPK`t)sX}7=Z|YTNXe|;DIA~anwa% zPm)r)Pe7q#QrY;&in_g}x3Qo!dxoseqa~Hp2+R+&PCzQ*R#ZN( zd?nLhBw9W=V;6|bfe3GIGRj(YvvD6Y)I=sETCGzUCJPuRc{HC>$`6*^$THb8~89G8k~jaN&KvgsC$CgwJhrHtqVx`|%gVBqq0)3JnXKJ*+z8o1^k?OG$v{IzyZLAYf0b4AMKc zZZ=KdJgQpMf&V@5Z>_EpUT{w|N@-TDw7Jd7aUw5%o{bpmxGfqcn}oBGY#lA}H9uiQ zdz{;dmf9XkP3u@y;8c5H?$l@`F;}Z0pW>)F@rm7PKUkW3%Ux-6@+HV;K|E^hwtbKh z_A%{Y)d(8N5)%p_=^OqXX%{2SlkN8srqI+iQn(HpNskBqK?TPk2X&ypIF;vx#hXK>>3GUA+xRb7+N`gcgI&G zH22+jF8l07B6d*|{6Y0b(-6(?su)4byELB6-4(jV`Tp5+-=BVNA?mLc($VWClf1Z-xo{4Ke9@dHAV;koi z3v+wMPQE;U5ZJtdS^9{U-9gs`(NFiA&j!*s`|JDy>zUJ5$>7f>tqg}6RWr3*_{3T7 z*ZlwytEbz#-Ht2aOzKPCUTwc|Q54ZouaiJ5NMk35Di6O>EZk&8($64X&|MxI9Y zxp~vImMo@UpqkRpdy^!zE~Ug$Ht^WQRXQ9kLiVER{E;ts1R$caEUtGs#C zq`$BoDZ%du5$I9b#jC%pQGMBLl<&%(`BLxE(pRTmPir^fNm|TSLCh!1uD3hGr``&& zI`fP~7DFZ*vBZ;`3Y>q9$yKnpB9+c~x0wexEGh=j<1bbQlq+9{c2nNJFGQCUF8&0QPGU_X$y^lG4*oMo`48`*rR!kM;eY1RBQw)rkzpChvGsWtLen z`sa!7OO(c$;DlpQ4jF=v?YO=OEzn6bYu${O{K;`!6$w|#f!6Bs(Bb^r`9U3rjT}es zd>_rq&%R7Xr`2=2rq(#@hT0jAaJUaYq~F}xZtS^jt_&fP22n zt5wmx=^-4*-&ixj0awDO4#^8Xa6R0z-5 z`3ea1BGKU6(#j+Ug`|nW&l62XGsxd~WCnZ^G7T^x`$18=*6np~VvGGA7PFbCi>7rL zOA$pvk<(*yjdhIzO^;M7h#pE>>=>3iN%cL5Q>mE!*&U#-w_PjQ{bDV(_r+w9(hKVW z@vx5F4;d`)UgWWTRCT`9oz?$cVj!~Iwu3^_mD--y_RvfAq@v?_3ft<=I$<2==Cd8LZ5L9B zwM*PNO~~-Jp4SO~JkDLXzt@>DHhcbax_2SFYI#}11b+IICXWe2JUO_>AZ8G@eZF{e zHp|VyAbLlA=4*}|5B&z720l)*BppQ-d&bT#F2T2ZO$q&L^5)BY-DUD>-2IPd^)l!| zs*TUGmPAjyR`ghsWVg!38MG3c2pb+!O>&(5$We;r_zipl!>!wrxR5!O_U6abnQ+mH z@qnrg@xPUGs|{>allgPvs1kxg;%ym+!}Rub+=hu@bBu z95TOW?DJQjR{k`f{x}kKfD_E(DKn>;T2h61-{k-k>q|R^Kw3;f zg}sMv4M z7iPmT;|5s=f1XgQI2&A+X|x!0oS_=*(c)Z~0fobx!#J&;W&?9Xn$iH@SX$AHUKEG* zV%tCl23en$`6mY1X}v~aNAMxOtudDBRfyD(zU2EMGO=F_n9p8r5=snjNMgwc2KQuJ znCI<%d{cYJZ0RYaD(0P4&*a|IcAglHQcv=3l^$6VUNf3sW)h=qe6Br>9M;8w1?P3! z;&ywN;_X3xr+z)_#!Om;-L0+zAQGV|c%kWEW_UEVM`mP!4@Sp?iMu6~4yv&e4YR-MqIc4=-lX^(ltUlneFkne#xbl|YXk3u~!jt|+Ia5Z5J2VEaS}P9rOoiarD+Fe;>le8HzR z75gzhjqu&#vu{VEsT{&N;==^8eEh#4xnhUwQ|t**rWZ&snCXi3km}?q37)AfVLqvw zO4=V6Jfd9;NJ=$YXplzXnoKjF3Tz3($4JY{BzugdRBHwZ_i9WlH+u<|3J;gAAiszD z{Z1Fh()>=v5X;~2H|PUM`>51SNWW?Gu^o+YYVG-quM_*yx@vTPERfSFtrF~PWG9V| zh5;jydi+=KEb}r!)khXke)ClJG>p&{(-FG~r)?yAk$N=i{A*pkT`6EFVhpb~_LVZV z>n)GoYN%X(IoihEVNve8G3HU$C2Uie7vnN;O6)ZTFEltUu{a3BNBwD0q~NT~x8d$6 z+sw(b%Qf6Z7#i-N+gNI-VBli6##Hb33_O)~R41kd*Wx0t6xXz{QOAHKhR1Dslqt4= zw%@MK*sP~^rP>Ad#dMLB>?83gTUu^HLEmY60xdM*pga2|ji6S{G(PY2DVXW|_sK$o zSP>r@rBQ*vZ~Y+!Z~K0E+4TDtRK|Ijs~DV&7w^5<$g>kcLo5+{kvdpk1c+{EHGGX3 zu^&L-M*g?89RS0l;Vv)R%)q}e_O3B{0SwjRfmHy5h0CYuag-LpguC+TGxy zM}W2_vas-qM}d=F>#RsMO%!;ibklkNtncMswi2&9@_9SmP%3(26+dF9z;kd0tXuSZ zHU&1^n>6Wm)jz?-`*t@eu76lw-C}RPhp@9}X>t1nVM@XE#LD(1da}`jRk2~_f zew~LVKN)l~GYNTWV~n+Mt5)=IU0BP^#}-hGXZ)EN@6*`bS2x5~T2n_ZSH4@r+{?n8 zb4m68(-IuuNO+M(%V4|EK|PQ$qG2q0K*mrDuBLQE0KK@9OHbpULP}D-+y{^tL!l3r?3qQx;B*Ebh*18 zb+u+B*I&%($_9Y5qY7sMS{i@&JiZC?Q2YU2ps z4H<)*G^jS)BzgDF3+mhWV!69)miHp*CxZ*vC{hPs?9o=aiZeUN{9v+)K-jl^L>SL} zdg?J>?i#vao1yn?(kw%dZqg-V`q`vi#x&iePlm{|Ns|l_$;kLRwsKPF^P3Ii5D(ha zu?BCxrMH+4Iq$#f9(s*@Zo$&6Jg(_s8S=*MN#S!>Su%d>wC-(y=&qZPG_waPcl%s; z0xJ6+tmg2Ge~sBuE+J$(RV9GhF6t4!)$+&Kn)BBJkSfQ36M2Q6X+ge67OW5OKb2Dz zNUd6HO6*f_CKKdRb5^0%j7Oo>TpB&Umw@Wgf!1XB*MtUc#5NwhuSp=@h!uN#&_w|W zAeB$3GbKJtcX?g){^@`tcP4lNt11+02}BXkME0NCI*;*IV}TKW7ae5Mhvgeh{ux7YRAp(FDVgU~j&pA`Tl*eH?3>$ql+ag1%U@fg}iJ>qo3mrVecGYnZN z3`Eg$u7z+e=?`4}8j+xQ9k}lBjRc+XLpll`dOiDh)zu&K7p2m^vGL`cJm#!=TtNYm zyajofG|r$TXJnHNVVnn7-^L$O^`Z?n6m zR9LvG`b8Kao3ghc-MUL5HPyyup&I{=2e&rI%{~u#Fvn?P5;o{nqay#?kH@CfEesNFV{~n0gh>BfQWN!tNjo( zGAz=2@SlzN?_yp{r)$VR3`nO$w7w|B8RuiD_R5Hryv17ifJvF_Ht?=mw)oAbl`r)q zzSx&o&E^%3x19HZ@9Nj-&=rGwR|18RA4ah8f3pxr7UIT}=(TLCZRU9xLBCJqn$3?i zjNfR{ME#86rPWL}Vhxq3H^eJflL>*a_xK6ngb;15jwWH=1GcjIr?k@9*N=`?YGE65 zMBZ$x1df*1FWzs}c7={JU6iOZL7w7^vST{ESn9>s?!WgGDTfgvdFwB&LF(yDoYg&x zs@wO=Z3^PH?-(N^-(X_4ZII``B5vC!5P5mdrrkN(U_!e$&h3-C#lh#F@GgEs9btWQ zCnKQe3IF?Qc^7C6n2Znrt=dUD=l7$Xx#KHoJaBe>Cal{j?o zOtKfN2=n1~vkfv~iM!o4=oIcKx@d$)0 zwqrd_g$GrC>3vEvn;=I+&Gx8&!{IqKep~2)ZTDz-s(pjjZKv)xBr7lL=S3lQqmd!) z(Lsbx#xK1PX>(;U9r~-!tF;rz39$(h-}4jgHR2RnVBHU2yq7jN90a$#QQCI1E#tp5 zecJom-O)i04KPAZR?xu}G7$>|*Zp#)LM-roRhye3S3D+@<|7F~A>P);i7P}7WEpWU zb+<-+TjKJ}B_YYl@JE*^@{%R)+GP9QrH9F^#~AmtIUhc_mF>!?b$Q26QU9*%oTB3GZOqcrbU_0nWE%}QjE>S_aB609(CuD+-IAZa8xL(>n%&St2MWi zs1HCCs>MY8BNoZ0Yq2zv&|-~GG83cy_XvgbX%F3TnX?r))O|8Al%qrp=w%1!<*#|q z;YR5s3aY=-S^LYoER*!KRPmnua1~Ko%Z*Oy3PW(B`^a45eY|JtNje$+Z4a;?gk$~Z z=EV~2Ue4Ev(p7ac2w5nEZOa%t)wkch8`{2O{tDK{?Y4uDUDtD^FYFfDR#8Y~t0rf# zj+Ir_%RS3b#5Y_eF>m=$+!1LKfO;UO0UE}JiqD&EC!vIFezCYxFUZc9Ui7Bs;e{p{ z^eEK#45z^1)nAAUvwOzJV`O@8@%ig=Kkz^3_xN<JuyjuUQ7 zTSKqwgZ#sEq@8yn@J9ZoePad}d+T`HYWrl;dE@aOd=DU)4%V2*`{QI}#V+1D z0a!vSqx1dPJE$lN+_U9A1ov|eE9`Fp+v7R3m=5_D-2v*vdT|Q3kAgXWjE2Y15z@Kx z5977t=-LS2Ii0lZrEjJ`o2Lj}&5gIo4Gn!NF>Y&T!xue|^W~rcQDSa~FSAUPMXsst zjla*(#Xh=tlUnTRbcoIGbPYHk;WU5t^7ueQ?8*7&k-@n?Dn1?BKSlXrC%vu#rAFgR zq5D01YYjI0W?LDKpo+(=aBi39j|gp2;3?tWsmjHI(_iwA zG!M4Tl5iWZnzoJ;$c3k8CQCN`YzS>0)NZ7eYo9eIc8Bk(NS6%T(j7i3O)*i{2}^4q z3qt~H&WO1ylGC6Tfa;*Ubnv9`0EP` z2bGp`Yq`JE;fEuyevt1wts1u6wEmj(SZ<7jT$!Bdt3xk1`*ek1LTZU-K#IGf@!Mm1>EIfyk`Hq;m~LgxlO*TkIPA zJ$DNZqG?vC+NXIIq-;S_ewe3X%d9YpKSu&Z1i0L~^LAmd>~ z@~ZMMT9X* zk}}F=#dy))Z@l^yXo9}BcLNR%+Q{25X~i@)=9GXQN%AbZ{tdCQGRtv))t?Qoo29k3iHg_ZbGWOKv<9Rmrfh#wHji zZqdbN@XL=<=aL2H)K=hQ+7^csUbM+0XV;?%x>^fBpqX-C1t2O>{O~M|up@BMZMj}{ zZeyz#OSIr-m7S;m4>SNV8i@WK0F=lL06}F_C03W6@=Y-kMpt|Gp`Qww_$O?#VlZd6IQ8 zs2bP^5JMjbMX&@u_@ya0E=59sYFa4Xq(-6Qb>a=k#KKOuSPI4YK}hy0O}~7u^h&0h zVvzaL<2Rf{d-51B7%rbGt8o9l4cdH)Mm3zIFC`{Yttp=?7kW#B!l=3!@5B;`#bQRf zMpVu-P!Bn;ZFQ*aw+3z+FRSQn-sbB!a@_k2C8S%2<`w3>{O%1Izf``H3e71bU1pMw zJN&=`W+|fRbq%mnV(z~rs{G(4s8+3~^4<$8c$O=zvF-$BRbv&AAPE1^w;jR{ z!sqp6dBr=gi#n*RDpiyn5uJ;rByd`HFmrI>m}4i8_UfI*B@^ieL#Z`HJiuLb{_R@FZ68AmK@n!Gh+;elj^= zt;8DBKl-hC+_YJBXFf~}H%5-UJ|k^ytEk+)L?Fx;G0<3q2(z-}r(q^yLhsqb%MtAO zQm${y>6-NjEzQrW1%ei#LE4mc$f* zGE>wE$Ho)v%ENZM`q~OVsPy;w>si$Xn=CgMt7R|>jUm-HH~UJBL)P zduuyT_LL5Ja|ci@yGkCUh7jk%gN?GsU78gK*f)sqfYz!w@L#_vCKSqs9h@0iXk|Lc ziAJ@BRiFoF)dCsySEkwSpO~$yWAb2PQ7PT_&rmDe=bY_g!-f|7w2`h#09k}cnS(W& zY%5;dxN}2yl4&H>#A9lrN5CE;>f?V?i0-+eMFl+`pR}Z|iN#48w>h(Z!QrLK+Jr#K zbA=1`9g|7@R^EX_BaIK z_*=Us+D8+`7)&sX(*D?hh+a{I9(-dA*&y2fBnfs^VcB-<>fDP=mJ>=-OyMb~vNNm` z2)oQ22+Br;T_&Ye39>BGx+ZevDLKJAA4dqqA^9qoHO(!MrMdsoic9-b&{+aaQEB

Z-KFdVKFjXX2({ao zzHwhXdDs{qS#a*L&}UZlX-iG;z;N6anlWoxA-zf=5|iHJMslQb%>O}7dL!a28eZG6 z(1)Ou-4uXNXyNhss#^Z9Vo&g@p8lhlMCW`Z@LU&>nsV!Gz?q=4&;Ke%0_e5V-X_;s)$3w>`9E?6ns_u6#?0`m?L&5CvO-i!~>HvCh&W@ET!JA!E$ zv!K}k@o3O>M}Z{&it>_>-D;CaaC~?He7O`dp=V0|ZqUJX+!~tEWLc5FGCZ5oDs%V{ zt=nXIjnne`Zc8VEH(pRPSNsU6eT-YKAjRfBOP;p^G^Z}bZ)#0mtmW>dgre@C!RiPz zgaOequSMg(7Oi3g2rz|z0!(uXz}mQ%@@nF7Sk+s{*pU#1CT%);Set!-Q?{kyU)oqm z%23zwMG0`=Sn&oC(*P2v5*14yXkn(Nph(NihcecxW2{>o4tF2*n=F?lS;kC+@|Fxx zNQx282PI7im_Wg#ohjl;gG)PH z7aEc>tz&u=4J40~3&e0a#E|W4xw|X=xg=d)8Kl=x4Q00c!)uIW+TjolXA)C6yHSQ| zxo!weS@L>(VNTFq&rLKt(GI%h8iw`v<{3FIQ21e%K&U(Mv`euR-_GU)x<#-xbL& zwndb$jK)dlTB+tDa#(by_c1R~-QfP4N`Q=Lp-!)bssMz_|M8DdceOA-rPMYKk({F- z$}ErE;Jaw|u>d%)$;VBh83xxl3z642_pWis{=p&t7mi`}uiG0DqttP<83srA6HIa* zX3OXQq(Fk7T7dB`)31&9w9J)sVq!9b+-=l;e*AG#L8MUo%VEKI6N{C5U45GJ>lf@> zMB;ek3}k#T#MyqwGS3M8x+-H*QvcQ2Pt=zG+n{IWjp<) zygc~CDSJHZSJ!q9*Bv2X1IQ4KuVviXiK0)`s?7gk?@QpJ-u}OpqO!G;y+SH$_FYNz5Q<8|L>;P^Yp*Z zyk1jgbDYmPpYz$z=N;QQ={;~J)!=a7)l>uCz6+_S!+i#+DBiwPsq%;WF2A{(49eff zPNnzy9Bg0VJPO&oucAhYVZrD~-sNtOYY$-2Z6&~rtbAhe&gDKkcHfJ}Obq|##SA`k zm(^a%Xht}#@i`6pj>Jc;D=Bot7I6NaNt*{x-laQb@OAVw#8I$&^qIY3YHCat;^Cca z()_Tmlt->`LKJLE#83ZZ?_CGrfjte(Qo=+%4H<+SMYK4-E4 z7PP23RD=TS>A4TB?LqHNYh4beI(wMvP}h@ut=(tueR@vOTzBFz%Ypd)cdt-#@1cye zzG-fHU*-+peF3Uettu|=aa*p;11B#rI$ygIz}>a^Y;2=XH-$^N z?SYd{n^hlPH&mtscI&ijyM8cMc13L{U=iN*$ocpHxeE%-IREIPe@Jaw4y= zetopUZ4Y%bpt&MkB#@h;3MsLilirt4T+$c0`S^xT41b^NUA4`suPIbt3rFpxyT6x? z>sv1tiNtNI<~$qAv$QX2WUoxtxa`SGNhh_G?mW&y7Chad`h4qs{)jobvx2e#Mfs`$ zz5x!y_qeX4M9!{h{1Eyf?YoP2UirU%g2_8Owh(_x}0z13e+)!Cw=cL#LKgZ<5I^Qcsvb`;W295~v|bmEd2=}|D{`d~{`>ZZSY7;>Fe=Nnw6 zY|eA9I(dm-DF_JOoV~{b7##N>q{lN}J$N+s0G}TRcN_zEpGE8=0kn`%8qYQ-c;sW* z{>JAa_t`kk-MNwQoWFME}c!wR37O)#);BGmzvO{%loej{%2agVN5;+m;QVeX@+`7)n z!hupWzSly9&TiPni@8$qF6+ro_CB+&GiT|67Zzs)lcdDX2(1syjQgkbQ_e=nE8jBD zymRoV^d|1K<;L;52auJD?n1<^QRg6S%^)XnYbq3Zo}YAX!y)<&(uY873?ibuC-d9^ zCVb^$3+ziuclE%DJpFf7)&7yGw@8l*jq%)}d+Gk}vB+}V`C4rir*drlhnUEbIcb0a zMJ~xHXl)uy_wp(7(cfF;)t|67&xVex&&6C?ms1u5`4si;I;rIMOZ*Die$vYKEVuqngPqJ1 zZj;A1jQ{S@b2k!kX$dc!$M2mRx>u;fL|`Z~a%3E~;}BPUizHe!kL)s4j3}85OmAq2Bq@Ej>G-ZFVet6 zs0Qkz#876-6lv$4U5Qd#p0+Udw798@6t);1nw5MQITq}xe(C*5Tb3|he^rY&i7AH| z7Px!!7Zz5qvq_QYUfo$^S+3svd=57V@s$I?Omu!mURFCF_=nLbtw!Y|oR}=fpySso z%Q2x9C6*a!%cAq)^0FWIBkiiU}}gujRp{%wFIh_P2qdnYO8t5K(7jU)~_fUDbGIv>K6`;t-CX*HyR{G!a0(bW{O1TM>vwg2RoW%v2XcRfKjRosV7~j zqnS&=6igP}laHB8QU0PyX(-wXlz+a0xxHdXQ!__WRf`mt5V~gSsgtrH(%(hqy&UNm zi^}_%pW(e{ma(X}9rjjhl@fZ6_7J0D(fKv~68!bmki^Nx?8+n^PSK{SgmH(vQe1_S z(W8UvXjI*x1{z+cppHh=DQKWu>Zh4SFXFfzqJWn zYnZsu(LFqEn26}<7+T9`1NVfo*{2ZNCtPoeIxka9h|X`C9J@MsBfrN&N~NC}=`>j> zF}*y3byJ3LC>GO;&SPy?d1Y6IxtBN|8 zcLC&D%$;;9adM9FEOV1w zZ{T#5`RHBJALO$d;faF=U53VsgNLVHI^r1zN8;iZZ0fpIN5W;1N>g(qy62f^5v9|FRpv3C}onWr!9v}rYINtt~ZDxGyaNPGg? zz}Ec`&f=nDMh|=t_UTRK{;<+<_L0WWQUs{2!>s*W%>r<^Co1+14AjU>xX+s2P;~;g z;Jj7K@DCOY1ybzSag780vJLvhn1+G=>#cN5H`$M~yG&QEPX#Rr+Na#Ev29KE3w3Kv zuCf)Gh#eISFCA`ZekhA7V|5v2@HT117l503%e2P}dn^;h~#rqV7>z9_S?xW|myPJ1X9~WT0ObIF*P3 z)470Nq}x24=CbG!E~j=LW|^48OqEszGAoQ4dz86r(@h7l(J~}c+UJ<$bWln<1$!1zM2)})H}9nM2heJSu9r7 zySq2NVS?A7aneyJdc|vD9~1Sv^}Eem*y(%2Uae4;37?*|>v*%YlU;$*#Bajg#Rk9k z&YY}sorrSKLJelprA)TbH)F{b)82+I8NXxO(NVAIjhGZxgDFp~^ooUcw(YTHPe+@L z(y*qZd#oRrhF!|iyeHs?vk(EkavmX@vCZu}W20qQZpYtIUPd}YC9$nm> zCRk-Chkxj2+g$}(L(k}zvkAu+I_)w4_~y>IS1}vNsT)#_uR}2;x;e~ zf$psO*y9mxjk*s zwHT+l`aWE^=BNE)1IF{}P` zkYG|o0JO>h0krAHDtXyMju4U$=C{`Dq#Bm1ZCbEgCK>sPYClqZpI+p6# z6mFUT2Yl2Dza?;?V>o?s%AdEppFOTPr3T6&;>Y zxqubt+80%!3 zav1AnYIGRuW>c=~g~XQPMzN)tiVMeSC5!zgv&PK!7kN0Aq1WOiUuLP;S&mPs;Bc1X z`I#z&`I*-tE%14t7c*BFqVr zMox3rT>R?BuDM8=OG-{MysI5sYr&p3&}bhvW5!zAOJ;R5SnRLnQsE~!(oXvKcTBo^ z0NXp=+n1c!>(sKn7m^aP5RK7q)5u!!^1Vm5uyB5~XqREpLO`3wO!Z2zxFT$Vw`gr& za`ReULW<799vfd%;&(rN(EaI6mjcw9zWW2V`8@o(7v-yY90s6u7aft-wJ|OhU}xJk z29M`+6eg!+aAFwRI~oaVVJp3x@>frp-yS*AAqu5i9YU@}WS(76? z9$k||wWP0<`qZNqT%<-i*W}nm5>wXscT?_5`;*}4H{R_uM>MVvP>KR;V&Sg=xOnJ@9t zfZm?HHn&YLT(n);BOAT_p12b1@R9B<^$Cx3K7Ww)>CJaH%D0!)h z6ECvYk3}KPq%>kdk*9wSq1iKADC@^$ZyNBZTuif()w{A!M%fT;U!?}n&Tz4wL56|_-$AC4n;$upI&5r z{luogK&J)dAF(~egM*1tOGn4VBp_hlH=Y!&O$Dfa=VS3c!L0G*sKz_>IAI##5B|sB z_~RWtgU=5P&g-oC zX8tX8wY7#CSx~8*Z+uC)KcJ9*mU9ndwcL^KZ`9xHAz#*OcM}1d3}Clk+J0vVzq7?( zSc|yVy0Y?z`L!(mmS4U<4HDn>O&vFZiRgWYE5E}cUpSn|E8Xe<=g0K^?T&orm~VWC z#g3^v&)xgHPF5@9|3vZ^+P`|zeWM&2TZk~LHN9T+jm`S@nf;oTmHPvi7=p4ZjD`^Q z;|8F`XsoBH#$jwr9Yh`76D*&Ibl3w@fHCa>NyCPCvDT)!yjTlU2VShb=`1hS#FUd4 zYh{|ki@k1YRQzdI%uVr>eEAH1ojXECzfU_!vV7~H6B#TknPU$lU;eix$=?W>PahG* z$#u-)L#R%?0GUPqB`g{T*BZ>7wJM&^kzZ8>$-#K{0QyRU7ie__xqvPXmQO*31Xm^@ zXZL`_VLf|5qOjsUAW7Kr9-J^NVh>IX*0BdC0?XC=#9Sh<_1c$ccuGO-$Y&k*El&L2 z=^+cS-;eb#BEWtHfl*|FUxLOgPlNihD{LZsJ2^Da&2_%#ZJbJWF;R1T0uIfB`x|^gOgU)AF=ZWAx@MeEo4S$a} zKg&C^di!17lGVu@VRr+UaQj;VrqQ%R`XS!FUl^#vYuTX~$t~e;q^v{W)M-nSh)Q zu8c?a2UjK{alzn+$i`rB0&+4K9FOeDCb^Fc@jBXBtqK+Ycbp{$UM(Fq?XUgaKY2@F zPq+Wc>HXsUe)Z%}V~{7$iMet(HO{>qNr|Nu@k@>+u3U6``=r}BH z4-Raadl>6&>TnqQoy0vchj8j}HznZA8(Ia_JN^DQzRETHeTIT8IX( z<)7_~t}e*%muE$<7zq>-65h74E>Xt94KD;jUiNrjU_X4EJ!V6Q`S{lTngoUtMm zP8yk8m6Ty8H%7&JFKlAr>_UlhEsy@s%8@mjTTGJoS8ll3W-R|DJ z{INfp5F}55n1}f#R>4GvP+C+$@S4&YEadgG(x3)OAQx&3X|c{wZU0IRbepjQHAoVP zt5KlEIzcu3!5ruoV+HS)*%-cZr8k*%CJ!v|f*&KUvj(|`Eh-#r$8 z61;`|ySn?-XYbViaH6`L-6R{csIJ5RqX|{=6o|s?mskZjbRA^pMOf&BRoG~(cS7i~ zw$Mrc%KhkZ<6J6`JTkFnkREFfUG@j>M~@n(P~qf|aWz%+SUc#fKYl-Y(zu!mhkr$q zQ{#=RLM`agY9I;vtwN7KNycyG>TQaNB6o0m$PX7DxXadF>z_)7>ilpG2YCuWmg|?; z2x=4g)yC{`yq}P~{vb6-1c|7D&|!U`O#YQ@=q}@2YLFkDP@2eY9O#wpY| z5oAwI6&)4~<@Cq1p?i$0Is1sB&S6a_V!cKL=Lsbym}yV z89o<$OzDf5+`1D`BFiNL~ff zDuDKPr`fdNQsTmaLeTlMAQ@zS4TJ$}3XSuxWI-<(J5YgSk>xdm3|JFrgg=-CybOwGP zJM`~3A45Wm%wr>_8uT{bK z@jgb6AE@gfCl84RIe8UGt02E^de(2?+8|-M6Fv@x^7_lOqkD}zs6oe(Ej5O8SZ}DL zeNvZKbA4vYJZl#p(SSXx%pvEXDNJ3aru z2Y7yl8uv5&qQ{`mPtIFl9Xy30SDcl$cxBq9>JfjBkMWlkD zib8fY(|zg@fDvjQ4|YrYF>Rk|XJXJl6~BR+j6#7d8(H}cI40Re0d95~mK!L;>neig zU>47BAWPZD*j<oof!yolkl`v>O+Uc+9NipQYmvUhS>|{Dg z&_!}i2VTc^h5eWX`oB|BL8!i}6tMYPV58{%@mh5M3Zm*4&|6rMtbVf=+)!K*kUa;d zq3GNdzbeNxfdUTEfBNbOnAvV09!8qG~3co*TM*OBcR^kpWTTgUj88)Rix{b z|2s|W|ERh%m&IpfjIN zL|Z{8zg$J*KzE!Y#U!{CyUA=xj!^+c&p(4LYs>H{ms@az>P2TSPM|_~1HO1L=QP$& z$HM5JJD_AqL0SQ_+W2y7HXHE8{n&uOdsTtJY~QpV#vY2R8KlL!Lp}T}Ini)q27h__ zzg*jeP=PqmjmC=9IC11`&3Z)vNlXB@cm07FQT9KMi;&rp%$8qP;1e?t*^=X@v1K%w zE&l~cmR}$qKx9kypT?FUWVR%;<&OWzEBwH%2BH#A{3D>Axv_vcD-a?oCI{3vk`Dd_ zB-O7GxwMY}N;8f6fYQvRYt;V=Kk4M}4^LsE){V+CeUj1XCq zBSinG01hknr`wo+36ue)Gykk_#LoyD{sQ$PK!|Ahj}TGU#zI8ZWWFSqG5wqn5qz~{ z18hlXyqCDs7pn+D1uHdX;=U`GQqqT5IX9FY44I#g_+0?v)JlpCpl z%P9%~F28T20uIRL0Ogk(sDLX2wCu)`wc6!$)73x)98g>d6lShDVCs#9sDb*T|GJ|Q zHHZy8)lDK~jMQ!mKlEcZD0xFjz4FMXlUUT@R@e_+mnL4Ow9*?aob zn;$bme}zLzme?eoAS%EA#}eDVwhTA@W`4ao&OUDW_tr5$ zh0%X~WsMk?ceNoY&^a>{zFq{R_$OQc>uBniX#cmKkmV&=UViDWN|KjuK(!H2$W~#~ zFb^ag$=2ltI&qQfkcfDeWqp7eSNLLGc5E>H zNDL8m{CA*zSp>`as>u4AF?>7hRfnR~rYe_lMtA9-Zefr=*qL+mbjD77;spPM7xWW) z*UFM%{r)Y8LI8T&GyuG^OhQjn=!E=pNI#%?%onstK%PdE(bLE{tQ$t71<=#L00=6M z1cJ(G^#iT3{qbI3uz3MIpk^{25E-?4!`R)QA)~=W$mooS0!x2+PBf`tSR6V1)$Q}Y zbn5uy(z)ChBy+e3Zj6j@v4KXiWK<+#mKH-qxFEL1u5#s{?L(;a{Q#t&u^$HsnU{!g zaXlV9PsWoNaFMJ-<} zrk`-i$dSu`4Hh~Oxg7l?a@oDX$R#xpxorHg8$X5pyMS8>vm3Z9L&hHa_aLwVkxQ>X ztV^2>MlOK{aLr~vmZ0n-VFP+>Ah(AK-*CW;42(+z#{C6W;WLu?=g4K@1|ydMlKB|y z$J%B71P5-zSaR-nfW{TF8-Q-wIEFWQ3ZEmFenwv+myH{ZToQe8ogb?*`etO}p9Js7 z#wjt(`R`Z-A~tUhu>l+rn|I0#^UncLzqmX^Y+h)qf>+j$^(rD;hW{SRaKm1LJneLK z4-u@79cWdw2*cV!C;cn;qsRYASD2I_lIGzfVFaYeb?*o%|8sHB7hn5tpJb6OLjVAR zyb8psvMdxw;L^LF=7@XO{a-LGi7n@*1AEQ2_ky_z@*%;L!4IB##h$&+F7|c+zy4wU z4gI}Bd!4D;GiO-$0jY~`=kI<(``cfk*Xb|N*YX#@L6xVQ?ge@nE|bt#JfEQGfu^rS zymJ8H@4qPQAmLFOY5We)+o5BTqKNo0$qL*kAtT$?{sd&(|CgO)*mL=JR3N$*^n&FN#yH7{lVrrn-#fe)_C-VO*QE+82$SgLbj4-8des@Z}oxcXR*W z>H=3tW=t|;{=t|C=(_6{d1+tJUo%7Oo0&;OM3w&vs&~{lg$gH!jH{`l$J#+>KOyvz zFoUL_kyHoJ1x|xMzr*3byN2t7Tl*ll_uK+C(a3nnQfg2lB z<0-lpDMMt;$qm$YkTEAoeT}R&;HxcPyq=QR_SEI9q-YWVJ-PH1;zfi%m<7FHY(#~V zK^E6keFC~5;Y#Ob{ElZ{4TL$XUz5Ea{@C7s9#JFdkN@Rf&nGSX6V4VSaH$7C1)7a3 z8aDtrrESa^_XEn=ebas{`c4Lz{{%2kju8QUsWX8XkpqAfFhoKM7*XDU&jSEhtT%|@ z)|7uNS4p<2NU25uz+z)496v!+{Q}WC5KH$EfL2vaLaV9|bC*S;h!7Uy0BBV%HAocM zUo%LD^@TF{gW1ps;}mL~2(qW9iVh2ga{A+mJ+d2XeC0o_B>;q)d>y+I_G6VD|BmG( z197^rAS;(EG48?UR@k#>WvPSXp zcBAv2vcsr5LcBiW!}vS7ygs7C{o98weDtkl*yEe@0dXgVcTHrtXM6R9kKkI)J?lvy zOlljq``LX=nOL9pBTO0*R+lk~1bhc!U6F!%|8NpWb=$WpTZd;h9&0!P%l$kep(lV=^r8y~P{!MZpD&KA|2N-x_{AHkU} z)2!$l``pODr>EFkBHViqN|Dcz*vP%qCyBd3sAJ(aP*w=pU zYBi2ty(#CxseHaoX3$AV0&_&XLh@;U`tw$T{cNE2{aoFbbm!d@M^hBL)An-Noz;s{ zF5+*rd@_eXFJw$ z6vCk!B^37(ThTf=y*Q$j!*?U=IfQr644ffh*Rk-8aMYuR^9mMVCQ&`@+$-b;R6 z#A2rZ{f4CvG*F&8!4p}x){0x!@*l-BM!K7 zNb7>e(x17=)!cv==q^CyZu%KbRPYUt&>Yn+ujVSZIV54a%iq0 z`YnOS4bxslVl&czSzx^gcFCL>9K`}BW5um7TBuX!)#+}G>gGj(nEqk8XBy|kI#%xr$EP>C;XnEmKEjja|Bey z8YU>t;lwoB&o0FW+sshYa9wzQDjI`rrrJ`iv{0=eiyIsD17n*T6`?QpWuhTItpYs* zc^U$eZ=BE56~A$WuqYJMb=bm_?WBSOBZeV}unwC6PvP5U4`)Ck%Ldl1*G9|UAg#k# zCyyZvrw6=csIwQOr)(KUj$c4%^2wW}uRWS6;Zb}V?EzabSD_O%9*G#`+rP5dOn>V- zwbaX<-m^ou+WFQd6|4Q0=NowwJ%o(Ft7F!=dH>s25ekx9^eW+_XDx(Orfn;cd?rUwq@VHYfh$eAl$3 zkl)%}wu-^j6b+6X^`W(KA-{Em-+j+hoqVzLDRFBVS3{I#tY2R%>24@jK!R5$8hdgf zA0DZCRIg89TSTX?@9%1RfKuY=-MROjbE#j&JtYUWS7#4=T9Yv2(E_k{!f?#C2;(Oz zFW`GsFp7TOgdUBK^|cHm-;Wjo4pf?cl;y}B}FTf1tX_7MnR-zI zo2V4bC__;e8Mk0DbQGZmR8&j36kKI7H$M-xmrl6I&e#_8V%xb#inO7|+?(P2r*czm zx9xwjQ274*3*r3wu!^FZE`jD)3d$7NrUu{qo)^ewDvAaLO8-^uo4ZhIFQ9ZDMZ;pk z_o()lO9;Em8z<#%A`P^LEdj_gCXu%Zex6Bkz7Jcx>-T|7Twc9Ewg3Yi{Kh~y31O_f z@r$Q;r-p6HhlE=lo@O3l-5f|HZ;voK!qUsm{}1X$C!XGNx(`ri_6_Rj?Tp#HUp#E@ zK0$RY_?56CYfhBoHr6N0g)PU_}|R&{i7Qs3}1q*Dfme z)Ndbd3dRyf+=K{@$^}X7IcOMS+lu0Vpo#&8L zZ49;^%=-Y_St<=44^R`7U}8R~q(T7uDN(3a+I)O;y!5OI!m_#T?!)rbaWRpo&73vC zGIF;ILc*^eg6^q5BrTzHIyudC8%Ok%Z*u5l3D$h#J}c&C@XI{MO$rrn8(fRx576&B zbyK)$r~YNS$ z>KU`1h&(hQBa)P$!ty%&t!bQ!R&cobF=eaKG*y|vU91PYP}{jAl%KOfk25d|zPQV@ z@Q`Bnq4PWZE5w1BHLCh&1xFrIPtb4MfAml~7yQ}r&TT$hn9BF-@?2t(P+m}Y5EgTo zIGutk9=xGQ&u7jr0u^;iD7Xwinr%LN_x@4Z`F61Z4K`7_yu-@(9$Gnzn?1gp5Kf!X zaF&Z|w?5j`Jm%>X_o=w(utd@@V^=&>LR%$Vf%!!4B+X}gJTM<`U_O$-e1bGc^YJ0g zXYhawL=pHbf*AJVMsZS0ZLTf6zbr)K1K;e&^s3BRO9 zI4U|F5pPO3aP;J}<}TXZowtn2y}DLQ9IZd3mRe(il(mANsEa(d@^jbcncA;rd-|$} z<%7M5u=yA31-gt^170uP=Gt@fJXo*M4WU(@({l60kMA2t*Y8m=Bmml3rfsCFBdIECQ0nbxirwQK43z5?ojS!pT0xd$0$a8MB_i$yt)$h z^f2O7Ux}*v6Jgue&e{b@%7NV$!LCkw?9)RMuil2`(>AC}up~Yzi+-bpZb4C8z4 z2}h{WLOhIu!-)o4CGY3nn7{7-#G1Bbmui0VrR(xZNv%GY&D$Aec;zKf7yT$4frSec zxt(~mwlx2xd*Sc^H+w?H#38flR?lQi(S7F^6BT)m+wHOY22PA*Hv7;eJU{+c`Em8( zbK(Pge?yJAuNE4R7VODWV8Qe;^KHit4(g^q?%U}Q6+YY$=;`KR$i(!*il;s=faitu zm7Dpf*2CfwH=Z|8utjnv@^{_5TnCEoXO=os;bCrTx8od>R85zlqgF7^bi0yTZn4u4 zH#=o`81DTHEn9i>Q@JC)ngSgO@>)0Z`&$pYeI7@VG|rY=E0D1rL9Qo@PUe*6(NG?H zw@oAM_@G2@I?a=}zD(ycx7@X4h7_KQ$^?dtrrS9^v*pR=bJ=ow5+8JSug(*EhIuMm zac%q~aHVtNTWFnpq;#JSXWV7r)fSy|&AS6LMB6JURQ3lfN$lOK6mRylr4Lz~wbB%$ zyWC@hzwS?HAlRPYq}_>|Sggm~x6qw*6A;37Ve;El7#JMW!}qXOF;aWNCC!6!euCW|nD#E%)E= z57D@^*TF*lly&wl<{i`MeRWZLQUzKr_qO`kbuQISpLUK2yh9o8t13l@mnr0q`-pE* zM%x5LvADdmj}lC>9}jtVMAuYUdz_;Kz&H0)77x@mI9YvhVle2Y4)Irl!gVIM};gl#p981y~U~&Fw9@=!-QN z=qyWY}fJiedn$PSwL z{^7&u)DXk_9}{ogKXKXtv)^93qwl@4eMVyOr8dmG*P9aXqj&Tg=YA_&cVu#7oUy3r z$b1~|C}wY19*>8rOhc`Nz-bR&#-eAZUT)HJZ>-(AX^YS(Si#;Ra`)y@2AJdPohKTm z4k&dGnDSjxiprF}DSRJs$z)i%!q)yN1-nh&2V3MWJ83?2yx}!-lQM{f>V0i3F%P7JSNT0pZkJ;V7{=q)+Hh!A~L|qQ_PHA zlqR223!*D^I~96gS4!Sbg_>8-JCB1V=%XdXSTnb*R-scMEovR3mYZf_vLa{AFL(dt z6I~=9-*%g+x0f9RDhzmpP+=VG({~)dDd2E@crzo`T5V#XjemER z@qH6BRk1sb?OSt{x=n}2bo!uz*JhNHa-koJ>TCP4*F0^AWbwCJ+z*)YPT)~8G#P$( zGi^2}z-ILV0brd3Y&_p=KTA1WIhUk{)6&4!sT;D|`=4c3s znCqIvZ93Zda?`2NVt)M>wT4~YKCt*RWru_X(4Egy=W+3u_xWcv*Phwu)NMX|XiBm)LD%yDsI;~g$4E2V z&tDnh*&{6H?$(e=e^58aX{L*^#VNArbQopd~hOif<5L7|w5Jm^(t z9Ua44x+UW_(E-csj8vY^`ul@ajx#oOLO5lO$KwM?=O_TN;Ng0RCQZGj_HA(R**m8- zQv#GEa{`D`M2x0oQqyesR_fNaTEn^H`Hsc&QfxU@wMu;=$-Xv-sX3P9tWtf!8|6mR zGj+8^KD<+RL})>S?E>eRUO~0JDv~AiBF`~g0bQiK6(}8{(3Bvi&!J!dQDE2OsFn{Z z7cP7u>;S(~9~k&L_7vQf%IaZGhSk2YeJtVhQmcY=J&TEA=LN5`gePho_M_pvVg^!o z6&3RlMq@ew+HL@}SrKUqWRPcRuq%Xa3WBE{<+I16H23^jNKSFqX{ z_lW`A#{zI43&4GkO$M`W*Xi)0V%|1qny_(PxbLLB6E^+IvG3`bt%oIy&HJ1@_W*0!Ir094#@@(P9CPmK7lR#Mp{c)L0Z8UIU`< z1|a&Z0MRD~h(0ku^r^xpE4zg4vjVz==_8(Gl?dFu6cmV1w?o_SiQKeyI}ouTloPcl zQZwVRNg=1opq4hgf;U(pCex%)>7Gn{tc{r52iUF)@X00f!Ug+;x?}0l!~W(gG-5@r zBC3rykg@9TXHLV5#BR-r! zSq20;aXo3suh?^WA1jNp9z9(?^J74!Ke>8e`-YUv+jr$+`UrT&%p5K_s$%$|6X|WL z1-EW#f8Wq0jH-xv-v#yI5NF}|SP=1KI7Eid$koa-CUrDBYXy~%{{CuIIIvAJ-KgL| zyVo%17aYmnEuCA%&ReGHaRdrT8@SVEWVXbfs4Ja$X!kJ!w=kyHuEVD=FFN9v?M>-n zX01%`&u^ok>t=h*P05Nlt$p65HAo#E5Nmz*nAq8~Kl9b+y&rQzO%@l0p4 zY`Yd-61~;OK1AA9r8)s_?KRFef2g(1E+P?4Ymip4JL`pjB!Axv-lwJfGyCtELr7{BRmc+H_W^aa_CoR22*!pZ})YNL`w5k>=M|e0UGyIN-KJVrI~*k z)Pd;Yz-%oPco||3qIqwj3qjvtdUGnk%lHJZhbN77hFC7fDKP`ozZ9{)B+gd>l!oo z<_IFO%+0&}>ifl4Y9m&98F7!z5;ayM4EChI?(j{mR)2}SmM&# ztTCx3zuKe`mJ#h>C2vqL5cbhXPeamX=|!Q0M!&WEyNla>n!M#Z^MW+r@L{7^E##Bm z7kh4P5Be=YvRSCle**YcUgeF((J6~zfGjWXr>+dNi(Y+42W>zD6H|tGj++wmuDUO% zYg-Y9TRE4)X zAF&-PPwaVy>|@jv3ZgvwwB`Z#U87%30hLUAag^G&jEW}iLxJ|o;s9_>h+KIPHH}_S zD$fVkobfaUyQ^MhM<&h`L*70=^Y#!>Q-WgEQxlYT7w0>K>+sTtQI0MSfY@}uxtAOok|6|hl@`RQaX;fn z9SHSJ#{Hub8q3xcn+hT`S`MAqX#v4Lr+DTuW>ripjNB=Q>Dd%@X~e2}=gtSf67g+P zlAbHLyknaw96?!llPk%>vrLnAn^2!o$oAn;4+jFim-j9Focoz(SJY$gFbn=DqHC?UII$NuK>gK@+unIhL2cli_$lwtM^lvbJ{X3@|R6vpr?(=%`CXY8Iq#k`M?E8#5 zJzMP6m|??j0?}oBuIgNAWgS7yhx9813X3@h39G|+74F&E>oIv@$!jOu+hgsxr}pdH z_6E+hJ02aO=%fUd@#yJnVRA6DD@LKmn7lV1pioLZ`hv$dg*yF0$=-U_=HZGu{;GCS zk>`wphUP}K>6|Ddo=P8HM2m++rJQQxTT?`fn@8ZeIhWJk##kqZ-r7SYo^yDVeSY-N z`1YF=Tb|7p49$*cdtL0ib1u>x!Up_dg;oX9a5pu9;mq}U=-e|Dz-9>JXjfW62|6tg z%MzsM?g!M^3SmaU+aXLA12qv>BdJ5==(k-mvaKF+I>fJ<2#it_4Gad8$%xb}betPu z+bxLKX*|~KDeEuZ5ePsitZ?8ZB?!8UhN%W9r(=_ljRXY&6Pt3aV9ywh zEZ815qK9c7re(@>VPU>X!!$b?d*>X1x98YVrScLbj&{Y~-UpAk+5JN2xQQyoycQ2gR$fXnT?u)f*sL%c`45@Dup>RhLeL2nzr z@!R)XN%2cmZq$RDTAdLti4X2SHaiPb-CibpuzvoY^CKy)+v(@-kE|b-8A6X))!f|s zQT1^L!=RJaNzZL<{6<*2TA?-k&JmuDsPgT{&a_yWpQpRRQhoPTi{KTlUM5tgLuxFevSibA_D+5EPm=co*sJ4o|=r~w;ylgb=^@p7ayzBW6JC4=& zAQ5z@KO`wPyg89RXS1ymee!yY+5Y8uSu_YlYZgVXRPSEhO&qUV3mC624;Zgv=p-(` z%@Eyo$7%3=ECLT%wz!DAmI(!hb1$C|M4bqH`Qo?})v++6lkcuG9m_l&v^<|xQW-`M zgoUrzx&mS0r%3M;<0mv3nmTzd&iPVfGTIEc1i__dU1?4Pn8ATz@hDUu-OtgTPc zZop9R;^Bj044xON(%;#A4kW%gkUmGbEg602dJGa{sI0y$;SLOS76#KpCEqvoNP0k7 z#C<#9+|3d86Qx1T%7Ip!XsA(}PYl1X^Q3CyIuh-`d_+PGr2Q^QS@{h`y(~wB-_f*a zgGX7r3sEf(rv{bn01iGPVVzmdbrEekp)76elBZj;<;dVJFVI74^P7xN$2S5Ld+B=v zEnmrT3$4W7G9AtTKYYDqSRCE9HHsy8a1HM6?h@Rc;2PXLXmBT3u*TgTf;$9vcXw@E zzb5ZK=k9y={_d}?>V6nC#~fqMRaL8M;TAMzVe$o0u@$lvO0hY_{Zu1tJ}2>>*TZhR zUW(@<`sYfJpj57`lH3OIB7f0{^*oc!P0T@P7204_cx8w}76jXgUc*Av^7K@o7C>qV zBEU@MH^u+WyhAz3(!~uTeD$O9r-d>$Oa}09w~+|~3S69o4|F;Q zm|$=r7Lbam(1_&gEQ;YJha&rIEIA*k)`+Pfs8$0MZ%cd4C#506qb5PO!WFF})!itw z7O=}5J4bXum&EAqK%+X(WDD6yOnDI{IWP>AJR8EGxRqheYUah3cc>zc>%H_|qRuJ7 zsLd*A04S`w1ujrn*?s*ME^ZE$(Oqxxu)t464!YFQU?NDWLFiPkssX7>eKCPH$!1O-J*Yz0}~ zG3_TS(xV5JQfy$Nl-g(nQQom=g=^YmgDM?_B45>@pZr~uTq{DIMC%iWR$88@dG-6~ z1qx=42HJWL?r$)21Y;b~Xyrjus{EgbAkNt4QfR`8%(%2`@<&Rg{_SHF8` zz_sh*CX65(KrGJO=f12n)$_H3ZPQfnU%6#}#+G{f@4Wh9O(n`yEMcqxJP8N$}B!`b`gT;R7 zKA|Q>@bPlDbly(y^&aJH(ld4$a)g({kr&??ty3(}w(#4@FYgW*0!0Cle@aJuwmToK zHNBaTi@OZ9O^gN3nd;2BA`OgzB$AhX`}bfQLJ~=|_IvTY2lFSrId-LoCRV2|Zo`PQ2~;Xrp9g1G zaTvr##J;^ODKfl|YmC1<{Za;c9Sh-Cq3lt*R*G>(<<3lhqff59I}$XcrQ4s)MC}u( zhwbMiLScO#mz!e#z2IK)K0Nv}phK)?|JH2jy*KaqF|=fQ3(*Xn>>(@U7OX#41G_;2 z(QKU`=Q_+uHP0X>)Hnf}SSk52yaIbLwz};SQwrrgDeWJDcmNVW$683^eNZckxazFX z)%+c(`;9T@J+Lp%X7?85q|MMMlcuy7zsc@UThQs<-rKt>y$%n`YSZUQ{tDE|zv<5T zn{E`{_jLC#3_-TI8g7DyTH;m65k8J5Odsvz>*WC14x7DoiaQpa@SnEtCRc+`(tEXO z#J&72Es0hBR5LJt~zbSYwb~VTC>g^ zmhj{h-PR7@4RADOlK(Mjt9JDN8DW#;72VF%NeMJykNzfo=5NxoD$b(qQ^rq}3P6K( z9K_$CjtKTgC%?Gtx7kAc4lO!c8R?Td+Z`+lJ*tV8JQavSDD9J>EaP<>Mu{m6beWXy zjzByHrCZNh6O``Og{q3H&NB&6OnR+VXD9^(XmjaE&9E0F-OWy{WoawJ?$pYTUnMq8 zH$Hn~GN%7NTZuX*&TP22=3Jmx~D$|-?QE7?yyQa!cS4bOXz~O zA=c}%|4oOpDd|$V*X1vcu@MNT^K1q21jOy+FV4bWoX)>EKXiA0tj2$P$N8~JDl0%y z#hZCd(HQ}AGB(-?Dw6Gdn3J05?%__2C^|i!SdjXQAoUkP>N9fGfYf)djs>ZIX++ur z%1|mOLz{gOCj^F9%(1HvBAnoQUrgL=#a-h)aTvu+l3dXBJ_=MAT~5KCj;&6dIV4Un zXi2$OXRngs_e3C`9-T#EeO^){K;NgXa)vc%(6hdSsf`IcwcW&Oh(09{vra0X@gZE4 zJgeQYfA#*t1INS+SjE;OUkdh3j_%niFgK@6vF;Fn*oNgei@EiB*4iWW-I0Hgify zf&g^s0%PFP-MMUweeadX#H1D0nR+t51$yjAM1As2>u$hdeOWTfwdu_|raGR5R2}Mk;wkowKs~>&;I|IdehrzY{e1?#3ZI%n~US>Id`iC*&R*en@Rmz%VzAe4g zM=lutdzFylvnw(zjm5&XN5ANxj{1W-r+m-qr){ndE znSyUmNxrWt$qhd4PkXb+nFKyB7r=2s9~T=F<#MK4mcaHviz#G@zkBOiel!a*Fx!kyfb3vPQ0u&i z3eAK!_S_{p+&?kDcVlNad;?u8i*~Dhlyv4i0^91V_p@%-Qmx79`OoW9-mr4fvZ#K7fhA_ze1}E`t6Y^2Rw`EMXi9oj9QCf> z6UVs`)C1}#ExVRxmYUSNmOyJOEKzBcjgq2-CEF>zr1)xAsYq+pxVDEz{N%7AWh1ll zoV(XmDvSF5$qGvXDMOs9z~JzNJz!<@8}R#6s3I zocP{=G8+|RXI~?mw8Jdjs$x|-UF@+N7SBzFAK7Bx5#Ij5np6mKK=_vW*|PQ|;p_fh zd4+B#w0-7i)=<1t58@aUx-9LG8^ojNzWX%FAKhv^w_rS&cGeJykX>6oflQN7O>Aik zWv!SU`ANyCQXhw~+sD>~MWF1$dAX_{~C(VP8N} ze^G0%MN|)=M9!h`=}>3tGjm~?hbu%Ddz`nb;=y4crQugE^x-Km(o7E_8jw4f8(Al* z5Sd4R5=T)mq#Bi%C%)q7`B?&@SEp?1qKZ+Sh+B%Kulad1gQa1L^u{jCK+QQ{;b>(z zs&WId9+GZ5uU%UCs)>)rou~F|ffS$Q5yzk3>rP4n-5*G)Y%KtQFko2z1p%W;MUnN$SaEc+lN%ng=;EGT<+OZCp zk;+D>N1o^0A_V>3q+ZuY>2fqrz~&nncL` zE7r*A6uA!yTf)kXO&iUEvCVR)Y7FRy&dg{Xn|@A~kX^v3s8m9~HZcya(j#%5XnT?0 zb!ri*@k#JFFEyeENgpx^$ud>kS^&Ls#2gaFF~-0jAzKWSlf@)wBIPdf;vT}gGfRhR zy*i-(e>9+^_eH0u-l^Qbw_1aA#otkElMgjE`vG${lY6FHp4wt??SX_rWXTXSFnGuI zy)V#MMt}e0gq2B#Pn_)E#K^cj0;} z**MAFu|Be0m$b&;vSz#G8jB{Ej?w)AY651UCV--(XaC*=FaS|)xPYiD|Jver3boZ5 z0kujMTxk*{Q%vhQkE~7{y!m%GB6?mUd&aR zPD#6FtlgFS3Gd)5x)2JvKIriQ92_2E?RpninmFyabjQ`rlVktdadI;iwH&w_PEm*X#RJu@#ThNLF9}!xx$<@pBbxJp^Pi8l)6KKcwVnf+R z8jD^>0Hg0pEdEsj5H;}=aQb!IP0WGgh#P?aBVGj#8m3_5K92;^@z3Hx@3O_bGRX0piN#w2Jm^t`ZB9k?uBJ?^N{qO zWm>^eN>-q0l=PMi15Lr!>J~X({%BL4TZ)DPurk*goNTR(Qx1nm`vv=9RFjD`kn)^081t`g!UASf^$ zM7Ls?c40Vs2_1(fgYlu*3h}y;i)ZLe{Q{{eEx1*p`3vsZx)Y6tgqLTjq4SM~h!u`h z#%jI?-wcD*a_oW zOdUMWk43m*O|>~_e#S!zCfGOI1{he-Ub@d5+$&%LIibJ9-*ULFW+IA9Ff}D2=xA3p zAD+Gfn0Q7m`a)mYt0AGF^jEYe(OJ05u}D&;Tih{hPMg4l#c6Cxp9LJ9hYxsw{`}d` zY$E1HddM0@W1mDMMo^|2A7u@njvl&K^iAiA7R^WTOVOwGij0;9F{ddmH&zTIEL?n3 zd99ht9lHpqhPnsF@H5v}1v?zf5dRzipm?)#Y(=~r@ogGZ(x}Bt%+pi+5$5+`5-@9f zWNSswQrBl@IJii&iU-DEVk)!bY{Qy}8a;GU^ZehOv};4WOAPCD8We7!#`hcc*r6H= z2^dN#sew(ukJmZ3f_n)K`xsV`eg9yzaGVfjjZWQfNacSEyBvQ8)Zu+&`1DAa4c|3l z-ZC^ug<&n5G2_8?Z1qvzO>uLrMnA$ugF3kHkJyr3vNf|cDpE}aeemo{n2QZ_8HmU5 zaQ8sX+08r>=!vbcs`M8$_H0}LF+`YrUtVU$E{J%GTY0Gi) z0Xl9IJ>*mm#GP-`8r16hdyC~tIDe(P*I;XSg84Y+tphh^)YX+!?Tz2n-4r9!^L2!e z?)>d8s+ILYBg^P8>RBePn)%!?M{WS-gL3iG)}8+YS1EVk$a$cE>>Qcjgojx=tKkQ! z=?|rJaz?__CkE+-Vn}i`4|6oKr`Og>H#8qAuu3{zYCcqe#^>3FPPIGAl7Ze)ftQAuyeuaV51(M6luAq+)Q^i(?f#q0n_6))WdlwinNW)UHNop*Z%f! zs&JXmRTRqDzM2%usoU7inc!Kdtu*kgTc$h~s(xiT{EHQ2Gg|9m92ej3K{njE4qY>> zHO`B)C-}+&a*AVIVclZ5=g7?Lvyo^TtTiIEQ9K?g0>O%PD-JTev$$)E?wAHXqP^cC zyE^t8*?9KaiJzcff@Lr5GK1tvV{oI5V%C_W+aM<&Yz)qux%Be=k44n%vE;%vJ=`u8qZVhC)~g)qpMz-@~po)3*mCfFEWDO z>T=7;7ubP@60sJ87+upt7CcYFQvd~(RmzvI@Lg=rRCD^cKRT$zQZZ7w8V(=Ff&+J#dv0-L)j*w?Ga zAn?*iJvte~w$o#_odULXkp>{S=gFhn6aX}MZXFJA`stdGe@rMy7xx6s9*7cbAnKTf zG#hXx`r*?c@%x4+PP|W?Q;872qgqS^?o~O@>8}TOkf)|)@{QV3a3#sPRa<~(okF~d zfTt#ny8du51WU&pOANZ2Kx0HX^$t`cZhpd0=K^@)e<@`fS@gjKFigYxhq2IEZ7g9E zeOdl8QijgrWW7Nlodmx0gnP^;%Cbk7(*|X(DLUL=MVI~nxmh-$_05FyLso>skVN?h zKMq=R4MFds`rnpSqM@?Tb3N?jDL? z!&kk2Fo?$$p9mhBQzdKJ74btBALY2Q#th~Jb#Uy=(&TYAv>u4lSOtiaXp6ng&bX^eCIb*gXj#|W z*bmI6@g^6Qxen3#iv`BSZ!xeh?VjIxPa(TH-M0L|SCs`OwzLH9F|$?pVs~1N9aC^m z#t_O17F0Db+=X@66W=WK0p-c6DH7-Lcc&W`!R{k;TLfh#pD$N;=ss8s7aooSLnCHY zR)(?8_ar$2o@`U~X;>w`-REx;Lf@{+I;7;yd2*6A5Y~UcYPTp`8$FYV+N|qyS(B@e z;9b_$0p(*&t|iI}VWP$2&LJ1oM->vDaZ~Oy7i5xr$y~}_>*dDT`WSLdO2o^uViCDE z${$O}B+EJx*Q$8rPm&A`_QMqShP;l^)g6#zKEJD+u0p`v_xr~7(bK|O*bfVZU3SsC zE~uCk)}WJaI27;VhwbrJdF<7p>&9Fq;z2p$TBesX_S>+&W6O>62X-E2B678Orm#Yp z>^U;BKC>`Y|NLtAjYF^%uWbOGxx}9#4Qz~*^7o@X2XE>Iz@PPvrfNpV+T!+>Erg(< zws>)U_QdA^NB&3)dd$+;so`^)bBaXg;+ZurB$Qc8Jx(GzKw>Pfcig7ssO}SBw%EINbvcixV-ji)q%_=^Lt0gRbZKpEOBZ*DqHJ{+4hxAXEs6N4z5FQs z*g>1ozEM1@CH-Iq%QB#LZSU_9y#G0ZJm?5VfJe{t_t=rK~H<*&SMcie@q;*`m{#Lyq4H@al~fei}>vRBpR zo>m(?dO`$xu6owaS8C`0=uh_-n4dWdv20b1;V&b~;ZRzsw9bSBT#w=tmmmW8&(c{T z8{e*-{(Re1JZM0LOaC~Y3hso?db5>3B^hl^Gi|z~8m=Zc8B@9b+ia8!D;!eKG3H2^ zm8-0NshFrPQRRZ~A~|J-d0p7r(i8u8SfuK8YY#k$`Le^A+2&@q?^aI`Yg%`#%YC0M z!zaZ6^3MJ6wj6Q=C8&=&mqqy1Q9Fwc@RfXGO8&dy5-%vGUo-F}JL|rbAZSnrM*3>mH7LTdV$P@Iw;oCwy-Ni9=}O41~i*VD=EiWMPJnrhjJebmepa9)yhyF=y< zYagXGIzytUxO zFf5jV@)yRC$wS^UFqF%r*bNwuHzLC4F5R8-YVf{7u{B&;Y5{z%%);)% zGx1r>hP;MHF*+?UD?s7L@y0gcJ_5!q6~6lZmv7#`t-A`n6j7VeLp9q>cPAwTG8?YF z1n_a*;uJ1gHhQZJ=CusNT?DZ#B0%9*qkE(dY==TZd7)^2Kq;F{t2_Pbfncw2W75Wmp@B8)J?Sp$j zuY($vM{IoX%Hs;LqbzX%Kqm4DqY57(cn_TTRIL9evu zlMLt!K0gCP^lM!&JqcebfyE02j143+Un%X`26((mlyw`$N@zii%S$V-x#nHH5?YXY zy2(dyS+0#ojaAegYENs7;h3Gcg}*6iXA!frd)40VUK!|$EWMg(@6l&D!Bu9I+DsSN zswk(XfDg_l&oTmi$L0e01#rIEe<@zGXXf}sDJT^^B&2HH{%a@M_Z-+pqH*QDq~sIc;6zHFbJZY)_HXr=6LD3$%D{6flNy-TtebRN$P~5xFCoKt5jd^)P;%yp|UY zi@?sg_jSiuVY3GC?vNZuV$usT)&;YaBE^( zlTuVhJ#_lcLV$64nd*ZxmDAGxw0DHU-G|H^o-0t5+2L>?URcPC?@z~GGCrVJ=7OT8 zc@BEF+|1OxSNJ2lfLQjPilyb^zjh4wRN6Imq}yYj?Lb>Twwzw6a=#RsM+>`gpzL+Z zQ`eu0`n_=9bT6p+efkPxX|x{XQx)1|b9xICz9ihE*JOa0C`XfJ=DfKG%(kU^HOtq$ z<;A@;iq-hWAzfL-o{WD)&%_*jEz7%iHmnf@8|05Pgb#bwPMmtnF$WjeC3`c;A1V|r zeiFze(DM3D1=1u|p*Z*ZaFvChg7$ZT%;-qp!9sWZ_nO&cM7IPf^Q(PNWv23y8jd|v zS!MWtc0fA(7e#CYFvf`dXuZNMM+z_3KV(jAYk2V}!{t28@K%vtQsd9X-lNlKf;dFq z{`3leoqtfhv%EUwnWadch(!~Mu#6`o+?mc<3Phw5pf8crl)60ZwnPJq^ThmvNh8-# zQm`X73E?%QMlmRzs1RZ);U&P|aDT0NL0v+csVs5x%WxX(KbnI6ztz#U%0G;}--`;g z^G#saQw-D){=9*Kz}cjv)P?#m!WhDwX-_XG(0^ zR4z*;xw?NHrL&g+a#X^~FoEc|dK-VL1RMXzUU?~{5xrKwlRn)MJ-&sLKKP;1b2G-8 zoTRotIUgfc+Oz9W8=)@V#P)0?-!7vIrOuJ?<>J=}ixw^01h~8gRD&f`mh#igB8n1ryb<{kw&0P{b9U^|K1c{Ohc&2*pVI1efOq>7}CXDx!aTdIXEwHtVJuG-c>@+&^AZ-bQ;%y#enOe0^Tk8nW`R zEm}Nwtjc?(H))eJsJ#r)W$Cw$@k5?a7yikn6S-h9o=oI4bTn$?GJqjK}KAot2vsZTZ5P7L{- z{lj;WZlH;yO))HhoqJ-N%>2RpR5U%6DbazZc)y_AA|W1=DbbK}*-pXNH%c)6?e%J& zG+O5EYQQcgku^;={E=F8>^UrZGr4yHy}(gCEIWUF5QjWi8f+BDGMTPLcU4)QK9aeu3Av53Jxy!$ zt*nTTW^*zDtm?BFX_nldn=OmoL9tfN+5|~Uv$nnv|NP4ZdX;3-T^f$*Bm!lrensvJK77Afre;l|&|i-x$dpdw)j_y_{w zo9rWh$`~F!;lMUco$o{j0zjNEn^Sb(-eAegroR8laH;iTz;O5o&S^o8rO^Bi$-^Bs zy*r}E##Jk~5jh*YU!XM>Y`bl;BhCkAb+O%lLhMn}7oGy8}$3^y)U4?x849F+8P7n=Ra+VPQ# zFc(}oc?ieC?>#&=KPW{&y7`N&c>TDX#S(jFdAJ|!@M}CK_+=#3D%4mB>>o-|7x?^1 zu?{h2Qf2TN=a$It(QsUdx}Af6z;y1DSvx*~5FwS5yBB47vaX-FYQZa%9)CCsaZNs^ zfP_B11AoXO=gl0|e9j!r(6?;v`MCv2CT}N@3zFmnvIrKyzYZN}h?r>LCB!#o!InAb z9)rY1xD7%a!g=@`qn97l1Q4e@a}cDk522rE@CY@YgWy_Z-`nB|Mj@z59XW2n-z~%N z+ObVxzei1z*=)^u4C~th6vyLDMy6*klb<=FKud!4eI+6!%GDanvxq^0DHSm2-+C+a7UEM9G?1$MM?!;|7WWFgZ1g~RSH0@f}5E2L2#(@sdt=|y?jN+d!^6$%oh7)U0Ac%MZPv zrq3zaxJm1ikxU0cMvp3(VZ_|X4hyk2Yo1jI6<3EIoVn5BiigGLa;Dy~n~~ z-;e}5pzFtmjHYYf4spq~dFM>yq`EPE#=o8lU7G}Tezw!SR1A=O=ycBi z)$oB@iy&SJt~h=8<;}w#=ng!erKSbT?bqLnZKi+G4ehihak<>W@O`A}9FB(28`rrU zpPyRgNoq-3J##$uo=MHL-*g=*d7C+dfWb0hmgzv_tV!na+Ym1`VUgZ!aGDid9k?s~ zo&G~Tml-Iz`pX_IX7S6>RzLjPwUXawJE)75c~@{!{bB6JJIuzrfE0S@G9>B8z~+W7 z=aDU6I2FQVGS+v{xD+0tZh9!`v7btCjp-3@NauEhmAR?moQdD)h2}gzLUx+P71T2|I_@j@tq^ZmB6=$LlJgE$!!S;1t(EgW0uF$Sgvr6_gr_-k6!;6{S z6Kh4tIrEW$mh{CJ+wKp=6H|giBJL?}z`}K`CPjSVs_pZF)+8aHi$$yE2l=&fBRAM? z+|M+kF2=9e^se0MSiBrCj)ylfFbmbfnk|jrI8Np{YV_5LLDSgLk^=kg9A3YhmH~+S z#$QC>RLn$CbMx0_@KcoViIq4!Zm-eNBM&6-B{L3pRSNm3Q6#n*dU zCCBGZa?1Q39mYB0LM)}mAf>FQ8+JV{@=}-M#Tqg@ebt^K9Nh8EIUI@Qjqn6A`-4Vu zAQ|lZ)Op{p$kJ${g(){}Pa1GLU2NnpndG|~a1x6cOMG4zG-IZ_BlB7Rx zE`9kEb0?EwQ_g&E@z8a)&F?)P-s98jOTS*Lw;LC~3s}GUj23TTIQDYs^i60d@3eGE z5hDz-p1V$b6tsZPe9bd68&I$59*JTQILU{SUKY*)TQ*S7 zX}3dgI3i;7OOXJV|!f#%+XN8e_zPaEk3O|}j=;Aij$Jr6dUJCE-idR5h8u*&N zV*4q}9j@9o`^NY#i-AnUDL?cqSjQZC2u&);@rtZ{Ka}eB!+Q+>-_`V7xm-#3K@02g z(}Mk9SJPwpyPDqg*Z0-*z&7rrp9twX0(z>s75|hpEqRxgG@M7{_+t>3o$8c4uJa<3 zw4Hz$3a~8!B~$it0~3?{-cKFG3fP=e^Nfru_4M3`E8kK5L3z)f&JHK$S|}8`Q{H- z7rTlH9>{~)nDFZ-sU&6zzFdS7BMPtMy;#Nc1h# zS8kKuMu%2ynii3A@8{WY5p4|*l56xCbKNIAa1ePKw~him47OdL=#O=yayXAMJbWEI z95LJI2{HttsNWd1ya@E4<%2~bbR!m%E-jun2ME{bhG)O4Tt)QXKkR-r-FCh$x!)4) zGV~z)?)!*;u8{b2KE$Mp9Gbk`mD%>SLSr(k)*psYMAOAH7nAW?2o{Zu19RXTm;Hdi zWVnk;VTO>321I%~fU&^W=V3dpwQb#(#Kq^CjwSq}ck7KROvne9KwLe=3|}H`n+Si7 z_Ser})+V~+pUsk3!v-1aGL{2?i_bda*8z6gG4`tmQ~b-d1EGX2&~&Z?p(->zs8+Fl zzeogJ4-&;?LyRElBar#|zkwfK#>5efO8Fv{jvBcNyd9J2331ePf~h>R{hZezfmXij zMDj{mv?XlZS?z20`cBi>d+nla%@N~yeYQZURV_XoFW6Qf@#2__RQ)xPqB1B7_H`ZCiA1ll7=SOMD zeCC(7kkL-ya3B7TLoRM%OmLE4PGg3DYD3($UX5zZjY;vx(b~b9Vc@s%x?`DU?r=3H z8QYYoQCWAfCq^|RlNW~6bszhrI*K`UspOWXSRRTtC;Dge&C*Z}r>!}Jh!BbqF~u!n zs%q2(yda_mQj}KSSO%2HBI|3%#UPefA!e->KdMI{)2=<5mmD+Wp`P8cJCZrC9Qf5!kKLw{rw2W!+o z-dmJB&0HuCQGeta7c`TQ2(*M_s9jv)31yfed?+c>{z#B%0YsJG0*U03BeGUR6>Z6> z1mT3+FrjX^gmwQ3lR;i_o=7s82Iz1=D(0f zJTP(MkvM%HwFLa@=#3Zb;B{jKue^?M9(wr#_f?R_3o~LBx}gRsBaB%y?FZVul*=Z) zu7aTk3uDf_Y6@{dzh@}$(`RPo@2HH&Doll%{xpIt-|)(DNE5Z^z;-NLs+9U%xS6BP z{VBw$XZm6PVV49|Vyl|VIeC<^KYkjGqJAl_E}AE>Z+2MWZGj4iuDEt*Y1lEHxcPZ0 zmGdbU(dK5-kE;Xik_E}GGwJ*~c(?Skxkl^{EF;7`MyKuWo*~#fx_`mi<&G+FQ4XlC@Q?5X!7? zeRPItqyze1{!<5XPT}Yi4#xO~4pM$cN+yd3;iSz@Bz`i#>R-1h6}_G`W!(;%}CrKN=KdC45-# z{%s{+w)b-mAq25XmK`v46qNkwwup-F{(tgVh0_DsNZh|`8@j%EyT9Fqr-;{$xWFo; z@^|~V1seclh8Z616p+uh7%Ihsm||_51DPV+18ff(SHqsmg_Q;=UX=skp_mJf4(QnZ z!<&eo9^F8*^tOj!r7PaO1Tw@|o6!I5oFjXj^@2|l3=G!_;{STi!TR@{Bkp|#U-Y26 z#79E9^RCuZVi=YjSS5+0982C+-aXW^g}+PqzCB?p#>Lizi9-zfox6>7QThr<{rHrH zsG<8qRIn3H}ezJK>MCr%E;h;+k_>=Tt-`!jV~iyETM|u9>5Du z6MX{k_$yOEd zcg9J3i2r*kGLmi;v&zv>(1FDCCS3Fp_me$eb)DU=4#I*OhBFhF6mpB%qZbQ=o0_s8 z@0bI?8R;W%-7L1*LHA**1s#B7;TEQYZZ}n1OfT>hq3_$=_G16i6GE8befhd7*m9?@ zca61L+3|bB=WG=8y}#NTd|S}vd)ks4dgR-ExiV^O zIiT9q;CX(krPTL&e5z#>@MbmjU^ZRU_u|2CN{z<*MLNG7yO|vAB|WQo#KJa1zB^j4 zUosU@a)1Xp?vU?v;vQ|4ZtROL*Pa6WGpESe#h-TN<54}XOS8;exGVp5k#V)M`}Q;q zx|n|RnQZH5d%D`{JFCS?QYiZAiCZ0EhBdG6>v_3P_UZe0uzv7buQe|cP%Q0tV^S~-;<$kl^+x;f+TEFpW$Kg%NJ-AZ; zGY-aAPDUd&9Cdkih5aVLc!H zFbqtp9PqPZhe^}{{@L?oEI2mI$Y#`E^}6d#O(y9|j^Q3)$=>U@KaojVjWc}|9jU`x z$k&+$NH6wJ%R&DtQQeCytKn3eyDG!Uk*=l?FUd{*Bu?*<=JqNu#pk>G5+(((jdU+KpHIjy(Mik2~P%3+QQ%m)p&xbphu$ zci?BiDaEPEM#3SZIYDhp;O%Y5T^UQ?k6=fE)~CyX#zs@&6G>4i!7KH0--f$O#<%Bz z+?Kn>HylKXqxyvNJHoYB*UzT17}=3P7cXCpF~78qw&sVu$Gu16{VpESSubkwhu2Yy zx9K$JwDJ1(x33vzK#~E4J2yhT^$yRM;g|6a0XRw%?hkViYdbyYFGQ4^Kx6)4=jUvB z71@j%JdYh`UVnkiib?u?g;yPx)y!>AC^pWVe)R3nCdQ=bJG9MQzP%-NhCKqZgwt?% z5xkBRP-%DGH)~dX_ikT-2%9f6;YF+5<=AfoICV>SVLq*i$()_9?5^Xbx6a&Y{b=&n z)0}nHbSDDh+h1E;>M@{K@|NHb>?G1YVRW>GrkqDX3+lNtC^*<*Y)7ViOj^hPMFZeR zoHp(7k~BVk^X>`f-c8pSG17fAl6O)c*(OQ(b?l)=M+jH7(Mr>fUTTysS{Y8O_9x;t z?Zu39VEVWDxy2*{=IGN=&ez=wtWlLYQ)-s-wz;0YoWu)b#5)T z7#Tgg$q{J>%+Y{qb4+-PHHs#4hEgH!!hP%8X7{7iTQOG0yGP5nMU86&PC-Y!{+6V+ zf{eX{`oI)M6ni!86obCR9vd!=7Rnwu17vWBncNeelu$=mBukhV?-78 zi5Hlm^Pib)<;6*`uocDo9Nsfh7wk7*3qgPS#=aNRRKRhLGO+@~;*l9uXyy&%wz4|9 z;$aeGkGS&NM>W$6xM6pBNbh=S0oPI)PIi|oA5+v-8HO>Dqc`4Sub;LA+Hyfz9c3HJ z;e*8G9zYAWIwEL|nRF+yvTWtDmy5#E)K#(LP<_57`PR-!@ci3t9b2!ZG2Ed)*)1d= z&P+knSI*m9Q>CyKn5yN4_G%;_FgHVTAO2yV{YIs_V2=Ab6}LzvbB+4`1J$B1T>>*R{47oh zT>=UWys7MnNa5_BoHk9 z{Q-n`n!kZxxyG>LgJdwqGJ*x*r>EhrbsH1hzHREYe&r|>rbF-2pmX=ylxbCREw44l zhHzmrNVYr1M2LWb4yHXs4U?XsXIe>OlJ&)AT5+K^4BBk>)WQ2B7QjSTiq~cTB?Vek zJsdb;YuBj=7S|}%T~*fojS1@87nmOWfK3Ab?8q>~qA|sw>_{O4Dq|yTo^p9Utb*$q4G!;79PzT_yLUhe_9P76j$}6ct-5() zanQr$eHq%#w3}||j?4s@Cc+NipvC0tR&3Sx`fssUzsJs(@K5X@(+6#4|7YxwJptgN z;F4<;ust z#N#VqciSU%|LjNmL9B-dBihZw`}7o7Cw$nrjx@f3f>H+z)kQ#;wVZ8(N-?xVD}$t*tQ(1 zc)><{p4(k9o=kj?On7FIuswf^f-qR&vqAFJ7!!Jng#L&HGJ@Cz20Vcw73cmD9d57? zJ_7dMa`T5ClCB?{(#>DWP+i~=6vz>#2|psl=t^rEx*ri>K|4+oAq>+bx-d566%OY{LF`#}tAE7yg@L`27EW97Fm4a!i$i`UlOQu`J_U=*!}IJ8{Y+y`m`I zeYp}u;g$b~uD1@WD%!e-2?>#ul$P!m1Oe$fbc2M_jWmZ2rKP*;&>(Q29kLHALnWI?YB}^XG1=@1iUH&E4hC-Jd;Y z2hkL~MW@MZivLP=RQ;DVG63UWIy^}Yme33f>;@r*BE+>QJP$R+=M|^oq7|ddB*JBX zN!Op89J+(9LD!G^DU^%OEElLrX3j4-j;j4bKPV+#%pQGuiK|43Ybl6Bx6B6>{$%VL7 zyt>?N*Jdbsj3-F)i336bGi7gOeCZGv!YD4cG_fBtRl!?pM!2mUBzl^HY3HEPDc z$|GUOKDUk>eba`Wg`l5{6i*nRL9bs=P^N{S_G!4z8=fOwpCkm zv?v3S`S+b4G@6nl#0)KY-*+pIn=_7^Eyw!?R1|&J#C}32{zSCRGhA1BZZ0FW=ha&! zE~Wxz!KagG+^Gp^3z;?1yttEJ4~LeeT) z#uN)9K8EZsgT&DezvjF~55Yj13~5-mc^e*EL-(eIbX}wvtm&s1&!KSuW>GG|2m*ci4MwZ+>Wl8c87lGSMK~Z?=bC@ zW$|G>#q6W&fo%uj6zjJg17ju%v~ zkN5P(jo>1g==7*}xW@@XnGpQ)!k+%#s-11a|19-J-7={F@j)4fahyr9S&yjb8)CYv zZO?~~67{5`@ulA#27W#NDAD^#CGz5{%<*rc;yot2=7JY5I;te?r;>b{4bb)z)zKqW z9eTT@U(5Z>i0SpCem^_*k%#Z)s0Pk~sQe4L*Qsx?JvT50e76%;D+Zn-k^Ut8f%V0u zxC>_{@OAxQAayljRnp>Dh%!p#ARMLDSA0_cpV;4H><@AY5I?GOz9c<+Vf9fR2aZ%j z9#y(>f|r!~6~-A+i(|x1>Vi76V=7O5#{te*Gy-#P&A_nuDDMo^PiSL_(Q-buJI7Y4UnWF+?5qrA>uGNv?W0~Niup>pP~&ZzWf zAY270{5yqr4n(BCSVPrNO6dC3_vh zAJhELI23A)DuFmUalTG{!w>$Bvyl7R<^7XhR%uWNC-$_mB-!g@a)Q;ZF3#xbkw&rC zyhD9(k*ri{Z9Frls-`vhMjzw3NXUgd9h9LOtXaT$qFQ|m@v)`(+P9 zKPf|W50Gv5KaOIe(#JE0;>KjV&Jw(=!>lJ;AvQXHAVX%1<2lr7$RWfwlD$rPyv1SZ zkuFJJ@Nq{~vT~%P@!>~QdOkS=+8yJJof#qZ-zK_v)m*CS%nQaA5kL?~t6Sj^$n_*B z#EjU2X;uJPiln4STzav~h}2sES(8LSOQshf{YX`h%~+BZ$ramnI4yo&-nY5K!_df` z?qHCykrA=*Gp;5gq{WUKYc9)GMmzsM`E7v-HvGY3XsLzg*y!h z3Qz%mU0kn&=CajCija%^?$;4%qe2N)p|QT5F)-J0^P*oWl5oxd|H)c4=bR({@bX9l zM*_Tu_Dk^F7091NNBS)ll)sLM+}iIcMx++7|-f&@oH&Fk;+)?MV8$7#cxwPcqh}AH9j@sCx5Sol`avpAZB;$gR->r>Tzd z^@O9(^(y*|s&h`)WH_hslYgD#1`f|3I*dyv$3p)OBr*Y8NrVx7V$3OSuZ2x4B2oAy zkz(<@gN~$&IwCEKHh<0F;j@o5xD$cEdKzkiR7s^5wv#7K7$ z76-#G3Hz}tIW4Dgab7B-@OY(I6uQa3c?`-+wqA`~PODdsZ;Q}%07|HTOWka&N!XSP zYRUS#!+I52aqQ8PpHXN$_-!?|_6W)x4y0DokwIx~Jz5 z!=uw+T`G(`mGHG!sd0zhs9zC1A*vWg{Mk4Br=9iXBTQa=8q&vy`Bv|_2#p9+Klxlgzw=YuTTx}5SDn*t9>}V%0mw82)6w_#G0UNk$zxD^G?WAin4Bj*$|4d1jl z!UA$Y#ej&*wAtJk$$nmD?y7XZL^ZTbcy&y4XzPXwVg5i^<^@juXF$tuI0}{T2i*Up z=QgJ|bh=SiDuav4_`V+F4~6&^S0fneBqA<}dIbGp;=WYmMDp5V3mgA0-;5 zt3D^X)6>JeG|ssrKao(0|G8r-Ed00iq`gFT<1r*s4x`TAIzFV*E0BA)cX-TFT+)^e zJ5ZO{PC{)?lLmFEPOS8B!Tkxp*Sd>pK>U{&nM2o9)rjWf470eWOSR-!93aHYy4PVr zqbfWy(!XNEzH14D!J;Xy{2L7(bdW|s@aclgxmV9|w3nSTC_%g|i zDe}16lP~bizFO(hAb(0P_yZNs7)mdvq^`5FPPbJYyh9998J_F&{-o!6m*?@V|P)fpmb{R`pET}$7;#X-Qbqh+zzwECTyp&Ul1!!fsA!h{di|z$Iq8pl6 zmnmzGYiS^Av&0)uDLJgo#lF-9;uyM?tgr1Ws0|CNOU3kJm4GCC3hlZ7+O(c$)I zW=X?>!JjGU*L9%8QOHO1t${Jp>jL?RwlR1GLppt8IqMIiOLz~l&@uvPT=7*M+&H3JKJM5b!BX&M9rJWV~^L+b#$A(OeYdgV!fHwc`P^qPyN_K}_ zqAb{8r4wR5#)7dmN98~)7dl2ss|aF}GGugE`HkxhAzkV-8L3}biD&z)CSsVmF~VnR zbee%_am`garfh}t?7Co!jh^6?wnhym01?Aq5tmw0%%=&a;M0Tx`sV)hw!!mmgnOdv zOk*E_G%4EkZvoPHKayq}Ak8U2nrnbGTO?O*$m6I;U*PlXd(dj}P*pKF#A^wkj`F$j z>p_{kfodeW)bU(0?_gxAUP2{82{v$e>78a~DY8TW8duiMMYaqDNOLU*!o#B2E?u^k z&3*F2KH4MXBBT9g>A~*ag7K}L2%o98-9}Y4XISk>B@eIG%D*kjcoXR zVN9NW`f@csjp~WN{Wauro$>kAQ)uMI{TvsU?&OCKF8B5NH||}x;|ca=Yw5abo(X7N z+^!F#9T>LW@9%zVzxgG($m;Sc{kWYF-NJbGgundyTpgq%{4UK3@3;<D@cGi~IApT}P|zF6+k|;w2n=g$Xque4eprSYJO(+BA6&Y|alY z87z1?c{|-5aaZ1+QZj4Em)`Id-YMB*D$zSUXACtxFwWQ165WGT2lHbb#;kr&#PdPt zx9+@Oq5!@ExzE-vb9sHYSGkb18lNZ5Q*2ncEwG?UzFvHD^-%id&$X11+XI^~P0B!$ z@tn~97F`N(;Tiqso^}_k*N`je!b9QEp-BdyNoo@;zi}97avVA!OAksm6w}tqy!%n) zw%XS≪Qe5y2=5 zE**Ah6EiP06a7Cplq4Q;HP~zC6Zx9HAR=I7)6dF1NYirFZ=5-A`QONQZeHd$f zI5x82WZ4+3`C){;5`eUCGNMh9K z>S)q+-OM$!v$qkmy}hx@syiHk{@!QHP1rR3dYnGGoItOt>An7R0#z4GMVrH{lwWq; zUz1Z`$_yt%lEAEl#-*8AD%{}p_4S3#x8sQ5@Nz+B-rrulAJ?Bwf0_&H(##aPBq==&t*$#R z!@2}BE4{*sNTA=_5htHkD9?FT8pg;uW~hs~ ze7|jlU`n|=!`Z`bztfhZSk*C&ngiIP0_44}qsf1%7-y>khCST4fj#!Pkl~q&qsAPS zFDvcS${dtyF^M#Mo@-<7UHDW!XrZTYKW@#xrqS-D;!rH-ODNFE32NcMK{e$2oGK@9 zpeW&+s!}XqMNwp^7N}|&T%px{;@&_6W$s)NjHHCZ>o@?N5fmkUb8xKLr#D4KX30TU zO|!c2P1L3pIgw!DmjG<2b&dF;AU4$)#^CQpc8LO_tWAIHlohc|=~=t5i2>{z+2aby zkaTW#rC10yShmNV?Q@@?;E5N#@5V%59yoGb{6x_HDW|&uX+5}Yzcyz#cizg$H)*lq z<@bY*Cw*7!IsS4n`iczhipQ(R%KeB9gqt=el}~PEq6;3H7U-h}uzmxaja#dpVS_^c zXluosq=!aIV(@yzM#u++Y`z)ZXqtZg3iRWX;FNjMk)9-+pcasbR!wQaB^|+}4eg&! zXk6}XVNpm>r&g-W-mV^Z0|&}YhbLgn%P4>X?rq}W;qi7l=q{oUIdnph!(H(m*2~N( zv*2a$vNpM3FBfe?b@+haroS;i{)^TZ6#R*d1RLORW3ZM$BFeV5fhuPvsFw?i0?g*C z-`8h+*s@S1uk~)x#OSc)wcUx=LTj8H=hUXs_LlvX_pHRlY0}0Oph_g@&q6)&)Lm`E ztRxN0$xWMgU-YtSxLVvIA#ZhHF*e2}4W?B`Xj&)M;O2t4A9D95j+k1T`t`#s1VOGC_A?J8z{ekYcA>hNf!b#zq zgdnDFrx!jwUDBD)zE1#~Ma$skx)d|##if6SOc^g%<=$qTx^W8xn=|l~8R~XQXACgh zIAhZ^0Wq_NOel7<3_W=BO|i+OhKXR-v69l0#KE~^(qwcTC|1PKctENT|Nq4FEkMe9 zG=nrbebb}#+_I^>jm$6Z+A#?X$GzwTupxese z5oIqXf^YP{*tVd2TSfd!ADJRoj ziv|>jC+-y+{@knLst+aSMuCrziYA(hJLT!RLq0khp_3Y{8f?bhuu<5A*c@r#cTF!~`pcFu$L4XtkbrO#sC8LY>_7 zuN1(4aU^)Gp~li8Y=5M2AZK`{cwLgD9t*HqaKeW_)a&^qc%e&nbUV7zczP|DsTTeHL<7X?p1F&EBuLKo<0LFc zAd0%rsY7uAMo&=uru?AIaf|Ts=8@hIV&LZKJ$v`b>>q4FEcEF&P(OvIY*0i*-p`Fo zS%p;8nbOFAiuJZ`P6!asD|p@?;ppx0XC?bTE2sP8AP@VxrASNg1hn>`L` zo4W&c#dvX>^6stNpQaeAVMS;AF8X*xuU7y%z=R@bZeJ*yS;Hlm32LmZpxWg3M700e z!U_d82aj$U&7Jg3GX5t$-`2XbDSVIJ#4|bc!qk%IsC#16tV=S4*FZjM-*_Lf7Gz z7A*RVSr{+3$6>sLsLcVDH9fTcZA)S9zGH$9@bQ7YCF$0L#mY%f)jh874q2S#u37i0 z=QU&}R-5goZyfI8*b4EK3zH=J#hu>~?IK=6!;oFzCku}S5s8_55Sw34B~GlFB)QsZ zKJ9P%Y(SEdg){4E_i8~@Q;iI7!1R>A#PtO}!m_>=^IG%VsWOLgqeAi23g4PX7#H?I zzd~=x=g1WId7`yl4>bV_8StR}tSWiXRpRq-6+V6}^jmPY*4X#wLw=EJsqcn8<4H&F&StA=mEn(?i6EKXW?kc;5OEuG|D2i;VNd zYfE~2FGIzJ*5VN%j%Tt|$`sn`1z@Y}#rl4gh^Xrhrus!$n{jE)#@r!|@p|obSBQok zeYqouDagYzVf8ol4n$+P&p7)&ugtNvFo792T|)?W;H*H$u6NM!iXHJxJV_00e5{mq zJ?E3h)&6YWSs|q2@mR>#2d(FlRUXo%*CTAbpd)4bt#y-E{5udsyZ+Wa#2aoTCn2rG zJ<6_h%rKQosETAOny7MRfYG?80+xzBc%x{FsfbU~32!5(%__Atf<)X~|CKbvztm&! z)s!lE$aN60rivlO<%x3C)`rIjpH>zP!kPa^yVOGD9q-?yJ(opTpPY6xx~05n(wS%V z#P8Z9Ung<1V;w?1+R64PvwwCH6wLDhe$ymB8>0nw{!lJ69V#lBHa#}dfgO63OL>8M zX2Wh~pEi@J^>~D{(@9w{!%NcfVIZO+^UBs@4I!h}e zaTWFQIJ2(%7ugqmz&|_le~Wb%5?XD@w9& z0hf9x%km{`dTT|=Y`X@C~^tqj3z+hsi3cJ4U$olLdL{>I+EaI>49s6;7fO$IODb;sR)~J3bmA4Z^ zJd0^eL9GV11S93@5eoYQ-tzy$;1Kft4+v(fjxUEDi2^v44p)MNJyi|g&8OjMc6 z?JZaLzTVbtf$VDNvr#%0a8lv7$AunY?dD9)w@J%)M04x;2$!b@a$t*cwRK4^4e)`e zk4kQjmwx0)`JI8>URjCbPE9?6hLGT&&4_)aF4khFiw)nTC3%mr)N`<&1^Pd;Z z(6%P|CC6XT*n_+*+NFcrEZVHGku2Ka{^PgY@^8t%OfcLs{8Clj!<7Q*+@nMl)FHi# zEnMO=kP7mJV>~F}qHnKlYi-}nY|npsv2*5T=zDU#VP9$2*4WnQbBc2|4w5O2t<6F= zlxp3k@0xm{d*e<;a_&$FFI+1)7}|-&{jg4l`@ljKymYtnGmHM0M8&Q41sCl+lzlP* z=T5u61tT@fhJ2?}z8RCf?ecW^-T{ikW3$U$Ra)m-lXpu}<&=1sXx%$*SK%7(OM)?H z@4FIDAa@?>G$E(>hA@4OYUChyKG$tZLF~#-;jIBbJ_=hK+?a*6e}{KjZQo&J?NvkQ zg!1x3{;nw*38%%r6~m#gDp+!?5$f5>OYz?B`X=Ur^&XlI1|KrsWr3LLh-2@S$b~C{ zJkEr1$M_?aq|dC1^x;zJQyLXy3*1X{TynUjMovdcU(z8gkWh_q)(yz^ScMoYFk_Xw zh-r%VnL%)t zJ2DsbuRHH+WXE^`1MKhZl#1sdb}Ii7m_@;+w@d9Q{^sbv9c^m7W+Ri ziANRe9S?ZnB&XS$gh`L##~Xi=RipbpPx5>a1__eFHqy7_5ncLE1vWKTOOr0m zO5{n*;kgn?1$_l+tzP`oB}|2kxJD%&HnM8(Q@eTAZ?KE@M&bOM2D1}!S5zDqHGOzd1~)gag1{WO9%GocCqg*P)*opi9ItFg{w`dm&Uiq#TLJ}$Z7R>Rlojf5J$MozIX zD5HQ0Ikz~hWMtgBU13ZnTiSc-EAN+^jD=)ork@UNIqc;KY(FOve$_HIiJR{9x!X3a zH#|*6c9bqDso_0akHlN8R6uN8^{^H0m`9&1V0G;EW^|heHLk{n{Zj8I17Aw0U3G;@ z(FGRlx%L7Gy_5PkLT2vsNpDm2M&s+g8$|7LzJnT9Ru! zqrsn{F<}f!MHr(gD0WY4v-2cP>($a6q_+^-o-i*S`%j8#$K=_y_mlY7N3Zyp^OR2$ z7sA6Q#rjoL)r!Oy9MWOa;f&jvc_IfbG1h%a%eGur%I9>m*tx-F{80!SGz424i;NNY zuC$%f??c`?$o5z;-GvHzd4-fF7RdYa32otPw~6k&tTWN`y_wS5h(wQhpUtzG{mgwn zit_$<`u3ftzbZb*FJ9qKj-{scp^M~pAB6{>`9C;v*>n$S}0EE7{&d_p{c<+Q z3MOU%0S`(h^*=RQrhk)nrB6&Zb3IQ;_fVTc7tJo7eJ(y`-GnhDlUZk29&qG1w*Tb_ zLw@x$G)(d%3&tn9_c%5zSfA)_!`QgzwjpNYZdjZq2&w*KQ9*P51qY{jL=>>WikJnj z!T?+IH z|L%PKV4r|_C})5XiRb5bFXj+FQg&!dO7l19XS!2^3g_$c9)S@P#kV@4d)ZG1Bd}9f zCVn(cu=9NpkF#7wx7cw~*Ggr2;$MIkmb3k8p$$=*xcY8qvs9dW-=S`_?DFzQ4qVRD z%S++`#GI$?p#!82ygc=!T<}93ktxUd9*5BL#Dr=h zd1P?ZNPPRL-TE))p~gf}p@`m^jk!9@{e***oh;uW{^?bnF>>GcVU4#*@I&4}Z($Mp zA(AY07f}Qk40W~4dZw_(Iv4nD;1L=}{(nJpD=BHki=cpyC$5&2ho*oZAfkrUGjf`0 zx0FFekK;muIn>ZQBh)ayh<77WJ?zixzovuSrjsT`;7@l=z>R+H1cx2{j#=T?Pa_s@3uJ-ZvoJ3|%NHUwlG4t}NNivTql*MgEydJ;HRV~iFL(#$;hD3Q z*bd+_EWv*|ELSt_8H>iHl{zTl%posvrT(ZDDk?xL41iW#W?@>1NwUOJ75hf8D-y>a zVnSONxWSK*s|RYcD7y(B%qB{`%~08yy>|O2D#fMvTlz(lDH zoXAb>ag9}veyXs6FF<6FqZbTpGmOxbW540i!t*oJIj|UbI(Prwr}v#RD9Lv-*Ymh? zjK1efhHErwzN*Djz0yXXXg$QR10J9gM;UT*7Hd=>wQxy`et{=`l0U5Sxd08QUjarI zJ64h-5fWlN?><_16u!#VIYRv+4ljl~g8C{EMeO90SX_#;jfEXQtZa#g0A-8rz@%;z zom6b>l+)KPVDz7*3p1z7M*nA&IYit-wkMmBOia-0Q^EKgF&N#Vj``ClQnZ_>_6W;! zQVW7PSyfRwo)qD&_gjIEuw_Lg?vLnS(VMnXTU75+prw}K*+UqIL_xkDBPJ`^uP$VM z?PY@_UolL@B9^mZa0MD!7y!8B6pLY7lmJv~(#7GSHXMOJLz?hRU$9_q%C6$UPW59g zsuILbO=93l;ph$8NED~beo+))(LiQ#T|yalq?PK=6!NdqTaqnaj3ywXF#;>SB>}L~ zYgq-H1Q@a5LxMb`JP7!jtwZyAgrzPnKS17s3pDcm>yv+wN;Uu>RW2OQfQR&m$=q8! zfK=o>5K4<}C9G6qk*ZM^<|;BCXbj>yuS534f{2+i`cUBxsfI-f_LEd5hM`o%JBESMTQl{a| zXBLjLrA+LPIg0u%-)JOWijrJdOpVw-LJ*k;{ve!|?_+|9cg)KB8g|!s?5X3del+Lz zn%TEWw6EPq*Yg9?^O1~#k6%!^Pwq#LUk#3LrKwrc&>vM4wQ>pYfma zxk)5#)W&2D%a&{BjzEZ{WWroyV0dc9i2cM86f>b^wQ%nl;(*J5At=hTfhp&$gxzxq z8{iSB4)V+G?);YXRx4@<2#!u>-Z(g#XTj6oH;&=8l|B<46Bg@_Iua_shY%g z_fxVB=Oj|6se0gRhyosx48nvg26)J9z(ab2BGFmL-7dAVnoxAwx#OueDAfn!kcno} z#Lf_BSoB_>+ZW}#n1Etj;_dkD5Fq|SAx&eV#r9YLI>5l&H_$=H$^5#%h={WKe}2 zNb3mIiElT0K=F$7 z7#BXH97YTZi0I{VBxn*Uv&tr9kav+J(#0)w^Hn%cGc7}aeG7r1mnY@(uroe{zUP_?q&&h+3rlQrgGiOlA#V5W^ZzYq1CSab;uZr#YJBnc%VhJ*NX87xvqeRz*j{G2k{LFj$%l-fBBgD6RfiezsJ<$OSEoN z3UHyQ0L?s!O~yO5`QV$meoS_3%}o zdu-#5s1T--09Efq0XYryPpU8t0Gf5he;QhJK&(uB@uvAKlKzVpr09?ygX0^MEd#cs zrTD-2p759Nw2ypG_&495lYy9jspy72@?EaGi(Brd(6Oc{=I8tEUdvFADGHpb$aU=!}A&gVr^1lORPI7EHfP8CU29bbY9FG=^1a8H~=RBO#l_ zVIFMWIf>#dK#~)IW>yDiW)p#C76df27o{?&;@(po09{^y;8k!is2f<26eL-Za#?JP zj57eLq`kMKWX|Pu)7}{fWB6eX40J1pP?FQ&LGMf?dsQ`^$6<5MXL+3S57?Z)JheMJ8mTSw=QM)o!sqYIq=!7*z z04hzS;?2u5<&M=@XVDO#){NSlglt|%cvOV^-zlf~cgo9QDQ81!mHPjuJe&71<)vR> zDbMEpSIWnwdR1*{)@#`l)gvIPw%uLyi6yNNc}4D>?F7ks&6taNH$#JYQuepajq)Vc z2kkAd^#q$Q$LN&O*#+FjcK+)$-C5 zpUZpguyoHGjflG9%)Ko2OS_=&m9BYOFaLul?Cj3Zetzg|OSapdp0_@9!s)Hny&705 zQhp@ip;{PS7}#by`Vft-|3~?ngW*E4kpfvodP+U_<^y(>GZ`x=sf_7?qliZz(4aSw z;MCZJ(>wfH(rb>QTqX)+pl(wjYoMQgP?ppXMh6OrKZ#`wKnh{>A9usT=m<@0#8QV{ zlv}$%?Y`rf1~y`XzXQeFiwHelpJ!t@Sk!PvlJh?JyU0wfK^jo~0K;25lB+Qaa#H^?(m3JU7L!X~XcmTd2GhAVOB`H<) z#^cc*K-T^k1&2V4GvF3zOTE_qq{^LY_YWMk<$q1rhf%zLre~*$3v&|1SJ2wlS_5a+Xsna*s1toqe47 z9We7ih+p(iqhjklV!0y?ANJLA+ss!NZrj#hPW{}MCo66X%@}K3$;hmyH~8ZH zI>$@wqc2aXSD$KKtK3r#Fh4nn)q09(`xdWDMW?yo&%2saJ?p8CJ?U}GwHK9quT3VGGB%=%_jGrU;GDSMTZY%|s#`THs?OEs z8?hwJ0(z)YXECUR6-s#8xE|H1xmWT1Ou>-(xmU@H6}Ts^>+LLw`_1X^{2w?h{u2kg z0l#`{kqm81zn6);k9_JA00Exh`)J3UzfmtG=LMjk7z|WZTpurQ!feG4B)0nJ09qvh5SgJ4}U!HUoYJg!NeISJ;3` zkB9G8)gQbIV^Jjt$6@N{b2q?7CNeop#e46%Y&Wh{_&PCFWhKyB|xB-25xkrBujf7$AR< z-2c-P%uD{u6F3lJQ1_`S&rhhr)>VN?9oQCdBJ#@L+SBk@dshC|o)=%gNzS`4_2|G^mzu$UcFYeC(A_*(2aUO8MWx?pyAJ4!9c{>pHT*3yswO25bZ$A{S&pXZq`7<=( ze}5KYTnsnY!8=0Phg^-&^=hOtJLF6Dg12;pl|yEWO_@?Csa0Q&b9T1?>q>=sSaU3% zoBq51jFuj#R)49r1Nuv?9R&w103t7ws#EKvv`2_Ch;_oknzdmNO);iILK>KLR@hRQ z%!{A9DJ&$JZJYP#3lUQO8hrU^)y_2jt?`q=1!* zM0lV$t!bNY$GSX*st#Ko{t405V$1hMbnRKHeK|-2bEy4Wipp}p_%wvWjL!;NUfg$8 z5liE$@iX!>mje}OtMrw!H*Q?=1p|c+%iZL90bn+Tj0&X^a~G)-fvS4$5@yD@A|#i1 zAyd$=Q_>=>b^+13)&c(I9Vd^|KO9@aza1N&?+q9q9A&WwIJQcdV-w2d3SdEMm1ac* zyk;LzQE7MSw29rLiZ%dz4sc-jv`C+{f&*ItUiEm!%N?l1F6LP?|4`i)0?v?wAQydG zCSOklE9SBF_zTzyBBw^-t+cR3v+g75q~BR?OPBp z$bSvuB<>U?Lw;zKuuO2Gf?U)GRo(8-PneF$f6e}8DKGmQ)Nf#!SjAB zg(1-*{fNXx2yCHV%zH%QR3|l|za6u3bHVCF-3I-_{sE9*5%>cL$!+#90LiwZsv{r;h*8cr*4 z;v`yBRVfxLi8E)Sh}{p6&!zBRn^LvxSqk>mAqkZ4I9?}#yd8z>iOPGnFW&nb>)zK za>-04A{<--CLA0t92}gx4ZE|2sjcbXUpZly4Gn7jw439=ZYA7$i`v9zutMe#FkSph zJRHF#JQH|h;Ca|{83D`twyqq4(b!!x#FaP+Axw%*jHMAmEnlvU1+|xB>Fjskb(Ss| zu#P#_k47KPoK7q^JXLYXpC>vsol+E^RXCQo`a>%q|z|e=-J)~_veW2v=Lbmb1Ay#zSR;)Po-W30wJ8)W0RtTG;YC_bK zgk%weM=Z>}-mJ5k-e&vaX!C-N-NQr$A=zq`_mbIxma>H;Gb|XcV74L99hFiPuGyke zXm${}G|kcWnF;w^)zqDX@7hZFXZPhQ+Me5NR` znA!~ul#c$cq@;We9ji?}{OVX^DKENVw(N-q zf$vcxghbd*Q0E!a(ur=cVDNE->?|LZDrv`b7&Ar%h9iCF&+MBxP^X>ygcscbUx7Wq z<;>DbmGn{Bf#@!Pyj$wU`AoeakGTiONboEJWvJDU-+Jn+l&M@>KfjTFdNTg|7p4(U ze3)P64c_xfBeu{J%;#fPhfki)&y;>mcKe#VeVCx05az<7h`*#{^itNdd z-;jUcoM%O#9rX8&ticm2A)&&J`^ZDKimX#obf}%m>fL(RL`)=&C2AM=lBlzpmJj6} z*nUmKS<8f2l1I7j&m`)(WVivh(W6Gtsv0eY;1a+(q9p6{-PRZ-)P~z z;k=7dy;Up808d)xc0<^H>Vny|tHPqu1dmE^LX};M=g%Lz8wpdQIj*juN%cPAx;4q- z3fy*cU(f$IjziAF2oacZChe zNB3P+9xt9x<@kf2I}{-$8bhVeiu*-=LY)RAMb6u$gJzOAB!U}Mx8r+I<-e>aL;12s ztr+~2=qCMOJ_;jFNk^hqYfv?|yTZ~zYIj&Vu#wxu)KT7*hb-@E6^!-lB1y%R_7EsZs4R~*L&oRyCQiBe5wL`cQjcq)1J zsp8aPG?Pwft9|xjG-7||%oa}KEWW(f!Irz!938Fgqwv-F@l^a7nliVwpBHOQP+6sE znF*D2)TKnXxoqmETf~u9u^cqQ!a=)4k^Z+~&z0LEV@*lSe3i~4^kpsIbKJ^(x;ova zkvGb;@~IBxC&IO1gpm1$#~oDBXMVTfv=xx`wWti~41ti0g=UR>vLv-ZDT$-z4Erd& zilb8fUP7MxNqG7%9khaEuUN4VDzSS0-}gwdeAq;_*d-YGK^|68s_;J(pJ`nPs@+$p zFCse|=+=5((e^O2I2x*#To4GHu2t4zLaYmy=RS?In!vl=H%v|Df{^t@yiAdp^Txy7(suJ;y2-DzYCOj0Tnc!rW~UcA}+o`WjcKhebqK zUyuoHMbE7cpJ6pzdHi;K*HtbPu)w&PJX<>Z5m38lGk)jMi=l2u_cB~_Lo9rWZOLj`mKE93igL@I*B4T)s_xptzlAyG|J;!t z-{H!eLa*t`I@(D?dg@zTs?dLy%PWbw)&)m>=l!f3r5b*Uhi;%zmX3(^@Xf1eGwTayv zx`H{W?#8WS71k>CPSJHU9nO;xcgt|X`HTE}Kjfkd3;hu#>Mwq4^bW3~@2Yl(1mNOZqdRK-8<&3lBezyB%oU_BTsSD|MJNGxA z?Blbu75B1iTKs` z6(ni~0}}rpwHdC6&uQ<6bbF&$Y)jG#oa*7+!(4YRA%f>C;rfZhvcj{W4*J!mXJK1i zG|JKfKg%3*=bXmm@Wia8USZCnn60z<*sGQ-=7zR4!ISZjaxJ=MH_>K0EH~3mA>;6-#FG#;>WuN)JuTh38*fSAs`bku{N_kr zqM8A_?C|JqgQ|yeg5S2`OQClMKf|b_B9^0N_(Nyk1kYwLSguHBl|Ha7E~@o36Of4U zhbpCu!VgiFD%P$w(h}OQtb?Z_pP2;01zU(;4eaNXYE1#39k-$Scxp6BvG(eB>?hzS zhCT04tr>W)z8>ABb^@+2?VOr-(@~}N}=X` z`=sJc!gcp(+y49J=RaQ-$WO@N;5b^~;PC!YLoGfynwqFNJ6hVAKbF#TeQSG?-q<^G z%7+i{5&bbtDtW|({*cTO;?dGen8@W=^d1|DTG-AKP^syv$a%p(T<%ruZ&y@kDea?> z7`0w=ZjL)o@dQKf&&~!kPBwR3oxrU=_t|&7=YeLmKE8Lq9q+cU0;j^09?sT8YZ{xi zeH$8@3@S6vv?=?mBgh|SlcAgvUIY_^r8q}c5h`gR0)WFV=J>I;zu%MI&lAdAQO9IcR zFLZ_c9zeA0$nt%AKL!_gIdRfpsf;f-Ol%0#BXy~%jOPajGbdV{YKsEOF=0so`3b>O z(#DnrKk98hg-}&td8|0^J`KI| z)46gdJ9y^=@7&;>_gtC1&~I^8r&6H2bIQ-&w#9X2bT_r4Q~s2{%5D|X@#*|x`spM{ zznMAh;31ZNLZi{h)5>~yRW@hztjqh(@cP`T!zz8p;>OD7=BRn``N2e65ua0xiiT3Y z=84>UfY8@BeVgCsjxCKYY0#qO%4|U*Ij7Fkxx;SFzf;3stHrXtWj{id zBRVJnFR8hBbqTj>RqGjDRJ*DYx2e&7<-+IkdFwE|s^C%w@kotudvdwgrBS2x-lXD|imwYphQ<3m`5pHdt+BBr+D!83GiL zTk~+V(MO~80GfS7mkE$vS)){OrUZr|<7V0{L==jD7z9KAMjFULX{JXC)L z;E`m6i}*F|XKdy1Y}_7lZmcYYHnDF4DZ6#Esz?_iu`60++I#SfZ-0bUCmPhrK%KqM zYwqmO_O)f;XsRr~d_H|hlt0WPV(46Xtk-EN9Rmpvs+{;VXs*)xJ90p8nlX8^&3*=t z0e&6__ME9d7SqBCxpgbRk0zA}UOF^&I$uOw{R+4xyfR$h;vbf(5CEp-gJ3>m|AdsHRg=`J5uFNWidhhQ&B;5E+uM+HTfQ&zYEOtvcl{Eo{!s6ql~iWeAp-pARIfP< zHi!&WpAb>*`gOrcko-_!27>ct=o+@WZAD!QZp=tft+>w;w)Y(Q_Tzz}BK`|gbu2jy zm_?>7F#@yIHL*-!_O@Dj=>tap`sK&LJluW(I!vSH@LjU1TA}T%(!;TYkxim5a8SRQ zH4P5ZH;I0MgTT$KM{r=XNrZYdmhgEqivk?*ZW3`HjVYAQ-_ zm9rVl%{k8D3R)jYS|b)WxRy7-ENJ1`p5h2O!zhG0aq;-*JxGv@=G|N)tGf%_`!7d7 zg`Zp1#nSr%^z{{l(GfR#1Q0#^Yc$!GUl7Vv^zB+ZLlS6`J&W%ih6hdjCV1^1A>Ha) zpDw*F*Oy<6tF(Ts4!F^@FHL_U`gQ(xL}GX^Pj!z>Yi>V};&O86^36uVejWi6(HsjQ zA!O=^?B!R&(eFMkHvHVC{JEyS{M;-=8N5W_#Xb33-&`8nN^hL+SKkXp7Z~u1+whAI z`G^ib_(Tr)MDE;wxgs6!xA^X(p-t!Uo5zNKf{ZIUnt+{%=dVo1G4~6=eW;59ULqc- zy`CkeZn85&@Yy7~eU5AI7yi=8IBBH6l9$KLa9VGd-k)97GFRE^fm0_A!@l?vB0%jw1KV26KadsTWhjI(iykhXO|3LHtU9W z{utv?ikcSPEqpw}rVThq_lqP}GGh+p)o8{L481|-bTdMDP%$)>{Em@t7BG^sIr|`7 z!jBa3jUo7#-wQ6kd1p(DVhd|fU-6}$;LDWS63XWNhcDBWvAk_sCu3Ai(htYMJL6iA z1g~+zZErYFK1$W&y)xo|7|s)zjry{UKT!eGb`bJy@8!V>1gZ|)EDqAhl|kFKzmDfF zZl+Ek)U#HkxZH)0CY|m*U0v&1U5SdQ1laBUZ3>Ut@~$75d4@N#Oz-HpOPLHzST~e7 zN$)n5cvCxEU{44+9Ks==twWz{^p|>#gF1$N4(Gl~2!Pi1C$EO4ytw%JqvVNJ zH`|$@Q{zC~vTY|(S}h`9#3Y>cbH&y%r`XKqo7R?l$NR+B3C`g5E{L<*Jo0mTP3fk5A=biXb$ZmG<4dG0!F{nJNfzj ze6@Hx+grL?Tf1m{E-*>I)8gk;6!0KZJXnd*3O`)FKN#ooA5Vfg7*ApW?=S}~=sKwG zd!OR?UE*U}g=3TPdEn&3@{#$*s4W@g!!mxm%4U=#GSA(2#5X!;j^lSLop74k7pFc@ zy2L$r!s8Gv^->8wQREfU3g#3nQP|Z4QQTF*nc!4c5M1rtZAP`)xJjJa zU52pFd}2f2zMX^a3WwMPsent8gO_OY8E$w4s+nZseThWR0+Cq+<5iCOa^E2y!kw}} zsI{L@4YJ>y6%oRn6PPG$3P4 zhxgoE8G)BCJBA!-CvN_+>!^<=0{SwcD|}1PiaK%8EiWzmq~7QK<9mf51dn#SIFbPq zR+(Ymq zc9gd6!#6?R=5S2H{&Ipxoh|^xnl; zlw$|HS!bHL5dOWb9jvAI&d+BWrKM;uXQRIfv7sI1aR?xiTpAC%g%LAuaVB^neEfbG zzL=)bS8!2En-L;4{OMaN_IC_h;zQ3(U3x}NmdW-FL;YpZU!Ei*!5x5Cotl+-KV0hm zT#$ZmOhFY{5&u1dnCy5n5`|kD>%BKQNq!}Bo6}2-7b_is;IhpvO8!GG{uLeeTX1_f zh5XHe^)B1olNj9KYv>^K`nDjh#E?Q+C+**Cp+rP;z4OMNM*vF8naVW~Ls?e{J^RAjekxfq0e%+6x?1c>G(he;p1A=*7K$vq&O81Y9{% zdJ*=MU=gt%7#F>#r}DK6j3s2N0up}tCdDW=j53@L%M*7M_x^zDf9iPl30FnWuE8I7 zg(BdHMtWEM6elbEV!}Z_i*G8srv!uG^Ml2zC3CL?frRmws)G%0~pmZ&Xt zBUgey^C{cnSI50zn}^oa5(iTr?SQMzli*b z!=mZwi{sFwnSt(*)|nt(3bx?3tn-yxoPiIjUa68+_n0h}R-Z6xg>eQ}3W*)y=9B80 z!U~){XIOMnCh@4FO&)+4FbIs)eA~nrtz6_PNL$TPL?iRXTt-=@p(fcpLtW&wMCa*P zmjzwq2uXG0*rzZ758B^g0{J~!bM3N`lPgU(d{QL8z1M}p7tX4e#9_~@9F)$X{iWI( zfHlb`I(?9OBGX!^NA0rfr`npis}50?FUFqSx}ZwV#Gd`Bj~h6W$f}dZu9%ASMUkDT z7rk}Z29)`(qYRjS1*Mc>MQ(+PC+b~_vjI?sILAVNQzLZn#R{e#pbQ1(-qwU!28=E= z1t+EP2txyA+;tsGP4{xy)=rZS>xAO;R}>$p{YL6FXB%XLQuj)yeCQ= z6R_ZQ>K!^|^MwFw5Fry(^vb~iDz{o?YDBMuk!-O~NRuv*=AhWt672VuE&2(Sn^X{= zJ7L%;ZCp@r@Lc0-mFS$*9KS9SK~Lo}pz-e+dzn@xYp%O2#^KsK_k=b}Qah5Dp}GPm zZiIG5`ANO&a3`_hPTWww)KMZCnYejrSAeuT5W$vGTd}shAI`X$M1S%^ zhn0^9r~O3I+oydZysbN9^f9qd(V@BLjBS=1wwUL%J{>;}T-@ATBG+}Yw0QOC^gA=< z1e;o&*130-RzV-|JodlgW1_~3UFUyXZx?9|Todn3@2KpusImMqJ;oAM6e-3sKIXI% z4G=d=Jdd47*+YH0{((I#Y21UH0sSh zBF(|NGuIEA)TNQ-7zrf9fV{3k+}c=H5iF;?+E_9%HD!wdC)m9B^j)nPC#>*~WVB+Y1Hwvd zCKTqubUWoF)>WcvL=hVX(WJBzW{DKFQxl#)Bg-9X4hNld$)vy)P6SIU zLJ?d!EZ~3hgXu6-Mbw^9y@QM@B$-JK`y#sY!2#clh2P1lk_K z2%KHyB~00teQvd#kzU>U4w1xjhS5J#S|F8|C^LN+I4?698;B{ZWKdv~3V9hz^S*pe zHjW1>1a^h$sRuyFqIo9vSx!sn{POkY4Q?x`8QhCYTOgr^bIjk-%fZf$?6YllGj7h&Ta5OiXv;b=c+Tzy!q!D#XMWf5bcM{7-4T>*6-h_QS(WO4@-i1Zpk;KXJy?C$5jcdK6;aaO9`^=}ID5g^t(|R`54{4-^ zJ-ak(m22+M^(kuRTICZYvD$)!v033;YiY}MHb4z~eIsM%R@e8X^|I5ptVEV-vzc4% zw(n;%xO1fxe*0xcqtqAsl$#u?fzI4qO#Mq=xc%MsHOkZFmE98yV;!TF3C;ZYN1G}+6^xOE{zPS?5Ss2(zjXOoD`5Z9=~?zb@9 zBG^!Yf<-(U^G_XGd^39qzkDbIrxeU7k1lM?*5B-!P+pd1*1Hk@u0R7s&~F+&7pj~~ ze||^iP?NB3mz~^J61CnWy-NCNc=TJ)-Gd4?6nIU=58uTs+INglXjULi2YZQYk7XDF zI{L&E6Lkp&kJujYmtg3-sY`cY_7^MJAbr@2?GrOmb^(xl z_w8qQLe+6$IJ|~l7aSB*r&rP!k15B&&Vk~_R(k3dBlA)}}@ecQE z#E>-%rgMMq-8DJW@2)7}N>Mw)+aMeg1|&a3$90oIv0u@5+&|VjcSsi^1em9mlXTvC z10u5NT0V%r#}?9bVh)W5kv?3E=Y4u~7?0S780+QV>w01gy}AjE;4=9kHuI|7RKMBn zJRvbKVk6gCsjBM^Mw&sZ>RDzkGGgLQMuh*RtA8cI9a>0VFKP?p9^=ylD3>-fMjtX@ zVF_22#a)G<%Qe1L%px%j7XH4Iv-`I9%J91{DlX%z4mW>vpaaE57*si;##3N_8wl5T zLOpH(YxNMdZ-h_#n=Xp%h2Sir=829cEOFZ*9F*j!I{ztgrPYwwABA9+<Jnq!pi(k7zY9+Nz%5nfAbwnK@#Rhd@G931&_(D-&6X4S``)p0Tlyrido%RaK#p&5 zUaSNEb?t5D`a!I4C^}94nA{@erj2TOM=;T%;f1(K+ODL&y~V$2~DN=&$8VivWp{ci#GKkt9@&7o@r$FKd5_doW(5W412 zt*Pcv*@sR^ows!Zz0dYR5f4Dm*Ukqk5fSmrh40_sDd@EBz7`kwc9LMKzS`qgR`#p8 zv4;M#f#b=eQausSTGXkQ_lw-VKxsR_(7J&lI`wf-rLGeYh| zlM6gAUgr><>wf+f04{T+^`XXd-F^_zRk3oP_mqvACRItHSy_?aVj)m$$ZFa^Zr+fP zk9h*iW>Z*^xKq&>+noCp6U=jo<0-+C^s<%*D(E?WE0>S2$ zVBp6L;!SiggDK2SS}5Y1`+yU)J^IV-rVp z-*z`?uS?Vv^Lmw0J|L1s8v?SH09jLg3f2JFXsd1WqUqh8JM|}SF({CcXI@=T$@9{B zw#2tk!anL;F}sB&wYS^o-XF|Es2-RM(#>6z zU0qv^5|EMX?C{k?u>tZqWFJ)NX%o)BJ%_Ma99}pp;@xO9um9TJ6Sthn3}pcGwM5;+Bh@* zVg5{^V|e8Qqkn{VGhv9`LOqLkc*o5JA&97OkT$FCLm53R!7L}m++sX=*WsIf-`#Z> z-(^n&@s{A3Apz-TS|NjWjIk}Me|s;{cL~*S9KHpcGe(0e`L}*MQi`#TO%?Blnw3YhR?dg|;KZmp5?#*;FI+pLFQm{}lxO zd?oqc5wPlELJ>U+di=KFP0kad7*3%tO)^jU1Rf}(L`|%`n3=!9MxmI#-!`7 ziG3XrWK0TQVJAou^hq?8&L@Mvu_{}G7tv2D5UX-vqHR>>HY_4ZYm3WFZC2RE5NpuB z&mr0Ix?DxP)I`?wTG=>7_GWWg!NN_hj$^k9Y9&L300w@SsXkkNUMDH5ZJM+1%NfmM z`6~p26tM%V69l({)%bVdRx;>vl zrix7Srd=$*S?w;V>3{mkN|8j=y#EpeZ2uC1`2WWtFuD9h`d@;8{a->b@&7mkvRWU#{v87H z|K(`-F9(AnSe5Wy9ckj%!9ew|!GMG08T9Mld&1~Bv%+CiiU>J8tnOFgiyHV(8h5Rk zH}=^Y_^x*0fmm23oQ-Wsd+1bD1wV}?%fo{fx~XH={^|++fuALbE|2qn@+R**M&nJi ztEt*v*u&P-7IC{{U9|9gX=Ny(dpUa@5B)^_(||kCaB)t=KYWCMPB9TnyKi~}=Cm6} z8=n7+hlie^xBuB-U@d?Q>iM_v@PCZ~>%VLVA&qZ`TLJ|uZ6Ds0wkL`mCrsGMT;9&s zum=%_^tT%>P2cjCFw)_pYc3qYV8kl;<{NB2xh-~lF>;(~qe0d3Anqwywp&t9PoF`H zX09v6GJ?;OfS$3PCT7y({z2SG4&V*J8TNqx> z&CJ12QsweO16moRb=p`{_}{K$0P7X83qF4 z7a9Zv)n5(40X%8S#nef~)Wzj>_7vm)#4|G(S=xmgh8j{EP#X=H3>Z@zPM8iD7DI$L zGw(oYatYR^lb}f^LYhKulp^4K_<;YFlu|Gi7$mfb1Qm_)@&aQ<2_qh?u5*u1Bbb^& z5)cOb3Ma|(Ms*T~2@(LEhD0uC<6>a3fp!IY+SbS9ALkTwQuaYWz;xaV&SLPk>AO_- zdD=rv+8@1IzG=!izWMB@PL;D$`6UZFTCa13u`+wHL#p?su?k@uYA#^xhH)Ne-sHDO za&wKwG0;^zb68Q&a4`4zr>gfJGxj6&Q#xMq6TXmYVotOp}gnRzu+{i}X6A3>Ga6K@af;;`Pe&Alit0ZL`xs zZKkek`tdV=M*nn8*Uu&*KNyFLgD>C2aqsSZ3R>lNy45Y(Mz$aR84(i6STtV#%%koI zo(*F0GG14AXs$m8Qa&S^yPGXFAk&ZEGmo>_4~$6>yB%dadhUF(BidW~oqzu&p*^P-JBvYbB~{+t7?hVgEvR;^-pc_6(+yL73u%0tHR^re4WjSqF%9S{A> z{ST_KGWWKd-Bmr4^P>axlN7Az^c2!~<0u)s8l!VVO%{r%v+MM$rY2;))7{fsc(dJi zr)}Bz#XAi*ThTGi#F-rJnY>kF2lA#*Adl;*8M5{v@H;ae@PsA|*zGzN7n>$x!Poq% zdpfYU-_jUdZ}j13HW7^wR_Py^rOI{|@H14@)qK5wp9XdQxYWn;Rf(_Sf|+Sj^JH{$ zc{z0_Wyo$iJRL1a^J9>F$uB;0n)KzX8&C6(t$?S^7?)qapO}|6$eCQlIqhEInO`2h z9gps+zZN4iuj%`-?thHnDiSdC=yfB%oTS|8Vwm^hY+ngk`Fz%jr%P)bDc~#R{IE^( z+v>C|a}}{c9ef1I_7XSUDCc*2Q)vu(K{Xn6geBc9!Io!U+Ze~f!v%lYQGpP6>J z8M??C21Cwzj$=U?@1pj*-I>#YRVD%Wiwn)Zp1yLL`k&{nj~mRS9%Iqfx%hP_p^iQXb`0FQUU=e2g-cuIWA=s8kF>0}# zLbOCSqnp}R^SE(&cqDSimd?;QPO5oC>ap^V&|d4sspP+3lCJBN)N7&RFx&!EIxCP- zu&CE$fUY_-g_?Am)6Ifri+|*iFyTV}{|E9Qh+6|2#x!k zN9FzqdKU9uRsOkEtx6Q&ZeE*Pt36JL|2jD#iISz;?8mB|c{4~Is}Q_-0RXDjP|HgI745>*woM7&R&Q+#Vm%4%~&Tpx+0ToGmPP`^>zu#a%At^z%gPf}CuqISW4 zSFON*a@;gMgWSpb49h<`t36v?kUY;*XrdMbM}assS0i4b9f85WzwY=uWABQA!u8Br zeGaE+hk@ z6mvy-qpp{@GU#E8B|OBhlVA_>D=HQw*yj8nF-xp}o29?a(%)w3Z?p8bS^C>7{ogW6 zk}?#~GXE`a>C>xOI!@H&obkozf0@?kQ%e-W$*V!Psx`%_H7^B{8;^FHA%~GHhpGWg zVk&AFb5hwUjpKEJ(%*zWST9bI_VTPn+-`MvGq!r|>-da&j&Y6OZe2cRt~;l{F(<}& z2mAQdfEZE{3i7LkT0i7FL)EWze8`;DpJLf+p3RSlAt3t7qbO;=aYFoj_noobn)VF> zq~Ld6`*%Mh5?bDX2#5_}W!$S9pJl&jH2SyInY2B-pL6TqI$a5l=XLo00N95o&{2i5+yoa7HZ(AIMr!Z5bPL7@V_2lKetMc( zBK}pHmAI=dfs{d6lB)6^?m;eAinNT)EAZJws@>-s^_@f-O@73>p`iY>2joksRH+}_ z(~TT_%TFdf^1?$hQIik!r~$CUb0uGbzL$+EOFzwQkem1w z50@PbaW&A%-Yk+5@_8=tK*QC#9#&+i6hWC`Q*odPC|IyAscck32ssL{IEiB{7aMH% zyu)tJLNB@{{~B_es!69=c*e?HO(C_^cZ!=lPR3FwAk%o(hT~E`b%zoyMAt)2ZW_JU zx3?0VS?Xrt`>VauxEs-0xHX=YLyWHjND|w^i!M(qeMRqG@$9R&j$zJJT6@- zV(L~#9Me{j`k-8OvGzR-_KcIRHomLhR30I!*Io`wgvBACjds_b?GqgnIX3P$0Q zoGsItH)e=t(Vm4D`Mt>$GIVfzevq7YZ}v%PFd|h7N)lQPYqTyyiMCMC!DfG_`mZYK zL~CPiN^NZ)JzkPsYTqe3_YE_M?CXM@ZZ958Q==*6r7!n3{itPb3U}w;T9CcNXpS@T zdYwl_%&AF1wRZA_OB820zA-9sHyJ^3kESdN&FuXEQbq%u4s`30P47KJ>(#Aw%IQFl z6~f>E^M_JsAQkI7=2mK=@T{ZC0I~gFp~G*)>o#eW4<_PNJKUuV8w4_Y;3mwgiyF7A zISvU|v3m5LF!>Ax5osA4s`-?km~m`#YRY#7;1el5lfvngB| z*wWSVn15B;wFtQ4N57{h{-`BOZAvATPaCcW`;m?YjW6nI9}4#fr!(qChFs5NFPQOD zlC^pMk;_N7F@$-{O$N*oZnPKlknk5*ss()Kbc-QYZZf}n$S@Q_={CPBs;^%ew^;(o z5=vT&Srzm`nR~c-IzL~Q58z4!E<8j!_@YT2#(nTxsrQoBw&T^s?VtVNnWdiS<0t`m z$3POQ9-CXs8&$~DV;+^rU2xDYPtF_jlLE`1U;r%*CvkB4h}kF9In9^3B(@^$jeP7QKU zOP|IHs&vG>ALTo)VLB|9G%zj27l)?Glyh6(CMH2g{d~BbDI66`P1_YvX#4s?k9I)odeBXd5G?&#WnHe zFmvtpvr=VMAS_A*$-$?mZrbO}sg0S3C@wJsYP@pJR^+JarQ6LwLs+egMY*STKgClJ zgEax%r5bc(E9Z#F8+bK+>o*@!CcfaA0^S*+n=|s~*{qb&8J(u9QfQh@TZ&K3n7AwA zZ?8Dzm`}0^73(_z5`q%+HxnLljj#tDOEVF z<2J30AF<~SK6xi^&QJhiJBW_*ZjPK-R;aC7BYUbsFA!UQ3~2n?+*5TXK)N|HMmGTe z?y^wt;Q!CKNo;?+Nq@UZf4fP4yGeh$Nq@UZ|F_(v3+?d^#s8L@#Qtw?5-)}q*iABa zsxU6eF-0)Oqli3~Q8I=zwH#s}j4ZI03av>ves3xVEJ#Tmk(?8T!wgT&m89uQB=M#k z%IKTTIPLLmw!h6O;@RK4707ZP+rRz&ls^9A%=-oQ9kd}a#9Jt|iMK+;sp>T_B<*ye zMM~c@ics65rUg{mARs^qJqHW%xcCj5F{Iv5N{xPF*oF% zQosDRd2!nx9DiJ|ky%EgI^Clc^0+FzG*=LZ{PHVSc^+Fm7~$v3iq1BNpR05MPbj>m z#Y#yGFh90|%(7Nw{)b@)=0fX!8SXNkyd;!@B8n|5_yxZF)3$T@gY!FeqY|V*E`BoA z*zH^Pvs_;I0-zq-s`y%lFqh;UW5YuJ7T1##(p0)BoQT)LsQd>#A_Je0?2oFmQLte> z%M5XIiQ0*W_LJ|>RdYnu0r%diwGCrP{=R)b>aks%|#hk<^F`SX8 zmBy{{wuiM|(UfPzHfJSP)Nw~thq4hawlwRMzldb{*`#hPP;+kb?g3l~Q~6#<6u%4& z?DN-~x&yagY*euol@<&LsGWE%oJXf7ri#_sx54 zTYS^X`?Gr|B4u3<8iIpSa*kD51xRfATk4Q3h|RdxhapF^h&1skbYv~!_dqU3!XRKD zeJ)Wb*>fmht#M0?t3kJz z)ya$|b*-QuTsWW`ro zijpKnPG)+@85#vWdxPVHFXO;#yky}r?5z0kZRsZpg+<#Imvo(t9$w(RaZ>US7_NS> zHJiMc!I6(8q+u?)mDhi;8qYalTImL&r!6G#NM%sqM)qSe7)LyPuzheRYtOjCFKvIb zEX^fa0A7@(H~!2nM7g1Uv|I*la$}fjO#2Smr(|Sf zxt-C`UlPbP_Nh+NTDzRy$cd}zj1_WY-oNl%`6!i~UfxV9PTHuCa+iHT&S0eFJWd77 zKyF>AiF}t6nst}AG-|$Q0$N}jI%)sT9J=X9F=1-@(U8bcEg)**{$cEULm3mNZPFmBS18ucnkVorwk<&N>B?acI6|>I&S&R79wzH{u70 z7+Yx{2_u%z6g7Uf!VxKAJ7m?Okf?qCw;P-B*ke10WHdEg#fS`}mc8&Q; zUAAx51-R(l&wCFW&R;jO%^XO2*&z9%mn&!Tg|Ls8fqPiv0@|kP)LQEv{%d{mtW-mD z-0qxvx)@d@BGLGmsozmtk4#rf4A9I83$hIRLe;Vzm5|I@_cPGL9RR2ilh%Hz9S^r3 zq5A%h-|wt!X4 z-p1F(db7`l5eDv7NVX$M;;C@%&9m9{ephkn&~C$nbv>IhCPdPO7%KuP0eJv4DY$pj z#@r={hT!E%_w+!t3u5cr70zk_L6MTn);Cq}+pEhpsE!r)iaikaMcVMXBVF}w3%fmR z^Al?}m}*p~Jr>%F6dT4kH9!a}kCWK6d5Djz+vpqM-@o*g{`*FW<8Pz%w^91rDE)1e z{x(W~8>Rm{M(H{w+_q30{MTOH8weEeObGDukH&^J#v&GmmUgd`4qY!Y8lz=b&C?EQdhS-8p5 zs!rES)5~R3m)~WV|8swp|2>G&|L$g2f6W&(I^Okoe&+u$%=mI1V*j$=wf=H)*|h%n zFrMXiKds>Z1Y#6;*<5}BT~@6>FLyo9zg&O>p0DNw{O&Im{O@mKVuWfmqN#kx?uD5~p2cx9dRA*}#+g4*1QZ7lM|TKhXj}kiyP0 zddrLG=_{Fb8NA|8dYd)yMCJ6t*Yc9N0#>Dq>K3fc+2GS{+IH-}MPzZbH4+8s_s)j! zc6Wu-B9ds%qrQDj9em}7_@f*|dcj3s2??beaK`Xja0#V&U;NGBaIzJtS0XC+_*InY zpTeNm!i)W=cEz0C8KPj~w0Ja_;?^+`B=|@Az`vK=c@+tK&EA`U4nA$O)7CqV&-k12 zTSH;sGw5*r4=4L`4vrafr1>{=~NeHj%SqTEM3ycRcTFJLBp#Te`V6z@S&ZyN72Jv)0)i7ULPa+0p7A zU!$4(B_U(lt;b?}|L`84TO-F7mCDQT*n{|6Rfn|Og%2A^?{a;P``&hmet3-t6)fFg ze+X6lb2J!o#8Y{!t?6Y%RY<78^A!~ZXK}@3R{dc+rz)xn-89+XN8KfAuxrd=hGXwI z8PP)B7LnUV-4YSd_N!M1V_A%GFL#2$iy2$Y?KQDF;-ZzhGNSAxfohdjp;bN8rAk0B zu8Q%@VG0pfK2)d&j@e>jH`~x05m#;JKLksAd>&IBQ<5t#5NDyA^R*oZ5NoJCJnz$2 zfovMZ{W5RYf?$3i;=kp!Q2d!KWEh<^Kyb(UD+}o#G2dW%k-$QlgJJD130F{~vF*}@ zz9qxjf|&}aCQszkr?1QHunMuS$MJ%G_~CQPUP|i#x4)J6$7ei5>_|<>+-K}us@8Q4G_RdykB0E2rXWdkO%%Goqks$ z;_V{h-6g7rM%IdiMec`vI)?2yhxNUI;Vkd7Ip!eYZ|)%rL~0}fYh4C4nSyaVH?1;rm+oRUR&4#(5z`}0Z7&sHUT(m z8k+#rwS^4;+?vJ);LX~i{#{FS#`Wrlb-?ISi%T8(hTeAHZ@c5!zGJ&`OtXDUg*gr$ ztV@TkfRn4MbyHU|K3}Q>M|m^_dEwDrvxd|E?uImN6!5<;gS2hW_|s~2^mWq}k7dU` zy5{(=Zy-Fo3^Yoi86A5&|5HCZzZq?Nx8jv!#TK$a=0wsdM>HJskfBkegfxPW96X=x z{z_ZSajFy9HT#bV1e-D_Rk0$38&y;5q>{c7#3%Ft@lEfhR!IX7BS|mKFct;#LUr@L ztWKmFes}ma!eqepsgWs%Deud^Vv^x^XX;_57{}rvrWhxDx!|wq+Xh<6oJo<8T>T{` z9|pL_$a@6G97%CtoT4r*47WI0-tXXt01b)ve@`MpafLM5gY#^`fb(ny)5&^}h<{D* zfn`Q$BJx0j{VD!+-$4KYDzoQaBl$O9BxGjKB@==NQdbX?2HvLY2N-KIpQs?Xq#kN8 z>+s61AifH+`2gdDq~606 zs3lJFc;CA-{+L?imsRk@gn1a5bBW%bT*r}xDJZTjJ4NY%TTJjmzRm6ST zn|h2dK&o}3`@*irU^x-o9>4-+VH})q2*V|93Nz7%Aa%t0lk1c<#?3VPZFGNV=@0_T zhsviQDCF8Ca5@aKR1X4+@vdifg&iUXiXrCkwCVn^k5tbz2PLJ^9E->n6V%AyArcKM zzU;^)MS8#mR@!W{!-ioUE}6H62WMrUgZ_Ku*Qkt;0g}5*N$m`V%6^BM$Af&`Mbw@I ze9b799y0<4{JZt?76+7J9ttE@gWU@Lbe0}Rw%}#0HAq^Qfz4)IGV9M~-`^9k;;S2z z4-6x`3XJL5!;g$qPr+>7mwEdJx=Awxem;v37&I=pl#n5}8Id-+TI$B_OmtIJFK3 z_Q6rKE`LQ8>;8!{=0VQaWsI2f40RGuF|4D+Mq;&@GuhdgFRxmh?DIt}3GarQJ4oJa zrp#kdG+QVi4C>JaXCT)a(#D@RnaOyMtPz(N>dH$(_M~FAkRAgc(zLK}RGga7#JO}N z`5BY2T7F#*tMU?MkumFQebX`Vj#nsuHy9;327C{&xPjFQO;}`!GiEOgc(5qr;O*4N zNTZZD)=nc1^-Gg48fFU`Cqduv+4)U&L?ZB`tXaHhUo&pgN9~)q7$xFV%l9Mnv*Gxr znFa$+^qMI{eqGeVNqTAL^W$4Hrisdh0(<+sqE40kx##wmg|Ca8XT_9P%}wg-6n(`X z;wIY;&z!ZAfH${A&Z-Qb{ki8&u6|bH=wp{47i~sq1tAO2_gj>^?$vxa3p!LN8jP|E z7kDzM&ciZRpgPdYzqztFz24MFyA{6P^%j6icxA#(6lG% z>s6@hewqZ|)3b9+Z#}zs0pMq|#*!&;pM1poW|S)3G3J+r8}`MY)`R0*=#`1auCV|B z%6hTGo|d&-%O4?GbJ{Li+?P7`uf?vhY%!m&roAHU6v5#90kA`CJ4E2Ael6GdHN6q6 z0q<@uTW^*h_ik=YZ`PPPT4#HE*qzy&(hcszUL$AO; zYv_COBr0pLdB$8dN`e&(o!oCt>|O?^X@uIR)xMYVWP?oXE-VBWtjVpVDUP{vqbsuc zNcAch8y1_?n$ENL?V7KO9La$#aA}&O03-GS7lA(m9%vfhWQ-XE9oJtNTq~L3$smfQ zT50?gSPCZVUzN6LtqESauoiufZ9dPBpVnvw)MW$%Yd!!`ATP?NnG?A1~7W@m)vBO-+Bvg_jO;upvAkCuJp7LDKc$5zht_p@B6jm7({@zU;#C)zjQKee`RB5mMXCdd1N?qmtFeR zxRJ&FOhaO#*hzU*RxA2|Jxrh9kTq8A!Pb~N#jfM-Vp}ZdT*;=-3x~6k$Q7y}Qcg<(+_$DdVxF!O!51fI0<>9K6aj0t03}zYj zdrSHpP?{sn9K9)g<{G}+h!#8SCm+)oaJ_Op50dGTTF*Q)lJh+FShiZ-!@L+yNk2>-OypG`{fcL*e5ivU} z;s$*0)}u&oQ3*JuWrn17z^_Mx?_7^9M1mF_(OQu6Ho%UZP~+>(EF^xfE4tbm*t-HM zGJj4dd3Cl%V!^k>q@Z1}b!TyTHS`e{#RD?jVYSgNrFqn#firHf&xc?CO2)mqe>$Bx zxdt0xmoOX`oICIL7Pw%z$SbL3T3qbU1ul4)4$fUn{95p1(JT4$m9(nK+4}B|W=h27 z^m+pl&lz5eT=sfHQXZAl{fQ^67P)Kg^#;V|Rn~qVnDoeqTGA{7w7iG?5o~s*nqy0+ zCQ1z5?=ETHv~h=p6M(U@$Jedoro%}R)X3bv$$_!bcO_1&?0~o3R@aH@m{9Y_ZF?jr zk6umQc%-oTVY^0F>j&NR|F!qlVR0>4-zWqN76>#F+%-7CwFw&B0)gP}?vUUTq;dBK z0)Ze&2=4Bd-~^Z85*%`OGc)g;$>p6p_j$hmzUgyPd)HoT{c7!6Yn3%!wx`mdRW!T&m?+PoAMO`ZQT|=5`d=45#%_O~1-EZi*)_V7{4kpL(s3BstNT^G zSn=xnej3`NS2|x8@PSflUVSh7Dw6cUevxOt^_viEHu*}yvuj%yg0 z7BYYq&~61}@PXOXp*pd#p~55}NS>eSx^3HPNPsy9%%65qfcev_7}(6|y9I1Y>M-LO z{aiN}cv*o?bQo>R(Ro*jJhqVO*!JY{g>1XzdaEp-^YM2bX%&LlZ3ob^$FeliDp;{) zE}$=B(rosPU;JH&?#S@57cQVq@+~T9m2;PD;1RLROCkG4S75d;909Xa@(5t3lWYEn zD)YDTUl(S?kY9LimjO1n&~^rx%1i;KCp_zAUwI&u77Je6fVl;VNF=AFZCe4s&!jLx zgWpqAW^|}zCojq5`GoRS+aQG0GbpYcZ^|Zxf1)B5e09Sa5R;wpLK>2MJ6~~&!H`-Wbu73 z@~Ui}He#EM>^QJte8JA`DVbCgFG?dJ(eDIqSF+V@uTGSGy1~FX6{A5}oRavCjQEbs z_|G&M(A`a_PpA#tYE-!=WL9i}EFGmbzejlggYSXnEXsb9??K2M%Kj)InX;JK;0Xbu zWP_yzYXR?iF{;hew^m7M`uNcbioL*4;N1E$ui`NUuv#))ULtb7`%S3Fm(^)_*7%s> ztA9f{4;Cym8m>-TiJizBq|aJs-Hs{F=$+<|{eGa>!}}fV&DtDPZF!jHdykMv$-cIO3(xH@a`Rx$6+V_t6A=Q(FWlNjNYWHJoS&9@*%$lqdVJs zc&Bd3AD@@amLglWp;-=T$T-K~jjfhI=(dBof0RQCp^;FTHpWFcj&S3act4K~LI-F> zvvHwnWFE9ut>u&IdNlm7T*}p_OQDsas#>{_j0i{4H&X^hWjeU)2dDbYYR9HVX{;Ae{M5h{p0qfL^~m$%6AAk)G2fBIVMsvaWf~eR)yLe@s5vID{}EL zbN%`h4ZPr2sa9mvsoH3C9+{S*DD4XI2X1@00hl-y$65?i6!3y)U>IFF?wM-VNnwO@ z>KT;x$zFi)mO^f-as0$ZVlmrP`~qkIZ%5WX;t1^&%Ik@VQo=q~g(GrSx9iNx9$yN*zhTq)adF(%+=%(2u+t zNU(CB?ZH4xs6aq!g#%Md-IW2BM%|?auykTp8GtJ;QK>*_ES@nOfpV7>v$e;fWEN+R z$D%|PQ+LFo_!h@4_XJk2z7jmjVgB}-#B(G;*Gro01j-ae4gAdp!%|ORwE8%QiE3Ij zsEzL^hg#z;z!M9mmnL(8hS0)N$Y3lAX|YBhkTR;ftcpupjX41+lL|k;{`$tS2g*&# zi1iZya_J7G#u89{nGQ=e24G^@L$EYt9iUG1Zomq2bOwZfQo?}bwuv|y6{PE)07{cG zqVB*TegwmW#|vO7-8AfZE9`lKyBkbE8h8zA(_&IUMb>0?nAQp7FhZSV8>}3zNtgh~ z9!!AE9e7^Tdn+gR#vQS%&x=AjS3MTkB!}8G9eBgXYEO#fL*y!W%vEQI8FTkxnpL<0 z5+y4Fuv$QZ)j|YPw9pPUULXPIM@|PhB??LSR(2Vt=NBy;!j;EjL=;viA|*vec}|Nd zS}fWm64+$F^ofJt3Pd1Bi*quyuT}F9644h>$ARzQm>MnpJxR*mB{9hqz0?*O2LOkT+X1|LL!7P(76A*51`>%Wya}IwV##%?*>l#IF2pY+ z07c%HnjFDAoOT-Ua8~_VR9JKz?ZHwKAQE?ZYjI%r8Fx{+_Z${4p?QBV1BeY2eG=NL-EXZ;g@OAM z3H}%DIZMmArBLIRPgRjXo7YDqfGos}zDZbv*Y|tr^GmzoiL8V|SJNvJPrjvuUFX#$ zAGPY?*wAr>X%T6%A)Y(J^c_L>j-d880{0zZG+~zO&UFDnap}HOSRBC!Be7M!(L$Rt zFbo%{O*Sk9093%EXJL^8g9F%ipTJ_~-%HuSq&Onw)Z+6y4uFr_(|XE7Y?agh8rXP+s9NN+mgIs%r(5M(W4ch29IX z4}Hh^_hojzxC{#7c(afm?@^zIjBjrSa%nh5WTd?3>r}vSS5m=^2X&Kl+RM_;idzLt zKOYezTcM>;8pVmnEz$~SEC?J7hzJ;QK}7;w{+5$ICT~Ttx@6^1TI)Lh6yx7~zK=e< zNDsN_%0|CcanPnh?J*KDRHR%!{tcrx&wEH=7`mn0CrIHUnq?o5<3nRy@bbNV#aJ2e zvpi9M%Ozn)oHEv1J1BtatO^xLaxd{Y(|hGXFUn~oX~sb{8RtO)oZ4hs1_r0{PmMV} zjf&dPvaN~QfFd*R!hKgpGv5{xZ~P;{qmd|r-XHfgtQ&B@T!+-`8f>U zYusoNRWAi~#8poF%n0SCF^a^F`po!{onG>^b3p23xnMpSCntoOD~0p;~x!ly?4RTT9=&+b@=Uy_!3Dg9=E{{ zFPV0q!($(jV8`bRrkhoPL7bA;2*$C)HCPdmxQZwU5G?y(1O*sD0I1qhRR~bk z{H-A>sNH}?6$%q;jM<7?M+UkMl9R>@l1 z_~1nK+(sY%;-XlSpUsf9yhSQ?^uY*ncDw1?=nvcBjAToEJUuDllMva%dVEgvB-Zz) z!@V;sD0)n7Q}ySSKofo!e{TK>vlpeI*O$V47hZv?Y^=j4xI&~KWqhXJ$&@+^FvyKf zmlS&EfijI9keS5IQ=+WFvx?n8Nxmy1x9go(pEeUlO2%n(74~rhjoC5$T3HowI6sWr z&sW5X_q6NLT)1P0=E_Zl$Nmu~cks!3LuO#zl)w9o3! z*BLh$kSGCzGe3mc6L_q0iUx*-A@=hBMo?9TGzMTJFg|odLoBE0;J~gA!0r~?L<5r` z#4T_#1y!gG2mk4Sld3<}~qTI6ML28Jz@ zaG!|vb-Kp!f~GQLx1v3gH4rH?K9zra2oBq+ilPYWX{x4vNLjT_6@X23r5CnOh&z4e zib(nV)b%{cuT$h9M{iMmB^H?E3B8mwSb8hNg=Pp>fB_9`lQ}M|g1t# zb}MD1%AREAhY`{n{7jrzu5~n@w|tEpFhW|{V&X&?Q@?F}wcGBeFd3-E0;9P#%^(Z@ zr~pFxAsC-05CTqnzyM_o0H=W&ptZH=mS}m9!WlG1y+`6<`7T8GW9oWgnR(xj{I~&$0sW= zU3xSem<9005QU-ffF9ZqbetpGL*DLQk^)nQSxH`CHc?$3c3pZP_2~5!0x`|N?Bob+ z0Q51-UzpUyDv0Swn8YNaA0sWH%YXS9&?gs0Gf9(i7oG!STHj)X{#X=SMzYTZWkXMk z430~<`Z=cRB2X~%Vc8#d*)Kl_oG?yH1wN4kl71Khe*8)1f)*|3YQ~R@QUH5steU9} zg!i}9HK46N%rTruT?3lwzdZZ}jt>!D3hz7kWLKJ(!x{`?n{&Ov~aTq-Ju$rqA1C3W&d71cj?& z5p4wd%N3OkqaH)Eo()Y;8g>MVwGDf}=o2C1?)`8U<=mDjBkD+wHA7Tb{@!DRLu(@f zg*5Q^IiNlWOCXq))%UqT%~U!uO6)CVrjA!ApOTr|yjEes1xpPV;&5|x%a*j6Bb#?u z;L5YpLxb9O-=?s57f$>!pHy(#5gYUZ9L)VpS?0I^&9X_8Qh^pUHUSIqOxx(OSPhv~ zy>3-l_%p-8Um4~nE*lKHhhQN5tzqFG%>wwz=xZR(BldtepKNkX$g2mac=LE5)AB(b zz(extVIDHiFZWmnaGi)|SaZOw0T7JxVT3IZ$fUfbQw&Wz<3TGkq9aDfM+mI3my?h7 z@6j;gj06K6@B$MDtgR34g|+nn0jgmHYq=q9>;M61(qV*8FapqW!w5L>h9FhGdkH}M z9SjOl3Gaoq_5UL=5R=IOJy2Op4N;>Ej#AA|SEDfhRm%_b+1cqZiATVglsoxz(q(1n zpo9)%_Z-j#M^^(~Fo`+PR1nGXH}FKzsfvcWV0;hJebsGX+f(3*ahjw1s@+DO+7=y? znx(%h_j1ts#C()ttYm~{tnehfm4gtu*&zADgPrb;?WQR1+sSjYaRaaYv5)p5kM4SC zxm<%l^^GXti-TWl#3}@KmQi*2^Y!7w&CjWej0+hEXqVqK!@D1u5&F>}CA@!r`KeII zhRkmOIics_xlj!k-r1;>AT*{;=YWgn99zi*QJ2Wsv#vv6t*zUV%FNAgeci#*r7t+< zp``6>_CkTzp_**X8ujA+R zjnw;Yq>_tC(?ciKmqX&UM2CijR5P*xQmXO9c_w)e`~LXAm6b#Niygac^N;3l$^lZb z5%=#)@4@)dA0O20eDwAo(7vPNah*`H*<*OkFGmT9bx@ka>?7W*t{3agQ(Cgzt7;Q_ z*?W_hy~Z{XHM_&Aya4K&nu8vwMXp$mkcd!t1UfY?W_59l3k_%P-#QW4b=5n#|9~M7 zH;DBvzmDbA#BCPh*F$>MT108D%=aDRR>&vOl(&U;2$~0@(rC4 z%zrlQ_mpUhiX~v+wW|f5tJ*E07X3p1NJ5IU&tv~IauJ?`(bZ)F9PN^C}O==RZt@4sObfjSIIcG#bUjmHzPcIsXb~OlNb`x(-`3+f^E3S z6{#$K2%Kd~f^ZStlm7_x<1zoV|AR9bOc7J}NEIkywv2?x%E8H*gp_kmjbbb*DT5t? z$t#oy9W?D(|78J5WRHi)X-W0Q`_u?qAO_{G9uDQ~48d+OPbWW;z_oDsZMCj84HVC9 z12+t46vkFO3a%0xnWK=HCnr_|5gqy@t#*A z-<}%gLvDOZw%RzfM6DJaFuup6iID{U$~VL5Hn^b(yjEX{hyv4H79$e^t*jLk*0G0> z0JlADqTjBK^DSa6Q!P>~k}Z-f5-k!e;w|DVVl5yRF&5Dvt*iPKz9N>qt@Ub);#&H| zZ;zGnqUdcmx@@Mtl28bM>~@{|gLAXWQMGU&DppI;O* z@2lm`Tj%s35H*bnvpFA@xnA?3v5akH5rBdt6w_UX`^C`kY!|n(lKnwUM8o64XZ{vO zN@qYHn_;u^sujPk4JPI&o0Dp5VL`?rDWN;E*-C6}`Kh61#})tLWRqDAV17?oyMff{ zp5SfAz}+E|$nAiESPnPOVIa#W+WnT28$ooC0M}1p3a=>qE#+@88yhYfMTrw2hTKWFx7h?yCVzfQNQf=-{kvoV>5sg}Rz$gN6 zu*pe$3t%M+C%?Xp&ngy4z{LeH2P+z2j-Oo)!0pFJz^w(}o1>9o%>kjUk*SMS!}Q&J z{s?K?>M~Z0lTPQP?ouB`Z#Cd+D$lN?Fv7_qY3#HvsIn)wra1uInawu0s|dJ zDB~A!S{@6O@i#b4jtN@a3r_p#hQs=dbgxq#4D?@f@L9c`oRGN{t8oq>bsCqCx;&{_ z;J&E==9M)FLc-lJV%+$NM!#4enfu$Kmum=)2)?r&rKSAmD-XO1mw!2gRs*`HOU}F`0WTbQiQIx_x#8<{Y%am zDM>39gmdt>9i)p&{KX<@){;XXjVn}FxdoBE)gQe#c4%6BbWlX{kT_VdCEMvaQ0e`- zfX_ee?g6?slBewem3|NIO<(G<3glA;7^rS1R$%1OFYAi28VM5#vjy~e(^m;hQ=X#C zb3nL6IuC)u9pyXZI=JW_RN%H_r zUiOs&?`NUdxfSBZt&mHx&$f+K@yx>G&m3~rae&w(9hKrjcIwSdw#;Ebb+N((5zq>&8e4HohaGue)MCWUmj3{!IPJ0oMM>CQX-{kP5hoEiJ_tSergi%bqZ;!jh z$~S3z@_rnKleNB7&f4_$LZZci4k^9tXTEHr`eoIRJMW=%g4Yy)qgOo`sMvo{Pl^zp zEBy;EfnK0fPuw%_4V&uRt&0u33p2pOXqt`EFWRh~kwS8i=piL1g*7RA5k4+oW}Sw>ySM z*Gu#4^ST{e{n)5=?Cd8(8(;ODX;*n)#|M1?H=DLt z;<;JmOh)0}8KP%=V2KWHTYrjKOE@g4vlt z_6&NX?b{59zh8dlCs4=QLM}mZ4V=&>g_2ESs$%UT7o)fbPDqT3{~SHSE2|k|I>JGa z)Qn9fWT=Xm>ky08Frh~-2^|c4z89NANR*con@7liMwGov0??r_I&`OdAM6FmZuVmI z4i4x#B1K@dfbMXmFfylEKLGf~-Nj?51LsygWg26}dP8@Pi=LStJ4#ZUW;gdUNoyzj zUYoUx^$d5jy(Jl+l(=TH3lL$lQoqh>B4ZdzRk@cfjq9|m%8z&1L;%NdpQK80*G*Q2k$WfZ93_LrB z-*pM>y9rZORvlew4(SWkhFrD9=vyVS%$$udM=)ME3+tCmX#^s$Bl((=wQ7kKn+e%} z^1q~vZ60E_A15$IoVjg?g70j4_v2v-ANBEynybk1nHu_uE86+hFXLZ~bkqadk?cRd zJ&ZS{mJcCV8qGf1RPsD261r3)yJ3v+gqu+-^oSa{I3K(3{|BBu*nA(bWARIkDQKPm zOJwp#r6dyKgM&5f$zTjYJ(Dg1Q=h~`-sCBJnul`Dn+8sMJvobVhy(o3*iEKbl~U|~ zIwKcQ7ln{KNr=vfb2L#Fa3ZplMlR5o;x)CF@qFq*&CeS>@Tsn;UWi&cgnv^hG?c`{|ubq%`>s{n^#=gs}aoisjKFj?YDtbEk zM*4iFO|dEmrQ7GFu3x-``Wa^C6;p?u`V!*Q3c2xVY1Tmo4u-b{H+K0Wo_Hy1$sM0E zII~Sb*H#qk+IDg>1B}NCgNfQ7K6-HSDwgOR>08s)H|si_>q@!x6HLs}2XpI>5+tuP zL2GUC88Z>jwnwruht$LeYtbw}MuF3)n4uq|8osnBTMS1(4KOYw%y^LH@W#pGhX@)* zuCSnAwtfCc7HM;^`+(481~_X2e!KsfVA<>%|KagQKxWa$cn5z!8P(82)y2~>B9Nu5?p|rkAkz-(HlnzSnZldQhk@a*3dJT34osjxO~;$RBRgQ z^v*rwW%cF=&(*&GPi_SdO<3o%Z<3*P&|VX~>IP0_)UO%8YExKDC1GYRFF$+C>*Sdq zeAzZQL*U2blDl=?7PUlRciA-JkZoDn=59|$wnaY`Df2GT|EA>$0xz)>b>M<>=3_Vh za(ew>ZmbD#nyNcalWFQ#e9(k0Yw!fi^HVYqC{>y2BdpPu&k}uiWAXGpiMR3V$Uv;~v1UH)z7VKt>#e^JikRs3;aE01_c6~cs6r#RNFe* z*Ite}?s>G=eH60{iE0@EH({1_y)_IiKX7DO)1`X6!_nBrpRwbV1^d`_pQtF++Mwg^ z@+kUKc8~e?xu2=5dnV&lav*vkJ*0K{aWI&`{jq_H9RGqTQ%e^##r8=esR2H!9w$p6$R39 zu0}&T((zB*j~@yYn)g%J8xUrSD28XaH3chjbf1*Enh27NGb24V5-i++v{$l6eorya z`tlkb)hQ}uGa$euzxtIj#CGBW4Q&jwc~a#)YveJ?gJ_;ePHd{^?->CBkQJ}SfPfVJ ziI>X^z`-^_c%+qnz^LuW7PeBcqzf!T2o(WK5Q#}n2}kU~6Q-g~;64G3IAvwy0y%mS zbW&M&U%faL(qteTvfoNwsr%DN*znVA?^Es&Z* z;yT^Yv>=Vn7=%5v>HP}Y3(u@<-hB+N^uf~T*j&_UM>$m&?RtT+Q_O@}jeM%Ly(j2x z5Ex`T_p%jOInx5g<@Z8#^e(uPCE_j{_`Wqs-MVtI#W4J0wyT)XA^WrlPrJ71FgNfH z?0W5F6DWBh=tae=^;4mC1T)D?jbIJ=MPq^gw$odV>$)B43U2s5?KqUA$z<2Ah6x=_ zb^n3|#YVV81b+SaqDKgIloF4MZo16E)~4R-|75wLGARD4wjt$`aamuCnph{sak=gE zQvl1tgmB7NzvEos*{>v;fftR%vj**KXX&au#81z3+)({d_P)9l0mum_3kPD21xVY+ zC6nI)R)g9fV}1|%omDaGR|yI)txwKuD<;zI)~0}BPDoqWeiarj4gzXeh=xWo#HpdnP(t&Qa8VC}7((;^9tOGdhlpu91T zJ!i0jRmEb4vZ}zUtzylde*9SMNNgXHhX6RFTz1PDENvyVlrf@$%;u}ODI+|dfh*9L zQ#_1HYTEJ*V2q&j5pYRJeaBN&HQ{zmTR@#lO-p&`Vmj?J6xgX+JsXSCtf%cDP1fMG z)<)`iuoe5_GA-eDZzT58{Csaj#q7&v25@i7Uc?y(`%ciAX@9S030L_rA6dU1U;61!ltYc?3=U%I?qBDMQwCC zmbkHv4sG{7Eeh1@UkT;PI?=m>(32u#a#L^}pwY>;!cP8x95h-&CR8x|+!@^DLbO#^blYQUz)4>MB*7wlc?(O}Iz-koRemXS0TsyiIYdzdl*4 ze>xrXT3O99nA;Orm+u3o&DKHIsh&a^i@|Bz{q=k!kNx+@rLo?|JU}>KR=P%RlU~|7 zf1q;B)OIC7f#c)t=kjYHaiuxEE3@WeS4x6$bSJ8Y3n$hWcg66~Z0iEnDp3i6Wy)(+(I(TM`7K;~9Z?}vz(mt=#T^G&*sQ_j z^?R|DPhn1rLxPayNN@Lfd5Qs$XAuU7Xd|%o?M1hNxnV^Z>sec74FLduLKwVb2ryWvS${D1bJ)w?tW=q#d7~r z^wvI}zM#9jsO^HsYfOg2FIL$_*6dA@yD3eNR;(AIw_ZiFK?DoSzn#z28ejg5VuKJP zPp)>nY$Y96+Bt8lHm>mVhP=FZuV zP8s)p5|&x*lKnVD$5eKxeru{F_wdQ}G6UjQUwA*y@`#1YvY9}rf0`PBIz8rukDj>e zn3w_`T1h;zm0V?xfMrgh3Hn{8K1X1y|6K!~L@c+m8XM9#S%hba8p@eKCJ>fEnvUmI zh6vwtqpx=$_!C7IL2^2fTRA~k=Ktg7WDTi#$`|qv)_s`-VZSrs^*nWV8acdXLUOj} zo=dzdF$CAko{;mIbIXflg6nEv5kjgv*`u&QSwkCEKIGKN9P2dz-_K{BE#rao zWxhA&TrT%%O$7z239(L8r8)@c=X6M#i7B3}ub4Y+$(B>W!d^CRyUocD8RVVsK@cIfkfK!Z1cXpjje?9^Qf4#qhpm!9Q@t_4%45uDtJ zfdL^Az!$~{FNRsZn4?*;_JafD@@Btf*VOi*i!u#iO(kvBmm-&-Q#JSOAbi7l1$B$il31rTyTwFm*eIG94e}GH zUFDLcOcY2FFiTi^IQU!=qyZ5+!6tSBhC^+`Y?RPYn?^&E?#uwBvbjP-4;_p>K97>E zc4@;e4D`UVUws-U2|{McF0l4`+=ojPl6?N2W%+ldD{^gh20Qj^)dWlvoM-#Z;>hl( zDs)8FkmN{NhDClj1@>|N@{#&IY&qZfKdIifDJIX>H1RI3f=HkYhZF%YG`T(=YIyxH2~{e*Q|UuWCmlO@uAA4Uw(?bbQrH37Tirea26Rw+ zQi5|=f)kx-<#n!K_@{3wlBb@kO|b!oND<<4rw0~Ko1ZZvGd`Zjx3N6j+cXVDw6L+PFAiH z3nq?MNP__{MxHXJNRkFgV~JgS=Qv;U6myiUNC*rk*zCVGs1TS@B*W0?rf;Plac5-x zkuBuBqevo?#XpZ6(;Ij}z%EZF|K+XWQA>&|I3vGh%Jq`a89pLATaIi~8~$_?t7-y+ zOzqM4*hQ0`QAb79LQUV6c%g&O4^ny&-l>v#o?wGSZ4#Xd*Iz$k_RR5I3qXk(!d>3Z z@!>kgM(lF3{!8W300VjPm&;g?n?`O z@QL!tH(c`XYM_QFd;jHbYc14v2e2~2W3l}0qXyy>cnu$Q;#E7=!C8=|jnnZro zM0Y+LT-)5F8JCV_ z_0pD3%diWRAH4qfAgPSfT&AVUagf7Kn*^e4;-kXA`JAznigB|J+o&(K@JkSi+M^v! z4|Y$pqReA5TqdEEgq5N=&Z~w5ee54NRsEVHUm&lKTGE1cz*W)5aRGQx;(%7_&xr~A zti~T!TjfSub&m{m>y(m(*a@0&Xc0kWL2p^tLa~*P3z`Tqo znnfS5dIKwgZIQnQ>Ba?2KW0Mh&Ea!MaT<{zt)s>AWfrEHzsfj^8F?;)yhiO4D>UvU zYX9+YgUnaQ7Zle3LSa-pBAGO&+hvY^VoTR;J{0&MebmIsr_fs&%9SP`Jv{LhoDF-h z9(3*hBrRw-qf+!CQDIim1%nR}X*vn{-bRhrsXBZFQ>_L8gl)}&QO^Ba@N&O%SBj9i zyez-4eBYLl>JXJeA4gWs;?IvOH@yh_rR|~H1%B*Qs}pM@M2yx5%a5-=YZ6J)9bfuTCh2#hjdW{7wv6(75lE}ZC|K16t|(U*!3A%^<4~#(HD9PDU(1C) zl?-)q?PlyqHW)A$FX|i|ZizEDPu}0RiTc$YdM!VIr%$^8xnt+x2`A zFq892_dx%k9bJ-16Yr+RDsYuaS51fk|Fd$mrB2VB(@%}z!s@M#Q-h-TDXVln!ygwR z9@vZP1V3q?szbG=3|@Xyu9a&8Nv>s@YZdqD;|PoU!RjqG9+*Iqji>QaAd2( zp)s%|ynprn<<8ljGr#&;-NEW-mIRx*+t6tA1BVZo%y4bB6d#y|NmW!obx-w>}m$t#T?s-C3?PyKbSyw6i8;+1>wW0$tamEJ7b(6dt@T{{NvlQr&NLP9l$v)V; z@}kUiovMi*?)b48zGE@;bmhY2qXCg(!t=e^C4B}cgIP&z0 zOA#%V#FKyZZW=?|T=0PFQ<57&bcjxS{*aWw@uW=mDIb`DX1S2oK3C>TcupzT6oKew%JcHpX zLV@gHso^(mNsxnYS$3q+@cZ}8Kh&L)JkiIg9+X1A8N~6^nuff%(I*t@Njvl|Pwv*S zbbH7sp&>^zt4TH7VNTep$Kv}quOt$k zQt?-C&2nH^0p_(|KLO6lw#a6LKS#rE-eX48M*J@80La9mE!W0F75WYVUj+_dj%6c( z4r?w!2|I88VdZYDt4y1o%>?$BL$f=rMvj(sg{>y>dpb5T*7?kEGuc!)L3xZ)MB%QSuh%>%x6aw1)~V~FG`CD^?}-??o6(&#(NH@Ox8ax)0wyGyU#IDi zHBiYHWv$vSfW9Ms&Pnm}!Qe0Qo8pPG{J2WqbH$1U8f&3*ou3)y?oUBk>}WHbHOZJ+@|wD=gm#WkH(j<+I|a5J*O?XQxm2k$mIP z&r^V(uxsiSZ8^Wq`O-);jCh!c{e9iw^!?a$+HmT7XF+&*bVZSjg6!&JP9?rFi1vE# zSP-SYOn-^_hxC|iPb`fos+!OFP~4WOApNxU=$%43LhcwNZk0g~PrZEOMVGAOlm0Ne z`7_Wew)EA^To`&74Z+^}Zq2n235VWqewF6yUmMMDZf?)Ae_x-?{=WC@o_aYopVz=C ztKq=eK9AuZ!kgF|D?8acII|hsJDI{ZwV}vEglEWs16cm={shI1%C)l-2Ja*Npj>TI zm{s^1T#ZmvkBt(5+gT5}o(-^7joYl=I8^cB70Z;I3sBfrd-mZN&Cw%F+d)3qNY(yOs zTH@XbzfruHKy09xey#b&&w|^ya0GvTCj-8BB;cZqF+DD;QqQWjROkGroF?qUjp(N$ zzu$IhpL|IWk6JBtj^7Jmnoaie55+Uc23Qc%te6TF9tP3HCkqV4T-3>UtB`?j6i5(9 z8N!4dpR>`qOwp6Ud&((_DBU96w^4fBb!E&p;BeZ&Ns!oo^+`hqhyS|dKf^F1VK{n* z9lL8k@$!+%9^_5fM@TPPtfcw_+vi$)AGs(sqe!Q5L6ogf$7VU`{^{rFxq!9TvU9ye6S-)pqPNaeA>*@@s&Sww0e4|C*P!((9S*#k6 zSW^zpu{{2ey75G_Ej+CZQIfk~YS0Z$>nyQ$!^Q*Hn3pggWysGcMn`o19yqDm&P89{)4|mFHEbZK{Ni5$ zzG$#hp8)Lgz+?o#_{--f0vw#alc|j}8!IgRQ_!LKh>n;;kZv5=I1l(X$HXiyCVF70&jFL%H5goe^!W0M+7G-Fm_05 zh5G|#wC!G$yHnHuM8R~*Z~R&U2Ukst^al#|!o4Wm_r1|)9yjEz0sv(X@eh=nFnCz~ z!fN)f_44dK6!Es#@qDFla9MSKqL8pXxDSQrK9n*il?-DD9GoWopC}Qt_oDFLhf*P4 z1nIGXgJW0t(?--b2>0p2cOS}PUeY&;KsdO<&OcEor|(7KzYnEQ<=X0vC9okaF*@9n zfAKnZUBvrz;b6ZHhHH~Pk3b0yj`Rlp4;Yp%qP=v!4}pdZG8gQNc! z9V-*=5FG%Yb1`*NGj(x+IUm~}c@EfQ@z1{Ce+QLG|4%^gj{N=;^v@$&|EcVc-2Vjh z?!eYRLH~D6?ce_=pm(S4{R#T#l>48WBA5Rspm%2`{pXi}>Fc^8S?m-z&NHAquSb g_`^~E%-^kYD8E1gd>;;u7Wgj-7!NAKhJbMY51#?xZU6uP diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 410dfcb1f..3c06a25b2 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -843,287 +843,279 @@ void io_enable_steppers(uint8_t mask) #if defined(MCU_HAS_SOFT_PWM_TIMER) || defined(IC74HC595_HAS_PWMS) // software pwm counters uint8_t g_io_soft_pwm[16]; -#ifdef IC74HC595_HAS_PWMS -static uint16_t soft_pwm_mask; -#endif // software pwm resolution reduction factor // PWM resolution in bits will be equal to (8 - g_soft_pwm_res) // this is determined by the mcu_softpwm_freq_config uint8_t g_soft_pwm_res; -void io_soft_pwm_update(void) +MCU_CALLBACK void io_soft_pwm_update(void) { - static uint8_t pwm_counter = 0; + static uint8_t pwm_counter_last = 0; + uint8_t pwm_counter = pwm_counter_last; uint8_t resolution = g_soft_pwm_res; #ifdef IC74HC595_HAS_PWMS static uint16_t pwm_mask_last = 0; - uint16_t pwm_mask = soft_pwm_mask; + uint16_t pwm_mask = 0; #endif // software PWM - if ((++pwm_counter) >> resolution) - { - uint8_t pwm_ref = pwm_counter << resolution; + pwm_counter += (1 << resolution); + pwm_counter_last = pwm_counter; #if ASSERT_PIN(PWM0) - if (pwm_ref > g_io_soft_pwm[0]) - { + if (pwm_counter > g_io_soft_pwm[0] || !g_io_soft_pwm[0]) + { #if ASSERT_PIN_IO(PWM0) - mcu_clear_output(PWM0); + mcu_clear_output(PWM0); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM0) + mcu_set_output(PWM0); #elif ASSERT_PIN_EXTENDED(PWM0) - pwm_mask &= ~(1 << 0); + pwm_mask |= (1 << 0); #endif - } + } #endif #if ASSERT_PIN(PWM1) - if (pwm_ref > g_io_soft_pwm[1]) - { + if (pwm_counter > g_io_soft_pwm[1] || !g_io_soft_pwm[1]) + { #if ASSERT_PIN_IO(PWM1) - mcu_clear_output(PWM1); + mcu_clear_output(PWM1); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM1) + mcu_set_output(PWM1); #elif ASSERT_PIN_EXTENDED(PWM1) - pwm_mask &= ~(1 << 1); + pwm_mask |= (1 << 1); #endif - } + } #endif #if ASSERT_PIN(PWM2) - if (pwm_ref > g_io_soft_pwm[2]) - { + if (pwm_counter > g_io_soft_pwm[2] || !g_io_soft_pwm[2]) + { +#if ASSERT_PIN_IO(PWM2) + mcu_clear_output(PWM2); +#endif + } + else + { #if ASSERT_PIN_IO(PWM2) - mcu_clear_output(PWM2); + mcu_set_output(PWM2); #elif ASSERT_PIN_EXTENDED(PWM2) - pwm_mask &= ~(1 << 2); + pwm_mask |= (1 << 2); #endif - } + } #endif #if ASSERT_PIN(PWM3) - if (pwm_ref > g_io_soft_pwm[3]) - { + if (pwm_counter > g_io_soft_pwm[3] || !g_io_soft_pwm[3]) + { #if ASSERT_PIN_IO(PWM3) - mcu_clear_output(PWM3); + mcu_clear_output(PWM3); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM3) + mcu_set_output(PWM3); #elif ASSERT_PIN_EXTENDED(PWM3) - pwm_mask &= ~(1 << 3); + pwm_mask |= (1 << 3); #endif - } + } #endif #if ASSERT_PIN(PWM4) - if (pwm_ref > g_io_soft_pwm[4]) - { + if (pwm_counter > g_io_soft_pwm[4] || !g_io_soft_pwm[4]) + { +#if ASSERT_PIN_IO(PWM4) + mcu_clear_output(PWM4); +#endif + } + else + { #if ASSERT_PIN_IO(PWM4) - mcu_clear_output(PWM4); + mcu_set_output(PWM4); #elif ASSERT_PIN_EXTENDED(PWM4) - pwm_mask &= ~(1 << 4); + pwm_mask |= (1 << 4); #endif - } + } #endif #if ASSERT_PIN(PWM5) - if (pwm_ref > g_io_soft_pwm[5]) - { + if (pwm_counter > g_io_soft_pwm[5] || !g_io_soft_pwm[5]) + { +#if ASSERT_PIN_IO(PWM5) + mcu_clear_output(PWM5); +#endif + } + else + { #if ASSERT_PIN_IO(PWM5) - mcu_clear_output(PWM5); + mcu_set_output(PWM5); #elif ASSERT_PIN_EXTENDED(PWM5) - pwm_mask &= ~(1 << 5); + pwm_mask |= (1 << 5); #endif - } + } #endif #if ASSERT_PIN(PWM6) - if (pwm_ref > g_io_soft_pwm[6]) - { + if (pwm_counter > g_io_soft_pwm[6] || !g_io_soft_pwm[6]) + { #if ASSERT_PIN_IO(PWM6) - mcu_clear_output(PWM6); + mcu_clear_output(PWM6); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM6) + mcu_set_output(PWM6); #elif ASSERT_PIN_EXTENDED(PWM6) - pwm_mask &= ~(1 << 6); + pwm_mask |= (1 << 6); #endif - } + } #endif #if ASSERT_PIN(PWM7) - if (pwm_ref > g_io_soft_pwm[7]) - { + if (pwm_counter > g_io_soft_pwm[7] || !g_io_soft_pwm[7]) + { #if ASSERT_PIN_IO(PWM7) - mcu_clear_output(PWM7); + mcu_clear_output(PWM7); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM7) + mcu_set_output(PWM7); #elif ASSERT_PIN_EXTENDED(PWM7) - pwm_mask &= ~(1 << 7); + pwm_mask |= (1 << 7); #endif - } + } #endif #if ASSERT_PIN(PWM8) - if (pwm_ref > g_io_soft_pwm[8]) - { + if (pwm_counter > g_io_soft_pwm[8] || !g_io_soft_pwm[8]) + { +#if ASSERT_PIN_IO(PWM8) + mcu_clear_output(PWM8); +#endif + } + else + { #if ASSERT_PIN_IO(PWM8) - mcu_clear_output(PWM8); + mcu_set_output(PWM8); #elif ASSERT_PIN_EXTENDED(PWM8) - pwm_mask &= ~(1 << 8); + pwm_mask |= (1 << 8); #endif - } + } #endif #if ASSERT_PIN(PWM9) - if (pwm_ref > g_io_soft_pwm[9]) - { + if (pwm_counter > g_io_soft_pwm[9] || !g_io_soft_pwm[9]) + { +#if ASSERT_PIN_IO(PWM9) + mcu_clear_output(PWM9); +#endif + } + else + { #if ASSERT_PIN_IO(PWM9) - mcu_clear_output(PWM9); + mcu_set_output(PWM9); #elif ASSERT_PIN_EXTENDED(PWM9) - pwm_mask &= ~(1 << 9); + pwm_mask |= (1 << 9); #endif - } + } #endif #if ASSERT_PIN(PWM10) - if (pwm_ref > g_io_soft_pwm[10]) - { + if (pwm_counter > g_io_soft_pwm[10] || !g_io_soft_pwm[10]) + { #if ASSERT_PIN_IO(PWM10) - mcu_clear_output(PWM10); + mcu_clear_output(PWM10); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM10) + mcu_set_output(PWM10); #elif ASSERT_PIN_EXTENDED(PWM10) - pwm_mask &= ~(1 << 10); + pwm_mask |= (1 << 10); #endif - } + } #endif #if ASSERT_PIN(PWM11) - if (pwm_ref > g_io_soft_pwm[11]) - { + if (pwm_counter > g_io_soft_pwm[11] || !g_io_soft_pwm[11]) + { #if ASSERT_PIN_IO(PWM11) - mcu_clear_output(PWM11); + mcu_clear_output(PWM11); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM11) + mcu_set_output(PWM11); #elif ASSERT_PIN_EXTENDED(PWM11) - pwm_mask &= ~(1 << 11); + pwm_mask |= (1 << 11); #endif - } + } #endif #if ASSERT_PIN(PWM12) - if (pwm_ref > g_io_soft_pwm[12]) - { + if (pwm_counter > g_io_soft_pwm[12] || !g_io_soft_pwm[12]) + { +#if ASSERT_PIN_IO(PWM12) + mcu_clear_output(PWM12); +#endif + } + else + { #if ASSERT_PIN_IO(PWM12) - mcu_clear_output(PWM12); + mcu_set_output(PWM12); #elif ASSERT_PIN_EXTENDED(PWM12) - pwm_mask &= ~(1 << 12); + pwm_mask |= (1 << 12); #endif - } + } #endif #if ASSERT_PIN(PWM13) - if (pwm_ref > g_io_soft_pwm[13]) - { + if (pwm_counter > g_io_soft_pwm[13] || !g_io_soft_pwm[13]) + { #if ASSERT_PIN_IO(PWM13) - mcu_clear_output(PWM13); + mcu_clear_output(PWM13); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM13) + mcu_set_output(PWM13); #elif ASSERT_PIN_EXTENDED(PWM13) - pwm_mask &= ~(1 << 13); + pwm_mask |= (1 << 13); #endif - } + } #endif #if ASSERT_PIN(PWM14) - if (pwm_ref > g_io_soft_pwm[14]) - { + if (pwm_counter > g_io_soft_pwm[14] || !g_io_soft_pwm[14]) + { #if ASSERT_PIN_IO(PWM14) - mcu_clear_output(PWM14); + mcu_clear_output(PWM14); +#endif + } + else + { +#if ASSERT_PIN_IO(PWM14) + mcu_set_output(PWM14); #elif ASSERT_PIN_EXTENDED(PWM14) - pwm_mask &= ~(1 << 14); + pwm_mask |= (1 << 14); #endif - } + } #endif #if ASSERT_PIN(PWM15) - if (pwm_ref > g_io_soft_pwm[15]) - { + if (pwm_counter > g_io_soft_pwm[15] || !g_io_soft_pwm[15]) + { #if ASSERT_PIN_IO(PWM15) - mcu_clear_output(PWM15); -#elif ASSERT_PIN_EXTENDED(PWM15) - pwm_mask &= ~(1 << 15); -#endif - } + mcu_clear_output(PWM15); #endif } else { - pwm_counter = 0; -#if ASSERT_PIN_IO(PWM0) - if (g_io_soft_pwm[0]) - { - mcu_set_output(PWM0); - } -#endif -#if ASSERT_PIN_IO(PWM1) - if (g_io_soft_pwm[1]) - { - mcu_set_output(PWM1); - } -#endif -#if ASSERT_PIN_IO(PWM2) - if (g_io_soft_pwm[2]) - { - mcu_set_output(PWM2); - } -#endif -#if ASSERT_PIN_IO(PWM3) - if (g_io_soft_pwm[3]) - { - mcu_set_output(PWM3); - } -#endif -#if ASSERT_PIN_IO(PWM4) - if (g_io_soft_pwm[4]) - { - mcu_set_output(PWM4); - } -#endif -#if ASSERT_PIN_IO(PWM5) - if (g_io_soft_pwm[5]) - { - mcu_set_output(PWM5); - } -#endif -#if ASSERT_PIN_IO(PWM6) - if (g_io_soft_pwm[6]) - { - mcu_set_output(PWM6); - } -#endif -#if ASSERT_PIN_IO(PWM7) - if (g_io_soft_pwm[7]) - { - mcu_set_output(PWM7); - } -#endif -#if ASSERT_PIN_IO(PWM8) - if (g_io_soft_pwm[8]) - { - mcu_set_output(PWM8); - } -#endif -#if ASSERT_PIN_IO(PWM9) - if (g_io_soft_pwm[9]) - { - mcu_set_output(PWM9); - } -#endif -#if ASSERT_PIN_IO(PWM10) - if (g_io_soft_pwm[10]) - { - mcu_set_output(PWM10); - } -#endif -#if ASSERT_PIN_IO(PWM11) - if (g_io_soft_pwm[11]) - { - mcu_set_output(PWM11); - } -#endif -#if ASSERT_PIN_IO(PWM12) - if (g_io_soft_pwm[12]) - { - mcu_set_output(PWM12); - } -#endif -#if ASSERT_PIN_IO(PWM13) - if (g_io_soft_pwm[13]) - { - mcu_set_output(PWM13); - } -#endif -#if ASSERT_PIN_IO(PWM14) - if (g_io_soft_pwm[14]) - { - mcu_set_output(PWM14); - } -#endif #if ASSERT_PIN_IO(PWM15) - if (g_io_soft_pwm[15]) - { - mcu_set_output(PWM15); - } + mcu_set_output(PWM15); +#elif ASSERT_PIN_EXTENDED(PWM15) + pwm_mask |= (1 << 15); #endif } +#endif #ifdef IC74HC595_HAS_PWMS if (pwm_mask_last != pwm_mask) diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index 702bae743..af9d6eeb4 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -56,11 +56,7 @@ extern "C" #define io_get_pwm(pin) io_hal_get_pwm(pin) #if defined(MCU_HAS_SOFT_PWM_TIMER) || defined(IC74HC595_HAS_PWMS) - extern uint8_t g_io_soft_pwm[16]; - extern uint8_t g_soft_pwm_res; -#define io_set_soft_pwm(pin, value) ({ g_io_soft_pwm[pin - PWM_PINS_OFFSET] = (0xFF & value); }) -#define io_get_soft_pwm(pin) g_io_soft_pwm[pin - PWM_PINS_OFFSET] - void io_soft_pwm_update(void); + MCU_CALLBACK void io_soft_pwm_update(void); #endif // inputs diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index 1fd5a9128..dc5212816 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -19,9 +19,15 @@ extern "C" #define io1_get_input mcu_get_input(STEP0) #elif ASSERT_PIN_EXTENDED(STEP0) #define io1_config_output -#define io1_set_output ic74hc595_set_pin(STEP0);ic74hc595_shift_io_pins() -#define io1_clear_output ic74hc595_clear_pin(STEP0);ic74hc595_shift_io_pins() -#define io1_toggle_output ic74hc595_toggle_pin(STEP0);ic74hc595_shift_io_pins() +#define io1_set_output \ + ic74hc595_set_pin(STEP0); \ + ic74hc595_shift_io_pins() +#define io1_clear_output \ + ic74hc595_clear_pin(STEP0); \ + ic74hc595_shift_io_pins() +#define io1_toggle_output \ + ic74hc595_toggle_pin(STEP0); \ + ic74hc595_shift_io_pins() #define io1_get_output ic74hc595_get_pin(STEP0) #define io1_config_input #define io1_config_pullup @@ -47,9 +53,15 @@ extern "C" #define io2_get_input mcu_get_input(STEP1) #elif ASSERT_PIN_EXTENDED(STEP1) #define io2_config_output -#define io2_set_output ic74hc595_set_pin(STEP1);ic74hc595_shift_io_pins() -#define io2_clear_output ic74hc595_clear_pin(STEP1);ic74hc595_shift_io_pins() -#define io2_toggle_output ic74hc595_toggle_pin(STEP1);ic74hc595_shift_io_pins() +#define io2_set_output \ + ic74hc595_set_pin(STEP1); \ + ic74hc595_shift_io_pins() +#define io2_clear_output \ + ic74hc595_clear_pin(STEP1); \ + ic74hc595_shift_io_pins() +#define io2_toggle_output \ + ic74hc595_toggle_pin(STEP1); \ + ic74hc595_shift_io_pins() #define io2_get_output ic74hc595_get_pin(STEP1) #define io2_config_input #define io2_config_pullup @@ -75,9 +87,15 @@ extern "C" #define io3_get_input mcu_get_input(STEP2) #elif ASSERT_PIN_EXTENDED(STEP2) #define io3_config_output -#define io3_set_output ic74hc595_set_pin(STEP2);ic74hc595_shift_io_pins() -#define io3_clear_output ic74hc595_clear_pin(STEP2);ic74hc595_shift_io_pins() -#define io3_toggle_output ic74hc595_toggle_pin(STEP2);ic74hc595_shift_io_pins() +#define io3_set_output \ + ic74hc595_set_pin(STEP2); \ + ic74hc595_shift_io_pins() +#define io3_clear_output \ + ic74hc595_clear_pin(STEP2); \ + ic74hc595_shift_io_pins() +#define io3_toggle_output \ + ic74hc595_toggle_pin(STEP2); \ + ic74hc595_shift_io_pins() #define io3_get_output ic74hc595_get_pin(STEP2) #define io3_config_input #define io3_config_pullup @@ -103,9 +121,15 @@ extern "C" #define io4_get_input mcu_get_input(STEP3) #elif ASSERT_PIN_EXTENDED(STEP3) #define io4_config_output -#define io4_set_output ic74hc595_set_pin(STEP3);ic74hc595_shift_io_pins() -#define io4_clear_output ic74hc595_clear_pin(STEP3);ic74hc595_shift_io_pins() -#define io4_toggle_output ic74hc595_toggle_pin(STEP3);ic74hc595_shift_io_pins() +#define io4_set_output \ + ic74hc595_set_pin(STEP3); \ + ic74hc595_shift_io_pins() +#define io4_clear_output \ + ic74hc595_clear_pin(STEP3); \ + ic74hc595_shift_io_pins() +#define io4_toggle_output \ + ic74hc595_toggle_pin(STEP3); \ + ic74hc595_shift_io_pins() #define io4_get_output ic74hc595_get_pin(STEP3) #define io4_config_input #define io4_config_pullup @@ -131,9 +155,15 @@ extern "C" #define io5_get_input mcu_get_input(STEP4) #elif ASSERT_PIN_EXTENDED(STEP4) #define io5_config_output -#define io5_set_output ic74hc595_set_pin(STEP4);ic74hc595_shift_io_pins() -#define io5_clear_output ic74hc595_clear_pin(STEP4);ic74hc595_shift_io_pins() -#define io5_toggle_output ic74hc595_toggle_pin(STEP4);ic74hc595_shift_io_pins() +#define io5_set_output \ + ic74hc595_set_pin(STEP4); \ + ic74hc595_shift_io_pins() +#define io5_clear_output \ + ic74hc595_clear_pin(STEP4); \ + ic74hc595_shift_io_pins() +#define io5_toggle_output \ + ic74hc595_toggle_pin(STEP4); \ + ic74hc595_shift_io_pins() #define io5_get_output ic74hc595_get_pin(STEP4) #define io5_config_input #define io5_config_pullup @@ -159,9 +189,15 @@ extern "C" #define io6_get_input mcu_get_input(STEP5) #elif ASSERT_PIN_EXTENDED(STEP5) #define io6_config_output -#define io6_set_output ic74hc595_set_pin(STEP5);ic74hc595_shift_io_pins() -#define io6_clear_output ic74hc595_clear_pin(STEP5);ic74hc595_shift_io_pins() -#define io6_toggle_output ic74hc595_toggle_pin(STEP5);ic74hc595_shift_io_pins() +#define io6_set_output \ + ic74hc595_set_pin(STEP5); \ + ic74hc595_shift_io_pins() +#define io6_clear_output \ + ic74hc595_clear_pin(STEP5); \ + ic74hc595_shift_io_pins() +#define io6_toggle_output \ + ic74hc595_toggle_pin(STEP5); \ + ic74hc595_shift_io_pins() #define io6_get_output ic74hc595_get_pin(STEP5) #define io6_config_input #define io6_config_pullup @@ -187,9 +223,15 @@ extern "C" #define io7_get_input mcu_get_input(STEP6) #elif ASSERT_PIN_EXTENDED(STEP6) #define io7_config_output -#define io7_set_output ic74hc595_set_pin(STEP6);ic74hc595_shift_io_pins() -#define io7_clear_output ic74hc595_clear_pin(STEP6);ic74hc595_shift_io_pins() -#define io7_toggle_output ic74hc595_toggle_pin(STEP6);ic74hc595_shift_io_pins() +#define io7_set_output \ + ic74hc595_set_pin(STEP6); \ + ic74hc595_shift_io_pins() +#define io7_clear_output \ + ic74hc595_clear_pin(STEP6); \ + ic74hc595_shift_io_pins() +#define io7_toggle_output \ + ic74hc595_toggle_pin(STEP6); \ + ic74hc595_shift_io_pins() #define io7_get_output ic74hc595_get_pin(STEP6) #define io7_config_input #define io7_config_pullup @@ -215,9 +257,15 @@ extern "C" #define io8_get_input mcu_get_input(STEP7) #elif ASSERT_PIN_EXTENDED(STEP7) #define io8_config_output -#define io8_set_output ic74hc595_set_pin(STEP7);ic74hc595_shift_io_pins() -#define io8_clear_output ic74hc595_clear_pin(STEP7);ic74hc595_shift_io_pins() -#define io8_toggle_output ic74hc595_toggle_pin(STEP7);ic74hc595_shift_io_pins() +#define io8_set_output \ + ic74hc595_set_pin(STEP7); \ + ic74hc595_shift_io_pins() +#define io8_clear_output \ + ic74hc595_clear_pin(STEP7); \ + ic74hc595_shift_io_pins() +#define io8_toggle_output \ + ic74hc595_toggle_pin(STEP7); \ + ic74hc595_shift_io_pins() #define io8_get_output ic74hc595_get_pin(STEP7) #define io8_config_input #define io8_config_pullup @@ -243,9 +291,15 @@ extern "C" #define io9_get_input mcu_get_input(DIR0) #elif ASSERT_PIN_EXTENDED(DIR0) #define io9_config_output -#define io9_set_output ic74hc595_set_pin(DIR0);ic74hc595_shift_io_pins() -#define io9_clear_output ic74hc595_clear_pin(DIR0);ic74hc595_shift_io_pins() -#define io9_toggle_output ic74hc595_toggle_pin(DIR0);ic74hc595_shift_io_pins() +#define io9_set_output \ + ic74hc595_set_pin(DIR0); \ + ic74hc595_shift_io_pins() +#define io9_clear_output \ + ic74hc595_clear_pin(DIR0); \ + ic74hc595_shift_io_pins() +#define io9_toggle_output \ + ic74hc595_toggle_pin(DIR0); \ + ic74hc595_shift_io_pins() #define io9_get_output ic74hc595_get_pin(DIR0) #define io9_config_input #define io9_config_pullup @@ -271,9 +325,15 @@ extern "C" #define io10_get_input mcu_get_input(DIR1) #elif ASSERT_PIN_EXTENDED(DIR1) #define io10_config_output -#define io10_set_output ic74hc595_set_pin(DIR1);ic74hc595_shift_io_pins() -#define io10_clear_output ic74hc595_clear_pin(DIR1);ic74hc595_shift_io_pins() -#define io10_toggle_output ic74hc595_toggle_pin(DIR1);ic74hc595_shift_io_pins() +#define io10_set_output \ + ic74hc595_set_pin(DIR1); \ + ic74hc595_shift_io_pins() +#define io10_clear_output \ + ic74hc595_clear_pin(DIR1); \ + ic74hc595_shift_io_pins() +#define io10_toggle_output \ + ic74hc595_toggle_pin(DIR1); \ + ic74hc595_shift_io_pins() #define io10_get_output ic74hc595_get_pin(DIR1) #define io10_config_input #define io10_config_pullup @@ -299,9 +359,15 @@ extern "C" #define io11_get_input mcu_get_input(DIR2) #elif ASSERT_PIN_EXTENDED(DIR2) #define io11_config_output -#define io11_set_output ic74hc595_set_pin(DIR2);ic74hc595_shift_io_pins() -#define io11_clear_output ic74hc595_clear_pin(DIR2);ic74hc595_shift_io_pins() -#define io11_toggle_output ic74hc595_toggle_pin(DIR2);ic74hc595_shift_io_pins() +#define io11_set_output \ + ic74hc595_set_pin(DIR2); \ + ic74hc595_shift_io_pins() +#define io11_clear_output \ + ic74hc595_clear_pin(DIR2); \ + ic74hc595_shift_io_pins() +#define io11_toggle_output \ + ic74hc595_toggle_pin(DIR2); \ + ic74hc595_shift_io_pins() #define io11_get_output ic74hc595_get_pin(DIR2) #define io11_config_input #define io11_config_pullup @@ -327,9 +393,15 @@ extern "C" #define io12_get_input mcu_get_input(DIR3) #elif ASSERT_PIN_EXTENDED(DIR3) #define io12_config_output -#define io12_set_output ic74hc595_set_pin(DIR3);ic74hc595_shift_io_pins() -#define io12_clear_output ic74hc595_clear_pin(DIR3);ic74hc595_shift_io_pins() -#define io12_toggle_output ic74hc595_toggle_pin(DIR3);ic74hc595_shift_io_pins() +#define io12_set_output \ + ic74hc595_set_pin(DIR3); \ + ic74hc595_shift_io_pins() +#define io12_clear_output \ + ic74hc595_clear_pin(DIR3); \ + ic74hc595_shift_io_pins() +#define io12_toggle_output \ + ic74hc595_toggle_pin(DIR3); \ + ic74hc595_shift_io_pins() #define io12_get_output ic74hc595_get_pin(DIR3) #define io12_config_input #define io12_config_pullup @@ -355,9 +427,15 @@ extern "C" #define io13_get_input mcu_get_input(DIR4) #elif ASSERT_PIN_EXTENDED(DIR4) #define io13_config_output -#define io13_set_output ic74hc595_set_pin(DIR4);ic74hc595_shift_io_pins() -#define io13_clear_output ic74hc595_clear_pin(DIR4);ic74hc595_shift_io_pins() -#define io13_toggle_output ic74hc595_toggle_pin(DIR4);ic74hc595_shift_io_pins() +#define io13_set_output \ + ic74hc595_set_pin(DIR4); \ + ic74hc595_shift_io_pins() +#define io13_clear_output \ + ic74hc595_clear_pin(DIR4); \ + ic74hc595_shift_io_pins() +#define io13_toggle_output \ + ic74hc595_toggle_pin(DIR4); \ + ic74hc595_shift_io_pins() #define io13_get_output ic74hc595_get_pin(DIR4) #define io13_config_input #define io13_config_pullup @@ -383,9 +461,15 @@ extern "C" #define io14_get_input mcu_get_input(DIR5) #elif ASSERT_PIN_EXTENDED(DIR5) #define io14_config_output -#define io14_set_output ic74hc595_set_pin(DIR5);ic74hc595_shift_io_pins() -#define io14_clear_output ic74hc595_clear_pin(DIR5);ic74hc595_shift_io_pins() -#define io14_toggle_output ic74hc595_toggle_pin(DIR5);ic74hc595_shift_io_pins() +#define io14_set_output \ + ic74hc595_set_pin(DIR5); \ + ic74hc595_shift_io_pins() +#define io14_clear_output \ + ic74hc595_clear_pin(DIR5); \ + ic74hc595_shift_io_pins() +#define io14_toggle_output \ + ic74hc595_toggle_pin(DIR5); \ + ic74hc595_shift_io_pins() #define io14_get_output ic74hc595_get_pin(DIR5) #define io14_config_input #define io14_config_pullup @@ -411,9 +495,15 @@ extern "C" #define io15_get_input mcu_get_input(DIR6) #elif ASSERT_PIN_EXTENDED(DIR6) #define io15_config_output -#define io15_set_output ic74hc595_set_pin(DIR6);ic74hc595_shift_io_pins() -#define io15_clear_output ic74hc595_clear_pin(DIR6);ic74hc595_shift_io_pins() -#define io15_toggle_output ic74hc595_toggle_pin(DIR6);ic74hc595_shift_io_pins() +#define io15_set_output \ + ic74hc595_set_pin(DIR6); \ + ic74hc595_shift_io_pins() +#define io15_clear_output \ + ic74hc595_clear_pin(DIR6); \ + ic74hc595_shift_io_pins() +#define io15_toggle_output \ + ic74hc595_toggle_pin(DIR6); \ + ic74hc595_shift_io_pins() #define io15_get_output ic74hc595_get_pin(DIR6) #define io15_config_input #define io15_config_pullup @@ -439,9 +529,15 @@ extern "C" #define io16_get_input mcu_get_input(DIR7) #elif ASSERT_PIN_EXTENDED(DIR7) #define io16_config_output -#define io16_set_output ic74hc595_set_pin(DIR7);ic74hc595_shift_io_pins() -#define io16_clear_output ic74hc595_clear_pin(DIR7);ic74hc595_shift_io_pins() -#define io16_toggle_output ic74hc595_toggle_pin(DIR7);ic74hc595_shift_io_pins() +#define io16_set_output \ + ic74hc595_set_pin(DIR7); \ + ic74hc595_shift_io_pins() +#define io16_clear_output \ + ic74hc595_clear_pin(DIR7); \ + ic74hc595_shift_io_pins() +#define io16_toggle_output \ + ic74hc595_toggle_pin(DIR7); \ + ic74hc595_shift_io_pins() #define io16_get_output ic74hc595_get_pin(DIR7) #define io16_config_input #define io16_config_pullup @@ -467,9 +563,15 @@ extern "C" #define io17_get_input mcu_get_input(STEP0_EN) #elif ASSERT_PIN_EXTENDED(STEP0_EN) #define io17_config_output -#define io17_set_output ic74hc595_set_pin(STEP0_EN);ic74hc595_shift_io_pins() -#define io17_clear_output ic74hc595_clear_pin(STEP0_EN);ic74hc595_shift_io_pins() -#define io17_toggle_output ic74hc595_toggle_pin(STEP0_EN);ic74hc595_shift_io_pins() +#define io17_set_output \ + ic74hc595_set_pin(STEP0_EN); \ + ic74hc595_shift_io_pins() +#define io17_clear_output \ + ic74hc595_clear_pin(STEP0_EN); \ + ic74hc595_shift_io_pins() +#define io17_toggle_output \ + ic74hc595_toggle_pin(STEP0_EN); \ + ic74hc595_shift_io_pins() #define io17_get_output ic74hc595_get_pin(STEP0_EN) #define io17_config_input #define io17_config_pullup @@ -495,9 +597,15 @@ extern "C" #define io18_get_input mcu_get_input(STEP1_EN) #elif ASSERT_PIN_EXTENDED(STEP1_EN) #define io18_config_output -#define io18_set_output ic74hc595_set_pin(STEP1_EN);ic74hc595_shift_io_pins() -#define io18_clear_output ic74hc595_clear_pin(STEP1_EN);ic74hc595_shift_io_pins() -#define io18_toggle_output ic74hc595_toggle_pin(STEP1_EN);ic74hc595_shift_io_pins() +#define io18_set_output \ + ic74hc595_set_pin(STEP1_EN); \ + ic74hc595_shift_io_pins() +#define io18_clear_output \ + ic74hc595_clear_pin(STEP1_EN); \ + ic74hc595_shift_io_pins() +#define io18_toggle_output \ + ic74hc595_toggle_pin(STEP1_EN); \ + ic74hc595_shift_io_pins() #define io18_get_output ic74hc595_get_pin(STEP1_EN) #define io18_config_input #define io18_config_pullup @@ -523,9 +631,15 @@ extern "C" #define io19_get_input mcu_get_input(STEP2_EN) #elif ASSERT_PIN_EXTENDED(STEP2_EN) #define io19_config_output -#define io19_set_output ic74hc595_set_pin(STEP2_EN);ic74hc595_shift_io_pins() -#define io19_clear_output ic74hc595_clear_pin(STEP2_EN);ic74hc595_shift_io_pins() -#define io19_toggle_output ic74hc595_toggle_pin(STEP2_EN);ic74hc595_shift_io_pins() +#define io19_set_output \ + ic74hc595_set_pin(STEP2_EN); \ + ic74hc595_shift_io_pins() +#define io19_clear_output \ + ic74hc595_clear_pin(STEP2_EN); \ + ic74hc595_shift_io_pins() +#define io19_toggle_output \ + ic74hc595_toggle_pin(STEP2_EN); \ + ic74hc595_shift_io_pins() #define io19_get_output ic74hc595_get_pin(STEP2_EN) #define io19_config_input #define io19_config_pullup @@ -551,9 +665,15 @@ extern "C" #define io20_get_input mcu_get_input(STEP3_EN) #elif ASSERT_PIN_EXTENDED(STEP3_EN) #define io20_config_output -#define io20_set_output ic74hc595_set_pin(STEP3_EN);ic74hc595_shift_io_pins() -#define io20_clear_output ic74hc595_clear_pin(STEP3_EN);ic74hc595_shift_io_pins() -#define io20_toggle_output ic74hc595_toggle_pin(STEP3_EN);ic74hc595_shift_io_pins() +#define io20_set_output \ + ic74hc595_set_pin(STEP3_EN); \ + ic74hc595_shift_io_pins() +#define io20_clear_output \ + ic74hc595_clear_pin(STEP3_EN); \ + ic74hc595_shift_io_pins() +#define io20_toggle_output \ + ic74hc595_toggle_pin(STEP3_EN); \ + ic74hc595_shift_io_pins() #define io20_get_output ic74hc595_get_pin(STEP3_EN) #define io20_config_input #define io20_config_pullup @@ -579,9 +699,15 @@ extern "C" #define io21_get_input mcu_get_input(STEP4_EN) #elif ASSERT_PIN_EXTENDED(STEP4_EN) #define io21_config_output -#define io21_set_output ic74hc595_set_pin(STEP4_EN);ic74hc595_shift_io_pins() -#define io21_clear_output ic74hc595_clear_pin(STEP4_EN);ic74hc595_shift_io_pins() -#define io21_toggle_output ic74hc595_toggle_pin(STEP4_EN);ic74hc595_shift_io_pins() +#define io21_set_output \ + ic74hc595_set_pin(STEP4_EN); \ + ic74hc595_shift_io_pins() +#define io21_clear_output \ + ic74hc595_clear_pin(STEP4_EN); \ + ic74hc595_shift_io_pins() +#define io21_toggle_output \ + ic74hc595_toggle_pin(STEP4_EN); \ + ic74hc595_shift_io_pins() #define io21_get_output ic74hc595_get_pin(STEP4_EN) #define io21_config_input #define io21_config_pullup @@ -607,9 +733,15 @@ extern "C" #define io22_get_input mcu_get_input(STEP5_EN) #elif ASSERT_PIN_EXTENDED(STEP5_EN) #define io22_config_output -#define io22_set_output ic74hc595_set_pin(STEP5_EN);ic74hc595_shift_io_pins() -#define io22_clear_output ic74hc595_clear_pin(STEP5_EN);ic74hc595_shift_io_pins() -#define io22_toggle_output ic74hc595_toggle_pin(STEP5_EN);ic74hc595_shift_io_pins() +#define io22_set_output \ + ic74hc595_set_pin(STEP5_EN); \ + ic74hc595_shift_io_pins() +#define io22_clear_output \ + ic74hc595_clear_pin(STEP5_EN); \ + ic74hc595_shift_io_pins() +#define io22_toggle_output \ + ic74hc595_toggle_pin(STEP5_EN); \ + ic74hc595_shift_io_pins() #define io22_get_output ic74hc595_get_pin(STEP5_EN) #define io22_config_input #define io22_config_pullup @@ -635,9 +767,15 @@ extern "C" #define io23_get_input mcu_get_input(STEP6_EN) #elif ASSERT_PIN_EXTENDED(STEP6_EN) #define io23_config_output -#define io23_set_output ic74hc595_set_pin(STEP6_EN);ic74hc595_shift_io_pins() -#define io23_clear_output ic74hc595_clear_pin(STEP6_EN);ic74hc595_shift_io_pins() -#define io23_toggle_output ic74hc595_toggle_pin(STEP6_EN);ic74hc595_shift_io_pins() +#define io23_set_output \ + ic74hc595_set_pin(STEP6_EN); \ + ic74hc595_shift_io_pins() +#define io23_clear_output \ + ic74hc595_clear_pin(STEP6_EN); \ + ic74hc595_shift_io_pins() +#define io23_toggle_output \ + ic74hc595_toggle_pin(STEP6_EN); \ + ic74hc595_shift_io_pins() #define io23_get_output ic74hc595_get_pin(STEP6_EN) #define io23_config_input #define io23_config_pullup @@ -663,9 +801,15 @@ extern "C" #define io24_get_input mcu_get_input(STEP7_EN) #elif ASSERT_PIN_EXTENDED(STEP7_EN) #define io24_config_output -#define io24_set_output ic74hc595_set_pin(STEP7_EN);ic74hc595_shift_io_pins() -#define io24_clear_output ic74hc595_clear_pin(STEP7_EN);ic74hc595_shift_io_pins() -#define io24_toggle_output ic74hc595_toggle_pin(STEP7_EN);ic74hc595_shift_io_pins() +#define io24_set_output \ + ic74hc595_set_pin(STEP7_EN); \ + ic74hc595_shift_io_pins() +#define io24_clear_output \ + ic74hc595_clear_pin(STEP7_EN); \ + ic74hc595_shift_io_pins() +#define io24_toggle_output \ + ic74hc595_toggle_pin(STEP7_EN); \ + ic74hc595_shift_io_pins() #define io24_get_output ic74hc595_get_pin(STEP7_EN) #define io24_config_input #define io24_config_pullup @@ -691,9 +835,15 @@ extern "C" #define io25_get_input mcu_get_input(PWM0) #elif ASSERT_PIN_EXTENDED(PWM0) #define io25_config_output -#define io25_set_output ic74hc595_set_pin(PWM0);ic74hc595_shift_io_pins() -#define io25_clear_output ic74hc595_clear_pin(PWM0);ic74hc595_shift_io_pins() -#define io25_toggle_output ic74hc595_toggle_pin(PWM0);ic74hc595_shift_io_pins() +#define io25_set_output \ + ic74hc595_set_pin(PWM0); \ + ic74hc595_shift_io_pins() +#define io25_clear_output \ + ic74hc595_clear_pin(PWM0); \ + ic74hc595_shift_io_pins() +#define io25_toggle_output \ + ic74hc595_toggle_pin(PWM0); \ + ic74hc595_shift_io_pins() #define io25_get_output ic74hc595_get_pin(PWM0) #define io25_config_input #define io25_config_pullup @@ -719,9 +869,15 @@ extern "C" #define io26_get_input mcu_get_input(PWM1) #elif ASSERT_PIN_EXTENDED(PWM1) #define io26_config_output -#define io26_set_output ic74hc595_set_pin(PWM1);ic74hc595_shift_io_pins() -#define io26_clear_output ic74hc595_clear_pin(PWM1);ic74hc595_shift_io_pins() -#define io26_toggle_output ic74hc595_toggle_pin(PWM1);ic74hc595_shift_io_pins() +#define io26_set_output \ + ic74hc595_set_pin(PWM1); \ + ic74hc595_shift_io_pins() +#define io26_clear_output \ + ic74hc595_clear_pin(PWM1); \ + ic74hc595_shift_io_pins() +#define io26_toggle_output \ + ic74hc595_toggle_pin(PWM1); \ + ic74hc595_shift_io_pins() #define io26_get_output ic74hc595_get_pin(PWM1) #define io26_config_input #define io26_config_pullup @@ -747,9 +903,15 @@ extern "C" #define io27_get_input mcu_get_input(PWM2) #elif ASSERT_PIN_EXTENDED(PWM2) #define io27_config_output -#define io27_set_output ic74hc595_set_pin(PWM2);ic74hc595_shift_io_pins() -#define io27_clear_output ic74hc595_clear_pin(PWM2);ic74hc595_shift_io_pins() -#define io27_toggle_output ic74hc595_toggle_pin(PWM2);ic74hc595_shift_io_pins() +#define io27_set_output \ + ic74hc595_set_pin(PWM2); \ + ic74hc595_shift_io_pins() +#define io27_clear_output \ + ic74hc595_clear_pin(PWM2); \ + ic74hc595_shift_io_pins() +#define io27_toggle_output \ + ic74hc595_toggle_pin(PWM2); \ + ic74hc595_shift_io_pins() #define io27_get_output ic74hc595_get_pin(PWM2) #define io27_config_input #define io27_config_pullup @@ -775,9 +937,15 @@ extern "C" #define io28_get_input mcu_get_input(PWM3) #elif ASSERT_PIN_EXTENDED(PWM3) #define io28_config_output -#define io28_set_output ic74hc595_set_pin(PWM3);ic74hc595_shift_io_pins() -#define io28_clear_output ic74hc595_clear_pin(PWM3);ic74hc595_shift_io_pins() -#define io28_toggle_output ic74hc595_toggle_pin(PWM3);ic74hc595_shift_io_pins() +#define io28_set_output \ + ic74hc595_set_pin(PWM3); \ + ic74hc595_shift_io_pins() +#define io28_clear_output \ + ic74hc595_clear_pin(PWM3); \ + ic74hc595_shift_io_pins() +#define io28_toggle_output \ + ic74hc595_toggle_pin(PWM3); \ + ic74hc595_shift_io_pins() #define io28_get_output ic74hc595_get_pin(PWM3) #define io28_config_input #define io28_config_pullup @@ -803,9 +971,15 @@ extern "C" #define io29_get_input mcu_get_input(PWM4) #elif ASSERT_PIN_EXTENDED(PWM4) #define io29_config_output -#define io29_set_output ic74hc595_set_pin(PWM4);ic74hc595_shift_io_pins() -#define io29_clear_output ic74hc595_clear_pin(PWM4);ic74hc595_shift_io_pins() -#define io29_toggle_output ic74hc595_toggle_pin(PWM4);ic74hc595_shift_io_pins() +#define io29_set_output \ + ic74hc595_set_pin(PWM4); \ + ic74hc595_shift_io_pins() +#define io29_clear_output \ + ic74hc595_clear_pin(PWM4); \ + ic74hc595_shift_io_pins() +#define io29_toggle_output \ + ic74hc595_toggle_pin(PWM4); \ + ic74hc595_shift_io_pins() #define io29_get_output ic74hc595_get_pin(PWM4) #define io29_config_input #define io29_config_pullup @@ -831,9 +1005,15 @@ extern "C" #define io30_get_input mcu_get_input(PWM5) #elif ASSERT_PIN_EXTENDED(PWM5) #define io30_config_output -#define io30_set_output ic74hc595_set_pin(PWM5);ic74hc595_shift_io_pins() -#define io30_clear_output ic74hc595_clear_pin(PWM5);ic74hc595_shift_io_pins() -#define io30_toggle_output ic74hc595_toggle_pin(PWM5);ic74hc595_shift_io_pins() +#define io30_set_output \ + ic74hc595_set_pin(PWM5); \ + ic74hc595_shift_io_pins() +#define io30_clear_output \ + ic74hc595_clear_pin(PWM5); \ + ic74hc595_shift_io_pins() +#define io30_toggle_output \ + ic74hc595_toggle_pin(PWM5); \ + ic74hc595_shift_io_pins() #define io30_get_output ic74hc595_get_pin(PWM5) #define io30_config_input #define io30_config_pullup @@ -859,9 +1039,15 @@ extern "C" #define io31_get_input mcu_get_input(PWM6) #elif ASSERT_PIN_EXTENDED(PWM6) #define io31_config_output -#define io31_set_output ic74hc595_set_pin(PWM6);ic74hc595_shift_io_pins() -#define io31_clear_output ic74hc595_clear_pin(PWM6);ic74hc595_shift_io_pins() -#define io31_toggle_output ic74hc595_toggle_pin(PWM6);ic74hc595_shift_io_pins() +#define io31_set_output \ + ic74hc595_set_pin(PWM6); \ + ic74hc595_shift_io_pins() +#define io31_clear_output \ + ic74hc595_clear_pin(PWM6); \ + ic74hc595_shift_io_pins() +#define io31_toggle_output \ + ic74hc595_toggle_pin(PWM6); \ + ic74hc595_shift_io_pins() #define io31_get_output ic74hc595_get_pin(PWM6) #define io31_config_input #define io31_config_pullup @@ -887,9 +1073,15 @@ extern "C" #define io32_get_input mcu_get_input(PWM7) #elif ASSERT_PIN_EXTENDED(PWM7) #define io32_config_output -#define io32_set_output ic74hc595_set_pin(PWM7);ic74hc595_shift_io_pins() -#define io32_clear_output ic74hc595_clear_pin(PWM7);ic74hc595_shift_io_pins() -#define io32_toggle_output ic74hc595_toggle_pin(PWM7);ic74hc595_shift_io_pins() +#define io32_set_output \ + ic74hc595_set_pin(PWM7); \ + ic74hc595_shift_io_pins() +#define io32_clear_output \ + ic74hc595_clear_pin(PWM7); \ + ic74hc595_shift_io_pins() +#define io32_toggle_output \ + ic74hc595_toggle_pin(PWM7); \ + ic74hc595_shift_io_pins() #define io32_get_output ic74hc595_get_pin(PWM7) #define io32_config_input #define io32_config_pullup @@ -915,9 +1107,15 @@ extern "C" #define io33_get_input mcu_get_input(PWM8) #elif ASSERT_PIN_EXTENDED(PWM8) #define io33_config_output -#define io33_set_output ic74hc595_set_pin(PWM8);ic74hc595_shift_io_pins() -#define io33_clear_output ic74hc595_clear_pin(PWM8);ic74hc595_shift_io_pins() -#define io33_toggle_output ic74hc595_toggle_pin(PWM8);ic74hc595_shift_io_pins() +#define io33_set_output \ + ic74hc595_set_pin(PWM8); \ + ic74hc595_shift_io_pins() +#define io33_clear_output \ + ic74hc595_clear_pin(PWM8); \ + ic74hc595_shift_io_pins() +#define io33_toggle_output \ + ic74hc595_toggle_pin(PWM8); \ + ic74hc595_shift_io_pins() #define io33_get_output ic74hc595_get_pin(PWM8) #define io33_config_input #define io33_config_pullup @@ -943,9 +1141,15 @@ extern "C" #define io34_get_input mcu_get_input(PWM9) #elif ASSERT_PIN_EXTENDED(PWM9) #define io34_config_output -#define io34_set_output ic74hc595_set_pin(PWM9);ic74hc595_shift_io_pins() -#define io34_clear_output ic74hc595_clear_pin(PWM9);ic74hc595_shift_io_pins() -#define io34_toggle_output ic74hc595_toggle_pin(PWM9);ic74hc595_shift_io_pins() +#define io34_set_output \ + ic74hc595_set_pin(PWM9); \ + ic74hc595_shift_io_pins() +#define io34_clear_output \ + ic74hc595_clear_pin(PWM9); \ + ic74hc595_shift_io_pins() +#define io34_toggle_output \ + ic74hc595_toggle_pin(PWM9); \ + ic74hc595_shift_io_pins() #define io34_get_output ic74hc595_get_pin(PWM9) #define io34_config_input #define io34_config_pullup @@ -971,9 +1175,15 @@ extern "C" #define io35_get_input mcu_get_input(PWM10) #elif ASSERT_PIN_EXTENDED(PWM10) #define io35_config_output -#define io35_set_output ic74hc595_set_pin(PWM10);ic74hc595_shift_io_pins() -#define io35_clear_output ic74hc595_clear_pin(PWM10);ic74hc595_shift_io_pins() -#define io35_toggle_output ic74hc595_toggle_pin(PWM10);ic74hc595_shift_io_pins() +#define io35_set_output \ + ic74hc595_set_pin(PWM10); \ + ic74hc595_shift_io_pins() +#define io35_clear_output \ + ic74hc595_clear_pin(PWM10); \ + ic74hc595_shift_io_pins() +#define io35_toggle_output \ + ic74hc595_toggle_pin(PWM10); \ + ic74hc595_shift_io_pins() #define io35_get_output ic74hc595_get_pin(PWM10) #define io35_config_input #define io35_config_pullup @@ -999,9 +1209,15 @@ extern "C" #define io36_get_input mcu_get_input(PWM11) #elif ASSERT_PIN_EXTENDED(PWM11) #define io36_config_output -#define io36_set_output ic74hc595_set_pin(PWM11);ic74hc595_shift_io_pins() -#define io36_clear_output ic74hc595_clear_pin(PWM11);ic74hc595_shift_io_pins() -#define io36_toggle_output ic74hc595_toggle_pin(PWM11);ic74hc595_shift_io_pins() +#define io36_set_output \ + ic74hc595_set_pin(PWM11); \ + ic74hc595_shift_io_pins() +#define io36_clear_output \ + ic74hc595_clear_pin(PWM11); \ + ic74hc595_shift_io_pins() +#define io36_toggle_output \ + ic74hc595_toggle_pin(PWM11); \ + ic74hc595_shift_io_pins() #define io36_get_output ic74hc595_get_pin(PWM11) #define io36_config_input #define io36_config_pullup @@ -1027,9 +1243,15 @@ extern "C" #define io37_get_input mcu_get_input(PWM12) #elif ASSERT_PIN_EXTENDED(PWM12) #define io37_config_output -#define io37_set_output ic74hc595_set_pin(PWM12);ic74hc595_shift_io_pins() -#define io37_clear_output ic74hc595_clear_pin(PWM12);ic74hc595_shift_io_pins() -#define io37_toggle_output ic74hc595_toggle_pin(PWM12);ic74hc595_shift_io_pins() +#define io37_set_output \ + ic74hc595_set_pin(PWM12); \ + ic74hc595_shift_io_pins() +#define io37_clear_output \ + ic74hc595_clear_pin(PWM12); \ + ic74hc595_shift_io_pins() +#define io37_toggle_output \ + ic74hc595_toggle_pin(PWM12); \ + ic74hc595_shift_io_pins() #define io37_get_output ic74hc595_get_pin(PWM12) #define io37_config_input #define io37_config_pullup @@ -1055,9 +1277,15 @@ extern "C" #define io38_get_input mcu_get_input(PWM13) #elif ASSERT_PIN_EXTENDED(PWM13) #define io38_config_output -#define io38_set_output ic74hc595_set_pin(PWM13);ic74hc595_shift_io_pins() -#define io38_clear_output ic74hc595_clear_pin(PWM13);ic74hc595_shift_io_pins() -#define io38_toggle_output ic74hc595_toggle_pin(PWM13);ic74hc595_shift_io_pins() +#define io38_set_output \ + ic74hc595_set_pin(PWM13); \ + ic74hc595_shift_io_pins() +#define io38_clear_output \ + ic74hc595_clear_pin(PWM13); \ + ic74hc595_shift_io_pins() +#define io38_toggle_output \ + ic74hc595_toggle_pin(PWM13); \ + ic74hc595_shift_io_pins() #define io38_get_output ic74hc595_get_pin(PWM13) #define io38_config_input #define io38_config_pullup @@ -1083,9 +1311,15 @@ extern "C" #define io39_get_input mcu_get_input(PWM14) #elif ASSERT_PIN_EXTENDED(PWM14) #define io39_config_output -#define io39_set_output ic74hc595_set_pin(PWM14);ic74hc595_shift_io_pins() -#define io39_clear_output ic74hc595_clear_pin(PWM14);ic74hc595_shift_io_pins() -#define io39_toggle_output ic74hc595_toggle_pin(PWM14);ic74hc595_shift_io_pins() +#define io39_set_output \ + ic74hc595_set_pin(PWM14); \ + ic74hc595_shift_io_pins() +#define io39_clear_output \ + ic74hc595_clear_pin(PWM14); \ + ic74hc595_shift_io_pins() +#define io39_toggle_output \ + ic74hc595_toggle_pin(PWM14); \ + ic74hc595_shift_io_pins() #define io39_get_output ic74hc595_get_pin(PWM14) #define io39_config_input #define io39_config_pullup @@ -1111,9 +1345,15 @@ extern "C" #define io40_get_input mcu_get_input(PWM15) #elif ASSERT_PIN_EXTENDED(PWM15) #define io40_config_output -#define io40_set_output ic74hc595_set_pin(PWM15);ic74hc595_shift_io_pins() -#define io40_clear_output ic74hc595_clear_pin(PWM15);ic74hc595_shift_io_pins() -#define io40_toggle_output ic74hc595_toggle_pin(PWM15);ic74hc595_shift_io_pins() +#define io40_set_output \ + ic74hc595_set_pin(PWM15); \ + ic74hc595_shift_io_pins() +#define io40_clear_output \ + ic74hc595_clear_pin(PWM15); \ + ic74hc595_shift_io_pins() +#define io40_toggle_output \ + ic74hc595_toggle_pin(PWM15); \ + ic74hc595_shift_io_pins() #define io40_get_output ic74hc595_get_pin(PWM15) #define io40_config_input #define io40_config_pullup @@ -1139,9 +1379,15 @@ extern "C" #define io41_get_input mcu_get_input(SERVO0) #elif ASSERT_PIN_EXTENDED(SERVO0) #define io41_config_output -#define io41_set_output ic74hc595_set_pin(SERVO0);ic74hc595_shift_io_pins() -#define io41_clear_output ic74hc595_clear_pin(SERVO0);ic74hc595_shift_io_pins() -#define io41_toggle_output ic74hc595_toggle_pin(SERVO0);ic74hc595_shift_io_pins() +#define io41_set_output \ + ic74hc595_set_pin(SERVO0); \ + ic74hc595_shift_io_pins() +#define io41_clear_output \ + ic74hc595_clear_pin(SERVO0); \ + ic74hc595_shift_io_pins() +#define io41_toggle_output \ + ic74hc595_toggle_pin(SERVO0); \ + ic74hc595_shift_io_pins() #define io41_get_output ic74hc595_get_pin(SERVO0) #define io41_config_input #define io41_config_pullup @@ -1167,9 +1413,15 @@ extern "C" #define io42_get_input mcu_get_input(SERVO1) #elif ASSERT_PIN_EXTENDED(SERVO1) #define io42_config_output -#define io42_set_output ic74hc595_set_pin(SERVO1);ic74hc595_shift_io_pins() -#define io42_clear_output ic74hc595_clear_pin(SERVO1);ic74hc595_shift_io_pins() -#define io42_toggle_output ic74hc595_toggle_pin(SERVO1);ic74hc595_shift_io_pins() +#define io42_set_output \ + ic74hc595_set_pin(SERVO1); \ + ic74hc595_shift_io_pins() +#define io42_clear_output \ + ic74hc595_clear_pin(SERVO1); \ + ic74hc595_shift_io_pins() +#define io42_toggle_output \ + ic74hc595_toggle_pin(SERVO1); \ + ic74hc595_shift_io_pins() #define io42_get_output ic74hc595_get_pin(SERVO1) #define io42_config_input #define io42_config_pullup @@ -1195,9 +1447,15 @@ extern "C" #define io43_get_input mcu_get_input(SERVO2) #elif ASSERT_PIN_EXTENDED(SERVO2) #define io43_config_output -#define io43_set_output ic74hc595_set_pin(SERVO2);ic74hc595_shift_io_pins() -#define io43_clear_output ic74hc595_clear_pin(SERVO2);ic74hc595_shift_io_pins() -#define io43_toggle_output ic74hc595_toggle_pin(SERVO2);ic74hc595_shift_io_pins() +#define io43_set_output \ + ic74hc595_set_pin(SERVO2); \ + ic74hc595_shift_io_pins() +#define io43_clear_output \ + ic74hc595_clear_pin(SERVO2); \ + ic74hc595_shift_io_pins() +#define io43_toggle_output \ + ic74hc595_toggle_pin(SERVO2); \ + ic74hc595_shift_io_pins() #define io43_get_output ic74hc595_get_pin(SERVO2) #define io43_config_input #define io43_config_pullup @@ -1223,9 +1481,15 @@ extern "C" #define io44_get_input mcu_get_input(SERVO3) #elif ASSERT_PIN_EXTENDED(SERVO3) #define io44_config_output -#define io44_set_output ic74hc595_set_pin(SERVO3);ic74hc595_shift_io_pins() -#define io44_clear_output ic74hc595_clear_pin(SERVO3);ic74hc595_shift_io_pins() -#define io44_toggle_output ic74hc595_toggle_pin(SERVO3);ic74hc595_shift_io_pins() +#define io44_set_output \ + ic74hc595_set_pin(SERVO3); \ + ic74hc595_shift_io_pins() +#define io44_clear_output \ + ic74hc595_clear_pin(SERVO3); \ + ic74hc595_shift_io_pins() +#define io44_toggle_output \ + ic74hc595_toggle_pin(SERVO3); \ + ic74hc595_shift_io_pins() #define io44_get_output ic74hc595_get_pin(SERVO3) #define io44_config_input #define io44_config_pullup @@ -1251,9 +1515,15 @@ extern "C" #define io45_get_input mcu_get_input(SERVO4) #elif ASSERT_PIN_EXTENDED(SERVO4) #define io45_config_output -#define io45_set_output ic74hc595_set_pin(SERVO4);ic74hc595_shift_io_pins() -#define io45_clear_output ic74hc595_clear_pin(SERVO4);ic74hc595_shift_io_pins() -#define io45_toggle_output ic74hc595_toggle_pin(SERVO4);ic74hc595_shift_io_pins() +#define io45_set_output \ + ic74hc595_set_pin(SERVO4); \ + ic74hc595_shift_io_pins() +#define io45_clear_output \ + ic74hc595_clear_pin(SERVO4); \ + ic74hc595_shift_io_pins() +#define io45_toggle_output \ + ic74hc595_toggle_pin(SERVO4); \ + ic74hc595_shift_io_pins() #define io45_get_output ic74hc595_get_pin(SERVO4) #define io45_config_input #define io45_config_pullup @@ -1279,9 +1549,15 @@ extern "C" #define io46_get_input mcu_get_input(SERVO5) #elif ASSERT_PIN_EXTENDED(SERVO5) #define io46_config_output -#define io46_set_output ic74hc595_set_pin(SERVO5);ic74hc595_shift_io_pins() -#define io46_clear_output ic74hc595_clear_pin(SERVO5);ic74hc595_shift_io_pins() -#define io46_toggle_output ic74hc595_toggle_pin(SERVO5);ic74hc595_shift_io_pins() +#define io46_set_output \ + ic74hc595_set_pin(SERVO5); \ + ic74hc595_shift_io_pins() +#define io46_clear_output \ + ic74hc595_clear_pin(SERVO5); \ + ic74hc595_shift_io_pins() +#define io46_toggle_output \ + ic74hc595_toggle_pin(SERVO5); \ + ic74hc595_shift_io_pins() #define io46_get_output ic74hc595_get_pin(SERVO5) #define io46_config_input #define io46_config_pullup @@ -1307,9 +1583,15 @@ extern "C" #define io47_get_input mcu_get_input(DOUT0) #elif ASSERT_PIN_EXTENDED(DOUT0) #define io47_config_output -#define io47_set_output ic74hc595_set_pin(DOUT0);ic74hc595_shift_io_pins() -#define io47_clear_output ic74hc595_clear_pin(DOUT0);ic74hc595_shift_io_pins() -#define io47_toggle_output ic74hc595_toggle_pin(DOUT0);ic74hc595_shift_io_pins() +#define io47_set_output \ + ic74hc595_set_pin(DOUT0); \ + ic74hc595_shift_io_pins() +#define io47_clear_output \ + ic74hc595_clear_pin(DOUT0); \ + ic74hc595_shift_io_pins() +#define io47_toggle_output \ + ic74hc595_toggle_pin(DOUT0); \ + ic74hc595_shift_io_pins() #define io47_get_output ic74hc595_get_pin(DOUT0) #define io47_config_input #define io47_config_pullup @@ -1335,9 +1617,15 @@ extern "C" #define io48_get_input mcu_get_input(DOUT1) #elif ASSERT_PIN_EXTENDED(DOUT1) #define io48_config_output -#define io48_set_output ic74hc595_set_pin(DOUT1);ic74hc595_shift_io_pins() -#define io48_clear_output ic74hc595_clear_pin(DOUT1);ic74hc595_shift_io_pins() -#define io48_toggle_output ic74hc595_toggle_pin(DOUT1);ic74hc595_shift_io_pins() +#define io48_set_output \ + ic74hc595_set_pin(DOUT1); \ + ic74hc595_shift_io_pins() +#define io48_clear_output \ + ic74hc595_clear_pin(DOUT1); \ + ic74hc595_shift_io_pins() +#define io48_toggle_output \ + ic74hc595_toggle_pin(DOUT1); \ + ic74hc595_shift_io_pins() #define io48_get_output ic74hc595_get_pin(DOUT1) #define io48_config_input #define io48_config_pullup @@ -1363,9 +1651,15 @@ extern "C" #define io49_get_input mcu_get_input(DOUT2) #elif ASSERT_PIN_EXTENDED(DOUT2) #define io49_config_output -#define io49_set_output ic74hc595_set_pin(DOUT2);ic74hc595_shift_io_pins() -#define io49_clear_output ic74hc595_clear_pin(DOUT2);ic74hc595_shift_io_pins() -#define io49_toggle_output ic74hc595_toggle_pin(DOUT2);ic74hc595_shift_io_pins() +#define io49_set_output \ + ic74hc595_set_pin(DOUT2); \ + ic74hc595_shift_io_pins() +#define io49_clear_output \ + ic74hc595_clear_pin(DOUT2); \ + ic74hc595_shift_io_pins() +#define io49_toggle_output \ + ic74hc595_toggle_pin(DOUT2); \ + ic74hc595_shift_io_pins() #define io49_get_output ic74hc595_get_pin(DOUT2) #define io49_config_input #define io49_config_pullup @@ -1391,9 +1685,15 @@ extern "C" #define io50_get_input mcu_get_input(DOUT3) #elif ASSERT_PIN_EXTENDED(DOUT3) #define io50_config_output -#define io50_set_output ic74hc595_set_pin(DOUT3);ic74hc595_shift_io_pins() -#define io50_clear_output ic74hc595_clear_pin(DOUT3);ic74hc595_shift_io_pins() -#define io50_toggle_output ic74hc595_toggle_pin(DOUT3);ic74hc595_shift_io_pins() +#define io50_set_output \ + ic74hc595_set_pin(DOUT3); \ + ic74hc595_shift_io_pins() +#define io50_clear_output \ + ic74hc595_clear_pin(DOUT3); \ + ic74hc595_shift_io_pins() +#define io50_toggle_output \ + ic74hc595_toggle_pin(DOUT3); \ + ic74hc595_shift_io_pins() #define io50_get_output ic74hc595_get_pin(DOUT3) #define io50_config_input #define io50_config_pullup @@ -1419,9 +1719,15 @@ extern "C" #define io51_get_input mcu_get_input(DOUT4) #elif ASSERT_PIN_EXTENDED(DOUT4) #define io51_config_output -#define io51_set_output ic74hc595_set_pin(DOUT4);ic74hc595_shift_io_pins() -#define io51_clear_output ic74hc595_clear_pin(DOUT4);ic74hc595_shift_io_pins() -#define io51_toggle_output ic74hc595_toggle_pin(DOUT4);ic74hc595_shift_io_pins() +#define io51_set_output \ + ic74hc595_set_pin(DOUT4); \ + ic74hc595_shift_io_pins() +#define io51_clear_output \ + ic74hc595_clear_pin(DOUT4); \ + ic74hc595_shift_io_pins() +#define io51_toggle_output \ + ic74hc595_toggle_pin(DOUT4); \ + ic74hc595_shift_io_pins() #define io51_get_output ic74hc595_get_pin(DOUT4) #define io51_config_input #define io51_config_pullup @@ -1447,9 +1753,15 @@ extern "C" #define io52_get_input mcu_get_input(DOUT5) #elif ASSERT_PIN_EXTENDED(DOUT5) #define io52_config_output -#define io52_set_output ic74hc595_set_pin(DOUT5);ic74hc595_shift_io_pins() -#define io52_clear_output ic74hc595_clear_pin(DOUT5);ic74hc595_shift_io_pins() -#define io52_toggle_output ic74hc595_toggle_pin(DOUT5);ic74hc595_shift_io_pins() +#define io52_set_output \ + ic74hc595_set_pin(DOUT5); \ + ic74hc595_shift_io_pins() +#define io52_clear_output \ + ic74hc595_clear_pin(DOUT5); \ + ic74hc595_shift_io_pins() +#define io52_toggle_output \ + ic74hc595_toggle_pin(DOUT5); \ + ic74hc595_shift_io_pins() #define io52_get_output ic74hc595_get_pin(DOUT5) #define io52_config_input #define io52_config_pullup @@ -1475,9 +1787,15 @@ extern "C" #define io53_get_input mcu_get_input(DOUT6) #elif ASSERT_PIN_EXTENDED(DOUT6) #define io53_config_output -#define io53_set_output ic74hc595_set_pin(DOUT6);ic74hc595_shift_io_pins() -#define io53_clear_output ic74hc595_clear_pin(DOUT6);ic74hc595_shift_io_pins() -#define io53_toggle_output ic74hc595_toggle_pin(DOUT6);ic74hc595_shift_io_pins() +#define io53_set_output \ + ic74hc595_set_pin(DOUT6); \ + ic74hc595_shift_io_pins() +#define io53_clear_output \ + ic74hc595_clear_pin(DOUT6); \ + ic74hc595_shift_io_pins() +#define io53_toggle_output \ + ic74hc595_toggle_pin(DOUT6); \ + ic74hc595_shift_io_pins() #define io53_get_output ic74hc595_get_pin(DOUT6) #define io53_config_input #define io53_config_pullup @@ -1503,9 +1821,15 @@ extern "C" #define io54_get_input mcu_get_input(DOUT7) #elif ASSERT_PIN_EXTENDED(DOUT7) #define io54_config_output -#define io54_set_output ic74hc595_set_pin(DOUT7);ic74hc595_shift_io_pins() -#define io54_clear_output ic74hc595_clear_pin(DOUT7);ic74hc595_shift_io_pins() -#define io54_toggle_output ic74hc595_toggle_pin(DOUT7);ic74hc595_shift_io_pins() +#define io54_set_output \ + ic74hc595_set_pin(DOUT7); \ + ic74hc595_shift_io_pins() +#define io54_clear_output \ + ic74hc595_clear_pin(DOUT7); \ + ic74hc595_shift_io_pins() +#define io54_toggle_output \ + ic74hc595_toggle_pin(DOUT7); \ + ic74hc595_shift_io_pins() #define io54_get_output ic74hc595_get_pin(DOUT7) #define io54_config_input #define io54_config_pullup @@ -1531,9 +1855,15 @@ extern "C" #define io55_get_input mcu_get_input(DOUT8) #elif ASSERT_PIN_EXTENDED(DOUT8) #define io55_config_output -#define io55_set_output ic74hc595_set_pin(DOUT8);ic74hc595_shift_io_pins() -#define io55_clear_output ic74hc595_clear_pin(DOUT8);ic74hc595_shift_io_pins() -#define io55_toggle_output ic74hc595_toggle_pin(DOUT8);ic74hc595_shift_io_pins() +#define io55_set_output \ + ic74hc595_set_pin(DOUT8); \ + ic74hc595_shift_io_pins() +#define io55_clear_output \ + ic74hc595_clear_pin(DOUT8); \ + ic74hc595_shift_io_pins() +#define io55_toggle_output \ + ic74hc595_toggle_pin(DOUT8); \ + ic74hc595_shift_io_pins() #define io55_get_output ic74hc595_get_pin(DOUT8) #define io55_config_input #define io55_config_pullup @@ -1559,9 +1889,15 @@ extern "C" #define io56_get_input mcu_get_input(DOUT9) #elif ASSERT_PIN_EXTENDED(DOUT9) #define io56_config_output -#define io56_set_output ic74hc595_set_pin(DOUT9);ic74hc595_shift_io_pins() -#define io56_clear_output ic74hc595_clear_pin(DOUT9);ic74hc595_shift_io_pins() -#define io56_toggle_output ic74hc595_toggle_pin(DOUT9);ic74hc595_shift_io_pins() +#define io56_set_output \ + ic74hc595_set_pin(DOUT9); \ + ic74hc595_shift_io_pins() +#define io56_clear_output \ + ic74hc595_clear_pin(DOUT9); \ + ic74hc595_shift_io_pins() +#define io56_toggle_output \ + ic74hc595_toggle_pin(DOUT9); \ + ic74hc595_shift_io_pins() #define io56_get_output ic74hc595_get_pin(DOUT9) #define io56_config_input #define io56_config_pullup @@ -1587,9 +1923,15 @@ extern "C" #define io57_get_input mcu_get_input(DOUT10) #elif ASSERT_PIN_EXTENDED(DOUT10) #define io57_config_output -#define io57_set_output ic74hc595_set_pin(DOUT10);ic74hc595_shift_io_pins() -#define io57_clear_output ic74hc595_clear_pin(DOUT10);ic74hc595_shift_io_pins() -#define io57_toggle_output ic74hc595_toggle_pin(DOUT10);ic74hc595_shift_io_pins() +#define io57_set_output \ + ic74hc595_set_pin(DOUT10); \ + ic74hc595_shift_io_pins() +#define io57_clear_output \ + ic74hc595_clear_pin(DOUT10); \ + ic74hc595_shift_io_pins() +#define io57_toggle_output \ + ic74hc595_toggle_pin(DOUT10); \ + ic74hc595_shift_io_pins() #define io57_get_output ic74hc595_get_pin(DOUT10) #define io57_config_input #define io57_config_pullup @@ -1615,9 +1957,15 @@ extern "C" #define io58_get_input mcu_get_input(DOUT11) #elif ASSERT_PIN_EXTENDED(DOUT11) #define io58_config_output -#define io58_set_output ic74hc595_set_pin(DOUT11);ic74hc595_shift_io_pins() -#define io58_clear_output ic74hc595_clear_pin(DOUT11);ic74hc595_shift_io_pins() -#define io58_toggle_output ic74hc595_toggle_pin(DOUT11);ic74hc595_shift_io_pins() +#define io58_set_output \ + ic74hc595_set_pin(DOUT11); \ + ic74hc595_shift_io_pins() +#define io58_clear_output \ + ic74hc595_clear_pin(DOUT11); \ + ic74hc595_shift_io_pins() +#define io58_toggle_output \ + ic74hc595_toggle_pin(DOUT11); \ + ic74hc595_shift_io_pins() #define io58_get_output ic74hc595_get_pin(DOUT11) #define io58_config_input #define io58_config_pullup @@ -1643,9 +1991,15 @@ extern "C" #define io59_get_input mcu_get_input(DOUT12) #elif ASSERT_PIN_EXTENDED(DOUT12) #define io59_config_output -#define io59_set_output ic74hc595_set_pin(DOUT12);ic74hc595_shift_io_pins() -#define io59_clear_output ic74hc595_clear_pin(DOUT12);ic74hc595_shift_io_pins() -#define io59_toggle_output ic74hc595_toggle_pin(DOUT12);ic74hc595_shift_io_pins() +#define io59_set_output \ + ic74hc595_set_pin(DOUT12); \ + ic74hc595_shift_io_pins() +#define io59_clear_output \ + ic74hc595_clear_pin(DOUT12); \ + ic74hc595_shift_io_pins() +#define io59_toggle_output \ + ic74hc595_toggle_pin(DOUT12); \ + ic74hc595_shift_io_pins() #define io59_get_output ic74hc595_get_pin(DOUT12) #define io59_config_input #define io59_config_pullup @@ -1671,9 +2025,15 @@ extern "C" #define io60_get_input mcu_get_input(DOUT13) #elif ASSERT_PIN_EXTENDED(DOUT13) #define io60_config_output -#define io60_set_output ic74hc595_set_pin(DOUT13);ic74hc595_shift_io_pins() -#define io60_clear_output ic74hc595_clear_pin(DOUT13);ic74hc595_shift_io_pins() -#define io60_toggle_output ic74hc595_toggle_pin(DOUT13);ic74hc595_shift_io_pins() +#define io60_set_output \ + ic74hc595_set_pin(DOUT13); \ + ic74hc595_shift_io_pins() +#define io60_clear_output \ + ic74hc595_clear_pin(DOUT13); \ + ic74hc595_shift_io_pins() +#define io60_toggle_output \ + ic74hc595_toggle_pin(DOUT13); \ + ic74hc595_shift_io_pins() #define io60_get_output ic74hc595_get_pin(DOUT13) #define io60_config_input #define io60_config_pullup @@ -1699,9 +2059,15 @@ extern "C" #define io61_get_input mcu_get_input(DOUT14) #elif ASSERT_PIN_EXTENDED(DOUT14) #define io61_config_output -#define io61_set_output ic74hc595_set_pin(DOUT14);ic74hc595_shift_io_pins() -#define io61_clear_output ic74hc595_clear_pin(DOUT14);ic74hc595_shift_io_pins() -#define io61_toggle_output ic74hc595_toggle_pin(DOUT14);ic74hc595_shift_io_pins() +#define io61_set_output \ + ic74hc595_set_pin(DOUT14); \ + ic74hc595_shift_io_pins() +#define io61_clear_output \ + ic74hc595_clear_pin(DOUT14); \ + ic74hc595_shift_io_pins() +#define io61_toggle_output \ + ic74hc595_toggle_pin(DOUT14); \ + ic74hc595_shift_io_pins() #define io61_get_output ic74hc595_get_pin(DOUT14) #define io61_config_input #define io61_config_pullup @@ -1727,9 +2093,15 @@ extern "C" #define io62_get_input mcu_get_input(DOUT15) #elif ASSERT_PIN_EXTENDED(DOUT15) #define io62_config_output -#define io62_set_output ic74hc595_set_pin(DOUT15);ic74hc595_shift_io_pins() -#define io62_clear_output ic74hc595_clear_pin(DOUT15);ic74hc595_shift_io_pins() -#define io62_toggle_output ic74hc595_toggle_pin(DOUT15);ic74hc595_shift_io_pins() +#define io62_set_output \ + ic74hc595_set_pin(DOUT15); \ + ic74hc595_shift_io_pins() +#define io62_clear_output \ + ic74hc595_clear_pin(DOUT15); \ + ic74hc595_shift_io_pins() +#define io62_toggle_output \ + ic74hc595_toggle_pin(DOUT15); \ + ic74hc595_shift_io_pins() #define io62_get_output ic74hc595_get_pin(DOUT15) #define io62_config_input #define io62_config_pullup @@ -1755,9 +2127,15 @@ extern "C" #define io63_get_input mcu_get_input(DOUT16) #elif ASSERT_PIN_EXTENDED(DOUT16) #define io63_config_output -#define io63_set_output ic74hc595_set_pin(DOUT16);ic74hc595_shift_io_pins() -#define io63_clear_output ic74hc595_clear_pin(DOUT16);ic74hc595_shift_io_pins() -#define io63_toggle_output ic74hc595_toggle_pin(DOUT16);ic74hc595_shift_io_pins() +#define io63_set_output \ + ic74hc595_set_pin(DOUT16); \ + ic74hc595_shift_io_pins() +#define io63_clear_output \ + ic74hc595_clear_pin(DOUT16); \ + ic74hc595_shift_io_pins() +#define io63_toggle_output \ + ic74hc595_toggle_pin(DOUT16); \ + ic74hc595_shift_io_pins() #define io63_get_output ic74hc595_get_pin(DOUT16) #define io63_config_input #define io63_config_pullup @@ -1783,9 +2161,15 @@ extern "C" #define io64_get_input mcu_get_input(DOUT17) #elif ASSERT_PIN_EXTENDED(DOUT17) #define io64_config_output -#define io64_set_output ic74hc595_set_pin(DOUT17);ic74hc595_shift_io_pins() -#define io64_clear_output ic74hc595_clear_pin(DOUT17);ic74hc595_shift_io_pins() -#define io64_toggle_output ic74hc595_toggle_pin(DOUT17);ic74hc595_shift_io_pins() +#define io64_set_output \ + ic74hc595_set_pin(DOUT17); \ + ic74hc595_shift_io_pins() +#define io64_clear_output \ + ic74hc595_clear_pin(DOUT17); \ + ic74hc595_shift_io_pins() +#define io64_toggle_output \ + ic74hc595_toggle_pin(DOUT17); \ + ic74hc595_shift_io_pins() #define io64_get_output ic74hc595_get_pin(DOUT17) #define io64_config_input #define io64_config_pullup @@ -1811,9 +2195,15 @@ extern "C" #define io65_get_input mcu_get_input(DOUT18) #elif ASSERT_PIN_EXTENDED(DOUT18) #define io65_config_output -#define io65_set_output ic74hc595_set_pin(DOUT18);ic74hc595_shift_io_pins() -#define io65_clear_output ic74hc595_clear_pin(DOUT18);ic74hc595_shift_io_pins() -#define io65_toggle_output ic74hc595_toggle_pin(DOUT18);ic74hc595_shift_io_pins() +#define io65_set_output \ + ic74hc595_set_pin(DOUT18); \ + ic74hc595_shift_io_pins() +#define io65_clear_output \ + ic74hc595_clear_pin(DOUT18); \ + ic74hc595_shift_io_pins() +#define io65_toggle_output \ + ic74hc595_toggle_pin(DOUT18); \ + ic74hc595_shift_io_pins() #define io65_get_output ic74hc595_get_pin(DOUT18) #define io65_config_input #define io65_config_pullup @@ -1839,9 +2229,15 @@ extern "C" #define io66_get_input mcu_get_input(DOUT19) #elif ASSERT_PIN_EXTENDED(DOUT19) #define io66_config_output -#define io66_set_output ic74hc595_set_pin(DOUT19);ic74hc595_shift_io_pins() -#define io66_clear_output ic74hc595_clear_pin(DOUT19);ic74hc595_shift_io_pins() -#define io66_toggle_output ic74hc595_toggle_pin(DOUT19);ic74hc595_shift_io_pins() +#define io66_set_output \ + ic74hc595_set_pin(DOUT19); \ + ic74hc595_shift_io_pins() +#define io66_clear_output \ + ic74hc595_clear_pin(DOUT19); \ + ic74hc595_shift_io_pins() +#define io66_toggle_output \ + ic74hc595_toggle_pin(DOUT19); \ + ic74hc595_shift_io_pins() #define io66_get_output ic74hc595_get_pin(DOUT19) #define io66_config_input #define io66_config_pullup @@ -1867,9 +2263,15 @@ extern "C" #define io67_get_input mcu_get_input(DOUT20) #elif ASSERT_PIN_EXTENDED(DOUT20) #define io67_config_output -#define io67_set_output ic74hc595_set_pin(DOUT20);ic74hc595_shift_io_pins() -#define io67_clear_output ic74hc595_clear_pin(DOUT20);ic74hc595_shift_io_pins() -#define io67_toggle_output ic74hc595_toggle_pin(DOUT20);ic74hc595_shift_io_pins() +#define io67_set_output \ + ic74hc595_set_pin(DOUT20); \ + ic74hc595_shift_io_pins() +#define io67_clear_output \ + ic74hc595_clear_pin(DOUT20); \ + ic74hc595_shift_io_pins() +#define io67_toggle_output \ + ic74hc595_toggle_pin(DOUT20); \ + ic74hc595_shift_io_pins() #define io67_get_output ic74hc595_get_pin(DOUT20) #define io67_config_input #define io67_config_pullup @@ -1895,9 +2297,15 @@ extern "C" #define io68_get_input mcu_get_input(DOUT21) #elif ASSERT_PIN_EXTENDED(DOUT21) #define io68_config_output -#define io68_set_output ic74hc595_set_pin(DOUT21);ic74hc595_shift_io_pins() -#define io68_clear_output ic74hc595_clear_pin(DOUT21);ic74hc595_shift_io_pins() -#define io68_toggle_output ic74hc595_toggle_pin(DOUT21);ic74hc595_shift_io_pins() +#define io68_set_output \ + ic74hc595_set_pin(DOUT21); \ + ic74hc595_shift_io_pins() +#define io68_clear_output \ + ic74hc595_clear_pin(DOUT21); \ + ic74hc595_shift_io_pins() +#define io68_toggle_output \ + ic74hc595_toggle_pin(DOUT21); \ + ic74hc595_shift_io_pins() #define io68_get_output ic74hc595_get_pin(DOUT21) #define io68_config_input #define io68_config_pullup @@ -1923,9 +2331,15 @@ extern "C" #define io69_get_input mcu_get_input(DOUT22) #elif ASSERT_PIN_EXTENDED(DOUT22) #define io69_config_output -#define io69_set_output ic74hc595_set_pin(DOUT22);ic74hc595_shift_io_pins() -#define io69_clear_output ic74hc595_clear_pin(DOUT22);ic74hc595_shift_io_pins() -#define io69_toggle_output ic74hc595_toggle_pin(DOUT22);ic74hc595_shift_io_pins() +#define io69_set_output \ + ic74hc595_set_pin(DOUT22); \ + ic74hc595_shift_io_pins() +#define io69_clear_output \ + ic74hc595_clear_pin(DOUT22); \ + ic74hc595_shift_io_pins() +#define io69_toggle_output \ + ic74hc595_toggle_pin(DOUT22); \ + ic74hc595_shift_io_pins() #define io69_get_output ic74hc595_get_pin(DOUT22) #define io69_config_input #define io69_config_pullup @@ -1951,9 +2365,15 @@ extern "C" #define io70_get_input mcu_get_input(DOUT23) #elif ASSERT_PIN_EXTENDED(DOUT23) #define io70_config_output -#define io70_set_output ic74hc595_set_pin(DOUT23);ic74hc595_shift_io_pins() -#define io70_clear_output ic74hc595_clear_pin(DOUT23);ic74hc595_shift_io_pins() -#define io70_toggle_output ic74hc595_toggle_pin(DOUT23);ic74hc595_shift_io_pins() +#define io70_set_output \ + ic74hc595_set_pin(DOUT23); \ + ic74hc595_shift_io_pins() +#define io70_clear_output \ + ic74hc595_clear_pin(DOUT23); \ + ic74hc595_shift_io_pins() +#define io70_toggle_output \ + ic74hc595_toggle_pin(DOUT23); \ + ic74hc595_shift_io_pins() #define io70_get_output ic74hc595_get_pin(DOUT23) #define io70_config_input #define io70_config_pullup @@ -1979,9 +2399,15 @@ extern "C" #define io71_get_input mcu_get_input(DOUT24) #elif ASSERT_PIN_EXTENDED(DOUT24) #define io71_config_output -#define io71_set_output ic74hc595_set_pin(DOUT24);ic74hc595_shift_io_pins() -#define io71_clear_output ic74hc595_clear_pin(DOUT24);ic74hc595_shift_io_pins() -#define io71_toggle_output ic74hc595_toggle_pin(DOUT24);ic74hc595_shift_io_pins() +#define io71_set_output \ + ic74hc595_set_pin(DOUT24); \ + ic74hc595_shift_io_pins() +#define io71_clear_output \ + ic74hc595_clear_pin(DOUT24); \ + ic74hc595_shift_io_pins() +#define io71_toggle_output \ + ic74hc595_toggle_pin(DOUT24); \ + ic74hc595_shift_io_pins() #define io71_get_output ic74hc595_get_pin(DOUT24) #define io71_config_input #define io71_config_pullup @@ -2007,9 +2433,15 @@ extern "C" #define io72_get_input mcu_get_input(DOUT25) #elif ASSERT_PIN_EXTENDED(DOUT25) #define io72_config_output -#define io72_set_output ic74hc595_set_pin(DOUT25);ic74hc595_shift_io_pins() -#define io72_clear_output ic74hc595_clear_pin(DOUT25);ic74hc595_shift_io_pins() -#define io72_toggle_output ic74hc595_toggle_pin(DOUT25);ic74hc595_shift_io_pins() +#define io72_set_output \ + ic74hc595_set_pin(DOUT25); \ + ic74hc595_shift_io_pins() +#define io72_clear_output \ + ic74hc595_clear_pin(DOUT25); \ + ic74hc595_shift_io_pins() +#define io72_toggle_output \ + ic74hc595_toggle_pin(DOUT25); \ + ic74hc595_shift_io_pins() #define io72_get_output ic74hc595_get_pin(DOUT25) #define io72_config_input #define io72_config_pullup @@ -2035,9 +2467,15 @@ extern "C" #define io73_get_input mcu_get_input(DOUT26) #elif ASSERT_PIN_EXTENDED(DOUT26) #define io73_config_output -#define io73_set_output ic74hc595_set_pin(DOUT26);ic74hc595_shift_io_pins() -#define io73_clear_output ic74hc595_clear_pin(DOUT26);ic74hc595_shift_io_pins() -#define io73_toggle_output ic74hc595_toggle_pin(DOUT26);ic74hc595_shift_io_pins() +#define io73_set_output \ + ic74hc595_set_pin(DOUT26); \ + ic74hc595_shift_io_pins() +#define io73_clear_output \ + ic74hc595_clear_pin(DOUT26); \ + ic74hc595_shift_io_pins() +#define io73_toggle_output \ + ic74hc595_toggle_pin(DOUT26); \ + ic74hc595_shift_io_pins() #define io73_get_output ic74hc595_get_pin(DOUT26) #define io73_config_input #define io73_config_pullup @@ -2063,9 +2501,15 @@ extern "C" #define io74_get_input mcu_get_input(DOUT27) #elif ASSERT_PIN_EXTENDED(DOUT27) #define io74_config_output -#define io74_set_output ic74hc595_set_pin(DOUT27);ic74hc595_shift_io_pins() -#define io74_clear_output ic74hc595_clear_pin(DOUT27);ic74hc595_shift_io_pins() -#define io74_toggle_output ic74hc595_toggle_pin(DOUT27);ic74hc595_shift_io_pins() +#define io74_set_output \ + ic74hc595_set_pin(DOUT27); \ + ic74hc595_shift_io_pins() +#define io74_clear_output \ + ic74hc595_clear_pin(DOUT27); \ + ic74hc595_shift_io_pins() +#define io74_toggle_output \ + ic74hc595_toggle_pin(DOUT27); \ + ic74hc595_shift_io_pins() #define io74_get_output ic74hc595_get_pin(DOUT27) #define io74_config_input #define io74_config_pullup @@ -2091,9 +2535,15 @@ extern "C" #define io75_get_input mcu_get_input(DOUT28) #elif ASSERT_PIN_EXTENDED(DOUT28) #define io75_config_output -#define io75_set_output ic74hc595_set_pin(DOUT28);ic74hc595_shift_io_pins() -#define io75_clear_output ic74hc595_clear_pin(DOUT28);ic74hc595_shift_io_pins() -#define io75_toggle_output ic74hc595_toggle_pin(DOUT28);ic74hc595_shift_io_pins() +#define io75_set_output \ + ic74hc595_set_pin(DOUT28); \ + ic74hc595_shift_io_pins() +#define io75_clear_output \ + ic74hc595_clear_pin(DOUT28); \ + ic74hc595_shift_io_pins() +#define io75_toggle_output \ + ic74hc595_toggle_pin(DOUT28); \ + ic74hc595_shift_io_pins() #define io75_get_output ic74hc595_get_pin(DOUT28) #define io75_config_input #define io75_config_pullup @@ -2119,9 +2569,15 @@ extern "C" #define io76_get_input mcu_get_input(DOUT29) #elif ASSERT_PIN_EXTENDED(DOUT29) #define io76_config_output -#define io76_set_output ic74hc595_set_pin(DOUT29);ic74hc595_shift_io_pins() -#define io76_clear_output ic74hc595_clear_pin(DOUT29);ic74hc595_shift_io_pins() -#define io76_toggle_output ic74hc595_toggle_pin(DOUT29);ic74hc595_shift_io_pins() +#define io76_set_output \ + ic74hc595_set_pin(DOUT29); \ + ic74hc595_shift_io_pins() +#define io76_clear_output \ + ic74hc595_clear_pin(DOUT29); \ + ic74hc595_shift_io_pins() +#define io76_toggle_output \ + ic74hc595_toggle_pin(DOUT29); \ + ic74hc595_shift_io_pins() #define io76_get_output ic74hc595_get_pin(DOUT29) #define io76_config_input #define io76_config_pullup @@ -2147,9 +2603,15 @@ extern "C" #define io77_get_input mcu_get_input(DOUT30) #elif ASSERT_PIN_EXTENDED(DOUT30) #define io77_config_output -#define io77_set_output ic74hc595_set_pin(DOUT30);ic74hc595_shift_io_pins() -#define io77_clear_output ic74hc595_clear_pin(DOUT30);ic74hc595_shift_io_pins() -#define io77_toggle_output ic74hc595_toggle_pin(DOUT30);ic74hc595_shift_io_pins() +#define io77_set_output \ + ic74hc595_set_pin(DOUT30); \ + ic74hc595_shift_io_pins() +#define io77_clear_output \ + ic74hc595_clear_pin(DOUT30); \ + ic74hc595_shift_io_pins() +#define io77_toggle_output \ + ic74hc595_toggle_pin(DOUT30); \ + ic74hc595_shift_io_pins() #define io77_get_output ic74hc595_get_pin(DOUT30) #define io77_config_input #define io77_config_pullup @@ -2175,9 +2637,15 @@ extern "C" #define io78_get_input mcu_get_input(DOUT31) #elif ASSERT_PIN_EXTENDED(DOUT31) #define io78_config_output -#define io78_set_output ic74hc595_set_pin(DOUT31);ic74hc595_shift_io_pins() -#define io78_clear_output ic74hc595_clear_pin(DOUT31);ic74hc595_shift_io_pins() -#define io78_toggle_output ic74hc595_toggle_pin(DOUT31);ic74hc595_shift_io_pins() +#define io78_set_output \ + ic74hc595_set_pin(DOUT31); \ + ic74hc595_shift_io_pins() +#define io78_clear_output \ + ic74hc595_clear_pin(DOUT31); \ + ic74hc595_shift_io_pins() +#define io78_toggle_output \ + ic74hc595_toggle_pin(DOUT31); \ + ic74hc595_shift_io_pins() #define io78_get_output ic74hc595_get_pin(DOUT31) #define io78_config_input #define io78_config_pullup @@ -2203,9 +2671,15 @@ extern "C" #define io100_get_input mcu_get_input(LIMIT_X) #elif ASSERT_PIN_EXTENDED(LIMIT_X) #define io100_config_output -#define io100_set_output ic74hc595_set_pin(LIMIT_X);ic74hc595_shift_io_pins() -#define io100_clear_output ic74hc595_clear_pin(LIMIT_X);ic74hc595_shift_io_pins() -#define io100_toggle_output ic74hc595_toggle_pin(LIMIT_X);ic74hc595_shift_io_pins() +#define io100_set_output \ + ic74hc595_set_pin(LIMIT_X); \ + ic74hc595_shift_io_pins() +#define io100_clear_output \ + ic74hc595_clear_pin(LIMIT_X); \ + ic74hc595_shift_io_pins() +#define io100_toggle_output \ + ic74hc595_toggle_pin(LIMIT_X); \ + ic74hc595_shift_io_pins() #define io100_get_output ic74hc595_get_pin(LIMIT_X) #define io100_config_input #define io100_config_pullup @@ -2231,9 +2705,15 @@ extern "C" #define io101_get_input mcu_get_input(LIMIT_Y) #elif ASSERT_PIN_EXTENDED(LIMIT_Y) #define io101_config_output -#define io101_set_output ic74hc595_set_pin(LIMIT_Y);ic74hc595_shift_io_pins() -#define io101_clear_output ic74hc595_clear_pin(LIMIT_Y);ic74hc595_shift_io_pins() -#define io101_toggle_output ic74hc595_toggle_pin(LIMIT_Y);ic74hc595_shift_io_pins() +#define io101_set_output \ + ic74hc595_set_pin(LIMIT_Y); \ + ic74hc595_shift_io_pins() +#define io101_clear_output \ + ic74hc595_clear_pin(LIMIT_Y); \ + ic74hc595_shift_io_pins() +#define io101_toggle_output \ + ic74hc595_toggle_pin(LIMIT_Y); \ + ic74hc595_shift_io_pins() #define io101_get_output ic74hc595_get_pin(LIMIT_Y) #define io101_config_input #define io101_config_pullup @@ -2259,9 +2739,15 @@ extern "C" #define io102_get_input mcu_get_input(LIMIT_Z) #elif ASSERT_PIN_EXTENDED(LIMIT_Z) #define io102_config_output -#define io102_set_output ic74hc595_set_pin(LIMIT_Z);ic74hc595_shift_io_pins() -#define io102_clear_output ic74hc595_clear_pin(LIMIT_Z);ic74hc595_shift_io_pins() -#define io102_toggle_output ic74hc595_toggle_pin(LIMIT_Z);ic74hc595_shift_io_pins() +#define io102_set_output \ + ic74hc595_set_pin(LIMIT_Z); \ + ic74hc595_shift_io_pins() +#define io102_clear_output \ + ic74hc595_clear_pin(LIMIT_Z); \ + ic74hc595_shift_io_pins() +#define io102_toggle_output \ + ic74hc595_toggle_pin(LIMIT_Z); \ + ic74hc595_shift_io_pins() #define io102_get_output ic74hc595_get_pin(LIMIT_Z) #define io102_config_input #define io102_config_pullup @@ -2287,9 +2773,15 @@ extern "C" #define io103_get_input mcu_get_input(LIMIT_X2) #elif ASSERT_PIN_EXTENDED(LIMIT_X2) #define io103_config_output -#define io103_set_output ic74hc595_set_pin(LIMIT_X2);ic74hc595_shift_io_pins() -#define io103_clear_output ic74hc595_clear_pin(LIMIT_X2);ic74hc595_shift_io_pins() -#define io103_toggle_output ic74hc595_toggle_pin(LIMIT_X2);ic74hc595_shift_io_pins() +#define io103_set_output \ + ic74hc595_set_pin(LIMIT_X2); \ + ic74hc595_shift_io_pins() +#define io103_clear_output \ + ic74hc595_clear_pin(LIMIT_X2); \ + ic74hc595_shift_io_pins() +#define io103_toggle_output \ + ic74hc595_toggle_pin(LIMIT_X2); \ + ic74hc595_shift_io_pins() #define io103_get_output ic74hc595_get_pin(LIMIT_X2) #define io103_config_input #define io103_config_pullup @@ -2315,9 +2807,15 @@ extern "C" #define io104_get_input mcu_get_input(LIMIT_Y2) #elif ASSERT_PIN_EXTENDED(LIMIT_Y2) #define io104_config_output -#define io104_set_output ic74hc595_set_pin(LIMIT_Y2);ic74hc595_shift_io_pins() -#define io104_clear_output ic74hc595_clear_pin(LIMIT_Y2);ic74hc595_shift_io_pins() -#define io104_toggle_output ic74hc595_toggle_pin(LIMIT_Y2);ic74hc595_shift_io_pins() +#define io104_set_output \ + ic74hc595_set_pin(LIMIT_Y2); \ + ic74hc595_shift_io_pins() +#define io104_clear_output \ + ic74hc595_clear_pin(LIMIT_Y2); \ + ic74hc595_shift_io_pins() +#define io104_toggle_output \ + ic74hc595_toggle_pin(LIMIT_Y2); \ + ic74hc595_shift_io_pins() #define io104_get_output ic74hc595_get_pin(LIMIT_Y2) #define io104_config_input #define io104_config_pullup @@ -2343,9 +2841,15 @@ extern "C" #define io105_get_input mcu_get_input(LIMIT_Z2) #elif ASSERT_PIN_EXTENDED(LIMIT_Z2) #define io105_config_output -#define io105_set_output ic74hc595_set_pin(LIMIT_Z2);ic74hc595_shift_io_pins() -#define io105_clear_output ic74hc595_clear_pin(LIMIT_Z2);ic74hc595_shift_io_pins() -#define io105_toggle_output ic74hc595_toggle_pin(LIMIT_Z2);ic74hc595_shift_io_pins() +#define io105_set_output \ + ic74hc595_set_pin(LIMIT_Z2); \ + ic74hc595_shift_io_pins() +#define io105_clear_output \ + ic74hc595_clear_pin(LIMIT_Z2); \ + ic74hc595_shift_io_pins() +#define io105_toggle_output \ + ic74hc595_toggle_pin(LIMIT_Z2); \ + ic74hc595_shift_io_pins() #define io105_get_output ic74hc595_get_pin(LIMIT_Z2) #define io105_config_input #define io105_config_pullup @@ -2371,9 +2875,15 @@ extern "C" #define io106_get_input mcu_get_input(LIMIT_A) #elif ASSERT_PIN_EXTENDED(LIMIT_A) #define io106_config_output -#define io106_set_output ic74hc595_set_pin(LIMIT_A);ic74hc595_shift_io_pins() -#define io106_clear_output ic74hc595_clear_pin(LIMIT_A);ic74hc595_shift_io_pins() -#define io106_toggle_output ic74hc595_toggle_pin(LIMIT_A);ic74hc595_shift_io_pins() +#define io106_set_output \ + ic74hc595_set_pin(LIMIT_A); \ + ic74hc595_shift_io_pins() +#define io106_clear_output \ + ic74hc595_clear_pin(LIMIT_A); \ + ic74hc595_shift_io_pins() +#define io106_toggle_output \ + ic74hc595_toggle_pin(LIMIT_A); \ + ic74hc595_shift_io_pins() #define io106_get_output ic74hc595_get_pin(LIMIT_A) #define io106_config_input #define io106_config_pullup @@ -2399,9 +2909,15 @@ extern "C" #define io107_get_input mcu_get_input(LIMIT_B) #elif ASSERT_PIN_EXTENDED(LIMIT_B) #define io107_config_output -#define io107_set_output ic74hc595_set_pin(LIMIT_B);ic74hc595_shift_io_pins() -#define io107_clear_output ic74hc595_clear_pin(LIMIT_B);ic74hc595_shift_io_pins() -#define io107_toggle_output ic74hc595_toggle_pin(LIMIT_B);ic74hc595_shift_io_pins() +#define io107_set_output \ + ic74hc595_set_pin(LIMIT_B); \ + ic74hc595_shift_io_pins() +#define io107_clear_output \ + ic74hc595_clear_pin(LIMIT_B); \ + ic74hc595_shift_io_pins() +#define io107_toggle_output \ + ic74hc595_toggle_pin(LIMIT_B); \ + ic74hc595_shift_io_pins() #define io107_get_output ic74hc595_get_pin(LIMIT_B) #define io107_config_input #define io107_config_pullup @@ -2427,9 +2943,15 @@ extern "C" #define io108_get_input mcu_get_input(LIMIT_C) #elif ASSERT_PIN_EXTENDED(LIMIT_C) #define io108_config_output -#define io108_set_output ic74hc595_set_pin(LIMIT_C);ic74hc595_shift_io_pins() -#define io108_clear_output ic74hc595_clear_pin(LIMIT_C);ic74hc595_shift_io_pins() -#define io108_toggle_output ic74hc595_toggle_pin(LIMIT_C);ic74hc595_shift_io_pins() +#define io108_set_output \ + ic74hc595_set_pin(LIMIT_C); \ + ic74hc595_shift_io_pins() +#define io108_clear_output \ + ic74hc595_clear_pin(LIMIT_C); \ + ic74hc595_shift_io_pins() +#define io108_toggle_output \ + ic74hc595_toggle_pin(LIMIT_C); \ + ic74hc595_shift_io_pins() #define io108_get_output ic74hc595_get_pin(LIMIT_C) #define io108_config_input #define io108_config_pullup @@ -2455,9 +2977,15 @@ extern "C" #define io109_get_input mcu_get_input(PROBE) #elif ASSERT_PIN_EXTENDED(PROBE) #define io109_config_output -#define io109_set_output ic74hc595_set_pin(PROBE);ic74hc595_shift_io_pins() -#define io109_clear_output ic74hc595_clear_pin(PROBE);ic74hc595_shift_io_pins() -#define io109_toggle_output ic74hc595_toggle_pin(PROBE);ic74hc595_shift_io_pins() +#define io109_set_output \ + ic74hc595_set_pin(PROBE); \ + ic74hc595_shift_io_pins() +#define io109_clear_output \ + ic74hc595_clear_pin(PROBE); \ + ic74hc595_shift_io_pins() +#define io109_toggle_output \ + ic74hc595_toggle_pin(PROBE); \ + ic74hc595_shift_io_pins() #define io109_get_output ic74hc595_get_pin(PROBE) #define io109_config_input #define io109_config_pullup @@ -2483,9 +3011,15 @@ extern "C" #define io110_get_input mcu_get_input(ESTOP) #elif ASSERT_PIN_EXTENDED(ESTOP) #define io110_config_output -#define io110_set_output ic74hc595_set_pin(ESTOP);ic74hc595_shift_io_pins() -#define io110_clear_output ic74hc595_clear_pin(ESTOP);ic74hc595_shift_io_pins() -#define io110_toggle_output ic74hc595_toggle_pin(ESTOP);ic74hc595_shift_io_pins() +#define io110_set_output \ + ic74hc595_set_pin(ESTOP); \ + ic74hc595_shift_io_pins() +#define io110_clear_output \ + ic74hc595_clear_pin(ESTOP); \ + ic74hc595_shift_io_pins() +#define io110_toggle_output \ + ic74hc595_toggle_pin(ESTOP); \ + ic74hc595_shift_io_pins() #define io110_get_output ic74hc595_get_pin(ESTOP) #define io110_config_input #define io110_config_pullup @@ -2511,9 +3045,15 @@ extern "C" #define io111_get_input mcu_get_input(SAFETY_DOOR) #elif ASSERT_PIN_EXTENDED(SAFETY_DOOR) #define io111_config_output -#define io111_set_output ic74hc595_set_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() -#define io111_clear_output ic74hc595_clear_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() -#define io111_toggle_output ic74hc595_toggle_pin(SAFETY_DOOR);ic74hc595_shift_io_pins() +#define io111_set_output \ + ic74hc595_set_pin(SAFETY_DOOR); \ + ic74hc595_shift_io_pins() +#define io111_clear_output \ + ic74hc595_clear_pin(SAFETY_DOOR); \ + ic74hc595_shift_io_pins() +#define io111_toggle_output \ + ic74hc595_toggle_pin(SAFETY_DOOR); \ + ic74hc595_shift_io_pins() #define io111_get_output ic74hc595_get_pin(SAFETY_DOOR) #define io111_config_input #define io111_config_pullup @@ -2539,9 +3079,15 @@ extern "C" #define io112_get_input mcu_get_input(FHOLD) #elif ASSERT_PIN_EXTENDED(FHOLD) #define io112_config_output -#define io112_set_output ic74hc595_set_pin(FHOLD);ic74hc595_shift_io_pins() -#define io112_clear_output ic74hc595_clear_pin(FHOLD);ic74hc595_shift_io_pins() -#define io112_toggle_output ic74hc595_toggle_pin(FHOLD);ic74hc595_shift_io_pins() +#define io112_set_output \ + ic74hc595_set_pin(FHOLD); \ + ic74hc595_shift_io_pins() +#define io112_clear_output \ + ic74hc595_clear_pin(FHOLD); \ + ic74hc595_shift_io_pins() +#define io112_toggle_output \ + ic74hc595_toggle_pin(FHOLD); \ + ic74hc595_shift_io_pins() #define io112_get_output ic74hc595_get_pin(FHOLD) #define io112_config_input #define io112_config_pullup @@ -2567,9 +3113,15 @@ extern "C" #define io113_get_input mcu_get_input(CS_RES) #elif ASSERT_PIN_EXTENDED(CS_RES) #define io113_config_output -#define io113_set_output ic74hc595_set_pin(CS_RES);ic74hc595_shift_io_pins() -#define io113_clear_output ic74hc595_clear_pin(CS_RES);ic74hc595_shift_io_pins() -#define io113_toggle_output ic74hc595_toggle_pin(CS_RES);ic74hc595_shift_io_pins() +#define io113_set_output \ + ic74hc595_set_pin(CS_RES); \ + ic74hc595_shift_io_pins() +#define io113_clear_output \ + ic74hc595_clear_pin(CS_RES); \ + ic74hc595_shift_io_pins() +#define io113_toggle_output \ + ic74hc595_toggle_pin(CS_RES); \ + ic74hc595_shift_io_pins() #define io113_get_output ic74hc595_get_pin(CS_RES) #define io113_config_input #define io113_config_pullup @@ -2595,9 +3147,15 @@ extern "C" #define io114_get_input mcu_get_input(ANALOG0) #elif ASSERT_PIN_EXTENDED(ANALOG0) #define io114_config_output -#define io114_set_output ic74hc595_set_pin(ANALOG0);ic74hc595_shift_io_pins() -#define io114_clear_output ic74hc595_clear_pin(ANALOG0);ic74hc595_shift_io_pins() -#define io114_toggle_output ic74hc595_toggle_pin(ANALOG0);ic74hc595_shift_io_pins() +#define io114_set_output \ + ic74hc595_set_pin(ANALOG0); \ + ic74hc595_shift_io_pins() +#define io114_clear_output \ + ic74hc595_clear_pin(ANALOG0); \ + ic74hc595_shift_io_pins() +#define io114_toggle_output \ + ic74hc595_toggle_pin(ANALOG0); \ + ic74hc595_shift_io_pins() #define io114_get_output ic74hc595_get_pin(ANALOG0) #define io114_config_input #define io114_config_pullup @@ -2623,9 +3181,15 @@ extern "C" #define io115_get_input mcu_get_input(ANALOG1) #elif ASSERT_PIN_EXTENDED(ANALOG1) #define io115_config_output -#define io115_set_output ic74hc595_set_pin(ANALOG1);ic74hc595_shift_io_pins() -#define io115_clear_output ic74hc595_clear_pin(ANALOG1);ic74hc595_shift_io_pins() -#define io115_toggle_output ic74hc595_toggle_pin(ANALOG1);ic74hc595_shift_io_pins() +#define io115_set_output \ + ic74hc595_set_pin(ANALOG1); \ + ic74hc595_shift_io_pins() +#define io115_clear_output \ + ic74hc595_clear_pin(ANALOG1); \ + ic74hc595_shift_io_pins() +#define io115_toggle_output \ + ic74hc595_toggle_pin(ANALOG1); \ + ic74hc595_shift_io_pins() #define io115_get_output ic74hc595_get_pin(ANALOG1) #define io115_config_input #define io115_config_pullup @@ -2651,9 +3215,15 @@ extern "C" #define io116_get_input mcu_get_input(ANALOG2) #elif ASSERT_PIN_EXTENDED(ANALOG2) #define io116_config_output -#define io116_set_output ic74hc595_set_pin(ANALOG2);ic74hc595_shift_io_pins() -#define io116_clear_output ic74hc595_clear_pin(ANALOG2);ic74hc595_shift_io_pins() -#define io116_toggle_output ic74hc595_toggle_pin(ANALOG2);ic74hc595_shift_io_pins() +#define io116_set_output \ + ic74hc595_set_pin(ANALOG2); \ + ic74hc595_shift_io_pins() +#define io116_clear_output \ + ic74hc595_clear_pin(ANALOG2); \ + ic74hc595_shift_io_pins() +#define io116_toggle_output \ + ic74hc595_toggle_pin(ANALOG2); \ + ic74hc595_shift_io_pins() #define io116_get_output ic74hc595_get_pin(ANALOG2) #define io116_config_input #define io116_config_pullup @@ -2679,9 +3249,15 @@ extern "C" #define io117_get_input mcu_get_input(ANALOG3) #elif ASSERT_PIN_EXTENDED(ANALOG3) #define io117_config_output -#define io117_set_output ic74hc595_set_pin(ANALOG3);ic74hc595_shift_io_pins() -#define io117_clear_output ic74hc595_clear_pin(ANALOG3);ic74hc595_shift_io_pins() -#define io117_toggle_output ic74hc595_toggle_pin(ANALOG3);ic74hc595_shift_io_pins() +#define io117_set_output \ + ic74hc595_set_pin(ANALOG3); \ + ic74hc595_shift_io_pins() +#define io117_clear_output \ + ic74hc595_clear_pin(ANALOG3); \ + ic74hc595_shift_io_pins() +#define io117_toggle_output \ + ic74hc595_toggle_pin(ANALOG3); \ + ic74hc595_shift_io_pins() #define io117_get_output ic74hc595_get_pin(ANALOG3) #define io117_config_input #define io117_config_pullup @@ -2707,9 +3283,15 @@ extern "C" #define io118_get_input mcu_get_input(ANALOG4) #elif ASSERT_PIN_EXTENDED(ANALOG4) #define io118_config_output -#define io118_set_output ic74hc595_set_pin(ANALOG4);ic74hc595_shift_io_pins() -#define io118_clear_output ic74hc595_clear_pin(ANALOG4);ic74hc595_shift_io_pins() -#define io118_toggle_output ic74hc595_toggle_pin(ANALOG4);ic74hc595_shift_io_pins() +#define io118_set_output \ + ic74hc595_set_pin(ANALOG4); \ + ic74hc595_shift_io_pins() +#define io118_clear_output \ + ic74hc595_clear_pin(ANALOG4); \ + ic74hc595_shift_io_pins() +#define io118_toggle_output \ + ic74hc595_toggle_pin(ANALOG4); \ + ic74hc595_shift_io_pins() #define io118_get_output ic74hc595_get_pin(ANALOG4) #define io118_config_input #define io118_config_pullup @@ -2735,9 +3317,15 @@ extern "C" #define io119_get_input mcu_get_input(ANALOG5) #elif ASSERT_PIN_EXTENDED(ANALOG5) #define io119_config_output -#define io119_set_output ic74hc595_set_pin(ANALOG5);ic74hc595_shift_io_pins() -#define io119_clear_output ic74hc595_clear_pin(ANALOG5);ic74hc595_shift_io_pins() -#define io119_toggle_output ic74hc595_toggle_pin(ANALOG5);ic74hc595_shift_io_pins() +#define io119_set_output \ + ic74hc595_set_pin(ANALOG5); \ + ic74hc595_shift_io_pins() +#define io119_clear_output \ + ic74hc595_clear_pin(ANALOG5); \ + ic74hc595_shift_io_pins() +#define io119_toggle_output \ + ic74hc595_toggle_pin(ANALOG5); \ + ic74hc595_shift_io_pins() #define io119_get_output ic74hc595_get_pin(ANALOG5) #define io119_config_input #define io119_config_pullup @@ -2763,9 +3351,15 @@ extern "C" #define io120_get_input mcu_get_input(ANALOG6) #elif ASSERT_PIN_EXTENDED(ANALOG6) #define io120_config_output -#define io120_set_output ic74hc595_set_pin(ANALOG6);ic74hc595_shift_io_pins() -#define io120_clear_output ic74hc595_clear_pin(ANALOG6);ic74hc595_shift_io_pins() -#define io120_toggle_output ic74hc595_toggle_pin(ANALOG6);ic74hc595_shift_io_pins() +#define io120_set_output \ + ic74hc595_set_pin(ANALOG6); \ + ic74hc595_shift_io_pins() +#define io120_clear_output \ + ic74hc595_clear_pin(ANALOG6); \ + ic74hc595_shift_io_pins() +#define io120_toggle_output \ + ic74hc595_toggle_pin(ANALOG6); \ + ic74hc595_shift_io_pins() #define io120_get_output ic74hc595_get_pin(ANALOG6) #define io120_config_input #define io120_config_pullup @@ -2791,9 +3385,15 @@ extern "C" #define io121_get_input mcu_get_input(ANALOG7) #elif ASSERT_PIN_EXTENDED(ANALOG7) #define io121_config_output -#define io121_set_output ic74hc595_set_pin(ANALOG7);ic74hc595_shift_io_pins() -#define io121_clear_output ic74hc595_clear_pin(ANALOG7);ic74hc595_shift_io_pins() -#define io121_toggle_output ic74hc595_toggle_pin(ANALOG7);ic74hc595_shift_io_pins() +#define io121_set_output \ + ic74hc595_set_pin(ANALOG7); \ + ic74hc595_shift_io_pins() +#define io121_clear_output \ + ic74hc595_clear_pin(ANALOG7); \ + ic74hc595_shift_io_pins() +#define io121_toggle_output \ + ic74hc595_toggle_pin(ANALOG7); \ + ic74hc595_shift_io_pins() #define io121_get_output ic74hc595_get_pin(ANALOG7) #define io121_config_input #define io121_config_pullup @@ -2819,9 +3419,15 @@ extern "C" #define io122_get_input mcu_get_input(ANALOG8) #elif ASSERT_PIN_EXTENDED(ANALOG8) #define io122_config_output -#define io122_set_output ic74hc595_set_pin(ANALOG8);ic74hc595_shift_io_pins() -#define io122_clear_output ic74hc595_clear_pin(ANALOG8);ic74hc595_shift_io_pins() -#define io122_toggle_output ic74hc595_toggle_pin(ANALOG8);ic74hc595_shift_io_pins() +#define io122_set_output \ + ic74hc595_set_pin(ANALOG8); \ + ic74hc595_shift_io_pins() +#define io122_clear_output \ + ic74hc595_clear_pin(ANALOG8); \ + ic74hc595_shift_io_pins() +#define io122_toggle_output \ + ic74hc595_toggle_pin(ANALOG8); \ + ic74hc595_shift_io_pins() #define io122_get_output ic74hc595_get_pin(ANALOG8) #define io122_config_input #define io122_config_pullup @@ -2847,9 +3453,15 @@ extern "C" #define io123_get_input mcu_get_input(ANALOG9) #elif ASSERT_PIN_EXTENDED(ANALOG9) #define io123_config_output -#define io123_set_output ic74hc595_set_pin(ANALOG9);ic74hc595_shift_io_pins() -#define io123_clear_output ic74hc595_clear_pin(ANALOG9);ic74hc595_shift_io_pins() -#define io123_toggle_output ic74hc595_toggle_pin(ANALOG9);ic74hc595_shift_io_pins() +#define io123_set_output \ + ic74hc595_set_pin(ANALOG9); \ + ic74hc595_shift_io_pins() +#define io123_clear_output \ + ic74hc595_clear_pin(ANALOG9); \ + ic74hc595_shift_io_pins() +#define io123_toggle_output \ + ic74hc595_toggle_pin(ANALOG9); \ + ic74hc595_shift_io_pins() #define io123_get_output ic74hc595_get_pin(ANALOG9) #define io123_config_input #define io123_config_pullup @@ -2875,9 +3487,15 @@ extern "C" #define io124_get_input mcu_get_input(ANALOG10) #elif ASSERT_PIN_EXTENDED(ANALOG10) #define io124_config_output -#define io124_set_output ic74hc595_set_pin(ANALOG10);ic74hc595_shift_io_pins() -#define io124_clear_output ic74hc595_clear_pin(ANALOG10);ic74hc595_shift_io_pins() -#define io124_toggle_output ic74hc595_toggle_pin(ANALOG10);ic74hc595_shift_io_pins() +#define io124_set_output \ + ic74hc595_set_pin(ANALOG10); \ + ic74hc595_shift_io_pins() +#define io124_clear_output \ + ic74hc595_clear_pin(ANALOG10); \ + ic74hc595_shift_io_pins() +#define io124_toggle_output \ + ic74hc595_toggle_pin(ANALOG10); \ + ic74hc595_shift_io_pins() #define io124_get_output ic74hc595_get_pin(ANALOG10) #define io124_config_input #define io124_config_pullup @@ -2903,9 +3521,15 @@ extern "C" #define io125_get_input mcu_get_input(ANALOG11) #elif ASSERT_PIN_EXTENDED(ANALOG11) #define io125_config_output -#define io125_set_output ic74hc595_set_pin(ANALOG11);ic74hc595_shift_io_pins() -#define io125_clear_output ic74hc595_clear_pin(ANALOG11);ic74hc595_shift_io_pins() -#define io125_toggle_output ic74hc595_toggle_pin(ANALOG11);ic74hc595_shift_io_pins() +#define io125_set_output \ + ic74hc595_set_pin(ANALOG11); \ + ic74hc595_shift_io_pins() +#define io125_clear_output \ + ic74hc595_clear_pin(ANALOG11); \ + ic74hc595_shift_io_pins() +#define io125_toggle_output \ + ic74hc595_toggle_pin(ANALOG11); \ + ic74hc595_shift_io_pins() #define io125_get_output ic74hc595_get_pin(ANALOG11) #define io125_config_input #define io125_config_pullup @@ -2931,9 +3555,15 @@ extern "C" #define io126_get_input mcu_get_input(ANALOG12) #elif ASSERT_PIN_EXTENDED(ANALOG12) #define io126_config_output -#define io126_set_output ic74hc595_set_pin(ANALOG12);ic74hc595_shift_io_pins() -#define io126_clear_output ic74hc595_clear_pin(ANALOG12);ic74hc595_shift_io_pins() -#define io126_toggle_output ic74hc595_toggle_pin(ANALOG12);ic74hc595_shift_io_pins() +#define io126_set_output \ + ic74hc595_set_pin(ANALOG12); \ + ic74hc595_shift_io_pins() +#define io126_clear_output \ + ic74hc595_clear_pin(ANALOG12); \ + ic74hc595_shift_io_pins() +#define io126_toggle_output \ + ic74hc595_toggle_pin(ANALOG12); \ + ic74hc595_shift_io_pins() #define io126_get_output ic74hc595_get_pin(ANALOG12) #define io126_config_input #define io126_config_pullup @@ -2959,9 +3589,15 @@ extern "C" #define io127_get_input mcu_get_input(ANALOG13) #elif ASSERT_PIN_EXTENDED(ANALOG13) #define io127_config_output -#define io127_set_output ic74hc595_set_pin(ANALOG13);ic74hc595_shift_io_pins() -#define io127_clear_output ic74hc595_clear_pin(ANALOG13);ic74hc595_shift_io_pins() -#define io127_toggle_output ic74hc595_toggle_pin(ANALOG13);ic74hc595_shift_io_pins() +#define io127_set_output \ + ic74hc595_set_pin(ANALOG13); \ + ic74hc595_shift_io_pins() +#define io127_clear_output \ + ic74hc595_clear_pin(ANALOG13); \ + ic74hc595_shift_io_pins() +#define io127_toggle_output \ + ic74hc595_toggle_pin(ANALOG13); \ + ic74hc595_shift_io_pins() #define io127_get_output ic74hc595_get_pin(ANALOG13) #define io127_config_input #define io127_config_pullup @@ -2987,9 +3623,15 @@ extern "C" #define io128_get_input mcu_get_input(ANALOG14) #elif ASSERT_PIN_EXTENDED(ANALOG14) #define io128_config_output -#define io128_set_output ic74hc595_set_pin(ANALOG14);ic74hc595_shift_io_pins() -#define io128_clear_output ic74hc595_clear_pin(ANALOG14);ic74hc595_shift_io_pins() -#define io128_toggle_output ic74hc595_toggle_pin(ANALOG14);ic74hc595_shift_io_pins() +#define io128_set_output \ + ic74hc595_set_pin(ANALOG14); \ + ic74hc595_shift_io_pins() +#define io128_clear_output \ + ic74hc595_clear_pin(ANALOG14); \ + ic74hc595_shift_io_pins() +#define io128_toggle_output \ + ic74hc595_toggle_pin(ANALOG14); \ + ic74hc595_shift_io_pins() #define io128_get_output ic74hc595_get_pin(ANALOG14) #define io128_config_input #define io128_config_pullup @@ -3015,9 +3657,15 @@ extern "C" #define io129_get_input mcu_get_input(ANALOG15) #elif ASSERT_PIN_EXTENDED(ANALOG15) #define io129_config_output -#define io129_set_output ic74hc595_set_pin(ANALOG15);ic74hc595_shift_io_pins() -#define io129_clear_output ic74hc595_clear_pin(ANALOG15);ic74hc595_shift_io_pins() -#define io129_toggle_output ic74hc595_toggle_pin(ANALOG15);ic74hc595_shift_io_pins() +#define io129_set_output \ + ic74hc595_set_pin(ANALOG15); \ + ic74hc595_shift_io_pins() +#define io129_clear_output \ + ic74hc595_clear_pin(ANALOG15); \ + ic74hc595_shift_io_pins() +#define io129_toggle_output \ + ic74hc595_toggle_pin(ANALOG15); \ + ic74hc595_shift_io_pins() #define io129_get_output ic74hc595_get_pin(ANALOG15) #define io129_config_input #define io129_config_pullup @@ -3043,9 +3691,15 @@ extern "C" #define io130_get_input mcu_get_input(DIN0) #elif ASSERT_PIN_EXTENDED(DIN0) #define io130_config_output -#define io130_set_output ic74hc595_set_pin(DIN0);ic74hc595_shift_io_pins() -#define io130_clear_output ic74hc595_clear_pin(DIN0);ic74hc595_shift_io_pins() -#define io130_toggle_output ic74hc595_toggle_pin(DIN0);ic74hc595_shift_io_pins() +#define io130_set_output \ + ic74hc595_set_pin(DIN0); \ + ic74hc595_shift_io_pins() +#define io130_clear_output \ + ic74hc595_clear_pin(DIN0); \ + ic74hc595_shift_io_pins() +#define io130_toggle_output \ + ic74hc595_toggle_pin(DIN0); \ + ic74hc595_shift_io_pins() #define io130_get_output ic74hc595_get_pin(DIN0) #define io130_config_input #define io130_config_pullup @@ -3071,9 +3725,15 @@ extern "C" #define io131_get_input mcu_get_input(DIN1) #elif ASSERT_PIN_EXTENDED(DIN1) #define io131_config_output -#define io131_set_output ic74hc595_set_pin(DIN1);ic74hc595_shift_io_pins() -#define io131_clear_output ic74hc595_clear_pin(DIN1);ic74hc595_shift_io_pins() -#define io131_toggle_output ic74hc595_toggle_pin(DIN1);ic74hc595_shift_io_pins() +#define io131_set_output \ + ic74hc595_set_pin(DIN1); \ + ic74hc595_shift_io_pins() +#define io131_clear_output \ + ic74hc595_clear_pin(DIN1); \ + ic74hc595_shift_io_pins() +#define io131_toggle_output \ + ic74hc595_toggle_pin(DIN1); \ + ic74hc595_shift_io_pins() #define io131_get_output ic74hc595_get_pin(DIN1) #define io131_config_input #define io131_config_pullup @@ -3099,9 +3759,15 @@ extern "C" #define io132_get_input mcu_get_input(DIN2) #elif ASSERT_PIN_EXTENDED(DIN2) #define io132_config_output -#define io132_set_output ic74hc595_set_pin(DIN2);ic74hc595_shift_io_pins() -#define io132_clear_output ic74hc595_clear_pin(DIN2);ic74hc595_shift_io_pins() -#define io132_toggle_output ic74hc595_toggle_pin(DIN2);ic74hc595_shift_io_pins() +#define io132_set_output \ + ic74hc595_set_pin(DIN2); \ + ic74hc595_shift_io_pins() +#define io132_clear_output \ + ic74hc595_clear_pin(DIN2); \ + ic74hc595_shift_io_pins() +#define io132_toggle_output \ + ic74hc595_toggle_pin(DIN2); \ + ic74hc595_shift_io_pins() #define io132_get_output ic74hc595_get_pin(DIN2) #define io132_config_input #define io132_config_pullup @@ -3127,9 +3793,15 @@ extern "C" #define io133_get_input mcu_get_input(DIN3) #elif ASSERT_PIN_EXTENDED(DIN3) #define io133_config_output -#define io133_set_output ic74hc595_set_pin(DIN3);ic74hc595_shift_io_pins() -#define io133_clear_output ic74hc595_clear_pin(DIN3);ic74hc595_shift_io_pins() -#define io133_toggle_output ic74hc595_toggle_pin(DIN3);ic74hc595_shift_io_pins() +#define io133_set_output \ + ic74hc595_set_pin(DIN3); \ + ic74hc595_shift_io_pins() +#define io133_clear_output \ + ic74hc595_clear_pin(DIN3); \ + ic74hc595_shift_io_pins() +#define io133_toggle_output \ + ic74hc595_toggle_pin(DIN3); \ + ic74hc595_shift_io_pins() #define io133_get_output ic74hc595_get_pin(DIN3) #define io133_config_input #define io133_config_pullup @@ -3155,9 +3827,15 @@ extern "C" #define io134_get_input mcu_get_input(DIN4) #elif ASSERT_PIN_EXTENDED(DIN4) #define io134_config_output -#define io134_set_output ic74hc595_set_pin(DIN4);ic74hc595_shift_io_pins() -#define io134_clear_output ic74hc595_clear_pin(DIN4);ic74hc595_shift_io_pins() -#define io134_toggle_output ic74hc595_toggle_pin(DIN4);ic74hc595_shift_io_pins() +#define io134_set_output \ + ic74hc595_set_pin(DIN4); \ + ic74hc595_shift_io_pins() +#define io134_clear_output \ + ic74hc595_clear_pin(DIN4); \ + ic74hc595_shift_io_pins() +#define io134_toggle_output \ + ic74hc595_toggle_pin(DIN4); \ + ic74hc595_shift_io_pins() #define io134_get_output ic74hc595_get_pin(DIN4) #define io134_config_input #define io134_config_pullup @@ -3183,9 +3861,15 @@ extern "C" #define io135_get_input mcu_get_input(DIN5) #elif ASSERT_PIN_EXTENDED(DIN5) #define io135_config_output -#define io135_set_output ic74hc595_set_pin(DIN5);ic74hc595_shift_io_pins() -#define io135_clear_output ic74hc595_clear_pin(DIN5);ic74hc595_shift_io_pins() -#define io135_toggle_output ic74hc595_toggle_pin(DIN5);ic74hc595_shift_io_pins() +#define io135_set_output \ + ic74hc595_set_pin(DIN5); \ + ic74hc595_shift_io_pins() +#define io135_clear_output \ + ic74hc595_clear_pin(DIN5); \ + ic74hc595_shift_io_pins() +#define io135_toggle_output \ + ic74hc595_toggle_pin(DIN5); \ + ic74hc595_shift_io_pins() #define io135_get_output ic74hc595_get_pin(DIN5) #define io135_config_input #define io135_config_pullup @@ -3211,9 +3895,15 @@ extern "C" #define io136_get_input mcu_get_input(DIN6) #elif ASSERT_PIN_EXTENDED(DIN6) #define io136_config_output -#define io136_set_output ic74hc595_set_pin(DIN6);ic74hc595_shift_io_pins() -#define io136_clear_output ic74hc595_clear_pin(DIN6);ic74hc595_shift_io_pins() -#define io136_toggle_output ic74hc595_toggle_pin(DIN6);ic74hc595_shift_io_pins() +#define io136_set_output \ + ic74hc595_set_pin(DIN6); \ + ic74hc595_shift_io_pins() +#define io136_clear_output \ + ic74hc595_clear_pin(DIN6); \ + ic74hc595_shift_io_pins() +#define io136_toggle_output \ + ic74hc595_toggle_pin(DIN6); \ + ic74hc595_shift_io_pins() #define io136_get_output ic74hc595_get_pin(DIN6) #define io136_config_input #define io136_config_pullup @@ -3239,9 +3929,15 @@ extern "C" #define io137_get_input mcu_get_input(DIN7) #elif ASSERT_PIN_EXTENDED(DIN7) #define io137_config_output -#define io137_set_output ic74hc595_set_pin(DIN7);ic74hc595_shift_io_pins() -#define io137_clear_output ic74hc595_clear_pin(DIN7);ic74hc595_shift_io_pins() -#define io137_toggle_output ic74hc595_toggle_pin(DIN7);ic74hc595_shift_io_pins() +#define io137_set_output \ + ic74hc595_set_pin(DIN7); \ + ic74hc595_shift_io_pins() +#define io137_clear_output \ + ic74hc595_clear_pin(DIN7); \ + ic74hc595_shift_io_pins() +#define io137_toggle_output \ + ic74hc595_toggle_pin(DIN7); \ + ic74hc595_shift_io_pins() #define io137_get_output ic74hc595_get_pin(DIN7) #define io137_config_input #define io137_config_pullup @@ -3267,9 +3963,15 @@ extern "C" #define io138_get_input mcu_get_input(DIN8) #elif ASSERT_PIN_EXTENDED(DIN8) #define io138_config_output -#define io138_set_output ic74hc595_set_pin(DIN8);ic74hc595_shift_io_pins() -#define io138_clear_output ic74hc595_clear_pin(DIN8);ic74hc595_shift_io_pins() -#define io138_toggle_output ic74hc595_toggle_pin(DIN8);ic74hc595_shift_io_pins() +#define io138_set_output \ + ic74hc595_set_pin(DIN8); \ + ic74hc595_shift_io_pins() +#define io138_clear_output \ + ic74hc595_clear_pin(DIN8); \ + ic74hc595_shift_io_pins() +#define io138_toggle_output \ + ic74hc595_toggle_pin(DIN8); \ + ic74hc595_shift_io_pins() #define io138_get_output ic74hc595_get_pin(DIN8) #define io138_config_input #define io138_config_pullup @@ -3295,9 +3997,15 @@ extern "C" #define io139_get_input mcu_get_input(DIN9) #elif ASSERT_PIN_EXTENDED(DIN9) #define io139_config_output -#define io139_set_output ic74hc595_set_pin(DIN9);ic74hc595_shift_io_pins() -#define io139_clear_output ic74hc595_clear_pin(DIN9);ic74hc595_shift_io_pins() -#define io139_toggle_output ic74hc595_toggle_pin(DIN9);ic74hc595_shift_io_pins() +#define io139_set_output \ + ic74hc595_set_pin(DIN9); \ + ic74hc595_shift_io_pins() +#define io139_clear_output \ + ic74hc595_clear_pin(DIN9); \ + ic74hc595_shift_io_pins() +#define io139_toggle_output \ + ic74hc595_toggle_pin(DIN9); \ + ic74hc595_shift_io_pins() #define io139_get_output ic74hc595_get_pin(DIN9) #define io139_config_input #define io139_config_pullup @@ -3323,9 +4031,15 @@ extern "C" #define io140_get_input mcu_get_input(DIN10) #elif ASSERT_PIN_EXTENDED(DIN10) #define io140_config_output -#define io140_set_output ic74hc595_set_pin(DIN10);ic74hc595_shift_io_pins() -#define io140_clear_output ic74hc595_clear_pin(DIN10);ic74hc595_shift_io_pins() -#define io140_toggle_output ic74hc595_toggle_pin(DIN10);ic74hc595_shift_io_pins() +#define io140_set_output \ + ic74hc595_set_pin(DIN10); \ + ic74hc595_shift_io_pins() +#define io140_clear_output \ + ic74hc595_clear_pin(DIN10); \ + ic74hc595_shift_io_pins() +#define io140_toggle_output \ + ic74hc595_toggle_pin(DIN10); \ + ic74hc595_shift_io_pins() #define io140_get_output ic74hc595_get_pin(DIN10) #define io140_config_input #define io140_config_pullup @@ -3351,9 +4065,15 @@ extern "C" #define io141_get_input mcu_get_input(DIN11) #elif ASSERT_PIN_EXTENDED(DIN11) #define io141_config_output -#define io141_set_output ic74hc595_set_pin(DIN11);ic74hc595_shift_io_pins() -#define io141_clear_output ic74hc595_clear_pin(DIN11);ic74hc595_shift_io_pins() -#define io141_toggle_output ic74hc595_toggle_pin(DIN11);ic74hc595_shift_io_pins() +#define io141_set_output \ + ic74hc595_set_pin(DIN11); \ + ic74hc595_shift_io_pins() +#define io141_clear_output \ + ic74hc595_clear_pin(DIN11); \ + ic74hc595_shift_io_pins() +#define io141_toggle_output \ + ic74hc595_toggle_pin(DIN11); \ + ic74hc595_shift_io_pins() #define io141_get_output ic74hc595_get_pin(DIN11) #define io141_config_input #define io141_config_pullup @@ -3379,9 +4099,15 @@ extern "C" #define io142_get_input mcu_get_input(DIN12) #elif ASSERT_PIN_EXTENDED(DIN12) #define io142_config_output -#define io142_set_output ic74hc595_set_pin(DIN12);ic74hc595_shift_io_pins() -#define io142_clear_output ic74hc595_clear_pin(DIN12);ic74hc595_shift_io_pins() -#define io142_toggle_output ic74hc595_toggle_pin(DIN12);ic74hc595_shift_io_pins() +#define io142_set_output \ + ic74hc595_set_pin(DIN12); \ + ic74hc595_shift_io_pins() +#define io142_clear_output \ + ic74hc595_clear_pin(DIN12); \ + ic74hc595_shift_io_pins() +#define io142_toggle_output \ + ic74hc595_toggle_pin(DIN12); \ + ic74hc595_shift_io_pins() #define io142_get_output ic74hc595_get_pin(DIN12) #define io142_config_input #define io142_config_pullup @@ -3407,9 +4133,15 @@ extern "C" #define io143_get_input mcu_get_input(DIN13) #elif ASSERT_PIN_EXTENDED(DIN13) #define io143_config_output -#define io143_set_output ic74hc595_set_pin(DIN13);ic74hc595_shift_io_pins() -#define io143_clear_output ic74hc595_clear_pin(DIN13);ic74hc595_shift_io_pins() -#define io143_toggle_output ic74hc595_toggle_pin(DIN13);ic74hc595_shift_io_pins() +#define io143_set_output \ + ic74hc595_set_pin(DIN13); \ + ic74hc595_shift_io_pins() +#define io143_clear_output \ + ic74hc595_clear_pin(DIN13); \ + ic74hc595_shift_io_pins() +#define io143_toggle_output \ + ic74hc595_toggle_pin(DIN13); \ + ic74hc595_shift_io_pins() #define io143_get_output ic74hc595_get_pin(DIN13) #define io143_config_input #define io143_config_pullup @@ -3435,9 +4167,15 @@ extern "C" #define io144_get_input mcu_get_input(DIN14) #elif ASSERT_PIN_EXTENDED(DIN14) #define io144_config_output -#define io144_set_output ic74hc595_set_pin(DIN14);ic74hc595_shift_io_pins() -#define io144_clear_output ic74hc595_clear_pin(DIN14);ic74hc595_shift_io_pins() -#define io144_toggle_output ic74hc595_toggle_pin(DIN14);ic74hc595_shift_io_pins() +#define io144_set_output \ + ic74hc595_set_pin(DIN14); \ + ic74hc595_shift_io_pins() +#define io144_clear_output \ + ic74hc595_clear_pin(DIN14); \ + ic74hc595_shift_io_pins() +#define io144_toggle_output \ + ic74hc595_toggle_pin(DIN14); \ + ic74hc595_shift_io_pins() #define io144_get_output ic74hc595_get_pin(DIN14) #define io144_config_input #define io144_config_pullup @@ -3463,9 +4201,15 @@ extern "C" #define io145_get_input mcu_get_input(DIN15) #elif ASSERT_PIN_EXTENDED(DIN15) #define io145_config_output -#define io145_set_output ic74hc595_set_pin(DIN15);ic74hc595_shift_io_pins() -#define io145_clear_output ic74hc595_clear_pin(DIN15);ic74hc595_shift_io_pins() -#define io145_toggle_output ic74hc595_toggle_pin(DIN15);ic74hc595_shift_io_pins() +#define io145_set_output \ + ic74hc595_set_pin(DIN15); \ + ic74hc595_shift_io_pins() +#define io145_clear_output \ + ic74hc595_clear_pin(DIN15); \ + ic74hc595_shift_io_pins() +#define io145_toggle_output \ + ic74hc595_toggle_pin(DIN15); \ + ic74hc595_shift_io_pins() #define io145_get_output ic74hc595_get_pin(DIN15) #define io145_config_input #define io145_config_pullup @@ -3491,9 +4235,15 @@ extern "C" #define io146_get_input mcu_get_input(DIN16) #elif ASSERT_PIN_EXTENDED(DIN16) #define io146_config_output -#define io146_set_output ic74hc595_set_pin(DIN16);ic74hc595_shift_io_pins() -#define io146_clear_output ic74hc595_clear_pin(DIN16);ic74hc595_shift_io_pins() -#define io146_toggle_output ic74hc595_toggle_pin(DIN16);ic74hc595_shift_io_pins() +#define io146_set_output \ + ic74hc595_set_pin(DIN16); \ + ic74hc595_shift_io_pins() +#define io146_clear_output \ + ic74hc595_clear_pin(DIN16); \ + ic74hc595_shift_io_pins() +#define io146_toggle_output \ + ic74hc595_toggle_pin(DIN16); \ + ic74hc595_shift_io_pins() #define io146_get_output ic74hc595_get_pin(DIN16) #define io146_config_input #define io146_config_pullup @@ -3519,9 +4269,15 @@ extern "C" #define io147_get_input mcu_get_input(DIN17) #elif ASSERT_PIN_EXTENDED(DIN17) #define io147_config_output -#define io147_set_output ic74hc595_set_pin(DIN17);ic74hc595_shift_io_pins() -#define io147_clear_output ic74hc595_clear_pin(DIN17);ic74hc595_shift_io_pins() -#define io147_toggle_output ic74hc595_toggle_pin(DIN17);ic74hc595_shift_io_pins() +#define io147_set_output \ + ic74hc595_set_pin(DIN17); \ + ic74hc595_shift_io_pins() +#define io147_clear_output \ + ic74hc595_clear_pin(DIN17); \ + ic74hc595_shift_io_pins() +#define io147_toggle_output \ + ic74hc595_toggle_pin(DIN17); \ + ic74hc595_shift_io_pins() #define io147_get_output ic74hc595_get_pin(DIN17) #define io147_config_input #define io147_config_pullup @@ -3547,9 +4303,15 @@ extern "C" #define io148_get_input mcu_get_input(DIN18) #elif ASSERT_PIN_EXTENDED(DIN18) #define io148_config_output -#define io148_set_output ic74hc595_set_pin(DIN18);ic74hc595_shift_io_pins() -#define io148_clear_output ic74hc595_clear_pin(DIN18);ic74hc595_shift_io_pins() -#define io148_toggle_output ic74hc595_toggle_pin(DIN18);ic74hc595_shift_io_pins() +#define io148_set_output \ + ic74hc595_set_pin(DIN18); \ + ic74hc595_shift_io_pins() +#define io148_clear_output \ + ic74hc595_clear_pin(DIN18); \ + ic74hc595_shift_io_pins() +#define io148_toggle_output \ + ic74hc595_toggle_pin(DIN18); \ + ic74hc595_shift_io_pins() #define io148_get_output ic74hc595_get_pin(DIN18) #define io148_config_input #define io148_config_pullup @@ -3575,9 +4337,15 @@ extern "C" #define io149_get_input mcu_get_input(DIN19) #elif ASSERT_PIN_EXTENDED(DIN19) #define io149_config_output -#define io149_set_output ic74hc595_set_pin(DIN19);ic74hc595_shift_io_pins() -#define io149_clear_output ic74hc595_clear_pin(DIN19);ic74hc595_shift_io_pins() -#define io149_toggle_output ic74hc595_toggle_pin(DIN19);ic74hc595_shift_io_pins() +#define io149_set_output \ + ic74hc595_set_pin(DIN19); \ + ic74hc595_shift_io_pins() +#define io149_clear_output \ + ic74hc595_clear_pin(DIN19); \ + ic74hc595_shift_io_pins() +#define io149_toggle_output \ + ic74hc595_toggle_pin(DIN19); \ + ic74hc595_shift_io_pins() #define io149_get_output ic74hc595_get_pin(DIN19) #define io149_config_input #define io149_config_pullup @@ -3603,9 +4371,15 @@ extern "C" #define io150_get_input mcu_get_input(DIN20) #elif ASSERT_PIN_EXTENDED(DIN20) #define io150_config_output -#define io150_set_output ic74hc595_set_pin(DIN20);ic74hc595_shift_io_pins() -#define io150_clear_output ic74hc595_clear_pin(DIN20);ic74hc595_shift_io_pins() -#define io150_toggle_output ic74hc595_toggle_pin(DIN20);ic74hc595_shift_io_pins() +#define io150_set_output \ + ic74hc595_set_pin(DIN20); \ + ic74hc595_shift_io_pins() +#define io150_clear_output \ + ic74hc595_clear_pin(DIN20); \ + ic74hc595_shift_io_pins() +#define io150_toggle_output \ + ic74hc595_toggle_pin(DIN20); \ + ic74hc595_shift_io_pins() #define io150_get_output ic74hc595_get_pin(DIN20) #define io150_config_input #define io150_config_pullup @@ -3631,9 +4405,15 @@ extern "C" #define io151_get_input mcu_get_input(DIN21) #elif ASSERT_PIN_EXTENDED(DIN21) #define io151_config_output -#define io151_set_output ic74hc595_set_pin(DIN21);ic74hc595_shift_io_pins() -#define io151_clear_output ic74hc595_clear_pin(DIN21);ic74hc595_shift_io_pins() -#define io151_toggle_output ic74hc595_toggle_pin(DIN21);ic74hc595_shift_io_pins() +#define io151_set_output \ + ic74hc595_set_pin(DIN21); \ + ic74hc595_shift_io_pins() +#define io151_clear_output \ + ic74hc595_clear_pin(DIN21); \ + ic74hc595_shift_io_pins() +#define io151_toggle_output \ + ic74hc595_toggle_pin(DIN21); \ + ic74hc595_shift_io_pins() #define io151_get_output ic74hc595_get_pin(DIN21) #define io151_config_input #define io151_config_pullup @@ -3659,9 +4439,15 @@ extern "C" #define io152_get_input mcu_get_input(DIN22) #elif ASSERT_PIN_EXTENDED(DIN22) #define io152_config_output -#define io152_set_output ic74hc595_set_pin(DIN22);ic74hc595_shift_io_pins() -#define io152_clear_output ic74hc595_clear_pin(DIN22);ic74hc595_shift_io_pins() -#define io152_toggle_output ic74hc595_toggle_pin(DIN22);ic74hc595_shift_io_pins() +#define io152_set_output \ + ic74hc595_set_pin(DIN22); \ + ic74hc595_shift_io_pins() +#define io152_clear_output \ + ic74hc595_clear_pin(DIN22); \ + ic74hc595_shift_io_pins() +#define io152_toggle_output \ + ic74hc595_toggle_pin(DIN22); \ + ic74hc595_shift_io_pins() #define io152_get_output ic74hc595_get_pin(DIN22) #define io152_config_input #define io152_config_pullup @@ -3687,9 +4473,15 @@ extern "C" #define io153_get_input mcu_get_input(DIN23) #elif ASSERT_PIN_EXTENDED(DIN23) #define io153_config_output -#define io153_set_output ic74hc595_set_pin(DIN23);ic74hc595_shift_io_pins() -#define io153_clear_output ic74hc595_clear_pin(DIN23);ic74hc595_shift_io_pins() -#define io153_toggle_output ic74hc595_toggle_pin(DIN23);ic74hc595_shift_io_pins() +#define io153_set_output \ + ic74hc595_set_pin(DIN23); \ + ic74hc595_shift_io_pins() +#define io153_clear_output \ + ic74hc595_clear_pin(DIN23); \ + ic74hc595_shift_io_pins() +#define io153_toggle_output \ + ic74hc595_toggle_pin(DIN23); \ + ic74hc595_shift_io_pins() #define io153_get_output ic74hc595_get_pin(DIN23) #define io153_config_input #define io153_config_pullup @@ -3715,9 +4507,15 @@ extern "C" #define io154_get_input mcu_get_input(DIN24) #elif ASSERT_PIN_EXTENDED(DIN24) #define io154_config_output -#define io154_set_output ic74hc595_set_pin(DIN24);ic74hc595_shift_io_pins() -#define io154_clear_output ic74hc595_clear_pin(DIN24);ic74hc595_shift_io_pins() -#define io154_toggle_output ic74hc595_toggle_pin(DIN24);ic74hc595_shift_io_pins() +#define io154_set_output \ + ic74hc595_set_pin(DIN24); \ + ic74hc595_shift_io_pins() +#define io154_clear_output \ + ic74hc595_clear_pin(DIN24); \ + ic74hc595_shift_io_pins() +#define io154_toggle_output \ + ic74hc595_toggle_pin(DIN24); \ + ic74hc595_shift_io_pins() #define io154_get_output ic74hc595_get_pin(DIN24) #define io154_config_input #define io154_config_pullup @@ -3743,9 +4541,15 @@ extern "C" #define io155_get_input mcu_get_input(DIN25) #elif ASSERT_PIN_EXTENDED(DIN25) #define io155_config_output -#define io155_set_output ic74hc595_set_pin(DIN25);ic74hc595_shift_io_pins() -#define io155_clear_output ic74hc595_clear_pin(DIN25);ic74hc595_shift_io_pins() -#define io155_toggle_output ic74hc595_toggle_pin(DIN25);ic74hc595_shift_io_pins() +#define io155_set_output \ + ic74hc595_set_pin(DIN25); \ + ic74hc595_shift_io_pins() +#define io155_clear_output \ + ic74hc595_clear_pin(DIN25); \ + ic74hc595_shift_io_pins() +#define io155_toggle_output \ + ic74hc595_toggle_pin(DIN25); \ + ic74hc595_shift_io_pins() #define io155_get_output ic74hc595_get_pin(DIN25) #define io155_config_input #define io155_config_pullup @@ -3771,9 +4575,15 @@ extern "C" #define io156_get_input mcu_get_input(DIN26) #elif ASSERT_PIN_EXTENDED(DIN26) #define io156_config_output -#define io156_set_output ic74hc595_set_pin(DIN26);ic74hc595_shift_io_pins() -#define io156_clear_output ic74hc595_clear_pin(DIN26);ic74hc595_shift_io_pins() -#define io156_toggle_output ic74hc595_toggle_pin(DIN26);ic74hc595_shift_io_pins() +#define io156_set_output \ + ic74hc595_set_pin(DIN26); \ + ic74hc595_shift_io_pins() +#define io156_clear_output \ + ic74hc595_clear_pin(DIN26); \ + ic74hc595_shift_io_pins() +#define io156_toggle_output \ + ic74hc595_toggle_pin(DIN26); \ + ic74hc595_shift_io_pins() #define io156_get_output ic74hc595_get_pin(DIN26) #define io156_config_input #define io156_config_pullup @@ -3799,9 +4609,15 @@ extern "C" #define io157_get_input mcu_get_input(DIN27) #elif ASSERT_PIN_EXTENDED(DIN27) #define io157_config_output -#define io157_set_output ic74hc595_set_pin(DIN27);ic74hc595_shift_io_pins() -#define io157_clear_output ic74hc595_clear_pin(DIN27);ic74hc595_shift_io_pins() -#define io157_toggle_output ic74hc595_toggle_pin(DIN27);ic74hc595_shift_io_pins() +#define io157_set_output \ + ic74hc595_set_pin(DIN27); \ + ic74hc595_shift_io_pins() +#define io157_clear_output \ + ic74hc595_clear_pin(DIN27); \ + ic74hc595_shift_io_pins() +#define io157_toggle_output \ + ic74hc595_toggle_pin(DIN27); \ + ic74hc595_shift_io_pins() #define io157_get_output ic74hc595_get_pin(DIN27) #define io157_config_input #define io157_config_pullup @@ -3827,9 +4643,15 @@ extern "C" #define io158_get_input mcu_get_input(DIN28) #elif ASSERT_PIN_EXTENDED(DIN28) #define io158_config_output -#define io158_set_output ic74hc595_set_pin(DIN28);ic74hc595_shift_io_pins() -#define io158_clear_output ic74hc595_clear_pin(DIN28);ic74hc595_shift_io_pins() -#define io158_toggle_output ic74hc595_toggle_pin(DIN28);ic74hc595_shift_io_pins() +#define io158_set_output \ + ic74hc595_set_pin(DIN28); \ + ic74hc595_shift_io_pins() +#define io158_clear_output \ + ic74hc595_clear_pin(DIN28); \ + ic74hc595_shift_io_pins() +#define io158_toggle_output \ + ic74hc595_toggle_pin(DIN28); \ + ic74hc595_shift_io_pins() #define io158_get_output ic74hc595_get_pin(DIN28) #define io158_config_input #define io158_config_pullup @@ -3855,9 +4677,15 @@ extern "C" #define io159_get_input mcu_get_input(DIN29) #elif ASSERT_PIN_EXTENDED(DIN29) #define io159_config_output -#define io159_set_output ic74hc595_set_pin(DIN29);ic74hc595_shift_io_pins() -#define io159_clear_output ic74hc595_clear_pin(DIN29);ic74hc595_shift_io_pins() -#define io159_toggle_output ic74hc595_toggle_pin(DIN29);ic74hc595_shift_io_pins() +#define io159_set_output \ + ic74hc595_set_pin(DIN29); \ + ic74hc595_shift_io_pins() +#define io159_clear_output \ + ic74hc595_clear_pin(DIN29); \ + ic74hc595_shift_io_pins() +#define io159_toggle_output \ + ic74hc595_toggle_pin(DIN29); \ + ic74hc595_shift_io_pins() #define io159_get_output ic74hc595_get_pin(DIN29) #define io159_config_input #define io159_config_pullup @@ -3883,9 +4711,15 @@ extern "C" #define io160_get_input mcu_get_input(DIN30) #elif ASSERT_PIN_EXTENDED(DIN30) #define io160_config_output -#define io160_set_output ic74hc595_set_pin(DIN30);ic74hc595_shift_io_pins() -#define io160_clear_output ic74hc595_clear_pin(DIN30);ic74hc595_shift_io_pins() -#define io160_toggle_output ic74hc595_toggle_pin(DIN30);ic74hc595_shift_io_pins() +#define io160_set_output \ + ic74hc595_set_pin(DIN30); \ + ic74hc595_shift_io_pins() +#define io160_clear_output \ + ic74hc595_clear_pin(DIN30); \ + ic74hc595_shift_io_pins() +#define io160_toggle_output \ + ic74hc595_toggle_pin(DIN30); \ + ic74hc595_shift_io_pins() #define io160_get_output ic74hc595_get_pin(DIN30) #define io160_config_input #define io160_config_pullup @@ -3911,9 +4745,15 @@ extern "C" #define io161_get_input mcu_get_input(DIN31) #elif ASSERT_PIN_EXTENDED(DIN31) #define io161_config_output -#define io161_set_output ic74hc595_set_pin(DIN31);ic74hc595_shift_io_pins() -#define io161_clear_output ic74hc595_clear_pin(DIN31);ic74hc595_shift_io_pins() -#define io161_toggle_output ic74hc595_toggle_pin(DIN31);ic74hc595_shift_io_pins() +#define io161_set_output \ + ic74hc595_set_pin(DIN31); \ + ic74hc595_shift_io_pins() +#define io161_clear_output \ + ic74hc595_clear_pin(DIN31); \ + ic74hc595_shift_io_pins() +#define io161_toggle_output \ + ic74hc595_toggle_pin(DIN31); \ + ic74hc595_shift_io_pins() #define io161_get_output ic74hc595_get_pin(DIN31) #define io161_config_input #define io161_config_pullup @@ -3929,16 +4769,21 @@ extern "C" #define io161_get_input 0 #endif - /*PWM*/ #if ASSERT_PIN_IO(PWM0) #define io25_config_pwm(freq) mcu_config_pwm(PWM0, freq) #define io25_set_pwm(value) mcu_set_pwm(PWM0, value) #define io25_get_pwm mcu_get_pwm(PWM0) #elif ASSERT_PIN_EXTENDED(PWM0) -#define io25_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io25_set_pwm(value) io_set_soft_pwm(PWM0, value) -#define io25_get_pwm io_get_soft_pwm(PWM0) +#define io25_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io25_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM0 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io25_get_pwm g_io_soft_pwm[PWM0 - PWM_PINS_OFFSET] #else #define io25_config_pwm(freq) #define io25_set_pwm(value) @@ -3949,9 +4794,15 @@ extern "C" #define io26_set_pwm(value) mcu_set_pwm(PWM1, value) #define io26_get_pwm mcu_get_pwm(PWM1) #elif ASSERT_PIN_EXTENDED(PWM1) -#define io26_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io26_set_pwm(value) io_set_soft_pwm(PWM1, value) -#define io26_get_pwm io_get_soft_pwm(PWM1) +#define io26_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io26_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM1 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io26_get_pwm g_io_soft_pwm[PWM1 - PWM_PINS_OFFSET] #else #define io26_config_pwm(freq) #define io26_set_pwm(value) @@ -3962,9 +4813,15 @@ extern "C" #define io27_set_pwm(value) mcu_set_pwm(PWM2, value) #define io27_get_pwm mcu_get_pwm(PWM2) #elif ASSERT_PIN_EXTENDED(PWM2) -#define io27_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io27_set_pwm(value) io_set_soft_pwm(PWM2, value) -#define io27_get_pwm io_get_soft_pwm(PWM2) +#define io27_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io27_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM2 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io27_get_pwm g_io_soft_pwm[PWM2 - PWM_PINS_OFFSET] #else #define io27_config_pwm(freq) #define io27_set_pwm(value) @@ -3975,9 +4832,15 @@ extern "C" #define io28_set_pwm(value) mcu_set_pwm(PWM3, value) #define io28_get_pwm mcu_get_pwm(PWM3) #elif ASSERT_PIN_EXTENDED(PWM3) -#define io28_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io28_set_pwm(value) io_set_soft_pwm(PWM3, value) -#define io28_get_pwm io_get_soft_pwm(PWM3) +#define io28_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io28_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM3 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io28_get_pwm g_io_soft_pwm[PWM3 - PWM_PINS_OFFSET] #else #define io28_config_pwm(freq) #define io28_set_pwm(value) @@ -3988,9 +4851,15 @@ extern "C" #define io29_set_pwm(value) mcu_set_pwm(PWM4, value) #define io29_get_pwm mcu_get_pwm(PWM4) #elif ASSERT_PIN_EXTENDED(PWM4) -#define io29_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io29_set_pwm(value) io_set_soft_pwm(PWM4, value) -#define io29_get_pwm io_get_soft_pwm(PWM4) +#define io29_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io29_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM4 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io29_get_pwm g_io_soft_pwm[PWM4 - PWM_PINS_OFFSET] #else #define io29_config_pwm(freq) #define io29_set_pwm(value) @@ -4001,9 +4870,15 @@ extern "C" #define io30_set_pwm(value) mcu_set_pwm(PWM5, value) #define io30_get_pwm mcu_get_pwm(PWM5) #elif ASSERT_PIN_EXTENDED(PWM5) -#define io30_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io30_set_pwm(value) io_set_soft_pwm(PWM5, value) -#define io30_get_pwm io_get_soft_pwm(PWM5) +#define io30_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io30_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM5 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io30_get_pwm g_io_soft_pwm[PWM5 - PWM_PINS_OFFSET] #else #define io30_config_pwm(freq) #define io30_set_pwm(value) @@ -4014,9 +4889,15 @@ extern "C" #define io31_set_pwm(value) mcu_set_pwm(PWM6, value) #define io31_get_pwm mcu_get_pwm(PWM6) #elif ASSERT_PIN_EXTENDED(PWM6) -#define io31_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io31_set_pwm(value) io_set_soft_pwm(PWM6, value) -#define io31_get_pwm io_get_soft_pwm(PWM6) +#define io31_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io31_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM6 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io31_get_pwm g_io_soft_pwm[PWM6 - PWM_PINS_OFFSET] #else #define io31_config_pwm(freq) #define io31_set_pwm(value) @@ -4027,9 +4908,15 @@ extern "C" #define io32_set_pwm(value) mcu_set_pwm(PWM7, value) #define io32_get_pwm mcu_get_pwm(PWM7) #elif ASSERT_PIN_EXTENDED(PWM7) -#define io32_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io32_set_pwm(value) io_set_soft_pwm(PWM7, value) -#define io32_get_pwm io_get_soft_pwm(PWM7) +#define io32_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io32_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM7 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io32_get_pwm g_io_soft_pwm[PWM7 - PWM_PINS_OFFSET] #else #define io32_config_pwm(freq) #define io32_set_pwm(value) @@ -4040,9 +4927,15 @@ extern "C" #define io33_set_pwm(value) mcu_set_pwm(PWM8, value) #define io33_get_pwm mcu_get_pwm(PWM8) #elif ASSERT_PIN_EXTENDED(PWM8) -#define io33_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io33_set_pwm(value) io_set_soft_pwm(PWM8, value) -#define io33_get_pwm io_get_soft_pwm(PWM8) +#define io33_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io33_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM8 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io33_get_pwm g_io_soft_pwm[PWM8 - PWM_PINS_OFFSET] #else #define io33_config_pwm(freq) #define io33_set_pwm(value) @@ -4053,9 +4946,15 @@ extern "C" #define io34_set_pwm(value) mcu_set_pwm(PWM9, value) #define io34_get_pwm mcu_get_pwm(PWM9) #elif ASSERT_PIN_EXTENDED(PWM9) -#define io34_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io34_set_pwm(value) io_set_soft_pwm(PWM9, value) -#define io34_get_pwm io_get_soft_pwm(PWM9) +#define io34_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io34_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM9 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io34_get_pwm g_io_soft_pwm[PWM9 - PWM_PINS_OFFSET] #else #define io34_config_pwm(freq) #define io34_set_pwm(value) @@ -4066,9 +4965,15 @@ extern "C" #define io35_set_pwm(value) mcu_set_pwm(PWM10, value) #define io35_get_pwm mcu_get_pwm(PWM10) #elif ASSERT_PIN_EXTENDED(PWM10) -#define io35_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io35_set_pwm(value) io_set_soft_pwm(PWM10, value) -#define io35_get_pwm io_get_soft_pwm(PWM10) +#define io35_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io35_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM10 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io35_get_pwm g_io_soft_pwm[PWM10 - PWM_PINS_OFFSET] #else #define io35_config_pwm(freq) #define io35_set_pwm(value) @@ -4079,9 +4984,15 @@ extern "C" #define io36_set_pwm(value) mcu_set_pwm(PWM11, value) #define io36_get_pwm mcu_get_pwm(PWM11) #elif ASSERT_PIN_EXTENDED(PWM11) -#define io36_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io36_set_pwm(value) io_set_soft_pwm(PWM11, value) -#define io36_get_pwm io_get_soft_pwm(PWM11) +#define io36_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io36_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM11 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io36_get_pwm g_io_soft_pwm[PWM11 - PWM_PINS_OFFSET] #else #define io36_config_pwm(freq) #define io36_set_pwm(value) @@ -4092,9 +5003,15 @@ extern "C" #define io37_set_pwm(value) mcu_set_pwm(PWM12, value) #define io37_get_pwm mcu_get_pwm(PWM12) #elif ASSERT_PIN_EXTENDED(PWM12) -#define io37_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io37_set_pwm(value) io_set_soft_pwm(PWM12, value) -#define io37_get_pwm io_get_soft_pwm(PWM12) +#define io37_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io37_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM12 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io37_get_pwm g_io_soft_pwm[PWM12 - PWM_PINS_OFFSET] #else #define io37_config_pwm(freq) #define io37_set_pwm(value) @@ -4105,9 +5022,15 @@ extern "C" #define io38_set_pwm(value) mcu_set_pwm(PWM13, value) #define io38_get_pwm mcu_get_pwm(PWM13) #elif ASSERT_PIN_EXTENDED(PWM13) -#define io38_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io38_set_pwm(value) io_set_soft_pwm(PWM13, value) -#define io38_get_pwm io_get_soft_pwm(PWM13) +#define io38_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io38_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM13 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io38_get_pwm g_io_soft_pwm[PWM13 - PWM_PINS_OFFSET] #else #define io38_config_pwm(freq) #define io38_set_pwm(value) @@ -4118,9 +5041,15 @@ extern "C" #define io39_set_pwm(value) mcu_set_pwm(PWM14, value) #define io39_get_pwm mcu_get_pwm(PWM14) #elif ASSERT_PIN_EXTENDED(PWM14) -#define io39_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io39_set_pwm(value) io_set_soft_pwm(PWM14, value) -#define io39_get_pwm io_get_soft_pwm(PWM14) +#define io39_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io39_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM14 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io39_get_pwm g_io_soft_pwm[PWM14 - PWM_PINS_OFFSET] #else #define io39_config_pwm(freq) #define io39_set_pwm(value) @@ -4131,9 +5060,15 @@ extern "C" #define io40_set_pwm(value) mcu_set_pwm(PWM15, value) #define io40_get_pwm mcu_get_pwm(PWM15) #elif ASSERT_PIN_EXTENDED(PWM15) -#define io40_config_pwm(freq) {g_soft_pwm_res = mcu_softpwm_freq_config(freq);} -#define io40_set_pwm(value) io_set_soft_pwm(PWM15, value) -#define io40_get_pwm io_get_soft_pwm(PWM15) +#define io40_config_pwm(freq) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(freq); \ + } +#define io40_set_pwm(value) \ + { \ + g_io_soft_pwm[PWM15 - PWM_PINS_OFFSET] = (0xFF & value); \ + } +#define io40_get_pwm g_io_soft_pwm[PWM15 - PWM_PINS_OFFSET] #else #define io40_config_pwm(freq) #define io40_set_pwm(value) @@ -4364,8 +5299,6 @@ extern "C" #define io129_get_analog 0 #endif - - /*output HAL*/ #define _io_hal_config_output_(pin) io##pin##_config_output #define io_hal_config_output(pin) _io_hal_config_output_(pin) @@ -4387,10 +5320,10 @@ extern "C" #define io_hal_get_input(pin) _io_hal_get_input_(pin) /*pwm and servo HAL*/ -#define _io_hal_config_pwm_(pin,freq) io##pin##_config_pwm(freq) -#define io_hal_config_pwm(pin,freq) _io_hal_config_pwm_(pin,freq) -#define _io_hal_set_pwm_(pin,value) io##pin##_set_pwm(value) -#define io_hal_set_pwm(pin,value) _io_hal_set_pwm_(pin,value) +#define _io_hal_config_pwm_(pin, freq) io##pin##_config_pwm(freq) +#define io_hal_config_pwm(pin, freq) _io_hal_config_pwm_(pin, freq) +#define _io_hal_set_pwm_(pin, value) io##pin##_set_pwm(value) +#define io_hal_set_pwm(pin, value) _io_hal_set_pwm_(pin, value) #define _io_hal_get_pwm_(pin) io##pin##_get_pwm #define io_hal_get_pwm(pin) _io_hal_get_pwm_(pin) diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 0e50cf0a6..3a68171d8 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1026,8 +1026,12 @@ extern "C" #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif +#define MCU_HAS_SOFT_PWM_TIMER +#define mcu_set_pwm(X, Y) ({g_io_soft_pwm[X - PWM_PINS_OFFSET] = (0xFF & Y);}) +#define mcu_get_pwm(X) g_io_soft_pwm[X - PWM_PINS_OFFSET] + #define mcu_config_output(X) pinMode(__indirect__(X, BIT), OUTPUT) -#define mcu_config_pwm(X, freq) pinMode(__indirect__(X, BIT), OUTPUT) +#define mcu_config_pwm(X, freq) g_soft_pwm_res = 1;pinMode(__indirect__(X, BIT), OUTPUT) #define mcu_config_input(X) pinMode(__indirect__(X, BIT), INPUT) #define mcu_config_analog(X) mcu_config_input(X) #define mcu_config_pullup(X) pinMode(__indirect__(X, BIT), INPUT_PULLUP) @@ -1039,10 +1043,7 @@ extern "C" #define mcu_clear_output(X) digitalWrite(__indirect__(X, BIT), 0) #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) -#define MCU_HAS_SOFT_PWM_TIMER -#define mcu_softpwm_freq_config(freq) 1 -#define mcu_set_pwm(X, Y) io_set_soft_pwm(X,Y) -#define mcu_get_pwm(X) io_get_soft_pwm(X) + #define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) #define mcu_spi_xmit(X) \ diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index 37882ef1a..bae4deb48 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -627,67 +627,6 @@ uint8_t mcu_get_servo(uint8_t servo) return 0; } -#ifndef mcu_get_input -uint8_t mcu_get_input(uint8_t pin) -{ -} -#endif - -#ifndef mcu_get_output -uint8_t mcu_get_output(uint8_t pin) -{ -} -#endif - -#ifndef mcu_set_output -void mcu_set_output(uint8_t pin) -{ -} -#endif - -#ifndef mcu_clear_output -void mcu_clear_output(uint8_t pin) -{ -} -#endif - -#ifndef mcu_toggle_output -void mcu_toggle_output(uint8_t pin) -{ -} -#endif - -#ifndef mcu_enable_probe_isr -void mcu_enable_probe_isr(void) -{ -} -#endif -#ifndef mcu_disable_probe_isr -void mcu_disable_probe_isr(void) -{ -} -#endif - -// Analog input -#ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) -{ -} -#endif - -// PWM -#ifndef mcu_set_pwm -void mcu_set_pwm(uint8_t pwm, uint8_t value) -{ -} -#endif - -#ifndef mcu_get_pwm -uint8_t mcu_get_pwm(uint8_t pwm) -{ -} -#endif - // ISR // enables all interrupts on the mcu. Must be called to enable all IRS functions #ifndef mcu_enable_global_isr diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index dd0f796bc..37a491219 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -39,7 +39,7 @@ extern "C" #endif #define STEP0 1 #define DIO1 -1 -#define STEP0_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_IO_OFFSET >> 3)-1) +#define STEP0_IO_BYTEOFFSET (STEP0_IO_OFFSET >> 3) #define STEP0_IO_BITMASK (1 << (STEP0_IO_OFFSET & 0x7)) #define DIO1_IO_BYTEOFFSET STEP0_IO_BYTEOFFSET #define DIO1_IO_BITMASK STEP0_IO_BITMASK @@ -58,7 +58,7 @@ extern "C" #endif #define STEP1 2 #define DIO2 -2 -#define STEP1_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_IO_OFFSET >> 3)-1) +#define STEP1_IO_BYTEOFFSET (STEP1_IO_OFFSET >> 3) #define STEP1_IO_BITMASK (1 << (STEP1_IO_OFFSET & 0x7)) #define DIO2_IO_BYTEOFFSET STEP1_IO_BYTEOFFSET #define DIO2_IO_BITMASK STEP1_IO_BITMASK @@ -77,7 +77,7 @@ extern "C" #endif #define STEP2 3 #define DIO3 -3 -#define STEP2_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_IO_OFFSET >> 3)-1) +#define STEP2_IO_BYTEOFFSET (STEP2_IO_OFFSET >> 3) #define STEP2_IO_BITMASK (1 << (STEP2_IO_OFFSET & 0x7)) #define DIO3_IO_BYTEOFFSET STEP2_IO_BYTEOFFSET #define DIO3_IO_BITMASK STEP2_IO_BITMASK @@ -96,7 +96,7 @@ extern "C" #endif #define STEP3 4 #define DIO4 -4 -#define STEP3_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_IO_OFFSET >> 3)-1) +#define STEP3_IO_BYTEOFFSET (STEP3_IO_OFFSET >> 3) #define STEP3_IO_BITMASK (1 << (STEP3_IO_OFFSET & 0x7)) #define DIO4_IO_BYTEOFFSET STEP3_IO_BYTEOFFSET #define DIO4_IO_BITMASK STEP3_IO_BITMASK @@ -115,7 +115,7 @@ extern "C" #endif #define STEP4 5 #define DIO5 -5 -#define STEP4_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_IO_OFFSET >> 3)-1) +#define STEP4_IO_BYTEOFFSET (STEP4_IO_OFFSET >> 3) #define STEP4_IO_BITMASK (1 << (STEP4_IO_OFFSET & 0x7)) #define DIO5_IO_BYTEOFFSET STEP4_IO_BYTEOFFSET #define DIO5_IO_BITMASK STEP4_IO_BITMASK @@ -134,7 +134,7 @@ extern "C" #endif #define STEP5 6 #define DIO6 -6 -#define STEP5_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_IO_OFFSET >> 3)-1) +#define STEP5_IO_BYTEOFFSET (STEP5_IO_OFFSET >> 3) #define STEP5_IO_BITMASK (1 << (STEP5_IO_OFFSET & 0x7)) #define DIO6_IO_BYTEOFFSET STEP5_IO_BYTEOFFSET #define DIO6_IO_BITMASK STEP5_IO_BITMASK @@ -153,7 +153,7 @@ extern "C" #endif #define STEP6 7 #define DIO7 -7 -#define STEP6_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_IO_OFFSET >> 3)-1) +#define STEP6_IO_BYTEOFFSET (STEP6_IO_OFFSET >> 3) #define STEP6_IO_BITMASK (1 << (STEP6_IO_OFFSET & 0x7)) #define DIO7_IO_BYTEOFFSET STEP6_IO_BYTEOFFSET #define DIO7_IO_BITMASK STEP6_IO_BITMASK @@ -172,7 +172,7 @@ extern "C" #endif #define STEP7 8 #define DIO8 -8 -#define STEP7_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_IO_OFFSET >> 3)-1) +#define STEP7_IO_BYTEOFFSET (STEP7_IO_OFFSET >> 3) #define STEP7_IO_BITMASK (1 << (STEP7_IO_OFFSET & 0x7)) #define DIO8_IO_BYTEOFFSET STEP7_IO_BYTEOFFSET #define DIO8_IO_BITMASK STEP7_IO_BITMASK @@ -191,7 +191,7 @@ extern "C" #endif #define DIR0 9 #define DIO9 -9 -#define DIR0_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR0_IO_OFFSET >> 3)-1) +#define DIR0_IO_BYTEOFFSET (DIR0_IO_OFFSET >> 3) #define DIR0_IO_BITMASK (1 << (DIR0_IO_OFFSET & 0x7)) #define DIO9_IO_BYTEOFFSET DIR0_IO_BYTEOFFSET #define DIO9_IO_BITMASK DIR0_IO_BITMASK @@ -210,7 +210,7 @@ extern "C" #endif #define DIR1 10 #define DIO10 -10 -#define DIR1_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR1_IO_OFFSET >> 3)-1) +#define DIR1_IO_BYTEOFFSET (DIR1_IO_OFFSET >> 3) #define DIR1_IO_BITMASK (1 << (DIR1_IO_OFFSET & 0x7)) #define DIO10_IO_BYTEOFFSET DIR1_IO_BYTEOFFSET #define DIO10_IO_BITMASK DIR1_IO_BITMASK @@ -229,7 +229,7 @@ extern "C" #endif #define DIR2 11 #define DIO11 -11 -#define DIR2_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR2_IO_OFFSET >> 3)-1) +#define DIR2_IO_BYTEOFFSET (DIR2_IO_OFFSET >> 3) #define DIR2_IO_BITMASK (1 << (DIR2_IO_OFFSET & 0x7)) #define DIO11_IO_BYTEOFFSET DIR2_IO_BYTEOFFSET #define DIO11_IO_BITMASK DIR2_IO_BITMASK @@ -248,7 +248,7 @@ extern "C" #endif #define DIR3 12 #define DIO12 -12 -#define DIR3_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR3_IO_OFFSET >> 3)-1) +#define DIR3_IO_BYTEOFFSET (DIR3_IO_OFFSET >> 3) #define DIR3_IO_BITMASK (1 << (DIR3_IO_OFFSET & 0x7)) #define DIO12_IO_BYTEOFFSET DIR3_IO_BYTEOFFSET #define DIO12_IO_BITMASK DIR3_IO_BITMASK @@ -267,7 +267,7 @@ extern "C" #endif #define DIR4 13 #define DIO13 -13 -#define DIR4_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR4_IO_OFFSET >> 3)-1) +#define DIR4_IO_BYTEOFFSET (DIR4_IO_OFFSET >> 3) #define DIR4_IO_BITMASK (1 << (DIR4_IO_OFFSET & 0x7)) #define DIO13_IO_BYTEOFFSET DIR4_IO_BYTEOFFSET #define DIO13_IO_BITMASK DIR4_IO_BITMASK @@ -286,7 +286,7 @@ extern "C" #endif #define DIR5 14 #define DIO14 -14 -#define DIR5_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR5_IO_OFFSET >> 3)-1) +#define DIR5_IO_BYTEOFFSET (DIR5_IO_OFFSET >> 3) #define DIR5_IO_BITMASK (1 << (DIR5_IO_OFFSET & 0x7)) #define DIO14_IO_BYTEOFFSET DIR5_IO_BYTEOFFSET #define DIO14_IO_BITMASK DIR5_IO_BITMASK @@ -305,7 +305,7 @@ extern "C" #endif #define DIR6 15 #define DIO15 -15 -#define DIR6_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR6_IO_OFFSET >> 3)-1) +#define DIR6_IO_BYTEOFFSET (DIR6_IO_OFFSET >> 3) #define DIR6_IO_BITMASK (1 << (DIR6_IO_OFFSET & 0x7)) #define DIO15_IO_BYTEOFFSET DIR6_IO_BYTEOFFSET #define DIO15_IO_BITMASK DIR6_IO_BITMASK @@ -324,7 +324,7 @@ extern "C" #endif #define DIR7 16 #define DIO16 -16 -#define DIR7_IO_BYTEOFFSET (IC74HC595_COUNT - (DIR7_IO_OFFSET >> 3)-1) +#define DIR7_IO_BYTEOFFSET (DIR7_IO_OFFSET >> 3) #define DIR7_IO_BITMASK (1 << (DIR7_IO_OFFSET & 0x7)) #define DIO16_IO_BYTEOFFSET DIR7_IO_BYTEOFFSET #define DIO16_IO_BITMASK DIR7_IO_BITMASK @@ -343,7 +343,7 @@ extern "C" #endif #define STEP0_EN 17 #define DIO17 -17 -#define STEP0_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP0_EN_IO_OFFSET >> 3)-1) +#define STEP0_EN_IO_BYTEOFFSET (STEP0_EN_IO_OFFSET >> 3) #define STEP0_EN_IO_BITMASK (1 << (STEP0_EN_IO_OFFSET & 0x7)) #define DIO17_IO_BYTEOFFSET STEP0_EN_IO_BYTEOFFSET #define DIO17_IO_BITMASK STEP0_EN_IO_BITMASK @@ -362,7 +362,7 @@ extern "C" #endif #define STEP1_EN 18 #define DIO18 -18 -#define STEP1_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP1_EN_IO_OFFSET >> 3)-1) +#define STEP1_EN_IO_BYTEOFFSET (STEP1_EN_IO_OFFSET >> 3) #define STEP1_EN_IO_BITMASK (1 << (STEP1_EN_IO_OFFSET & 0x7)) #define DIO18_IO_BYTEOFFSET STEP1_EN_IO_BYTEOFFSET #define DIO18_IO_BITMASK STEP1_EN_IO_BITMASK @@ -381,7 +381,7 @@ extern "C" #endif #define STEP2_EN 19 #define DIO19 -19 -#define STEP2_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP2_EN_IO_OFFSET >> 3)-1) +#define STEP2_EN_IO_BYTEOFFSET (STEP2_EN_IO_OFFSET >> 3) #define STEP2_EN_IO_BITMASK (1 << (STEP2_EN_IO_OFFSET & 0x7)) #define DIO19_IO_BYTEOFFSET STEP2_EN_IO_BYTEOFFSET #define DIO19_IO_BITMASK STEP2_EN_IO_BITMASK @@ -400,7 +400,7 @@ extern "C" #endif #define STEP3_EN 20 #define DIO20 -20 -#define STEP3_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP3_EN_IO_OFFSET >> 3)-1) +#define STEP3_EN_IO_BYTEOFFSET (STEP3_EN_IO_OFFSET >> 3) #define STEP3_EN_IO_BITMASK (1 << (STEP3_EN_IO_OFFSET & 0x7)) #define DIO20_IO_BYTEOFFSET STEP3_EN_IO_BYTEOFFSET #define DIO20_IO_BITMASK STEP3_EN_IO_BITMASK @@ -419,7 +419,7 @@ extern "C" #endif #define STEP4_EN 21 #define DIO21 -21 -#define STEP4_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP4_EN_IO_OFFSET >> 3)-1) +#define STEP4_EN_IO_BYTEOFFSET (STEP4_EN_IO_OFFSET >> 3) #define STEP4_EN_IO_BITMASK (1 << (STEP4_EN_IO_OFFSET & 0x7)) #define DIO21_IO_BYTEOFFSET STEP4_EN_IO_BYTEOFFSET #define DIO21_IO_BITMASK STEP4_EN_IO_BITMASK @@ -438,7 +438,7 @@ extern "C" #endif #define STEP5_EN 22 #define DIO22 -22 -#define STEP5_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP5_EN_IO_OFFSET >> 3)-1) +#define STEP5_EN_IO_BYTEOFFSET (STEP5_EN_IO_OFFSET >> 3) #define STEP5_EN_IO_BITMASK (1 << (STEP5_EN_IO_OFFSET & 0x7)) #define DIO22_IO_BYTEOFFSET STEP5_EN_IO_BYTEOFFSET #define DIO22_IO_BITMASK STEP5_EN_IO_BITMASK @@ -457,7 +457,7 @@ extern "C" #endif #define STEP6_EN 23 #define DIO23 -23 -#define STEP6_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP6_EN_IO_OFFSET >> 3)-1) +#define STEP6_EN_IO_BYTEOFFSET (STEP6_EN_IO_OFFSET >> 3) #define STEP6_EN_IO_BITMASK (1 << (STEP6_EN_IO_OFFSET & 0x7)) #define DIO23_IO_BYTEOFFSET STEP6_EN_IO_BYTEOFFSET #define DIO23_IO_BITMASK STEP6_EN_IO_BITMASK @@ -476,7 +476,7 @@ extern "C" #endif #define STEP7_EN 24 #define DIO24 -24 -#define STEP7_EN_IO_BYTEOFFSET (IC74HC595_COUNT - (STEP7_EN_IO_OFFSET >> 3)-1) +#define STEP7_EN_IO_BYTEOFFSET (STEP7_EN_IO_OFFSET >> 3) #define STEP7_EN_IO_BITMASK (1 << (STEP7_EN_IO_OFFSET & 0x7)) #define DIO24_IO_BYTEOFFSET STEP7_EN_IO_BYTEOFFSET #define DIO24_IO_BITMASK STEP7_EN_IO_BITMASK @@ -495,7 +495,7 @@ extern "C" #endif #define PWM0 25 #define DIO25 -25 -#define PWM0_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM0_IO_OFFSET >> 3)-1) +#define PWM0_IO_BYTEOFFSET (PWM0_IO_OFFSET >> 3) #define PWM0_IO_BITMASK (1 << (PWM0_IO_OFFSET & 0x7)) #define DIO25_IO_BYTEOFFSET PWM0_IO_BYTEOFFSET #define DIO25_IO_BITMASK PWM0_IO_BITMASK @@ -514,7 +514,7 @@ extern "C" #endif #define PWM1 26 #define DIO26 -26 -#define PWM1_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM1_IO_OFFSET >> 3)-1) +#define PWM1_IO_BYTEOFFSET (PWM1_IO_OFFSET >> 3) #define PWM1_IO_BITMASK (1 << (PWM1_IO_OFFSET & 0x7)) #define DIO26_IO_BYTEOFFSET PWM1_IO_BYTEOFFSET #define DIO26_IO_BITMASK PWM1_IO_BITMASK @@ -533,7 +533,7 @@ extern "C" #endif #define PWM2 27 #define DIO27 -27 -#define PWM2_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM2_IO_OFFSET >> 3)-1) +#define PWM2_IO_BYTEOFFSET (PWM2_IO_OFFSET >> 3) #define PWM2_IO_BITMASK (1 << (PWM2_IO_OFFSET & 0x7)) #define DIO27_IO_BYTEOFFSET PWM2_IO_BYTEOFFSET #define DIO27_IO_BITMASK PWM2_IO_BITMASK @@ -552,7 +552,7 @@ extern "C" #endif #define PWM3 28 #define DIO28 -28 -#define PWM3_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM3_IO_OFFSET >> 3)-1) +#define PWM3_IO_BYTEOFFSET (PWM3_IO_OFFSET >> 3) #define PWM3_IO_BITMASK (1 << (PWM3_IO_OFFSET & 0x7)) #define DIO28_IO_BYTEOFFSET PWM3_IO_BYTEOFFSET #define DIO28_IO_BITMASK PWM3_IO_BITMASK @@ -571,7 +571,7 @@ extern "C" #endif #define PWM4 29 #define DIO29 -29 -#define PWM4_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM4_IO_OFFSET >> 3)-1) +#define PWM4_IO_BYTEOFFSET (PWM4_IO_OFFSET >> 3) #define PWM4_IO_BITMASK (1 << (PWM4_IO_OFFSET & 0x7)) #define DIO29_IO_BYTEOFFSET PWM4_IO_BYTEOFFSET #define DIO29_IO_BITMASK PWM4_IO_BITMASK @@ -590,7 +590,7 @@ extern "C" #endif #define PWM5 30 #define DIO30 -30 -#define PWM5_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM5_IO_OFFSET >> 3)-1) +#define PWM5_IO_BYTEOFFSET (PWM5_IO_OFFSET >> 3) #define PWM5_IO_BITMASK (1 << (PWM5_IO_OFFSET & 0x7)) #define DIO30_IO_BYTEOFFSET PWM5_IO_BYTEOFFSET #define DIO30_IO_BITMASK PWM5_IO_BITMASK @@ -609,7 +609,7 @@ extern "C" #endif #define PWM6 31 #define DIO31 -31 -#define PWM6_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM6_IO_OFFSET >> 3)-1) +#define PWM6_IO_BYTEOFFSET (PWM6_IO_OFFSET >> 3) #define PWM6_IO_BITMASK (1 << (PWM6_IO_OFFSET & 0x7)) #define DIO31_IO_BYTEOFFSET PWM6_IO_BYTEOFFSET #define DIO31_IO_BITMASK PWM6_IO_BITMASK @@ -628,7 +628,7 @@ extern "C" #endif #define PWM7 32 #define DIO32 -32 -#define PWM7_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM7_IO_OFFSET >> 3)-1) +#define PWM7_IO_BYTEOFFSET (PWM7_IO_OFFSET >> 3) #define PWM7_IO_BITMASK (1 << (PWM7_IO_OFFSET & 0x7)) #define DIO32_IO_BYTEOFFSET PWM7_IO_BYTEOFFSET #define DIO32_IO_BITMASK PWM7_IO_BITMASK @@ -647,7 +647,7 @@ extern "C" #endif #define PWM8 33 #define DIO33 -33 -#define PWM8_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM8_IO_OFFSET >> 3)-1) +#define PWM8_IO_BYTEOFFSET (PWM8_IO_OFFSET >> 3) #define PWM8_IO_BITMASK (1 << (PWM8_IO_OFFSET & 0x7)) #define DIO33_IO_BYTEOFFSET PWM8_IO_BYTEOFFSET #define DIO33_IO_BITMASK PWM8_IO_BITMASK @@ -666,7 +666,7 @@ extern "C" #endif #define PWM9 34 #define DIO34 -34 -#define PWM9_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM9_IO_OFFSET >> 3)-1) +#define PWM9_IO_BYTEOFFSET (PWM9_IO_OFFSET >> 3) #define PWM9_IO_BITMASK (1 << (PWM9_IO_OFFSET & 0x7)) #define DIO34_IO_BYTEOFFSET PWM9_IO_BYTEOFFSET #define DIO34_IO_BITMASK PWM9_IO_BITMASK @@ -685,7 +685,7 @@ extern "C" #endif #define PWM10 35 #define DIO35 -35 -#define PWM10_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM10_IO_OFFSET >> 3)-1) +#define PWM10_IO_BYTEOFFSET (PWM10_IO_OFFSET >> 3) #define PWM10_IO_BITMASK (1 << (PWM10_IO_OFFSET & 0x7)) #define DIO35_IO_BYTEOFFSET PWM10_IO_BYTEOFFSET #define DIO35_IO_BITMASK PWM10_IO_BITMASK @@ -704,7 +704,7 @@ extern "C" #endif #define PWM11 36 #define DIO36 -36 -#define PWM11_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM11_IO_OFFSET >> 3)-1) +#define PWM11_IO_BYTEOFFSET (PWM11_IO_OFFSET >> 3) #define PWM11_IO_BITMASK (1 << (PWM11_IO_OFFSET & 0x7)) #define DIO36_IO_BYTEOFFSET PWM11_IO_BYTEOFFSET #define DIO36_IO_BITMASK PWM11_IO_BITMASK @@ -723,7 +723,7 @@ extern "C" #endif #define PWM12 37 #define DIO37 -37 -#define PWM12_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM12_IO_OFFSET >> 3)-1) +#define PWM12_IO_BYTEOFFSET (PWM12_IO_OFFSET >> 3) #define PWM12_IO_BITMASK (1 << (PWM12_IO_OFFSET & 0x7)) #define DIO37_IO_BYTEOFFSET PWM12_IO_BYTEOFFSET #define DIO37_IO_BITMASK PWM12_IO_BITMASK @@ -742,7 +742,7 @@ extern "C" #endif #define PWM13 38 #define DIO38 -38 -#define PWM13_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM13_IO_OFFSET >> 3)-1) +#define PWM13_IO_BYTEOFFSET (PWM13_IO_OFFSET >> 3) #define PWM13_IO_BITMASK (1 << (PWM13_IO_OFFSET & 0x7)) #define DIO38_IO_BYTEOFFSET PWM13_IO_BYTEOFFSET #define DIO38_IO_BITMASK PWM13_IO_BITMASK @@ -761,7 +761,7 @@ extern "C" #endif #define PWM14 39 #define DIO39 -39 -#define PWM14_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM14_IO_OFFSET >> 3)-1) +#define PWM14_IO_BYTEOFFSET (PWM14_IO_OFFSET >> 3) #define PWM14_IO_BITMASK (1 << (PWM14_IO_OFFSET & 0x7)) #define DIO39_IO_BYTEOFFSET PWM14_IO_BYTEOFFSET #define DIO39_IO_BITMASK PWM14_IO_BITMASK @@ -780,7 +780,7 @@ extern "C" #endif #define PWM15 40 #define DIO40 -40 -#define PWM15_IO_BYTEOFFSET (IC74HC595_COUNT - (PWM15_IO_OFFSET >> 3)-1) +#define PWM15_IO_BYTEOFFSET (PWM15_IO_OFFSET >> 3) #define PWM15_IO_BITMASK (1 << (PWM15_IO_OFFSET & 0x7)) #define DIO40_IO_BYTEOFFSET PWM15_IO_BYTEOFFSET #define DIO40_IO_BITMASK PWM15_IO_BITMASK @@ -799,7 +799,7 @@ extern "C" #endif #define SERVO0 41 #define DIO41 -41 -#define SERVO0_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO0_IO_OFFSET >> 3)-1) +#define SERVO0_IO_BYTEOFFSET (SERVO0_IO_OFFSET >> 3) #define SERVO0_IO_BITMASK (1 << (SERVO0_IO_OFFSET & 0x7)) #define DIO41_IO_BYTEOFFSET SERVO0_IO_BYTEOFFSET #define DIO41_IO_BITMASK SERVO0_IO_BITMASK @@ -818,7 +818,7 @@ extern "C" #endif #define SERVO1 42 #define DIO42 -42 -#define SERVO1_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO1_IO_OFFSET >> 3)-1) +#define SERVO1_IO_BYTEOFFSET (SERVO1_IO_OFFSET >> 3) #define SERVO1_IO_BITMASK (1 << (SERVO1_IO_OFFSET & 0x7)) #define DIO42_IO_BYTEOFFSET SERVO1_IO_BYTEOFFSET #define DIO42_IO_BITMASK SERVO1_IO_BITMASK @@ -837,7 +837,7 @@ extern "C" #endif #define SERVO2 43 #define DIO43 -43 -#define SERVO2_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO2_IO_OFFSET >> 3)-1) +#define SERVO2_IO_BYTEOFFSET (SERVO2_IO_OFFSET >> 3) #define SERVO2_IO_BITMASK (1 << (SERVO2_IO_OFFSET & 0x7)) #define DIO43_IO_BYTEOFFSET SERVO2_IO_BYTEOFFSET #define DIO43_IO_BITMASK SERVO2_IO_BITMASK @@ -856,7 +856,7 @@ extern "C" #endif #define SERVO3 44 #define DIO44 -44 -#define SERVO3_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO3_IO_OFFSET >> 3)-1) +#define SERVO3_IO_BYTEOFFSET (SERVO3_IO_OFFSET >> 3) #define SERVO3_IO_BITMASK (1 << (SERVO3_IO_OFFSET & 0x7)) #define DIO44_IO_BYTEOFFSET SERVO3_IO_BYTEOFFSET #define DIO44_IO_BITMASK SERVO3_IO_BITMASK @@ -875,7 +875,7 @@ extern "C" #endif #define SERVO4 45 #define DIO45 -45 -#define SERVO4_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO4_IO_OFFSET >> 3)-1) +#define SERVO4_IO_BYTEOFFSET (SERVO4_IO_OFFSET >> 3) #define SERVO4_IO_BITMASK (1 << (SERVO4_IO_OFFSET & 0x7)) #define DIO45_IO_BYTEOFFSET SERVO4_IO_BYTEOFFSET #define DIO45_IO_BITMASK SERVO4_IO_BITMASK @@ -894,7 +894,7 @@ extern "C" #endif #define SERVO5 46 #define DIO46 -46 -#define SERVO5_IO_BYTEOFFSET (IC74HC595_COUNT - (SERVO5_IO_OFFSET >> 3)-1) +#define SERVO5_IO_BYTEOFFSET (SERVO5_IO_OFFSET >> 3) #define SERVO5_IO_BITMASK (1 << (SERVO5_IO_OFFSET & 0x7)) #define DIO46_IO_BYTEOFFSET SERVO5_IO_BYTEOFFSET #define DIO46_IO_BITMASK SERVO5_IO_BITMASK @@ -913,7 +913,7 @@ extern "C" #endif #define DOUT0 47 #define DIO47 -47 -#define DOUT0_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT0_IO_OFFSET >> 3)-1) +#define DOUT0_IO_BYTEOFFSET (DOUT0_IO_OFFSET >> 3) #define DOUT0_IO_BITMASK (1 << (DOUT0_IO_OFFSET & 0x7)) #define DIO47_IO_BYTEOFFSET DOUT0_IO_BYTEOFFSET #define DIO47_IO_BITMASK DOUT0_IO_BITMASK @@ -932,7 +932,7 @@ extern "C" #endif #define DOUT1 48 #define DIO48 -48 -#define DOUT1_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT1_IO_OFFSET >> 3)-1) +#define DOUT1_IO_BYTEOFFSET (DOUT1_IO_OFFSET >> 3) #define DOUT1_IO_BITMASK (1 << (DOUT1_IO_OFFSET & 0x7)) #define DIO48_IO_BYTEOFFSET DOUT1_IO_BYTEOFFSET #define DIO48_IO_BITMASK DOUT1_IO_BITMASK @@ -951,7 +951,7 @@ extern "C" #endif #define DOUT2 49 #define DIO49 -49 -#define DOUT2_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT2_IO_OFFSET >> 3)-1) +#define DOUT2_IO_BYTEOFFSET (DOUT2_IO_OFFSET >> 3) #define DOUT2_IO_BITMASK (1 << (DOUT2_IO_OFFSET & 0x7)) #define DIO49_IO_BYTEOFFSET DOUT2_IO_BYTEOFFSET #define DIO49_IO_BITMASK DOUT2_IO_BITMASK @@ -970,7 +970,7 @@ extern "C" #endif #define DOUT3 50 #define DIO50 -50 -#define DOUT3_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT3_IO_OFFSET >> 3)-1) +#define DOUT3_IO_BYTEOFFSET (DOUT3_IO_OFFSET >> 3) #define DOUT3_IO_BITMASK (1 << (DOUT3_IO_OFFSET & 0x7)) #define DIO50_IO_BYTEOFFSET DOUT3_IO_BYTEOFFSET #define DIO50_IO_BITMASK DOUT3_IO_BITMASK @@ -989,7 +989,7 @@ extern "C" #endif #define DOUT4 51 #define DIO51 -51 -#define DOUT4_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT4_IO_OFFSET >> 3)-1) +#define DOUT4_IO_BYTEOFFSET (DOUT4_IO_OFFSET >> 3) #define DOUT4_IO_BITMASK (1 << (DOUT4_IO_OFFSET & 0x7)) #define DIO51_IO_BYTEOFFSET DOUT4_IO_BYTEOFFSET #define DIO51_IO_BITMASK DOUT4_IO_BITMASK @@ -1008,7 +1008,7 @@ extern "C" #endif #define DOUT5 52 #define DIO52 -52 -#define DOUT5_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT5_IO_OFFSET >> 3)-1) +#define DOUT5_IO_BYTEOFFSET (DOUT5_IO_OFFSET >> 3) #define DOUT5_IO_BITMASK (1 << (DOUT5_IO_OFFSET & 0x7)) #define DIO52_IO_BYTEOFFSET DOUT5_IO_BYTEOFFSET #define DIO52_IO_BITMASK DOUT5_IO_BITMASK @@ -1027,7 +1027,7 @@ extern "C" #endif #define DOUT6 53 #define DIO53 -53 -#define DOUT6_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT6_IO_OFFSET >> 3)-1) +#define DOUT6_IO_BYTEOFFSET (DOUT6_IO_OFFSET >> 3) #define DOUT6_IO_BITMASK (1 << (DOUT6_IO_OFFSET & 0x7)) #define DIO53_IO_BYTEOFFSET DOUT6_IO_BYTEOFFSET #define DIO53_IO_BITMASK DOUT6_IO_BITMASK @@ -1046,7 +1046,7 @@ extern "C" #endif #define DOUT7 54 #define DIO54 -54 -#define DOUT7_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT7_IO_OFFSET >> 3)-1) +#define DOUT7_IO_BYTEOFFSET (DOUT7_IO_OFFSET >> 3) #define DOUT7_IO_BITMASK (1 << (DOUT7_IO_OFFSET & 0x7)) #define DIO54_IO_BYTEOFFSET DOUT7_IO_BYTEOFFSET #define DIO54_IO_BITMASK DOUT7_IO_BITMASK @@ -1065,7 +1065,7 @@ extern "C" #endif #define DOUT8 55 #define DIO55 -55 -#define DOUT8_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT8_IO_OFFSET >> 3)-1) +#define DOUT8_IO_BYTEOFFSET (DOUT8_IO_OFFSET >> 3) #define DOUT8_IO_BITMASK (1 << (DOUT8_IO_OFFSET & 0x7)) #define DIO55_IO_BYTEOFFSET DOUT8_IO_BYTEOFFSET #define DIO55_IO_BITMASK DOUT8_IO_BITMASK @@ -1084,7 +1084,7 @@ extern "C" #endif #define DOUT9 56 #define DIO56 -56 -#define DOUT9_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT9_IO_OFFSET >> 3)-1) +#define DOUT9_IO_BYTEOFFSET (DOUT9_IO_OFFSET >> 3) #define DOUT9_IO_BITMASK (1 << (DOUT9_IO_OFFSET & 0x7)) #define DIO56_IO_BYTEOFFSET DOUT9_IO_BYTEOFFSET #define DIO56_IO_BITMASK DOUT9_IO_BITMASK @@ -1103,7 +1103,7 @@ extern "C" #endif #define DOUT10 57 #define DIO57 -57 -#define DOUT10_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT10_IO_OFFSET >> 3)-1) +#define DOUT10_IO_BYTEOFFSET (DOUT10_IO_OFFSET >> 3) #define DOUT10_IO_BITMASK (1 << (DOUT10_IO_OFFSET & 0x7)) #define DIO57_IO_BYTEOFFSET DOUT10_IO_BYTEOFFSET #define DIO57_IO_BITMASK DOUT10_IO_BITMASK @@ -1122,7 +1122,7 @@ extern "C" #endif #define DOUT11 58 #define DIO58 -58 -#define DOUT11_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT11_IO_OFFSET >> 3)-1) +#define DOUT11_IO_BYTEOFFSET (DOUT11_IO_OFFSET >> 3) #define DOUT11_IO_BITMASK (1 << (DOUT11_IO_OFFSET & 0x7)) #define DIO58_IO_BYTEOFFSET DOUT11_IO_BYTEOFFSET #define DIO58_IO_BITMASK DOUT11_IO_BITMASK @@ -1141,7 +1141,7 @@ extern "C" #endif #define DOUT12 59 #define DIO59 -59 -#define DOUT12_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT12_IO_OFFSET >> 3)-1) +#define DOUT12_IO_BYTEOFFSET (DOUT12_IO_OFFSET >> 3) #define DOUT12_IO_BITMASK (1 << (DOUT12_IO_OFFSET & 0x7)) #define DIO59_IO_BYTEOFFSET DOUT12_IO_BYTEOFFSET #define DIO59_IO_BITMASK DOUT12_IO_BITMASK @@ -1160,7 +1160,7 @@ extern "C" #endif #define DOUT13 60 #define DIO60 -60 -#define DOUT13_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT13_IO_OFFSET >> 3)-1) +#define DOUT13_IO_BYTEOFFSET (DOUT13_IO_OFFSET >> 3) #define DOUT13_IO_BITMASK (1 << (DOUT13_IO_OFFSET & 0x7)) #define DIO60_IO_BYTEOFFSET DOUT13_IO_BYTEOFFSET #define DIO60_IO_BITMASK DOUT13_IO_BITMASK @@ -1179,7 +1179,7 @@ extern "C" #endif #define DOUT14 61 #define DIO61 -61 -#define DOUT14_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT14_IO_OFFSET >> 3)-1) +#define DOUT14_IO_BYTEOFFSET (DOUT14_IO_OFFSET >> 3) #define DOUT14_IO_BITMASK (1 << (DOUT14_IO_OFFSET & 0x7)) #define DIO61_IO_BYTEOFFSET DOUT14_IO_BYTEOFFSET #define DIO61_IO_BITMASK DOUT14_IO_BITMASK @@ -1198,7 +1198,7 @@ extern "C" #endif #define DOUT15 62 #define DIO62 -62 -#define DOUT15_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT15_IO_OFFSET >> 3)-1) +#define DOUT15_IO_BYTEOFFSET (DOUT15_IO_OFFSET >> 3) #define DOUT15_IO_BITMASK (1 << (DOUT15_IO_OFFSET & 0x7)) #define DIO62_IO_BYTEOFFSET DOUT15_IO_BYTEOFFSET #define DIO62_IO_BITMASK DOUT15_IO_BITMASK @@ -1217,7 +1217,7 @@ extern "C" #endif #define DOUT16 63 #define DIO63 -63 -#define DOUT16_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT16_IO_OFFSET >> 3)-1) +#define DOUT16_IO_BYTEOFFSET (DOUT16_IO_OFFSET >> 3) #define DOUT16_IO_BITMASK (1 << (DOUT16_IO_OFFSET & 0x7)) #define DIO63_IO_BYTEOFFSET DOUT16_IO_BYTEOFFSET #define DIO63_IO_BITMASK DOUT16_IO_BITMASK @@ -1236,7 +1236,7 @@ extern "C" #endif #define DOUT17 64 #define DIO64 -64 -#define DOUT17_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT17_IO_OFFSET >> 3)-1) +#define DOUT17_IO_BYTEOFFSET (DOUT17_IO_OFFSET >> 3) #define DOUT17_IO_BITMASK (1 << (DOUT17_IO_OFFSET & 0x7)) #define DIO64_IO_BYTEOFFSET DOUT17_IO_BYTEOFFSET #define DIO64_IO_BITMASK DOUT17_IO_BITMASK @@ -1255,7 +1255,7 @@ extern "C" #endif #define DOUT18 65 #define DIO65 -65 -#define DOUT18_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT18_IO_OFFSET >> 3)-1) +#define DOUT18_IO_BYTEOFFSET (DOUT18_IO_OFFSET >> 3) #define DOUT18_IO_BITMASK (1 << (DOUT18_IO_OFFSET & 0x7)) #define DIO65_IO_BYTEOFFSET DOUT18_IO_BYTEOFFSET #define DIO65_IO_BITMASK DOUT18_IO_BITMASK @@ -1274,7 +1274,7 @@ extern "C" #endif #define DOUT19 66 #define DIO66 -66 -#define DOUT19_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT19_IO_OFFSET >> 3)-1) +#define DOUT19_IO_BYTEOFFSET (DOUT19_IO_OFFSET >> 3) #define DOUT19_IO_BITMASK (1 << (DOUT19_IO_OFFSET & 0x7)) #define DIO66_IO_BYTEOFFSET DOUT19_IO_BYTEOFFSET #define DIO66_IO_BITMASK DOUT19_IO_BITMASK @@ -1293,7 +1293,7 @@ extern "C" #endif #define DOUT20 67 #define DIO67 -67 -#define DOUT20_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT20_IO_OFFSET >> 3)-1) +#define DOUT20_IO_BYTEOFFSET (DOUT20_IO_OFFSET >> 3) #define DOUT20_IO_BITMASK (1 << (DOUT20_IO_OFFSET & 0x7)) #define DIO67_IO_BYTEOFFSET DOUT20_IO_BYTEOFFSET #define DIO67_IO_BITMASK DOUT20_IO_BITMASK @@ -1312,7 +1312,7 @@ extern "C" #endif #define DOUT21 68 #define DIO68 -68 -#define DOUT21_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT21_IO_OFFSET >> 3)-1) +#define DOUT21_IO_BYTEOFFSET (DOUT21_IO_OFFSET >> 3) #define DOUT21_IO_BITMASK (1 << (DOUT21_IO_OFFSET & 0x7)) #define DIO68_IO_BYTEOFFSET DOUT21_IO_BYTEOFFSET #define DIO68_IO_BITMASK DOUT21_IO_BITMASK @@ -1331,7 +1331,7 @@ extern "C" #endif #define DOUT22 69 #define DIO69 -69 -#define DOUT22_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT22_IO_OFFSET >> 3)-1) +#define DOUT22_IO_BYTEOFFSET (DOUT22_IO_OFFSET >> 3) #define DOUT22_IO_BITMASK (1 << (DOUT22_IO_OFFSET & 0x7)) #define DIO69_IO_BYTEOFFSET DOUT22_IO_BYTEOFFSET #define DIO69_IO_BITMASK DOUT22_IO_BITMASK @@ -1350,7 +1350,7 @@ extern "C" #endif #define DOUT23 70 #define DIO70 -70 -#define DOUT23_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT23_IO_OFFSET >> 3)-1) +#define DOUT23_IO_BYTEOFFSET (DOUT23_IO_OFFSET >> 3) #define DOUT23_IO_BITMASK (1 << (DOUT23_IO_OFFSET & 0x7)) #define DIO70_IO_BYTEOFFSET DOUT23_IO_BYTEOFFSET #define DIO70_IO_BITMASK DOUT23_IO_BITMASK @@ -1369,7 +1369,7 @@ extern "C" #endif #define DOUT24 71 #define DIO71 -71 -#define DOUT24_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT24_IO_OFFSET >> 3)-1) +#define DOUT24_IO_BYTEOFFSET (DOUT24_IO_OFFSET >> 3) #define DOUT24_IO_BITMASK (1 << (DOUT24_IO_OFFSET & 0x7)) #define DIO71_IO_BYTEOFFSET DOUT24_IO_BYTEOFFSET #define DIO71_IO_BITMASK DOUT24_IO_BITMASK @@ -1388,7 +1388,7 @@ extern "C" #endif #define DOUT25 72 #define DIO72 -72 -#define DOUT25_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT25_IO_OFFSET >> 3)-1) +#define DOUT25_IO_BYTEOFFSET (DOUT25_IO_OFFSET >> 3) #define DOUT25_IO_BITMASK (1 << (DOUT25_IO_OFFSET & 0x7)) #define DIO72_IO_BYTEOFFSET DOUT25_IO_BYTEOFFSET #define DIO72_IO_BITMASK DOUT25_IO_BITMASK @@ -1407,7 +1407,7 @@ extern "C" #endif #define DOUT26 73 #define DIO73 -73 -#define DOUT26_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT26_IO_OFFSET >> 3)-1) +#define DOUT26_IO_BYTEOFFSET (DOUT26_IO_OFFSET >> 3) #define DOUT26_IO_BITMASK (1 << (DOUT26_IO_OFFSET & 0x7)) #define DIO73_IO_BYTEOFFSET DOUT26_IO_BYTEOFFSET #define DIO73_IO_BITMASK DOUT26_IO_BITMASK @@ -1426,7 +1426,7 @@ extern "C" #endif #define DOUT27 74 #define DIO74 -74 -#define DOUT27_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT27_IO_OFFSET >> 3)-1) +#define DOUT27_IO_BYTEOFFSET (DOUT27_IO_OFFSET >> 3) #define DOUT27_IO_BITMASK (1 << (DOUT27_IO_OFFSET & 0x7)) #define DIO74_IO_BYTEOFFSET DOUT27_IO_BYTEOFFSET #define DIO74_IO_BITMASK DOUT27_IO_BITMASK @@ -1445,7 +1445,7 @@ extern "C" #endif #define DOUT28 75 #define DIO75 -75 -#define DOUT28_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT28_IO_OFFSET >> 3)-1) +#define DOUT28_IO_BYTEOFFSET (DOUT28_IO_OFFSET >> 3) #define DOUT28_IO_BITMASK (1 << (DOUT28_IO_OFFSET & 0x7)) #define DIO75_IO_BYTEOFFSET DOUT28_IO_BYTEOFFSET #define DIO75_IO_BITMASK DOUT28_IO_BITMASK @@ -1464,7 +1464,7 @@ extern "C" #endif #define DOUT29 76 #define DIO76 -76 -#define DOUT29_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT29_IO_OFFSET >> 3)-1) +#define DOUT29_IO_BYTEOFFSET (DOUT29_IO_OFFSET >> 3) #define DOUT29_IO_BITMASK (1 << (DOUT29_IO_OFFSET & 0x7)) #define DIO76_IO_BYTEOFFSET DOUT29_IO_BYTEOFFSET #define DIO76_IO_BITMASK DOUT29_IO_BITMASK @@ -1483,7 +1483,7 @@ extern "C" #endif #define DOUT30 77 #define DIO77 -77 -#define DOUT30_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT30_IO_OFFSET >> 3)-1) +#define DOUT30_IO_BYTEOFFSET (DOUT30_IO_OFFSET >> 3) #define DOUT30_IO_BITMASK (1 << (DOUT30_IO_OFFSET & 0x7)) #define DIO77_IO_BYTEOFFSET DOUT30_IO_BYTEOFFSET #define DIO77_IO_BITMASK DOUT30_IO_BITMASK @@ -1502,7 +1502,7 @@ extern "C" #endif #define DOUT31 78 #define DIO78 -78 -#define DOUT31_IO_BYTEOFFSET (IC74HC595_COUNT - (DOUT31_IO_OFFSET >> 3)-1) +#define DOUT31_IO_BYTEOFFSET (DOUT31_IO_OFFSET >> 3) #define DOUT31_IO_BITMASK (1 << (DOUT31_IO_OFFSET & 0x7)) #define DIO78_IO_BYTEOFFSET DOUT31_IO_BYTEOFFSET #define DIO78_IO_BITMASK DOUT31_IO_BITMASK @@ -1518,7 +1518,7 @@ extern "C" #error "The maximum number of chained IC74HC595 is 7" #endif -#if (IC74HC595_COUNT>0) +#if (IC74HC595_COUNT > 0) #ifndef __indirect__ #define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) From d0405d6c261c848e99f0e0e9164073fb8f8e2cf0 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 12 Jul 2023 00:11:33 +0100 Subject: [PATCH 016/168] fixed ESP8266 compilation --- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 3a68171d8..1c1aff349 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1027,6 +1027,8 @@ extern "C" #endif #define MCU_HAS_SOFT_PWM_TIMER +extern uint8_t g_io_soft_pwm[16]; +extern uint8_t g_soft_pwm_res; #define mcu_set_pwm(X, Y) ({g_io_soft_pwm[X - PWM_PINS_OFFSET] = (0xFF & Y);}) #define mcu_get_pwm(X) g_io_soft_pwm[X - PWM_PINS_OFFSET] From 29a736f683faa1fe2a9507d96062cb85fe5498f4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 12 Jul 2023 23:25:13 +0100 Subject: [PATCH 017/168] updated tools to new IO HAL --- uCNC/cnc_config.h | 2 +- uCNC/src/hal/tools/tools/pen_servo.c | 8 ++++---- uCNC/src/hal/tools/tools/spindle_besc.c | 8 ++++---- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index e200aa080..3ad8ce253 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -452,7 +452,7 @@ extern "C" * helps to reduce code size if features are not needed * */ #ifndef DISABLE_ALL_CONTROLS -// #define DISABLE_ALL_CONTROLS +#define DISABLE_ALL_CONTROLS #endif #ifndef DISABLE_ALL_LIMITS // #define DISABLE_ALL_LIMITS diff --git a/uCNC/src/hal/tools/tools/pen_servo.c b/uCNC/src/hal/tools/tools/pen_servo.c index 4c360a5d3..c98dc2de1 100644 --- a/uCNC/src/hal/tools/tools/pen_servo.c +++ b/uCNC/src/hal/tools/tools/pen_servo.c @@ -44,14 +44,14 @@ static uint8_t speed; static void startup_code(void) { #if ASSERT_PIN(PEN_SERVO) - mcu_set_servo(PEN_SERVO, PEN_SERVO_LOW); + io_set_pwm(PEN_SERVO, PEN_SERVO_LOW); #endif } static void shutdown_code(void) { #if ASSERT_PIN(PEN_SERVO) - mcu_set_servo(PEN_SERVO, PEN_SERVO_LOW); + io_set_pwm(PEN_SERVO, PEN_SERVO_LOW); #endif } @@ -71,13 +71,13 @@ static void set_speed(int16_t value) if ((value <= 0)) { #if ASSERT_PIN(PEN_SERVO) - mcu_set_servo(PEN_SERVO, PEN_SERVO_LOW); + io_set_pwm(PEN_SERVO, PEN_SERVO_LOW); #endif } else { #if ASSERT_PIN(PEN_SERVO) - mcu_set_servo(PEN_SERVO, (uint8_t)value); + io_set_pwm(PEN_SERVO, (uint8_t)value); #endif } diff --git a/uCNC/src/hal/tools/tools/spindle_besc.c b/uCNC/src/hal/tools/tools/spindle_besc.c index d39109c58..6c5c58154 100644 --- a/uCNC/src/hal/tools/tools/spindle_besc.c +++ b/uCNC/src/hal/tools/tools/spindle_besc.c @@ -65,12 +65,12 @@ static void startup_code(void) // do whatever routine you need to do here to arm the ESC #if ASSERT_PIN(SPINDLE_BESC_POWER_RELAY) #if ASSERT_PIN(SPINDLE_BESC_SERVO) - mcu_set_servo(SPINDLE_BESC_SERVO, SPINDLE_BESC_MID); + io_set_pwm(SPINDLE_BESC_SERVO, SPINDLE_BESC_MID); #endif io_set_output(SPINDLE_BESC_POWER_RELAY); cnc_delay_ms(1000); #if ASSERT_PIN(SPINDLE_BESC_SERVO) - mcu_set_servo(SPINDLE_BESC_SERVO, SPINDLE_BESC_LOW); + io_set_pwm(SPINDLE_BESC_SERVO, SPINDLE_BESC_LOW); #endif cnc_delay_ms(2000); #endif @@ -100,13 +100,13 @@ static void set_speed(int16_t value) if ((value <= 0)) { #if ASSERT_PIN(SPINDLE_BESC_SERVO) - mcu_set_servo(SPINDLE_BESC_SERVO, SPINDLE_BESC_LOW); + io_set_pwm(SPINDLE_BESC_SERVO, SPINDLE_BESC_LOW); #endif } else { #if ASSERT_PIN(SPINDLE_BESC_SERVO) - mcu_set_servo(SPINDLE_BESC_SERVO, (uint8_t)value); + io_set_pwm(SPINDLE_BESC_SERVO, (uint8_t)value); #endif } From 38fb680ddced402e13e5412ba4c15f2ed78e66e9 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 15 Jul 2023 10:57:37 +0100 Subject: [PATCH 018/168] Update cnc_build.h --- uCNC/src/cnc_build.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index 9964e749e..66fddde4c 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -24,8 +24,8 @@ extern "C" { #endif -#define CNC_MAJOR_MINOR_VERSION "1.7" -#define CNC_PATCH_VERSION ".3" +#define CNC_MAJOR_MINOR_VERSION "1.8" +#define CNC_PATCH_VERSION ".x" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION From b3165fc5b04df4d770f4b526131a60e40ae13d82 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 15 Jul 2023 15:59:37 +0100 Subject: [PATCH 019/168] limit max plasma up and down speed --- uCNC/src/hal/tools/tools/plasma_thc.c | 31 +++++++++++++++++++-------- 1 file changed, 22 insertions(+), 9 deletions(-) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 7500cefcd..5ba0eeb5f 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -182,22 +182,30 @@ bool plasma_thc_probe_and_start(void) void itp_rt_stepbits(uint8_t *stepbits, uint8_t *dirs) { int8_t step_error = plasma_step_error; - if (!step_error) + + // no error or no steps being performed + if (!step_error || !*stepbits) { return; } if (step_error > 0) { - *stepbits |= PLASMA_STEPPERS_MASK; - *dirs &= ~PLASMA_STEPPERS_MASK; + if (step_error == 1) + { + *stepbits |= PLASMA_STEPPERS_MASK; + *dirs &= ~PLASMA_STEPPERS_MASK; + } step_error--; } if (step_error < 0) { - *stepbits |= PLASMA_STEPPERS_MASK; - *dirs |= PLASMA_STEPPERS_MASK; + if (step_error == -1) + { + *stepbits |= PLASMA_STEPPERS_MASK; + *dirs |= PLASMA_STEPPERS_MASK; + } step_error++; } @@ -296,7 +304,7 @@ bool plasma_thc_update_loop(void *ptr) } } - if (plasma_thc_up()) + if (plasma_thc_up() && !plasma_step_error) { // option 1 - modify the planner block // this assumes Z is not moving in this motion @@ -305,9 +313,12 @@ bool plasma_thc_update_loop(void *ptr) // p->dirbits &= 0xFB; // option 2 - mask the step bits directly - plasma_step_error = 1; + // clamp tool max step rate according to the actual motion feed + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = 1 + (uint8_t)max_feed_ratio; } - else if (plasma_thc_down()) + else if (plasma_thc_down() && !plasma_step_error) { // option 1 - modify the planner block // this assumes Z is not moving in this motion @@ -316,7 +327,9 @@ bool plasma_thc_update_loop(void *ptr) // p->dirbits |= 4; // option 2 - mask the step bits directly - plasma_step_error = -1; + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = -(1 + (uint8_t)max_feed_ratio); } else { From 9b45f4b70c05b78dc8cc515621238fa079eb93ca Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 15 Jul 2023 20:10:03 +0100 Subject: [PATCH 020/168] cleanup code and helper macros for plasma thc - reset configs - cleanup code and helper macros for plasma thc --- docs/mcumap_gen.xlsx | Bin 464549 -> 468967 bytes uCNC/cnc_config.h | 16 +- uCNC/cnc_hal_config.h | 96 +++- uCNC/src/cnc.c | 8 +- uCNC/src/cnc_build.h | 2 +- uCNC/src/cnc_hal_config_helper.h | 22 +- uCNC/src/core/interpolator.c | 8 - uCNC/src/core/planner.h | 2 +- uCNC/src/hal/boards/avr/boardmap_uno.h | 20 +- uCNC/src/hal/mcus/virtual/mcu_virtual.c | 14 +- uCNC/src/hal/mcus/virtual/mcumap_virtual.h | 159 +++++- uCNC/src/hal/tools/tools/plasma_thc.c | 560 +++++++++++---------- 12 files changed, 565 insertions(+), 342 deletions(-) diff --git a/docs/mcumap_gen.xlsx b/docs/mcumap_gen.xlsx index 70e29b4d691f0033d9c6cb91430ec3708522844a..52cd0f8609e6403cf34912b956f5985323ce5b6c 100644 GIT binary patch delta 33331 zcmeFX^lvC`CQjn;WY|H5-Zm zH=_AHn$IG=oBLbeCP0f1lP->y4DQd&6K|#{NX-9mVjK;)XguqieJ#{V)aj!CtWWO+ z#ZHK`Az|l93vP_1A-X(^sIBH;@LZ6V(w{oEPP^(NGNhOei~ zG@(4;c+h`yJ4xAvyM~p5wZa4AQi4HEicpB4ikPU_wJ6BXkpLKd~&eQ*Lm-h&PC{#T?Y%eSLygXhMc6MCo!XRKwMzN8OMs6VNAqT ztDI1}0IWVG+xRU0@uebWy(;$3ijQwnZKOjQ$*7imZ!N+)0XZojhF5oud%&S1lO+zR zMjSgW+NgB^@S#}x`HoRrhC|~geb+~G1Sv)&Lbjy4WQMMkLg}pI49lw84O#~DLQ{tU zLpA(?6pbXtWV6MrB>d#uw2tRT>ucYLF#diClTqZ=PI#7v`}EY}mur*R+pepz0%f5^t?A?Tifh-z6fv$H4Ap=>}j)LJcares01vO z$~0{B)rXu&q1PW!{DcgANA|O{z#`Y~yvt#&TtB@upL^sZN3qlXaPq>7+I&x7f#Rco zy(wBtWw~9f7))WJMgxrppLSZvG(r|pB!p#kEcmJV)+%~(d&Q=ErbNvMx#%deQqE_O7mNG4!?Cti+EBBe2ZLD_YIEy){CsnQ5_4UccN3mldWBik`H^D6bvSX#$rHEPI{$j#P z<5A4MLfai`5MCCwt48s4c`Ji^fFZM`-Cml#r|8@z2JwN#&jlx_-U=jic_o`?ttMfa z_eY!$Q=+EXU3<+Jrzhs7s6pPs8IGmHsKg~CWm66B1E%btiRET$QOzx`>T%mY_tlN% zo|CZxXhc4R4d$ddDx`6mgVT=JQaj`~5l8MYwTdJm*`WXy369qn6ZK&cS?j=n=)HldvjwT_f3oxGc`$ z4jJ$HysZ2ci8pT}mGJSdtlYadJ}=J?-1}1h0M6orlR%f0ZCAz6A!S#eU~Sf>)TsU1 z@sfOHT2z*6fG15o3TFM>Y@Y;UTN>6$NyGH9ALT0RAK%|vj!VzwN9i23KO%4Qp&Asv zL&IMDp#H5;klUa{_&qOLw1(%CIX_r!Y2(bu*B1(%sa%5w76VlEdxv%hkIEUarw9lz zSb~KKF789E^Nl`OQ$5fT5XcaoAwpL$QORn%(a{ls0oyJv+*d~-kHOwoE%}VL9#BbS{?qV~_NL z^>HJdfJ28t$w&=?1Z4B`VjK6IKOwJ(B};AJuN_JE^3i+1K4B**$SO~QZ0t}G{n28d z^ew_pu%bc0TfMfBd)Jy&FVo)2t}imiWYsh-j7fRsYM)&Bt5M#*}ih#?w?u4zx)o{3XEkD|tV8 z%vSm+6!IbRj{08(tmVX#)j~I3L1|_)K|oOPf>zHXkwO71)Tcm3f+{4P3%BPe>6Vgx zHM}FxA?US^UVI(fg_`zqi>Rf1*<8xPh@|$zp(rjxvj)ewA`J?OzY~>zmKaquqmT24 z`NEt5nnGkU8@A~(jN4Ny(rD%rDZZq!`oN&9_Q}4#vz!UR?gnj$&ydlgIsY(z7O?s? zghjHBS|5V4IyD23;vLVFr#ex7DTVc0_ikPXlID_mGj1JHg_hefm^f~aydoIEMb$^n zSas6cL6XOZx)E3sr#bKQr=k-reSLS_|vhBfGxTeqQFWoEFvb9)fK4(yO$kc z{#(}IPC}EKY1R5&($b7^E9v7Nj6*4&2i0f#<(g;&;Fu54H`iQ?+FvWobrH=xa6pf= zw8wyZ8;Q-o>@mb$=7a^C`z&NV3dBj9JZuTuu~3_vY!#-YPNG9YJXCinD}_h#0gb`J z1PQ51bnM4B%0UjmYf8njAA2fXjqhdO%{Vr%SWU&??MVgiPrOF{aOr$#bnKLJ*4BbQ zb3?nGiQmko=vT&BGbFLtMp2SOEK2FW*oC9Er`#T$n7hfrl1K&9i5@7}9K zzxZ)>DhSiBXVYUCFFYY!_S!6HZ`rO;(wqZ@#%Oc=jlRto*~m%+@pc|uI?$Kf;8m;Z zhq&Psbobx8FX}Q0kljg~Xvw>}e(L$eG|TgF`<@{$zjj5(ZQxbNy?qH=01(%)8C z7?+p@Hg@S^J2@-hpG}{IRd$W?b_FdRv+B^Z$+vPa=<&DjclnJX)p0(bh&(rr$#s)FRnQ=$?&x5kkf2Kh|y{tXM40^p0|<(PJLlg#ThTReQ`n{ZKtd zLQ2KgKSCzG<{U7Z<1Y1%xevBm^36P_22nJ7`S&dT-b$YlK*^Ge??bt=e}Yl$KzTf7 zp4i`lGlR)C=ePs?DaP6HmXCFiv`3HWgMPGjxi=N^O;^VMVZErqN%F(0ukYFU-WBk$ zy8a;Oxw(A2?&RcuLj$`qZz1=;Wroqg9@dYjB_1z0flqg5u`P!!0UwD|P5}cv)-}3;%`&=xLK!_IsGFRBe0Q4Qm_{KCD^tBYMkG zZ9dE}tLEDOv_Z}J<5MGrV7G5Y9OWK*Vu4G4;>gOcQk)@?D`vgo6_EQRmmWVy$U*Js zUAyFa63^=n!(^vJV%XagNs*p=r<;?O{j(9+k*d>5+rx?DC)nk(py$rbfR`b5{I-=a zKzNw7^8SeW@bO~U=<%}I>huWM!A4-o{q?+mA9fjNoOJM&?hmnPk#kgthj_~!lzO%G z?grZM=6Vx4->}Z%C=rKp@c;VD!e=jyz?RU>!EJt ziy^VrMYFbFLQ2O&N?n&up+>SCR+J+oP=*Jdj}h6LWq+Z$gU^fifmDJAp6%?y)eBIXnuWgr2}Q?$h+$m?nzry-^S3wKK}EwEg49kTYdct-HB8upaI*U z7Gb3tLkz?%Iu^H1x~fz&e$u*ml7u8C!e6<)`kUPUi{5&97uDK9m?D!DzNgTsVKOqr zacYOqE=VqkQ%$&i^MmG1L-+&mvb*f~vI}vIGPGRJc`Le^pxGsLlehr)hC?mMTh zC_?_^89I>VA7Fr~k4F_sMl znC_Hg>P^hMI(8B1M6vk-e1f^HyM=J*y!)Ar*%&vn%FaJ6XrOoW^K8Jr1TTfgxg&o= zjbf+wqV_b|@;3qbIJ$r@iah9Z5s6WLW!*&sa&$fla7NyaU8>D)+b39SRHh)TqU(z* z9F-O2cMqaS=G9#5u;@h5b#O?S+;yO7otZr;9sMqnQGZzSV#`wo=j60~(|*NSFvu+m z)l?W?^s8si6jT>;Xt|rmC7~=kfSr)%z^rFlu|418rIX^@ zX#bFq;N&e-ZTbeOk%=@|Coxhk+>v*{TB^sPP{MI@(mZirKzQL}kg9E>I?k$+{lXXm zfBSVRUdEtM$FBN>P$XuZ*1fFkXP@h6RUkpVW_8P&T=9~;jLJzg!oo&(DKCoj*C@64 z+r$hTs=|mZB|rMUq5*b2SJ%2|hPT){5cZq#r*#27N!-@{xPSG&{#6>{(pIwCH4~9g zwj3w~EoYzqSmkY8qL%!%OMED$J?QiX@MCHqA4PWEFV(;t#HI8oDLUDvZ#k<*4`21>;BES+jNANHS7ar* z6B;&bB@n2c+_GLA?^g+)?i%ke#KKx@H3QR{DwNa@uuO*LvP$q?osecTE|=V>3GY~w z%U+U#vTH2fApN0okCdY8-Q=2NGe5=Fld8^eA!7(Xu%t0&X4!P0C1!cJ32;j& zOHg^WGs-Q#s_8SnK!_JdAydO#zMEZiaH|S4a^Zch62EwPZgarHorxHeF~LTK?VSkx)h%*yI;pK#6~k^35j}qZyMgU{$HH zr}*MaB00vwFLuG~h+%d=``)4ffM(tj+|2Zgm^wIMGY7E;!C#2hYzke&@#P=h+9iKh ziQ03xZvwZvwlngSX_{`IenXAj=N&`1SXPeGm#XLrlC9m(-#Tf&oanRmO~Z_jhTC!~ zkEL@((?@AUpZoOwm>cCKjnT@7`<-CtHzj(qEG4n~=i$mM{1|V6Vbj~e&~HXn-ZTU6 zGwfCd23|-4QBu4L>!BZNl{7S7%=g(PyC#~iyQEP#h%(OGRe95wa3o~k@-bR+B@j9m z3q<;!sH>+JKo-D_zi;^+%+~la0bTKUt=R!pKPCd+6a{p_TP@kvq>{O4Sjuq&@DdDQ zyuG0Cf^7T&3h+%X{{9cD!7E6Q*_e_>W9|yOD^BU3;R!h>-!!H83(yw%nib;<`S|R| zR~XlN=9p<9-+8(PCqvSnIdz*}(5uhTge&~cL4V89?}0Vj#k{3sH;|4xb__shb?M954){p1-5TvtOHq*DSq)h( z+twZK^Z<7<#k?cDERNFUBHnZ8W9kbJz9-+d6jo3OF{5tM8|p|)lB^gQXN>t*z~uaC z(7~-pf@z0mb45SB2=?ze9<14E&m$n(>@nUImPyycK~0ydty9# zpM+&?vSn?}JeXZ_R26XLBxAc#)MlCBFeH=nH1~KArILLM)v2zTEi0^i_?HMVWeZ-} zeX=-aV}mY|W!C)PGX4^M)4S7+R!umZWitRxrG(h?>n^)(+5I6RYwrr&U-nLTZ^{<6KD>#+kKdMnUl^+UOjx4U()Dj-lADe8Lb;rBM`tlza z{XZ^xkPE;8+c}7~&$wlW=?jX2RcZ(4Ke(j%Q5T)q@F;kINk=yTmJK8Y4>IcjvNuuc zyb6E!a;D2%Ti=yguJ+mbrb)Yw>LlbT)Bp2Fygffy?7xuYS;n7L$yLrDfg8hrs}(YP z&6i5=1G*#5yb^RSy$=@Ot7zKZ;#6RZXMf!OGA~g}{*pW0&qlyU;9n|P!et7OgED2| zGE+xUmn|j1c$!l;%y&Uw!VehP_&)opA56kojl5_t*KS^e^+J|K^F{8;{`Tj}Kf|q) zWtQ8q16dcnFg(xGhFo~c;W1n>ovHZK#64w_9cISqqQU~KIIVnpobNvaZGKarm)|K0 zWKcM~83+xYrc*rBc#RR^6xfCF9HjQ5xMUXg5#DBtuRWp@h9AfA{|;H#DsSnM+r;fF z@t%fuylt!Bc*m2GE0=vt4dZR!ISEKqyafgx@QM8!b?}ZlDVl|i1G~|DZ`>x zOnt6-dM9YV=XWX=WhRQPc#5B&{1crG7rp;aH0s${(1zXSm(w`XQa`heU-O4_cYPH} zL(Z>qMWQq`q~_&{u?y5Fb&J75%YZ?obH!Xl*~W_ba?R_7BfxDd!8*GhAnTrzpC42M zQKwYQ6RA?)25$rctYuW{HR@6r*TK66QEBRfz9rULs9*qO-T#mVVX>yNI#1acj=oVy}Y4HUu=7=M+n~#%eyw?i!brftVdg0 ziIQclKu_^au^2WgUukg0DN&xtIX7!IBXyF!mhggyR*kv|9E+~6<{L->84OLGrxImV z?Lu_ep(*n1@xb=82QMbf^B!=!7Qu@N*vxr)9|C%}T&}=(%r|GCU^}sLZloG=a19TG z3Oo#p@HAY+t_x_32crd$7JT#@^T2i;d}qHi*XIFVzFoJn28F}YbxUubmmQf9zY%(* zXnjp^jWtYCmvevl*nIb{5=MVUd!{wuSh1xj_%PS^$u|v)>1xug5s%4ps=BprpiAkU z{gak2guxye0P#mYi_;Nh+4p}-sqb_lsYwYbzrLRA~ zozFx3&ijhyKe-l(hmm`^R#NVvW-U#AW<1_Y=e~Yw)x4>Yz;a|Ru>HPZ(|>>SmBesw zg3qDwQhx&Kn=1b`U|?C<`U&8P7i{GGLo|!8QN-!3-po{f(e%sZDl`l1VNXgz!?rglCB5o_a1N=f-|y z9uI2D1nknuNDPN2pmMl^PK6kD-@0!8Vv{9C;?8BlQC`dP#ng9}08X4+(S*`0yqG50 zpJ!WlePt?=(BGOgPq|Oq77kl9E}b^3@)r`g@e<{e>cGtA)-zuD(CYn(<6A~7VKlAG zcOr8YKOn!qXx_MnaNC(qDVY|G_o?wXQTi(l!eHVQ&g_TB%iYn+N*o+cWa>(WP2z-- zFXJT;k{dp94dOfsN9jS+&lgA<#B|nABGobVV;>)Ja8^G&rLc)J&?u}g{8a)W2BAtb zUnv|v59otXr5Rf5Cw3sz_``=*e-|H?EkHhEX^`i8frW}6Todbmnka*sP=ie=f~f-D zC_O!EiMz-71{~NSN8*;WV@T=(K5vnP3K$-t`Ea;@MDf5(nh&o+^F679U_8w@q*YMd zB2FtQ=X2Z5lZN{-i8+kir3T*w%%Y@cX*nDjSZ^aI0%Y6&0vrkX(vB^u3qc^IBAin1 zA0-={QZGCQZFj`UL z@V5d^x174r$$Og8Iw_K0^#!{vmgQ|+;U_xvdRj%?*weT2iz<#nDb%b5#gwJZfPOq# z6Opy;+p+$xTNSk-VM5vO=*rikhs=(_r8Bv?$cU_aqCXg>2r#0@5Z= z2iX^u3Yk`%_U2nZBFU*?P=A7R(a*`~ASzsZui+Q5kUN;+)%Saytw_C$-g(18gxsf|fRT~w>dUu8?FMooEMUZ1lW!Z#rQ>V_-PsFJX_F!i~t z3XR$eser*1>2hN?MH5l&t5_Ra&v<^jK}-A@m7$Eo!J|Z3|7ne?Lg3S8dBjCHK62T< z>Y~b{0mBc8{-7Hy@xVT`~)Bwm)$dIUN<0tY@ z&s#GZS0sy(UF%*41tf{vE)JMkBq*+P3h6IvCmJfw)Ul*1=-%}wM&Y*01UT463R0Dq zX(rMbTV#LLsZuXEehwJB&#Jq!>TSvn+O`BpXfT*P4M-{nfu>Sfhe-@ z!S~t8L!eXu6gyBX%T;P>LJF%0TFSDQ?Lp&!Gs=RDf)8*;a*6Vc|1v5?(`ee>P>|YH zQRXQYnm(Z^HAmOaJ-RYFPMvtTa;+?4_-MYEH2uZnv=~pURM(b~GEV@qf$SO;iu_8; zi?A+eb^I+$RA2EQ{PKc-lt5j=>*yS{o;2QY>xhPn3*kUqEVO`P4QA^Q?Dwljg;zW_7^j}$4?%F1d~wz>g814Sgaioc3@T&j7YO{a(b7E->r_f`5AlD^%&>U^SZUZD^uG%JJCd)n zr~pcKWwZ~8FC?k=IO&PC?)e8S%q+8cV#i8cs32D|oF>#EgTi_b(csahj(tD*!2}VJ z|E(FiL2d;7_=afB!Jw_0X!s=ZM!wEkoD0fgU}-lCTaKspU(`%u?nIGxGY z5byuc#TTQ|m+Fo(N_|%#WWp^5^uHEvET$YEyjfsdDNdB_q1P$iP^z717}x#vY~Q2~@-+yGwW=qSMKl~( zd(gJz;R+lUz2;3+f^(Xx)TO~W(WjaclyAi53#Z~Gczzm-0vbumJ;(^!<#vq^q>?1% zzO0PZuZg_A7Wn-~U3^x_2lLR`karj4ow|==3CAn-$%M?@{MVty zmRzjg=OCCoDKT0q&i?~cie^zDvQ5d?@<`BAeE1>2Q@dDZ#gatnoHk(y73)uc4F4o#!r`M!}*)UD)}jIK4# zr*A6{<{XwSlY6?<@|5=*oLRA)GDayWl&Q%~TI12eQ?od8$^pflO=mCMuYtnJ$9f2DYomPH zVS{C((x%dw)ONR@5Dcnv9#Qyzyrj`UI#sUwgGuUp2{{;4NU^~QmTDa)sID{*1L#lX zyzT!*W|Zjm{NG4#;FI^#94zA1}Fx3yHboxv>efz5`L}iUDd#Kcsl4%oF~_^L=bGPyD|PqOeS?)?nI` z{poh+)8cYAfuVVLaPMy+7o6=GmPsvF`>G-D+t=7fk+a)_J7xzSgpK|h}>SDmu z&J)}=>csz4g#6@*{6f>LUgT+W4c5R{(?;gX_uzd(&4Twlj_hkP-Np9V-7M4z_U75f z&Oaeqq9s#Lur+_pq!jzh7TnirG{sS7XPnh)s9%XT(JkE+<&EB7_lwS+oO_~ODB3#) z9_e12xo=pp1W_icQVzYa1$rJ&y*a;}oV|uSaX-`C4snRZ(p_ne+}v&;`?*TSD{M=7 z+>%mMU6)Gd5H-$$?&8edVBGFX4A3Xq#TA+MLpuuf1t?Y92o6={@ug%FJ;+(RUoG!c z07f-!r-5#Y-*3C$B7RvV9{g7&%nj^p3~Uh$as=jd(6n19fk?E@+(9P>qseSEwP`C9 z?y#r34|z6)Ng|c zhXSvc7K;GJ*$G+r43$P`y(mg^lEQ6g}RJ`q4~siAAj!zsX3h(3OYn5@lHz~DqRLve0Z(I z8#M);d^r3}!;P7)GeUj!#o0&y4=t#ABWr#vpgkgKHMlDaDd zNFidl`K%7(AK!hSJfw6()44ac-zgZszv7mDL1#gr-5Kvt(dGv6I}Hmav_|c9Ek~zN zejW9S`@P$Dj^mw5))X^yN^O23eW^f*@k!Td-}}~COEUw6Ffpn5Ck-R+q%V@c)0AZX z!A^ut0@idTXK!m6>v>=8t;Z75V|TH{C9?U_n*SyabtD^E)2l5<-d4dy3KCgubMUen z`kCh=*JI>EqvR0g-8;p2-n??h zrS61*k{!D{j2fE6=zKevpvl+IBy%T^h@8dOKEO+vzx@%MRd-IEg>+?Y90?9y@7E-4 zv_}SaEr{7Wy@==)2vIEb#h<$H8;CKk-&^1V=I4=F2&FHk!`7Y1%}+}mOiPrdRRX`_G%)f7z7*RaWhM z1-_wYdAU4&%#QT@8juZ>hnLEr~WUu zo!?-nzP(~2Z8_+e~){s-=JG-)DE*2lpo?>rq*u>EU#;+e5!C(Qjo8Gqc}o)i~<^ zEgr~b!Yj7d&kIP1T$|GAgN$?|cW1mP?NXd@!)*}xs;ucSC4pm9 z)m99er~OE#b0fiUCN8|M@(l1a9m#ZU)Ev&l|2Kf}kV>v=H?cTYT}*sc&nYP9xV<*ZE%_U3$5#`9DKyA3?!`Kl9 z7RjDjopFA9GF_@zT~K8Dl%V!Um?UZT|JD`0=>OIghJ93B8R^(UPn@j#pd|YQnc>ib zFKte2TLMm>enmysF3r`>F#I%^&3`yl>fncFnH;QUF^geVc^1)TbPI}TqzsRlr1a7{ zTyb328CPg@sC|n|6V4#o>ypu=Z!1J9zdhy$IAo9~aS}{S2%)0kh;)bo4MyRJUWHKA zr6;HjtDH}q%b>&dNT>}uOHVvw5rrE@?2)$ZpO7LztFTaspp`hNC=H|YNS48f++hOm zksAcwKP9q7?hwHx#z`no5TQm%C}dFIWR!NOWC{uu2@Wl?^(pCg&xE}$$z zW3Mbz9v{q0Xd8c095yZ89t*1OKIaXSCl>heBxK9%xpkGZFyOcUs#<7wi4g52d%v^w z%(vUm2?-h--1Is)2Ty%G_wUwDNFGL`=s6jc1_P1L1S1lI4W~G8n2GEBEl0hIDg)d3zI%OI zxre?;LLov9QI|}G%B7+({&N9R*aQkRA{B-AiFh!yEfvKEkrT?2hC&S$gQBoNO_M<< z0Z`CMB1EXT4bRb0w-BMWMWDY{b5M91ywgxDP|(9TWVZL7ARr{7L-Ej2nE^fyQya&9 zofgMQHNwYu4QV_Lug?+T49XLQFD+=p7g@FO!-PsiHf9>iwfpMr!|G@RP^fZo+TkBH z#$@a$F$C52sP1R0)dcdB5!sK$NEzQY?|?&3$mq>Jk5c1tv1YN!Q@4J)KAsR-1{ayqQw7{1%{BpFGc6&H0UoLT_u1edr0WC&pXZA15r9*Aubl znHPUxs^>I=*|N;encHM;J(7Yps||dfAQ0cCco6 zrnS_=tZIMt{1D6&b= zS07i|iFnkFx&_4me{=SQV@O&4xKAxgaMBS+D_6KQ5U}gddQMU8dS?o%=k9zoo7B(a z$sRgT?+JZACH9t~oHulBT&PNC%r@AwX~tSh!uNim^{r2(u%|qc*NAt}#mn6n(+ss} zM+&6LnJEpvOLEB!-HaanrkN>dMS6=AX#LqQ+#~IZ=C6dZ02zoI2m7UW#;|E<@>ye_ zPRvOx0|dSK#}eJ>ff-%b&i?67zlGz*m57(xjk8Ss4O-cB21VDqrY<`q1wjU5FqXse zYoGBKx5#&nQKwA5QwfSW7iNQmRok*rYjb=juiRXNH>)aFM)OYMx@)_8IGnPnPfjha zh2&;Le8eOlodPvZodbOML@Fc%WFOcY2@*xSTlz9Q{nNw5f4_!MjGIX)_mRHzY8#QP zw59kKdH+N{rfKW>0L9HB&j2%P{XMe;6Fo*o;^w391BD6AdQL}pFK&9cOq%73K|z8#=rgs4vAvYQJ|uPVCm6KL!pI^)}cIWs47DF zf`Ta6;FE@8{{P)Dy#Hsz{GSc;|FaE~S%<=dDAX`khmwc_p86u_s2%?~S~!)g z5=w4FO{M-lf>NY-hvnM`4f6;L@VD`}>A$|2t?KY-hABrtQA64Yuhd`QUbcB>A}M z+4is_>Hqk5wC!PgCmVLtVB~+b{%|+icDMLvZMp67QFZkJROOI*#qVmiqpJ^8hUXFR zx@yh=sLy3cW5W#-Rdak%wo%o3*AyisgIvjJS#lPm^Ly@1|H`()U~{%cTlcavCmnCa z9k}1`_A~GHG2;iS(?7|RN0vpy6H=fMR-ko`mtLdi@u%B)@x)1f#mW3p_E1tjaAp?O z6&APz&|FdXKfs$ouvdqYv3EFIz@v{VOuPw}wFIahwlQ6;CfpqjJX~%4cUb;VGX4&- z^+?wQ`+ql8w;lPWM6b&kZv-OAyxWeAl8pi*(i_rvoeb^Rz$GP?RKh0rVP%#ic@Br!|=L!Q=iCY4- z0qCzl-Kfc}roGr|0H4+CZ&%S>-m9O=uA+y$SFg*iD7p{)Hovb3I_~-L#>^ZDY&P<5 zep#by+P9?0JUYlYDkqiO@dwCZK6VtxpvKy|gJwbY&@40^VPKe}AH@{vb=(ysTBPIv{ ze_qDW?yc)l$o%fABw<~ONXWTm%ZSJWzYQbun6I3fW4>;6WeP>qK!`fk*577G&xbL& z5L!_CcdIA*eZrGdzpQ>u!m9I(3Eluq5er>k@Wg?nY@w$EVPUtla$8hK&H~m|*HXa+m}FkfGV04h zHkQDlH3k|E8N0<8&AOCbZ%67K*&SYblH69lN)V|eEt5N;u8*|JF7vak)=~($fHfud z6DlEQ)3KbYyV9?>g8eJ)CWOH#GMHrMJk}{9!81|8aog?un`?=Um8JENVD%%gV~i>8 zJS;>KhhxZ#&B1~+8x{O^%I|>ZTBvag3xJR1f@5@w27k$ig}$mKgV;Yjhk`$nrMf;- z)LByeVnVGTMXj9-wCk0Eih{F^xJ&6z&BoGPoDsTFmo~Wq_{~3nMVcT`ctjkV<&#lemeBDU^MVRRmNTKnsQnRDAAi{k-o864 zeaYG}9}2pYR^~gQ_zmX4Ea7u;><-;Gzc;Uh)Ha!2sbvho1dI;099~~(-02mq9dvQ> zb=yoMA6*jq-ODNH*aVymMr%6y^5o6?Y{rp?EnRQ+QVOm#y7WeKIvTochU+ai3;H*@ zbVWaR%y8ZeP8DA!$N6RZr{%2ei`!A=l|zQpX6=ty$1MGe{u~UNFSbjLo8@CM-^BHt zEZJ|@eV;C}O{@|<$SF}VnV@dr5sa(PA$oP^3lMr{Q!V*%2T+7jUJ476}7GIQ}Dydc47$t&)2 zCX4BmSOS9YMj_6cGqKbKC(L3Z~p|dy*=ELhriwb7$0(EV^AT%ug}bJzTLa(yv1U z6U}URFt;c$CVRVom=pF32T66k8o|>cLvf8knC6Og`}~8PU?@(VW=A&)6G>Pu%8{gB z_^Tg?i4!CNFkc|UgRaWcZo{crzm1ge?2(N9*93!ia=FI$uryFpDG?ONvBP zFqEdodh5kmijE+IshQUOiDfb93RgF7zX0PY?|Z zG+i3}=s78d*V$Dp8NntGN{VS@`b59(qm|ei$n`Qu+tbuiO(x(D&Xj`t@-62iE!QhoANRp55Dm+l`Q6?{{d4AY@QhV@# zlso-5rRq-ZSBLAa6nhL}A=S*4zaeGWC>FW=+)3E{P;bS7D~o=gX_k1!VjID_tDPopZ*|N5cg$l+DZTgio|a*uUj{YZ&JN~c-SY}` zocPOqM-hYk@ptUZv2n!3e9Kbgd3t>3G)~#x2oC2})_Z z%!idG?%V<`db?6F?JsF+N()hMI;N1UgTrLHn76Vfu3jw`arv&}I6+%EV41fDe7-F% zlyQ-TR52BFyRqS6+l-xaVaV7OX4bjYvJ)nRc@4PBy<;q$k0OKjc%9i7pA9kIeyw$o@7;7-3Y#UU$CAyWkSMm_qgT z*I^VfGbGbFQ*X?o$-~t7W=MLD`6BZ8Wv5wl(=Xy1cWw(@Hrn)v=+M?82uXvlUM+lA zq2U)deoC;tjG=#q619*eQwg?QQi+VGoOtx{uI@ zU?#jJ+jEnJ1Y8bbKK&gKwhp30b{T@>or4Re1dpuRTRx4GQM~kriS+)9iVJvQe zP!9-1xpdgZ-9_S)V4DC?B2YBlGm|7JsrR0O=d!wM_k&=mKc&tUS-Rb$`vRjn2&T?; z=q<6TjRBYaZ81w2yKvKIGK(B%=+<`48=T$zn8?rccL7vC(tJNMEkF=tbm-0HaPrru zH%p&MwR*71+nu#ZcRBvm=3g^BCx2P#CIh!a|2;*_8Bm$+`_bP0ZkCkaQR_j(Em^32 zNBqe}l*1>v@fCqmU%|_Za$$v8#_8X64MOjnUN3@jE{VhNe%=hMY#`#$9)OI0{c47#A|KN^4%=YdO51;h(jG5)+#nep~rQnB&S zl=oiDKXrFZFEfIsvWYt8^W8Diw@`YjH=4LQU8=j zsn0LIde7T-<={)~joU$!Y2O8cy?>1e86~qzID5CsySKrj^9Gtqh?9L&#B`4Mi@|m2 z$VjW=1<#c;!s?5L1=C1g?#GVAm>J)`^#bU3qT_~xlYUn_A^MQ`_^M5}SL-)9ZqJ=r z@4IRYv+F|+(>giZ#_IB+{&v_es+PQ6j?Hq$uIKDSTQDgciiPjSDI!gr?-r(|#~Xb6;%sO88xj^JX)0{jSG%!xlT1d(-=4h&P#Mt z7_M_4+yXw6*CWmT5_NROp?Dbn@xv<8hq+Xf>XX;@G3Q8cq^6TnG9&t2<+H>c@Skv~ zmj?#^V^AlOsIv@x5&{*E6zeo-IAb-ym?oWIO{VJIRmnE}%zGEkP=D=Vj_RU(b;@;&;CwcK>v?5Vz?;mHv#qM{>?xRHo;Cu}2mG7_J z5vIyRUy{9%o!UcRbGzkM3#H?Z3J{bhgmW!Dmx&X;e6uu{35j36`8c16ld*h*x$whp zNEg^num!2XTe@%e!AQ}{p)c;?h}Gtyuc6~Vj@%z`4(7YLzb=IDXe2h=b_^sz{88jL z)y)j@)n7XihrZK)M*1L!zI1;_iV_cfUH*=QrRtz9qf9k!_0kDqH=XoFi#q;v*^DAL zT58wzDyMh;buk2a<{_+<_g?a!+Q(nKg6J2v( zRzrW>$#VGmg41dH-Y(qnN2>2*0Zp5aK(Il9^ee7TQJ=Wk&>-V|}^^b%v z!y4?CZ&0Q(1^=(Y-UFPDZ|egNg6JH*_Z~qIo#-6B9no75B|6cME<|wjsL^}xf*^WC zIePDj-n&S?Im!RN_rCXgpYOx7XVzN3wPw#QYtNoN*7jJs$(o!`J>!PEdWFnpUPV{D zf3o-PjdKMKJECX{><@l=$qZ#R=~Nt$*$)Wz0mgx+Lht@*DBFWc$}jSj>Y#(HH_-R_ zQ8>0&1_ST4xi;l(NvPbHQpI@8?x3>kO;BA)MZ#o7ZL~;!$y7x*YNh-^ABJxy%<#lS zSfY{;su4S@3$_QFhY-Ej5d?{vw-(LuecDX60!$1q<9ERk3cZgU(DqC4Y_wX8q-U;nx)62!P&r zxbSDNt@skN8{6}0UKqUdAcc0Tl?cqy?)j3SiJEU7Br_<4rm4xN`(S&N&_Q5<+PZ-DN zp*hfHz96$3hA%ulI3!ejM^#g%JL|mAnZaD$M>_)sAlVaCW)qeZEm-!IoG|qf@ZP5} z#`&d!R%HmS+-!u_&1-~Kk03&eE(xKftA@~$VFk3J2B8QwtEE49q5daYQ|X>ngaAu- z6p^BaA_NS*2t)KQ5r(!o5r)P-APiBc0*2~$GJx}v+oM^zQlANzUaVUqd2Q_{lD!#4yi5kr~F;^hd#CcQ7W}ebzQ_Avos+bY) z7XGA(5pQ1W)xkhWrTc6r3|*By|IMb9`g{R^Q3f+pd5^&^-LYHP2*NWEk!rCj z(75Mo)5eHxE3&6E;)%cyQNOe}+H>DJy99|Tzno%)2=pF!dtD1{I zO-;hkscrR!5oz6@6z?12-2PA6|0iV}0XQY)_5*V4B5>}TKbJm3qygDK0PE*_Vu&1Y zNg-0?Iz$f85VqkRf3A=;4`}c7JBLG!5_1`+>ZuWm7vB+z_RkP1-OY%Mv@Zg%HTiG$ zn!B?wvMP{*T)6yY)ikb%R>R<+w!U z6{0jy|76Uc+B;QY9(#FU7RwXNMYp8s`1T&fJ`67P6Z&+Jx51Cl7d@t=Aaz#QS*0Oc zH2!$@Sv5ql*z#(IcWeWk@~-a#1vgkO7r#MkD@vB!j(LbUvZWEe8P#KCsN^b_>)foh zna24IR6n=COBpleMEX@tm{>WyC^`!Di?&3s>spP$^=rv)1^04cB=2&g2j0WbATevr z=UJ}Bm{9D@sqMCPH5b#~Oopf^(VNmJ(TZT=H)B|ZBTAgEU|($uV|h_|ld7yNJH=T# zBvE2mwNxqag>C;6P_>7$osk{|liA*{@m88-%Y+cHn2NE$Y)J;9*A*|gghT)eNr|^W zPjfqEa)=8oSk{Sh>XUCTAyO}=$~mi6OoF0MEg_nz@MtKGZtjW(+(b(^%IW$KuzE5b ze1engqs`vYrRBuYEBInpwEze{(aw%Z2a)qkIbzVg;ZQ*|Y@IjiKuV;@v~SzNo~SrG z;it_5t1i0v(_7C}k$|TDJzY8~RJq-M-x}Fx@(z=&G=d()uHHVBe8%ALf#A;I#3N+J#x_4CGFP3x;+&0Z$Ya;|ns(%Cm ze*{y11gd`o#HtPAGEczcuu^|SS3{uO^X;+`Z5Pl3I>OKW(?bpPqP)!R&mWUCOaDTI|*X zUEqPyg=Dn&n1uo*I4&3+uo zi84!e9Q{CY9b_SSi#c>-0OuAyVje&Ot^2!AE zmJ?!T!no(NdM?tp%3EjG5bMHBB|Q4nl7xSx-RJ7%ucDMpQ~ghKsFQM6R)(nLnb=r zQ>wN3a6CB}%tLhUlI%}O7dDeXwoyW`LViM9%qOtIXnu>EXB2N=h$RR zY6L|tmT@F$Y??^W=M1!S$YT(f&Y@`C_iMUhNAkaxfDN=m#iXQRz7+=;a)%8DtVAs{ zw|i_{^^vlN9#K3wuY^SiQ#IbCUWzUB1{fLEY`T0I$b)+-A1vwKWD>Yx=U4KX#sm%PesjiVsPGCN~$mY1&pw5#VAHp4fVo8|ip z099+-|9oU9h8jhfb3q{5^+gdtX(6aRcR=AWoHvdy;KEJs(xzftXh$$9&ztkOJmV|x zs=j^_(DEs%T7 z18ug10Mw8^mCVsoMx!sUP&(P&xz69IKEL34aS=d~f~&Hj!-4kLt)NU*=r>0&1ZkS+ zVG*fM(U`)9#3Qv?;d(UDhWKhJk%wKsoU2*f7*yXg!-=FAR5O8t41;O~lvyj9Ldscs z%DjSZRx@oHD0$+CKt1T;X8_d(2*T{}ABuv{L}7(H%%Fd>VZNwcK%Ef-GAU<!1Owc4?3+<^M z{yv$akyN!g(L+(xbqGK`GDJY^5Ri|=4=LrPs~WE6uU=qfFUO-6bDX^ zF*oa>@A%(!EX4%pZ;*}Z(l^nHXo$ymDz@SVI$nHSD8m(48VZV9w6|4abFJ#_)-+%R z*`}EQwaH8m)UCiEVbmfg213TvqY0Jt%}oyP?2VaIPmkh2JkCIa)Y zf~kiGES-TYjG#8l5gK&}$Or-gFnOa9M*l_q2jmMIh6~V5|6dA!A%AV|=_CS8CDYdx zu?MR3(b_V zuh!44b(o_Wv+_1t^pvvs&l@S%l z1o+=SRc`Q@sz8?>XaLp$fX_^WZUFUUpN#03-dP$``F&OIzSp}X?&3ts&g~sm1HIPc z(Nmy4m-dnXZ|k@-U)XQl|pLwKfefQ1_jG z;#HtIFK7dX?$O{(q=#z+C`9I-9MKa7_v5HsCM*A^)xM z7h|4?CjyKK691t=Nq9pytpgYrEB6B~?)~BlAF0=V?YgzJZu&>=`OQa0ygi!k;sNv< zk7o8vc1DnzU6^^2dNW(56!6YMgY#9Hf4BI~FvVTDC)o{M+}ks#g?7|{$P5E56KJg` zitx^F%ptWV_f)FCb40ho6MLF)suX8JHWJ%~obhRA@1g^;Y+nSnBRRE&xRjZ)`We?k zow@6M*`xA+mn2uUResLcd86nP)Q4_#YVaXon#vQ&zm=`%_B@hbAWqRuBa%NNNl_ak zlD{ENanr;;J+B`667cFXwTXbU{|W|1VlE<}=O--*gX<(p~Qg%p#1h_*~6NUN8K~P?9lS0krrW8*J)uvKqB(vJJ32xLM%J^mYCZM z0`|@C$MiUO-T))?#{*!5?wtEGLQ7s&L)>8^p=)Hb;nD{EozIBiB4}e;^x;PG74bX&_x7Bs1A zcC1-!3{g6+eo|c1j^41ZHdvgvda%{Hmen_|y|okMdt4c=^89OQ za&Sw$z0zK9$2wlHJd#^ICg(Y)7sV;kP}mO&+K+8(-+QnU8>Bv5_w9F7l)bhn#r7WM z>8{AtqVeiHg?1Ch<7uF&PgF2vaoBz|OJ>4(mfocUM`_|P$zNp|KxcDmZa+n~dQDq2 zuIo!-Jx+$FR|IZxj@Xp>6zkYNwLT4TT*sg}Dm+z@HvhHguENH}_suV;X8#di^uD*@ zjgdbak^^siE*``sYF4m4W>{A}1<`>h%aM4bp760Sj@*Bx1AKBr8_$%C!6_M&0U+JxrK1U6c`4 zhI=}#bwH*_NepKtWvMhVT5k??wUQM$C}|CJd0Vd*%1i?b3L(wLz8?c;DuGf9z$>twUBxX=V4w9638Q*Cs;a$=5gb?QLGU>(8_ z_+k&be&AWU^jMwxR}JKR;9SLBcQw!ZBCZ~abx1b*7fGP%$1-m}<<lR!6~=>X?ViF4TQftIRTaE=lj4BR@+Poq z-NH`s(4}GL6_B>8lbpb{>7xe2WDyX)MYpk-GUU?dY)@3t_pPcS8zF=mh zw3YO@t26pFLJR$xqpt99uzkosrki@T%so{jQT*@$E%2fkz<+%8CmjGdu@0j`y7JpZ z)s;Wtyk-Z_s@atD;WqBbH$I~mQZ1Ato~d=n@M+=F%)`VqPqCxI(4mf?Q~2CiV?FJs1V zsNp*9F{?i_U}wD{nw6UQo@t56WXKDygx~`=HP+u31K0`$o|mIZpE4MoL86tdXKhmZ z_}~p=+|Q7vnjVe#78;t1!G)6M@m|PNp@w&HtF{CbMBZC8(Jq`M1hxP8%;6o$|3NW- zP@dsi0Vj-wGg1c+x8i;!w6q^8KW$Q*=lsB#xC5ApY&@Jpl=w5pu$+>+k}Fw;D4=v*jL)$gm zhU~pEg)ICgNKGhXfbXAqUmzcYogE5&IaMs%4k_hy?89b!82jE}^S{;e%=S{fiqvz< z3)~kEv1#+9L}w}|HmQ0~w!*tgUNs_d(z;JrHPE+)e?%@;)nt;wyqYw_YT^dSefsvw z2{uI08iVw7^9J@SI{DN-NxIxhM72)i$q@XcptJCELd_x%hw@-*Mjzdq;jUj15^NZ9 z{tO2s{hfC_w`Rv(vzG1pt&h#yRa@Dy)3^D_tDk0l?03kWa?-4OUyp%7aTNz2mmV)l%I?D=Bmj={eNQB`Z#w#nIwI!_iVb z1em!YI(1u|G3&S0nki&#wNXPo&tbZgEND^Xxgxw80og2X zcSMf-y<-&PjL)QK-SMoo-!@IYG&KKigi-dSC3pBALHdeXkEVc?o)5ug5w(^vifa zH)rpMk7H@7ZU_nws(*z@Ftkdo?nL~F$t=0y=aIU~T%iql)w*Dm*!A#OymYrcLBA27 z1HbzKyAYGYVW<}=!Rl9{1OjVr`Bbc20+z4xsZf$ejH}xu-}|BVfGv~Hu2rTj>fdJd z3T?@9PEQ*CuRr3`I7Vj(Jp*~UB^}e$1{De~d#x)rs(@b1`xYXOcoaQ)c*YtY#0S{rQx(- zJ-x$CN|p8XMbQ?a-AICL+WI0(bpTnqqT6hGeelEBJ!dgrRCNr2J8-^jL?r)vMi@(3 zBtI!RSJ4gnQk?<&!8=v@Ni?IpzQQGeaW)y*_!KeTS6={V+ta<=w>8}%Iradg+_ zSGU~q)xH?MTt?tS(ia%jf;}e#u+SWOwS<0DifKZ%6BD63-!dk)?V%m?$6Gx_uV_2&H26gL3N)=)oA*e6{j(a)VMQL+9|?RW9{!X z&L%D>A3_!Sxv6eCoQtl)(mNwmrv@9N#0Mp8mxZML*Q^h)Bq>{+w|{oOUn6zA?QmWV zNb1c{q8g=ADM7c1M-)fghtiCzGE?ML39YCciMnBg1u3F5l&AP^X?qN3D z_g1iT!@09hw#HE#qACU}-KtFUlGbIfI&IJ6pCF7}`r@j0Fh{wbIj2ArA!tVo29?ZT zL5sh}`w}Oq7-^QO=GzUI?Z#_(Sd?p3;5~}{T4kZPTUOh8n6Fga^1Y>Y50jvY=EEzZ zU@uPD8V*9AvRhzc6BxVDRi5;$F9Vs`>}iA(f6bttFzWqk(8VLG@}#yDZL<$vX!me( zBq!Yhm$k^VN0H@8(hNmrL>$)?Xt7BV+)zR6A}W%zN9pCnEHhyW8H^6Kkoia#%!w`Q z4k#zGewkgVUZxdkYlWxJ_==s|Xv;)nCM*&AHF$A)HMMlTNcx$5LGvQJ^Cr(yk;NM) zR2TM8cWe^=F#DJw(w_XcjKb4kq;lN6hd^;Bonc0zy@ z5-Egy&1*FytB_EOOuM8AgYfoGmU`%jQfa@zWa#x&si0RdGbfu%)yonvCd6=kk1~#d zI@q^tCoR=j6Pc2toIMqo6s<+M-b{F~Z zUCc@z3-H?8Apv;JLGlB5e*w5B;Qa-Dx90q%dcNJ_2C>$mHW%pGWGS6#uEgN`r>J3f zdngM|5b^2hNq9pyt);O`t2PgYN8d1SHQqfYoVOZxDi|lv4Mi=;mW|N`8(ZeXduZl; zpiO4=RaRG>+U}>?i-~EdY_8N^5fX-62t+7Oga1_~z9Jh%{RlBL5spD*RnF!~CNjz9 z5fus=k&193u9pgyy5LD zF*4zsQWtexvnfLUvt})cYm7A1nVZl<89aJh>2MG{${Vm@b(X zP|`#!m=r)@(f$}LCv7W|8-2uB@2j6U&q|_rKOFB5l{TIaqX!KcAlcoE=oI9Q?-NED z1i2g#+QE^qE-{!Z0^80b$L_5(IY1(CPo$2R#5F5TJ77@4&8t@5e#Ok)puVkWQ#i-! zULRjL52T>VsL+^t^6n}bg)&#oTb-o&jv)Tg4e}J_LlY2f6REZ&nQTIz^Xv}o%i`};$^X|)%{6J|{2VCHt1l?*G zg8i7%9w2KHys>Jiq9nX(0@1ovFG@yBf`d4Qzm^2l*b#pkm3h{{K}_jA5TrTbC#?HK z1K(dikwHC~>(9m21hA4HlN4M=db^kERU6f?HK-5gX;%anM9G!-TR>?l;Bs;nG!@-I zS|K{c_9FL1BK$|G{Qe5Y`LFGu(;k%GV017t9@8(peHSqZ35}Ro97}9=Ptr<;Slp>Z z-0X7A1>X?)Zqb0bRq3Zx0-urr7S!Flo>6t&&l2XZmaZbg_VMd@skZO(@^)NOX(C?X zs1=%ieo_(GaUibG3yu1jpk0{iC*yB7z&?8oY1<;BqSp|!Ba>@S2lX!qGUHm1GlP*k z^tkWd#FHSi+Uly|6dfBq5SwFDua??Nu9i(B*<<3Gi`3crG!jGsR*KS0jBY;eEP~@Z z38>Dn>w379_xV;@pN8(Pn@}Ekt9ci7Iwv9vp-F2iI+2m-K^Lue$fA|$o8G@u_pOkb z4H$lKR9h}Hiy&+C@{daB<`{D(c%#e;!4I@_*88AfU!>|BRl4zg=2seNE@ z9nyhmcQ#NH zc4Z|Eh@f3Q?mr?MAb+!N0%ofqKFU~2;)AxigahuSgWN>$%YwDn9JXW9+iZFA(Pmu+ zlU+|0W2N;AhyKY1W)smjDpMnrRb@!bCS{iarDz*g4*fc!ej7M~AA7Jim(?4lybcz5 zJ^FgF4#K+xgikn{fxMcePiUB(wb4hC?j4&@o0NSq^hi_oC|qdJT&-NWj;yrogz{B( z(yk3OO?DcZzt*(dA}i-=KHot8dYtH-Xr#yCw%Yjg?jpqV{8D}7kO^nf$cnHu9?dR* zI|q1K$U=yrtArw;_bIeAKPW9;wHQoMEKCY2jqg|{svwI3cs@!9UP<{M0EG%bunlD8 z2Lf_ROcW2e62HyW z5d{@QnMTJVX_{PryS@)M6~hBXyw6UCwy!m9<Bf_I!Pg)lS zjXC7BHP-woFous5R?rZP%!IgXHR`axvCquhm3QH?)3jrM5mb z_4>$j%55JOfy-^u)8&in#fP5N^ht>I1nMvs7U^ND+@+dE7;cZu>N_<;OFVIy_4|cQ zL$Hy|sof9pG!mJ`uzP#i&9-#0Z$c@~v@C4LnFQkY^C@GObkb#CgBek17cQ$8h#jBxH@hxC4OIv4 zW;m_9vN%4jSr-Nsn!bdQH$Kf2iWG>rz=X4JyU; zZ6DZYqsCBWa;-wi!qDY1_u?f}Xe&#mfHYLTnF85WW<|<+uxaxp);=vV6B=ryLdn`x zqDF~H92c_grXZ+yV(gL}UDu$3V4_QB`{#%0sC-!^BhT5jfV!1&ggxGBW$78tf5mnB@L2in+#Va99F#}dVT zj1{A>50*H6m5*_2hMGH>XM(3rjQiZR`}q(Ii3#f){XjVPXY;A5fcpgVJ~x7P5QJ|yxuuQYQ@fI)%HP?%7wkZH)HBYh*9WCn;p09 z*DX_6jS7zyQe6mN^lWNohoS1y^YCBRy7;J*r>aRB985go)-NEvB;pWw^`lw}mz)?R z+29T&iI{8UnLX~KJ0?L84Yv~CoYG0KT~s~-aQ&@erjg)>p^(TxnxQugbf*KmMlxAm=&teM zAsIcQ`2#u3tvOWs#!){9@@iOJyP7~Pak+C!I>>{$lU?*%#Su!au>OuI8u+3A$Q>(m z{2|l3Qzd?>EZg>M!I|sd;@K^5BMhIEtT zz$LC1iKF2BHSr-ISD%r?`arS* zzZm_>7ScMRpE{J7Cqa2LcKo&#;=ObGvW3x4d4_c_<*nFm?8yUeaWn6zuY8>(OpiJW4_^E=w=p3TW zILB0e4dM>gOFjlU(rYcwn;nJZoU$otGp$bD+T^~TqX}j4be>F)cW}IXc7d(#CdfT4 zraIUmA4Nph>;FI^28_$}EstrCfaG<%l^XLmE(`s5o0Vha3s?LICt7wTlRT(Nu1Sv1 z$Q4QH6_;PO;Un;sRK5t9knE76<5~7f*hAlCS0`&r1&cR#ALAwbt3A~7PAD!w{`xtm zTI9nQC7bW^oB=wyKOu7qP zY@ticjc0p;VJo}{l z*!5j`b@yWrFU(Y<8SmE;)McVO%g`{+m5*1JhHBS;#c&D-ojo*Ue8<}O0raVML*`S` zz0jHAk!fPem(A-lbT?Z%O8pl$_s2wr9t2L!LZ6f;V*-fHK#4MOgq0F^PJ&NP0J&;Bzs zH$(jmM?;MnI0Jpigp6v)B;xguhnlgZ^rq{H^Z`gUS+aOH^32-VUPyiQt6a#SnPgXe z4rbwNqhNi5l{f3NtW?C@4Je@>f__gAYU*azPXv9SHC1Rz&>6!#=iu`;tp*K8j#`GE z+MUaZ=w7tMjg)k_S3s~yk+t+eMUpNgigJU>z(cDAbmlrlwz=>*vWz#Y38Fwn)K;I;e-iE35kLG2n zwz#2nFzxKOZ^OSPCuNeTi0E;z9O-xOLV92J-hVq;Krgx7hPvXHmhoLE4+knru$OpIU)-O^9d^2?1{s_LK4 z48IC%^EIKqw*xiLtaJG=z-b+@lNc}b8p}kgEH~_BI=KZ~ac$RNTgOVYZTN%!mR0-K zMzf~f$a3r3p$UdN72JZqnI z2$eZ~l*3!v(Q>`bDFGFBneglZ=W-KcG$AOex#}99ki?e5w;#hR?-M?4 zY7}-m8Bag9nfq?bNyTKd5YOP7cz5xPy)sVI_A64O+4;w7{i}ziM7g#jHJ>>gICBe* z;Le;wd0MXOZ%5n;={R%O3^Hr?-sZJTv=Gpmj$6wucw|EA)L(FZzQ6df0=@t78T#ue zTk_ZcY@Uir@m!DCqDk{1Itvn1N)6a8Rqjf0k^WS|CBAV?UWr3GFpePY5OVF=DOH^kU7A;CAN39!8F0IU+Vm3TG>lvcz zdA+Y|q`j&7YG`Bby$ob0n9`U}_6zjyEIW7?iF<5se)qs=P433?otvHGqa%9w=$!n2 z|75x${S$N*gT8Ec^8(nZ)~)FX4gCocRFbY$nx*U!i6%xp!JzA#OpF@4{Q(+=?S*sw zTMG|G!BEFZ8K;e#zU%$N=BwPMH%jN|Jt6d)?8N!|@p;@osf3BnHjK04cIp4RWuMh&Tc7KOw1wS^-lwYPnfa7ek6T)8 zjDhsmU;-O#ooyr-Q$m3>DtG&WQORwn22xU^$g0^jdH1)w4(kUW-B&3_C)Iv08<1Lo zBh9~DSJSq^`abEBVJpu$f+~L(G%()rt>CURt7di2IgCx%B{*x$v3yUKudvE`@Za;ZuMTlZbJ1dEb^7Ea63 ziDS;EhjX*WQ@OnQ$vQOj(5f3Y{_L5Y`v}=ChkbRw1uJfaw!0OETO7ppn$2(Kv;HkepQi-nbX#0oi|oANZU9g#lan5>x)i&anRlTTZFMLFc6U zk08ST1^Bf3*A5mgIyW-*)?Xq87YGMxjf+l!68;V;r3MF`2oXXQHKhR$h_qLZ;NJ@( z|K&5{0nkzh6nvln|MlZL@Q=_IAr!(x$0i{Em+a5cO917sHV|@@Bqab3Fu2kD59<=a zV(mx8$Nsm<4MWNrf-Qj$*u%z0r$FX*{mThMaI_JeJfA-tB>t2dJRrYm01u_BA2p>3 zA6)_^?kj4_H9oo!%H$Yo3V{c(GrS@qUgltBQ5HS-?`5bYE*MHB?69)QrXQ;I?8 zxF{T1{|F}lXo@7^zxZ6)|5y_IW9cCx^l8co2%Qx9;~xQK%Ign+HAF_J5y3>i0EHqA zI3}il7Y=YHkn<0i7hydEksFcRe=Zn|U;zze31enXQ28sOacYu z0t87V_+N-k;*=d?bVk|#@$Epb{@*tI$hM`$=z@m7;n5)(3{%qJJvOc@Y;=|I>QN+V8ZJV3^CbsQo z{_5(B5xcKmtE4oEA4|FqEAxpk;r@1|m){Lv3l@IjnSAqVE{e5fM?iJ+b4I6QmuELr!<)1gf~x0<~73~POZ_{vahe6 z9+l55T1&pY-F~54sm>)_j?Y!%ce+K9r15#U0)l(tIy%AEi!f-4B-vVSUUTsIC@`Ev zhDyMP-l^&9uAv^Eo)zbT-7k*CJ0y(m{yyW@>7_FdTHBl!tq2G0(bl2DB%oc!Ks2MJQP`cAxk5k7=$Ii`!JgKBU2=$V-c63;IenaOB(4{DwU6+0@IXT4`+0SE7?^ipQ8B@~df9P!I=a}tb9A(2_p-Mu z&>eTklf?61v3L&rEfOjvOIH{px71?uqqpIzr+~;TSt-!$eb|S|i8`Ga@LBq}%;(Zn* zLE^P}VfD;wei|uSu0kT*b{{id1lKEnZ;JoPQB!YgParH}T=RK^dH)0Lkb|P8HnY6J z>jL7i*W+U{WS`IYmJG4HJrZgOJ=luvFXNqc7rd!W;p&h3A|sO-_s#+B!0F{e;Eyg{ zBZV_(HGd)CO3#={R)rM;PlIAq6OWrm&GxeTlb`2D4yvwON5D&LW&Z65z~%mhW2+fh zAC)2R_wJ6~n7w^AQ^3KSbo%FBbbpzr$Bz_l8b{AnIBVE%9#atT4~T=@UY*6+F>3J zkZHRpIPLaSG5oRKVIyJQVLvu7AP<5yP88K0doeU!15w0vI3?i1aK?7Qm3YcGzWScN zqYLjq*7g2%NoI%CLbVJjpZ`AA%2yQ<{hds{De;iytM5nz@zcK#AuawPZ9g2|qrkur!yv<^#gHNq*G{9N!UDq| zx;fGNj)PlePW;_78*D_;ln|f>zFXkKf)kiOH{aWO#sZhI^u;?t9IrjGUg*IuHEQt{JN%M_- z>)-l^M$i31WyHb}Jd?p!B8AmiZp%O&{&Au3AgUKmA5$Y>Ugd|!GyjsP_P%RdBGc#V z?elCAD+%JLyuVw{QVQO~&@9ai%m`9S16*2lXXwMv+HCK4z2CdTy-kU^ik+k<<2lPa zCMx=+>2lFh;sui;^DWA=Kg{jCdWp#%NnJ-@N4uMh-(_IHxSV-;Oz_r%sChsYF4W;A zs+FdtgV&j+CK0v)vD6wX{3NTAJ$<2+=Z8l(GWyByDqGi+!aGiQT%onduWNHm`2)@P zEpq8odT&?ojqWz=&d!C6$i(lmHzjI0Ul?kmQDM?c@tDED7<GM#k3C{j(fiZgpw6E+!mLuv?fu`rZnZG;Mn~2`gk1k zNFS$=KR}+T*T7`W9nKUeKd;QUAJo>ynvYE<9$thq&#yj)>vbpi_+aBw<*+XR6G)kR zintUqwiWH&3`_IS(J;39bzYbTfcx0OcU}pvaj7EDL*9q^8+m$+hsyJs)6SR$#g)Yq zlI|2HI7XcVv};thk467PdLOcIG_PndN&T*{4z-wEIU?cqyro*Tf_KFKwIG%IW6AEBv$4=OI`XQDvrrBiY!&;P=Q4iInpV_ zEV|o2w6B;lRPPWTb)8O*Kj8e@dubgHt4^0oJ9{NEm5WeWow2U`axSHQ;oBvVKu^iv z`&3oA{+uhP<+fE5&MUyjjJx7oZcxO`L+7K3i4p64$+J^Ikimi5jSc3CWTgP?p@kQW zanRWwFA@h=3!}s;k>)det)Y2>3EDZTg$Ei53=Cfv%)eSz(vlPK4~haT^UJgm}|&dh9cM3Q6#3&{ZC_liK-`OEZ# z>(ywd1>=`Ww!*R%DY|RCl1yARUUPLb5%s+-aiaK%q-5e;Z3A*vH$c8cvfIppaCH3d z5uue-2{T;!jTAS-XJf)_ZY1Anid7cok0#2ZKWhH!0s3dE`X56t7d9ia%9QUuoo|Xp zP>9PV9ZrNLvNuPx__u$r8=f0<3zwDyzh1J9@n@7=M~2f`eTAE>Q| zCbD|LKyACQrWBipuwU(`(Hwr24%?79DP4WKmJn-djdX$JU@dEBG1niS%$8QiY}qg zsCfciak}t3<*ZCWOEH(+71;QB9-cECsG(tJ!0+x62gS45r)$-z7w)Pa8akPN>Dag_ ziXT~Fy!TQ$+MXUxP7cpb7y9%#+8)+{77h-*$Flpo(YW@HDbK!b#_ke8(sRP|$GhY2 zD^I7_5@HW$CPxhAN5K7XpV}yJ*FMz!M-8)mP-h3jqp z7RoQ9-nX~L&Fofd*kyS6oaBGkxdAwR22NhXscK--YmB}n4a9R( zliFv2{QO(-o$xerDCNh6;ZLg;k70IW`1Te~{+r<8w{O4kA93`wyVW(fZ#Htc48Ol_ zmjE8lPA1Fl&rWVP_jtu6E;CxaZsl5luD$6!7vILav^d~-yM3wu_}Tji<_!1D4>EeR z>>HHQCnsio){uW}F8)ogT;k#49`|GxH7n9f95c~Au&*ApVdB^W( zM}lsz@H#%c@A`0s^TvLM?xnp>Mad}<@%vg#t_)5t+)60?N+sE z$WhBv#n$CPaxtT0v)y?}7l|tw`heQ<465xUn;A?+FiOSTtB`uX8Y2Uz$OdNpsT=ed zF;<@`_S@Fmq&@q}ss`h=T9#OJpP2)?t~|9Brui~cjddR0t13avfn${l21nb_`u$YS zocEWuxCSFCzvN7swYYUp^Jd=L9R`lCdju}vo-h#_CLI2t!;!U04!@6{V*orZriCxZ z^+Tf#zE;;O$YUOslXVBPwuxgZ~h` z9b4p?#E{Vx0Oh@1rxZ(5XCTW?aHn-51MRmA$y(lD9Lh~_L!G4Oh0D8VtRP7V`` zu=^nvl|I@?d?tn4m=N6ptbp{gyAeETGe6(`4*a?x;5V&-HR3jXpm}9{h5M>Li|P4^ zv-*ZheHW3@$(ZQiRzJQK5`?64b&=MEl@QDmDH_C%yuUi<6S80wTJKgTzrr_89nRSj z$Toe#`dpAjB~4!$Y=*B3su4S}U=kXJK}YN3KIT5VZ`$ADPI+E*@4=DpU$tsxq|C~tb(FBM&4eyr&*4Jd{{OO&|N@6j5GEm4c6hdG?2vgklcAQt5q$QU#lyiOu z^jFHf74&yZpTpD@$$ldN3pt>+5iCBx$6P=mePFl;=2~^MDX9ZalbEFwbC@{b0p8u#q2%cZuOF3sqDh4$Szv zy=m=GVLFaXQ$FD~%=%5x46Rq*`UiUy*lIh$TqdhLHR6ghE!n+yFd6sRy^$c55tQoi z$H7Y}YyNrDkZI|P7m4*4#J2EuN4eF+p)fnIxDm|(nmU=Z%l9ExG-&erE!{O>cjQ#F zg55#9&x9P%MytiiFD>F>E`=STva`eIHJw)6LSp%k2OW%ygawSNx|%xx#>>hVbw<}N!-3U0I3|YQ$$^^x2({Rvva5G^bav6) z+#UwDWC^KrKGJ@{vKo-QtFG2Sf?C>xS~^9Ck^?=G1f%`6qw zU3OR>OR;0|vtse9EMPX>5@q;0{5(2LWKXwDnGZe*Aqx3oxMJC93e=7xXBg4g>C@2K z8UyAr0mJYDmp;CB=29nPiz{L5_r~!VF|TJkj^I*J1^|P;7)v;Q%*Cnu!)h@|rwot4 zoTa)ts>Ax^@yh$v#e!=RmQahz^n zT-0YaJ@1H7kfekow?*r&a>mQdjh~m z4wFfcY930Z@sDZ>q;ge@5g|e7pqMnZ+qL82yG9#z&owLgJe=OTk#B=#k%`&#P z4Rw*BrtrbaPTeed2Eup^G7}n>f=5F@3i!a!gJL)v{`(HBeo3`>2k7vS26Di5MNoCh zeC`6lROgI5nV`UK>%aaesTPJJqCf;gB@|J;Ku`xFNT7+a4TdIW9tKQI#S2Opa`p6} zdZA%s&xIi2*|`#UXre^Q+;c^DSJ{kGVq@U4w*kWwP(lxSEkY~hvpwHZtp^e50turj? zw&O0ffOpS3Dk$m)c%$f^D?#+M(A#saAV{qL)>m!N0iueXu%t$Ppct|iV<}GHzz!kU zHL0W86uiMXu@Y8!!xXy+&dLraQZ+FKxgwpZ{OCR}^|a0345*f(SZEMgZMHvMVG$-7 zjlrP!VJzivV7C$Gn)JDL5!Bye6{zwy{dU%V`!WLir1v*dlUH3WhF9bQx`V#wkD%q* zg`F4BTTN>M^j70&dJYo{;7W!ET)V4w&ZB=j_CV~cZp0>q-X?=+pf}Q0sK@UEuwWg3 zX9m?1Esh1KAYuqIBs&Fp#>&Y&O%9%7qcvs&>~XsAk0y3zjZ3ZxZeR=TI{rqxw zmQx_eVdW6*)#oezyzXYDRed*FTQU$jD;i)v4vT$~psWQ{@dt~z-3RT=E`(!1b2I)g zH*V0}$RWwb+sC4defzswV2g56z3?)*ds$vcPymIL<&#AveBU5=O>(LrrG#596GF7L zjU)N9)Rsev!9NJzLRa;LpvH7DpvE>~uunXOq3v_|KM@hDJ|p<5z<`mQYQ2QH?#f z*>>lEQA8}RnceX?;4F+pRrT&gFN0{6i~M0rJPL&!ZHQ}a)w;Ie7nV6^_UJ<~k&zur z1cJ)Wn-B&MD?P<9On&CB<~Os>{F%Q~4g|@1ud>M)+_B&|USonRH9SA0#r>+VaYlx_ zVsZake6#2y;%c})5d0pD)!&I1eR$x2U`$0LKC6fV4G3UzhDMZ0xZvx?TyEZ2>2S)9wl4aim@qkh7?#%vE8)U;7NRi~i}-y1KN9#oXgms2 zGQPJZg@29a5CTUdsSrjYgR2pj7Cb$Rl{)ZyC*$~Cy1=q{6)rG++3zS#gr8l$79s~; zhGF3~MYduWJQUwwdpd63JOq6foDT5s^d z$#ilcaAIXhY{nrSLa{sUtj-L;(g#!#%+Z?8A3u3cw#KuBgRsva%!QRcu{n`63WN<* ze-6N!Dj#v&vZnGp-`cudYJYXwp~)ANACn3q-74rnLNZ$rIbNOGfpuf4r_mhKhC`k; zRm7A+D>(n3G;4y9j8`XjT#=K#LP3^l-CF=xEmeo>z4FGa_3!YEC@ zD6=N`_J$rgzZHjS2*YI+yXHur-357vZg?wU9J05 z$R?7|3Gy3&^`%fqg=F3>N~=1rV(Ca=v>*vp$RXBGLRBBLI=w6DRH}^*8Vj--qYbPY zoQN$3%1m1;f+9YPgE{221BO!Uw*(CTv5O70Oa2D5`zAs592YB+o@rV#Uc;IsME$9G z8_`Acwa|xDtTXj8KEFFcO&?$36s0JAyfK^;qkfUE2~n zFW4`2Cr5k0Gg7lr&C|$XrN6I9n^-C=KV~P8R%06b!Jl~NG(^EIeo};4>CDS}Fa2)n z=j)5B7{5=i_;4%~=flZ&uyyD=SBeA4M?GbcB-M5k`u4T|-~nYb7aO=n%&C<56Y>|5 z(N1&d-naD;*dCNU8?Ep;#lQO35zB3vb!~mlF4=Tc;sb4Hd~#%KeBd3H4R-38K-|So z5SHA(o>FeBtY_=vy1Um!%}kWRpNB+E%OZlcTOWb-UyyA7I$eeB2Yrxhm`z6`ehuUT zawKZ@;1k}~{V8NSklgWxdWOkZG;CX%7nS-;t*x0GU7xv#l4c5Y&c{LynYxvKw-X~I z+Y{y@`63{1{sSSWKFRI?p=oJR5V{)4IQ(?NGUdapXw`X6A=R6ngi~(9!^(*ZAP$Sbb^$qd@zI+G5%`u&&v1&7N%g< ztY7F@fLRk?(Xu4S0|Tvtq|WK)1AOk^z84JT@hcY+SQyQRQJ_$P-fTd1;|Nk4$Nep#y-nVJSK4A~CRXaLCjj4al4bvg+XQ<}}K>D9xc% z9u_@le`yx!MP>s*$wAyN1>F%4hf4v)opM?DB2Y^r%M8S& zm(A+IL_RU%TgQ)E(*%H}8-!q+W;~f9!Kv@ZQ7tfG!AcV<2Tp1Cx525?DwgU7N6V4G zBA_JV3x&fh&?1Xq1sDXOmpN$vWc~@Cf{dbSAOTS4Nh@2DSP0HTDDf(eYJHGkO$~?b zHdhbegS55n>_&A>53nt-pzArjOg2=FG{%dE9# zhXXE(&ju`ASiiDlQuUq1-06!q!;EgelF&cx^lNm4jB^#1VR4t)hfuh^)>WnY>uA{D zgMrZQ8StnV^H#>v!QH^X?aca_Y&Sq0mQlD!n^GFm5CanwtHDS8;J@dN4o2*AWU-1H zTKK$WR-!eT*NmUD^I5YJnP`C@4p~?}1&BJiwt?xtm(PPg2>gIf!t7B#IhmIPwt=~_ zC5?sG0x~5k^0MgP<4G8Gwsq9PM(iBo-mtx;J-m8CITlIKKU5s!G!X2kDT*Dbqpox5Q#rO7;?$*M#&VmWJ@=Mjf`cQ{t_SPKoh{3o2RUDb3X;I-9w)Tk5JNE zTfNbg4rr7z-BzAU3fWh3;Aj2==9t$AzgWX|D8FB-4X(vZPUd|-H~|mZF0~zBoP}4= zpe`K5MnmB4D9pdlS{7Kb9rx zB;86g89opRLwZz;g(!!z`QxQG1>4D!A8_Y%D+QCv&(mx$N6^ZlM=9fB^#);;(y}D0rQF^D|#?` z$VpIi)9;|`9bnNwhg8BZY+TAGeo`~?>Sqj6NvbFU1)K4Shak`-(M}K)3YafG6a;k^ z6Dxl#FMYimgg?n9Bt@6}eTt02%cdABI*D5k)1-t+Ox1V{`{yEZXP37Fcf9=tRGp90f+gy{r_jShcB{x?~<@gHRHT`nu1-V&X0n$(kR-sG`33fx}i zp0E6@{Uv>_bBZKta{1JkI|MLzXlxPUb6w{aiAEGlb*KFZY@MfduS{$fj=<_xr#MZ2 zw`G`F;j_I{J>q?Jx&7&rV_Mvbc-tND@BcXd4YDyBs9l^`vfpbCVC{nOatmO0Ju$J} zlkg@T=Il=I45;n|j=8#LLun@zgDq`%d~%Te=k5`bB42B zFIjZ*rJ)!t=r`AN#ZQ0xPfq4KZ<*=NFcX7EkOSYakTP(jzE_gnTTbG9fuDvVBE#}D&iEjTxHYn+ zL)hWc-ey6F)7yJ?uTNT_MPc@V5LuPjJMnqnS=Da|Y!f}0kQ3qeYY$^-WVvmxkd zYPk?{SnjlU*^teD^E5jeP|-RIRQ&iA(%JZ`5RwK-14nMq)W<@I1thJs9$fG?F4jZh zAdRx$A(oKTUT}xMk*61u3<2Z$m=76-MGazSW;&3Ef#Il6`#J(41eU(pHzs5q!*7tG zFBMn1Ur@|0bqM>8wCcgE&|y-}DlY`E39!;AE{oeaYddTEZ^U3|`^MK=;SbyyXSUxr zKHoRCKW#lfT*R3?on3zgo_p3!+8+K2NIX9DwLkB2NIc&kx8ImNpFcUS0H+xyPq*vf z|1O<=2cB<>!Hs9&0}&mw>c{Dcrn`kc-i>1 z?cr=;<;ni_Nl*LJQC$0N-*J1Bc+C4pOU~2jm+iOvH^6q($`-}Pa0%Mo^3I)K>=VHS zYP2zP_Z{Dr?!pQjmF{8-{66)(Y<^B(1XPaN>94<@{2E<}n&!}Y`?dXLx$1-@Lxc|a zp?Rd#&7%F!M@mE~$OEVOIdJh=@(7^3mWaPUKK&JiSLGBKjD~LH^%UA?f{A?WBkA=A z9_ae<ROH9}$WD78#s@g#L5k#MiJ@r2v_Ec-vFarlmj;jUdu8{(?S zGX8Q$?bO#M3HRUoAN4k#SX`d*E&qL*<8Zs0z<){`Pqr@4msYs(_umH||NL9=H9v>3 zY?BN=k+?j+XnwW=YRv{71vdV>3|jt)JS_}+%lxkm&y6P$muIr( z=h#I+;i#SFdc{8W)&JN~JL;SvIk+VGeMwSrN%DG|#10%U4N2Eb3cdZKXcmYsP8yV2T% z?Jx;$(z;MU)%;1QZ5zX=`L*jk7Cux1H zZaC{FM4IO~4gtvitG3Sdp_qX?Ao2L*#>Kp@ZNpHsZSiv@hrn?)-;a#z@Y#W1XR~jX z!?RHx&dISQ@E5nlsDqfBhJEeOPiTS|DSmKu#v$jUI^@S87l0!sJ?1hwiOj>S{@=b{ zJPH1Wn`*A!IOLMd_86g$vWhxRAZ1S3D*rxn7jvI|^qIMN3I$1R^b&A7l66o1CGzsO z=h5PIzc%6CDV@jBz121bvByzPLgVlVnPA0@RB#B=3zm;#lxtGmkpSSd-F80qV|Q%P zB)B;PW0;I<7iUT3(^e7MrJpQivpfbdf`B#FNzU315ijGxZMgpISE(xq1{^sr8RUC3K8o=q5D8-_1a2O(VF9%Z$baWM)6FMev|C?Vfl3E5gcw>^sz&DN~ z#mxsU>;x-Zci7M1t8_v~nIGH1^wwkicR5NVO)=uu)JR}9(ifpHq)t~?Q}lUx3ef-v zxJhmeWx(u*ioQ*BXi$i@e+5K0zt$nD8ALN+_Axy6GPDjc_>VD&O*1^sF|;mkUr%*j z8!2DZe%0`=f{zowPs)BwdU{UM=t`>o#giz1CEH6kdfYE&p81}(){p&LwqmqUq%A|D zUF_dMv%2f(y6hJg8#fQB+cqU@RUp6`wu#@$?_)U06G@wb+@AUu>Md&Fc+&g+9 z*t1^rN;)2#_li1Joc9Vk+MW0EI4iAHKIw&XL_ZmM>KgSwsyObwaj=^iDcpD8 zSX+y)tJWi_{ZXy^IkFfKd$V$&|GT>u$F8`zeNcCIR|JJG!|WasEjZdAXhO|MwAz{(`2! z5OF-eJmj>Ge1V9BzP+}k@OWa?*E1X&l|lAWK!n}F!)WoKscFvHxpw{U|Cb=fXa7em za9a`3_6mr~ne@djXqAgUBamt_3{lV0uvm_!Cb7n=w#BO=G2lTb#K=#m{?Uo#ICTDw1 zsvsYjxz5RrzCkM9Vn(@ra`ggUNMX?w06~lKp(q@`7~@@UD8tsS;78X2W*JXNk3N}o zxC&CB;kJF!=y3HS4}%?D^CX1W()`5eHnk5Kt>#>FAw;yLA^o@fVFnUqz5uPQeISIm zU?`ZIQQw;3^$Sffh6QHQP?>{bO%do+sg5&2i5qo;REP;g0|`q|pS-!jd4e;~@7^Lt zQiB}UGQkKdI_|L8JhO<0{CsNz>Wp1R;xxu0!Vm9pY;e0XP6O*A*Mkx24X?Ei`)#!Iey*b&3x**Yt{xy!dJJ`+Z?$5tH zq~iPHw6${$ORsngHIB<2rdYYb;y9%%wUy-Bp_AK-;gj1E$D5<5WHpLU(@(pWH-6eg z}LE{BAe?(JPupy_h-oKP4Fz&+E?rL2@Ye5`xId>)}6!vv)ale-mQs; zo?k*oJn{S=`>1Vu*17V^xP#Hd zz9)ymW7edB2neQ9H#)cZrgu)I!wUf{GyI`R%k3dQrS3@qdir-W+%kVTWzu6U-{qm} zSSgZP%~td};SHkqO%noNx~M-5e=rg}sd^K$Hi1VTTh8Tz97_+rtTd5#_qaSMkw{Do z*3aF>u_}BqtHpSU!DBaLBpAM#h4YE1>P(kH^~+ilako92V<5iphLcfD0v|JvX=p4F z$b++C88$rE8e?vF_gFCUE8CUhGn@T7H z7)4F9KyMi=rVt0wNqk$KyrN=SV`X1?N3Ej}xfgfA&+Ib3Bl}}f0DzA1HG|^e^ysoT zpg28RR%Z>?_KYSY*jrWpYUn-XA&m&K0FUWo<+Ak3n{me`Fk$pGo{d(7qNIN;E*MiA zJJLycz^Mh^5W0SndDyxT5%3rXCP}E-$zM$NsP=aNpOBZ}w}G8XRvuFo&@FKbw|A*T zRjPgHeSAdz8UKN*V2p3t;KpB6EBXumF)ygF=VH^O80jH=Q7HaUhes29q)+Ue_f2jO zeLP6vxJ+WBj-BT4cw(c>sN~6Q{%9w{n5T^cRLG(KfG-X_)RE>_&wS~7_w!|$MAq7C zZLNphVpIALTvu+1M{*z3;nD&>hI_DiMD$z&WE`m{dhy}uVsbt@ zs8%A2;ji>%vFo%PZkEKOMSec*ky`PeCiTbN=(7Cr(f1aw$u@lyoLkwneI2Hr?FE(o zdFePlYb|Y9AfCC;mQLVzW78^ET*xze*`N+Q?ix9c>#nIuR5tEFKweN0bls5m27-hmB_8YcbO&fB0WkW$uEDajiZ#)jSe+Cd z);HbFd$DvWDsq-u>OwPG{F``*-^{rzrxg>u!3iDR{LbrRXvQwuN( zT9u`uaOk&;v95Y{M&2OxC6V_-_28K^Ye|*I8SSol!u+H_C~l%S0qE&zBU3SHITMia z4poVwPZPDAUJWYX8C~bNGx{^}q+cLTigs$QrAxIdOrXQhho2}Oi=Uz*6%)Mn zmgJiP`dgLTkb-@E(YYxlMW00AVm|q`VoNL{?u>kPhRXo;W#g8Q`QwIgnsNtv*F zjKJ|HiXGR8jbt>0f*}oNAt{$pI)PDdwlkWq zu7@QFc#c$@twxD-SG?efh3?+`DT)fq-jVxrlXw4-E4zvRg++AJk#Syjl&=;?Za=&3 zB)jeddn#q$yt!&uWbLl5A$R~t;(|i2s~z4P`&3PvF=94(wmtO#OJ2_VF`v#PXMBj% zN-0p{rz!{ZMEV(hbn?q9)gh>nO+C@!z}gYQ_F zD>LeAY$6ehpE!;g!B?TMe8!vEw%EKKa|IIS-?2%I_nfHETX~)b_#80v3w)K*_XeK} z%)-#|--m-zpr2JJvL@~zEuZnee+)Wh&C8_*%?*mX6hjr;_rb>jmoey6?Fc%(4T}s4 z1T`5y2!iOYC{U3R1FHBTB{%PB6I3j71=0CIJ0Q9&6FS9#a+LLiMZ&KrCHqhHLmxe~ z{(^fIu>h!EB^-u2c>pRt7=W&=)k4X#NuX1A;ScXC`L~!!5lGT8Y;)~db!90L8>`=} z9S|(`evm`f1m94Q73Q4RjPT}rPr_Ezok%800u?)*nFchR5`eF7 z{QQE)8LZ|4cj2<{I_)p8&5XbisOIXqjnW5S=X&Q>Oq@vkLu}td$M%0C?r~F$#>h%9 z!J<3`$&bwI>eOlyf7#OVRsOs1AgFpZ*XZp%JE%Q2ySYEJz~{2$V`wdCJX6^iyKY!v z=!k|fZ``;{K&m^`a@nw&Q}4cS-)X-bTyDAKvv1yf2XO$-$&H5L8@=PgHHLWjkFnSO z$v+=eizoQf>Y zfX0-J1q+!R+t~P!p`$%zR`2_|BH>8X@ZZJxj8BR$g(AC(?=u^h=OtVIdhb_)W!uqk z1AD491X|(kQH^9V_{^V|GZ1e5K|@Ed!U{v_Ajq1{70+_Cip#OJJ`i2%e8vzg>$ni~ z5%U8YR1rArhicw$_ww^7ofNd6S#+%tvGMjIWEI%CJL6fZjUF^}4ZLm@6@Yk~#|dnC zna2q9ekMP3HILk-kPry_ynN+q9=7}AedUTQVUG`k^O7SgCvJe6Jkw~_?UMdV%=rB5 za?HTIw{)$?dycyLAF|F%-R2(?J!{(Ls=Wwrfo0N*ch(PD6I0&t-+yp?{h7gw>7o$9 z$DmZAisPz^b&DcB5Ssn8r7EL?>EF+)Rr4SfkeW7_VxYN8Qp ze#Y3T@Mty|tOd7=?mzUvZ=tIAtqymt|1~Yv{kIE%+tbv%5Y=S94Wv>d1_2G3&duKM zzaaz%c-Ih-uWzfQ_Ra^t3Gpj+j8tk=Nx^x1TMv4HQ{`$-U>6^d{uP|!nkkl3yYhGJ*-RfhC$=)C%UXZ8iXNpH2%o{v_Y0jNB1&jeLoApn*4 zIHB_mMJQ2OC3K9;MFZJxEud_9M^J{hndV7Tmqjx<(8ZDmR6v{rHR&A*of`rDP{Fbu zXs75v3Tn-<&Q#4ODFbSZ>Hc_@*1ffqSsh%I8vGmip&{&AeSxa!e1eYC;s555(6RLe zl(mc)(RVDPj0~cpJehvSP3k@N=q!hZj}djPtRVg=p*SqoJV1_L2udUXi;=++$a z&+W_xP%y!U1BGTaL&pebsDfWJxZkC6rKfrKgN9Rg2HqK{)|7j?2#!s*ciE6qcx{=< zO~l+epQ&WySP;?%W$&DUW*~MSWY@-b0x`@4f@f86+*;K~DaZpH%4(Eyux7*0vYJ$b zNU^&SSqu{}8X_keV)(cz@O=UA5!N)G>ot%|^6&NuY4f>_9BhMgoi&AVB1+IxL~v|M z0Q6)L9ACEXjo5>l7H-8OMOq9V*`w--*HQ~UBJ$m@iL>7^7on?R}RaZll{18_VZT!_-&QO7K{gTo@ww@HNdSBtAbOdMTJO0YwG*RDACyAnKZzBu4-&w z)#|~w^#aFhXR|2~JaJk|p`R#WMFiA3AtJWZTbHmUw;IkjZganJS3Ye0=fSs0Q;XtqpJ9kUM~-N z7I-wE2QP~edf3$Qz+>jZ1U*4Q_)yYCRPbc)t9W0B4sTsZ@BMh6bGMe7wQFfAQC7pz znse8gWV{=ziO~{&$MltL7g6pgg`1r*yF;1aJVf292^}~_Iy4RaUg-Aig?8)=lNXbv z8CkHNrtUP?V`%nZqA4m=(QaW($2qWTn;_oUuc zVuM#gXQtlChpro)M~qN~X$^-_=!yBKNA`~+7AlrffI@R+LI`@2Brf>l!b+ae)9zJ9XBXI0G(z zaZ|+F5z~iviGM%m-|&@Mh$yOX`q9uc#-8GAiORitt(y6ct|%FUAB`DRI!Of2txC`B z{=#GF)h>sBjSiXT7&`xGr>YbiwChvUaMW7SRj=pTg0j-*OpB?(JB9z-FZ9ovHFoM$ zDqnz?6UkOoDxLTf$r@BD&Ul(XFI!Y}dUJB_Y&Z3U$qJ`*sS zbENt9LoHsC7V@f54fB~OZoEy+$?0z$xeB7b7Oq5#T-<+fPfjEYl|7o4(^oeVQg+3| z(~A{;K#gQkc=SQ+Ny+E^ls{#mr%#*W%+@ezyzDO&)ear3EME zl%AG6r0}II8Eb_7Msw(Wl79!S2<7L{izOHLz@Ns1R4z02Nlxv#yPzXfE{2*V*E^wZ zRAdI5Q@-ECB83-XVOS;Xf5X)Vu6qu`H0qA<`rnKd<;J(+MqEDbK`8x=bPT=BJ$3Sk--8&J9=5Srou z8Y@R%2UY*AiIwEkz#kZ46bHQTk&T5NjdTW|AMk4h!)7dfn!+?H*6`8^=6hmfF3W58 z&h3EL!ki@e6I`ZW7>p^p9{*q);hU7K1Ik$Q2U8gpELY`sa5LosI#v3fL+LBj37NoT&xGsTN5YE@oV^T2?vvcP3j_<{ z@@U%0=@OI$=UrZ~O{i!{C)Ou9!@Mg5Nz_#u1rwQR+6|OYZiAUbNyfh*Y7nb1cYA|Jm2LLY0OV7V9tL z|3#pw9^V>-1tk*1I0h8 zF{Md~7~~bC6?QY-Xh(2`8BwL}vL?keu>KNe27->%I;&VO?0z1raU`8LF-HUlvTzLC zTWITc{ogsEhjntqC5khBnci)5*dL;__}zdhjq1@h4-o-Ys!W63kfjOugX5*s;TQ{; zf~3=>84H@5(QHuj;)~`{nciYZh3C5w6HI8o1&fJD1(p^+1bQw0SMN`u`EJa3IL&{= zp{4cx37*ZvGqBzuMB7A@2<#6jMXLW<*8iuiw}6Z4=>moc*`><`mIkQ>36YZS4(X5* zDM7kHVCj+$mu8U?kWi8C?p9imF6l16i~r|)pLk!E-`+c?=FGiw&zU*1_lzd+qzA?S zMYB)J`(_8jGvvo2fzgLR97O~+KLpc`tn&io7$5Naih7z3bxu|Qm{L?%MBIEjki$2g zMyF&PoSPbL1x7&S*@2?e7PcX5N1{{~Q3JT?$=!j=e83>HFqTc8hPUuyI05Wej6RS6 zwr8cODkvLfFM4@g!ZW}T?LSLzZsY{31J76?!*s)6P zR)QdK!9CDiGs^&Y=)b3}0VehkX*QX*1{j9_fc@*#6516EnDT$<{ufO`Kp}UC)B-Gf zFd&PB;NIMe)IK4C6D+Ifh-~(D^c8uHCWN~Z(5QC?d)0ps&){Lb{s-cq-5KmFG??tu z9}$wEB=G4N>tO*6?=Tj6ike~0!*xZ`H$ZRdhyVwMXR-g=$XlowEmb>p!a~AHQ+3#>|FO z2TsHdE}NW1gL~fWuC%#?U;7fVY*_#k%BP{cYo-dvq1ZOI$oO?-l5yWMsdOb+esQQ2 z;DG0-3K&Y`dz)el?%lC2;J0^>Fqlil=CH=>3h<=AnIZ+OJGCLu4?Z*i{Qyp~aPN2h zc3`re_lBVUG0=-LYJgrO>j`*>$MvqskE*4B?gYOldtCw`y5#N=hCg0SM|5hnpR@!uS2w89z+zw%mn@QS3cDGS5| z0I#s^>I#?(TDBPbBBl)Au)z?B1I~xB%P;xKkg-9(A$@!R^aDH67;Qtjx2SyaG z-u0bAYwbNYkE}fW*VmnF-1D<_A)#yNnd<;L_{+)2f(G7PhMov z_7V#88PzT@dDM*XOnq(9D>ACp=1zy-Hm&zn@Qu1-;6=&yAuqDMy#~q4R=;2}m_g&?qi)+}1WQk;#N!LzRlNSt5x$>DU)YUX zmK(Wc;Fp7#h1=dz`*vFBQMN-!#e!PhA?g55PJE*zxyWho&LbP-)c`K!N2|1V%$LpU z>xEjK!$%kbl7NV%vwoapc3QH?72l1}57NtUku2b%QYQ*H)HO=f{1{tpV<+Lz=#M%qs5bDon5Vz3tKd5NchODBZO&sl_ag83`nek) zx^8Ix-XwwM`3*So)1y6d*wa8vTcpo}Cknpu59}(yE;+$6dkON?FqgQ@U5SLZouAO* zvU^0g_>)GKvT>ri6cmrn*^VwHLINwENMUq&%IpChS@=<$kh-t@ss$K(o`LToae-Sd z;gv5v-epwB#3BLtP~ftVtcM%27BAk08s@-iVGoYlfsilJLtnqxi*1U-&DTOokTdj1 z__^#+p|AB_I^(`)d0NIrj-yAtS{4kS;g08jn$Ja}BGTm5d5E&s7hyN6EMMgu@o63> ztpPy+@`e0VjseHEQD~wEn^y+KfAcLiXqThEzSNuuHLvuaZ2SfNM9UZW474LZ#2DLl zB?-DL=q8~IRXI_{dvb5L74C<|c!I!bLMXiWvPW+0(ZtiSCu5vr>|<>3G1wUM7~|NZ zF}g9DF)G%|GtVApHA9(+A^R~+S1z_v1|%EB^V#8;x$zAhtI(Iy znn{g0d|tR!ZCZ~FeL#eE&NLBEMRE>u6>S!uVyn>9ceu`gz#Fk(D z9tiWX<`<_*rKhvz|FlYglg_HYMyTlhERt%Nl1Kpa`WC!3Szk8Xxp0QO$e$49f?<5-s4gn}J7PzRqcudibT6pkJU+FS7=!bY~Bjfj%r*tX9f zx4)S?(G_FwK|dMrZZ`iFan-C{=ZX6xP6*}RwkEZ5>x;j3@$cKH(s=zIIJf}@k`o&+ zknrtpC*ZssA2@&g41PE|qB|(EH9CE{Y?kpmPcTZ}zPgMP_oU19eGmI{1K!(aukND= z*}S87VD{fc`eD_Tt;omhT-nRKm{nkrO`AxY{>}M=_#(qL1{#q(jx*UmsK38)-RSSg zZlIPma$ROt&k9tC2^t}ktc1SCuQ!mw#~}*zs>LMZ5PN!6W^5a_;`l;l9Gj9k#o9?X zFDfl8V6@{5_F^U*kZ_4BRqX-32UL0ZwkKA6CQeoW_qKw6a6)yDR92hN<3MM9JCB-e zl0wj_T9o#Y9ac^?k17UAya(F+cq&?_S3jari!P!S4!AIYlRF;1L*p4h0GSfqL!kv8 zOW{_ASspbKA|Z@VkDJ|ap@_V7XeCGZ2=~huv3X`r;0qkjfR@$#E7&Iz!G_p2rG$xH z=&pt!GPdn9NVwJ1h0YGLhXU^-0tTtTk9B}?EEVwN4ZBq01_Rhy^cyDYVR^}67i?;D z!GSv9Ca}X@+3IBi$Ao=z85J%Tz9hSKk z0E}R|<#|ki)=-IMg#RE06np*H8PL#lz-vr>Ty0!sS(%)RLUA7TuAO@6*VS~!GX8;6 zE>-ZiKrV}rhV{Hn#AxvcxSrI6R70)v$62P?j?XBecfH*oPc&YVQw5tH;COsa6lgZp zzSfA%!Tod>IJinOZt)?WnKG1@oHf5siT<=Z_tPIz?S00+7hm#5QBvKvfI-Iv?-B4c zj8P&SUZ?qQH^ujgUV$g@P6IdnDS->TpMVFc>)G(1z~gw%czz)VcdXA9BeXZ%-(6K2 zal@nfSl2mVHQ$ovnf!-Aw8CxB={6ZG7AfXYmNkAnAq@PHsk)4{5 z(0FzfYHV_`>-hd0Cu$#N3e0y!XKUNZs+~7A-qC=2B+52DeRJgxsFTUAvVTfOJ}4G% zYMBw`|V4;-BUgtJp$Q> zrwe4wU#{Dy+)OWQ9T?;NtPY|p7UY6MV%n$Pbo6-Q>cXj;g#f&z=|z+sZ}`RFl3>ee zy34R*Ju`->D<18lRri#^J>ejFa|wl_6)i^g*c^>mb4}7 zroZ$70A=8I82JDWS|kjK+s~^6Z~2X0BKH#(*^T>rGbt&1g5{F%AFDDiM8?!yl{z{& z!t0%}_}6LkoE!oy|ISkoE^r6&#;;{QT`DtiO$z%8vmqM1xSG$mw8>$OpQW}xE1g(# zjm8XWx|vggaAmlv%r0)mTBA3@zt(}QHohhu;B`Ir@uCi0`V+;!5wuOeAaROxh!-ji zo!_kjs1h`wn4Kr#h4kTrRQ>}7lU5M5R`Ap;8g61CeYaa!pO^c!M` zv^0cQ6M`-)x$-sZ9-n-VPrkh{RvinL! zR9^F$6K@}aZMN`XV~}`}Yk6;fJdfdpP3$#X8lm z7p3=Mg{vc{zQwQf@Zk8ZkdqYe2j-{+>4%L&pzUy(JE4k3Rnusq*Vo7VAjmbRKf}xA z=)t(>-!BIjpL2}PK@L23dbYJxX{8tGw#qvmi>uTU z?a==t{z(5o&c%T$&D!11(_1b!b0^$YO5UXkh@-3)5Rp^#QF6L`+vQqzg^LjgB`$6P z6Bf=gYXM*5Hv&(%G=7|Cnp}jf;h2_39nDgZT(`3x$3zEN8~0e3l`gCp$c^oJ^!vWo zDooCNTJRZ0&s~HPjC0KO+mkYMxU`kMg)w_A`I0?vNe`WS#6?T$m0FskZTa8}_pYQm zXU&DgKQDM@Zr6f3HlBVlY=$G(#aQz%qnc}Z_2`G}zbb4o)|!T&?Yd=S+Yaj}xY|R; zAqMpB_N!$WVN!2BEQqLhx|SdZA=gPA*Jm0pF@Mh-Ui(spp6y<6G@7rEZ9tAh2=qN_ifIa{k0=YH^-nE85+Q_QDfwx~%Ty4StCC4P0!;j{Juems?8)Oc+Elv~Xp<&l5 z??{^89v>)(w^_-&_=F4J1rI}OXW}WzPr|mND+jzqFWK_Fk)-3v^+^XD1C8I1$aNRi zd=e}P2a8ex$aUDYi zS5zq0BHX{P(cWTP&iE-uKC2eXFX?xz6G7=lK)Bh4e(bAyI=lwCiO!aJLe_phZpwB; ziMfasXR*+3q1G6G)jyQ!CF!oZ>bwg3eIm7dqFN2g)EpF*Af6fZ*$OrpJbvqcQiw&v6NhVflMj`Ra=Xxu zLW@vlIe48+%+#Ot*PG)d^EI;pybg}=4v~4lB@U4|B$?OR)RWXFOIB;J6+OeaCYo?d za@GiFVNNvSkBL7gCNU{|^OEre&gFdUR-TE=3@P)hJv8zdeNQQwcg*!X~hx*o&btl><*!A8y59+TL7h{gRU`jHn1S zbQ^zja018M8&fYF0mXst(%ROGYzbg^4$zr3`1PE;II6?;y0eI5kGZp|F^azf>b z;r?k*P|6w8sQ9mXdu$)*`>_X{#HJV*BDTz1xRW(!Je)K8aW6M`V0yd^0&s zYK&ukNmCLr)>acnuv_dOjet&T=}^G!@OD4{SnxapVrp}>6+!najW9;}B>I}hBWuoZ z##3+Sk|x3}GDbpgt266|(J9D59*bn$&1$MmOjyU7j@$gx z2Lrc-$wQ!l+xNy&OM%xM3pOu{1(=!yMARK^+O8V6zqtdX`g=81Iju*T+8vyip~e31 z?wSD|C%A|JeL4KV2g>lKVpcC6pyF(t^@5*n$30enlDCEYTt=U2^4%Dd3rQ_SXv-H2 zHLo(KUzg-NseM$|fj-Lp_-SS;f zvt#3baj^QSZ7K}GG9L={FBObnQ5RdM1HOoy_Y{cZi*M2`6 z+wzy0kukfRJ!8bXQor9r_-JYBG0t9ZuwI2xEdzm=sEeYb;?_Psbul~)__ow7y%)O( za%E$%aZFC;FFM+b#VvDZ98B_gd*QaraC$=+>6ed2kuWW9D@jj$t)O>E2rxX1RM>!mB-P*XBdVN+qo3823r zQid~ZZk`y3_}g=_+N)W$C5|VIjtXC>4Ntg?+ASBee3IJwY>g|m`I#jb zux6j_-)l@)bm`G=L`Q%1KAG7YUdW+lfWyp@IKI(o;MuQFhjru8ulJFo=gdm;YT|R; zQ~Cu!>#I}dGYu;yP5B}b*>y(Jryja+Az*k$3zuL{s z>cP&#`XASqm5TUclna5kzP!9|sj7S03|H2thds9*oJd_*biuwnS4(^KG|CsP2zkH( zAK-pXA1@B9sE9qUQsz+MeMQcsiDpu&w>+RIgqfMIRfn57?uJ_VRpb53z@zt-Qrmdw z-pZ+YZv159MlaykpNm`%H+r?BVBcEgx3bkS{f`&x9DOYuSYIdIQn>eyQ}idLY!m zp3hn=mA*63@NASQaDPIcARrD6{bKp~4X9oI*VYA^#tmEhwKN?u-1n`&+v#A+N=rs} zR_*0)Ice6hwd6X@%%|U1llv023KKJ*%C06CKPn1%!xTlu6KVySkEAq}bO#pT+q;1U zcq}Lo%)HSQZ?@b9qM&=7F=3A=Lxr7JJc)t$X6-`(f8}3!bk8V2xl zhyqCLQD7Ddf4t-|I6tCxPkY{;RZ9j)$RV5=#J0!^I%V(JhxU?tF3TaxVgTIO-Wv3i zwaK%NYb&n>T*r)GmOPE5;WZ;mx{()}HHXo2ua^gY#cu7Bm&&mV;W1qCl%T2APQ5njiRZf)?bSd`$twBhj|;i=^fhQX#WU-Jgi-F@XuKHwxMOVziAc^aq!fgssk+b zl`zR~mSGQS{80Vx@}quUmCYvQ2c~P0X|vz~{!P+-TmpzNlq7*{l|CbdY>c}rW`^`N@$=k6q#mi(XE1@v18>^ekR<3MtWJOHQd$|8n z&6+u#z*GNMBI-t_89C29b4@O=4ObIySbA3zwGl3N65|>dRT?Hidg^|^*O|O< z`23mY^(;+-YSg`jz3ANqSE)@gzRRYc!W8xG#*0?>~f9ATf&O;d*d`ul~G0*%vkIslH+*vRqZu{*?dmEXj{533sgm$>$ zpswixBTtcr_UIjSh}(;+%QUv_RVx^q;qHsZ#ptilxNlwieRdGX_12Bw?eJ=i3%K1( z=!jjnBZYl(qfya;N&x6EcTju@6e+Hf^FyGm!vEmWO>R!P9?K1?wJFO@E^XD7cY$bV z|8L(DvODyjH4m4MdCsIoZ;*WDg(j(trh7tJNyUD!-k~8Pl6C1ftM39Q|Xx zW8~sqY)03}*a=ES4%b~Xk$h4zFOhZbW+3bh6;ZN-CY(pvSDqD9F{doR;Vcwnr}fc61`T#+(pOqVJ?V+ zz8b1C(h2^;w^|w6kqB27aH80<+muTe(ukWeDQA1XNTI13((yu?v&`tXDk(yDl)d)B zP-2iyGJ}W@N`KA#5@G|ji=<5xpVS1&bsgN+|1C=dS~Abl#xUy1%DI>$;<~FwrI1}W z4~pvxJ|%miLc{(o!0bpOZH<0d7WfV~XG>PR9lS)NApK^K8xL8jm_XLyQ8s`pwDIPM1P&|SSb?J|r?NL+y= z5kpG)Da`)^n_-)NuG*+T6p9!-4s1hLDf{Xev!0pY#9)+9KG48&NIGyPK6*QnV22g^ zXLpUn;mS8w@)bDo12vl0I4(@Lt@hQ+k-@&hi1hgh2fN0@hj?KYb>y$|k#>VmUXY^| zW!9162eS|WuK+4$!lrjem7wbF%`<+3Xe2JY+>Fh2Zeg8>S16exMKuY5EDFG#MEUYP z-#3?L0M zmCR@c{BZHJ)nM&st2fU!8kZHy=+{SDzc>&5oI2(xGo^}Ovfi1ZGEX^E;WQhP3)-G( z^Q^#4PLmXJy~l+EoWEP%YrNA5^Puv(Y=Af{0f95wvawwjjZG5nVO zHgb zm;y?emKFD^6g8R-r|8=KFuGX&eM@_9nj9vdP?x;6`%Ev z{&4oVh&L$&<Rgx|w<*YOioENa3Dn1Ju!P64!jB1aMyznV?al?4kY=tY(PfCx)usp&WPbi34e)u_xB)_y#`=rYY3sq9*8=!P#@i4WK0 zxxq(dRmr38-^7hxX*pVDh4Md60?qi1u?_eUbibt20={jDnF& zs-(>^`S|SZc^!3$i?P1THmMT7!?kn=hF5J7o-j epX=2sP)A1~&Hv{|P%C_+{}+ zwCd%zLjEDYne}g4ze?eYg5pdY8W`oz60x}UpcO?7#>ZL3)$JXM%UX6~B#Ag=`5w(b z$0nI+7>)M4<2m;fdk2ksCDFXsaH>C30l)6ZPZO_YKV4$`an_VA&4NL_)~7~OX7}|( zO6a=MnYzF+-<+Ki>vFK=5sr^11kMv`!TN_dOs;PuEjcYr$CXf}w|cICa5y5k@9u<= z8?K+hmRd#jmHf-F$C9-b$8XL|atFK-H~w*h7CE8WaRtJPul&M3@3~-JS6w5p{MRZ^ za`qAj_ze#==zf13s4~L^2TlHv-!R=7*T^P3?e2`65Z8*30@>MEJ=r>GV20ZU50NeP z2cyf@pS7X7X`Jr&tK^-{XR}^de2$3J;dV4q(?& zszMh_`|wCMdLz?omb_^mw(b2IR>8T(P#Ypt-ErF|idl(II|}Z&aA_=tE}EtWR`Pg- zLy~jZn23M-Hdcr6Y&WEMs=<|R!>iFf@C&P&ho~*gUfjqz?rhrWa&4}Gq+-)6&Z}q! z1HS&&dXg2BPzL=apDvTqZeuDvIA0{AMe9#E^UzSlXYbEMJk!H02&SHD#?n~R5E414 z*_1vjg^p|YRQnZNX4h3FHq(9l1Nww`vvf_;>NvKIj#ZA4?jyfto@n^X()ZPv8amyf zghf|UMu(D}%Sln#B67W~!xP7+ss1 z>1A(e-D~f-LB4%q){ulpo<+Rg@17y5A3fH;ng0Ws!Wj@|A=BeoV;W1-89`q>{F9%5 zmno~NEu^;I9$tx!YG3o{?awv@HMVn%6dso%C52s|kj@iw zpG3*Fix$T~*9lthsNjMo3NC*_-RviB!aGe1aCOkvE<7cNmFNTE`Y#2MuQcO*HfxlR zdxLdCwkMMshtj1o0!SefadGq;lLT{xPlvK@(7hKe13#oa@1qj)uf5oh*wGNHb73*R zyz~%pDfCNe-V)~K9X}HYc;GX>ksfIw7yIpG7Q#KKM#?rV zy8uhNIsU!Qh^_#o_%TgMrL5DIj3Pt8XRMa0G~q9Eypp+FQDahkYXvQG4oke*6W5k9 zN$YR1T_W=Q>}fhNWD;>ak3Ee1h2*2B;GC0O@Y~CM)0RKCpbhaqw`bz_Nrf=p(9U<7 z*PN4pnNi_mYVA)TVf(7S;RWY;J7L&E&`3e_96obL!PPbp44e*U#B{ZOD9l}dh$ue_DJ zjj99h$)qR|b$rmd!mUF;Dc!R$Vz&6Xxn2oJSd+j z^{n0ubvGv1&j0r7_Tf$9qIk7NhZKL!a=;gDr+&OAMJm+*)jugPy|@Z9$or zrHUELMi0$gCld`2*Vh#|gf-W8f*BjEcgE*8{Ax81WR~#8Ifp+VXAbV^;v{!zP=${@ ziI#u-^n-=U%Hf-@XLilp^CTr5M}Hy}p$j1)pO#aZL+~rqBIG50T#5Z*oDsOc*jR}- zpW}9by@U*ElA&NuR5(1MJiZS*K~@{hUPgbfoQGaFhI-~9x`K^uRBsQ8``ElspD1FjA%CY=KT45T&RP!*R^3-uIFgoez8D`y<%OG z*Q+n7-p~)ta}brLZIJ7>N2Y&HDbT?#cnHL8re4Tr0qmPl+An9)T{kwq2^1bk0lVLFSP z5>JfQKvjN2MWzj<`zb2<19TUUQ6|kULhHnr5B8;(<}ucBjv7EgCk+zUy#!lEYE02*p*t zwuhA86{v#tn=H1po@L#szH67XOyUgYny^xzE65f9oWV0{p!bTBhJ!*(5^ zyr8>-)hYWgj^{mZ>}zivewH*T!P>81h%qbbYU0%`tj^8;B(|^@(0up9!a&nIV^^#I0%xf@yi3Xqe4;9I8gpy+wdXUDZv`p+rVaS zrY@Ftu3QLb1~3Wb|8DRGWE}g~9|1y@3jB!jzxSj1|B?5{XhakhSRRcY5AmlKofNS} z1%^=l$9766(ElVxu{OIWBSCOd1GWCgPCfraHi|Hz20y;fJw|~>^z$E68 zn+8mR5TpmbNNB(m=tW#;@9WSZKrS*8gyB7aX8tb#A$Jdn>_sEQ`?m&}cIfxSh-d&u z{aZqEl{Xj#C9V(sf2vQL`G;)$UIZsCAQavB0l-LtAg2W&UXaCX8 z$M64z1Tv^mAf_3B`Z$3MXn(o;?&6 z5U4ajFZ}Cd0K4amhJr%$U-V)R5CJS;2DblW86TkhkHl#Z7{$WTT;0Xd$(75@$?31e n|5fi23rO$-Tms6coUd#g)Ri$n_q8wqpZC}(D3>^3p!EL%(stRD diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 5aff7f47e..3ffe80c5f 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -289,23 +289,21 @@ extern "C" /** * enable step counting on sync motion command (needed for some Gcode extensions like G33) * */ - - #define ENABLE_RT_SYNC_MOTIONS + // #define ENABLE_RT_SYNC_MOTIONS /** * enable motion control and planner highjacking * this unlocks funtions to perform a full planner copy and restore - * this requires some memory since the full planned contents must be stored and also the motion control reference position + * this requires some memory since the full planned contents must be stored and also the motion control reference position * */ - - #define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING + // #define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING /** * Uncomment to enable module extensions * */ - #define ENABLE_MAIN_LOOP_MODULES +// #define ENABLE_MAIN_LOOP_MODULES // #define ENABLE_IO_MODULES - #define ENABLE_PARSER_MODULES +// #define ENABLE_PARSER_MODULES // #define ENABLE_MOTION_CONTROL_MODULES // #define ENABLE_SETTINGS_MODULES @@ -318,7 +316,7 @@ extern "C" // enables automatic status report sending // this value sets the millisecond interval of the reports // values bellow 100ms have no effect -#define STATUS_AUTOMATIC_REPORT_INTERVAL 1000 +#define STATUS_AUTOMATIC_REPORT_INTERVAL 0 /** * @@ -464,7 +462,7 @@ extern "C" * helps to reduce code size if features are not needed * */ #ifndef DISABLE_ALL_CONTROLS -#define DISABLE_ALL_CONTROLS +// #define DISABLE_ALL_CONTROLS #endif #ifndef DISABLE_ALL_LIMITS // #define DISABLE_ALL_LIMITS diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 3fd46f1aa..eba55e8f4 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -97,7 +97,7 @@ extern "C" * NOTE: If Laser PPI is enabled one of the stepper drivers position will be used by the laser controller * Usually that is STEPPER so if AXIS_COUNT=3, STEPPER3 will be used by laser PPI */ -//#define ENABLE_DUAL_DRIVE_AXIS +// #define ENABLE_DUAL_DRIVE_AXIS #ifdef ENABLE_DUAL_DRIVE_AXIS // defines the first dual drive capable axis // #define DUAL_DRIVE0_AXIS X @@ -107,7 +107,7 @@ extern "C" // #define DUAL_DRIVE0_ENABLE_SELFSQUARING // defines the first second drive capable axis -//#define DUAL_DRIVE1_AXIS Y +// #define DUAL_DRIVE1_AXIS Y // by default this will be rewired to STEPPER7 (if available on the board) // this can be uncommented to re-wire to an available (unused stepper other then 7) // #define DUAL_DRIVE1_STEPPER 7 @@ -122,11 +122,10 @@ extern "C" You can't skip tool numbers (for example define TOOL1 and TOOL3 without having a TOOL2) */ - /** - * - * Enables Laser PPI capabilities - * + * + * Enables Laser PPI capabilities + * * **/ #ifdef ENABLE_LASER_PPI #define LASER_PPI PWM0 @@ -135,25 +134,76 @@ extern "C" #endif /** - * + * * Enables Plasma THC capabilities - * + * * **/ - #define ENABLE_PLASMA_THC - +// #define ENABLE_PLASMA_THC /** + * + * Tool pallete + * You can assign your tool pallete indexes here + * Up to 16 tools can be defined + * M6 command is available if TOOL_COUNT >= 2 + * + * to set a tool you just need to define which tool will be in which index. + * For example: Set TOOL1 as laser_pwm * + * #define TOOL1 laser_pwm * - * + * Tools can be any of the built in tools available in /src/hal/tools/tools/ or you can use your own custom tool. * * **/ // assign the tools from 1 to 16 -#define TOOL1 plasma_thc -// #define TOOL2 laser -// #define TOOL3 laser_ppi -// #define TOOL4 spindle_besc -// #define TOOL5 spindle_relay +#if (TOOL_COUNT >= 1) +#define TOOL1 spindle_pwm +#endif +#if (TOOL_COUNT >= 2) +#define TOOL2 spindle_pwm +#endif +#if (TOOL_COUNT >= 3) +#define TOOL3 spindle_pwm +#endif +#if (TOOL_COUNT >= 4) +#define TOOL4 spindle_pwm +#endif +#if (TOOL_COUNT >= 5) +#define TOOL5 spindle_pwm +#endif +#if (TOOL_COUNT >= 6) +#define TOOL6 spindle_pwm +#endif +#if (TOOL_COUNT >= 7) +#define TOOL7 spindle_pwm +#endif +#if (TOOL_COUNT >= 8) +#define TOOL8 spindle_pwm +#endif +#if (TOOL_COUNT >= 9) +#define TOOL9 spindle_pwm +#endif +#if (TOOL_COUNT >= 10) +#define TOOL10 spindle_pwm +#endif +#if (TOOL_COUNT >= 11) +#define TOOL11 spindle_pwm +#endif +#if (TOOL_COUNT >= 12) +#define TOOL12 spindle_pwm +#endif +#if (TOOL_COUNT >= 13) +#define TOOL13 spindle_pwm +#endif +#if (TOOL_COUNT >= 14) +#define TOOL14 spindle_pwm +#endif +#if (TOOL_COUNT >= 15) +#define TOOL15 spindle_pwm +#endif +#if (TOOL_COUNT >= 16) +#define TOOL16 spindle_pwm +#endif // enable RPM encoder for spindle_pwm // depends on encoders (below) @@ -333,7 +383,7 @@ extern "C" #define STEPPER0_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER1_HAS_TMC +// #define STEPPER1_HAS_TMC #ifdef STEPPER1_HAS_TMC #define STEPPER1_DRIVER_TYPE 2208 // choose the interface type @@ -360,7 +410,7 @@ extern "C" #define STEPPER1_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER2_HAS_TMC +// #define STEPPER2_HAS_TMC #ifdef STEPPER2_HAS_TMC #define STEPPER2_DRIVER_TYPE 2208 // choose the interface type @@ -387,7 +437,7 @@ extern "C" #define STEPPER2_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER3_HAS_TMC +// #define STEPPER3_HAS_TMC #ifdef STEPPER3_HAS_TMC #define STEPPER3_DRIVER_TYPE 2208 // choose the interface type @@ -414,7 +464,7 @@ extern "C" #define STEPPER3_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER4_HAS_TMC +// #define STEPPER4_HAS_TMC #ifdef STEPPER4_HAS_TMC #define STEPPER4_DRIVER_TYPE 2208 // choose the interface type @@ -441,7 +491,7 @@ extern "C" #define STEPPER4_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER5_HAS_TMC +// #define STEPPER5_HAS_TMC #ifdef STEPPER5_HAS_TMC #define STEPPER5_DRIVER_TYPE 2208 // choose the interface type @@ -468,7 +518,7 @@ extern "C" #define STEPPER5_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER6_HAS_TMC +// #define STEPPER6_HAS_TMC #ifdef STEPPER6_HAS_TMC #define STEPPER6_DRIVER_TYPE 2208 // choose the interface type @@ -495,7 +545,7 @@ extern "C" #define STEPPER6_STALL_SENSITIVITY 10 #endif // uncomment to enable trinamic driver -//#define STEPPER7_HAS_TMC +// #define STEPPER7_HAS_TMC #ifdef STEPPER7_HAS_TMC #define STEPPER7_DRIVER_TYPE 2208 // choose the interface type diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 1c31b9a17..85c0eacb7 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -252,6 +252,7 @@ bool cnc_dotasks(void) void cnc_store_motion(void) { + #ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING // set hold and wait for motion to stop uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); @@ -259,7 +260,7 @@ void cnc_store_motion(void) { if (!cnc_dotasks()) { - return false; + return; } } // store planner and motion controll data away @@ -276,10 +277,12 @@ void cnc_store_motion(void) } lock_itp = false; + #endif } void cnc_restore_motion(void) { + #ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING // set hold and wait for motion to stop uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); @@ -287,7 +290,7 @@ void cnc_restore_motion(void) { if (!cnc_dotasks()) { - return false; + return; } } @@ -307,6 +310,7 @@ void cnc_restore_motion(void) cnc_clear_exec_state(EXEC_HOLD); } lock_itp = false; + #endif } // this function is executed every millisecond diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index 66fddde4c..d18e8a124 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -25,7 +25,7 @@ extern "C" #endif #define CNC_MAJOR_MINOR_VERSION "1.8" -#define CNC_PATCH_VERSION ".x" +#define CNC_PATCH_VERSION ".0-beta" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 4c12a723f..a8ad7fe17 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -640,14 +640,14 @@ extern "C" #define LASER_PPI_MASK STEP6_MASK #endif #ifndef LASER_PPI -#define LASER_PPI -1 +#define LASER_PPI UNDEF_PIN #endif // #ifdef STEP_ISR_SKIP_MAIN // #undef STEP_ISR_SKIP_MAIN // #warning "STEP_ISR_SKIP_MAIN was disabled for Laser PPI mode" // #endif #else -#define LASER_PPI -1 +#define LASER_PPI UNDEF_PIN #endif #define __stepname_helper__(x) STEP##x##_MASK @@ -2274,6 +2274,24 @@ typedef uint16_t step_t; #endif #endif +#ifdef ENABLE_PLASMA_THC + +//forces modes +#ifndef ENABLE_MAIN_LOOP_MODULES +#define ENABLE_MAIN_LOOP_MODULES +#endif +#ifndef ENABLE_PARSER_MODULES +#define ENABLE_PARSER_MODULES +#endif +#ifndef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +#define ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +#endif +#ifndef ENABLE_RT_SYNC_MOTIONS +#define ENABLE_RT_SYNC_MOTIONS +#endif + +#endif + #ifdef __cplusplus } #endif diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 1b9693014..8352d12ea 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1157,19 +1157,11 @@ uint32_t itp_get_rt_line_number(void) // turn laser off callback MCU_CALLBACK void laser_ppi_turnoff_cb(void) { -#if ASSERT_PIN(LASER_PPI) #ifndef INVERT_LASER_PPI_LOGIC io_clear_output(LASER_PPI); #else io_set_output(LASER_PPI); #endif -#elif ASSERT_PIN_EXTENDER(LASER_PPI) -#ifndef INVERT_LASER_PPI_LOGIC - io_set_output(LASER_PPI, false); -#else - io_set_output(LASER_PPI, true); -#endif -#endif } #endif diff --git a/uCNC/src/core/planner.h b/uCNC/src/core/planner.h index 15a062fc2..6e99ba5f3 100644 --- a/uCNC/src/core/planner.h +++ b/uCNC/src/core/planner.h @@ -30,7 +30,7 @@ extern "C" #include #ifndef PLANNER_BUFFER_SIZE -#define PLANNER_BUFFER_SIZE 30 +#define PLANNER_BUFFER_SIZE 20 #endif #define PLANNER_MOTION_EXACT_PATH 32 // default (not used) diff --git a/uCNC/src/hal/boards/avr/boardmap_uno.h b/uCNC/src/hal/boards/avr/boardmap_uno.h index e67e3de9d..52b3cc157 100644 --- a/uCNC/src/hal/boards/avr/boardmap_uno.h +++ b/uCNC/src/hal/boards/avr/boardmap_uno.h @@ -29,7 +29,9 @@ extern "C" #endif // reduces RAM usage a bit to prevent hardware resets +#ifndef PLANNER_BUFFER_SIZE #define PLANNER_BUFFER_SIZE 14 +#endif #define PCINT0_PORT B #define PCINT1_PORT C @@ -43,8 +45,8 @@ extern "C" #define STEP1_PORT D // assigns STEP1 port #define STEP0_BIT 2 // assigns STEP0 pin #define STEP0_PORT D // assigns STEP0 port -//#define STEP6_BIT 4 //assigns STEP6 pin (will mirror DUAL_AXIS0) -//#define STEP6_PORT C //assigns STEP6 port (will mirror DUAL_AXIS0) +// #define STEP6_BIT 4 //assigns STEP6 pin (will mirror DUAL_AXIS0) +// #define STEP6_PORT C //assigns STEP6 port (will mirror DUAL_AXIS0) // Setup dir pins #define DIR2_BIT 7 // assigns DIR2 pin @@ -58,9 +60,9 @@ extern "C" #define LIMIT_Z_BIT 4 // assigns LIMIT_Z pin #define LIMIT_Z_PORT B // assigns LIMIT_Z port #define LIMIT_Z_ISR 0 // assigns LIMIT_Z ISR -// #define LIMIT_Y2_BIT 4 //Z and second Y limit share the pin -// #define LIMIT_Y2_PORT B //Z and second Y limit share the pin -// #define LIMIT_Y2_ISR 0 //Z and second Y limit share the pin + // #define LIMIT_Y2_BIT 4 //Z and second Y limit share the pin + // #define LIMIT_Y2_PORT B //Z and second Y limit share the pin + // #define LIMIT_Y2_ISR 0 //Z and second Y limit share the pin #define LIMIT_Y_BIT 2 // assigns LIMIT_Y pin #define LIMIT_Y_PORT B // assigns LIMIT_Y port @@ -93,7 +95,7 @@ extern "C" #define TX_PORT D #define RX_PULLUP // only uncomment this if other port other then 0 is used - //#define UART_PORT 0 + // #define UART_PORT 0 // Setup PWM #define PWM0_BIT 3 // assigns PWM0 pin @@ -134,13 +136,13 @@ extern "C" // Setup the Step Timer used has the heartbeat for µCNC // Timer 1 is used by default - //#define ITP_TIMER 1 + // #define ITP_TIMER 1 // Setup the RTC Timer used by µCNC to provide an (mostly) accurate time base for all time dependent functions // Timer 0 is set by default - //#define RTC_TIMER 0 + // #define RTC_TIMER 0 - #define ONESHOT_TIMER 2 +#define ONESHOT_TIMER 2 #ifdef __cplusplus } diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 1f00d8914..3a1dcc4c9 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -1242,21 +1242,21 @@ void mcu_start_timeout() uint8_t mcu_get_pin_offset(uint8_t pin) { - if (pin >= STEP0 && pin <= STEP7_EN) + if (pin >= 1 && pin <= 24) { return pin; } - else if (pin >= DOUT0 && pin <= DOUT31) + else if (pin >= 47 && pin <= 78) { - return pin - DOUT0; + return pin - 47; } - if (pin >= LIMIT_X && pin <= CS_RES) + if (pin >= 100 && pin <= 113) { - return pin - LIMIT_X; + return pin - 100; } - else if (pin >= DIN0 && pin <= DIN31) + else if (pin >= 130 && pin <= 161) { - return pin - DIN0; + return pin - 130; } return -1; diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index 7c2beba5c..a0df47bd3 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -51,155 +51,310 @@ // joints step/dir pins #define STEP0 1 +#define DIO1 1 #define STEP1 2 +#define DIO2 2 #define STEP2 3 +#define DIO3 3 #define STEP3 4 +#define DIO4 4 #define STEP4 5 +#define DIO5 5 #define STEP5 6 +#define DIO6 6 #define STEP6 7 +#define DIO7 7 #define STEP7 8 +#define DIO8 8 #define DIR0 9 +#define DIO9 9 #define DIR1 10 +#define DIO10 10 #define DIR2 11 +#define DIO11 11 #define DIR3 12 +#define DIO12 12 #define DIR4 13 +#define DIO13 13 #define DIR5 14 +#define DIO14 14 #define DIR6 15 +#define DIO15 15 #define DIR7 16 +#define DIO16 16 #define STEP0_EN 17 +#define DIO17 17 #define STEP1_EN 18 +#define DIO18 18 #define STEP2_EN 19 +#define DIO19 19 #define STEP3_EN 20 +#define DIO20 20 #define STEP4_EN 21 +#define DIO21 21 #define STEP5_EN 22 +#define DIO22 22 #define STEP6_EN 23 +#define DIO23 23 #define STEP7_EN 24 +#define DIO24 24 #define PWM0 25 +#define DIO25 25 #define PWM1 26 +#define DIO26 26 #define PWM2 27 +#define DIO27 27 #define PWM3 28 +#define DIO28 28 #define PWM4 29 +#define DIO29 29 #define PWM5 30 +#define DIO30 30 #define PWM6 31 +#define DIO31 31 #define PWM7 32 +#define DIO32 32 #define PWM8 33 +#define DIO33 33 #define PWM9 34 +#define DIO34 34 #define PWM10 35 +#define DIO35 35 #define PWM11 36 +#define DIO36 36 #define PWM12 37 +#define DIO37 37 #define PWM13 38 +#define DIO38 38 #define PWM14 39 +#define DIO39 39 #define PWM15 40 +#define DIO40 40 #define SERVO0 41 +#define DIO41 41 #define SERVO1 42 +#define DIO42 42 #define SERVO2 43 +#define DIO43 43 #define SERVO3 44 +#define DIO44 44 #define SERVO4 45 +#define DIO45 45 #define SERVO5 46 +#define DIO46 46 #define DOUT0 47 +#define DIO47 47 #define DOUT1 48 +#define DIO48 48 #define DOUT2 49 +#define DIO49 49 #define DOUT3 50 +#define DIO50 50 #define DOUT4 51 +#define DIO51 51 #define DOUT5 52 +#define DIO52 52 #define DOUT6 53 +#define DIO53 53 #define DOUT7 54 +#define DIO54 54 #define DOUT8 55 +#define DIO55 55 #define DOUT9 56 +#define DIO56 56 #define DOUT10 57 +#define DIO57 57 #define DOUT11 58 +#define DIO58 58 #define DOUT12 59 +#define DIO59 59 #define DOUT13 60 +#define DIO60 60 #define DOUT14 61 +#define DIO61 61 #define DOUT15 62 +#define DIO62 62 #define DOUT16 63 +#define DIO63 63 #define DOUT17 64 +#define DIO64 64 #define DOUT18 65 +#define DIO65 65 #define DOUT19 66 +#define DIO66 66 #define DOUT20 67 +#define DIO67 67 #define DOUT21 68 +#define DIO68 68 #define DOUT22 69 +#define DIO69 69 #define DOUT23 70 +#define DIO70 70 #define DOUT24 71 +#define DIO71 71 #define DOUT25 72 +#define DIO72 72 #define DOUT26 73 +#define DIO73 73 #define DOUT27 74 +#define DIO74 74 #define DOUT28 75 +#define DIO75 75 #define DOUT29 76 +#define DIO76 76 #define DOUT30 77 +#define DIO77 77 #define DOUT31 78 +#define DIO78 78 #define LIMIT_X 100 +#define DIO100 100 #define LIMIT_Y 101 +#define DIO101 101 #define LIMIT_Z 102 +#define DIO102 102 #define LIMIT_X2 103 +#define DIO103 103 #define LIMIT_Y2 104 +#define DIO104 104 #define LIMIT_Z2 105 +#define DIO105 105 #define LIMIT_A 106 +#define DIO106 106 #define LIMIT_B 107 +#define DIO107 107 #define LIMIT_C 108 +#define DIO108 108 #define PROBE 109 +#define DIO109 109 #define ESTOP 110 +#define DIO110 110 #define SAFETY_DOOR 111 +#define DIO111 111 #define FHOLD 112 +#define DIO112 112 #define CS_RES 113 +#define DIO113 113 #define ANALOG0 114 +#define DIO114 114 #define ANALOG1 115 +#define DIO115 115 #define ANALOG2 116 +#define DIO116 116 #define ANALOG3 117 +#define DIO117 117 #define ANALOG4 118 +#define DIO118 118 #define ANALOG5 119 +#define DIO119 119 #define ANALOG6 120 +#define DIO120 120 #define ANALOG7 121 +#define DIO121 121 #define ANALOG8 122 +#define DIO122 122 #define ANALOG9 123 +#define DIO123 123 #define ANALOG10 124 +#define DIO124 124 #define ANALOG11 125 +#define DIO125 125 #define ANALOG12 126 +#define DIO126 126 #define ANALOG13 127 +#define DIO127 127 #define ANALOG14 128 +#define DIO128 128 #define ANALOG15 129 +#define DIO129 129 #define DIN0 130 +#define DIO130 130 #define DIN1 131 +#define DIO131 131 #define DIN2 132 +#define DIO132 132 #define DIN3 133 +#define DIO133 133 #define DIN4 134 +#define DIO134 134 #define DIN5 135 +#define DIO135 135 #define DIN6 136 +#define DIO136 136 #define DIN7 137 +#define DIO137 137 #define DIN8 138 +#define DIO138 138 #define DIN9 139 +#define DIO139 139 #define DIN10 140 +#define DIO140 140 #define DIN11 141 +#define DIO141 141 #define DIN12 142 +#define DIO142 142 #define DIN13 143 +#define DIO143 143 #define DIN14 144 +#define DIO144 144 #define DIN15 145 +#define DIO145 145 #define DIN16 146 +#define DIO146 146 #define DIN17 147 +#define DIO147 147 #define DIN18 148 +#define DIO148 148 #define DIN19 149 +#define DIO149 149 #define DIN20 150 +#define DIO150 150 #define DIN21 151 +#define DIO151 151 #define DIN22 152 +#define DIO152 152 #define DIN23 153 +#define DIO153 153 #define DIN24 154 +#define DIO154 154 #define DIN25 155 +#define DIO155 155 #define DIN26 156 +#define DIO156 156 #define DIN27 157 +#define DIO157 157 #define DIN28 158 +#define DIO158 158 #define DIN29 159 +#define DIO159 159 #define DIN30 160 +#define DIO160 160 #define DIN31 161 +#define DIO161 161 #define TX 200 +#define DIO200 200 #define RX 201 +#define DIO201 201 #define USB_DM 202 +#define DIO202 202 #define USB_DP 203 +#define DIO203 203 #define SPI_CLK 204 +#define DIO204 204 #define SPI_SDI 205 +#define DIO205 205 #define SPI_SDO 206 +#define DIO206 206 #define SPI_CS 207 -#define I2C_CLK 208 -#define I2C_DATA 209 +#define DIO207 207 +#define I2C_SCL 208 +#define DIO208 208 +#define I2C_SDA 209 +#define DIO209 209 +#define TX2 210 +#define DIO210 210 +#define RX2 211 +#define DIO211 211 + #define MCU_HAS_ONESHOT_TIMER diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 5ba0eeb5f..525e8a40a 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -1,19 +1,19 @@ /* - Name: plasma_thc.c - Description: Defines a plasma tool with THC for µCNC. + Name: plasma_thc.c + Description: Defines a plasma tool with THC for µCNC. - Copyright: Copyright (c) João Martins - Author: João Martins - Date: 29/06/2023 + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 29/06/2023 - µCNC 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. Please see + µCNC 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. Please see - µCNC is distributed WITHOUT ANY WARRANTY; - Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - See the GNU General Public License for more details. + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. */ #include @@ -43,14 +43,16 @@ #define PLASMA_STEPPERS_MASK (1 << 2) #endif +#ifdef ENABLE_PLASMA_THC + // overridable // user can implement the plasma thc up condition based on analog voltage reading using analog the controller analog inputs and PID controllers uint8_t __attribute__((weak)) plasma_thc_up(void) { #if ASSERT_PIN(PLASMA_UP_INPUT) - return mcu_get_input(PLASMA_UP_INPUT); + return io_get_input(PLASMA_UP_INPUT); #else - return 0; + return 0; #endif } @@ -59,9 +61,9 @@ uint8_t __attribute__((weak)) plasma_thc_up(void) uint8_t __attribute__((weak)) plasma_thc_down(void) { #if ASSERT_PIN(PLASMA_DOWN_INPUT) - return mcu_get_input(PLASMA_DOWN_INPUT); + return io_get_input(PLASMA_DOWN_INPUT); #else - return 0; + return 0; #endif } @@ -70,9 +72,9 @@ uint8_t __attribute__((weak)) plasma_thc_down(void) uint8_t __attribute__((weak)) plasma_thc_arc_ok(void) { #if ASSERT_PIN(PLASMA_ARC_OK_INPUT) - return mcu_get_input(PLASMA_ARC_OK_INPUT); + return io_get_input(PLASMA_ARC_OK_INPUT); #else - return 0; + return 0; #endif } @@ -86,130 +88,130 @@ static volatile int8_t plasma_step_error; typedef struct plasma_start_params_ { - float probe_depth; // I - float probe_feed; // J - float retract_height; // R - float cut_depth; // K - float cut_feed; // F - uint16_t dwell; // P*1000 - uint8_t retries; // L + float probe_depth; // I + float probe_feed; // J + float retract_height; // R + float cut_depth; // K + float cut_feed; // F + uint16_t dwell; // P*1000 + uint8_t retries; // L } plasma_start_params_t; static plasma_start_params_t plasma_start_params; bool plasma_thc_probe_and_start(void) { - static bool plasma_starting = false; - if (plasma_starting) - { - // prevent reentrancy - return false; - } - - plasma_starting = true; - uint8_t ret = plasma_start_params.retries; - cnc_store_motion(); - - // wait for cycle start - while (cnc_get_exec_state(EXEC_HOLD)) - { - cnc_dotasks(); - } - - while (ret--) - { - // cutoff torch - // temporary disable - plasma_thc_state = PLASMA_ARC_OFF; - motion_data_t block = {0}; - block.motion_flags.bit.spindle_running = 0; - mc_update_tools(&block); - - // get current position - float pos[AXIS_COUNT]; - mc_get_position(pos); - - // modify target to probe depth - pos[AXIS_Z] += plasma_start_params.probe_depth; - // probe feed speed - block.feed = plasma_start_params.probe_feed; - // similar to G38.2 - if (mc_probe(pos, 0, &block) == STATUS_PROBE_SUCCESS) - { - // modify target to probe depth - mc_get_position(pos); - pos[AXIS_Z] -= plasma_start_params.probe_depth * 0.5; - block.feed = plasma_start_params.probe_feed * 0.5f; // half speed - // similar to G38.4 - if (mc_probe(pos, 1, &block) == STATUS_PROBE_SUCCESS) - { - // modify target to torch start height - mc_get_position(pos); - pos[AXIS_Z] += plasma_start_params.retract_height; - // rapid feed - block.feed = FLT_MAX; - mc_line(pos, &block); - // turn torch on and wait before confirm the arc on signal - block.motion_flags.bit.spindle_running = 1; - block.dwell = plasma_start_params.dwell; - // updated tools and wait - mc_dwell(&block); - - // confirm if arc is ok - if (plasma_thc_arc_ok()) - { - mc_get_position(pos); - pos[AXIS_Z] -= plasma_start_params.cut_depth; - // rapid feed - block.feed = plasma_start_params.cut_feed; - mc_line(pos, &block); - // enable plasma mode - plasma_thc_state = PLASMA_ARC_OK; - // continues program - plasma_starting = false; - cnc_restore_motion(); - return true; - } - } - } - } - - cnc_restore_motion(); - plasma_starting = false; - return false; + static bool plasma_starting = false; + if (plasma_starting) + { + // prevent reentrancy + return false; + } + + plasma_starting = true; + uint8_t ret = plasma_start_params.retries; + cnc_store_motion(); + + // wait for cycle start + while (cnc_get_exec_state(EXEC_HOLD)) + { + cnc_dotasks(); + } + + while (ret--) + { + // cutoff torch + // temporary disable + plasma_thc_state = PLASMA_ARC_OFF; + motion_data_t block = {0}; + block.motion_flags.bit.spindle_running = 0; + mc_update_tools(&block); + + // get current position + float pos[AXIS_COUNT]; + mc_get_position(pos); + + // modify target to probe depth + pos[AXIS_Z] += plasma_start_params.probe_depth; + // probe feed speed + block.feed = plasma_start_params.probe_feed; + // similar to G38.2 + if (mc_probe(pos, 0, &block) == STATUS_PROBE_SUCCESS) + { + // modify target to probe depth + mc_get_position(pos); + pos[AXIS_Z] -= plasma_start_params.probe_depth * 0.5; + block.feed = plasma_start_params.probe_feed * 0.5f; // half speed + // similar to G38.4 + if (mc_probe(pos, 1, &block) == STATUS_PROBE_SUCCESS) + { + // modify target to torch start height + mc_get_position(pos); + pos[AXIS_Z] += plasma_start_params.retract_height; + // rapid feed + block.feed = FLT_MAX; + mc_line(pos, &block); + // turn torch on and wait before confirm the arc on signal + block.motion_flags.bit.spindle_running = 1; + block.dwell = plasma_start_params.dwell; + // updated tools and wait + mc_dwell(&block); + + // confirm if arc is ok + if (plasma_thc_arc_ok()) + { + mc_get_position(pos); + pos[AXIS_Z] -= plasma_start_params.cut_depth; + // rapid feed + block.feed = plasma_start_params.cut_feed; + mc_line(pos, &block); + // enable plasma mode + plasma_thc_state = PLASMA_ARC_OK; + // continues program + plasma_starting = false; + cnc_restore_motion(); + return true; + } + } + } + } + + cnc_restore_motion(); + plasma_starting = false; + return false; } #ifdef ENABLE_RT_SYNC_MOTIONS void itp_rt_stepbits(uint8_t *stepbits, uint8_t *dirs) { - int8_t step_error = plasma_step_error; - - // no error or no steps being performed - if (!step_error || !*stepbits) - { - return; - } - - if (step_error > 0) - { - if (step_error == 1) - { - *stepbits |= PLASMA_STEPPERS_MASK; - *dirs &= ~PLASMA_STEPPERS_MASK; - } - step_error--; - } - - if (step_error < 0) - { - if (step_error == -1) - { - *stepbits |= PLASMA_STEPPERS_MASK; - *dirs |= PLASMA_STEPPERS_MASK; - } - step_error++; - } - - plasma_step_error = step_error; + int8_t step_error = plasma_step_error; + + // no error or no steps being performed + if (!step_error || !*stepbits) + { + return; + } + + if (step_error > 0) + { + if (step_error == 1) + { + *stepbits |= PLASMA_STEPPERS_MASK; + *dirs &= ~PLASMA_STEPPERS_MASK; + } + step_error--; + } + + if (step_error < 0) + { + if (step_error == -1) + { + *stepbits |= PLASMA_STEPPERS_MASK; + *dirs |= PLASMA_STEPPERS_MASK; + } + step_error++; + } + + plasma_step_error = step_error; } #endif @@ -225,53 +227,53 @@ CREATE_EVENT_LISTENER(gcode_exec, m103_exec); // this just parses and acceps the code bool m103_parse(void *args) { - gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; - if (ptr->word == 'M' && ptr->code == 103) - { - if (ptr->cmd->group_extended != 0) - { - // there is a collision of custom gcode commands (only one per line can be processed) - *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; - return EVENT_HANDLED; - } - // tells the gcode validation and execution functions this is custom code M42 (ID must be unique) - ptr->cmd->group_extended = M103; - *(ptr->error) = STATUS_OK; - return EVENT_HANDLED; - } - - // if this is not catched by this parser, just send back the error so other extenders can process it - return EVENT_CONTINUE; + gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; + if (ptr->word == 'M' && ptr->code == 103) + { + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + return EVENT_HANDLED; + } + // tells the gcode validation and execution functions this is custom code M42 (ID must be unique) + ptr->cmd->group_extended = M103; + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + + // if this is not catched by this parser, just send back the error so other extenders can process it + return EVENT_CONTINUE; } // this actually performs 2 steps in 1 (validation and execution) bool m103_exec(void *args) { - gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; - if (ptr->cmd->group_extended == M103) - { - if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) - { - *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; - return EVENT_HANDLED; - } - - plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); - plasma_start_params.probe_depth = ptr->words->ijk[0]; - plasma_start_params.probe_feed = ptr->words->ijk[1]; - plasma_start_params.cut_depth = ptr->words->ijk[2]; - plasma_start_params.retract_height = ptr->words->r; - if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) - { - plasma_start_params.cut_feed = ptr->words->f; - } - plasma_start_params.retries = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; - - *(ptr->error) = STATUS_OK; - return EVENT_HANDLED; - } - - return EVENT_CONTINUE; + gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; + if (ptr->cmd->group_extended == M103) + { + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) + { + *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; + return EVENT_HANDLED; + } + + plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); + plasma_start_params.probe_depth = ptr->words->ijk[0]; + plasma_start_params.probe_feed = ptr->words->ijk[1]; + plasma_start_params.cut_depth = ptr->words->ijk[2]; + plasma_start_params.retract_height = ptr->words->r; + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) + { + plasma_start_params.cut_feed = ptr->words->f; + } + plasma_start_params.retries = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; + + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + + return EVENT_CONTINUE; } #endif @@ -279,70 +281,70 @@ bool m103_exec(void *args) #ifdef ENABLE_MAIN_LOOP_MODULES bool plasma_thc_update_loop(void *ptr) { - if (plasma_thc_state == PLASMA_ARC_OK) - { - // arc lost - // on arc lost the plasma must enter hold - if (!(plasma_thc_arc_ok())) - { - // places the machine under a HOLD and signals the arc lost - // this requires the operator to inspect the work to see if was - // a simple arc lost or the torch is hover a hole - plasma_thc_state = PLASMA_ARC_LOST; - cnc_set_exec_state(EXEC_HOLD); - - // prepares the reprobing action to be executed on cycle resume action - if (plasma_thc_probe_and_start()) - { - } - else - { - // must restore the planner and motion to be purged - mc_restore(); - planner_restore(); - cnc_alarm(EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE); - } - } - - if (plasma_thc_up() && !plasma_step_error) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits &= 0xFB; - - // option 2 - mask the step bits directly - // clamp tool max step rate according to the actual motion feed - float feed = itp_get_rt_feed(); - float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); - plasma_step_error = 1 + (uint8_t)max_feed_ratio; - } - else if (plasma_thc_down() && !plasma_step_error) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits |= 4; - - // option 2 - mask the step bits directly - float feed = itp_get_rt_feed(); - float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); - plasma_step_error = -(1 + (uint8_t)max_feed_ratio); - } - else - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = 0; - - // option 2 - mask the step bits directly - plasma_step_error = 0; - } - } - return EVENT_CONTINUE; + if (plasma_thc_state == PLASMA_ARC_OK) + { + // arc lost + // on arc lost the plasma must enter hold + if (!(plasma_thc_arc_ok())) + { + // places the machine under a HOLD and signals the arc lost + // this requires the operator to inspect the work to see if was + // a simple arc lost or the torch is hover a hole + plasma_thc_state = PLASMA_ARC_LOST; + cnc_set_exec_state(EXEC_HOLD); + + // prepares the reprobing action to be executed on cycle resume action + if (plasma_thc_probe_and_start()) + { + } + else + { + // must restore the planner and motion to be purged + mc_restore(); + planner_restore(); + cnc_alarm(EXEC_ALARM_PLASMA_THC_ARC_START_FAILURE); + } + } + + if (plasma_thc_up() && !plasma_step_error) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits &= 0xFB; + + // option 2 - mask the step bits directly + // clamp tool max step rate according to the actual motion feed + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = 1 + (uint8_t)max_feed_ratio; + } + else if (plasma_thc_down() && !plasma_step_error) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits |= 4; + + // option 2 - mask the step bits directly + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = -(1 + (uint8_t)max_feed_ratio); + } + else + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = 0; + + // option 2 - mask the step bits directly + plasma_step_error = 0; + } + } + return EVENT_CONTINUE; } CREATE_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); @@ -351,13 +353,13 @@ CREATE_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); DECL_MODULE(plasma_thc) { #ifdef ENABLE_MAIN_LOOP_MODULES - ADD_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); + ADD_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); #else #error "Main loop extensions are not enabled. TMC configurations will not work." #endif #ifdef ENABLE_PARSER_MODULES - ADD_EVENT_LISTENER(gcode_parse, m103_parse); - ADD_EVENT_LISTENER(gcode_exec, m103_exec); + ADD_EVENT_LISTENER(gcode_parse, m103_parse); + ADD_EVENT_LISTENER(gcode_exec, m103_exec); #else #error "Parser extensions are not enabled. M103 code extension will not work." #endif @@ -367,7 +369,7 @@ static void startup_code(void) { // force plasma off #if ASSERT_PIN(PLASMA_ON_OUTPUT) - mcu_clear_output(PLASMA_ON_OUTPUT); + io_clear_output(PLASMA_ON_OUTPUT); #endif } @@ -375,71 +377,73 @@ static void shutdown_code(void) { // force plasma off #if ASSERT_PIN(PLASMA_ON_OUTPUT) - mcu_clear_output(PLASMA_ON_OUTPUT); + io_clear_output(PLASMA_ON_OUTPUT); #endif } static void set_speed(int16_t value) { - // turn plasma on - if (value) - { - // enable plasma mode - plasma_thc_state = true; - if (!plasma_thc_arc_ok()) - { - if (plasma_thc_probe_and_start()) - { - cnc_clear_exec_state(EXEC_HOLD); + // turn plasma on + if (value) + { + // enable plasma mode + plasma_thc_state = true; + if (!plasma_thc_arc_ok()) + { + if (plasma_thc_probe_and_start()) + { + cnc_clear_exec_state(EXEC_HOLD); #if ASSERT_PIN(PLASMA_ON_OUTPUT) - mcu_set_output(PLASMA_ON_OUTPUT); + io_set_output(PLASMA_ON_OUTPUT); #endif - } - } - } - else - { - // disable plasma THC mode - plasma_thc_state = false; + } + } + } + else + { + // disable plasma THC mode + plasma_thc_state = false; #if ASSERT_PIN(PLASMA_ON_OUTPUT) - mcu_clear_output(PLASMA_ON_OUTPUT); + io_clear_output(PLASMA_ON_OUTPUT); #endif - mc_sync_position(); - } + mc_sync_position(); + } } static int16_t range_speed(int16_t value) { - // binary output - value = value ? 1 : 0; - return value; + // binary output + value = value ? 1 : 0; + return value; } static void set_coolant(uint8_t value) { // easy macro #ifdef ENABLE_COOLANT - SET_COOLANT(LASER_PWM_AIR_ASSIST, UNDEF_PIN, value); + SET_COOLANT(LASER_PWM_AIR_ASSIST, UNDEF_PIN, value); #endif } static uint16_t get_speed(void) { #if ASSERT_PIN(PLASMA_ON_OUTPUT) - return mcu_get_output(PLASMA_ON_OUTPUT); + return io_get_output(PLASMA_ON_OUTPUT); #else - return 0; + return 0; #endif } const tool_t plasma_thc = { - .startup_code = &startup_code, - .shutdown_code = &shutdown_code, + .startup_code = &startup_code, + .shutdown_code = &shutdown_code, #if PID_CONTROLLERS > 0 - .pid_update = NULL, - .pid_error = NULL, + .pid_update = NULL, + .pid_error = NULL, #endif - .range_speed = &range_speed, - .get_speed = &get_speed, - .set_speed = &set_speed, - .set_coolant = &set_coolant}; + .range_speed = &range_speed, + .get_speed = &get_speed, + .set_speed = &set_speed, + .set_coolant = &set_coolant}; + +#endif \ No newline at end of file From eac22c9f530bf85d4d1967e9ae0d717e77e19483 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 18 Jul 2023 11:34:11 +0100 Subject: [PATCH 021/168] new PID module and updated tools - new PID module more flexible - updated tools functions --- uCNC/cnc_hal_config.h | 59 +---- uCNC/src/cnc.c | 13 +- uCNC/src/cnc_hal_config_helper.h | 160 +------------ uCNC/src/core/io_control.c | 4 - uCNC/src/hal/boards/stm32/stm32.ini | 2 +- uCNC/src/hal/tools/tool.c | 31 ++- uCNC/src/hal/tools/tool.h | 9 +- uCNC/src/hal/tools/tools/laser_ppi.c | 3 +- uCNC/src/hal/tools/tools/laser_pwm.c | 3 +- uCNC/src/hal/tools/tools/pen_servo.c | 19 +- uCNC/src/hal/tools/tools/plasma_thc.c | 14 +- uCNC/src/hal/tools/tools/spindle_besc.c | 10 +- uCNC/src/hal/tools/tools/spindle_pwm.c | 59 +++-- uCNC/src/hal/tools/tools/spindle_relay.c | 12 +- uCNC/src/hal/tools/tools/vfd_modbus.c | 3 +- uCNC/src/hal/tools/tools/vfd_pwm.c | 62 ++--- uCNC/src/interface/protocol.c | 11 +- uCNC/src/interface/protocol.h | 1 + uCNC/src/interface/settings.c | 40 +--- uCNC/src/interface/settings.h | 83 ++++++- uCNC/src/module.c | 4 - uCNC/src/modules/pid.c | 284 +++-------------------- uCNC/src/modules/pid.h | 20 +- 23 files changed, 245 insertions(+), 661 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index eba55e8f4..29953ade4 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -213,6 +213,14 @@ extern "C" // depends on encoders (below) // #define SPINDLE_BESC_HAS_RPM_ENCODER +/** + * Uncomment to enable PID controller for tools + * Each tool has it's own PID controller and EEPROM settings + * Chech the tool file to find the settings for each tool + * + * **/ +// #define ENABLE_TOOL_PID_CONTROLLER + // Assigns an output to an blinking led (1Hz rate) #define ACTIVITY_LED DOUT31 @@ -278,57 +286,6 @@ extern "C" #endif #endif -/* - Sets the number of PID controllers to be used -*/ -#define PID_CONTROLLERS 0 - -#if PID_CONTROLLERS > 0 -#include "src/modules/pid.h" - - /** - * To use PID you need to set the number o PID controllers. - * PID0 is hardwired to run the tool PID (defined or not). That being said if you need a PID for any other purpose other than the tool the number of PID controllers - * to be enabled must be greater then 1. - * - * µCNC will run each PID in a timed slot inside the rtc timer scheduler like this. - * Let's say you have enabled 3 PID controllers. At each RTC call of the scheduller it will run the current PID controller in a ring loop - * - * |--RTC+0--|--RTC+1--|--RTC+2--|--RTC+3--|--RTC+4--|--RTC+5--|--RTC+6--|..etc.. - * |--PID 0--|--PID 1--|--PID 2--|--PID 0--|--PID 1--|--PID 2--|--PID 0--|..etc.. - * - * REMEMBER PID0 is hardwired to the tool PID. If the tool PID is not defined for the current tool it will simply do nothing. - * - * - * To use the PID controller 3 definitions are needed - * PIDx_DELTA() -> sets the function that gets the error between the setpoint and the current value for x PID controller - * PIDx_OUTPUT(X) -> sets the output after calculating the pid corrected value for x PID controller - * PIDx_STOP() -> runs this function on any halt or emergency stop of the machine - * - * For example - * - * #define PID1_DELTA() (my_setpoint - io_get_analog(ANA0)) - * #define PID1_OUTPUT(X) (io_set_pwm(PWM0, X)) - * #define PID1_STOP() (io_set_pwm(PWM0, 0)) - * - * An optional configuration is the sampling rate of the PID update. By default the sampling rate is 125Hz. - * To reduce the sampling rate a 125/PIDx_FREQ_DIV can be defined between 1 (125Hz) and 250 (0.5Hz) - * - * You can but you should not define PID for tools. Tools have a dedicated PID that can be customized for each tool. Check the tool HAL for this. - * - * */ - // here is an example on how to add an PID controller to the spindle - // this exemple assumes that the spindle speed is feedback via an analog pin - // reference to io_get_spindle defined in io_control - // extern uint8_t io_get_spindle(void); - // #define SPINDLE_SPEED ANALOG0 - // #define PID1_DELTA() (io_get_spindle() - io_get_analog(SPINDLE_SPEED)) - // #define PID1_OUTPUT(X) (io_set_pwm(SPINDLE_PWM, X)) - // #define PID1_STOP() (io_set_pwm(PWM0, 0)) - // //optional - // #define PID1_FREQ_DIV 50 -#endif - /** * * Software emulated communication interfaces diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 85c0eacb7..f8c6fd7ab 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -236,6 +236,11 @@ bool cnc_dotasks(void) return !cnc_get_exec_state(EXEC_INTERLOCKING_FAIL); } +#ifdef ENABLE_TOOL_PID_CONTROLLER + // run the tool pid update + tool_pid_update(); +#endif + if (!lock_itp) { lock_itp = true; @@ -252,7 +257,7 @@ bool cnc_dotasks(void) void cnc_store_motion(void) { - #ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING // set hold and wait for motion to stop uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); @@ -277,12 +282,12 @@ void cnc_store_motion(void) } lock_itp = false; - #endif +#endif } void cnc_restore_motion(void) { - #ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING +#ifdef ENABLE_MOTION_CONTROL_PLANNER_HIJACKING // set hold and wait for motion to stop uint8_t prevholdstate = cnc_get_exec_state(EXEC_HOLD); cnc_set_exec_state(EXEC_HOLD); @@ -310,7 +315,7 @@ void cnc_restore_motion(void) cnc_clear_exec_state(EXEC_HOLD); } lock_itp = false; - #endif +#endif } // this function is executed every millisecond diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index a8ad7fe17..fe77bf98f 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -314,160 +314,6 @@ extern "C" #define STEPPERS_ENCODERS_MASK 0 #endif -#ifndef PID_CONTROLLERS -#define PID_CONTROLLERS 0 -#endif - -#if PID_CONTROLLERS > 0 - /*PID controllers*/ -#if PID_CONTROLLERS == 1 -#define PID_DIVISIONS 0 -#elif PID_CONTROLLERS == 2 -#define PID_DIVISIONS 1 -#elif PID_CONTROLLERS <= 4 -#define PID_DIVISIONS 2 -#else -#define PID_DIVISIONS 3 -#endif - -#define PID_SAMP_FREQ (1 << (10 - PID_DIVISIONS)) -#endif - -#if PID_CONTROLLERS > 0 -#ifdef PID0_DELTA -#error "The PID0 is reserved for the tool PID" -#else -#define PID0_DELTA() tool_pid_error() -#endif -#ifdef PID0_OUTPUT -#error "The PID0 is reserved for the tool PID" -#else -#define PID0_OUTPUT(X) tool_pid_update(X) -#endif -#ifdef PID0_STOP -#error "The PID0 is reserved for the tool PID" -#else -#define PID0_STOP() tool_stop() -#endif -#ifndef PID0_FREQ_DIV -#define PID0_FREQ_DIV 1 -#elif (PID0_FREQ_DIV < 1 || PID0_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID0 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 1 -#ifndef PID1_DELTA -#error "The PID1 error is not defined" -#endif -#ifndef PID1_OUTPUT -#error "The PID1 output is not defined" -#endif -#ifndef PID1_STOP -#error "The PID1 stop is not defined" -#endif -#ifndef PID1_FREQ_DIV -#define PID1_FREQ_DIV 1 -#elif (PID1_FREQ_DIV < 1 || PID1_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID1 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 2 -#ifndef PID2_DELTA -#error "The PID2 error is not defined" -#endif -#ifndef PID2_OUTPUT -#error "The PID2 output is not defined" -#endif -#ifndef PID2_STOP -#error "The PID2 stop is not defined" -#endif -#ifndef PID2_FREQ_DIV -#define PID2_FREQ_DIV 1 -#elif (PID2_FREQ_DIV < 1 || PID2_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID2 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 3 -#ifndef PID3_DELTA -#error "The PID3 error is not defined" -#endif -#ifndef PID3_OUTPUT -#error "The PID3 output is not defined" -#endif -#ifndef PID3_STOP -#error "The PID3 stop is not defined" -#endif -#ifndef PID3_FREQ_DIV -#define PID3_FREQ_DIV 1 -#elif (PID3_FREQ_DIV < 1 || PID3_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID3 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 4 -#ifndef PID4_DELTA -#error "The PID4 error is not defined" -#endif -#ifndef PID4_OUTPUT -#error "The PID4 output is not defined" -#endif -#ifndef PID4_STOP -#error "The PID4 stop is not defined" -#endif -#ifndef PID4_FREQ_DIV -#define PID4_FREQ_DIV 1 -#elif (PID4_FREQ_DIV < 1 || PID4_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID4 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 5 -#ifndef PID5_DELTA -#error "The PID5 error is not defined" -#endif -#ifndef PID5_OUTPUT -#error "The PID5 output is not defined" -#endif -#ifndef PID5_STOP -#error "The PID5 stop is not defined" -#endif -#ifndef PID5_FREQ_DIV -#define PID5_FREQ_DIV 1 -#elif (PID5_FREQ_DIV < 1 || PID5_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID5 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 6 -#ifndef PID6_DELTA -#error "The PID6 error is not defined" -#endif -#ifndef PID6_OUTPUT -#error "The PID6 output is not defined" -#endif -#ifndef PID6_STOP -#error "The PID6 stop is not defined" -#endif -#ifndef PID6_FREQ_DIV -#define PID6_FREQ_DIV 1 -#elif (PID6_FREQ_DIV < 1 || PID6_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID6 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif -#if PID_CONTROLLERS > 7 -#ifndef PID7_DELTA -#error "The PID7 error is not defined" -#endif -#ifndef PID7_OUTPUT -#error "The PID7 output is not defined" -#endif -#ifndef PID7_STOP -#error "The PID7 stop is not defined" -#endif -#ifndef PID7_FREQ_DIV -#define PID7_FREQ_DIV 1 -#elif (PID7_FREQ_DIV < 1 || PID7_FREQ_DIV > PID_SAMP_FREQ) -#error "The PID7 sampling frequency devider value must be between 1 and MAX SAMPLE RATE = 1000/log2(Total PID's)" -#endif -#endif - #ifdef STEPPER0_HAS_TMC #if (STEPPER0_TMC_INTERFACE == TMC_UART) // if driver uses uart set pins @@ -2292,6 +2138,12 @@ typedef uint16_t step_t; #endif +#ifdef ENABLE_TOOL_PID_CONTROLLER +#ifndef ENABLE_SETTINGS_MODULES +#define ENABLE_SETTINGS_MODULES +#endif +#endif + #ifdef __cplusplus } #endif diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 3c06a25b2..17b786802 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -20,10 +20,6 @@ #include "../cnc.h" -#if PID_CONTROLLERS > 0 -static volatile uint8_t io_spindle_speed; -#endif - static uint8_t io_lock_limits_mask; static uint8_t io_invert_limits_mask; diff --git a/uCNC/src/hal/boards/stm32/stm32.ini b/uCNC/src/hal/boards/stm32/stm32.ini index aa5691a5a..0ee7cea08 100644 --- a/uCNC/src/hal/boards/stm32/stm32.ini +++ b/uCNC/src/hal/boards/stm32/stm32.ini @@ -5,7 +5,7 @@ [common_stm32] platform = ststm32 ; debug with st-link -upload_protocol = cmsis-dap +upload_protocol = dfu debug_tool = cmsis-dap platform_packages = platformio/tool-openocd debug_build_flags = -Og -g3 -ggdb3 -gdwarf-2 diff --git a/uCNC/src/hal/tools/tool.c b/uCNC/src/hal/tools/tool.c index 03db596b8..3bfbf0d74 100644 --- a/uCNC/src/hal/tools/tool.c +++ b/uCNC/src/hal/tools/tool.c @@ -25,6 +25,7 @@ #define DECL_TOOL(tool) extern const tool_t tool static tool_t tool_current; +static int16_t tool_current_speed; #ifdef TOOL1 DECL_TOOL(TOOL1); @@ -191,6 +192,7 @@ void tool_change(uint8_t tool) void tool_set_speed(int16_t value) { #if TOOL_COUNT > 0 + tool_current_speed = value; if (tool_current.set_speed) { tool_current.set_speed(value); @@ -205,6 +207,16 @@ uint16_t tool_get_speed() { return tool_current.get_speed(); } + return tool_current_speed; +#endif + return 0; +} + +int16_t tool_get_setpoint(void) +{ + // input value will always be positive +#if TOOL_COUNT > 0 + return tool_current_speed; #endif return 0; } @@ -240,27 +252,14 @@ void tool_stop() #endif } -void tool_pid_update(int16_t value) +void tool_pid_update(void) { -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER #if TOOL_COUNT > 0 if (tool_current.pid_update) { - tool_current.pid_update(value); - } -#endif -#endif -} - -int16_t tool_pid_error(void) -{ -#if PID_CONTROLLERS > 0 -#if TOOL_COUNT > 0 - if (tool_current.pid_error) - { - return tool_current.pid_error(); + tool_current.pid_update(); } #endif #endif - return 0; } diff --git a/uCNC/src/hal/tools/tool.h b/uCNC/src/hal/tools/tool.h index 7f6f4613e..e747e551f 100644 --- a/uCNC/src/hal/tools/tool.h +++ b/uCNC/src/hal/tools/tool.h @@ -31,8 +31,6 @@ extern "C" #include typedef void (*tool_func)(void); - typedef int16_t (*tool_pid_err_func)(void); - typedef void (*tool_pid_upd_func)(int16_t); typedef int16_t (*tool_range_speed_func)(int16_t); typedef uint16_t (*tool_get_speed_func)(void); typedef void (*tool_set_speed_func)(int16_t); @@ -42,8 +40,7 @@ extern "C" { tool_func startup_code; /*runs any custom code after the tool is loaded*/ tool_func shutdown_code; /*runs any custom code before the tool is unloaded*/ - tool_pid_upd_func pid_update; /*runs de PID update code needed to keep the tool at the desired speed/power*/ - tool_pid_err_func pid_error; /*runs de PID update code needed to keep the tool at the desired speed/power*/ + tool_func pid_update; /*runs de PID update code needed to keep the tool at the desired speed/power*/ tool_range_speed_func range_speed; /*converts core speed to tool speed*/ tool_get_speed_func get_speed; /*gets the tool speed/power (converts from tool speed to core speed)*/ tool_set_speed_func set_speed; /*sets the speed/power of the tool*/ @@ -52,8 +49,8 @@ extern "C" void tool_init(void); void tool_change(uint8_t tool); - void tool_pid_update(int16_t value); - int16_t tool_pid_error(void); + void tool_pid_update(void); + int16_t tool_get_setpoint(void); int16_t tool_range_speed(int16_t value); uint16_t tool_get_speed(void); void tool_set_speed(int16_t value); diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 06bc35b7c..2b628298a 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -89,9 +89,8 @@ static uint16_t get_speed(void) const tool_t laser_ppi = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = NULL, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/laser_pwm.c b/uCNC/src/hal/tools/tools/laser_pwm.c index e0757ea12..f89674928 100644 --- a/uCNC/src/hal/tools/tools/laser_pwm.c +++ b/uCNC/src/hal/tools/tools/laser_pwm.c @@ -111,9 +111,8 @@ static uint16_t get_speed(void) const tool_t laser_pwm = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = &range_speed, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/pen_servo.c b/uCNC/src/hal/tools/tools/pen_servo.c index c98dc2de1..6b0af8a3d 100644 --- a/uCNC/src/hal/tools/tools/pen_servo.c +++ b/uCNC/src/hal/tools/tools/pen_servo.c @@ -39,8 +39,6 @@ #endif #define PEN_SERVO_RANGE (ABS((PEN_SERVO_HIGH - PEN_SERVO_LOW))) -static uint8_t speed; - static void startup_code(void) { #if ASSERT_PIN(PEN_SERVO) @@ -80,28 +78,15 @@ static void set_speed(int16_t value) io_set_pwm(PEN_SERVO, (uint8_t)value); #endif } - - speed = (value <= 0) ? 0 : value; -} - -static uint16_t get_speed(void) -{ -#if ASSERT_PIN(PEN_SERVO) - float spindle = (float)speed * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)lroundf(spindle); -#else - return 0; -#endif } const tool_t pen_servo = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = &range_speed, - .get_speed = &get_speed, + .get_speed = NULL, .set_speed = &set_speed, .set_coolant = NULL}; diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 525e8a40a..4213a5ef6 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -425,24 +425,14 @@ static void set_coolant(uint8_t value) #endif } -static uint16_t get_speed(void) -{ -#if ASSERT_PIN(PLASMA_ON_OUTPUT) - return io_get_output(PLASMA_ON_OUTPUT); -#else - return 0; -#endif -} - const tool_t plasma_thc = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = &range_speed, - .get_speed = &get_speed, + .get_speed = NULL, .set_speed = &set_speed, .set_coolant = &set_coolant}; diff --git a/uCNC/src/hal/tools/tools/spindle_besc.c b/uCNC/src/hal/tools/tools/spindle_besc.c index 6c5c58154..c4aca1876 100644 --- a/uCNC/src/hal/tools/tools/spindle_besc.c +++ b/uCNC/src/hal/tools/tools/spindle_besc.c @@ -58,8 +58,6 @@ #endif #endif -static uint8_t speed; - static void startup_code(void) { // do whatever routine you need to do here to arm the ESC @@ -109,8 +107,6 @@ static void set_speed(int16_t value) io_set_pwm(SPINDLE_BESC_SERVO, (uint8_t)value); #endif } - - speed = (value <= 0) ? 0 : value; } static void set_coolant(uint8_t value) @@ -126,8 +122,7 @@ static uint16_t get_speed(void) return encoder_get_rpm(); #else #if ASSERT_PIN(SPINDLE_BESC_SERVO) - float spindle = (float)speed * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)lroundf(spindle); + return tool_get_setpoint(); #else return 0; #endif @@ -137,9 +132,8 @@ static uint16_t get_speed(void) const tool_t spindle_besc = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = &range_speed, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 5258a17d8..54769796b 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -50,21 +50,37 @@ #endif #endif -static uint8_t speed; +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) +#ifndef SPINDLE_PWM_PID_SAMPLE_RATE_HZ +#define SPINDLE_PWM_PID_SAMPLE_RATE_HZ 125 +#endif +#define SPINDLE_PWM_PID_SETTING_ID 300 +#include +#include "../../../modules/pid.h" +static pid_data_t spindle_pwm_pid; +DECL_EXTENDED_SETTING(SPINDLE_PWM_PID_SETTING_ID, spindle_pwm_pid.k, float, 3, protocol_send_gcode_setting_line_flt); +#endif -static void startup_code(void) +static void +startup_code(void) { // force pwm mode #if ASSERT_PIN(SPINDLE_PWM) io_config_pwm(SPINDLE_PWM, 1000); #endif + +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) + EXTENDED_SETTING_INIT(SPINDLE_PWM_PID_SETTING_ID, spindle_pwm_pid.k); + settings_load(EXTENDED_SETTING_ADDRESS(SPINDLE_PWM_PID_SETTING_ID), (uint8_t *)spindle_pwm_pid.k, sizeof(spindle_pwm_pid.k)); + spindle_pwm_pid.max = g_settings.spindle_max_rpm; + spindle_pwm_pid.min = g_settings.spindle_min_rpm; +#endif } static void set_speed(int16_t value) { // easy macro to execute the same code as below // SET_SPINDLE(SPINDLE_PWM, SPINDLE_PWM_DIR, value, invert); - speed = (uint8_t)ABS(value); // speed optimized version (in AVR it's 24 instruction cycles) #if ASSERT_PIN(SPINDLE_PWM_DIR) if ((value <= 0)) @@ -104,45 +120,38 @@ static uint16_t get_speed(void) return encoder_get_rpm(); #else #if ASSERT_PIN(SPINDLE_PWM) - float spindle = (float)speed * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)lroundf(spindle); + return tool_get_setpoint(); #else return 0; #endif #endif } -#if PID_CONTROLLERS > 0 -static void pid_update(int16_t value) +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) +static void pid_update(void) { - if (speed != 0) + float output = tool_get_setpoint(); + + if (output != 0) { - uint8_t newval = CLAMP(0, io_get_pwm(SPINDLE_PWM) + value, 255); -#if ASSERT_PIN(SPINDLE_PWM) - io_set_pwm(SPINDLE_PWM, newval); -#else - io_set_pwm(SPINDLE_PWM, newval); -#endif + if (pid_compute(&spindle_pwm_pid, &output, output, get_speed(), HZ_TO_MS(SPINDLE_PWM_PID_SAMPLE_RATE_HZ))) + { + io_set_pwm(SPINDLE_PWM, range_speed((int16_t)output)); + } } } -static int16_t pid_error(void) -{ -#if (ASSERT_PIN(SPINDLE_FEEDBACK) && ASSERT_PIN(SPINDLE_PWM)) - uint8_t reader = io_get_analog(ANALOG0); - return (speed - reader); -#else - return 0; -#endif -} #endif const tool_t spindle_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER +#ifndef DISABLE_SPINDLE_PWM_PID .pid_update = &pid_update, - .pid_error = &pid_error, +#else + .pid_update = NULL, +#endif #endif .range_speed = &range_speed, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/spindle_relay.c b/uCNC/src/hal/tools/tools/spindle_relay.c index f88f623a3..92ca76fac 100644 --- a/uCNC/src/hal/tools/tools/spindle_relay.c +++ b/uCNC/src/hal/tools/tools/spindle_relay.c @@ -42,8 +42,6 @@ #endif #endif -static int16_t spindle_speed; - void set_speed(int16_t value) { @@ -83,19 +81,13 @@ void set_coolant(uint8_t value) #endif } -uint16_t get_speed(void) -{ - return ABS(spindle_speed); -} - const tool_t spindle_relay = { .startup_code = NULL, .shutdown_code = NULL, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = NULL, - .get_speed = &get_speed, + .get_speed = NULL, .set_speed = &set_speed, .set_coolant = &set_coolant}; diff --git a/uCNC/src/hal/tools/tools/vfd_modbus.c b/uCNC/src/hal/tools/tools/vfd_modbus.c index a144a515e..543b0c2f8 100644 --- a/uCNC/src/hal/tools/tools/vfd_modbus.c +++ b/uCNC/src/hal/tools/tools/vfd_modbus.c @@ -467,9 +467,8 @@ static uint16_t get_speed(void) const tool_t vfd_modbus = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, - .pid_error = NULL, #endif .range_speed = NULL, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index 9ab92f569..28c5f1fea 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -48,6 +48,16 @@ #define VFD_PWM_ANALOG_FEEDBACK ANALOG0 #endif +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) +#ifndef VFD_PWM_PID_SAMPLE_RATE_HZ +#define VFD_PWM_PID_SAMPLE_RATE_HZ 125 +#endif +#define VFD_PWM_PID_SETTING_ID 304 +#include "../../../modules/pid.h" +static pid_data_t vfd_pwm_pid; +DECL_EXTENDED_SETTING(VFD_PWM_PID_SETTING_ID, vfd_pwm_pid.k, float, 3, protocol_send_gcode_setting_line_flt); +#endif + static uint8_t speed; static void startup_code(void) @@ -56,6 +66,13 @@ static void startup_code(void) #if ASSERT_PIN(VFD_PWM) io_config_pwm(VFD_PWM, 1000); #endif + +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) + EXTENDED_SETTING_INIT(VFD_PWM_PID_SETTING_ID, vfd_pwm_pid.k); + settings_load(EXTENDED_SETTING_ADDRESS(VFD_PWM_PID_SETTING_ID), (uint8_t*)vfd_pwm_pid.k, sizeof(vfd_pwm_pid.k)); + vfd_pwm_pid.max = g_settings.spindle_max_rpm; + vfd_pwm_pid.min = g_settings.spindle_min_rpm; +#endif } static void set_speed(int16_t value) @@ -96,49 +113,32 @@ static int16_t range_speed(int16_t value) return value; } -static uint16_t get_speed(void) +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) +static void pid_update(void) { -#if ASSERT_PIN(VFD_PWM_ANALOG_FEEDBACK) - float spindle = (float)io_get_analog(VFD_PWM_ANALOG_FEEDBACK) * g_settings.spindle_max_rpm * UINT8_MAX_INV; - return (uint16_t)lroundf(spindle); -#else - return 0; -#endif -} + float output = tool_get_setpoint(); -#if PID_CONTROLLERS > 0 -static void pid_update(int16_t value) -{ - if (speed != 0) + if (output != 0) { - uint8_t newval = CLAMP(0, io_get_pwm(VFD_PWM) + value, 255); -#if ASSERT_PIN(VFD_PWM) - io_set_pwm(VFD_PWM, newval); -#else - io_set_pwm(VFD_PWM, newval); -#endif + if (pid_compute(&vfd_pwm_pid, &output, output, get_speed(), HZ_TO_MS(VFD_PWM_PID_SAMPLE_RATE_HZ))) + { + io_set_pwm(VFD_PWM, range_speed((int16_t)output)); + } } } - -static int16_t pid_error(void) -{ -#if (ASSERT_PIN(VFD_PWM_ANALOG_FEEDBACK) && ASSERT_PIN(VFD_PWM)) - uint8_t reader = io_get_analog(VFD_PWM_ANALOG_FEEDBACK); - return (speed - reader); -#else - return 0; -#endif -} #endif const tool_t vfd_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#if PID_CONTROLLERS > 0 +#ifdef ENABLE_TOOL_PID_CONTROLLER +#ifndef DISABLE_SPINDLE_PWM_PID .pid_update = &pid_update, - .pid_error = &pid_error, +#else + .pid_update = NULL, +#endif #endif .range_speed = &range_speed, - .get_speed = &get_speed, + .get_speed = NULL, .set_speed = &set_speed, .set_coolant = &set_coolant}; diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 4ead8452e..fe6cfe9a4 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -534,7 +534,7 @@ void protocol_send_gcode_setting_line_int(setting_offset_t setting, uint16_t val protocol_send_newline(); } -static void protocol_send_gcode_setting_line_flt(uint8_t setting, float value) +void protocol_send_gcode_setting_line_flt(setting_offset_t setting, float value) { serial_putc('$'); serial_print_int(setting); @@ -633,15 +633,6 @@ void protocol_send_cnc_settings(void) #endif #endif -#if PID_CONTROLLERS > 0 - for (uint8_t i = 0; i < PID_CONTROLLERS; i++) - { - protocol_send_gcode_setting_line_flt(40 + 4 * i, g_settings.pid_gain[i][0]); - protocol_send_gcode_setting_line_flt(41 + 4 * i, g_settings.pid_gain[i][1]); - protocol_send_gcode_setting_line_flt(42 + 4 * i, g_settings.pid_gain[i][2]); - } -#endif - #if TOOL_COUNT > 0 protocol_send_gcode_setting_line_int(80, g_settings.default_tool); for (uint8_t i = 0; i < TOOL_COUNT; i++) diff --git a/uCNC/src/interface/protocol.h b/uCNC/src/interface/protocol.h index f5a2b98eb..dc978976b 100644 --- a/uCNC/src/interface/protocol.h +++ b/uCNC/src/interface/protocol.h @@ -40,6 +40,7 @@ extern "C" void protocol_send_cnc_settings(void); void protocol_send_start_blocks(void); void protocol_send_gcode_setting_line_int(setting_offset_t setting, uint16_t value); + void protocol_send_gcode_setting_line_flt(setting_offset_t setting, float value); #ifdef ENABLE_WIFI void protocol_send_ip(uint32_t ip); #endif diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index 14f297c88..b41a61145 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -148,30 +148,6 @@ const settings_t __rom__ default_settings = .encoders_pulse_invert_mask = 0, .encoders_dir_invert_mask = 0, #endif -#if PID_CONTROLLERS > 0 - .pid_gain[0] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 1 - .pid_gain[1] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 2 - .pid_gain[2] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 3 - .pid_gain[3] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 4 - .pid_gain[4] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 5 - .pid_gain[5] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 6 - .pid_gain[6] = DEFAULT_ARRAY(3, 0), -#endif -#if PID_CONTROLLERS > 7 - .pid_gain[7] = DEFAULT_ARRAY(3, 0), -#endif }; #ifdef ENABLE_SETTINGS_MODULES @@ -518,21 +494,7 @@ uint8_t settings_change(setting_offset_t id, float value) g_settings.backlash_steps[setting] = value16; } #endif -#if PID_CONTROLLERS > 0 - // kp ki and kd 0 -> 41, 42, 43 - // kp ki and kd 1 -> 45, 46, 47, etc... - else if (setting >= 40 && setting < (40 + (4 * PID_CONTROLLERS))) - { - uint8_t k = (setting & 0x03); - uint8_t pid = (setting >> 2) - 10; - // 3 is invalid index - if (k == 0x03) - { - return STATUS_INVALID_STATEMENT; - } - g_settings.pid_gain[pid][k] = value; - } -#endif + #if TOOL_COUNT > 0 else if (setting > 80 && setting <= (80 + TOOL_COUNT)) { diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index 952bf3ac8..222cb43ab 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -96,9 +96,6 @@ extern "C" #if ENCODERS > 0 uint8_t encoders_pulse_invert_mask; uint8_t encoders_dir_invert_mask; -#endif -#if PID_CONTROLLERS > 0 - float pid_gain[PID_CONTROLLERS][3]; #endif } settings_t; @@ -136,7 +133,7 @@ typedef uint16_t setting_offset_t; bool settings_check_startup_gcode(uint16_t address); void settings_save_startup_gcode(uint16_t address); uint16_t settings_register_external_setting(uint8_t size); - + #if (defined(ENABLE_SETTINGS_MODULES) || defined(BOARD_HAS_CUSTOM_SYSTEM_COMMANDS)) // event_settings_change_handler typedef struct setting_args_ @@ -159,6 +156,84 @@ typedef uint16_t setting_offset_t; DECL_EVENT_HANDLER(settings_erase); #endif + /** + * + * Settings quick/help macros + * These allow custom settings setup of simple settings + * + * **/ +#define DECL_EXTENDED_SETTING(ID, var, type, count, print_cb) \ + static uint32_t set##ID##_settings_address; \ + bool set##ID##_settings_load(void *args) \ + { \ + settings_args_t *set = (settings_args_t *)args; \ + if (set->address == SETTINGS_ADDRESS_OFFSET || set->address == set##ID##_settings_address) \ + { \ + settings_load(set##ID##_settings_address, (uint8_t *)var, sizeof(type) * count); \ + return EVENT_CONTINUE; \ + } \ + return EVENT_HANDLED; \ + } \ + bool set##ID##_settings_save(void *args) \ + { \ + settings_args_t *set = (settings_args_t *)args; \ + if (set->address == SETTINGS_ADDRESS_OFFSET || set->address == set##ID##_settings_address) \ + { \ + settings_save(set##ID##_settings_address, (uint8_t *)var, sizeof(type) * count); \ + return EVENT_HANDLED; \ + } \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_settings_change(void *args) \ + { \ + setting_args_t *set = (setting_args_t *)args; \ + type *ptr = var; \ + if (set->id >= ID && set->id <= (ID + count)) \ + { \ + ptr[set->id - ID] = (type)set->value; \ + return EVENT_HANDLED; \ + } \ + return EVENT_CONTINUE; \ + } \ + bool set##ID##_settings_erase(void *args) \ + { \ + settings_args_t *set = (settings_args_t *)args; \ + if (set->address == SETTINGS_ADDRESS_OFFSET || set->address == set##ID##_settings_address) \ + { \ + memset(var, 0, sizeof(type) * count); \ + } \ + return EVENT_HANDLED; \ + } \ + bool set##ID##_protocol_send_cnc_settings(void *args) \ + { \ + type *ptr = var; \ + for (uint8_t i = 0; i < count; i++) \ + { \ + print_cb(ID + i, ptr[i]); \ + } \ + return EVENT_CONTINUE; \ + } \ + CREATE_EVENT_LISTENER(settings_load, set##ID##_settings_load); \ + CREATE_EVENT_LISTENER(settings_save, set##ID##_settings_save); \ + CREATE_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ + CREATE_EVENT_LISTENER(settings_erase, set##ID##_settings_erase); \ + CREATE_EVENT_LISTENER(protocol_send_cnc_settings, set##ID##_protocol_send_cnc_settings) + +#define EXTENDED_SETTING_ADDRESS(ID) set##ID##_settings_address + +#define EXTENDED_SETTING_INIT(ID, var) \ + static bool set##ID##_init = false; \ + if (!set##ID##_init) \ + { \ + set##ID##_settings_address = settings_register_external_setting(sizeof(var)); \ + ADD_EVENT_LISTENER(settings_load, set##ID##_settings_load); \ + ADD_EVENT_LISTENER(settings_save, set##ID##_settings_save); \ + ADD_EVENT_LISTENER(settings_change, set##ID##_settings_change); \ + ADD_EVENT_LISTENER(settings_erase, set##ID##_settings_erase); \ + ADD_EVENT_LISTENER(protocol_send_cnc_settings, set##ID##_protocol_send_cnc_settings); \ + set##ID##_init = true; \ + } + #ifdef __cplusplus } #endif diff --git a/uCNC/src/module.c b/uCNC/src/module.c index 2ce344b72..d5522d828 100644 --- a/uCNC/src/module.c +++ b/uCNC/src/module.c @@ -48,10 +48,6 @@ void mod_init(void) LOAD_MODULE(digipot); #endif -#if PID_CONTROLLERS > 0 - LOAD_MODULE(pid); -#endif - #if ENCODERS > 0 LOAD_MODULE(encoder); #endif diff --git a/uCNC/src/modules/pid.c b/uCNC/src/modules/pid.c index 8f9a68773..5b1e24415 100644 --- a/uCNC/src/modules/pid.c +++ b/uCNC/src/modules/pid.c @@ -17,268 +17,38 @@ */ #include "../cnc.h" +#include "pid.h" #include #include -#if (PID_CONTROLLERS > 0) - -// These parameters adjust the PID to use integer math only and output limiting (usually to be used with PWM) -#define PID_BITSHIFT_FACTOR 8 -#define PID_OUTPUT_MAX ((1 << PID_BITSHIFT_FACTOR) - 1) -#define PID_OUTPUT_MIN (-((1 << PID_BITSHIFT_FACTOR) - 1)) - -static float cumulative_delta[PID_CONTROLLERS]; -static float last_error[PID_CONTROLLERS]; -static float ki[PID_CONTROLLERS]; -static float kd[PID_CONTROLLERS]; -static uint8_t pid_freqdiv[PID_CONTROLLERS]; - -// #define GAIN_FLT_TO_INT (1 << PID_BITSHIFT_FACTOR) -// #define ERROR_MAX (GAIN_FLT_TO_INT - 1) -// #define KP_MAX (GAIN_FLT_TO_INT - 1) -// #define KI_MAX (((GAIN_FLT_TO_INT << 1) >> PID_DIVISIONS) - 1) -// #define KD_MAX ((GAIN_FLT_TO_INT << 10) - 1) -// #define ERROR_SUM_MAX (1 << (31 - PID_BITSHIFT_FACTOR - PID_DIVISIONS)) - -static int32_t pid_get_freqdiv(uint8_t i) -{ - switch (i) - { -#if (PID_CONTROLLERS > 0) - case 0: - return PID0_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 1) - case 1: - return PID1_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 2) - case 2: - return PID2_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 3) - case 3: - return PID3_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 4) - case 4: - return PID4_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 5) - case 5: - return PID5_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 6) - case 6: - return PID6_FREQ_DIV; -#endif -#if (PID_CONTROLLERS > 7) - case 7: - return PID7_FREQ_DIV; -#endif - } - - return 0; -} - -static int32_t pid_get_error(uint8_t i) -{ - switch (i) - { -#if (PID_CONTROLLERS > 0) - case 0: - return (int32_t)PID0_DELTA(); -#endif -#if (PID_CONTROLLERS > 1) - case 1: - return (int32_t)PID1_DELTA(); -#endif -#if (PID_CONTROLLERS > 2) - case 2: - return (int32_t)PID2_DELTA(); -#endif -#if (PID_CONTROLLERS > 3) - case 3: - return (int32_t)PID3_DELTA(); -#endif -#if (PID_CONTROLLERS > 4) - case 4: - return (int32_t)PID4_DELTA(); -#endif -#if (PID_CONTROLLERS > 5) - case 5: - return (int32_t)PID5_DELTA(); -#endif -#if (PID_CONTROLLERS > 6) - case 6: - return (int32_t)PID6_DELTA(); -#endif -#if (PID_CONTROLLERS > 7) - case 7: - return (int32_t)PID7_DELTA(); -#endif - } - - return 0; -} - -static int32_t pid_set_output(uint8_t i, int16_t val) -{ - switch (i) - { -#if (PID_CONTROLLERS > 0) - case 0: - PID0_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 1) - case 1: - PID1_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 2) - case 2: - PID2_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 3) - case 3: - PID3_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 4) - case 4: - PID4_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 5) - case 5: - PID5_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 6) - case 6: - PID6_OUTPUT(val); - return; -#endif -#if (PID_CONTROLLERS > 7) - case 7: - PID7_OUTPUT(val); - return; -#endif - } -} - -void FORCEINLINE pid_stop() -{ - -#if (PID_CONTROLLERS > 0) - PID0_STOP(); -#endif -#if (PID_CONTROLLERS > 1) - PID1_STOP(); -#endif -#if (PID_CONTROLLERS > 2) - PID2_STOP(val); -#endif -#if (PID_CONTROLLERS > 3) - PID3_STOP(val); -#endif -#if (PID_CONTROLLERS > 4) - PID4_STOP(val); -#endif -#if (PID_CONTROLLERS > 5) - PID5_STOP(val); -#endif -#if (PID_CONTROLLERS > 6) - PID6_STOP(val); -#endif -#if (PID_CONTROLLERS > 7) - PID7_STOP(val); -#endif -} - -// this overrides the event handler since no other module is using it -// may be modified in the future -OVERRIDE_EVENT_HANDLER(cnc_stop) -{ - pid_stop(); -} - -void FORCEINLINE pid_update(void) +bool pid_compute(pid_data_t *pid, float *output, float setpoint, float input, uint32_t sample_rate_ms) { - static uint8_t current_pid = 0; - if (current_pid < PID_CONTROLLERS) + if (mcu_millis() < pid->next_sample) { - if (!pid_freqdiv[current_pid]) - { - float error = (float)pid_get_error(current_pid); - float output = 0; - float pidkp = g_settings.pid_gain[current_pid][0]; - float pidki = ki[current_pid]; - float pidkd = kd[current_pid]; - if (pidkp) - { - output = pidkp * error; - } - - if (pidki) - { - float sum = cumulative_delta[current_pid] + error; - cumulative_delta[current_pid] = sum; - output += (pidki * sum); - } - - if (pidkd) - { - float rateerror = (error - last_error[current_pid]) * pidkd; - last_error[current_pid] = error; - output += rateerror; - } - - pid_set_output(current_pid, (int16_t)lroundf(output)); - } - - if (++pid_freqdiv[current_pid] >= pid_get_freqdiv(current_pid)) - { - pid_freqdiv[current_pid] = 0; - } + return false; } - // restart - if (++current_pid >= PID_CONTROLLERS) - { - current_pid = 0; - } + uint32_t next_sample = mcu_millis() + sample_rate_ms; + float delta_t = ((next_sample - pid->next_sample) * 0.001f); // convert to seconds + pid->next_sample = next_sample; + float pidkp = pid->k[0]; + float pidki = pid->k[1] * delta_t; + float pidkd = pid->k[2] / delta_t; + *output = 0; + float error = setpoint - input; + float input_delta = input - pid->last_input; + pid->last_input = input; + + pidkp *= error; + pidki *= error; + pidki += pid->i_accum; + pidkd *= input_delta; + + pidki = CLAMP(pid->min, pidki, pid->max); + pid->i_accum = pidki; + + *output = pidkp + pidki + pidkd; + *output = CLAMP(pid->min, *output, pid->max); + + return true; } - -// overrides the default event_rtc_tick_handler -// may be modified in the future -OVERRIDE_EVENT_HANDLER(rtc_tick) -{ - pid_update(); -} - -// overrides the default event_rtc_tick_handler -// may be modified in the future -OVERRIDE_EVENT_HANDLER(settings_change) -{ - pid_init(); -} - -// PID ISR should run once every millisecond -// sampling rate is 1000/(log2*(Nº of PID controllers)) -// a single PID controller can run at 1000Hz -// all 8 PID will run at a max freq of 125Hz -// this precomputes the PID factors to save computation cycles -DECL_MODULE(pid) -{ - for (uint8_t i = 0; i < PID_CONTROLLERS; i++) - { - // error gains must be between 0% and 100% (0 and 1) - ki[i] = (g_settings.pid_gain[i][1] / (PID_SAMP_FREQ / (float)pid_get_freqdiv(i))); - kd[i] = (g_settings.pid_gain[i][2] * (PID_SAMP_FREQ / (float)pid_get_freqdiv(i))); - } -} - -#endif diff --git a/uCNC/src/modules/pid.h b/uCNC/src/modules/pid.h index 386dfa011..c0b8fc24b 100644 --- a/uCNC/src/modules/pid.h +++ b/uCNC/src/modules/pid.h @@ -25,8 +25,24 @@ extern "C" #endif #include "../module.h" - - DECL_MODULE(pid); +#include +#include +#include +#include + +#define HZ_TO_MS(hz) ((uint32_t)(0.001f*hz)) + + typedef struct pid_data_ + { + float k[3]; + float last_input; + float i_accum; + float max; + float min; + uint32_t next_sample; + } pid_data_t; + + bool pid_compute(pid_data_t *pid, float *output, float setpoint, float input, uint32_t sample_rate_ms); #ifdef __cplusplus } From b81fd07cdb5b4a76efca282e93efc2e0f8851076 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 18 Jul 2023 14:35:04 +0100 Subject: [PATCH 022/168] code cleaning --- uCNC/src/hal/tools/tools/vfd_pwm.c | 3 --- uCNC/src/module.h | 2 +- 2 files changed, 1 insertion(+), 4 deletions(-) diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index 28c5f1fea..2d6c8faac 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -58,8 +58,6 @@ static pid_data_t vfd_pwm_pid; DECL_EXTENDED_SETTING(VFD_PWM_PID_SETTING_ID, vfd_pwm_pid.k, float, 3, protocol_send_gcode_setting_line_flt); #endif -static uint8_t speed; - static void startup_code(void) { // force pwm mode @@ -79,7 +77,6 @@ static void set_speed(int16_t value) { // easy macro to execute the same code as below // SET_SPINDLE(VFD_PWM, VFD_PWM_DIR, value, invert); - speed = (uint8_t)ABS(value); // speed optimized version (in AVR it's 24 instruction cycles) #if ASSERT_PIN(VFD_PWM_DIR) if ((value <= 0)) diff --git a/uCNC/src/module.h b/uCNC/src/module.h index c2d1c8af8..1c93ff5d9 100644 --- a/uCNC/src/module.h +++ b/uCNC/src/module.h @@ -28,7 +28,7 @@ extern "C" #include #include -#define UCNC_MODULE_VERSION 010700 +#define UCNC_MODULE_VERSION 010800 #define EVENT_CONTINUE false #define EVENT_HANDLED true From 77493cf15c1a09b95dea785b3c26c67a2f8d734a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 18 Jul 2023 16:11:54 +0100 Subject: [PATCH 023/168] modified analog resolution to 10bit --- uCNC/src/hal/mcus/avr/mcumap_avr.h | 4 ++-- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 2 +- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 4 ++-- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 2 +- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 2 +- uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 2 +- uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h | 2 +- uCNC/src/hal/mcus/mcu.h | 2 +- uCNC/src/hal/mcus/rp2040/mcu_rp2040.c | 2 +- uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h | 2 +- uCNC/src/hal/mcus/samd21/mcu_samd21.c | 4 ++-- uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h | 2 +- uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h | 2 +- uCNC/src/hal/mcus/virtual/mcu_virtual.c | 2 +- 14 files changed, 17 insertions(+), 17 deletions(-) diff --git a/uCNC/src/hal/mcus/avr/mcumap_avr.h b/uCNC/src/hal/mcus/avr/mcumap_avr.h index 6b3941f9d..ce460caa7 100644 --- a/uCNC/src/hal/mcus/avr/mcumap_avr.h +++ b/uCNC/src/hal/mcus/avr/mcumap_avr.h @@ -4619,11 +4619,11 @@ extern "C" #define ADC_PRESC (_min(7, (0xff & ((uint8_t)((float)(F_CPU / 100000) / LOG2))))) #define mcu_get_analog(diopin) \ { \ - ADMUX = (0x60 | __indirect__(diopin, CHANNEL)); \ + ADMUX = (0x00 | __indirect__(diopin, CHANNEL)); \ ADCSRA = (0xC0 | ADC_PRESC); \ while (ADCSRA & 0x40) \ ; \ - ADCH; \ + (0x3FF & ((ADCH << 8) | ADCL)); \ } #ifdef PROBE_ISR diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 61bfec7b8..06a2d5e24 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -520,7 +520,7 @@ void mcu_disable_probe_isr(void) * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { return 0; } diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 8aa4624d9..d6f1d533b 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2800,7 +2800,7 @@ extern "C" #define mcu_config_analog(X) \ { \ mcu_config_input(X); \ - adc1_config_width(ADC_WIDTH_BIT_9); \ + adc1_config_width(ADC_WIDTH_BIT_10); \ adc1_config_channel_atten(__indirect__(X, ADC_CHANNEL), ADC_ATTEN_DB_11); \ } #define mcu_config_pullup(X) \ @@ -2861,7 +2861,7 @@ extern "C" ledc_update_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)); \ } #define mcu_get_pwm(X) ledc_get_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)) -#define mcu_get_analog(X) (adc1_get_raw(__indirect__(X, ADC_CHANNEL)) >> 1) +#define mcu_get_analog(X) adc1_get_raw(__indirect__(X, ADC_CHANNEL)) #ifdef MCU_HAS_ONESHOT_TIMER #define mcu_start_timeout() timer_start(ONESHOT_TIMER_TG, ONESHOT_TIMER_IDX) diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 900765c00..0c037b27c 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -249,7 +249,7 @@ void mcu_disable_probe_isr(void) * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { return 0; } diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index 1c1aff349..e36ed79b7 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -1046,7 +1046,7 @@ extern uint8_t g_soft_pwm_res; #define mcu_toggle_output(X) digitalWrite(__indirect__(X, BIT), !digitalRead(__indirect__(X, BIT))) -#define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) +#define mcu_get_analog(X) analogRead(__indirect__(X, BIT)) #define mcu_spi_xmit(X) \ { \ diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index fd9d4243e..05b06eecf 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -519,7 +519,7 @@ void mcu_disable_probe_isr(void) * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { return 0; } diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index 2c2dbb75c..ed64b3fed 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -3927,7 +3927,7 @@ extern "C" } #define mcu_get_pwm(diopin) (uint8_t) LPC_PWM1->__indirect__(diopin, MR) -#define mcu_get_analog(diopin) (uint8_t)(((LPC_ADC->__indirect__(diopin, ADDR)) & 0xFFF) >> 4) +#define mcu_get_analog(diopin) (uint16_t)(((LPC_ADC->__indirect__(diopin, ADDR)) >> 2) & 0x03FF) extern volatile bool lpc_global_isr_enabled; #define mcu_enable_global_isr() \ diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index a5707a7a1..e67843ed5 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -163,7 +163,7 @@ extern "C" * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog - uint8_t mcu_get_analog(uint8_t channel); + uint16_t mcu_get_analog(uint8_t channel); #endif /** diff --git a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c index 6b032574f..dd188e749 100644 --- a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c +++ b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c @@ -326,7 +326,7 @@ void mcu_disable_probe_isr(void) * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { return 0; } diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index 69f3293e9..1a444f6ce 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -1156,7 +1156,7 @@ extern "C" analogWrite(__indirect__(X, BIT), Y); \ } #define mcu_get_pwm(X) (rp2040_pwm[X - PWM_PINS_OFFSET]) -#define mcu_get_analog(X) (analogRead(__indirect__(X, BIT)) >> 2) +#define mcu_get_analog(X) analogRead(__indirect__(X, BIT)) #if (defined(ENABLE_WIFI) || defined(ENABLE_BLUETOOTH)) #ifndef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index 6a931774a..191aa66df 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -114,7 +114,7 @@ static void mcu_setup_clocks(void) while (ADC->STATUS.bit.SYNCBUSY) ; // set resolution - ADC->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_8BIT_Val; + ADC->CTRLB.bit.RESSEL = ADC_CTRLB_RESSEL_10BIT_Val; ADC->CTRLB.bit.PRESCALER = ADC_CTRLB_PRESCALER_DIV32_Val; while (ADC->STATUS.bit.SYNCBUSY) ; @@ -709,7 +709,7 @@ void mcu_disable_probe_isr(void) * can be defined either as a function or a macro call * */ #ifndef mcu_get_analog -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { return 0; } diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index 09ddd1ab6..ccbe90d68 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -4755,7 +4755,7 @@ extern bool tud_cdc_n_connected (uint8_t itf); while (!(ADC1->SR & ADC_SR_EOS)) \ ; \ ADC1->SR &= ~ADC_SR_EOS; \ - (0xFF & (ADC1->DR >> 4)); \ + (0x3FF & (ADC1->DR >> 2)); \ }) #define mcu_spi_xmit(X) \ diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index 5c38f66d5..f79805205 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -3331,7 +3331,7 @@ extern bool tud_cdc_n_connected (uint8_t itf); while (!(ADC1->SR & ADC_SR_EOC)) \ ; \ ADC1->SR &= ~ADC_SR_EOC; \ - (0xFF & (ADC1->DR >> 4)); \ + (0x3FF & (ADC1->DR >> 2)); \ }) #define mcu_spi_xmit(X) \ diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 3a1dcc4c9..b149f8f56 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -1383,7 +1383,7 @@ void mcu_toggle_output(uint8_t pin) } } -uint8_t mcu_get_analog(uint8_t channel) +uint16_t mcu_get_analog(uint8_t channel) { channel -= ANALOG0; return virtualmap.analog[channel]; From 5e79798d5c603aef5b6b0143e144abcaee8ccc5b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 18 Jul 2023 16:30:18 +0100 Subject: [PATCH 024/168] new RT_STEP_PREVENT_CONDITION condition - Set a custom filter that prevents step motions in realtime --- uCNC/cnc_hal_config.h | 11 +++++++++++ uCNC/src/core/interpolator.c | 7 +++++++ 2 files changed, 18 insertions(+) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 29953ade4..ad446a7dc 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -221,6 +221,17 @@ extern "C" * **/ // #define ENABLE_TOOL_PID_CONTROLLER +/** + * Set a custom filter that prevents step motions in realtime + * This can be any expression that can be evaluated as true or false + * If defined and the expression evaluates to true the ISR will be unable to generate steps until condition cleared + * + * In the example bellow if input pin DIN19 is active step ISR will stop generating steps + * Can be uses for example in sewing machines to prevent motion on needle down detection and avoid damadge to the needle + * + * **/ +// #define RT_STEP_PREVENT_CONDITION io_get_input(DIN19) + // Assigns an output to an blinking led (1Hz rate) #define ACTIVITY_LED DOUT31 diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 8352d12ea..0e5b0395f 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1186,6 +1186,13 @@ MCU_CALLBACK void mcu_step_cb(void) static uint16_t new_laser_ppi = 0; #endif +#ifdef RT_STEP_PREVENT_CONDITION + if (RT_STEP_PREVENT_CONDITION) + { + return; + } +#endif + if (itp_busy) // prevents reentrancy { return; From acfcf181073e53d348951ec8951250dfba241944 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 18 Jul 2023 18:45:46 +0100 Subject: [PATCH 025/168] Update parser.h --- uCNC/src/core/parser.h | 1 + 1 file changed, 1 insertion(+) diff --git a/uCNC/src/core/parser.h b/uCNC/src/core/parser.h index 75b8ff8be..88731db45 100644 --- a/uCNC/src/core/parser.h +++ b/uCNC/src/core/parser.h @@ -153,6 +153,7 @@ extern "C" // only used in canned cycles and splines for now // can overlap same memory position #define GCODE_WORD_Q GCODE_WORD_D +#define GCODE_WORD_E GCODE_WORD_A #define GCODE_WORD_TOOL (1 << AXIS_TOOL) From ddc6d63c9b9d7a136b5a0705b1f80f32c7f6629c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 19 Jul 2023 13:20:37 +0100 Subject: [PATCH 026/168] Update module.h --- uCNC/src/module.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/module.h b/uCNC/src/module.h index 1c93ff5d9..9f1ad3efe 100644 --- a/uCNC/src/module.h +++ b/uCNC/src/module.h @@ -28,7 +28,7 @@ extern "C" #include #include -#define UCNC_MODULE_VERSION 010800 +#define UCNC_MODULE_VERSION 10800 #define EVENT_CONTINUE false #define EVENT_HANDLED true From 33edcdd1fd287f9404ce7e6e85c5556583dacaaf Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 19 Jul 2023 22:55:52 +0100 Subject: [PATCH 027/168] added parsing debug message --- uCNC/cnc_config.h | 7 +++++++ uCNC/src/cnc.c | 16 ++++++++++++++++ uCNC/src/utils.h | 3 +-- 3 files changed, 24 insertions(+), 2 deletions(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 3ffe80c5f..a50af1f7b 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -101,6 +101,13 @@ extern "C" // #define ECHO_CMD + /** + * Debug command parsing time + * Uncomment to enable. This measures the time it takes to execute a command line and place it in the planner + * */ + + // #define ENABLE_PARSING_TIME_DEBUG + /** * Override default configuration settings. Use _PER_AXIS parameters to * define different settings for each axis. diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index f8c6fd7ab..6fce090ce 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -170,6 +170,9 @@ void cnc_run(void) bool cnc_exec_cmd(void) { +#ifdef ENABLE_PARSING_TIME_DEBUG + uint32_t exec_time; +#endif // process gcode commands if (!serial_rx_is_empty()) { @@ -186,7 +189,20 @@ bool cnc_exec_cmd(void) serial_getc(); break; default: +#ifdef ENABLE_PARSING_TIME_DEBUG + if (!exec_time) + { + exec_time = mcu_millis(); + } +#endif error = parser_read_command(); +#ifdef ENABLE_PARSING_TIME_DEBUG + exec_time = mcu_millis() - exec_time; + protocol_send_string(MSG_START); + protocol_send_string(__romstr__("exec time ")); + serial_print_int(exec_time); + protocol_send_string(MSG_END); +#endif break; } if (!error) diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index 79e46a443..a181dcf35 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -135,9 +135,8 @@ extern "C" res.i = ((res.i << 1) - 0x3f7adaba); \ if (res.i < 0) \ res.i = 0; \ - res.f; \ } \ - 0; \ + res.f; \ }) // mul10 takes about 26 clock cycles on AVR instead of 77 on 32bit integer multiply by 10 (x~3 faster). Can be customized for each MCU #ifndef fast_int_mul10 From ae69b32e501752b9ec03c9a04dca5ea231317526 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 01:00:44 +0100 Subject: [PATCH 028/168] update changelog and readme --- CHANGELOG.md | 19 +++++++++++++++++++ README.md | 19 +++++++++++++++++-- 2 files changed, 36 insertions(+), 2 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 03178c62d..7e780c8d5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -6,6 +6,24 @@ # Changelog +# Changelog + +## [1.8.0-beta] - 20-07-2023 + +### Added + +- new IO HAL that simplifies io control and calls (#443) +- added support for motion control/planner hijack. This allows to stash and restore all current buffered motions to allow execution of a completly new set of intermediate motions (#432) +- added realtime modification of step and dir bits to be executed in the fly (#447) +- added new tool for plasma THC (#447) +- added debugging parsing execution time option (#452) +- added new step/dir output condition filter that prevents motion based on condition assert (#451) + +### Changed + +- all analog inputs were modified from 8bit resolution to 10bit (#450) +- complete redesign of PID module and modiified tools functions to make use of PID update loop (#449) + ## [1.7.3] - 15-07-2023 ### Changed @@ -1252,6 +1270,7 @@ Version 1.1.0 comes with many added features and improvements over the previous ### Initial release +[1.8.0-beta]: https://github.com/Paciente8159/uCNC/releases/tag/v1.8.0-beta [1.7.3]: https://github.com/Paciente8159/uCNC/releases/tag/v1.7.3 [1.7.2]: https://github.com/Paciente8159/uCNC/releases/tag/v1.7.2 [1.7.1]: https://github.com/Paciente8159/uCNC/releases/tag/v1.7.1 diff --git a/README.md b/README.md index 361cb1fcd..f3dd1f922 100644 --- a/README.md +++ b/README.md @@ -11,7 +11,9 @@ To configure µCNC to fit your hardware you can use [µCNC config builder web tool](https://paciente8159.github.io/uCNC-config-builder/) to generate the config override files. Although most of the options are configurable via the web tool, some options might be missing and you might need to add them manually (regarding tools or addon modules mostly). -# VERSION 1.7+ NOTES +# VERSION 1.8+ NOTES + +Version 1.8 introduced some small but breaking changes to tools functions declarations. This version also introduces a new IO HAL that makes io abstraction easier. Previous version modules should work in this version but future module will begin to use this new IO HALL. Previous modules will be also gradually converted to use this new IO HAL. Version 1.7 introduced some small but breaking changes to modules function declarations. If you are upgrading from a previous version you need to upgrade the modules also. Modules for previous versions are available in the releases section of the [µCNC-modules repository](https://github.com/Paciente8159/uCNC-modules). @@ -54,7 +56,20 @@ You can also reach me at µCNC discord channel ## Current µCNC status -µCNC current major version is v1.6. You can check all the new features, changes and bug fixes in the [CHANGELOG](https://github.com/Paciente8159/uCNC/blob/master/CHANGELOG.md). +µCNC current major version is v1.8. You can check all the new features, changes and bug fixes in the [CHANGELOG](https://github.com/Paciente8159/uCNC/blob/master/CHANGELOG.md). + +Version 1.8 added the following new major features. + +- new IO HAL that simplifies io control and calls. +- added support for motion control/planner hijack. This allows to stash and restore all current buffered motions to allow execution of a completly new set of intermediate motions. +- added realtime modification of step and dir bits to be executed in the fly. +- added new tool for plasma THC. +- all analog inputs were modified from 8bit resolution to 10bit. +- complete redesign of PID module and modiified tools functions to make use of PID update loop. + +Version 1.7 added a new major feature. + +- added system menus module that allows to manage and render user menus in any type of display. Version 1.6 added a couple of new features. From bbe61e04bc30fc9e462d7b5668ca1d2efa744ec2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 01:02:45 +0100 Subject: [PATCH 029/168] Update CHANGELOG.md --- CHANGELOG.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 7e780c8d5..9fe89694e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -22,7 +22,7 @@ ### Changed - all analog inputs were modified from 8bit resolution to 10bit (#450) -- complete redesign of PID module and modiified tools functions to make use of PID update loop (#449) +- complete redesign of PID module and modified tools functions to make use of PID update loop (#449) ## [1.7.3] - 15-07-2023 From daff67be5a0cf6a7687d43e52dbd6c0d146750dc Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 01:11:30 +0100 Subject: [PATCH 030/168] Update CHANGELOG.md --- CHANGELOG.md | 1 + 1 file changed, 1 insertion(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 9fe89694e..29101888c 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -18,6 +18,7 @@ - added new tool for plasma THC (#447) - added debugging parsing execution time option (#452) - added new step/dir output condition filter that prevents motion based on condition assert (#451) +- new set of macros that allow quick custom settings prototyping (#449) ### Changed From f009aeeb95d679311429fb7b996b38a9c8cbca4d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 09:05:06 +0100 Subject: [PATCH 031/168] modified THC loop to use tool PID loop --- uCNC/cnc_hal_config.h | 6 ++++-- uCNC/src/cnc_hal_config_helper.h | 4 ++-- uCNC/src/hal/tools/tools/laser_ppi.c | 2 -- uCNC/src/hal/tools/tools/laser_pwm.c | 2 -- uCNC/src/hal/tools/tools/pen_servo.c | 2 -- uCNC/src/hal/tools/tools/plasma_thc.c | 15 ++------------- uCNC/src/hal/tools/tools/spindle_besc.c | 2 -- uCNC/src/hal/tools/tools/spindle_pwm.c | 4 +--- uCNC/src/hal/tools/tools/spindle_relay.c | 2 -- uCNC/src/hal/tools/tools/vfd_modbus.c | 2 -- uCNC/src/hal/tools/tools/vfd_pwm.c | 4 +--- 11 files changed, 10 insertions(+), 35 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index ad446a7dc..71fd5ff43 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -138,7 +138,7 @@ extern "C" * Enables Plasma THC capabilities * * **/ -// #define ENABLE_PLASMA_THC + #define ENABLE_PLASMA_THC /** * @@ -157,7 +157,7 @@ extern "C" * **/ // assign the tools from 1 to 16 #if (TOOL_COUNT >= 1) -#define TOOL1 spindle_pwm +#define TOOL1 plasma_thc #endif #if (TOOL_COUNT >= 2) #define TOOL2 spindle_pwm @@ -219,7 +219,9 @@ extern "C" * Chech the tool file to find the settings for each tool * * **/ +#ifndef ENABLE_TOOL_PID_CONTROLLER // #define ENABLE_TOOL_PID_CONTROLLER +#endif /** * Set a custom filter that prevents step motions in realtime diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index fe77bf98f..ad9dc8eb1 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2123,8 +2123,8 @@ typedef uint16_t step_t; #ifdef ENABLE_PLASMA_THC //forces modes -#ifndef ENABLE_MAIN_LOOP_MODULES -#define ENABLE_MAIN_LOOP_MODULES +#ifndef ENABLE_TOOL_PID_CONTROLLER +#define ENABLE_TOOL_PID_CONTROLLER #endif #ifndef ENABLE_PARSER_MODULES #define ENABLE_PARSER_MODULES diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 2b628298a..2844954a0 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -89,9 +89,7 @@ static uint16_t get_speed(void) const tool_t laser_ppi = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = NULL, .get_speed = &get_speed, .set_speed = NULL, diff --git a/uCNC/src/hal/tools/tools/laser_pwm.c b/uCNC/src/hal/tools/tools/laser_pwm.c index f89674928..e022edef3 100644 --- a/uCNC/src/hal/tools/tools/laser_pwm.c +++ b/uCNC/src/hal/tools/tools/laser_pwm.c @@ -111,9 +111,7 @@ static uint16_t get_speed(void) const tool_t laser_pwm = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = &range_speed, .get_speed = &get_speed, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/pen_servo.c b/uCNC/src/hal/tools/tools/pen_servo.c index 6b0af8a3d..1dc395ce5 100644 --- a/uCNC/src/hal/tools/tools/pen_servo.c +++ b/uCNC/src/hal/tools/tools/pen_servo.c @@ -83,9 +83,7 @@ static void set_speed(int16_t value) const tool_t pen_servo = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = &range_speed, .get_speed = NULL, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 4213a5ef6..3d6ba9915 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -278,8 +278,7 @@ bool m103_exec(void *args) #endif -#ifdef ENABLE_MAIN_LOOP_MODULES -bool plasma_thc_update_loop(void *ptr) +static void pid_update(void) { if (plasma_thc_state == PLASMA_ARC_OK) { @@ -347,16 +346,8 @@ bool plasma_thc_update_loop(void *ptr) return EVENT_CONTINUE; } -CREATE_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); -#endif - DECL_MODULE(plasma_thc) { -#ifdef ENABLE_MAIN_LOOP_MODULES - ADD_EVENT_LISTENER(cnc_dotasks, plasma_thc_update_loop); -#else -#error "Main loop extensions are not enabled. TMC configurations will not work." -#endif #ifdef ENABLE_PARSER_MODULES ADD_EVENT_LISTENER(gcode_parse, m103_parse); ADD_EVENT_LISTENER(gcode_exec, m103_exec); @@ -428,9 +419,7 @@ static void set_coolant(uint8_t value) const tool_t plasma_thc = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER - .pid_update = NULL, -#endif + .pid_update = &pid_update, .range_speed = &range_speed, .get_speed = NULL, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/spindle_besc.c b/uCNC/src/hal/tools/tools/spindle_besc.c index c4aca1876..b27c281f9 100644 --- a/uCNC/src/hal/tools/tools/spindle_besc.c +++ b/uCNC/src/hal/tools/tools/spindle_besc.c @@ -132,9 +132,7 @@ static uint16_t get_speed(void) const tool_t spindle_besc = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = &range_speed, .get_speed = &get_speed, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 54769796b..21cee6a23 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -127,7 +127,7 @@ static uint16_t get_speed(void) #endif } -#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) +#ifndef DISABLE_SPINDLE_PWM_PID static void pid_update(void) { float output = tool_get_setpoint(); @@ -146,12 +146,10 @@ static void pid_update(void) const tool_t spindle_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#ifdef ENABLE_TOOL_PID_CONTROLLER #ifndef DISABLE_SPINDLE_PWM_PID .pid_update = &pid_update, #else .pid_update = NULL, -#endif #endif .range_speed = &range_speed, .get_speed = &get_speed, diff --git a/uCNC/src/hal/tools/tools/spindle_relay.c b/uCNC/src/hal/tools/tools/spindle_relay.c index 92ca76fac..3432fed71 100644 --- a/uCNC/src/hal/tools/tools/spindle_relay.c +++ b/uCNC/src/hal/tools/tools/spindle_relay.c @@ -84,9 +84,7 @@ void set_coolant(uint8_t value) const tool_t spindle_relay = { .startup_code = NULL, .shutdown_code = NULL, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = NULL, .get_speed = NULL, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/vfd_modbus.c b/uCNC/src/hal/tools/tools/vfd_modbus.c index 543b0c2f8..bc9247710 100644 --- a/uCNC/src/hal/tools/tools/vfd_modbus.c +++ b/uCNC/src/hal/tools/tools/vfd_modbus.c @@ -467,9 +467,7 @@ static uint16_t get_speed(void) const tool_t vfd_modbus = { .startup_code = &startup_code, .shutdown_code = &shutdown_code, -#ifdef ENABLE_TOOL_PID_CONTROLLER .pid_update = NULL, -#endif .range_speed = NULL, .get_speed = &get_speed, .set_speed = &set_speed, diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index 2d6c8faac..d91ff8496 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -110,7 +110,7 @@ static int16_t range_speed(int16_t value) return value; } -#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) +#ifndef DISABLE_VFD_PWM_PID static void pid_update(void) { float output = tool_get_setpoint(); @@ -128,12 +128,10 @@ static void pid_update(void) const tool_t vfd_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#ifdef ENABLE_TOOL_PID_CONTROLLER #ifndef DISABLE_SPINDLE_PWM_PID .pid_update = &pid_update, #else .pid_update = NULL, -#endif #endif .range_speed = &range_speed, .get_speed = NULL, From 6eb112e7ea54d35b1821a7ccb957cd82a970ac56 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 09:16:04 +0100 Subject: [PATCH 032/168] Update cnc_hal_config.h --- uCNC/cnc_hal_config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 71fd5ff43..246e75dd0 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -138,7 +138,7 @@ extern "C" * Enables Plasma THC capabilities * * **/ - #define ENABLE_PLASMA_THC +// #define ENABLE_PLASMA_THC /** * @@ -157,7 +157,7 @@ extern "C" * **/ // assign the tools from 1 to 16 #if (TOOL_COUNT >= 1) -#define TOOL1 plasma_thc +#define TOOL1 spindle_pwm #endif #if (TOOL_COUNT >= 2) #define TOOL2 spindle_pwm From 02ca1b808df74fae37ebbf79294c57abc60a646b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 11:53:33 +0100 Subject: [PATCH 033/168] fixed build --- uCNC/src/hal/tools/tools/spindle_pwm.c | 4 ++-- uCNC/src/hal/tools/tools/vfd_pwm.c | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 21cee6a23..3f182bd55 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -127,7 +127,7 @@ static uint16_t get_speed(void) #endif } -#ifndef DISABLE_SPINDLE_PWM_PID +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) static void pid_update(void) { float output = tool_get_setpoint(); @@ -146,7 +146,7 @@ static void pid_update(void) const tool_t spindle_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#ifndef DISABLE_SPINDLE_PWM_PID +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_SPINDLE_PWM_PID) .pid_update = &pid_update, #else .pid_update = NULL, diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index d91ff8496..b907c0329 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -110,7 +110,7 @@ static int16_t range_speed(int16_t value) return value; } -#ifndef DISABLE_VFD_PWM_PID +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) static void pid_update(void) { float output = tool_get_setpoint(); @@ -128,7 +128,7 @@ static void pid_update(void) const tool_t vfd_pwm = { .startup_code = &startup_code, .shutdown_code = NULL, -#ifndef DISABLE_SPINDLE_PWM_PID +#if defined(ENABLE_TOOL_PID_CONTROLLER) && !defined(DISABLE_VFD_PWM_PID) .pid_update = &pid_update, #else .pid_update = NULL, From 130aa69fa5db7fdc2b5a795fb1058ee45e0cdecf Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 12:47:45 +0100 Subject: [PATCH 034/168] status message module extender - status message module extender - status extension for THC tool --- uCNC/src/hal/tools/tools/plasma_thc.c | 29 +++++++++++++++++++++++++++ uCNC/src/interface/protocol.c | 19 ++++++++++++++++++ uCNC/src/interface/protocol.h | 1 + 3 files changed, 49 insertions(+) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 3d6ba9915..145a674c5 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -78,6 +78,12 @@ uint8_t __attribute__((weak)) plasma_thc_arc_ok(void) #endif } +// overridable +// user can implement aditional data to be printed in the status message +void __attribute__((weak)) plasma_thc_send_status(void) +{ +} + #define PLASMA_ARC_OFF 0 #define PLASMA_ARC_OK 1 #define PLASMA_ARC_LOST 2 @@ -356,6 +362,29 @@ DECL_MODULE(plasma_thc) #endif } +bool plasma_protocol_send_status(void *args) +{ + protocol_send_string(__romstr__("THC:")); + serial_putc(plasma_thc_state + 48); + serial_putc(','); + if (plasma_thc_up()) + { + serial_putc('U'); + } + else if(plasma_thc_down()){ + serial_putc('D'); + } + else{ + serial_putc('-'); + } + + plasma_thc_send_status + + return EVENT_CONTINUE; +} + +CREATE_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); + static void startup_code(void) { // force plasma off diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index fe6cfe9a4..1f2bca997 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -127,6 +127,23 @@ static uint8_t protocol_get_tools(void) return coolant; } +WEAK_EVENT_HANDLER(protocol_send_status) +{ + // custom handler + protocol_send_status_delegate_event_t *ptr = protocol_send_status_event; + while (ptr != NULL) + { + if (ptr->fptr != NULL) + { + serial_putc('|'); + ptr->fptr(args); + } + ptr = ptr->next; + } + + return EVENT_CONTINUE; +} + static void protocol_send_status_tail(void) { float axis[MAX(AXIS_COUNT, 3)]; @@ -372,6 +389,8 @@ void protocol_send_status(void) protocol_send_status_tail(); + EVENT_INVOKE(protocol_send_status, NULL); + if ((g_settings.status_report_mask & 2)) { protocol_send_string(MSG_STATUS_BUF); diff --git a/uCNC/src/interface/protocol.h b/uCNC/src/interface/protocol.h index dc978976b..7230dd837 100644 --- a/uCNC/src/interface/protocol.h +++ b/uCNC/src/interface/protocol.h @@ -32,6 +32,7 @@ extern "C" void protocol_send_error(uint8_t error); void protocol_send_alarm(int8_t alarm); void protocol_send_status(void); + DECL_EVENT_HANDLER(protocol_send_status); void protocol_send_string(const char *__s); void protocol_send_feedback(const char *__s); void protocol_send_probe_result(uint8_t val); From baecf1ccd606cd52864d97a523aef0f922a55f7e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 17:33:08 +0100 Subject: [PATCH 035/168] updated plasma THC status report --- uCNC/src/hal/tools/tools/plasma_thc.c | 39 +++++++++++++++------------ 1 file changed, 22 insertions(+), 17 deletions(-) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 145a674c5..197122b48 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -84,9 +84,8 @@ void __attribute__((weak)) plasma_thc_send_status(void) { } -#define PLASMA_ARC_OFF 0 -#define PLASMA_ARC_OK 1 -#define PLASMA_ARC_LOST 2 +#define PLASMA_THC_DISABLED 0 +#define PLASMA_THC_ENABLED 1 // plasma thc controller variables static uint8_t plasma_thc_state; @@ -127,7 +126,7 @@ bool plasma_thc_probe_and_start(void) { // cutoff torch // temporary disable - plasma_thc_state = PLASMA_ARC_OFF; + plasma_thc_state = PLASMA_THC_DISABLED; motion_data_t block = {0}; block.motion_flags.bit.spindle_running = 0; mc_update_tools(&block); @@ -171,7 +170,7 @@ bool plasma_thc_probe_and_start(void) block.feed = plasma_start_params.cut_feed; mc_line(pos, &block); // enable plasma mode - plasma_thc_state = PLASMA_ARC_OK; + plasma_thc_state = PLASMA_THC_ENABLED; // continues program plasma_starting = false; cnc_restore_motion(); @@ -286,7 +285,7 @@ bool m103_exec(void *args) static void pid_update(void) { - if (plasma_thc_state == PLASMA_ARC_OK) + if (CHECKFLAG(plasma_thc_state, PLASMA_THC_ENABLED)) { // arc lost // on arc lost the plasma must enter hold @@ -295,7 +294,7 @@ static void pid_update(void) // places the machine under a HOLD and signals the arc lost // this requires the operator to inspect the work to see if was // a simple arc lost or the torch is hover a hole - plasma_thc_state = PLASMA_ARC_LOST; + plasma_thc_state = PLASMA_THC_DISABLED; cnc_set_exec_state(EXEC_HOLD); // prepares the reprobing action to be executed on cycle resume action @@ -362,23 +361,29 @@ DECL_MODULE(plasma_thc) #endif } +// uses similar status to grblhal bool plasma_protocol_send_status(void *args) { protocol_send_string(__romstr__("THC:")); - serial_putc(plasma_thc_state + 48); - serial_putc(','); + + plasma_thc_send_status(); + + if (CHECKFLAG(plasma_thc_state, PLASMA_THC_ENABLED)) + { + serial_putc('E'); + } + if (plasma_thc_ok()) + { + serial_putc('A'); + } if (plasma_thc_up()) { serial_putc('U'); } - else if(plasma_thc_down()){ + if (plasma_thc_down()) + { serial_putc('D'); } - else{ - serial_putc('-'); - } - - plasma_thc_send_status return EVENT_CONTINUE; } @@ -407,7 +412,7 @@ static void set_speed(int16_t value) if (value) { // enable plasma mode - plasma_thc_state = true; + plasma_thc_state = PLASMA_THC_ENABLED; if (!plasma_thc_arc_ok()) { if (plasma_thc_probe_and_start()) @@ -422,7 +427,7 @@ static void set_speed(int16_t value) else { // disable plasma THC mode - plasma_thc_state = false; + plasma_thc_state = PLASMA_THC_DISABLED; #if ASSERT_PIN(PLASMA_ON_OUTPUT) io_clear_output(PLASMA_ON_OUTPUT); #endif From e55ff739d1aaaf8c215e54c9f533e510c20fea24 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 20 Jul 2023 19:13:16 +0100 Subject: [PATCH 036/168] add event listener and code fixing --- uCNC/src/hal/tools/tools/plasma_thc.c | 15 +++++++++++---- uCNC/src/hal/tools/tools/vfd_pwm.c | 2 +- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 197122b48..e5bff3f38 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -80,7 +80,7 @@ uint8_t __attribute__((weak)) plasma_thc_arc_ok(void) // overridable // user can implement aditional data to be printed in the status message -void __attribute__((weak)) plasma_thc_send_status(void) +void __attribute__((weak)) plasma_thc_extension_send_status(void) { } @@ -348,7 +348,6 @@ static void pid_update(void) plasma_step_error = 0; } } - return EVENT_CONTINUE; } DECL_MODULE(plasma_thc) @@ -366,13 +365,13 @@ bool plasma_protocol_send_status(void *args) { protocol_send_string(__romstr__("THC:")); - plasma_thc_send_status(); + plasma_thc_extension_send_status(); if (CHECKFLAG(plasma_thc_state, PLASMA_THC_ENABLED)) { serial_putc('E'); } - if (plasma_thc_ok()) + if (plasma_thc_arc_ok()) { serial_putc('A'); } @@ -392,10 +391,18 @@ CREATE_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); static void startup_code(void) { + static bool run_once = false; + // force plasma off #if ASSERT_PIN(PLASMA_ON_OUTPUT) io_clear_output(PLASMA_ON_OUTPUT); #endif + + if (!run_once) + { + ADD_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); + run_once = true; + } } static void shutdown_code(void) diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index b907c0329..ac48577d5 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -117,7 +117,7 @@ static void pid_update(void) if (output != 0) { - if (pid_compute(&vfd_pwm_pid, &output, output, get_speed(), HZ_TO_MS(VFD_PWM_PID_SAMPLE_RATE_HZ))) + if (pid_compute(&vfd_pwm_pid, &output, output, tool_get_speed(), HZ_TO_MS(VFD_PWM_PID_SAMPLE_RATE_HZ))) { io_set_pwm(VFD_PWM, range_speed((int16_t)output)); } From 7105189068f122f5a130f75047b1eb5c5e6689d9 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 22 Jul 2023 21:40:07 +0100 Subject: [PATCH 037/168] plasma thc tool update - added velocity anti-dive feature - added similar linuxcnc M62-M65 THC enable control --- makefiles/virtual/uCNC.dev | 22 ++- uCNC/src/hal/tools/tools/plasma_thc.c | 260 ++++++++++++++++++-------- 2 files changed, 207 insertions(+), 75 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 40f6a34c9..32ec8f46c 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=79 +UnitCount=81 [VersionInfo] Major=1 @@ -940,3 +940,23 @@ Priority=1000 OverrideBuildCmd=0 BuildCmd= +[Unit80] +FileName=..\..\uCNC\src\hal\io_hal.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit81] +FileName=..\..\uCNC\src\modules\M62-M65\parser_m62_m65.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index e5bff3f38..ea3f5cea8 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -43,8 +43,39 @@ #define PLASMA_STEPPERS_MASK (1 << 2) #endif +#ifndef PLASMA_THC_ENABLE_PIN +#define PLASMA_THC_ENABLE_PIN 64 +#endif + +#if PLASMA_THC_ENABLE_PIN < 64 +#error "Plasma THC virtual pin must be equal or greated then 64" +#endif + #ifdef ENABLE_PLASMA_THC +#define PLASMA_THC_ENABLED 1 +#define PLASMA_THC_ACTIVE 2 +#define PLASMA_THC_VAD_ACTIVE 4 +// #define PLASMA_THC_UP_ACTIVE 8 +// #define PLASMA_THC_DOWN_ACTIVE 16 + +// plasma thc controller variables +static uint8_t plasma_thc_state; +static volatile int8_t plasma_step_error; + +typedef struct plasma_start_params_ +{ + float probe_depth; // I + float probe_feed; // J + float retract_height; // R + float cut_depth; // K + float cut_feed; // F + float vad; // D + uint16_t dwell; // P*1000 + uint8_t retries; // L +} plasma_start_params_t; +static plasma_start_params_t plasma_start_params; + // overridable // user can implement the plasma thc up condition based on analog voltage reading using analog the controller analog inputs and PID controllers uint8_t __attribute__((weak)) plasma_thc_up(void) @@ -84,24 +115,21 @@ void __attribute__((weak)) plasma_thc_extension_send_status(void) { } -#define PLASMA_THC_DISABLED 0 -#define PLASMA_THC_ENABLED 1 - -// plasma thc controller variables -static uint8_t plasma_thc_state; -static volatile int8_t plasma_step_error; - -typedef struct plasma_start_params_ +// overridable +// user can implement the plasma thc VAD (velocity anti-dive) condition on it's on conditions or external signals +uint8_t __attribute__((weak)) plasma_thc_vad_active(void) { - float probe_depth; // I - float probe_feed; // J - float retract_height; // R - float cut_depth; // K - float cut_feed; // F - uint16_t dwell; // P*1000 - uint8_t retries; // L -} plasma_start_params_t; -static plasma_start_params_t plasma_start_params; + planner_block_t *p = planner_get_block(); + // not exactly the current programmed feed but close enough + float feed = fast_flt_sqrt(p->feed_sqr) * p->feed_conversion; + float current_feed = itp_get_rt_feed(); + float ratio = current_feed / feed; + if (ratio < plasma_start_params.vad){ + return PLASMA_THC_VAD_ACTIVE; + } + + return 0; +} bool plasma_thc_probe_and_start(void) { @@ -126,7 +154,7 @@ bool plasma_thc_probe_and_start(void) { // cutoff torch // temporary disable - plasma_thc_state = PLASMA_THC_DISABLED; + CLEARFLAG(plasma_thc_state, PLASMA_THC_ACTIVE); motion_data_t block = {0}; block.motion_flags.bit.spindle_running = 0; mc_update_tools(&block); @@ -155,7 +183,7 @@ bool plasma_thc_probe_and_start(void) // rapid feed block.feed = FLT_MAX; mc_line(pos, &block); - // turn torch on and wait before confirm the arc on signal + // turn torch on and wait before confirm the arc on signal and form puddle block.motion_flags.bit.spindle_running = 1; block.dwell = plasma_start_params.dwell; // updated tools and wait @@ -170,7 +198,7 @@ bool plasma_thc_probe_and_start(void) block.feed = plasma_start_params.cut_feed; mc_line(pos, &block); // enable plasma mode - plasma_thc_state = PLASMA_THC_ENABLED; + SETFLAG(plasma_thc_state, PLASMA_THC_ACTIVE); // continues program plasma_starting = false; cnc_restore_motion(); @@ -257,23 +285,31 @@ bool m103_exec(void *args) gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; if (ptr->cmd->group_extended == M103) { - if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P)) + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P | GCODE_WORD_D)) != (GCODE_WORD_I | GCODE_WORD_J | GCODE_WORD_K | GCODE_WORD_R | GCODE_WORD_P | GCODE_WORD_D)) { *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; return EVENT_HANDLED; } + if (ptr->words->d < 0 || ptr->words->d > 100) + { + *(ptr->error) = STATUS_INVALID_STATEMENT; + return EVENT_HANDLED; + } + plasma_start_params.dwell = (uint16_t)(ptr->words->p * 1000); plasma_start_params.probe_depth = ptr->words->ijk[0]; plasma_start_params.probe_feed = ptr->words->ijk[1]; plasma_start_params.cut_depth = ptr->words->ijk[2]; plasma_start_params.retract_height = ptr->words->r; + plasma_start_params.vad = ptr->words->d * 0.01f; if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_F))) { plasma_start_params.cut_feed = ptr->words->f; } plasma_start_params.retries = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; + SETFLAG(plasma_thc_state, PLASMA_THC_ENABLED); *(ptr->error) = STATUS_OK; return EVENT_HANDLED; } @@ -281,11 +317,49 @@ bool m103_exec(void *args) return EVENT_CONTINUE; } +#define M62 EXTENDED_MCODE(62) +#define M63 EXTENDED_MCODE(63) +#define M64 EXTENDED_MCODE(64) +#define M65 EXTENDED_MCODE(65) + +bool plasma_virtual_pins(void *args) +{ + gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; + switch (ptr->cmd->group_extended) + { + case M62: + case M64: + if (ptr->words->p == PLASMA_THC_ENABLE_PIN) + { + SETFLAG(plasma_thc_state, PLASMA_THC_ENABLED); + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + break; + case M63: + mc_sync_position(); + case M65: + if (ptr->words->p == PLASMA_THC_ENABLE_PIN) + { + CLEARFLAG(plasma_thc_state, PLASMA_THC_ENABLED); + *(ptr->error) = STATUS_OK; + return EVENT_HANDLED; + } + break; + default: + break; + } + + return EVENT_CONTINUE; +} + +CREATE_EVENT_LISTENER(gcode_exec, plasma_virtual_pins); #endif static void pid_update(void) { - if (CHECKFLAG(plasma_thc_state, PLASMA_THC_ENABLED)) + uint8_t state = plasma_thc_state; + if (CHECKFLAG(state, PLASMA_THC_ENABLED) && CHECKFLAG(state, PLASMA_THC_ACTIVE)) { // arc lost // on arc lost the plasma must enter hold @@ -294,7 +368,6 @@ static void pid_update(void) // places the machine under a HOLD and signals the arc lost // this requires the operator to inspect the work to see if was // a simple arc lost or the torch is hover a hole - plasma_thc_state = PLASMA_THC_DISABLED; cnc_set_exec_state(EXEC_HOLD); // prepares the reprobing action to be executed on cycle resume action @@ -310,42 +383,46 @@ static void pid_update(void) } } - if (plasma_thc_up() && !plasma_step_error) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits &= 0xFB; - - // option 2 - mask the step bits directly - // clamp tool max step rate according to the actual motion feed - float feed = itp_get_rt_feed(); - float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); - plasma_step_error = 1 + (uint8_t)max_feed_ratio; - } - else if (plasma_thc_down() && !plasma_step_error) - { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = p->steps[p->main_stepper]; - // p->dirbits |= 4; - - // option 2 - mask the step bits directly - float feed = itp_get_rt_feed(); - float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); - plasma_step_error = -(1 + (uint8_t)max_feed_ratio); - } - else + // evals if VAD is active before running plasma UP/DOWN + if (!plasma_thc_vad_active()) { - // option 1 - modify the planner block - // this assumes Z is not moving in this motion - // planner_block_t *p = planner_get_block(); - // p->steps[2] = 0; + if (plasma_thc_up() && !plasma_step_error) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits &= 0xFB; + + // option 2 - mask the step bits directly + // clamp tool max step rate according to the actual motion feed + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = 1 + (uint8_t)max_feed_ratio; + } + else if (plasma_thc_down() && !plasma_step_error) + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = p->steps[p->main_stepper]; + // p->dirbits |= 4; + + // option 2 - mask the step bits directly + float feed = itp_get_rt_feed(); + float max_feed_ratio = ceilf(feed / g_settings.max_feed_rate[AXIS_TOOL]); + plasma_step_error = -(1 + (uint8_t)max_feed_ratio); + } + else + { + // option 1 - modify the planner block + // this assumes Z is not moving in this motion + // planner_block_t *p = planner_get_block(); + // p->steps[2] = 0; - // option 2 - mask the step bits directly - plasma_step_error = 0; + // option 2 - mask the step bits directly + plasma_step_error = 0; + } } } } @@ -355,6 +432,7 @@ DECL_MODULE(plasma_thc) #ifdef ENABLE_PARSER_MODULES ADD_EVENT_LISTENER(gcode_parse, m103_parse); ADD_EVENT_LISTENER(gcode_exec, m103_exec); + ADD_EVENT_LISTENER(gcode_exec, plasma_virtual_pins); #else #error "Parser extensions are not enabled. M103 code extension will not work." #endif @@ -363,18 +441,37 @@ DECL_MODULE(plasma_thc) // uses similar status to grblhal bool plasma_protocol_send_status(void *args) { + uint8_t state = plasma_thc_state; + protocol_send_string(__romstr__("THC:")); plasma_thc_extension_send_status(); - - if (CHECKFLAG(plasma_thc_state, PLASMA_THC_ENABLED)) + + if (CHECKFLAG(state, PLASMA_THC_ENABLED)) { serial_putc('E'); } + else{ + serial_putc('*'); + } + if (CHECKFLAG(state, PLASMA_THC_ACTIVE)) + { + serial_putc('R'); + } +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + if (io_get_output(PLASMA_ON_OUTPUT)) + { + serial_putc('T'); + } +#endif if (plasma_thc_arc_ok()) { serial_putc('A'); } + if (plasma_thc_vad_active()) + { + serial_putc('V'); + } if (plasma_thc_up()) { serial_putc('U'); @@ -415,31 +512,46 @@ static void shutdown_code(void) static void set_speed(int16_t value) { - // turn plasma on - if (value) + uint8_t state = plasma_thc_state; + + if (CHECKFLAG(state, PLASMA_THC_ENABLED)) { - // enable plasma mode - plasma_thc_state = PLASMA_THC_ENABLED; - if (!plasma_thc_arc_ok()) + // turn plasma on + if (value) { - if (plasma_thc_probe_and_start()) + if (!plasma_thc_arc_ok()) { - cnc_clear_exec_state(EXEC_HOLD); -#if ASSERT_PIN(PLASMA_ON_OUTPUT) - io_set_output(PLASMA_ON_OUTPUT); -#endif + if (plasma_thc_probe_and_start()) + { + cnc_clear_exec_state(EXEC_HOLD); + } + else + { + // plasma not started + value = 0; + } } } + else + { + // disable plasma THC mode + CLEARFLAG(plasma_thc_state, PLASMA_THC_ACTIVE); + } + } + +#if ASSERT_PIN(PLASMA_ON_OUTPUT) + if (value) + { + // turn plasma on + io_set_output(PLASMA_ON_OUTPUT); } else { - // disable plasma THC mode - plasma_thc_state = PLASMA_THC_DISABLED; -#if ASSERT_PIN(PLASMA_ON_OUTPUT) + // disable plasma and sync position io_clear_output(PLASMA_ON_OUTPUT); -#endif mc_sync_position(); } +#endif } static int16_t range_speed(int16_t value) @@ -466,4 +578,4 @@ const tool_t plasma_thc = { .set_speed = &set_speed, .set_coolant = &set_coolant}; -#endif \ No newline at end of file +#endif From cc2e530d8c9bda8b1ee28e90c45730e6498c1f35 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 22 Jul 2023 22:06:32 +0100 Subject: [PATCH 038/168] removed test flag --- uCNC/src/hal/tools/tools/plasma_thc.c | 1 - 1 file changed, 1 deletion(-) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index ea3f5cea8..7972267cb 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -309,7 +309,6 @@ bool m103_exec(void *args) } plasma_start_params.retries = (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_L))) ? ptr->words->l : 1; - SETFLAG(plasma_thc_state, PLASMA_THC_ENABLED); *(ptr->error) = STATUS_OK; return EVENT_HANDLED; } From 18851c4c3f355b4386b72a3265d4c9c16c8167a4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 23 Jul 2023 18:47:06 +0100 Subject: [PATCH 039/168] fixed stepbit output bug - fixed stupid stepbit output bug --- uCNC/src/core/interpolator.c | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 0e5b0395f..6a4b33b3a 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -1236,11 +1236,13 @@ MCU_CALLBACK void mcu_step_cb(void) } } + uint8_t new_stepbits = stepbits; + // sets step bits #ifdef ENABLE_LASER_PPI if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) { - if (stepbits & LASER_PPI_MASK) + if (new_stepbits & LASER_PPI_MASK) { if (new_laser_ppi) { @@ -1256,7 +1258,7 @@ MCU_CALLBACK void mcu_step_cb(void) } } #endif - io_toggle_steps(stepbits); + io_toggle_steps(new_stepbits); // if buffer empty loads one if (itp_rt_sgm == NULL) @@ -1337,13 +1339,13 @@ MCU_CALLBACK void mcu_step_cb(void) } #ifdef ENABLE_RT_SYNC_MOTIONS - if (stepbits && (itp_rt_sgm->flags & ITP_SYNC)) + if (new_stepbits && (itp_rt_sgm->flags & ITP_SYNC)) { itp_sync_step_counter++; } #endif - uint8_t new_stepbits = 0; + new_stepbits = 0; itp_busy = true; mcu_enable_global_isr(); @@ -1658,6 +1660,8 @@ MCU_CALLBACK void mcu_step_cb(void) #if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) stepbits = (new_stepbits & ~itp_step_lock); +#else + stepbits = new_stepbits; #endif } From b3abc57706cfa580a593260eea5bb76ab82dab5f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 09:13:07 +0100 Subject: [PATCH 040/168] new interpolator unified function - new unified acceleration interpolator function - infinite low speed is now possible without changing DSS - 3 types of s-curve profiles available --- tests/arduino_math/arduino_math.ino | 14 +- uCNC/cnc_config.h | 16 +- uCNC/src/cnc_hal_config_helper.h | 6 +- uCNC/src/core/interpolator.c | 582 ++++++---------------------- uCNC/src/interface/protocol.c | 4 +- 5 files changed, 127 insertions(+), 495 deletions(-) diff --git a/tests/arduino_math/arduino_math.ino b/tests/arduino_math/arduino_math.ino index 2abf91391..1babef98d 100644 --- a/tests/arduino_math/arduino_math.ino +++ b/tests/arduino_math/arduino_math.ino @@ -37,7 +37,9 @@ typedef union #define COS cos(a) #define SIN sin(a) #define TAN tan(a) -#define HALF (0.5f*a) +#define TANH ({float k=a*0.001;k-=0.5f;((k / (0.5f + abs(k))) + 0.5f);}) +#define SCURVE ({float k=a*0.001;float x=(1.0f/(1.0f+pow(k/(1.0f-k),-2)));x;}) +#define BEZIER ({uint32_t k=128*a*0.001;float k2=k*k; float c1=k2-2.5*k; float c2=(c1*3+5); (c2*2*k2*k);}) #define HALF_FAST ({int32_t result = (*(int32_t*)&a); if((result&0x7f800000)!=0) result-=0x00800000; else result = 0; (*(float*)&result); }) #define MUL_124 ((a<<7)-(a<<2)) #define DIV_124 ((a>>7)+(a>>12)) @@ -87,7 +89,7 @@ void setup() { offset = TCNT1; TCCR1B=0; - Serial.println("8-bit"); + /*Serial.println("8-bit"); DO_OP(uint8_t, uint16_t, 0,0xFF,ADD); DO_OP(uint8_t, uint16_t, 0,0xFF,SUB); DO_OP(uint8_t, uint16_t, 0,0xFF,MUL); @@ -109,11 +111,11 @@ void setup() { DO_OP(uint64_t, uint64_t, 0,0xFFFF,ADD); DO_OP(uint64_t, uint64_t, 0,0xFFFF,SUB); DO_OP(uint64_t, uint64_t, 0,0xFFFF,MUL); - DO_OP(uint64_t, uint64_t, 0,0xFFFF,DIV); + DO_OP(uint64_t, uint64_t, 0,0xFFFF,DIV);*/ Serial.println("float"); - DO_OP(float, float, 0,10000,ADD); - DO_OP(float, float, 0,10000,SUB); - DO_OP(float, float, 0,10000,MUL); + DO_OP(float, float, 0,1000,TANH); + DO_OP(float, float, 0,1000,SCURVE); + DO_OP(float, float, 0,1000,BEZIER); DO_OP(float, float, 0,10000,DIV); DO_OP(float, float, 0,10000,FLT_BY4); /*Serial.println("testes"); diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index a50af1f7b..de1858132 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -427,19 +427,15 @@ extern "C" * Performs motions with variable acceleration (trapezoidal speed profile * with rounded speed transition between accel/deaccel and constant speed) * instead of constant acceleration (trapezoidal speed profile) + * + * 0 - disabled + * 1 - mild profile (smaller mid slope and higher initial and exit slopes) + * 2 - medium profile (medium mid slope and medium initial and exit slopes) + * 3 - agressive (higher mid slope and smaller initial and exit slopes - uses bezier 5th order) * * */ - // #define ENABLE_S_CURVE_ACCELERATION - - /** - * Enables legacy step interpolation generator (prior to version 1.4) - * This runs a variable time window Riemman sum integrator (better performance). - * S-Curve acceleration will disable this option - * This produces option outputs code smaller size - * */ - -#define USE_LEGACY_STEP_INTERPOLATOR + #define S_CURVE_ACCELERATION_LEVEL 1 /** * Forces pin pooling for all limits and control pins (with or without diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index ad9dc8eb1..772c12bd6 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -1996,10 +1996,8 @@ typedef uint16_t step_t; #error "DSS_CUTOFF_FREQ should not be set above 1/8th of the max step rate" #endif -#ifdef ENABLE_S_CURVE_ACCELERATION -#ifdef USE_LEGACY_STEP_INTERPOLATOR -#undef USE_LEGACY_STEP_INTERPOLATOR -#endif +#if S_CURVE_ACCELERATION_LEVEL > 3 +#error "invalid s-curve velocity profile setting" #endif #if (defined(KINEMATICS_MOTION_BY_SEGMENTS)) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 6a4b33b3a..41097d7d4 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -215,440 +215,54 @@ void itp_init(void) itp_sgm_clear(); } -#ifndef USE_LEGACY_STEP_INTERPOLATOR -void itp_run(void) +#if S_CURVE_ACCELERATION_LEVEL != 0 +// evals the point in a s-curve function +// receives a value between 0 and 1 +// outputs a value along a curve according to the scale +static float s_curve_function(float pt, float scale) { - // conversion vars - static uint32_t accel_until = 0; - static uint32_t deaccel_from = 0; - static float top_speed = 0; - static float exit_speed = 0; - static float feed_convert = 0; - static uint16_t accel_jumps = 0; - static uint16_t deaccel_jumps = 0; - float profile_steps_limit = 0; - float partial_distance = 0; - float avg_speed = 0; -#ifdef ENABLE_S_CURVE_ACCELERATION - static float current_accel = 0; - static float entry_speed = 0; - static float jerk_accel = 0; - static float jerk_deaccel = 0; -#endif - bool start_is_synched = false; - itp_segment_t *sgm = NULL; - - // creates segments and fills the buffer - while (!itp_sgm_is_full()) - { - if (cnc_get_exec_state(EXEC_ALARM)) - { - // on any active alarm exits - return; - } - - // no planner blocks has beed processed or last planner block was fully processed - if (itp_cur_plan_block == NULL) - { - // planner is empty or interpolator block buffer full. Nothing to be done - // itp block will never be full if itp segment is not full - if (planner_buffer_is_empty() /* || itp_blk_is_full()*/) - { - break; - } - // get the first block in the planner - itp_cur_plan_block = planner_get_block(); - // clear the data block - memset(&itp_blk_data[itp_blk_data_write], 0, sizeof(itp_block_t)); -#ifdef GCODE_PROCESS_LINE_NUMBERS - itp_blk_data[itp_blk_data_write].line = itp_cur_plan_block->line; -#endif - -// overwrites previous values -#ifdef ENABLE_BACKLASH_COMPENSATION - itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->planner_flags.bit.backlash_comp; -#endif - - itp_blk_data[itp_blk_data_write].dirbits = itp_cur_plan_block->dirbits; -#ifdef ENABLE_DUAL_DRIVE_AXIS -#ifdef DUAL_DRIVE0_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL0) ? STEP_DUAL0_MASK : 0; -#endif -#ifdef DUAL_DRIVE1_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL1) ? STEP_DUAL1_MASK : 0; -#endif -#endif - step_t total_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; - itp_blk_data[itp_blk_data_write].total_steps = total_steps << 1; - - feed_convert = itp_cur_plan_block->feed_conversion; - -#ifdef STEP_ISR_SKIP_IDLE - itp_blk_data[itp_blk_data_write].idle_axis = 0; -#endif -#ifdef STEP_ISR_SKIP_MAIN - itp_blk_data[itp_blk_data_write].main_stepper = itp_cur_plan_block->main_stepper; -#endif - for (uint8_t i = 0; i < STEPPER_COUNT; i++) - { - itp_blk_data[itp_blk_data_write].errors[i] = total_steps; - itp_blk_data[itp_blk_data_write].steps[i] = itp_cur_plan_block->steps[i] << 1; -#ifdef STEP_ISR_SKIP_IDLE - if (!itp_cur_plan_block->steps[i]) - { - itp_blk_data[itp_blk_data_write].idle_axis |= (1 << i); - } -#endif - } - - // flags block for recalculation of speeds - itp_needs_update = true; - - // checks for synched motion - if (itp_cur_plan_block->planner_flags.bit.synched) - { - start_is_synched = true; - } - } - - uint32_t remaining_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; - - sgm = &itp_sgm_data[itp_sgm_data_write]; - - // clear the data segment - memset(sgm, 0, sizeof(itp_segment_t)); - sgm->block = &itp_blk_data[itp_blk_data_write]; - - // if an hold is active forces to deaccelerate - if (cnc_get_exec_state(EXEC_HOLD)) - { - // forces deacceleration by overriding the profile juntion points - accel_until = remaining_steps; - deaccel_from = remaining_steps; - deaccel_jumps = 0xffff; - itp_needs_update = true; - } - else if (itp_needs_update) // forces recalculation of acceleration and deacceleration profiles - { - itp_needs_update = false; - float exit_speed_sqr = planner_get_block_exit_speed_sqr(); - float junction_speed_sqr = planner_get_block_top_speed(exit_speed_sqr); - float accel_inv = 1.0f / itp_cur_plan_block->acceleration; - top_speed = fast_flt_sqrt(junction_speed_sqr); - exit_speed = fast_flt_sqrt(exit_speed_sqr); - - accel_until = remaining_steps; - deaccel_from = 0; -#ifdef ENABLE_S_CURVE_ACCELERATION - current_accel = 0; -#endif - - if (junction_speed_sqr != itp_cur_plan_block->entry_feed_sqr) - { - float d = ABS(junction_speed_sqr - itp_cur_plan_block->entry_feed_sqr) * accel_inv; - d = fast_flt_div2(d); - accel_until -= truncf(d); -#ifdef ENABLE_S_CURVE_ACCELERATION - entry_speed = fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr); -#else - float entry_speed = fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr); -#endif - float t = ABS(top_speed - entry_speed); - t *= accel_inv; -#ifdef ENABLE_S_CURVE_ACCELERATION - jerk_accel = fast_flt_mul4(itp_cur_plan_block->acceleration / t); -#endif - accel_jumps = (uint16_t)truncf(t * INTERPOLATOR_FREQ); - } - - if (junction_speed_sqr > exit_speed_sqr) - { - float d = (junction_speed_sqr - exit_speed_sqr) * accel_inv; - d = fast_flt_div2(d); - deaccel_from = floorf(d); - exit_speed = fast_flt_sqrt(exit_speed_sqr); - float t = (top_speed - exit_speed); - t *= accel_inv; -#ifdef ENABLE_S_CURVE_ACCELERATION - jerk_deaccel = fast_flt_mul4(itp_cur_plan_block->acceleration / t); -#endif - deaccel_jumps = (uint16_t)truncf(t * INTERPOLATOR_FREQ); - } - } - - float current_speed = fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr); - float initial_speed = current_speed; - uint16_t segm_steps = 0; - do - { - // acceleration profile - if (remaining_steps > accel_until) - { - - // computes the traveled distance within a fixed amount of time - // this time is the reverse integrator frequency (t > INTERPOLATOR_DELTA_T) - // for constant acceleration or deceleration the traveled distance will be equal - // to the same distance traveled at a constant average speed given that - // avg_speed = 0.5 * (final_speed + initial_speed) - // where - // final_speed = initial_speed + acceleration * t; - // the travelled speed at interval t is aprox. given by - // final_distance = initial_distance + avg_speed * t - - if ((accel_jumps > 1)) - { -#ifdef ENABLE_S_CURVE_ACCELERATION - float prev_accel = current_accel; - float accel_delta = (INTERPOLATOR_DELTA_T * jerk_accel); - if ((entry_speed < top_speed) && (current_speed > fast_flt_div2(top_speed + entry_speed))) - { - accel_delta = -accel_delta; - } - - if ((entry_speed > top_speed) && (current_speed < fast_flt_div2(top_speed + entry_speed))) - { - accel_delta = -accel_delta; - } - current_accel += accel_delta; - // calcs the next average acceleration based on the jerk - float avg_accel = fast_flt_div2(current_accel + prev_accel); - // determines the acceleration profile (first half - convex, second half - concave) - current_speed += (current_speed < top_speed) ? (INTERPOLATOR_DELTA_T * avg_accel) : (-INTERPOLATOR_DELTA_T * avg_accel); -#else - current_speed += (current_speed < top_speed) ? (INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration) : (-INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration); -#endif - avg_speed = fast_flt_div2(current_speed + initial_speed); - partial_distance += avg_speed * INTERPOLATOR_DELTA_T; - accel_jumps--; - } - else - { - // if the number of jumps required are less than 1 just jumps to the final distance and applies the same principle - // in practice this translates to a Riemann sample with t < INTERPOLATOR_DELTA_T - - current_speed = top_speed; - partial_distance = remaining_steps - accel_until; - } - - profile_steps_limit = accel_until; - sgm->flags = (ITP_UPDATE_ISR | ITP_ACCEL); - } - else if (remaining_steps > deaccel_from) - { - // constant speed segment - sgm->flags = (remaining_steps == accel_until) ? (ITP_UPDATE_ISR | ITP_CONST) : ITP_CONST; - partial_distance += top_speed * INTERPOLATOR_DELTA_CONST_T; - profile_steps_limit = deaccel_from; - current_speed = top_speed; - initial_speed = top_speed; - } - else - { - if ((deaccel_jumps > 1)) - { -#ifdef ENABLE_S_CURVE_ACCELERATION - float prev_accel = current_accel; - float accel_delta = (INTERPOLATOR_DELTA_T * jerk_deaccel); - if ((current_speed < fast_flt_div2(top_speed + exit_speed))) - { - accel_delta = -accel_delta; - } - current_accel += accel_delta; - // calcs the next average acceleration based on the jerk - float avg_accel = fast_flt_div2(current_accel + prev_accel); - // determines the acceleration profile (first half - convex, second half - concave) - current_speed -= INTERPOLATOR_DELTA_T * avg_accel; -#else - current_speed -= INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration; -#endif - // prevents negative or zero speeds - float min_exit_speed = 2 * INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration; - bool flushsteps = false; - if (current_speed < min_exit_speed) - { - current_speed = min_exit_speed * remaining_steps; - flushsteps = true; - } - avg_speed = fast_flt_div2(current_speed + initial_speed); - partial_distance += avg_speed * INTERPOLATOR_DELTA_T; - deaccel_jumps--; - // speed reached 0. just flush remaining steps - if (flushsteps) - { - deaccel_jumps = 0; - partial_distance = remaining_steps; - } - } - else - { - // if the number of jumps required are less than 1 just jumps to the final distance and applies the same principle - // in practice this translates to a Riemann sample with t < INTERPOLATOR_DELTA_T - - current_speed = exit_speed; - partial_distance = remaining_steps; - sgm->flags = (ITP_UPDATE_ISR | ITP_DEACCEL); - } - - profile_steps_limit = 0; - } - - // computes how many steps it will perform at this speed and frame window - segm_steps = (uint16_t)lroundf(partial_distance); - } while (segm_steps == 0); - - avg_speed = fast_flt_div2(current_speed + initial_speed); - // float min_exit_speed = INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration; - // if (current_speed > min_exit_speed) - // { - // avg_speed = fast_flt_div2(current_speed + initial_speed); - // } - // else - // { - // // prevents slow exits - // avg_speed = fast_flt_div2(min_exit_speed); - // } - - // if computed steps exceed the remaining steps for the motion shortens the distance - if (segm_steps > (remaining_steps - profile_steps_limit)) - { - segm_steps = (uint16_t)(remaining_steps - profile_steps_limit); - } - -// The DSS (Dynamic Step Spread) algorithm reduces stepper vibration by spreading step distribution at lower speads. -// This is done by oversampling the Bresenham line algorithm by multiple factors of 2. -// This way stepping actions fire in different moments in order to reduce vibration caused by the stepper internal mechanics. -// This works in a similar way to Grbl's AMASS but has a modified implementation to minimize the processing penalty on the ISR and also take less static memory. -// DSS never loads the step generating ISR with a frequency above half of the absolute maximum frequency -#if (DSS_MAX_OVERSAMPLING != 0) - float dss_speed = avg_speed; - uint8_t dss = 0; - while (dss_speed < DSS_CUTOFF_FREQ && dss < DSS_MAX_OVERSAMPLING) - { - dss_speed = fast_flt_mul2(dss_speed); - dss++; - } - - if (dss != prev_dss) - { - sgm->flags = ITP_UPDATE_ISR; - } - sgm->next_dss = dss - prev_dss; - prev_dss = dss; - - // completes the segment information (step speed, steps) and updates the block - sgm->remaining_steps = segm_steps << dss; - dss_speed = MIN(dss_speed, g_settings.max_step_rate); - mcu_freq_to_clocks(dss_speed, &(sgm->timer_counter), &(sgm->timer_prescaller)); -#else - sgm->remaining_steps = segm_steps; - avg_speed = MIN(avg_speed, g_settings.max_step_rate); - mcu_freq_to_clocks(avg_speed, &(sgm->timer_counter), &(sgm->timer_prescaller)); +#ifdef S_CURVE_TANH + return 0.5 * (tanh(6 * pt - 3) + 1) * scale; +#endif +#if S_CURVE_ACCELERATION_LEVEL == 3 + // from this https://forum.duet3d.com/topic/4802/6th-order-jerk-controlled-motion-planning/95 + float pt_sqr = fast_flt_pow2(pt); + float k = 3.0f * (pt_sqr - 2.5f * pt) + 5.0f; + k = fast_flt_mul2(k) * pt_sqr * pt; + return k * scale; +#elif S_CURVE_ACCELERATION_LEVEL == 2 + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + return scale * (0.75f * (pt / (0.25f + ABS(pt))) + 0.5f); +#elif S_CURVE_ACCELERATION_LEVEL == 1 + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + return scale * ((pt / (0.5f + ABS(pt))) + 0.5f); #endif - - sgm->feed = avg_speed * feed_convert; -#if TOOL_COUNT > 0 - if (g_settings.laser_mode == LASER_PWM_MODE) - { - float top_speed_inv = fast_flt_invsqrt(itp_cur_plan_block->feed_sqr); - int16_t newspindle = planner_get_spindle_speed(MIN(1, avg_speed * top_speed_inv)); - - if ((prev_spindle != newspindle)) - { - prev_spindle = newspindle; - sgm->flags |= ITP_UPDATE_TOOL; - } - - sgm->spindle = newspindle; - } -#ifdef ENABLE_LASER_PPI - else if (g_settings.laser_mode & (LASER_PPI_VARPOWER_MODE | LASER_PPI_MODE)) - { - int16_t newspindle; - if (g_settings.laser_mode & LASER_PPI_VARPOWER_MODE) - { - float new_s = (float)ABS(planner_get_spindle_speed(1)); - new_s /= (float)g_settings.spindle_max_rpm; - if (g_settings.laser_mode & LASER_PPI_MODE) - { - float blend = g_settings.laser_ppi_mixmode_uswidth; - new_s = (new_s * blend) + (1.0f - blend); - } - - newspindle = (int16_t)((float)g_settings.laser_ppi_uswidth * new_s); - sgm->spindle = newspindle; - } - else - { - newspindle = g_settings.laser_ppi_uswidth; - sgm->spindle = newspindle; - } - - if ((prev_spindle != (int16_t)newspindle) && newspindle) - { - prev_spindle = (int16_t)newspindle; - sgm->flags |= ITP_UPDATE_TOOL; - } - } -#endif -#endif - remaining_steps -= segm_steps; - - if (remaining_steps == accel_until) // resets float additions error - { - // fixes rounding errors - current_speed = top_speed; - profile_steps_limit = deaccel_from; -#ifdef ENABLE_S_CURVE_ACCELERATION - current_accel = 0; -#endif - } - - itp_cur_plan_block->entry_feed_sqr = fast_flt_pow2(current_speed); - itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper] = remaining_steps; - - // checks for synched motion - if (itp_cur_plan_block->planner_flags.bit.synched) - { - // prevents subsequent sync starts - itp_cur_plan_block->planner_flags.bit.synched = 0; - sgm->flags |= ITP_SYNC; - } - - if (remaining_steps == 0) - { - itp_blk_buffer_write(); - itp_cur_plan_block = NULL; - planner_discard_block(); // discards planner block -#if (DSS_MAX_OVERSAMPLING != 0) - prev_dss = 0; -#endif - // accel_profile = 0; //no updates necessary to planner - // break; - } - - // finally write the segment - itp_sgm_buffer_write(); - } -#if TOOL_COUNT > 0 - // updated the coolant pins - tool_set_coolant(planner_get_coolant()); +} #endif - // starts the step isr if is stopped and there are segments to execute - // check if the start is controlled by synched motion before start - itp_start(start_is_synched); -} -#else void itp_run(void) { // conversion vars static uint32_t accel_until = 0; static uint32_t deaccel_from = 0; - static float junction_speed_sqr = 0; - static float half_speed_change = 0; - static bool initial_accel_negative = false; + static float junction_speed = 0; static float feed_convert = 0; - static bool const_speed = false; + static float partial_distance = 0; + static float t_acc_integrator = 0; + static float t_deac_integrator = 0; +#if S_CURVE_ACCELERATION_LEVEL != 0 + static float acc_step = 0; + static float acc_step_acum = 0; + static float acc_scale = 0; + static float acc_init_speed = 0; + + static float deac_step = 0; + static float deac_step_acum = 0; + static float deac_scale = 0; + +#endif itp_segment_t *sgm = NULL; bool start_is_synched = false; @@ -723,11 +337,6 @@ void itp_run(void) // flags block for recalculation of speeds itp_needs_update = true; - // in every new block speed update is needed - const_speed = false; - - half_speed_change = INTERPOLATOR_DELTA_T * itp_cur_plan_block->acceleration; - half_speed_change = fast_flt_div2(half_speed_change); // checks for synched motion if (itp_cur_plan_block->planner_flags.bit.synched) @@ -744,6 +353,8 @@ void itp_run(void) memset(sgm, 0, sizeof(itp_segment_t)); sgm->block = &itp_blk_data[itp_blk_data_write]; + float current_speed = fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr); + // if an hold is active forces to deaccelerate if (cnc_get_exec_state(EXEC_HOLD)) { @@ -756,16 +367,35 @@ void itp_run(void) { itp_needs_update = false; float exit_speed_sqr = planner_get_block_exit_speed_sqr(); - junction_speed_sqr = planner_get_block_top_speed(exit_speed_sqr); + float junction_speed_sqr = planner_get_block_top_speed(exit_speed_sqr); + + junction_speed = fast_flt_sqrt(junction_speed_sqr); + float accel_inv = 1.0f / itp_cur_plan_block->acceleration; accel_until = remaining_steps; deaccel_from = 0; if (junction_speed_sqr != itp_cur_plan_block->entry_feed_sqr) { - float accel_dist = ABS(junction_speed_sqr - itp_cur_plan_block->entry_feed_sqr) / itp_cur_plan_block->acceleration; + float accel_dist = ABS(junction_speed_sqr - itp_cur_plan_block->entry_feed_sqr) * accel_inv; accel_dist = fast_flt_div2(accel_dist); accel_until -= floorf(accel_dist); - initial_accel_negative = (junction_speed_sqr < itp_cur_plan_block->entry_feed_sqr); + float t = ABS(junction_speed - current_speed); +#if S_CURVE_ACCELERATION_LEVEL != 0 + acc_scale = t; + acc_step_acum = 0; + acc_init_speed = current_speed; +#endif + t *= accel_inv; + // slice up time in an integral number of periods (half with positive jerk and half with negative) + float slices_inv = 1.0f / ceilf(INTERPOLATOR_FREQ * t); + t_acc_integrator = t * slices_inv; +#if S_CURVE_ACCELERATION_LEVEL != 0 + acc_step = slices_inv; +#endif + if ((junction_speed_sqr < itp_cur_plan_block->entry_feed_sqr)) + { + t_acc_integrator = -t_acc_integrator; + } } // if entry speed already a junction speed updates it. @@ -776,14 +406,29 @@ void itp_run(void) if (junction_speed_sqr > exit_speed_sqr) { - float deaccel_dist = (junction_speed_sqr - exit_speed_sqr) / itp_cur_plan_block->acceleration; + float deaccel_dist = (junction_speed_sqr - exit_speed_sqr) * accel_inv; deaccel_dist = fast_flt_div2(deaccel_dist); deaccel_from = floorf(deaccel_dist); + // same as before t can be calculated using the normal ramp equation + float t = ABS(junction_speed - fast_flt_sqrt(exit_speed_sqr)); +#if S_CURVE_ACCELERATION_LEVEL != 0 + deac_scale = t; + deac_step_acum = 0; +#endif + t *= accel_inv; + // slice up time in an integral number of periods (half with positive jerk and half with negative) + float slices_inv = 1.0f / ceilf(INTERPOLATOR_FREQ * t); + t_deac_integrator = t * slices_inv; + +#if S_CURVE_ACCELERATION_LEVEL != 0 + deac_step = slices_inv; +#endif } } float speed_change; float profile_steps_limit; + float integrator; // acceleration profile if (remaining_steps > accel_until) { @@ -796,36 +441,52 @@ void itp_run(void) where (final_speed - initial_speed) = acceleration * INTERPOLATOR_DELTA_T; */ - speed_change = (!initial_accel_negative) ? half_speed_change : -half_speed_change; + integrator = t_acc_integrator; +#if S_CURVE_ACCELERATION_LEVEL != 0 + float acum = acc_step_acum; + acum += acc_step; + acc_step_acum = MIN(acum, 0.999f); + float new_speed = s_curve_function(acum, acc_scale) + acc_init_speed; + new_speed = (t_acc_integrator >= 0) ? (new_speed + acc_init_speed) : (acc_init_speed - new_speed); + speed_change = new_speed - current_speed; +#else + speed_change = integrator * itp_cur_plan_block->acceleration; +#endif + profile_steps_limit = accel_until; sgm->flags = ITP_UPDATE_ISR | ITP_ACCEL; - const_speed = false; } else if (remaining_steps > deaccel_from) { // constant speed segment speed_change = 0; profile_steps_limit = deaccel_from; - sgm->flags = (!const_speed) ? (ITP_UPDATE_ISR | ITP_CONST) : ITP_CONST; - if (!const_speed) - { - const_speed = true; - } + integrator = INTERPOLATOR_DELTA_T; + sgm->flags = (remaining_steps == accel_until) ? (ITP_UPDATE_ISR | ITP_CONST) : ITP_CONST; } else { - speed_change = -half_speed_change; + integrator = t_deac_integrator; +#if S_CURVE_ACCELERATION_LEVEL != 0 + float acum = deac_step_acum; + acum += deac_step; + deac_step_acum = MIN(acum, 0.999f); + float new_speed = junction_speed - s_curve_function(acum, deac_scale); + speed_change = new_speed - current_speed; +#else + speed_change = -(integrator * itp_cur_plan_block->acceleration); +#endif profile_steps_limit = 0; sgm->flags = ITP_UPDATE_ISR | ITP_DEACCEL; - const_speed = false; } - float current_speed = fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr); + // update speed at the end of segment + itp_cur_plan_block->entry_feed_sqr = MAX(0, fast_flt_pow2((current_speed + speed_change))); /* common calculations for all three profiles (accel, constant and deaccel) */ - current_speed += speed_change; + current_speed += fast_flt_div2(speed_change); if (current_speed <= 0) { @@ -838,15 +499,11 @@ void itp_run(void) current_speed = 0; } - float partial_distance = current_speed * INTERPOLATOR_DELTA_T; - - if (partial_distance < 1) - { - partial_distance = 1; - } + partial_distance += current_speed * integrator; // computes how many steps it will perform at this speed and frame window uint16_t segm_steps = (uint16_t)floorf(partial_distance); + partial_distance -= segm_steps; // if computed steps exceed the remaining steps for the motion shortens the distance if (segm_steps > (remaining_steps - profile_steps_limit)) @@ -854,26 +511,6 @@ void itp_run(void) segm_steps = (uint16_t)(remaining_steps - profile_steps_limit); } - if (speed_change) - { - float new_speed_sqr = itp_cur_plan_block->acceleration * segm_steps; - new_speed_sqr = fast_flt_mul2(new_speed_sqr); - if (speed_change > 0) - { - // calculates the final speed at the end of this position - new_speed_sqr += itp_cur_plan_block->entry_feed_sqr; - } - else - { - // calculates the final speed at the end of this position - new_speed_sqr = itp_cur_plan_block->entry_feed_sqr - new_speed_sqr; - new_speed_sqr = MAX(new_speed_sqr, 0); // avoids rounding errors since speed is always positive - } - current_speed = (fast_flt_sqrt(new_speed_sqr) + fast_flt_sqrt(itp_cur_plan_block->entry_feed_sqr)); - current_speed = fast_flt_div2(current_speed); - itp_cur_plan_block->entry_feed_sqr = new_speed_sqr; - } - // The DSS (Dynamic Step Spread) algorithm reduces stepper vibration by spreading step distribution at lower speads. // This is done by oversampling the Bresenham line algorithm by multiple factors of 2. // This way stepping actions fire in different moments in order to reduce vibration caused by the stepper internal mechanics. @@ -882,7 +519,7 @@ void itp_run(void) #if (DSS_MAX_OVERSAMPLING != 0) float dss_speed = current_speed; uint8_t dss = 0; - while (dss_speed < DSS_CUTOFF_FREQ && dss < DSS_MAX_OVERSAMPLING) + while (dss_speed < DSS_CUTOFF_FREQ && dss < DSS_MAX_OVERSAMPLING && segm_steps) { dss_speed = fast_flt_mul2(dss_speed); dss++; @@ -956,7 +593,7 @@ void itp_run(void) if (remaining_steps == accel_until) // resets float additions error { - itp_cur_plan_block->entry_feed_sqr = junction_speed_sqr; + itp_cur_plan_block->entry_feed_sqr = fast_flt_pow2(junction_speed); } itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper] = remaining_steps; @@ -990,7 +627,6 @@ void itp_run(void) // starts the step isr if is stopped and there are segments to execute itp_start(start_is_synched); } -#endif void itp_update(void) { diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 1f2bca997..9a22f8d2f 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -800,8 +800,8 @@ void protocol_send_pins_states(void) #define BRESENHAM_INFO "" #endif -#ifdef ENABLE_S_CURVE_ACCELERATION -#define DYNACCEL_INFO "S," +#if S_CURVE_ACCELERATION_LEVEL != 0 +#define DYNACCEL_INFO "S" STRGIFY(S_CURVE_ACCELERATION_LEVEL) "," #else #define DYNACCEL_INFO "" #endif From 3841692e82cde56871681eef44b60e3bee15378f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 09:17:24 +0100 Subject: [PATCH 041/168] reset defaults --- uCNC/cnc_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index de1858132..77ebdea83 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -435,7 +435,7 @@ extern "C" * * */ - #define S_CURVE_ACCELERATION_LEVEL 1 + #define S_CURVE_ACCELERATION_LEVEL 0 /** * Forces pin pooling for all limits and control pins (with or without From 7eea01687d1eeed0929856ce60ce233bed3f412c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 09:23:07 +0100 Subject: [PATCH 042/168] cleanup --- uCNC/src/interface/protocol.c | 6 ------ 1 file changed, 6 deletions(-) diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 9a22f8d2f..84f8bb64b 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -806,12 +806,6 @@ void protocol_send_pins_states(void) #define DYNACCEL_INFO "" #endif -#ifndef USE_LEGACY_STEP_INTERPOLATOR -#define ACCELALG_INFO "NI," -#else -#define ACCELALG_INFO "" -#endif - #ifdef INVERT_EMERGENCY_STOP #define INVESTOP_INFO "IE," #else From 9e86905bee941009a36d9f57e15b6453b8ec8189 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 13:53:29 +0100 Subject: [PATCH 043/168] new fast inversion and div methods - new fast inversion and div methods to speed feed calculations - s-curve uses custom inversion method (tuned) - fixed compilation --- tests/arduino_math/arduino_math.ino | 13 +++++++------ uCNC/src/core/interpolator.c | 23 +++++++++++++++++------ uCNC/src/core/motion_control.c | 12 ++++++------ uCNC/src/core/planner.c | 2 +- uCNC/src/interface/protocol.c | 2 +- uCNC/src/utils.h | 20 +++++++++++++++++++- 6 files changed, 51 insertions(+), 21 deletions(-) diff --git a/tests/arduino_math/arduino_math.ino b/tests/arduino_math/arduino_math.ino index 1babef98d..4087560ec 100644 --- a/tests/arduino_math/arduino_math.ino +++ b/tests/arduino_math/arduino_math.ino @@ -31,7 +31,8 @@ typedef union #define ROUND roundf(a / b) #define ROUNDA roundf(a) #define CAST (int32_t)a -#define INV 1 / a +#define INV 1 / (a*0.001f) +#define INV2 ({flt_t res; res.f=a*0.001f; res.i = (0x7eef1aa0 - res.i);res.f;}) #define DBL 2 * a #define SQRT sqrtf(a) #define COS cos(a) @@ -65,14 +66,14 @@ uint16_t clocks = TCNT1;TCCR1B=0;\ Serial.println(#TYPE);\ PRINT_OP(OP);\ Serial.print("a = ");\ -Serial.println((uint32_t)a);\ +Serial.println(a);\ Serial.print("b = ");\ -Serial.println((uint32_t)b);\ +Serial.println(b);\ if(a ");\ else \ Serial.print("res < ");\ -Serial.println((uint32_t) res);\ +Serial.println(res);\ Serial.print("Elapsed (clocks): ");\ Serial.println(clocks-offset);\ } @@ -116,8 +117,8 @@ void setup() { DO_OP(float, float, 0,1000,TANH); DO_OP(float, float, 0,1000,SCURVE); DO_OP(float, float, 0,1000,BEZIER); - DO_OP(float, float, 0,10000,DIV); - DO_OP(float, float, 0,10000,FLT_BY4); + DO_OP(float, float, 0,1000,INV); + DO_OP(float, float, 0,1000,INV2); /*Serial.println("testes"); DO_OP(float, 0,10000,ROUND); DO_OP(float, 0,10000,ROUNDA); diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 41097d7d4..ef8378883 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -233,11 +233,19 @@ static float s_curve_function(float pt, float scale) #elif S_CURVE_ACCELERATION_LEVEL == 2 // from this https://en.wikipedia.org/wiki/Sigmoid_function pt -= 0.5f; - return scale * (0.75f * (pt / (0.25f + ABS(pt))) + 0.5f); + // optimized fast inverse aproximation + float k = (0.25f + ABS(pt)); + int32_t *i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + return scale * (0.75f * pt * k + 0.5f); #elif S_CURVE_ACCELERATION_LEVEL == 1 // from this https://en.wikipedia.org/wiki/Sigmoid_function pt -= 0.5f; - return scale * ((pt / (0.5f + ABS(pt))) + 0.5f); + // optimized fast inverse aproximation + float k = (0.5f + ABS(pt)); + int32_t *i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + return scale * (pt * k + 0.5f); #endif } #endif @@ -370,7 +378,7 @@ void itp_run(void) float junction_speed_sqr = planner_get_block_top_speed(exit_speed_sqr); junction_speed = fast_flt_sqrt(junction_speed_sqr); - float accel_inv = 1.0f / itp_cur_plan_block->acceleration; + float accel_inv = fast_flt_inv(itp_cur_plan_block->acceleration); accel_until = remaining_steps; deaccel_from = 0; @@ -387,7 +395,7 @@ void itp_run(void) #endif t *= accel_inv; // slice up time in an integral number of periods (half with positive jerk and half with negative) - float slices_inv = 1.0f / ceilf(INTERPOLATOR_FREQ * t); + float slices_inv = fast_flt_inv(ceilf(INTERPOLATOR_FREQ * t)); t_acc_integrator = t * slices_inv; #if S_CURVE_ACCELERATION_LEVEL != 0 acc_step = slices_inv; @@ -417,7 +425,7 @@ void itp_run(void) #endif t *= accel_inv; // slice up time in an integral number of periods (half with positive jerk and half with negative) - float slices_inv = 1.0f / ceilf(INTERPOLATOR_FREQ * t); + float slices_inv = fast_flt_inv(ceilf(INTERPOLATOR_FREQ * t)); t_deac_integrator = t * slices_inv; #if S_CURVE_ACCELERATION_LEVEL != 0 @@ -481,7 +489,10 @@ void itp_run(void) } // update speed at the end of segment - itp_cur_plan_block->entry_feed_sqr = MAX(0, fast_flt_pow2((current_speed + speed_change))); + if (speed_change) + { + itp_cur_plan_block->entry_feed_sqr = MAX(0, fast_flt_pow2((current_speed + speed_change))); + } /* common calculations for all three profiles (accel, constant and deaccel) diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index d898aac17..0ebf0885e 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -361,7 +361,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) // calculates the linear distance traveled line_dist = fast_flt_sqrt(line_dist); - float inv_dist = 1.0f / line_dist; + float inv_dist = fast_flt_inv(line_dist); // feed values float max_feed = FLT_MAX; @@ -382,9 +382,9 @@ uint8_t mc_line(float *target, motion_data_t *block_data) dir_vect[i] = normal_vect; normal_vect = ABS(normal_vect); // denormalize max feed rate for each axis - float denorm_param = g_settings.max_feed_rate[i] / normal_vect; + float denorm_param = fast_flt_div(g_settings.max_feed_rate[i], normal_vect); max_feed = MIN(max_feed, denorm_param); - denorm_param = g_settings.acceleration[i] / normal_vect; + denorm_param = fast_flt_div(g_settings.acceleration[i], normal_vect); max_accel = MIN(max_accel, denorm_param); } max_feed *= inv_dist; @@ -399,7 +399,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) // modify PPI settings according o the S value if (g_settings.laser_mode & LASER_PPI_MODE) { - float laser_ppi_scale = (float)block_data->spindle / (float)g_settings.spindle_max_rpm; + float laser_ppi_scale = fast_flt_div((float)block_data->spindle, (float)g_settings.spindle_max_rpm); if (g_settings.laser_mode & LASER_PPI_VARPOWER_MODE) { float blend = g_settings.laser_ppi_mixmode_ppi; @@ -434,7 +434,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) block_data->feed = MIN(max_feed, step_feed); block_data->max_feed = max_feed; - block_data->feed_conversion = line_dist / feed_convert_to_steps_per_sec; + block_data->feed_conversion = fast_flt_div(line_dist, feed_convert_to_steps_per_sec); #ifdef MOTION_SEGMENTED // this contains a motion. Any tool update will be done here @@ -866,7 +866,7 @@ uint8_t mc_probe(float *target, uint8_t flags, motion_data_t *block_data) io_enable_probe(); mcu_probe_changed_cb(); mc_line(target, block_data); - + do { if (io_get_probe() ^ (flags & 0x01)) diff --git a/uCNC/src/core/planner.c b/uCNC/src/core/planner.c index e518c3c60..fd36c298a 100644 --- a/uCNC/src/core/planner.c +++ b/uCNC/src/core/planner.c @@ -150,7 +150,7 @@ void planner_add_line(motion_data_t *block_data) // this way the output will be between 0 Date: Tue, 25 Jul 2023 14:47:48 +0100 Subject: [PATCH 044/168] fast math functions error tunning --- uCNC/src/utils.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index d389626ee..431d32891 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -114,7 +114,7 @@ extern "C" flt_t res; \ res.f = (x); \ if (res.i) \ - res.i = (0x1fbeecc0 + (res.i >> 1)); \ + res.i = ((res.i >> 1) - 0xe041a9fb); \ res.f; \ }) // fast_flt_invsqrt takes about 18 clock cycles on AVR instead of +/-960 if using normal 1/sqrt (x53 faster). The error of this shortcut should be under 4~5%. @@ -132,7 +132,7 @@ extern "C" res.f = ABS((x)); \ if (res.f != 0) \ { \ - res.i = ((res.i << 1) - 0x3f7adaba); \ + res.i = ((res.i << 1) + 0xc0858106); \ if (res.i < 0) \ res.i = 0; \ } \ From c0c96f164028e9e110b97138fac7cfd66657c8b3 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 15:02:37 +0100 Subject: [PATCH 045/168] Update cnc_hal_config_helper.h --- uCNC/src/cnc_hal_config_helper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 772c12bd6..5faec073a 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -1996,7 +1996,7 @@ typedef uint16_t step_t; #error "DSS_CUTOFF_FREQ should not be set above 1/8th of the max step rate" #endif -#if S_CURVE_ACCELERATION_LEVEL > 3 +#if ((S_CURVE_ACCELERATION_LEVEL < 0) || (S_CURVE_ACCELERATION_LEVEL > 3)) #error "invalid s-curve velocity profile setting" #endif From 4bb973b19e101fa9aebb511d51ae3ab8fb540ace Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 15:23:30 +0100 Subject: [PATCH 046/168] updated changelog --- CHANGELOG.md | 18 ++++++++++++++++++ uCNC/src/cnc_build.h | 2 +- 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 29101888c..8fbba2897 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,6 +8,23 @@ # Changelog +## [1.8.0-rc] - unreleased + +### Added + +- added status report extender callcack (#454) +- added Plasma THC velocity anty-dive (#456) + +### Changed + +- Unified interpolator run function and new S-Curve acceleration profiles (#458) +- implemented Plasma THC status report callback (#454) +- Plasma THC tool update via PID callback (#453) + +### Fixed + +- step output generation from beta (#457) + ## [1.8.0-beta] - 20-07-2023 ### Added @@ -1271,6 +1288,7 @@ Version 1.1.0 comes with many added features and improvements over the previous ### Initial release +[1.8.0-rc]: https://github.com/Paciente8159/uCNC/releases/tag/v1.8.0-rc [1.8.0-beta]: https://github.com/Paciente8159/uCNC/releases/tag/v1.8.0-beta [1.7.3]: https://github.com/Paciente8159/uCNC/releases/tag/v1.7.3 [1.7.2]: https://github.com/Paciente8159/uCNC/releases/tag/v1.7.2 diff --git a/uCNC/src/cnc_build.h b/uCNC/src/cnc_build.h index d18e8a124..041a2d012 100644 --- a/uCNC/src/cnc_build.h +++ b/uCNC/src/cnc_build.h @@ -25,7 +25,7 @@ extern "C" #endif #define CNC_MAJOR_MINOR_VERSION "1.8" -#define CNC_PATCH_VERSION ".0-beta" +#define CNC_PATCH_VERSION ".0-rc" #define CNC_VERSION CNC_MAJOR_MINOR_VERSION CNC_PATCH_VERSION From 0f0757ee489df27a480113679149394a2faf4267 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 25 Jul 2023 20:11:59 +0100 Subject: [PATCH 047/168] configurable s-curve option --- uCNC/cnc_config.h | 13 +++-- uCNC/src/cnc_hal_config_helper.h | 6 +-- uCNC/src/core/interpolator.c | 74 ++++++++++++++++++++++++---- uCNC/src/hal/tools/tools/laser_ppi.c | 16 ++---- uCNC/src/interface/protocol.c | 3 ++ uCNC/src/interface/settings.c | 10 +++- uCNC/src/interface/settings.h | 3 ++ 7 files changed, 94 insertions(+), 31 deletions(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 77ebdea83..81382af12 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -427,11 +427,14 @@ extern "C" * Performs motions with variable acceleration (trapezoidal speed profile * with rounded speed transition between accel/deaccel and constant speed) * instead of constant acceleration (trapezoidal speed profile) - * - * 0 - disabled - * 1 - mild profile (smaller mid slope and higher initial and exit slopes) - * 2 - medium profile (medium mid slope and medium initial and exit slopes) - * 3 - agressive (higher mid slope and smaller initial and exit slopes - uses bezier 5th order) + * + * -1 - selectable via setting $14 + * 0 - disabled + * 1 - mild profile (smaller mid slope and higher initial and exit slopes) + * 2 - medium profile (medium mid slope and medium initial and exit slopes) + * 3 - stron profile (high mid slope and medium initial and exit slopes) + * 4 - agressive (higher mid slope and smaller initial and exit slopes - uses bezier 5th order) + * 5 - agressive2 (higher mid slope and smaller initial and exit slopes - uses tanh curve) * * */ diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 5faec073a..8dd5dc677 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -24,7 +24,7 @@ extern "C" { #endif -//undefined pin +// undefined pin #define UNDEF_PIN 0 // assert pin (io or extended) #define ASSERT_PIN(X) (X != 0) @@ -1996,7 +1996,7 @@ typedef uint16_t step_t; #error "DSS_CUTOFF_FREQ should not be set above 1/8th of the max step rate" #endif -#if ((S_CURVE_ACCELERATION_LEVEL < 0) || (S_CURVE_ACCELERATION_LEVEL > 3)) +#if ((S_CURVE_ACCELERATION_LEVEL < -1) || (S_CURVE_ACCELERATION_LEVEL > 5)) #error "invalid s-curve velocity profile setting" #endif @@ -2120,7 +2120,7 @@ typedef uint16_t step_t; #ifdef ENABLE_PLASMA_THC -//forces modes +// forces modes #ifndef ENABLE_TOOL_PID_CONTROLLER #define ENABLE_TOOL_PID_CONTROLLER #endif diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index ef8378883..1f4cbe664 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -219,17 +219,25 @@ void itp_init(void) // evals the point in a s-curve function // receives a value between 0 and 1 // outputs a value along a curve according to the scale -static float s_curve_function(float pt, float scale) +static float s_curve_function(float pt) { -#ifdef S_CURVE_TANH - return 0.5 * (tanh(6 * pt - 3) + 1) * scale; -#endif -#if S_CURVE_ACCELERATION_LEVEL == 3 +#if S_CURVE_ACCELERATION_LEVEL == 5 + return 0.5 * (tanh(6 * pt - 3) + 1); +#elif S_CURVE_ACCELERATION_LEVEL == 4 // from this https://forum.duet3d.com/topic/4802/6th-order-jerk-controlled-motion-planning/95 float pt_sqr = fast_flt_pow2(pt); float k = 3.0f * (pt_sqr - 2.5f * pt) + 5.0f; k = fast_flt_mul2(k) * pt_sqr * pt; - return k * scale; + return k; +#elif S_CURVE_ACCELERATION_LEVEL == 3 + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + // optimized fast inverse aproximation + float k = (0.15f + ABS(pt)); + int32_t *i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + k = (0.65f * pt * k + 0.5f); + return CLAMP(0, k, 1); #elif S_CURVE_ACCELERATION_LEVEL == 2 // from this https://en.wikipedia.org/wiki/Sigmoid_function pt -= 0.5f; @@ -237,7 +245,8 @@ static float s_curve_function(float pt, float scale) float k = (0.25f + ABS(pt)); int32_t *i = (int32_t *)&k; *i = 0x7EEF1AA0 - *i; - return scale * (0.75f * pt * k + 0.5f); + k = (0.75f * pt * k + 0.5f); + return CLAMP(0, k, 1); #elif S_CURVE_ACCELERATION_LEVEL == 1 // from this https://en.wikipedia.org/wiki/Sigmoid_function pt -= 0.5f; @@ -245,7 +254,52 @@ static float s_curve_function(float pt, float scale) float k = (0.5f + ABS(pt)); int32_t *i = (int32_t *)&k; *i = 0x7EEF1AA0 - *i; - return scale * (pt * k + 0.5f); + k = (pt * k + 0.5f); + return CLAMP(0, k, 1); +#elif S_CURVE_ACCELERATION_LEVEL == -1 + float k, pt_sqr; + int32_t *i; + switch (g_settings.s_curve_profile) + { + case 1: + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + // optimized fast inverse aproximation + k = (0.5f + ABS(pt)); + i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + k = (pt * k + 0.5f); + return CLAMP(0, k, 1); + case 2: + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + // optimized fast inverse aproximation + k = (0.25f + ABS(pt)); + i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + k = (0.75f * pt * k + 0.5f); + return CLAMP(0, k, 1); + case 3: + // from this https://en.wikipedia.org/wiki/Sigmoid_function + pt -= 0.5f; + // optimized fast inverse aproximation + k = (0.15f + ABS(pt)); + i = (int32_t *)&k; + *i = 0x7EEF1AA0 - *i; + k = (0.65f * pt * k + 0.5f); + return CLAMP(0, k, 1); + case 4: + // from this https://forum.duet3d.com/topic/4802/6th-order-jerk-controlled-motion-planning/95 + pt_sqr = fast_flt_pow2(pt); + k = 3.0f * (pt_sqr - 2.5f * pt) + 5.0f; + k = fast_flt_mul2(k) * pt_sqr * pt; + return k; + case 5: + return 0.5 * (tanh(6 * pt - 3) + 1); + default: + // defaults to linear + return pt; + } #endif } #endif @@ -454,7 +508,7 @@ void itp_run(void) float acum = acc_step_acum; acum += acc_step; acc_step_acum = MIN(acum, 0.999f); - float new_speed = s_curve_function(acum, acc_scale) + acc_init_speed; + float new_speed = acc_scale * s_curve_function(acum) + acc_init_speed; new_speed = (t_acc_integrator >= 0) ? (new_speed + acc_init_speed) : (acc_init_speed - new_speed); speed_change = new_speed - current_speed; #else @@ -479,7 +533,7 @@ void itp_run(void) float acum = deac_step_acum; acum += deac_step; deac_step_acum = MIN(acum, 0.999f); - float new_speed = junction_speed - s_curve_function(acum, deac_scale); + float new_speed = junction_speed - deac_scale * s_curve_function(acum); speed_change = new_speed - current_speed; #else speed_change = -(integrator * itp_cur_plan_block->acceleration); diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 2844954a0..2e45763c1 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -23,6 +23,10 @@ #include #include +#ifndef LASER_PPI +#define LASER_PPI PWM0 +#endif + // #define ENABLE_COOLANT #ifdef ENABLE_COOLANT #ifndef LASER_PPI_AIR_ASSIST @@ -42,12 +46,6 @@ static void startup_code(void) #else io_set_output(LASER_PPI); #endif -#elif ASSERT_PIN_EXTENDER(LASER_PPI) -#ifndef INVERT_LASER_PPI_LOGIC - io_set_output(LASER_PPI, false); -#else - io_set_output(LASER_PPI, true); -#endif #endif g_settings.laser_mode |= LASER_PPI_MODE; parser_config_ppi(); @@ -61,12 +59,6 @@ static void shutdown_code(void) #else io_set_output(LASER_PPI); #endif -#elif ASSERT_PIN_EXTENDER(LASER_PPI) -#ifndef INVERT_LASER_PPI_LOGIC - io_set_output(LASER_PPI, false); -#else - io_set_output(LASER_PPI, true); -#endif #endif // restore laser mode g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index a91b9cdac..bf22c0586 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -624,6 +624,9 @@ void protocol_send_cnc_settings(void) protocol_send_gcode_setting_line_flt(11, g_settings.g64_angle_factor); protocol_send_gcode_setting_line_flt(12, g_settings.arc_tolerance); protocol_send_gcode_setting_line_int(13, g_settings.report_inches); +#if S_CURVE_ACCELERATION_LEVEL == -1 + protocol_send_gcode_setting_line_int(14, g_settings.s_curve_profile); +#endif protocol_send_gcode_setting_line_int(20, g_settings.soft_limits_enabled); protocol_send_gcode_setting_line_int(21, g_settings.hard_limits_enabled); protocol_send_gcode_setting_line_int(22, g_settings.homing_enabled); diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index b41a61145..90b97714c 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -97,6 +97,9 @@ const settings_t __rom__ default_settings = .g64_angle_factor = DEFAULT_G64_FACTOR, .arc_tolerance = DEFAULT_ARC_TOLERANCE, .report_inches = DEFAULT_REPORT_INCHES, +#if S_CURVE_ACCELERATION_LEVEL == -1 + .s_curve_profile = 0, +#endif .soft_limits_enabled = DEFAULT_SOFT_LIMITS_ENABLED, .hard_limits_enabled = DEFAULT_HARD_LIMITS_ENABLED, .homing_enabled = DEFAULT_HOMING_ENABLED, @@ -370,6 +373,11 @@ uint8_t settings_change(setting_offset_t id, float value) case 13: g_settings.report_inches = value1; break; +#if S_CURVE_ACCELERATION_LEVEL == -1 + case 14: + g_settings.s_curve_profile = CLAMP(0, value8, 5); + break; +#endif case 20: if (!g_settings.homing_enabled && value1) { @@ -618,7 +626,7 @@ uint16_t settings_register_external_setting(uint8_t size) setting_offset += size + 1; // include crc return new_offset; #else - #warning "External/extension settings storing is disabled" +#warning "External/extension settings storing is disabled" return UINT16_MAX; #endif } diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index 222cb43ab..b67f2656f 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -46,6 +46,9 @@ extern "C" // juntion deviation is automatic and always on float arc_tolerance; bool report_inches; +#if S_CURVE_ACCELERATION_LEVEL == -1 + uint8_t s_curve_profile; +#endif bool soft_limits_enabled; bool hard_limits_enabled; bool homing_enabled; From 6afa5cea9a253c4d30a1580071141613d889ca10 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 11:10:55 +0100 Subject: [PATCH 048/168] added tool creation readme --- uCNC/src/hal/tools/README.md | 126 +++++++++++++++++++++++++++++++++++ uCNC/src/hal/tools/tool.h | 18 ++--- 2 files changed, 135 insertions(+), 9 deletions(-) create mode 100644 uCNC/src/hal/tools/README.md diff --git a/uCNC/src/hal/tools/README.md b/uCNC/src/hal/tools/README.md new file mode 100644 index 000000000..b07567dff --- /dev/null +++ b/uCNC/src/hal/tools/README.md @@ -0,0 +1,126 @@ +

+ +

+ + +# µCNC +µCNC - Universal CNC firmware for microcontrollers + +# Adding custom tools to µCNC + +µCNC tool is a bit different from modules but it's equally straight forward. +tool.h file sets a struct with a set of function pointer that can be defined to create a custom tool. In the end you just need to add the tool in cnc_hal_config.h file by attributing it to a TOOL. + +## µCNC tool structure + +The tool struct is like this: + +``` + typedef void (*tool_func)(void); + typedef int16_t (*tool_range_speed_func)(int16_t); + typedef uint16_t (*tool_get_speed_func)(void); + typedef void (*tool_set_speed_func)(int16_t); + typedef void (*tool_coolant_func)(uint8_t); + + typedef struct + { + tool_func startup_code; /*runs any custom code after the tool is loaded*/ + tool_func shutdown_code; /*runs any custom code before the tool is unloaded*/ + tool_func pid_update; /*runs de PID update code needed to keep the tool at the desired speed/power*/ + tool_range_speed_func range_speed; /*converts core speed to tool speed*/ + tool_get_speed_func get_speed; /*gets the tool speed/power (converts from tool speed to core speed)*/ + tool_set_speed_func set_speed; /*sets the speed/power of the tool*/ + tool_coolant_func set_coolant; /*enables/disables the coolant*/ + } tool_t; +``` + +## µCNC creating a dummy tool + +This is an example for creating a dummy tool. Again all current tools are inside the `src/hal/tool/tools` directory but it's not mandatory. It's just a matter of having them organized. + +Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code + +__NOTE:__ You don't need to define all functions for the tool. Just the ones you need on your tool. + +``` +//include cnc.h relative path +#include "src/cnc.h" + +//may be needed (contains the definition of bool) +#include + +static void dummy_tool_startup_code(void) +{ + // run code on tool loading + // can be anything. Configuring IO, special motions, changing states, etc... +} + +static void dummy_tool_shutdown_code(void) +{ + // run code on tool unloading + // can be anything. Configuring IO, special motions, changing states, etc... +} + +static void dummy_tool_set_speed(int16_t value) +{ + // if M3 the value will be positive + // if M4 the value will be negative + // a value of 0 is for an absolute stop + + // this value is received in tool IO units (for PWM should be between -255(inverse direction-M4) and 255(forward direction-M3)) + + // with this value some operation must be done in order to update the tool +} + +static int16_t dummy_tool_range_speed(int16_t value) +{ + // in this function you do all your calculations to convert from GCode S speed to tool IO control speed (to PWM value or other for example) + + // if M3 the value will be positive + // if M4 the value will be negative + + // do something to value and return the converted value, that can be either a convertion formula or a lookup table + + return value; +} + +static uint16_t dummy_tool_get_speed(void) +{ + // this can return the tool real speed value is some sort of sensor is present + // this should return the value of the sensor converted to S units + return 0; +} + +static void dummy_tool_pid_update(void) +{ + // you can do anything here + // for example read the tool sensor and based on that modify the tool speed or the axis speed to match sync motions +} + +// declares the tool in ROM +// all unused function pointer must be initialized to NULL to prevent unexpected behavior + +// this is an example + +const tool_t dummy_tool = { + .startup_code = &dummy_tool_startup_code, // pointer to startup function + .shutdown_code = NULL, // not used (empty pointer) + .pid_update = &dummy_tool_pid_update, // pointer to pid function + .range_speed = &dummy_tool_range_speed, // pointer to range function + .get_speed = &dummy_tool_get_speed, // pointer to custom get_speed function + .set_speed = &dummy_tool_set_speed, // pointer to set_speed function + .set_coolant = NULL // not used (empty pointer) +}; + +``` + +That's it. +The only thing left is to add the tool in cnc_hal_config.h +Lets say you have setup 5 tools in total and this will be TOOL5 + +Open uCNC.ino +add this to cnc_hal_config.h + +`#define TOOL5 dummy_tool` + +That's it. You can use your tool via `M6 T5` command. diff --git a/uCNC/src/hal/tools/tool.h b/uCNC/src/hal/tools/tool.h index e747e551f..585d9974c 100644 --- a/uCNC/src/hal/tools/tool.h +++ b/uCNC/src/hal/tools/tool.h @@ -47,15 +47,15 @@ extern "C" tool_coolant_func set_coolant; /*enables/disables the coolant*/ } tool_t; - void tool_init(void); - void tool_change(uint8_t tool); - void tool_pid_update(void); - int16_t tool_get_setpoint(void); - int16_t tool_range_speed(int16_t value); - uint16_t tool_get_speed(void); - void tool_set_speed(int16_t value); - void tool_set_coolant(uint8_t value); - void tool_stop(void); + void tool_init(void); // initializes tool inside µCNC + void tool_change(uint8_t tool); // executes a tool change µCNC. This runs the shutdown code of the current tool and then runs the startup code of the next tool + void tool_pid_update(void); // if tool PID option is enabled this function is called in the main loop to update the tool or make some adjustment + int16_t tool_get_setpoint(void); // return the current tool setpoint. That is the value set with S parameter in gcode + int16_t tool_range_speed(int16_t value); // this function is always called when you send an M3, M4 or S command. It runs before tool_set_speed function and converts from S to whatever tool value needed (for example if using PWM will convert to a PWM value 0-255) + uint16_t tool_get_speed(void); // this function returns the current tool speed. Always returns the setpoint value, unless the tool has a custom get_speed function (for example to return the true speed of a feedback sensor) + void tool_set_speed(int16_t value); // this sets the tool speed. The value passed to this function is the actual IO value needed (for example a PWM value). On M5 or tool shutdown, this value is always 0. + void tool_set_coolant(uint8_t value); // this gets a maks with the coolant outputs to enable(1) or disable(0) + void tool_stop(void); // this stops the tool and coolant #ifdef __cplusplus } From 3ad0fa14c28f31c515aa75234fbf94aac84dd628 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 15:37:17 +0100 Subject: [PATCH 049/168] Create README.md --- uCNC/src/modules/README.md | 267 +++++++++++++++++++++++++++++++++++++ 1 file changed, 267 insertions(+) create mode 100644 uCNC/src/modules/README.md diff --git a/uCNC/src/modules/README.md b/uCNC/src/modules/README.md new file mode 100644 index 000000000..2bfc4ca29 --- /dev/null +++ b/uCNC/src/modules/README.md @@ -0,0 +1,267 @@ +

+ +

+ + +# µCNC +µCNC - Universal CNC firmware for microcontrollers + +# Adding custom modules to µCNC + +__IMPORTANT NOTE__: _Version 1.7 implemented breaking changes to modules declarations. Please check the modules releases to get the right modules for your version [repository](https://github.com/Paciente8159/uCNC-modules)_ + +__NOTE__: _Version 1.4.6 implemented changes to module initialization. Also additional modules were moved to a new [repository](https://github.com/Paciente8159/uCNC-modules)_ + +µCNC has implemented a module system that allows the user to perform custom actions that get executed in an event/delegate fashion style similar to what is done with C#. Multiple callbacks functions can be attached to the same event. +These modules can be quite useful and perform several things like adding custom custom gcodes to perform actions, or modifying IO states if a given condition is verified. +µCNC already has a few useful modules like PID controller, Encoder module, TMC drivers support and custom G/M code support. + +## µCNC existing events/delegates + +Without having to modify core code inside µCNC it is possible to listen to several already existing events. Here is a list of current events: + +__NOTE__: Not all event hooks might be listed here. To find all available event hooks declarations, do a search on all files (on VSCode in Windows it's Ctrl+Shift+F) of the project of `DECL_EVENT_HANDLER`. You can also search for the `EVENT_INVOKE` to see what argument is being passed to the event handler. + +| Event name | Argument | Enable option | Description | +| --- | --- | --- | --- | +| gcode_parse | gcode_parse_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command was not captured/understood by the core parser is trying to parse the code. Arg is a pointer to a gcode_parse_args_t struct | +| gcode_exec | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command that was not captured/understood by the core parser is intercepted by gcode_parse event an recognized as an extended gcode command. Arg is a pointer to a gcode_exec_args_t struct | +| gcode_exec_modifier | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires prior to gcode execution phase and can be used to modify the parsed command or execute custom actions or issue motions before gcode execution. Arg is a pointer to a gcode_exec_args_t struct | +| gcode_before_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires before a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | +| gcode_after_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires after a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | +| grbl_cmd | grbl_cmd_args_t* | ENABLE_PARSER_MODULES | Fires when a custom/unknown '$' grbl type command is received. Arg is a pointer to a grbl_cmd_args_t struct | +| parse_token | NULL | ENABLE_PARSER_MODULES | Fires when a custom/unknown token/char is received for further processing | +| parser_get_modes | uint8_t * | ENABLE_PARSER_MODULES | Fires when $G command is issued and the active modal states array is being requested (can be used to modify the active modes with extended gcodes). Arg is a pointer to an uint8_t array with the parser motion groups current values | +| parser_reset | NULL | ENABLE_PARSER_MODULES | Fires on parser reset | +| cnc_reset | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when µCNC resets | +| rtc_tick | NULL | ENABLE_MAIN_LOOP_MODULES | Fires every millisecond. This code runs inside the RTC interrupt. Do not run long routines here. This is for time critical (periodic) tasks. | +| cnc_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main loop running. Any repeating task should be hooked here | +| cnc_io_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main IO loop running. This is similar to cnc_dotasks, the main difference is that this task will run also during delays | +| cnc_stop | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when a halt/stop condition is triggered | +| cnc_exec_cmd_error | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when an invalid command is received | +| settings_change | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when a $ setting is changed. Arg is a pointer to a settings_args_t struct | +| settings_load | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are loaded from memory. Arg is a pointer to a settings_args_t struct | +| settings_save | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are saved into memory. Arg is a pointer to a settings_args_t struct | +| settings_erase | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are erased/reset. Arg is a pointer to a settings_args_t struct | +| protocol_send_status | NULL | - | Fires when printing the status message | +| protocol_send_cnc_settings | NULL | ENABLE_SETTINGS_MODULES | Fires when printing settings values | +| protocol_send_cnc_info | NULL | ENABLE_SYSTEM_INFO | Fires when printing response to $I command | +| protocol_send_pins_states | NULL | ENABLE_IO_MODULES | Fires when $P command is printing the pins states | +| protocol_send_gcode_modes | NULL | ENABLE_PARSER_MODULES | Fires when $G printing modals states message | +| input_change | uint8_t* | ENABLE_IO_MODULES | Fires when a generic input (DIN0-7) pin changes state. Args is an uint8_t array with 2 values. The first is the inputs current values mask and the second a maks with the inputs that changed since the last time | +| probe_enable | NULL | ENABLE_IO_MODULES | Fires when the probe is enabled | +| probe_disable | NULL | ENABLE_IO_MODULES | Fires when the probe is disabled | +| mc_line_segment | NULL | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner | +| mc_home_axis_start | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is starting. Pointer to homing_status_t struct with homming information | +| mc_home_axis_finish | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is finnished | +| mc_line_segment | motion_data_t* | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner. Arg is a pointer to a motion_data_t struct with the current motion block data | + +Each of these events exposes a delegate and and event that have the following naming convention: + +`_delegate` -> type of a function pointer that defines the function prototype to be called by the event handler +`_event` -> pointer to the event that contains all the subscribers that are going to be called by the event handler +`event__handler` -> the event handler that is called inside the core code and calls and executes every subscriber callback + +For example `cnc_dotasks` exposes `cnc_dotasks_delegate` and `cnc_dotasks_event` that will enable to create an attach a listener that gets called when the event executed inside the core code. This is done by the call to `event__handler` inside `cnc_dotasks` main loop function. + +All delegates are of type `bool (*delegate_function_pointer) (void* args)`. All functions should reply with a `EVENT_CONTINUE`(false) or `EVENT_HANDLED`(true) to the handler. By default the event handler propagates the event to all the registered listeners until one of them replies with `EVENT_HANDLED`, at which point the handler prevents further propagation and resumes execution. + +In most events the input argument is `NULL`. The exceptions are: + +#### gcode_parse + +**Input args:** + +gcode_parse_args_t* - Pointer to a struct of type gcode_parse_args_t. The gcode_parse_args_t struct is defined like this: + +``` +typedef struct gcode_parse_args_ +{ + unsigned char word; // This is the GCode word being parsed (usually 'G' or 'M') + uint8_t code; // This is the GCode word argument converted to uint8_t format (example 98) + uint8_t error; // The parser current error code (STATUS_GCODE_EXTENDED_UNSUPPORTED) + float value; // This is the actual GCode word argument parsed as float. Useful if code has mantissa or is bigger then 255 (example 98.1) + parser_state_t *new_state; // The current parser state (struct) + parser_words_t *words; // The current parser words argument values (struct) + parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups +} gcode_parse_args_t; +``` + +#### gcode_exec, gcode_exec_modifier, gcode_before_motion and gcode_after_motion + +**Input args:** + +gcode_exec_args_t* - Pointer to a struct of type gcode_exec_args_t. The gcode_exec_args_t struct is defined like this: + +``` +typedef struct gcode_exec_args_ +{ + parser_state_t *new_state; // The current parser state (struct) + parser_words_t *words; // The current parser words argument values (struct) + parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups +} gcode_exec_args_t; +``` + +#### grbl_cmd + +**Input args:** + +grbl_cmd_args_t* - Pointer to a struct of type grbl_cmd_args_t. The grbl_cmd_args_t struct is defined like this: + +``` +typedef struct grbl_cmd_args_ +{ + uint8_t *error; // current parser error state + unsigned char *cmd; // pointer to the command string + uint8_t len; // command string length + char next_char; // next char to be read +} grbl_cmd_args_t; +``` + +#### parser_get_modes + +**Input args:** + +uint8_t* - An array with the parser current active modal states + +#### input_change + +**Input args:** + +uint8_t* - An array with the DIN7- states. `array[0]` contains the mask value of pins DIN7(MSB) to DIN0(LSB). `array[1]` contains the mask value of all pins DIN7(MSB) to DIN0(LSB) that changed state since the last time. + +#### mc_home_axis_start and mc_home_axis_finnish + +**Input args:** + +homing_status_t* - Pointer to a struct of type homing_status_t. The homing_status_t struct is defined like this: + +``` +typedef struct homing_status_ { + uint8_t axis; // current axis homming (mask) + uint8_t axis_limit; // current axis homming limit switch enabled (mask) + uint8_t status; // status of the motion (defaults to STATUS_OK) +} homing_status_t; +``` + +#### mc_line_segment + +**Input args:** + +motion_data_t* - Pointer to a struct of type motion_data_t. The motion_data_t struct is defined like this: + +``` +typedef struct +{ +#ifdef GCODE_PROCESS_LINE_NUMBERS + uint32_t line; // gcode line number +#endif + step_t steps[STEPPER_COUNT]; // step count for each linear actuator + uint8_t dirbits; // step dir mask +#ifdef ENABLE_LINACT_PLANNER + uint32_t full_steps; // number of steps of all linear actuators +#endif + float feed; // programmed feedrate in steps per second + float max_feed; // rapid motion feedrate in steps per second + float max_accel; // maximum acceleration in steps per second^2 + float feed_conversion; // step to units convertion constant + float cos_theta; // angle between current and previous motion + uint8_t main_stepper; // dominant step linear actuator for this motion + uint16_t spindle; // spindle speed and direction + uint16_t dwell; // dwell in milliseconds + uint8_t motion_mode; // motion mode mask + motion_flags_t motion_flags; // motion type flags +} motion_data_t; +``` + +## modules.h and events + +`src/module.h` exposes a few handy macros that make event listeners, or custom events creations easy. + +### event creation + +To create custom event handlers these macros are available: + +DECL_EVENT_HANDLER(name) +WEAK_EVENT_HANDLER(name) +DEFAULT_EVENT_HANDLER(gcode_parse) + +To create custom event listeners these macros are available: + +CREATE_EVENT_LISTENER(name, handler) +ADD_EVENT_LISTENER(name, handler) + +There are also a few other usefull macros that make module initialization and declaration easier. These are: + +DECL_MODULE(name) +LOAD_MODULE(name) + +## Creating a new event listener + +Creating a new event listener is easy. All current modules are placed inside the `src/modules` directory but it's not mandatory. It's just a matter of having them organized. +If you place them in other places the only difference is the `#includes` directives should be updated since they use relative paths. + +Also new modules should be initialized inside the load_modules function in module.c. This is not mandatory. It's a matter of keeping code organized and insure that the function calls are done in the correct order. Due to Arduino IDE limitations (not supporting folders) in the way you can access and modify source that is not in the same directory as the .ino file, different ways of including custom code can be adopted to make it work. + +Let's look at an example in the Arduino IDE environment by creating and attaching and event listener to cnc_dotasks. + +Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code + +``` +// include cnc.h relative path +#include "src/cnc.h" + +// preprocessor check if module is enabled +#ifdef ENABLE_MAIN_LOOP_MODULES + +// custom function declaration +void my_custom_code(void); +// create a listener of type cnc_dotasks +CREATE_LISTENER(cnc_dotasks_delegate, my_custom_code); +// custom code implementation +void my_custom_code(void) +{ + // do something +} + +// you only need to add the event listener to the event handler +// you can either call the ADD_EVENT_LISTENER inside the main µCNC initialization code +// or you can create a module initialization function and call it inside the main µCNC initialization code. The advantage of the latest is that you can have multiple event listeners you want to attach to multiple events and perform other loading actions and that way, you perform this in one call. +// Here is an example + +DECL_MODULE(my_custom_module){ + // attach the listener + ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); +} +#endif +``` + +This created the event listener that is of type cnc_dotasks. The only thing left to do is to attach it so that it gets called when cnc_dotasks is fired. + +In the uCNC.ino it's just a matter of adding the listener to the event like this: + +Open uCNC.ino + +``` +#include "src/cnc.h" + +int main(void) +{ + //initializes all systems + cnc_init(); + + // add the listener to cnc_dotasks + // ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); + + // or instead of calling the listener you can call the module initializer that does that task like this + + LOAD_MODULE(my_custom_module); + + for (;;) + { + cnc_run(); + } +} +``` + +That's it. Your custom function will run inside the main loop. From e8f01f7bd733728a9b6ea13eb7113c3e8c758f68 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:10:08 +0100 Subject: [PATCH 050/168] added custom modules README --- uCNC/src/README.md | 327 ++++++++++++++++++++++++++++++++++++- uCNC/src/modules/README.md | 267 ------------------------------ 2 files changed, 325 insertions(+), 269 deletions(-) delete mode 100644 uCNC/src/modules/README.md diff --git a/uCNC/src/README.md b/uCNC/src/README.md index fb425dbd8..000dde4b7 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -7,6 +7,329 @@ µCNC - Universal CNC firmware for microcontrollers ## module.c and module.h -These files contain initialization code for all modules that extend µCNC functionalities, like the PID controler and parser extender modules. +These files contain initialization code for all modules that extend µCNC functionalities, like custom modules. -For more information please head to the [µCNC wiki page](https://github.com/Paciente8159/uCNC/wiki) +# Adding custom modules to µCNC + +__IMPORTANT NOTE__: _Version 1.7 implemented breaking changes to modules declarations. Please check the modules releases to get the right modules for your version [repository](https://github.com/Paciente8159/uCNC-modules)_ + +__NOTE__: _Version 1.4.6 implemented changes to module initialization. Also additional modules were moved to a new [repository](https://github.com/Paciente8159/uCNC-modules)_ + +µCNC has implemented a module system that allows the user to perform custom actions that get executed in an event/delegate fashion style similar to what is done with C#. Multiple callbacks functions can be attached to the same event. +These modules can be quite useful and perform several things like adding custom custom gcodes to perform actions, or modifying IO states if a given condition is verified. +µCNC already has a few useful modules like PID controller, Encoder module, TMC drivers support and custom G/M code support. + +## µCNC existing events/delegates + +Without having to modify core code inside µCNC it is possible to listen to several already existing events. Here is a list of current events: + +__NOTE__: Not all event hooks might be listed here. To find all available event hooks declarations, do a search on all files (on VSCode in Windows it's Ctrl+Shift+F) of the project of `DECL_EVENT_HANDLER`. You can also search for the `EVENT_INVOKE` to see what argument is being passed to the event handler. + +| Event name | Argument | Enable option | Description | +| --- | --- | --- | --- | +| gcode_parse | gcode_parse_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command was not captured/understood by the core parser is trying to parse the code. Arg is a pointer to a gcode_parse_args_t struct | +| gcode_exec | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command that was not captured/understood by the core parser is intercepted by gcode_parse event an recognized as an extended gcode command. Arg is a pointer to a gcode_exec_args_t struct | +| gcode_exec_modifier | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires prior to gcode execution phase and can be used to modify the parsed command or execute custom actions or issue motions before gcode execution. Arg is a pointer to a gcode_exec_args_t struct | +| gcode_before_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires before a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | +| gcode_after_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires after a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | +| grbl_cmd | grbl_cmd_args_t* | ENABLE_PARSER_MODULES | Fires when a custom/unknown '$' grbl type command is received. Arg is a pointer to a grbl_cmd_args_t struct | +| parse_token | NULL | ENABLE_PARSER_MODULES | Fires when a custom/unknown token/char is received for further processing | +| parser_get_modes | uint8_t * | ENABLE_PARSER_MODULES | Fires when $G command is issued and the active modal states array is being requested (can be used to modify the active modes with extended gcodes). Arg is a pointer to an uint8_t array with the parser motion groups current values | +| parser_reset | NULL | ENABLE_PARSER_MODULES | Fires on parser reset | +| cnc_reset | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when µCNC resets | +| rtc_tick | NULL | ENABLE_MAIN_LOOP_MODULES | Fires every millisecond. This code runs inside the RTC interrupt. Do not run long routines here. This is for time critical (periodic) tasks. | +| cnc_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main loop running. Any repeating task should be hooked here | +| cnc_io_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main IO loop running. This is similar to cnc_dotasks, the main difference is that this task will run also during delays | +| cnc_stop | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when a halt/stop condition is triggered | +| cnc_exec_cmd_error | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when an invalid command is received | +| settings_change | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when a $ setting is changed. Arg is a pointer to a settings_args_t struct | +| settings_load | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are loaded from memory. Arg is a pointer to a settings_args_t struct | +| settings_save | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are saved into memory. Arg is a pointer to a settings_args_t struct | +| settings_erase | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are erased/reset. Arg is a pointer to a settings_args_t struct | +| protocol_send_status | NULL | - | Fires when printing the status message | +| protocol_send_cnc_settings | NULL | ENABLE_SETTINGS_MODULES | Fires when printing settings values | +| protocol_send_cnc_info | NULL | ENABLE_SYSTEM_INFO | Fires when printing response to $I command | +| protocol_send_pins_states | NULL | ENABLE_IO_MODULES | Fires when $P command is printing the pins states | +| protocol_send_gcode_modes | NULL | ENABLE_PARSER_MODULES | Fires when $G printing modals states message | +| input_change | uint8_t* | ENABLE_IO_MODULES | Fires when a generic input (DIN0-7) pin changes state. Args is an uint8_t array with 2 values. The first is the inputs current values mask and the second a maks with the inputs that changed since the last time | +| probe_enable | NULL | ENABLE_IO_MODULES | Fires when the probe is enabled | +| probe_disable | NULL | ENABLE_IO_MODULES | Fires when the probe is disabled | +| mc_line_segment | NULL | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner | +| mc_home_axis_start | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is starting. Pointer to homing_status_t struct with homming information | +| mc_home_axis_finish | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is finnished | +| mc_line_segment | motion_data_t* | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner. Arg is a pointer to a motion_data_t struct with the current motion block data | + +Each of these events exposes a delegate and and event that have the following naming convention: + +`_delegate` -> type of a function pointer that defines the function prototype to be called by the event handler +`_event` -> pointer to the event that contains all the subscribers that are going to be called by the event handler +`event__handler` -> the event handler that is called inside the core code and calls and executes every subscriber callback + +For example `cnc_dotasks` exposes `cnc_dotasks_delegate` and `cnc_dotasks_event` that will enable to create an attach a listener that gets called when the event executed inside the core code. This is done by the call to `event__handler` inside `cnc_dotasks` main loop function. + +All delegates are of type `bool (*delegate_function_pointer) (void* args)`. All functions should reply with a `EVENT_CONTINUE`(false) or `EVENT_HANDLED`(true) to the handler. By default the event handler propagates the event to all the registered listeners until one of them replies with `EVENT_HANDLED`, at which point the handler prevents further propagation and resumes execution. + +In most events the input argument is `NULL`. The exceptions are: + +#### gcode_parse + +**Input args:** + +gcode_parse_args_t* - Pointer to a struct of type gcode_parse_args_t. The gcode_parse_args_t struct is defined like this: + +``` +typedef struct gcode_parse_args_ +{ + unsigned char word; // This is the GCode word being parsed (usually 'G' or 'M') + uint8_t code; // This is the GCode word argument converted to uint8_t format (example 98) + uint8_t error; // The parser current error code (STATUS_GCODE_EXTENDED_UNSUPPORTED) + float value; // This is the actual GCode word argument parsed as float. Useful if code has mantissa or is bigger then 255 (example 98.1) + parser_state_t *new_state; // The current parser state (struct) + parser_words_t *words; // The current parser words argument values (struct) + parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups +} gcode_parse_args_t; +``` + +#### gcode_exec, gcode_exec_modifier, gcode_before_motion and gcode_after_motion + +**Input args:** + +gcode_exec_args_t* - Pointer to a struct of type gcode_exec_args_t. The gcode_exec_args_t struct is defined like this: + +``` +typedef struct gcode_exec_args_ +{ + parser_state_t *new_state; // The current parser state (struct) + parser_words_t *words; // The current parser words argument values (struct) + parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups +} gcode_exec_args_t; +``` + +#### grbl_cmd + +**Input args:** + +grbl_cmd_args_t* - Pointer to a struct of type grbl_cmd_args_t. The grbl_cmd_args_t struct is defined like this: + +``` +typedef struct grbl_cmd_args_ +{ + uint8_t *error; // current parser error state + unsigned char *cmd; // pointer to the command string + uint8_t len; // command string length + char next_char; // next char to be read +} grbl_cmd_args_t; +``` + +#### parser_get_modes + +**Input args:** + +uint8_t* - An array with the parser current active modal states + +#### input_change + +**Input args:** + +uint8_t* - An array with the DIN7- states. `array[0]` contains the mask value of pins DIN7(MSB) to DIN0(LSB). `array[1]` contains the mask value of all pins DIN7(MSB) to DIN0(LSB) that changed state since the last time. + +#### mc_home_axis_start and mc_home_axis_finnish + +**Input args:** + +homing_status_t* - Pointer to a struct of type homing_status_t. The homing_status_t struct is defined like this: + +``` +typedef struct homing_status_ { + uint8_t axis; // current axis homming (mask) + uint8_t axis_limit; // current axis homming limit switch enabled (mask) + uint8_t status; // status of the motion (defaults to STATUS_OK) +} homing_status_t; +``` + +#### mc_line_segment + +**Input args:** + +motion_data_t* - Pointer to a struct of type motion_data_t. The motion_data_t struct is defined like this: + +``` +typedef struct +{ +#ifdef GCODE_PROCESS_LINE_NUMBERS + uint32_t line; // gcode line number +#endif + step_t steps[STEPPER_COUNT]; // step count for each linear actuator + uint8_t dirbits; // step dir mask +#ifdef ENABLE_LINACT_PLANNER + uint32_t full_steps; // number of steps of all linear actuators +#endif + float feed; // programmed feedrate in steps per second + float max_feed; // rapid motion feedrate in steps per second + float max_accel; // maximum acceleration in steps per second^2 + float feed_conversion; // step to units convertion constant + float cos_theta; // angle between current and previous motion + uint8_t main_stepper; // dominant step linear actuator for this motion + uint16_t spindle; // spindle speed and direction + uint16_t dwell; // dwell in milliseconds + uint8_t motion_mode; // motion mode mask + motion_flags_t motion_flags; // motion type flags +} motion_data_t; +``` + +## modules.h and events + +`src/module.h` exposes a few handy macros that make event listeners, or custom events creations easy. + +### event creation + +To create custom event handlers these macros are available: + +DECL_EVENT_HANDLER(name) +WEAK_EVENT_HANDLER(name) +DEFAULT_EVENT_HANDLER(name) + +To create custom event listeners these macros are available: + +CREATE_EVENT_LISTENER(name, handler) +ADD_EVENT_LISTENER(name, handler) + +There are also a few other usefull macros that make module initialization and declaration easier. These are: + +DECL_MODULE(name) +LOAD_MODULE(name) + +As mentioned all events run a default calback handler that runs through all the listeners or shortens the execution if one of the listeners responds with a `EVENT_HANDLED`. + +This behaviour can be modified with a custom callback function that can be declared using: + +``` +OVERRIDE_EVENT_HANDLER(name){ + // your custom code here +} +``` +This is usefull if you want to to make a listener the only one that is able to listen to an event or bypass the event handler processing with some custom code. + +## Creating a new custom event listener + +Creating a new event listener is easy. All current modules are placed inside the `src/modules` directory but it's not mandatory. It's just a matter of having them organized. +If you place them in other places the only difference is the `#includes` directives should be updated since they use relative paths. + +Also new modules should be initialized inside the load_modules function in module.c. This is not mandatory. It's a matter of keeping code organized and insure that the function calls are done in the correct order. Due to Arduino IDE limitations (not supporting folders) in the way you can access and modify source that is not in the same directory as the .ino file, different ways of including custom code can be adopted to make it work. + +Let's look at an example in the Arduino IDE environment by creating and attaching and event listener to cnc_dotasks. + +Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code + +``` +// include cnc.h relative path +#include "src/cnc.h" + +// preprocessor check if module is enabled +#ifdef ENABLE_MAIN_LOOP_MODULES + +// custom function declaration +void my_custom_code(void); +// create a listener of type cnc_dotasks +CREATE_LISTENER(cnc_dotasks_delegate, my_custom_code); +// custom code implementation +void my_custom_code(void) +{ + // do something +} + +// you only need to add the event listener to the event handler +// you can either call the ADD_EVENT_LISTENER inside the main µCNC initialization code +// or you can create a module initialization function and call it inside the main µCNC initialization code. The advantage of the latest is that you can have multiple event listeners you want to attach to multiple events and perform other loading actions and that way, you perform this in one call. +// Here is an example + +DECL_MODULE(my_custom_module){ + // attach the listener + ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); +} +#endif +``` + +This created the event listener that is of type cnc_dotasks. The only thing left to do is to attach it so that it gets called when cnc_dotasks is fired. + +In the uCNC.ino it's just a matter of adding the listener to the event like this: + +Open uCNC.ino + +``` +#include "src/cnc.h" + +int main(void) +{ + //initializes all systems + cnc_init(); + + // add the listener to cnc_dotasks + // ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); + + // or instead of calling the listener you can call the module initializer that does that task like this + + LOAD_MODULE(my_custom_module); + + for (;;) + { + cnc_run(); + } +} +``` + +That's it. Your custom function will run inside the main loop. + +## Creating a new custom event + +Creating custom events inside the core code is also easy. + +First you need to declare the event inside one of the .h core code files + +For example lets create an event to be fired when µCNC enters alarm any alarm state, that will be called inside function `void cnc_alarm(int8_t code)` in `cnc.c` + +We start by declaring a new event called *cnc_alarm* (in our example inside `cnc.h`) like this + +``` +DECL_EVENT_HANDLER(cnc_alarm); +``` + +Now (in our example inside `cnc.c`) we need to add the event callback that will check if it as event listeners and call them one by one. To create a default event listener we just need to add this code: + +``` +WEAK_EVENT_HANDLER(cnc_alarm) +{ + DEFAULT_EVENT_HANDLER(cnc_alarm); +} + +``` + +*Again remember. You can make a module take hover this event callback (disabling all existing listeners of this event by creating and override callback with `OVERRIDE_EVENT_HANDLER` like showned above).* + +The only step left is to actually add the callback inside the core code to be executed. In this case let's lace it inside our `void cnc_alarm(int8_t code)` function like this: + +``` +void cnc_alarm(int8_t code) +{ + cnc_set_exec_state(EXEC_KILL); + cnc_stop(); + cnc_state.alarm = code; +#ifdef ENABLE_IO_ALARM_DEBUG + protocol_send_string(MSG_START); + protocol_send_string(__romstr__("LIMITS:")); + serial_print_int(io_alarm_limits); + protocol_send_string(__romstr__("|CONTROLS:")); + serial_print_int(io_alarm_controls); + protocol_send_string(MSG_END); +#endif + + // we add our callback here + // in this callback we will pass to the listeners our error code + // since all event callback argument is of type void* (void pointer) we send the pointer to the error code like this + + EVENT_INVOKE(cnc_alarm, &code); +} + +``` + +That's it. Every time there is an alarm, the event handler will run and execute the listener callbacks. diff --git a/uCNC/src/modules/README.md b/uCNC/src/modules/README.md deleted file mode 100644 index 2bfc4ca29..000000000 --- a/uCNC/src/modules/README.md +++ /dev/null @@ -1,267 +0,0 @@ -

- -

- - -# µCNC -µCNC - Universal CNC firmware for microcontrollers - -# Adding custom modules to µCNC - -__IMPORTANT NOTE__: _Version 1.7 implemented breaking changes to modules declarations. Please check the modules releases to get the right modules for your version [repository](https://github.com/Paciente8159/uCNC-modules)_ - -__NOTE__: _Version 1.4.6 implemented changes to module initialization. Also additional modules were moved to a new [repository](https://github.com/Paciente8159/uCNC-modules)_ - -µCNC has implemented a module system that allows the user to perform custom actions that get executed in an event/delegate fashion style similar to what is done with C#. Multiple callbacks functions can be attached to the same event. -These modules can be quite useful and perform several things like adding custom custom gcodes to perform actions, or modifying IO states if a given condition is verified. -µCNC already has a few useful modules like PID controller, Encoder module, TMC drivers support and custom G/M code support. - -## µCNC existing events/delegates - -Without having to modify core code inside µCNC it is possible to listen to several already existing events. Here is a list of current events: - -__NOTE__: Not all event hooks might be listed here. To find all available event hooks declarations, do a search on all files (on VSCode in Windows it's Ctrl+Shift+F) of the project of `DECL_EVENT_HANDLER`. You can also search for the `EVENT_INVOKE` to see what argument is being passed to the event handler. - -| Event name | Argument | Enable option | Description | -| --- | --- | --- | --- | -| gcode_parse | gcode_parse_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command was not captured/understood by the core parser is trying to parse the code. Arg is a pointer to a gcode_parse_args_t struct | -| gcode_exec | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires when a gcode command that was not captured/understood by the core parser is intercepted by gcode_parse event an recognized as an extended gcode command. Arg is a pointer to a gcode_exec_args_t struct | -| gcode_exec_modifier | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires prior to gcode execution phase and can be used to modify the parsed command or execute custom actions or issue motions before gcode execution. Arg is a pointer to a gcode_exec_args_t struct | -| gcode_before_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires before a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | -| gcode_after_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires after a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | -| grbl_cmd | grbl_cmd_args_t* | ENABLE_PARSER_MODULES | Fires when a custom/unknown '$' grbl type command is received. Arg is a pointer to a grbl_cmd_args_t struct | -| parse_token | NULL | ENABLE_PARSER_MODULES | Fires when a custom/unknown token/char is received for further processing | -| parser_get_modes | uint8_t * | ENABLE_PARSER_MODULES | Fires when $G command is issued and the active modal states array is being requested (can be used to modify the active modes with extended gcodes). Arg is a pointer to an uint8_t array with the parser motion groups current values | -| parser_reset | NULL | ENABLE_PARSER_MODULES | Fires on parser reset | -| cnc_reset | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when µCNC resets | -| rtc_tick | NULL | ENABLE_MAIN_LOOP_MODULES | Fires every millisecond. This code runs inside the RTC interrupt. Do not run long routines here. This is for time critical (periodic) tasks. | -| cnc_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main loop running. Any repeating task should be hooked here | -| cnc_io_dotasks | NULL | ENABLE_MAIN_LOOP_MODULES | Fires on the main IO loop running. This is similar to cnc_dotasks, the main difference is that this task will run also during delays | -| cnc_stop | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when a halt/stop condition is triggered | -| cnc_exec_cmd_error | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when an invalid command is received | -| settings_change | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when a $ setting is changed. Arg is a pointer to a settings_args_t struct | -| settings_load | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are loaded from memory. Arg is a pointer to a settings_args_t struct | -| settings_save | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are saved into memory. Arg is a pointer to a settings_args_t struct | -| settings_erase | settings_args_t* | ENABLE_SETTINGS_MODULES | Fires when settings are erased/reset. Arg is a pointer to a settings_args_t struct | -| protocol_send_status | NULL | - | Fires when printing the status message | -| protocol_send_cnc_settings | NULL | ENABLE_SETTINGS_MODULES | Fires when printing settings values | -| protocol_send_cnc_info | NULL | ENABLE_SYSTEM_INFO | Fires when printing response to $I command | -| protocol_send_pins_states | NULL | ENABLE_IO_MODULES | Fires when $P command is printing the pins states | -| protocol_send_gcode_modes | NULL | ENABLE_PARSER_MODULES | Fires when $G printing modals states message | -| input_change | uint8_t* | ENABLE_IO_MODULES | Fires when a generic input (DIN0-7) pin changes state. Args is an uint8_t array with 2 values. The first is the inputs current values mask and the second a maks with the inputs that changed since the last time | -| probe_enable | NULL | ENABLE_IO_MODULES | Fires when the probe is enabled | -| probe_disable | NULL | ENABLE_IO_MODULES | Fires when the probe is disabled | -| mc_line_segment | NULL | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner | -| mc_home_axis_start | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is starting. Pointer to homing_status_t struct with homming information | -| mc_home_axis_finish | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is finnished | -| mc_line_segment | motion_data_t* | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner. Arg is a pointer to a motion_data_t struct with the current motion block data | - -Each of these events exposes a delegate and and event that have the following naming convention: - -`_delegate` -> type of a function pointer that defines the function prototype to be called by the event handler -`_event` -> pointer to the event that contains all the subscribers that are going to be called by the event handler -`event__handler` -> the event handler that is called inside the core code and calls and executes every subscriber callback - -For example `cnc_dotasks` exposes `cnc_dotasks_delegate` and `cnc_dotasks_event` that will enable to create an attach a listener that gets called when the event executed inside the core code. This is done by the call to `event__handler` inside `cnc_dotasks` main loop function. - -All delegates are of type `bool (*delegate_function_pointer) (void* args)`. All functions should reply with a `EVENT_CONTINUE`(false) or `EVENT_HANDLED`(true) to the handler. By default the event handler propagates the event to all the registered listeners until one of them replies with `EVENT_HANDLED`, at which point the handler prevents further propagation and resumes execution. - -In most events the input argument is `NULL`. The exceptions are: - -#### gcode_parse - -**Input args:** - -gcode_parse_args_t* - Pointer to a struct of type gcode_parse_args_t. The gcode_parse_args_t struct is defined like this: - -``` -typedef struct gcode_parse_args_ -{ - unsigned char word; // This is the GCode word being parsed (usually 'G' or 'M') - uint8_t code; // This is the GCode word argument converted to uint8_t format (example 98) - uint8_t error; // The parser current error code (STATUS_GCODE_EXTENDED_UNSUPPORTED) - float value; // This is the actual GCode word argument parsed as float. Useful if code has mantissa or is bigger then 255 (example 98.1) - parser_state_t *new_state; // The current parser state (struct) - parser_words_t *words; // The current parser words argument values (struct) - parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups -} gcode_parse_args_t; -``` - -#### gcode_exec, gcode_exec_modifier, gcode_before_motion and gcode_after_motion - -**Input args:** - -gcode_exec_args_t* - Pointer to a struct of type gcode_exec_args_t. The gcode_exec_args_t struct is defined like this: - -``` -typedef struct gcode_exec_args_ -{ - parser_state_t *new_state; // The current parser state (struct) - parser_words_t *words; // The current parser words argument values (struct) - parser_cmd_explicit_t *cmd; // The current parser GCode command active words/groups -} gcode_exec_args_t; -``` - -#### grbl_cmd - -**Input args:** - -grbl_cmd_args_t* - Pointer to a struct of type grbl_cmd_args_t. The grbl_cmd_args_t struct is defined like this: - -``` -typedef struct grbl_cmd_args_ -{ - uint8_t *error; // current parser error state - unsigned char *cmd; // pointer to the command string - uint8_t len; // command string length - char next_char; // next char to be read -} grbl_cmd_args_t; -``` - -#### parser_get_modes - -**Input args:** - -uint8_t* - An array with the parser current active modal states - -#### input_change - -**Input args:** - -uint8_t* - An array with the DIN7- states. `array[0]` contains the mask value of pins DIN7(MSB) to DIN0(LSB). `array[1]` contains the mask value of all pins DIN7(MSB) to DIN0(LSB) that changed state since the last time. - -#### mc_home_axis_start and mc_home_axis_finnish - -**Input args:** - -homing_status_t* - Pointer to a struct of type homing_status_t. The homing_status_t struct is defined like this: - -``` -typedef struct homing_status_ { - uint8_t axis; // current axis homming (mask) - uint8_t axis_limit; // current axis homming limit switch enabled (mask) - uint8_t status; // status of the motion (defaults to STATUS_OK) -} homing_status_t; -``` - -#### mc_line_segment - -**Input args:** - -motion_data_t* - Pointer to a struct of type motion_data_t. The motion_data_t struct is defined like this: - -``` -typedef struct -{ -#ifdef GCODE_PROCESS_LINE_NUMBERS - uint32_t line; // gcode line number -#endif - step_t steps[STEPPER_COUNT]; // step count for each linear actuator - uint8_t dirbits; // step dir mask -#ifdef ENABLE_LINACT_PLANNER - uint32_t full_steps; // number of steps of all linear actuators -#endif - float feed; // programmed feedrate in steps per second - float max_feed; // rapid motion feedrate in steps per second - float max_accel; // maximum acceleration in steps per second^2 - float feed_conversion; // step to units convertion constant - float cos_theta; // angle between current and previous motion - uint8_t main_stepper; // dominant step linear actuator for this motion - uint16_t spindle; // spindle speed and direction - uint16_t dwell; // dwell in milliseconds - uint8_t motion_mode; // motion mode mask - motion_flags_t motion_flags; // motion type flags -} motion_data_t; -``` - -## modules.h and events - -`src/module.h` exposes a few handy macros that make event listeners, or custom events creations easy. - -### event creation - -To create custom event handlers these macros are available: - -DECL_EVENT_HANDLER(name) -WEAK_EVENT_HANDLER(name) -DEFAULT_EVENT_HANDLER(gcode_parse) - -To create custom event listeners these macros are available: - -CREATE_EVENT_LISTENER(name, handler) -ADD_EVENT_LISTENER(name, handler) - -There are also a few other usefull macros that make module initialization and declaration easier. These are: - -DECL_MODULE(name) -LOAD_MODULE(name) - -## Creating a new event listener - -Creating a new event listener is easy. All current modules are placed inside the `src/modules` directory but it's not mandatory. It's just a matter of having them organized. -If you place them in other places the only difference is the `#includes` directives should be updated since they use relative paths. - -Also new modules should be initialized inside the load_modules function in module.c. This is not mandatory. It's a matter of keeping code organized and insure that the function calls are done in the correct order. Due to Arduino IDE limitations (not supporting folders) in the way you can access and modify source that is not in the same directory as the .ino file, different ways of including custom code can be adopted to make it work. - -Let's look at an example in the Arduino IDE environment by creating and attaching and event listener to cnc_dotasks. - -Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code - -``` -// include cnc.h relative path -#include "src/cnc.h" - -// preprocessor check if module is enabled -#ifdef ENABLE_MAIN_LOOP_MODULES - -// custom function declaration -void my_custom_code(void); -// create a listener of type cnc_dotasks -CREATE_LISTENER(cnc_dotasks_delegate, my_custom_code); -// custom code implementation -void my_custom_code(void) -{ - // do something -} - -// you only need to add the event listener to the event handler -// you can either call the ADD_EVENT_LISTENER inside the main µCNC initialization code -// or you can create a module initialization function and call it inside the main µCNC initialization code. The advantage of the latest is that you can have multiple event listeners you want to attach to multiple events and perform other loading actions and that way, you perform this in one call. -// Here is an example - -DECL_MODULE(my_custom_module){ - // attach the listener - ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); -} -#endif -``` - -This created the event listener that is of type cnc_dotasks. The only thing left to do is to attach it so that it gets called when cnc_dotasks is fired. - -In the uCNC.ino it's just a matter of adding the listener to the event like this: - -Open uCNC.ino - -``` -#include "src/cnc.h" - -int main(void) -{ - //initializes all systems - cnc_init(); - - // add the listener to cnc_dotasks - // ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); - - // or instead of calling the listener you can call the module initializer that does that task like this - - LOAD_MODULE(my_custom_module); - - for (;;) - { - cnc_run(); - } -} -``` - -That's it. Your custom function will run inside the main loop. From 9f8f954e60cb941e96efc565ac800d5223fe3637 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:23:45 +0100 Subject: [PATCH 051/168] Update README.md --- uCNC/src/README.md | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 000dde4b7..26ee1c07b 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -185,19 +185,23 @@ typedef struct To create custom event handlers these macros are available: -DECL_EVENT_HANDLER(name) -WEAK_EVENT_HANDLER(name) -DEFAULT_EVENT_HANDLER(name) +`DECL_EVENT_HANDLER(name)` + +`WEAK_EVENT_HANDLER(name)` + +`DEFAULT_EVENT_HANDLER(name)` To create custom event listeners these macros are available: -CREATE_EVENT_LISTENER(name, handler) -ADD_EVENT_LISTENER(name, handler) +`CREATE_EVENT_LISTENER(name, handler)` + +`ADD_EVENT_LISTENER(name, handler)` There are also a few other usefull macros that make module initialization and declaration easier. These are: -DECL_MODULE(name) -LOAD_MODULE(name) +`DECL_MODULE(name)` + +`LOAD_MODULE(name)` As mentioned all events run a default calback handler that runs through all the listeners or shortens the execution if one of the listeners responds with a `EVENT_HANDLED`. From e4c102472324b0b301d7035f3476253fde562233 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:29:46 +0100 Subject: [PATCH 052/168] added jump sections --- uCNC/src/README.md | 7 +++++++ uCNC/src/hal/tools/README.md | 5 +++++ 2 files changed, 12 insertions(+) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 26ee1c07b..2e3e6d274 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -9,6 +9,13 @@ ## module.c and module.h These files contain initialization code for all modules that extend µCNC functionalities, like custom modules. +_**Jump to section**_ +* [Adding custom modules to µCNC](#adding-custom-modules-to-µcnc) + * [µCNC existing events/delegates](#µcnc-existing-eventsdelegates) + * [modules.h and events](#modulesh-and-events) + * [Creating a new custom event listener](#creating-a-new-custom-event-listener) + * [Creating a new custom event](#creating-a-new-custom-event) + # Adding custom modules to µCNC __IMPORTANT NOTE__: _Version 1.7 implemented breaking changes to modules declarations. Please check the modules releases to get the right modules for your version [repository](https://github.com/Paciente8159/uCNC-modules)_ diff --git a/uCNC/src/hal/tools/README.md b/uCNC/src/hal/tools/README.md index b07567dff..c156979ef 100644 --- a/uCNC/src/hal/tools/README.md +++ b/uCNC/src/hal/tools/README.md @@ -6,6 +6,11 @@ # µCNC µCNC - Universal CNC firmware for microcontrollers +_**Jump to section**_ +* [Adding custom tools to µCNC](#adding-custom-tools-to-µcnc) + * [µCNC tool structure](#µcnc-tool-structure) + * [µCNC creating a dummy tool](#µcnc-creating-a-dummy-tool) + # Adding custom tools to µCNC µCNC tool is a bit different from modules but it's equally straight forward. From 04ec5baf8834a54b9fa202d7f492f3fb8d5e91a4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:48:27 +0100 Subject: [PATCH 053/168] Update README.md --- uCNC/src/README.md | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 2e3e6d274..eeb461bb3 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -239,26 +239,27 @@ Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code // preprocessor check if module is enabled #ifdef ENABLE_MAIN_LOOP_MODULES -// custom function declaration -void my_custom_code(void); -// create a listener of type cnc_dotasks -CREATE_LISTENER(cnc_dotasks_delegate, my_custom_code); // custom code implementation void my_custom_code(void) { // do something } +// create a listener of type cnc_dotasks +CREATE_EVENT_LISTENER(cnc_dotasks, my_custom_code); +#endif + // you only need to add the event listener to the event handler // you can either call the ADD_EVENT_LISTENER inside the main µCNC initialization code // or you can create a module initialization function and call it inside the main µCNC initialization code. The advantage of the latest is that you can have multiple event listeners you want to attach to multiple events and perform other loading actions and that way, you perform this in one call. // Here is an example DECL_MODULE(my_custom_module){ +#ifdef ENABLE_MAIN_LOOP_MODULES // attach the listener - ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); -} + ADD_EVENT_LISTENER(cnc_dotasks, my_custom_code); #endif +} ``` This created the event listener that is of type cnc_dotasks. The only thing left to do is to attach it so that it gets called when cnc_dotasks is fired. @@ -276,7 +277,7 @@ int main(void) cnc_init(); // add the listener to cnc_dotasks - // ADD_LISTENER(cnc_dotasks_delegate, my_custom_code, cnc_dotasks_event); + // ADD_EVENT_LISTENER(cnc_dotasks, my_custom_code); // or instead of calling the listener you can call the module initializer that does that task like this From 0ef795f3d474f74c049ee9b9ee7e09633893576f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:51:05 +0100 Subject: [PATCH 054/168] Update README.md --- uCNC/src/README.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index eeb461bb3..b5027e30f 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -239,8 +239,9 @@ Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code // preprocessor check if module is enabled #ifdef ENABLE_MAIN_LOOP_MODULES -// custom code implementation -void my_custom_code(void) +// custom code listener callback implementation +// all callbacks must be of type bool (*function_pointer) (void*) +bool my_custom_code(void* args) { // do something } From 8907728c22d52e9cca1a23eb30edabe832d086bc Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:52:45 +0100 Subject: [PATCH 055/168] Update README.md --- uCNC/src/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index b5027e30f..2b73052c0 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -244,6 +244,9 @@ Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code bool my_custom_code(void* args) { // do something + + // in this case we will return EVENT_CONTINUE to allow event to propagate to other listeners + return EVENT_CONTINUE; } // create a listener of type cnc_dotasks From 5b84bfc67a6e95ee9d9699f5d88b7d7e3aa4ed3a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 16:57:53 +0100 Subject: [PATCH 056/168] Update README.md --- uCNC/src/README.md | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 2b73052c0..491daf25f 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -226,9 +226,9 @@ This is usefull if you want to to make a listener the only one that is able to l Creating a new event listener is easy. All current modules are placed inside the `src/modules` directory but it's not mandatory. It's just a matter of having them organized. If you place them in other places the only difference is the `#includes` directives should be updated since they use relative paths. -Also new modules should be initialized inside the load_modules function in module.c. This is not mandatory. It's a matter of keeping code organized and insure that the function calls are done in the correct order. Due to Arduino IDE limitations (not supporting folders) in the way you can access and modify source that is not in the same directory as the .ino file, different ways of including custom code can be adopted to make it work. +Also new modules should be initialized inside the `load_modules` function in module.c. This is not mandatory. It's a matter of keeping code organized and insure that the function calls are done in the correct order. Due to Arduino IDE limitations (not supporting folders) in the way you can access and modify source that is not in the same directory as the .ino file, different ways of including custom code can be adopted to make it work. -Let's look at an example in the Arduino IDE environment by creating and attaching and event listener to cnc_dotasks. +Let's look at an example in the Arduino IDE environment by creating and attaching and event listener to `cnc_dotasks`. Add a new file .c to uCNC directory (same has uCNC.ino) and paste this code @@ -266,7 +266,7 @@ DECL_MODULE(my_custom_module){ } ``` -This created the event listener that is of type cnc_dotasks. The only thing left to do is to attach it so that it gets called when cnc_dotasks is fired. +This created the event listener that is of type `cnc_dotasks`. The only thing left to do is to attach it so that it gets called when `cnc_dotasks` is fired. In the uCNC.ino it's just a matter of adding the listener to the event like this: @@ -284,7 +284,6 @@ int main(void) // ADD_EVENT_LISTENER(cnc_dotasks, my_custom_code); // or instead of calling the listener you can call the module initializer that does that task like this - LOAD_MODULE(my_custom_module); for (;;) From 87961b6c578d24da1329b25704ecb7aa3846e44f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 17:59:17 +0100 Subject: [PATCH 057/168] updated mcu.h and README --- uCNC/src/hal/mcus/README.md | 878 +++++++++++++++++++++++++++++++++++- uCNC/src/hal/mcus/mcu.h | 35 +- 2 files changed, 901 insertions(+), 12 deletions(-) diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index ad944e322..daddeb476 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -1,12 +1,876 @@ +

+ +

+ + # µCNC -µCNC - A universal CNC firmware for microcontrollers +µCNC - Universal CNC firmware for microcontrollers + +_**Jump to section**_ +* [µCNC HAL](#µCNC-HAL) +* [The microcontroller HAL](#The-microcontroller-HAL) + * [Pin naming conventions ](#pin-naming-conventions ) + * [Creating the HAL for a custom MCU](#creating-the-hal-for-a-custom-mcu) + +# µCNC HAL (Hardware Abstraction Layer) +µCNC has several HAL dimensions/layers. The first is the microcontroller HAL. +This HAL provides the abstraction layer needed to use all the core functionalities in any microcontroller/PC board. + +## The microcontroller HAL +This HAL is actually composed of two parts. The MCU and the board/kit. + * The MCU defines all the basic functions required by the µCNC to write and read on and from the microcontroller I/O. These functions include for example how to set or clear an output pin or read from an input pin. + * The board contains all the definitions needed to map the µCNC internal named pins to the microcontroller physical pins. + * From v1.2.0 on there is a general cnc_hal_config.h file that allows to connect the general purpose pins to certain modules or functionalities. This allows the user to customize µCNC for custom needs. + +The way to implement/code this completely free. The only thing µCNC needs to know is that when it want's to set the step pin of motor 0 high it has to call: +```mcu_set_output(STEP0);``` + +### Pin naming conventions +µCNC sets a list of names that are used by the core functions to tell the microcontroller what to do. +These are the fixed names used internally: + +#### Output pins - special ++ ```STEP#``` pin defines the step output pin that controls linear actuator driver. + + ```STEP0 to STEP5``` are the output pins to control the step signal up to 6 independent drivers. + + ```STEP6 and STEP7``` are the output pins used as shadow registers to drive dual drive linear actuators. ++ ```DIR#``` pin defines the dir output pin that controls the linear actuator driver. + + ```DIR0 to DIR5``` are the output pins to control the direction signal up to 6 independent drivers ++ ```STEPPER#_ENABLE``` pin defines the enable output pin that controls the linear actuator driver. + + ```STEPPER0_ENABLE to STEPPER5_ENABLE``` are the output pins to control the enable signal up to 6 independent drivers. ++ ```SERVO#``` pin defines the servo signal output pin that controls common servo motors (1-2ms tON with 20ms period). + + ```SERVO0 to SERVO7``` are the the servo signal output pins with up to 8 independent servos. + +#### Input pins - special ++ ```LIMIT_#``` pin defines the input pin that controls end-stop switch detection. + + ```LIMIT_X```, ```LIMIT_Y```, ```LIMIT_Z```, ```LIMIT_A```, ```LIMIT_B```, ```LIMIT_C```, ```LIMIT_X2```, ```LIMIT_Y2``` and ```LIMIT_Z2```. ++ ```ESTOP```, ```SAFETY_DOOR```, ```FHOLD``` and ```CS_RES``` pin defines the input pins that controls user actions and safety features. ++ ```PROBE``` pin defines the input pin used for probing and tool length detection. + +#### COM pins - special ++ ```TX``` pin defines the UART port tx pin. ++ ```RX``` pin defines the UART port rx. ++ ```TX2``` pin defines the UART2 port tx pin. ++ ```RX2``` pin defines the UART2 port rx. ++ ```USB_DP``` pin defines the USB D+ port pin. ++ ```USB_DM``` pin defines the USB D- port pin. ++ ```SPI_CLK``` pin defines the SPI clock port pin. ++ ```SPI_SDI``` pin defines the SPI data input (MISO) port pin. ++ ```SPI_SDO``` pin defines the SPI data output (MOSI) port pin. ++ ```SPI_CS``` pin defines the SPI chip select port pin. ++ ```I2C_CLK``` pin defines the I2S clock port pin. ++ ```I2C_DATA``` pin defines the I2C data port pin. + +SPI_CLK + +#### Output pins - generic ++ ```PWM#``` pin defines a pwm output pin. + + ```PWM0 to PWM15``` are the pwm output pins. ++ ```DOUT#``` pin defines a generic output pin. + + ```DOUT0 to DOUT31``` are the generic output pins. + +#### Input pins - generic ++ ```ANALOG#``` pin defines an analog input pin. + + ```ANALOG0 to ANALOG15``` are the analog input pins. ++ ```DIN#``` pin defines a generic input pin. + + ```DIN0 to DIN31``` are the generic input pins. Pins ```DIN0 to DIN7``` can also be have ISR on change option enabled. In conjunction with ```DIN8 to DIN31``` they can form a pair for the encoder module. + +These pins also obey a numbering system to make them transversal between boards and MCU as mapped in the table bellow: + +| Pin number | Alias | Pin name | +| --- | --- | --- | +| 0 | DIO0 | STEP0 | +| 1 | DIO1 | STEP1 | +| 2 | DIO2 | STEP2 | +| 3 | DIO3 | STEP3 | +| 4 | DIO4 | STEP4 | +| 5 | DIO5 | STEP5 | +| 6 | DIO6 | STEP6 | +| 7 | DIO7 | STEP7 | +| 8 | DIO8 | DIR0 | +| 9 | DIO9 | DIR1 | +| 10 | DIO10 | DIR2 | +| 11 | DIO11 | DIR3 | +| 12 | DIO12 | DIR4 | +| 13 | DIO13 | DIR5 | +| 14 | DIO14 | DIR6 | +| 15 | DIO15 | DIR7 | +| 16 | DIO16 | STEP0_EN | +| 17 | DIO17 | STEP1_EN | +| 18 | DIO18 | STEP2_EN | +| 19 | DIO19 | STEP3_EN | +| 20 | DIO20 | STEP4_EN | +| 21 | DIO21 | STEP5_EN | +| 22 | DIO22 | STEP6_EN | +| 23 | DIO23 | STEP7_EN | +| 24 | DIO24 | PWM0 | +| 25 | DIO25 | PWM1 | +| 26 | DIO26 | PWM2 | +| 27 | DIO27 | PWM3 | +| 28 | DIO28 | PWM4 | +| 29 | DIO29 | PWM5 | +| 30 | DIO30 | PWM6 | +| 31 | DIO31 | PWM7 | +| 32 | DIO32 | PWM8 | +| 33 | DIO33 | PWM9 | +| 34 | DIO34 | PWM10 | +| 35 | DIO35 | PWM11 | +| 36 | DIO36 | PWM12 | +| 37 | DIO37 | PWM13 | +| 38 | DIO38 | PWM14 | +| 39 | DIO39 | PWM15 | +| 40 | DIO40 | SERVO0 | +| 41 | DIO41 | SERVO1 | +| 42 | DIO42 | SERVO2 | +| 43 | DIO43 | SERVO3 | +| 44 | DIO44 | SERVO4 | +| 45 | DIO45 | SERVO5 | +| 46 | DIO46 | DOUT0 | +| 47 | DIO47 | DOUT1 | +| 48 | DIO48 | DOUT2 | +| 49 | DIO49 | DOUT3 | +| 50 | DIO50 | DOUT4 | +| 51 | DIO51 | DOUT5 | +| 52 | DIO52 | DOUT6 | +| 53 | DIO53 | DOUT7 | +| 54 | DIO54 | DOUT8 | +| 55 | DIO55 | DOUT9 | +| 56 | DIO56 | DOUT10 | +| 57 | DIO57 | DOUT11 | +| 58 | DIO58 | DOUT12 | +| 59 | DIO59 | DOUT13 | +| 60 | DIO60 | DOUT14 | +| 61 | DIO61 | DOUT15 | +| 62 | DIO62 | DOUT16 | +| 63 | DIO63 | DOUT17 | +| 64 | DIO64 | DOUT18 | +| 65 | DIO65 | DOUT19 | +| 66 | DIO66 | DOUT20 | +| 67 | DIO67 | DOUT21 | +| 68 | DIO68 | DOUT22 | +| 69 | DIO69 | DOUT23 | +| 70 | DIO70 | DOUT24 | +| 71 | DIO71 | DOUT25 | +| 72 | DIO72 | DOUT26 | +| 73 | DIO73 | DOUT27 | +| 74 | DIO74 | DOUT28 | +| 75 | DIO75 | DOUT29 | +| 76 | DIO76 | DOUT30 | +| 77 | DIO77 | DOUT31 | +| 100 | DIO100 | LIMIT_X | +| 101 | DIO101 | LIMIT_Y | +| 102 | DIO102 | LIMIT_Z | +| 103 | DIO103 | LIMIT_X2 | +| 104 | DIO104 | LIMIT_Y2 | +| 105 | DIO105 | LIMIT_Z2 | +| 106 | DIO106 | LIMIT_A | +| 107 | DIO107 | LIMIT_B | +| 108 | DIO108 | LIMIT_C | +| 109 | DIO109 | PROBE | +| 110 | DIO110 | ESTOP | +| 111 | DIO111 | SAFETY_DOOR | +| 112 | DIO112 | FHOLD | +| 113 | DIO113 | CS_RES | +| 114 | DIO114 | ANALOG0 | +| 115 | DIO115 | ANALOG1 | +| 116 | DIO116 | ANALOG2 | +| 117 | DIO117 | ANALOG3 | +| 118 | DIO118 | ANALOG4 | +| 119 | DIO119 | ANALOG5 | +| 120 | DIO120 | ANALOG6 | +| 121 | DIO121 | ANALOG7 | +| 122 | DIO122 | ANALOG8 | +| 123 | DIO123 | ANALOG9 | +| 124 | DIO124 | ANALOG10 | +| 125 | DIO125 | ANALOG11 | +| 126 | DIO126 | ANALOG12 | +| 127 | DIO127 | ANALOG13 | +| 128 | DIO128 | ANALOG14 | +| 129 | DIO129 | ANALOG15 | +| 130 | DIO130 | DIN0 | +| 131 | DIO131 | DIN1 | +| 132 | DIO132 | DIN2 | +| 133 | DIO133 | DIN3 | +| 134 | DIO134 | DIN4 | +| 135 | DIO135 | DIN5 | +| 136 | DIO136 | DIN6 | +| 137 | DIO137 | DIN7 | +| 138 | DIO138 | DIN8 | +| 139 | DIO139 | DIN9 | +| 140 | DIO140 | DIN10 | +| 141 | DIO141 | DIN11 | +| 142 | DIO142 | DIN12 | +| 143 | DIO143 | DIN13 | +| 144 | DIO144 | DIN14 | +| 145 | DIO145 | DIN15 | +| 146 | DIO146 | DIN16 | +| 147 | DIO147 | DIN17 | +| 148 | DIO148 | DIN18 | +| 149 | DIO149 | DIN19 | +| 150 | DIO150 | DIN20 | +| 151 | DIO151 | DIN21 | +| 152 | DIO152 | DIN22 | +| 153 | DIO153 | DIN23 | +| 154 | DIO154 | DIN24 | +| 155 | DIO155 | DIN25 | +| 156 | DIO156 | DIN26 | +| 157 | DIO157 | DIN27 | +| 158 | DIO158 | DIN28 | +| 159 | DIO159 | DIN29 | +| 160 | DIO160 | DIN30 | +| 161 | DIO161 | DIN31 | +| 200 | DIO200 | TX | +| 201 | DIO201 | RX | +| 202 | DIO202 | USB_DM | +| 203 | DIO203 | USB_DP | +| 204 | DIO204 | SPI_CLK | +| 205 | DIO205 | SPI_SDI | +| 206 | DIO206 | SPI_SDO | +| 207 | DIO207 | SPI_CS | +| 208 | DIO208 | I2C_SCL | +| 209 | DIO209 | I2C_SDA | +| 210 | DIO210 | TX2 | +| 211 | DIO211 | RX2 | + +### Creating the HAL for a custom MCU +Before creating a custom HAL for a custom board/microcontroller the microcontroller must have the following hardware features available: + * At least 2 hardware timers (it might be possible with only a single timer but with limitations) + * At least a communication hardware port + * A non volatile memory if you need to store the configuration parameter (optional: is possible to work without this feature) + * PWM hardware IO (optional: is possible to work without this feature) + * Input pins with interrupt on change (the interrupt on change is optional: is possible to work without this feature by using only soft pooling but some features may not be available) + * Input pins with ADC (optional: is possible to work without this feature but some feature may not be available) + +**After this 4 steps are needed:** + + **1. Implement all functions defined in the mcu.h** + + All functions defined by the ```muc.h``` must be implemented. These are: + + ``` +#ifndef MCU_CALLBACK +#define MCU_CALLBACK +#endif + +#ifndef MCU_RX_CALLBACK +#define MCU_RX_CALLBACK MCU_CALLBACK +#endif + +#ifndef MCU_IO_CALLBACK +#define MCU_IO_CALLBACK MCU_CALLBACK +#endif + +#ifndef F_STEP_MAX +#define F_STEP_MAX 30000 +#endif + +// defines special mcu to access flash strings and arrays +#ifndef __rom__ +#define __rom__ +#endif +#ifndef __romstr__ +#define __romstr__ +#endif +#ifndef __romarr__ +#define __romarr__ const char +#endif +#ifndef rom_strptr +#define rom_strptr * +#endif +#ifndef rom_strcpy +#define rom_strcpy strcpy +#endif +#ifndef rom_strncpy +#define rom_strncpy strncpy +#endif +#ifndef rom_memcpy +#define rom_memcpy memcpy +#endif +#ifndef rom_read_byte +#define rom_read_byte * +#endif + + // the extern is not necessary + // this explicit declaration just serves to reeinforce the idea that these callbacks are implemented on other µCNC core code translation units + // these callbacks provide a transparent way for the mcu to call them when the ISR/IRQ is triggered + + MCU_CALLBACK void mcu_step_cb(void); + MCU_CALLBACK void mcu_step_reset_cb(void); + MCU_RX_CALLBACK void mcu_com_rx_cb(uint8_t c); + MCU_CALLBACK void mcu_rtc_cb(uint32_t millis); + MCU_IO_CALLBACK void mcu_controls_changed_cb(void); + MCU_IO_CALLBACK void mcu_limits_changed_cb(void); + MCU_IO_CALLBACK void mcu_probe_changed_cb(void); + MCU_IO_CALLBACK void mcu_inputs_changed_cb(void); + +/*IO functions*/ + +/** + * config a pin in input mode + * can be defined either as a function or a macro call + * */ +#ifndef mcu_config_input + void mcu_config_input(uint8_t pin); +#endif + +/** + * config pullup + * can be defined either as a function or a macro call + * */ +#ifndef mcu_config_pullup + void mcu_config_pullup(uint8_t pin); +#endif + +/** + * config a pin in output mode + * can be defined either as a function or a macro call + * */ +#ifndef mcu_config_output + void mcu_config_output(uint8_t pin); +#endif + +/** + * get the value of a digital input pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_input + uint8_t mcu_get_input(uint8_t pin); +#endif + +/** + * gets the value of a digital output pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_output + uint8_t mcu_get_output(uint8_t pin); +#endif + +/** + * sets the value of a digital output pin to logical 1 + * can be defined either as a function or a macro call + * */ +#ifndef mcu_set_output + void mcu_set_output(uint8_t pin); +#endif + +/** + * sets the value of a digital output pin to logical 0 + * can be defined either as a function or a macro call + * */ +#ifndef mcu_clear_output + void mcu_clear_output(uint8_t pin); +#endif + +/** + * toggles the value of a digital output pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_toggle_output + void mcu_toggle_output(uint8_t pin); +#endif + + /** + * + * This is used has by the generic mcu functions has generic (overridable) IO initializer + * + * */ + void mcu_io_init(void); + + /** + * initializes the mcu + * this function needs to: + * - configure all IO pins (digital IO, PWM, Analog, etc...) + * - configure all interrupts + * - configure uart or usb + * - start the internal RTC + * */ + void mcu_init(void); + +/** + * enables the pin probe mcu isr on change + * can be defined either as a function or a macro call + * */ +#ifndef mcu_enable_probe_isr + void mcu_enable_probe_isr(void); +#endif + +/** + * disables the pin probe mcu isr on change + * can be defined either as a function or a macro call + * */ +#ifndef mcu_disable_probe_isr + void mcu_disable_probe_isr(void); +#endif + +/** + * gets the voltage value of a built-in ADC pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_analog + uint16_t mcu_get_analog(uint8_t channel); +#endif + +/** + * configs the pwm pin and output frequency + * can be defined either as a function or a macro call + * */ +#ifndef mcu_config_pwm + void mcu_config_pwm(uint8_t pin, uint16_t freq); +#endif + +/** + * sets the pwm value of a built-in pwm pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_set_pwm + void mcu_set_pwm(uint8_t pwm, uint8_t value); +#endif + +/** + * gets the configured pwm value of a built-in pwm pin + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_pwm + uint8_t mcu_get_pwm(uint8_t pwm); +#endif + +/** + * sets the pwm for a servo (50Hz with tON between 1~2ms) + * can be defined either as a function or a macro call + * */ +#ifndef mcu_set_servo + void mcu_set_servo(uint8_t servo, uint8_t value); +#endif + +/** + * gets the pwm for a servo (50Hz with tON between 1~2ms) + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_servo + uint8_t mcu_get_servo(uint8_t servo); +#endif + +// ISR +/** + * enables global interrupts on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_enable_global_isr + void mcu_enable_global_isr(void); +#endif + +/** + * disables global interrupts on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_disable_global_isr + void mcu_disable_global_isr(void); +#endif + +/** + * gets global interrupts state on the MCU + * can be defined either as a function or a macro call + * */ +#ifndef mcu_get_global_isr + bool mcu_get_global_isr(void); +#endif + + // Step interpolator + /** + * convert step rate/frequency to timer ticks and prescaller + * */ + void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller); + + /** + * convert timer ticks and prescaller to step rate/frequency + * */ + float mcu_clocks_to_freq(uint16_t ticks, uint16_t prescaller); + + /** + * starts the timer interrupt that generates the step pulses for the interpolator + * */ + void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller); + + /** + * changes the step rate of the timer interrupt that generates the step pulses for the interpolator + * */ + void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller); + + /** + * stops the timer interrupt that generates the step pulses for the interpolator + * */ + void mcu_stop_itp_isr(void); + + /** + * gets the MCU running time in milliseconds. + * the time counting is controled by the internal RTC + * */ + uint32_t mcu_millis(void); + + /** + * gets the MCU running time in microseconds. + * the time counting is controled by the internal RTC + * */ + uint32_t mcu_micros(void); + +#ifndef mcu_nop +#define mcu_nop() asm volatile("nop\n\t") +#endif + + void mcu_delay_loop(uint16_t loops); + +#ifndef mcu_delay_cycles +// set per MCU +#ifndef MCU_CLOCKS_PER_CYCLE +#error "MCU_CLOCKS_PER_CYCLE not defined for this MCU" +#endif +#ifndef MCU_CYCLES_PER_LOOP_OVERHEAD +#error "MCU_CYCLES_PER_LOOP_OVERHEAD not defined for this MCU" +#endif +#ifndef MCU_CYCLES_PER_LOOP +#error "MCU_CYCLES_PER_LOOP not defined for this MCU" +#endif +#ifndef MCU_CYCLES_PER_LOOP_OVERHEAD +#error "MCU_CYCLES_PER_LOOP_OVERHEAD not defined for this MCU" +#endif + +#define mcu_delay_cycles(X) \ + { \ + if (X > (MCU_CYCLES_PER_LOOP + MCU_CYCLES_PER_LOOP_OVERHEAD)) \ + { \ + mcu_delay_loop((uint16_t)((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP)); \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 0) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 1) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 2) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 3) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 4) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 5) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 6) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 7) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 8) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 9) \ + { \ + mcu_nop(); \ + } \ + if (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) - (((X - MCU_CYCLES_PER_LOOP_OVERHEAD) / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 10) \ + { \ + mcu_nop(); \ + } \ + } \ + else \ + { \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 0) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 1) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 2) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 3) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 4) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 5) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 6) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 7) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 8) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 9) \ + { \ + mcu_nop(); \ + } \ + if ((X - ((X / MCU_CYCLES_PER_LOOP) * MCU_CYCLES_PER_LOOP)) > 10) \ + { \ + mcu_nop(); \ + } \ + } \ + } +#endif + +#ifndef mcu_delay_100ns +#define mcu_delay_100ns() mcu_delay_cycles((F_CPU / MCU_CLOCKS_PER_CYCLE / 10000000UL)) +#endif + +/** + * provides a delay in us (micro seconds) + * the maximum allowed delay is 255 us + * */ +#ifndef mcu_delay_us +#define mcu_delay_us(X) mcu_delay_cycles(F_CPU / MCU_CLOCKS_PER_CYCLE / 1000000UL * X) +#endif + +#ifdef MCU_HAS_ONESHOT_TIMER + typedef void (*mcu_timeout_delgate)(void); + extern MCU_CALLBACK mcu_timeout_delgate mcu_timeout_cb; +/** + * configures a single shot timeout in us + * */ +#ifndef mcu_config_timeout + void mcu_config_timeout(mcu_timeout_delgate fp, uint32_t timeout); +#endif + +/** + * starts the timeout. Once hit the the respective callback is called + * */ +#ifndef mcu_start_timeout + void mcu_start_timeout(); +#endif +#endif + + /** + * runs all internal tasks of the MCU. + * for the moment these are: + * - if USB is enabled and MCU uses tinyUSB framework run tinyUSB tud_task + * */ + void mcu_dotasks(void); + + // Non volatile memory + /** + * gets a byte at the given EEPROM (or other non volatile memory) address of the MCU. + * */ + uint8_t mcu_eeprom_getc(uint16_t address); + + /** + * sets a byte at the given EEPROM (or other non volatile memory) address of the MCU. + * */ + void mcu_eeprom_putc(uint16_t address, uint8_t value); + + /** + * flushes all recorded registers into the eeprom. + * */ + void mcu_eeprom_flush(void); + +#ifdef MCU_HAS_SPI +#ifndef mcu_spi_xmit + uint8_t mcu_spi_xmit(uint8_t data); +#endif + +#ifndef mcu_spi_config + void mcu_spi_config(uint8_t mode, uint32_t frequency); +#endif +#endif + +#ifdef MCU_HAS_I2C +#ifndef I2C_OK +#define I2C_OK 0 +#endif +#ifndef I2C_NOTOK +#define I2C_NOTOK 1 +#endif + +#ifndef mcu_i2c_send + // master sends command to slave + uint8_t mcu_i2c_send(uint8_t address, uint8_t *data, uint8_t datalen, bool release); +#endif +#ifndef mcu_i2c_receive + // master receive response from slave + uint8_t mcu_i2c_receive(uint8_t address, uint8_t *data, uint8_t datalen, uint32_t ms_timeout); +#endif + +#if defined(MCU_SUPPORTS_I2C_SLAVE) && (I2C_ADDRESS != 0) +#ifndef I2C_SLAVE_BUFFER_SIZE +#define I2C_SLAVE_BUFFER_SIZE 48 +#endif +#ifndef mcu_i2c_slave_cb + MCU_IO_CALLBACK void mcu_i2c_slave_cb(uint8_t *data, uint8_t *datalen); +#endif +#endif + +#ifndef mcu_i2c_config + void mcu_i2c_config(uint32_t frequency); +#endif + +#endif + +#ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS + uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char); +#endif + +/** + * sends a char either via uart (hardware, software USB CDC, Wifi or BT) + * can be defined either as a function or a macro call + * */ +#ifndef mcu_putc + void mcu_putc(uint8_t c); +#endif + +#ifndef mcu_flush + void mcu_flush(void); +#endif + +#ifdef MCU_HAS_USB + void mcu_usb_putc(uint8_t c); + void mcu_usb_flush(void); +#ifdef DETACH_USB_FROM_MAIN_PROTOCOL + MCU_RX_CALLBACK void mcu_usb_rx_cb(uint8_t c); +#endif +#endif + +#ifdef MCU_HAS_UART + void mcu_uart_putc(uint8_t c); + void mcu_uart_flush(void); +#ifdef DETACH_UART_FROM_MAIN_PROTOCOL + MCU_RX_CALLBACK void mcu_uart_rx_cb(uint8_t c); +#endif +#endif + +#ifdef MCU_HAS_UART2 + void mcu_uart2_putc(uint8_t c); + void mcu_uart2_flush(void); +#ifdef DETACH_UART2_FROM_MAIN_PROTOCOL + MCU_RX_CALLBACK void mcu_uart2_rx_cb(uint8_t c); +#endif +#endif + +#ifdef MCU_HAS_WIFI + void mcu_wifi_putc(uint8_t c); + void mcu_wifi_flush(void); +#ifdef DETACH_WIFI_FROM_MAIN_PROTOCOL + MCU_RX_CALLBACK void mcu_wifi_rx_cb(uint8_t c); +#endif +#endif + +#ifdef MCU_HAS_BLUETOOTH + void mcu_bt_putc(uint8_t c); + void mcu_bt_flush(void); +#ifdef DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL + MCU_RX_CALLBACK void mcu_bt_rx_cb(uint8_t c); +#endif +#endif + ``` + +Also internally **AT LEAST** these macros need to be defined + +``` +// defines the maximum and minimum step rates +#ifndef F_STEP_MAX +#define F_STEP_MAX 100000 +#endif +// defines special mcu to access flash strings and arrays +// the following definition will work on all MCU +// custom adjustments can be tailored for each MCU architecture (check for example AVR) +#define __rom__ +#define __romstr__ +#define __romarr__ const char +#define rom_strptr * +#define rom_strcpy strcpy +#define rom_strncpy strncpy +#define rom_memcpy memcpy +#define rom_read_byte * +``` + +And add some definitions to generate internal software delays like this +``` +// needed by software delays +#ifndef MCU_CLOCKS_PER_CYCLE +#define MCU_CLOCKS_PER_CYCLE 1 +#endif +#ifndef MCU_CYCLES_PER_LOOP +#define MCU_CYCLES_PER_LOOP 4 +#endif +#ifndef MCU_CYCLES_PER_LOOP_OVERHEAD +#define MCU_CYCLES_PER_LOOP_OVERHEAD 11 +#endif + +/* OR IN ALTERNATIVE YOU CAN DEFINE A CUSTOM CYCLE DELAY FUNCTION LIKE FOR EXAMPLE USED IN ARM */ + +// needed by software delays +#ifndef MCU_CLOCKS_PER_CYCLE +#define MCU_CLOCKS_PER_CYCLE 1 +#endif +#define mcu_delay_cycles(X) \ + { \ + DWT->CYCCNT = 0; \ + uint32_t t = X; \ + while (t > DWT->CYCCNT) \ + ; \ + } +``` + + + Internally the implementation of the MCU must: + + - use a interrupt timer to call `mcu_step_cb()` and `mcu_step_reset_cb()` alternately (evenly spaced). Both these ISR run once every step at a maximum rate (set by Grbl's setting `$0`) + + - use a 1ms interrupt timer or RTC to generate the running time and call `mcu_rtc_cb(uint32_t millis)`. `mcu_dotasks()` **MUST NOT BE CALLED HERE** + + - if a hardware communications has events or ISR, the ISR must call `mcu_com_rx_cb(unsigned char c)` with the received char, or if handled internally by library or RTOS send every received char in the buffer through `mcu_com_rx_cb(unsigned char c)`. + + - if interruptible inputs are used they appropriately call mcu_limits_changed_cb(), mcu_controls_changed_cb(), mcu_probe_changed_cb() and mcu_inputs_changed_cb() + + **2. Map all µCNC internal pin names to I/O pins** + + The HAL must know the I/O pin to modify when the core want's to modify STEP0 pin for example. Again...µCNC doesn't care how it's done as long has it does what it is asked...If the switch is flicked on the bulb should turn on... simple. + + **3. Add the new board and mcu libraries to µCNC** + + * The mcu to the `mcus.h` file and give it an ID. Add the needed libraries to load if the MCU is chosen in the `mcudefs.f` file. + * Execute the same steps above for files `boards.h` and `boarddefs.h` + + **4. Create the project and build** + From this point on you just need to create a project to run the program. This can be either a `main` file and a `makefile` and build, or using Arduino IDE to compile the project (the appropriate core/board manager must also be installed). + Then on main just call the two functions needed to run µCNC. A bare minimum main file should look like this + +``` +#include "cnc.h" + +void main(void) +{ + //initializes all systems + cnc_init(); -## How to add a custom MCU to µCNC -µCNC can be extended to other custom MCU as well. For that you only need to define how your mcu responds to the HAL interface: - 1. Create the needed files that implements all the functions defined in the [mcu.h](https://github.com/Paciente8159/uCNC/blob/master/src/hal/mcus/mcu.h) header file. mcu.h acts has the HAL interface and contains all the needed mcu function declarations that µCNC needs (direct IO operations, pwm outputs, analog reading, communications, etc...). - 2. You must also edit [mcus.h](https://github.com/Paciente8159/uCNC/blob/master/src/hal/mcus/mcus.h) and [mcudefs.h](https://github.com/Paciente8159/uCNC/blob/master/src/hal/mcus/mcudefs.h) to add you custom MCU. + for(;;) + { + cnc_run(); + } - Compile it and test it. +} - For more detailed explanation please refer to the [wiki](https://github.com/Paciente8159/uCNC/wiki/Understanding-the-HAL#Creating-the-HAL-for-a-custom-MCU) +``` \ No newline at end of file diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index e67843ed5..e24590124 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -33,16 +33,42 @@ extern "C" #define MCU_CALLBACK #endif -#ifndef MCU_TX_CALLBACK -#define MCU_TX_CALLBACK MCU_CALLBACK -#endif - #ifndef MCU_RX_CALLBACK #define MCU_RX_CALLBACK MCU_CALLBACK #endif #ifndef MCU_IO_CALLBACK #define MCU_IO_CALLBACK MCU_CALLBACK +#endif + +#ifndef F_STEP_MAX +#define F_STEP_MAX 30000 +#endif + +// defines special mcu to access flash strings and arrays +#ifndef __rom__ +#define __rom__ +#endif +#ifndef __romstr__ +#define __romstr__ +#endif +#ifndef __romarr__ +#define __romarr__ const char +#endif +#ifndef rom_strptr +#define rom_strptr * +#endif +#ifndef rom_strcpy +#define rom_strcpy strcpy +#endif +#ifndef rom_strncpy +#define rom_strncpy strncpy +#endif +#ifndef rom_memcpy +#define rom_memcpy memcpy +#endif +#ifndef rom_read_byte +#define rom_read_byte * #endif // the extern is not necessary @@ -52,7 +78,6 @@ extern "C" MCU_CALLBACK void mcu_step_cb(void); MCU_CALLBACK void mcu_step_reset_cb(void); MCU_RX_CALLBACK void mcu_com_rx_cb(uint8_t c); - MCU_TX_CALLBACK void mcu_com_tx_cb(); MCU_CALLBACK void mcu_rtc_cb(uint32_t millis); MCU_IO_CALLBACK void mcu_controls_changed_cb(void); MCU_IO_CALLBACK void mcu_limits_changed_cb(void); From cac5a8d3a31016fb61af9f35855fe76c8125a039 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 23:34:32 +0100 Subject: [PATCH 058/168] added readme for MCU HAL --- uCNC/src/cnc_hal_config_helper.h | 3 + uCNC/src/hal/mcus/README.md | 296 +++++++++++++++++++------------ 2 files changed, 189 insertions(+), 110 deletions(-) diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 8dd5dc677..ba72b5b5a 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -730,6 +730,9 @@ extern "C" /** * final pin cleaning and configuration **/ +#ifndef DIO0 +#define DIO0 UNDEF_PIN +#endif #ifndef STEP0 #define STEP0 UNDEF_PIN #ifdef DIO1 diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index daddeb476..ae762828e 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -7,26 +7,30 @@ µCNC - Universal CNC firmware for microcontrollers _**Jump to section**_ -* [µCNC HAL](#µCNC-HAL) -* [The microcontroller HAL](#The-microcontroller-HAL) - * [Pin naming conventions ](#pin-naming-conventions ) +* [µCNC HAL](#µcnc-hal) +* [The microcontroller HAL](#the-microcontroller-hal) + * [The microcontroller IO internal logic](#the-microcontroller-io-internal-logic) + * [Pin naming conventions](#pin-naming-conventions) * [Creating the HAL for a custom MCU](#creating-the-hal-for-a-custom-mcu) # µCNC HAL (Hardware Abstraction Layer) -µCNC has several HAL dimensions/layers. The first is the microcontroller HAL. +µCNC has several HAL dimensions/layers. The first and most important layer is the microcontroller HAL. This HAL provides the abstraction layer needed to use all the core functionalities in any microcontroller/PC board. ## The microcontroller HAL -This HAL is actually composed of two parts. The MCU and the board/kit. +Starting version 1.8, this HAL is actually composed of three parts (instead of 2 like in the previous versions). The MCU, the board/kit HAL and the new IO HAL. * The MCU defines all the basic functions required by the µCNC to write and read on and from the microcontroller I/O. These functions include for example how to set or clear an output pin or read from an input pin. * The board contains all the definitions needed to map the µCNC internal named pins to the microcontroller physical pins. - * From v1.2.0 on there is a general cnc_hal_config.h file that allows to connect the general purpose pins to certain modules or functionalities. This allows the user to customize µCNC for custom needs. + * From v1.8.0 and newer a new IO HAL was introduced. This allow the precompiller to link at build time the correct I/O function (either direct MCU IO pin or using a supported extender like the IC74HC595). -The way to implement/code this completely free. The only thing µCNC needs to know is that when it want's to set the step pin of motor 0 high it has to call: -```mcu_set_output(STEP0);``` +The way this works is like this: + +### The microcontroller IO internal logic + +Every pin inside µCNC has a friendly definition, an intermediate translation definition and an internal number definition. ### Pin naming conventions -µCNC sets a list of names that are used by the core functions to tell the microcontroller what to do. +µCNC sets a list of names that are used by the core functions to tell the microcontroller what to do. These have friendly names to make them easy to understand. These are the fixed names used internally: #### Output pins - special @@ -76,86 +80,86 @@ SPI_CLK These pins also obey a numbering system to make them transversal between boards and MCU as mapped in the table bellow: -| Pin number | Alias | Pin name | +| Pin value | Alias | Pin name | | --- | --- | --- | -| 0 | DIO0 | STEP0 | -| 1 | DIO1 | STEP1 | -| 2 | DIO2 | STEP2 | -| 3 | DIO3 | STEP3 | -| 4 | DIO4 | STEP4 | -| 5 | DIO5 | STEP5 | -| 6 | DIO6 | STEP6 | -| 7 | DIO7 | STEP7 | -| 8 | DIO8 | DIR0 | -| 9 | DIO9 | DIR1 | -| 10 | DIO10 | DIR2 | -| 11 | DIO11 | DIR3 | -| 12 | DIO12 | DIR4 | -| 13 | DIO13 | DIR5 | -| 14 | DIO14 | DIR6 | -| 15 | DIO15 | DIR7 | -| 16 | DIO16 | STEP0_EN | -| 17 | DIO17 | STEP1_EN | -| 18 | DIO18 | STEP2_EN | -| 19 | DIO19 | STEP3_EN | -| 20 | DIO20 | STEP4_EN | -| 21 | DIO21 | STEP5_EN | -| 22 | DIO22 | STEP6_EN | -| 23 | DIO23 | STEP7_EN | -| 24 | DIO24 | PWM0 | -| 25 | DIO25 | PWM1 | -| 26 | DIO26 | PWM2 | -| 27 | DIO27 | PWM3 | -| 28 | DIO28 | PWM4 | -| 29 | DIO29 | PWM5 | -| 30 | DIO30 | PWM6 | -| 31 | DIO31 | PWM7 | -| 32 | DIO32 | PWM8 | -| 33 | DIO33 | PWM9 | -| 34 | DIO34 | PWM10 | -| 35 | DIO35 | PWM11 | -| 36 | DIO36 | PWM12 | -| 37 | DIO37 | PWM13 | -| 38 | DIO38 | PWM14 | -| 39 | DIO39 | PWM15 | -| 40 | DIO40 | SERVO0 | -| 41 | DIO41 | SERVO1 | -| 42 | DIO42 | SERVO2 | -| 43 | DIO43 | SERVO3 | -| 44 | DIO44 | SERVO4 | -| 45 | DIO45 | SERVO5 | -| 46 | DIO46 | DOUT0 | -| 47 | DIO47 | DOUT1 | -| 48 | DIO48 | DOUT2 | -| 49 | DIO49 | DOUT3 | -| 50 | DIO50 | DOUT4 | -| 51 | DIO51 | DOUT5 | -| 52 | DIO52 | DOUT6 | -| 53 | DIO53 | DOUT7 | -| 54 | DIO54 | DOUT8 | -| 55 | DIO55 | DOUT9 | -| 56 | DIO56 | DOUT10 | -| 57 | DIO57 | DOUT11 | -| 58 | DIO58 | DOUT12 | -| 59 | DIO59 | DOUT13 | -| 60 | DIO60 | DOUT14 | -| 61 | DIO61 | DOUT15 | -| 62 | DIO62 | DOUT16 | -| 63 | DIO63 | DOUT17 | -| 64 | DIO64 | DOUT18 | -| 65 | DIO65 | DOUT19 | -| 66 | DIO66 | DOUT20 | -| 67 | DIO67 | DOUT21 | -| 68 | DIO68 | DOUT22 | -| 69 | DIO69 | DOUT23 | -| 70 | DIO70 | DOUT24 | -| 71 | DIO71 | DOUT25 | -| 72 | DIO72 | DOUT26 | -| 73 | DIO73 | DOUT27 | -| 74 | DIO74 | DOUT28 | -| 75 | DIO75 | DOUT29 | -| 76 | DIO76 | DOUT30 | -| 77 | DIO77 | DOUT31 | +| 1 | DIO1 | STEP0 | +| 2 | DIO2 | STEP1 | +| 3 | DIO3 | STEP2 | +| 4 | DIO4 | STEP3 | +| 5 | DIO5 | STEP4 | +| 6 | DIO6 | STEP5 | +| 7 | DIO7 | STEP6 | +| 8 | DIO8 | STEP7 | +| 9 | DIO9 | DIR0 | +| 10 | DIO10 | DIR1 | +| 11 | DIO11 | DIR2 | +| 12 | DIO12 | DIR3 | +| 13 | DIO13 | DIR4 | +| 14 | DIO14 | DIR5 | +| 15 | DIO15 | DIR6 | +| 16 | DIO16 | DIR7 | +| 17 | DIO17 | STEP0_EN | +| 18 | DIO18 | STEP1_EN | +| 19 | DIO19 | STEP2_EN | +| 20 | DIO20 | STEP3_EN | +| 21 | DIO21 | STEP4_EN | +| 22 | DIO22 | STEP5_EN | +| 23 | DIO23 | STEP6_EN | +| 24 | DIO24 | STEP7_EN | +| 25 | DIO25 | PWM0 | +| 26 | DIO26 | PWM1 | +| 27 | DIO27 | PWM2 | +| 28 | DIO28 | PWM3 | +| 29 | DIO29 | PWM4 | +| 30 | DIO30 | PWM5 | +| 31 | DIO31 | PWM6 | +| 32 | DIO32 | PWM7 | +| 33 | DIO33 | PWM8 | +| 34 | DIO34 | PWM9 | +| 35 | DIO35 | PWM10 | +| 36 | DIO36 | PWM11 | +| 37 | DIO37 | PWM12 | +| 38 | DIO38 | PWM13 | +| 39 | DIO39 | PWM14 | +| 40 | DIO40 | PWM15 | +| 41 | DIO41 | SERVO0 | +| 42 | DIO42 | SERVO1 | +| 43 | DIO43 | SERVO2 | +| 44 | DIO44 | SERVO3 | +| 45 | DIO45 | SERVO4 | +| 46 | DIO46 | SERVO5 | +| 47 | DIO47 | DOUT0 | +| 48 | DIO48 | DOUT1 | +| 49 | DIO49 | DOUT2 | +| 50 | DIO50 | DOUT3 | +| 51 | DIO51 | DOUT4 | +| 52 | DIO52 | DOUT5 | +| 53 | DIO53 | DOUT6 | +| 54 | DIO54 | DOUT7 | +| 55 | DIO55 | DOUT8 | +| 56 | DIO56 | DOUT9 | +| 57 | DIO57 | DOUT10 | +| 58 | DIO58 | DOUT11 | +| 59 | DIO59 | DOUT12 | +| 60 | DIO60 | DOUT13 | +| 61 | DIO61 | DOUT14 | +| 62 | DIO62 | DOUT15 | +| 63 | DIO63 | DOUT16 | +| 64 | DIO64 | DOUT17 | +| 65 | DIO65 | DOUT18 | +| 66 | DIO66 | DOUT19 | +| 67 | DIO67 | DOUT20 | +| 68 | DIO68 | DOUT21 | +| 69 | DIO69 | DOUT22 | +| 70 | DIO70 | DOUT23 | +| 71 | DIO71 | DOUT24 | +| 72 | DIO72 | DOUT25 | +| 73 | DIO73 | DOUT26 | +| 74 | DIO74 | DOUT27 | +| 75 | DIO75 | DOUT28 | +| 76 | DIO76 | DOUT29 | +| 77 | DIO77 | DOUT30 | +| 78 | DIO78 | DOUT31 | | 100 | DIO100 | LIMIT_X | | 101 | DIO101 | LIMIT_Y | | 102 | DIO102 | LIMIT_Z | @@ -231,6 +235,40 @@ These pins also obey a numbering system to make them transversal between boards | 210 | DIO210 | TX2 | | 211 | DIO211 | RX2 | +With the introduction of the new IO HAL `src/hal/io_hal.h` all these definitions/values must be interchangable and match the above table. +`src/hal/io_hal.h` and `src/core/io_control.h` will then provide a series of preprocessor macros that translate between a µCNC IO call and the actual MCU IO call, based on all the available information (the IO HAL, the boardmap and the MCU HAL). + +This (I hope) will become clearer in the example at the end of this file. + +### How is a pin evaluated? + +As state before a pin must respect the constrains described in the previous table. +If an IO pin is defined (for example STEP0), then it can only assume 3 values: + +It's an MCU IO pin then: +STEP0 must evaluate to value 1 and DIO1 must evaluate to 1 also + +It's an extended IO pin then: +STEP0 must evaluate to value 1 and DIO1 must evaluate to -1 + +If it's and undefined pin then +STEP0 must evaluate to value 0 and DIO1 must evaluate to 0 also + +Lets take and example: + +When we want to set generic output pin 0 (friendly name DOUT0) pin high we call this: + +`io_set_output(DOUT0);` + +Internally µCNC starts to decode this by a series of translations performed by the preprocessor, that are performed this way + * `io_set_output(DOUT0);` -> DOUT0 (friendly name) is converted to a µCNC internal pin value. In this case DOUT0 is number 47. If not defined all pins will return 0. + * Next this number is prefixed with `DIO` and is converted to an intermediate translation name `DIO47` (or DIO0 if undefined). + * DIO47 is evaluated also for it's value. If DIO47 is positive then it's an IO pin of the MCU. If is negative then it's an extended pin via a supported extender (currently only IC74HC595 or similar). In our example it will evaluate to 47 (and IO pin of the MCU). + * `io_set_output(DOUT0);` will then go through several translations and will become `mcu_set_output(STEP0)`. This function or preprocessor macro is part of the mcu template that has to be created for each MCU and implements the way the it does certain tasks, like setting and output pin logic high for example. + +This is kind of convoluted work ensures that the once the translation HAL between the MCU and µCNC is correctly created, every part of the core and most modules work as expected in your microcontroller. +A bit further down on this document an example to use the Arduino framework will be provided, to make this easier to understand. + ### Creating the HAL for a custom MCU Before creating a custom HAL for a custom board/microcontroller the microcontroller must have the following hardware features available: * At least 2 hardware timers (it might be possible with only a single timer but with limitations) @@ -787,25 +825,6 @@ Before creating a custom HAL for a custom board/microcontroller the microcontrol Also internally **AT LEAST** these macros need to be defined -``` -// defines the maximum and minimum step rates -#ifndef F_STEP_MAX -#define F_STEP_MAX 100000 -#endif -// defines special mcu to access flash strings and arrays -// the following definition will work on all MCU -// custom adjustments can be tailored for each MCU architecture (check for example AVR) -#define __rom__ -#define __romstr__ -#define __romarr__ const char -#define rom_strptr * -#define rom_strcpy strcpy -#define rom_strncpy strncpy -#define rom_memcpy memcpy -#define rom_read_byte * -``` - -And add some definitions to generate internal software delays like this ``` // needed by software delays #ifndef MCU_CLOCKS_PER_CYCLE @@ -833,7 +852,6 @@ And add some definitions to generate internal software delays like this } ``` - Internally the implementation of the MCU must: - use a interrupt timer to call `mcu_step_cb()` and `mcu_step_reset_cb()` alternately (evenly spaced). Both these ISR run once every step at a maximum rate (set by Grbl's setting `$0`) @@ -855,7 +873,66 @@ And add some definitions to generate internal software delays like this **4. Create the project and build** From this point on you just need to create a project to run the program. This can be either a `main` file and a `makefile` and build, or using Arduino IDE to compile the project (the appropriate core/board manager must also be installed). - Then on main just call the two functions needed to run µCNC. A bare minimum main file should look like this + Then on main just call the two functions needed to run µCNC. A bare minimum main file should look like this: + + ``` + #include "cnc.h" + + void main(void) + { + //initializes all systems + cnc_init(); + + for(;;) + { + cnc_run(); + } + + } + + ``` + +Again the example bellow will (I hope) help to clarify this. + +### An example of implementing the some functions for a custom MCU + +Now for a practical example of how to implement all this. + +Let's create a boarmap were we link the internal µCNC pins and then make the MCU execute the desired action. +This example will use Arduino IDE as a base. + +In our boardmap we need to assign out pins. These names and definitions can be set freely + +Let's also assume that on your boardmap you want to define pins using Arduino IDE pin numbers with the and you have DOUT0 pin defined like _PIN: + +`#define DOUT0_PIN 50 // DOUT0 is pin 50 of the IDE` + +Assuming that this is an actual IO pin of the MCU we can tell the IO HAL that the pin exists like this: + +``` +#if defined(DOUT0_PIN) +#define DOUT0 47 +#define DIO47 47 +#endif +``` + +The IO HAL will try to set this pin by calling the `mcu.h` function `mcu_set_output(pin)`. We can define it like this: + +``` +// this not a performant way to do this but works as an example +void mcu_set_output(uint8_t pin){ + switch(pin){ + case DOUT0: + digitalWrite(DOUT0_PIN); + break; + + ...other pins... + } +} + +``` + + ``` #include "cnc.h" @@ -873,4 +950,3 @@ void main(void) } ``` - \ No newline at end of file From 50e58147206a991ba224777f85653a5b6c657e6c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 23:35:52 +0100 Subject: [PATCH 059/168] Update README.md --- uCNC/src/hal/mcus/README.md | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index ae762828e..de205136a 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -875,22 +875,21 @@ Also internally **AT LEAST** these macros need to be defined From this point on you just need to create a project to run the program. This can be either a `main` file and a `makefile` and build, or using Arduino IDE to compile the project (the appropriate core/board manager must also be installed). Then on main just call the two functions needed to run µCNC. A bare minimum main file should look like this: - ``` - #include "cnc.h" - - void main(void) - { - //initializes all systems - cnc_init(); +``` +#include "cnc.h" - for(;;) - { - cnc_run(); - } +void main(void) +{ + //initializes all systems + cnc_init(); + for(;;) + { + cnc_run(); } - ``` +} +``` Again the example bellow will (I hope) help to clarify this. From 6ea8cd8a26569e735ad9065af23c85a8c637b7c5 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 26 Jul 2023 23:37:12 +0100 Subject: [PATCH 060/168] Update README.md --- uCNC/src/hal/mcus/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index de205136a..a3bcdf768 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -902,7 +902,7 @@ This example will use Arduino IDE as a base. In our boardmap we need to assign out pins. These names and definitions can be set freely -Let's also assume that on your boardmap you want to define pins using Arduino IDE pin numbers with the and you have DOUT0 pin defined like _PIN: +Let's also assume that on your boardmap you want to define pins using Arduino IDE pin numbers with the and you have DOUT0 pin defined like friendly_name_PIN: `#define DOUT0_PIN 50 // DOUT0 is pin 50 of the IDE` From efecc3f3a446b78b2237ee2467dc9190a0242a58 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 27 Jul 2023 10:26:12 +0100 Subject: [PATCH 061/168] Update README.md --- uCNC/src/hal/mcus/README.md | 46 ++++++++++++++++++++++++++----------- 1 file changed, 32 insertions(+), 14 deletions(-) diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index a3bcdf768..98dae1912 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -11,7 +11,9 @@ _**Jump to section**_ * [The microcontroller HAL](#the-microcontroller-hal) * [The microcontroller IO internal logic](#the-microcontroller-io-internal-logic) * [Pin naming conventions](#pin-naming-conventions) + * [How is a pin evaluated?](#how-is-a-pin-evaluated) * [Creating the HAL for a custom MCU](#creating-the-hal-for-a-custom-mcu) + * [An example of implementing the some functions for a custom MCU](#an-example-of-implementing-the-some-functions-for-a-custom-mcu) # µCNC HAL (Hardware Abstraction Layer) µCNC has several HAL dimensions/layers. The first and most important layer is the microcontroller HAL. @@ -900,18 +902,26 @@ Now for a practical example of how to implement all this. Let's create a boarmap were we link the internal µCNC pins and then make the MCU execute the desired action. This example will use Arduino IDE as a base. -In our boardmap we need to assign out pins. These names and definitions can be set freely +In our boardmap we need to create a way to assign out pins. These names and definitions can be set freely. Accross all MCU it was conventioned to use a friendly_name_BIT and friendly_name_PORT, but this is not mandatory. For example in AVR to set up a pin we do it like this: -Let's also assume that on your boardmap you want to define pins using Arduino IDE pin numbers with the and you have DOUT0 pin defined like friendly_name_PIN: +``` +// assign DOUT0 to pin B4 of the MCU +#define DOUT0_BIT 4 +#define DOUT0_PORT B +``` -`#define DOUT0_PIN 50 // DOUT0 is pin 50 of the IDE` +Let's also assume that on your boardmap you want to define pins using Arduino IDE pin numbers with the and you have DOUT0 pin defined like friendly_name_IDEPIN: + +`#define DOUT0_IDEPIN 50 // DOUT0 is pin 50 of the IDE` Assuming that this is an actual IO pin of the MCU we can tell the IO HAL that the pin exists like this: ``` -#if defined(DOUT0_PIN) +// if DOUT0 IDE pin is defined then define DOUT0 and DIO47 to match the table +#if defined(DOUT0_IDEPIN) #define DOUT0 47 #define DIO47 47 +#define DIO47_IDEPIN DOUT0_IDEPIN // calling DOUT0_IDEPIN or DIO47_IDEPIN will be the same. this will prove usefull later #endif ``` @@ -931,21 +941,29 @@ void mcu_set_output(uint8_t pin){ ``` +There is a way to improve this and avoid going through a long switch/case statement for all pins. With a bit a preprocessor trickery we can make a direct call (that is why it's possible to define some calls as functions or macros). + +Let's define a couple of macros to resolve the friendly name to out friendly_name_IDEPIN definition. +Here is a preprocessor trick. This macro takes 2 arguments, makes some replacements and concatenates the replacement results ``` -#include "cnc.h" +// Indirect macro access +#ifndef __indirect__ +#define __indirect__ex__(X, Y) DIO##X##_##Y +#define __indirect__(X, Y) __indirect__ex__(X, Y) +#endif +``` -void main(void) -{ - //initializes all systems - cnc_init(); +So if we call `__indirect__(DOUT0, IDEPIN)` it will first evaluate both parameters to resolve them. `DOUT0` will be replaced by 47 and IDEPIN (if you have not created any definition for it) will remain the same and will be passed to the next macro. Next `47` and `IDEPIN` wil be be concatenated to `DIO` and `_` and will become `DIO47_IDEPIN` that is equivalent to `DOUT0_IDEPIN`. - for(;;) - { - cnc_run(); - } +Resuming: `__indirect__(DOUT0, IDEPIN)` -> `__indirect__ex__(47, IDEPIN)` -> `DIO47_IDEPIN` -> `DOUT0_IDEPIN` -> `50` -} +We can now define a macro `mcu_set_output` that makes use of this replacement and converts to our Arduino call to `digitalWrite` like this: ``` +#define mcu_set_output(X) digitalWrite(__indirect__(X, IDEPIN)) +``` + +Again the preprocessor will convert `mcu_set_output(DOUT0)` to `digitalWrite(50)` like we need it. And this aplicable to all pins. + From ea99c384f63aa7a3925681c2b997d551ace4902e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 27 Jul 2023 10:31:17 +0100 Subject: [PATCH 062/168] Update README.md --- uCNC/src/hal/mcus/README.md | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index 98dae1912..3204c1f7c 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -13,7 +13,7 @@ _**Jump to section**_ * [Pin naming conventions](#pin-naming-conventions) * [How is a pin evaluated?](#how-is-a-pin-evaluated) * [Creating the HAL for a custom MCU](#creating-the-hal-for-a-custom-mcu) - * [An example of implementing the some functions for a custom MCU](#an-example-of-implementing-the-some-functions-for-a-custom-mcu) + * [Implementation example for a custom MCU using ArduinoIDE](#implementation-example-for-a-custom-mcu-using-arduinoide) # µCNC HAL (Hardware Abstraction Layer) µCNC has several HAL dimensions/layers. The first and most important layer is the microcontroller HAL. @@ -71,6 +71,8 @@ SPI_CLK #### Output pins - generic + ```PWM#``` pin defines a pwm output pin. + ```PWM0 to PWM15``` are the pwm output pins. ++ ```SERVO#``` pin defines a pwm output pin. + + ```SERVO0 to SERVO5``` are the servo output pins. + ```DOUT#``` pin defines a generic output pin. + ```DOUT0 to DOUT31``` are the generic output pins. @@ -895,12 +897,12 @@ void main(void) Again the example bellow will (I hope) help to clarify this. -### An example of implementing the some functions for a custom MCU +### Implementation example for a custom MCU using ArduinoIDE Now for a practical example of how to implement all this. Let's create a boarmap were we link the internal µCNC pins and then make the MCU execute the desired action. -This example will use Arduino IDE as a base. +This example will use Arduino IDE as a base, but you can use (and I recommend) using baremetal or as close to the MCU programming as possible for best performance. In our boardmap we need to create a way to assign out pins. These names and definitions can be set freely. Accross all MCU it was conventioned to use a friendly_name_BIT and friendly_name_PORT, but this is not mandatory. For example in AVR to set up a pin we do it like this: From 2426508129d27693862e9cbcf5d55e000b6cecb8 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 27 Jul 2023 10:44:53 +0100 Subject: [PATCH 063/168] updated READMEs --- uCNC/src/hal/kinematics/README.md | 82 +++++++++++++++++++++++++++++++ uCNC/src/hal/mcus/README.md | 2 +- 2 files changed, 83 insertions(+), 1 deletion(-) diff --git a/uCNC/src/hal/kinematics/README.md b/uCNC/src/hal/kinematics/README.md index 54ea22b2c..59928ac90 100644 --- a/uCNC/src/hal/kinematics/README.md +++ b/uCNC/src/hal/kinematics/README.md @@ -51,3 +51,85 @@ In addition to the standard configurations you need to set 5 extra settings: | $109 | [Delta forearm length, mm](https://github.com/Paciente8159/uCNC/wiki/Basic-user-guide#109---delta-forearm-length-mm) | For more information please head to the [µCNC wiki page](https://github.com/Paciente8159/uCNC/wiki) + +## The kinematics HAL +This HAL is manages the way the linear actuators and the 3D Cartesian space axis relate to each other. + * Converts linear actuators (steppers) in to X,Y,Z,A,B,C coordinates and back. + * Converts any X,Y,Z transformation to compensate for non perpendicular axis (un-skew) and back. + * Defines the order of the axis movements when homing. + +### Creating the HAL for a custom kinematics + **2 steps are needed:** + + **1. Implement all functions defined in the kinematics.h** + + All functions defined by the ```kinematics.h``` must be implemented. These are: + + ``` + /** + * @brief Initializes the kinematic system. + * This can be for example read the non volatile memory parameters for that kinematics and store them in RAM + * Any other kind of initialization procedure can be done + */ + void kinematics_init(void); + + /** + * @brief Converts from machine absolute coordinates to step position. + * This is done after computing position relative to the active coordinate system + * + * @param axis Position in world coordinates + * @param steps Position in steps + */ + + void kinematics_apply_inverse(float *axis, int32_t *steps); + + /** + * @brief Converts from step position to machine absolute coordinates. + * This is done after computing position relative to the active coordinate system + * + * @param steps Position in steps + * @param axis Position in world coordinates + */ + void kinematics_apply_forward(int32_t *steps, float *axis); + + /** + * @brief Executes the homing motion for the machine. + * The homing motion for each axis is defined in the motion control. + * In the kinematics home function the axis order of the homing motion and other custom motions can be defined + * + * @return uint8_t Error status + */ + uint8_t kinematics_home(void); + + /** + * @brief Aplies a transformation to the position sent to planner. + * This is aplied only on normal and jog moves. Homing motions go directly to planner. + * + * @param axis Target in absolute coordinates + */ + void kinematics_apply_transform(float *axis); + + /** + * @brief Aplies a reverse transformation to the position returned from the planner. + * This is aplied only on normal and jog moves. Homing motions go directly to planner. + * + * @param axis Target in absolute coordinates + */ + void kinematics_apply_reverse_transform(float *axis); + + /** + * @brief Checks if the desired target is inside sofware boundries + * + * @param axis Target in absolute coordinates + * @return true If inside boundries + * @return false If outside boundries + */ + bool kinematics_check_boundaries(float *axis); + + ``` + +**2. Add the new kinematic library to µCNC** + + * Add the new kinematic to `kinematics.h` file and give it an ID. Add the needed libraries to load in the `kinematicdefs.h` file. + +Now just edit the config file to specify the kinemtics file you want to use and recompile µCNC for your board. diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index 3204c1f7c..16e7c0fc3 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -957,7 +957,7 @@ Here is a preprocessor trick. This macro takes 2 arguments, makes some replaceme #endif ``` -So if we call `__indirect__(DOUT0, IDEPIN)` it will first evaluate both parameters to resolve them. `DOUT0` will be replaced by 47 and IDEPIN (if you have not created any definition for it) will remain the same and will be passed to the next macro. Next `47` and `IDEPIN` wil be be concatenated to `DIO` and `_` and will become `DIO47_IDEPIN` that is equivalent to `DOUT0_IDEPIN`. +So if we call `__indirect__(DOUT0, IDEPIN)` it will first evaluate both parameters to resolve them. `DOUT0` will be replaced by 47 and IDEPIN (you cannot have a #define IDEPIN anywere in yor code or this will not work) will remain the same and will be passed to the next macro. Next `47` and `IDEPIN` wil be be concatenated to `DIO` and `_` and will become `DIO47_IDEPIN` that is equivalent to `DOUT0_IDEPIN`. Resuming: `__indirect__(DOUT0, IDEPIN)` -> `__indirect__ex__(47, IDEPIN)` -> `DIO47_IDEPIN` -> `DOUT0_IDEPIN` -> `50` From 3f2f7313752ec810064badf9f3597f916255a113 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 27 Jul 2023 11:06:33 +0100 Subject: [PATCH 064/168] fixed kinematic checking --- uCNC/src/cnc_hal_config_helper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index ba72b5b5a..ccfb7fd87 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2003,7 +2003,7 @@ typedef uint16_t step_t; #error "invalid s-curve velocity profile setting" #endif -#if (defined(KINEMATICS_MOTION_BY_SEGMENTS)) +#if (defined(IS_DELTA_KINEMATICS)) #ifdef ENABLE_DUAL_DRIVE_AXIS #error "Delta does not support dual drive axis" #endif From b0c6ec84c1bd1472bd24b94e3b6f96878df15445 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 28 Jul 2023 15:39:03 +0100 Subject: [PATCH 065/168] initial implementation of scara kinematic --- uCNC/cnc_config.h | 2 +- uCNC/src/hal/kinematics/kinematic_scara.c | 214 ++++++++++++++++++++++ uCNC/src/hal/kinematics/kinematic_scara.h | 50 +++++ uCNC/src/hal/kinematics/kinematicdefs.h | 2 + uCNC/src/hal/kinematics/kinematics.h | 1 + uCNC/src/interface/defaults.h | 18 +- uCNC/src/interface/settings.c | 5 + uCNC/src/interface/settings.h | 17 +- 8 files changed, 301 insertions(+), 8 deletions(-) create mode 100644 uCNC/src/hal/kinematics/kinematic_scara.c create mode 100644 uCNC/src/hal/kinematics/kinematic_scara.h diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 81382af12..5a0e24d21 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -71,7 +71,7 @@ extern "C" #endif #ifndef KINEMATIC -#define KINEMATIC KINEMATIC_CARTESIAN +#define KINEMATIC KINEMATIC_SCARA #endif /** diff --git a/uCNC/src/hal/kinematics/kinematic_scara.c b/uCNC/src/hal/kinematics/kinematic_scara.c new file mode 100644 index 000000000..6d4ef30d1 --- /dev/null +++ b/uCNC/src/hal/kinematics/kinematic_scara.c @@ -0,0 +1,214 @@ +/* + Name: KINEMATIC_LINEAR_SCARA.c + Description: Implements all kinematics math equations to translate the motion of a scara machine. + Also implements the homing motion for this type of machine. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 28/072023 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#include "../../cnc.h" + +#if (KINEMATIC == KINEMATIC_SCARA) +#include +#include +#include + +#define FULL_TURN_INV 0.0027777777777777778f +#define DOUBLE_PI_INV (0.5f * M_PI_INV) + + +static float scara_arm_angle_fact[2]; +static float scara_min_distance_to_center_sqr; +static float scara_max_distance_to_center_sqr; + +void kinematics_init(void) +{ + // reset home offset + scara_arm_angle_fact[0] = 2.0f * M_PI / g_settings.step_per_mm[0]; + scara_arm_angle_fact[1] = 2.0f * M_PI / g_settings.step_per_mm[1]; + scara_max_distance_to_center_sqr = g_settings.scara_arm_length + g_settings.scara_forearm_length; + scara_max_distance_to_center_sqr *= scara_max_distance_to_center_sqr; + scara_min_distance_to_center_sqr = g_settings.scara_arm_length - g_settings.scara_forearm_length; + scara_min_distance_to_center_sqr *= scara_min_distance_to_center_sqr; +} + +void kinematics_apply_inverse(float *axis, int32_t *steps) +{ + float arm = g_settings.scara_arm_length; + float forearm = g_settings.scara_forearm_length; + + float distance = (axis[AXIS_X] * axis[AXIS_X] + axis[AXIS_Y] * axis[AXIS_Y] - arm * arm - forearm * forearm) / (2.0f * arm * forearm); + float angle2 = acosf(distance); + + steps[1] = (int32_t)roundf(angle2 * DOUBLE_PI_INV * g_settings.step_per_mm[1]); + float angle1 = atan2f(axis[AXIS_Y], axis[AXIS_X]) - atan2f(forearm * sin(angle2), (arm + forearm * distance)); + steps[0] = (int32_t)roundf(angle1 * DOUBLE_PI_INV * g_settings.step_per_mm[0]); + +#if AXIS_COUNT > 2 + for (uint8_t i = 2; i < AXIS_COUNT; i++) + { + steps[i] = (int32_t)lroundf(g_settings.step_per_mm[i] * axis[i]); + } +#endif +} + +void kinematics_apply_forward(int32_t *steps, float *axis) +{ + // calcs X and Y based on arms lengths and angles + + // calculate joints positions + float joint1 = steps[0] * scara_arm_angle_fact[0]; + float joint2 = steps[1] * scara_arm_angle_fact[1]; + + joint2 += joint1; + + float arm = g_settings.scara_arm_length; + float forearm = g_settings.scara_forearm_length; + + axis[AXIS_X] = arm * cos(joint1) + forearm * cos(joint2); + axis[AXIS_Y] = arm * sin(joint1) + forearm * sin(joint2); + +#if AXIS_COUNT > 2 + for (uint8_t i = 2; i < AXIS_COUNT; i++) + { + axis[i] = (((float)steps[i]) / g_settings.step_per_mm[i]); + } +#endif +} + +uint8_t kinematics_home(void) +{ + float target[AXIS_COUNT]; + +#ifndef DISABLE_ALL_LIMITS +#ifndef DISABLE_Z_HOMING +#if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) + if (mc_home_axis(AXIS_Z, LIMIT_Z_MASK)) + { + return KINEMATIC_HOMING_ERROR_Z; + } +#endif +#endif + +#ifndef DISABLE_X_HOMING +#if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) + if (mc_home_axis(AXIS_X, LIMIT_X_MASK)) + { + return KINEMATIC_HOMING_ERROR_X; + } +#endif +#endif + +#ifndef DISABLE_Y_HOMING +#if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) + if (mc_home_axis(AXIS_Y, LIMIT_Y_MASK)) + { + return KINEMATIC_HOMING_ERROR_Y; + } +#endif +#endif + +#ifndef DISABLE_A_HOMING +#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) + if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + { + return (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y | KINEMATIC_HOMING_ERROR_Z); + } +#endif +#endif + +#ifndef DISABLE_B_HOMING +#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) + if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + { + return KINEMATIC_HOMING_ERROR_B; + } +#endif +#endif + +#ifndef DISABLE_C_HOMING +#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) + if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + { + return KINEMATIC_HOMING_ERROR_C; + } +#endif +#endif + + cnc_unlock(true); + // flags homing clear by the unlock + int32_t steps_homing[STEPPER_COUNT] = {0}; + steps_homing[0] = g_settings.scara_arm_homing_angle * g_settings.step_per_mm[0] * FULL_TURN_INV; + steps_homing[1] = g_settings.scara_forearm_homing_angle * g_settings.step_per_mm[1] * FULL_TURN_INV; + kinematics_apply_forward(steps_homing, target); + itp_reset_rt_position(target); + mc_sync_position(); + + cnc_set_exec_state(EXEC_HOMING); + motion_data_t block_data = {0}; + mc_get_position(target); + + for (uint8_t i = 0; i < AXIS_COUNT; i++) + { + target[i] += ((g_settings.homing_dir_invert_mask & (1 << i)) ? -g_settings.homing_offset : g_settings.homing_offset); + } + + block_data.feed = g_settings.homing_fast_feed_rate; + block_data.spindle = 0; + block_data.dwell = 0; + // starts offset and waits to finnish + mc_line(target, &block_data); + itp_sync(); +#endif + // unlocks the machine to go to offset + cnc_clear_exec_state(EXEC_HOMING); + + return STATUS_OK; +} + +void kinematics_apply_transform(float *axis) +{ +} + +void kinematics_apply_reverse_transform(float *axis) +{ +} + +bool kinematics_check_boundaries(float *axis) +{ + float distance_to_center_sqr = axis[AXIS_X] * axis[AXIS_X] + axis[AXIS_Y] * axis[AXIS_Y]; + + if (distance_to_center_sqr < scara_max_distance_to_center_sqr || distance_to_center_sqr > scara_max_distance_to_center_sqr) + { + return false; + } + + for (uint8_t i = AXIS_COUNT; i != 2;) + { + i--; +#ifdef SET_ORIGIN_AT_HOME_POS + float value = !(g_settings.homing_dir_invert_mask & (1 << i)) ? -axis[i] : axis[i]; +#else + float value = axis[i]; +#endif + if (value > g_settings.max_distance[i] || value < 0) + { + return false; + } + } + + return true; +} + +#endif diff --git a/uCNC/src/hal/kinematics/kinematic_scara.h b/uCNC/src/hal/kinematics/kinematic_scara.h new file mode 100644 index 000000000..4f82cd295 --- /dev/null +++ b/uCNC/src/hal/kinematics/kinematic_scara.h @@ -0,0 +1,50 @@ +/* + Name: kinematic_scara.h + Description: Custom kinematics definitions for scara machine + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 28/072023 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#ifndef KINEMATIC_SCARA_H +#define KINEMATIC_SCARA_H + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define KINEMATIC_TYPE_STR "SC" + +// kinematic motion is done by segments to cope with non linear kinematics motion +#define KINEMATICS_MOTION_BY_SEGMENTS +// kinematics homing +#define IS_SCARA_KINEMATICS + +// the maximum size of the computed segments that are sent to the planner +// this forces linear motions in the scara to treated has an arc motion to +// cope with the non linear kinematic motion of the towers +#ifndef KINEMATICS_MOTION_SEGMENT_SIZE +#define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f +#endif + + + /* + Enable Skew compensation +*/ + //#define ENABLE_SKEW_COMPENSATION + +#ifdef __cplusplus +} +#endif +#endif diff --git a/uCNC/src/hal/kinematics/kinematicdefs.h b/uCNC/src/hal/kinematics/kinematicdefs.h index a6c642a5a..dba298dcb 100644 --- a/uCNC/src/hal/kinematics/kinematicdefs.h +++ b/uCNC/src/hal/kinematics/kinematicdefs.h @@ -65,6 +65,8 @@ extern "C" #include "kinematic_linear_delta.h" #elif (KINEMATIC == KINEMATIC_DELTA) #include "kinematic_delta.h" +#elif (KINEMATIC == KINEMATIC_SCARA) +#include "kinematic_scara.h" #else #error Kinematics not implemented #endif diff --git a/uCNC/src/hal/kinematics/kinematics.h b/uCNC/src/hal/kinematics/kinematics.h index cfe8e7f71..71f7737e0 100644 --- a/uCNC/src/hal/kinematics/kinematics.h +++ b/uCNC/src/hal/kinematics/kinematics.h @@ -28,6 +28,7 @@ extern "C" #define KINEMATIC_COREXY 2 #define KINEMATIC_LINEAR_DELTA 3 #define KINEMATIC_DELTA 4 +#define KINEMATIC_SCARA 5 #ifdef __cplusplus } diff --git a/uCNC/src/interface/defaults.h b/uCNC/src/interface/defaults.h index acdca22a6..681524214 100644 --- a/uCNC/src/interface/defaults.h +++ b/uCNC/src/interface/defaults.h @@ -248,7 +248,7 @@ extern "C" #define DEFAULT_DELTA_BICEP_LENGTH 100 #endif -#if (!defined(DEFAULT_DELTA_FOREARM_LENGHT)) +#if (!defined(DEFAULT_DELTA_FOREARM_LENGTH)) #define DEFAULT_DELTA_FOREARM_LENGTH 300 #endif @@ -264,6 +264,22 @@ extern "C" #define DEFAULT_DELTA_BICEP_HOMING_ANGLE 0 #endif +#if (!defined(DEFAULT_SCARA_ARM_LENGTH)) +#define DEFAULT_SCARA_ARM_LENGTH 100 +#endif + +#if (!defined(DEFAULT_SCARA_FOREARM_LENGTH)) +#define DEFAULT_SCARA_FOREARM_LENGTH 80 +#endif + +#if (!defined(DEFAULT_SCARA_ARM_HOMING_ANGLE)) +#define DEFAULT_SCARA_ARM_HOMING_ANGLE 0 +#endif + +#if (!defined(DEFAULT_SCARA_FOREARM_HOMING_ANGLE)) +#define DEFAULT_SCARA_FOREARM_HOMING_ANGLE 0 +#endif + // laser mode #if (!defined(DEFAULT_LASER_PPI)) #define DEFAULT_LASER_PPI 254 diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index 90b97714c..b8d6cc205 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -135,6 +135,11 @@ const settings_t __rom__ default_settings = .delta_bicep_length = DEFAULT_DELTA_BICEP_LENGTH, .delta_forearm_length = DEFAULT_DELTA_FOREARM_LENGTH, .delta_bicep_homing_angle = DEFAULT_DELTA_BICEP_HOMING_ANGLE, +#elif (KINEMATIC == KINEMATIC_SCARA) + .scara_arm_length = DEFAULT_SCARA_ARM_LENGTH, + .scara_forearm_length = DEFAULT_SCARA_FOREARM_LENGTH, + .scara_arm_homing_angle = DEFAULT_SCARA_ARM_HOMING_ANGLE, + .scara_forearm_homing_angle = DEFAULT_SCARA_FOREARM_HOMING_ANGLE, #endif #ifdef ENABLE_BACKLASH_COMPENSATION diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index b67f2656f..6c396048a 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -85,6 +85,11 @@ extern "C" float delta_bicep_length; float delta_forearm_length; float delta_bicep_homing_angle; +#elif (KINEMATIC == KINEMATIC_SCARA) + float scara_arm_length; + float scara_forearm_length; + float scara_arm_homing_angle; + float scara_forearm_homing_angle; #endif #ifdef ENABLE_BACKLASH_COMPENSATION uint16_t backlash_steps[AXIS_TO_STEPPERS]; @@ -159,12 +164,12 @@ typedef uint16_t setting_offset_t; DECL_EVENT_HANDLER(settings_erase); #endif - /** - * - * Settings quick/help macros - * These allow custom settings setup of simple settings - * - * **/ +/** + * + * Settings quick/help macros + * These allow custom settings setup of simple settings + * + * **/ #define DECL_EXTENDED_SETTING(ID, var, type, count, print_cb) \ static uint32_t set##ID##_settings_address; \ bool set##ID##_settings_load(void *args) \ From 7282a27c1f33284a5e70ff90d25f3b72e27abb29 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 30 Jul 2023 23:29:38 +0100 Subject: [PATCH 066/168] scara settings --- uCNC/cnc_config.h | 2 +- .../src/hal/boards/rp2040/boardmap_rpi_pico.h | 6 ++--- uCNC/src/hal/kinematics/kinematic_scara.c | 8 ++++++- uCNC/src/interface/protocol.c | 6 +++++ uCNC/src/interface/settings.c | 24 +++++++++++++++---- uCNC/src/modules/system_menu.c | 6 +++++ 6 files changed, 42 insertions(+), 10 deletions(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 5a0e24d21..81382af12 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -71,7 +71,7 @@ extern "C" #endif #ifndef KINEMATIC -#define KINEMATIC KINEMATIC_SCARA +#define KINEMATIC KINEMATIC_CARTESIAN #endif /** diff --git a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h index 8722aaf18..5285f8976 100644 --- a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h +++ b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h @@ -74,9 +74,9 @@ extern "C" #define DOUT31_BIT 25 //disable EEPROM emulation -#ifndef RAM_ONLY_SETTINGS -#define RAM_ONLY_SETTINGS -#endif +// #ifndef RAM_ONLY_SETTINGS +// #define RAM_ONLY_SETTINGS +// #endif #define I2C_CLK_BIT 27 #define I2C_DATA_BIT 26 diff --git a/uCNC/src/hal/kinematics/kinematic_scara.c b/uCNC/src/hal/kinematics/kinematic_scara.c index 6d4ef30d1..d8c4893c2 100644 --- a/uCNC/src/hal/kinematics/kinematic_scara.c +++ b/uCNC/src/hal/kinematics/kinematic_scara.c @@ -41,6 +41,7 @@ void kinematics_init(void) scara_max_distance_to_center_sqr *= scara_max_distance_to_center_sqr; scara_min_distance_to_center_sqr = g_settings.scara_arm_length - g_settings.scara_forearm_length; scara_min_distance_to_center_sqr *= scara_min_distance_to_center_sqr; + mc_sync_position(); } void kinematics_apply_inverse(float *axis, int32_t *steps) @@ -187,9 +188,14 @@ void kinematics_apply_reverse_transform(float *axis) bool kinematics_check_boundaries(float *axis) { + if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) + { + return true; + } + float distance_to_center_sqr = axis[AXIS_X] * axis[AXIS_X] + axis[AXIS_Y] * axis[AXIS_Y]; - if (distance_to_center_sqr < scara_max_distance_to_center_sqr || distance_to_center_sqr > scara_max_distance_to_center_sqr) + if (distance_to_center_sqr < scara_min_distance_to_center_sqr || distance_to_center_sqr > scara_max_distance_to_center_sqr) { return false; } diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index bf22c0586..db4b350b7 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -637,6 +637,9 @@ void protocol_send_cnc_settings(void) protocol_send_gcode_setting_line_flt(27, g_settings.homing_offset); #if (KINEMATIC == KINEMATIC_DELTA) protocol_send_gcode_setting_line_flt(28, g_settings.delta_bicep_homing_angle); +#elif (KINEMATIC == KINEMATIC_SCARA) + protocol_send_gcode_setting_line_flt(28, g_settings.scara_arm_homing_angle); + protocol_send_gcode_setting_line_flt(29, g_settings.scara_forearm_homing_angle); #endif protocol_send_gcode_setting_line_int(30, g_settings.spindle_max_rpm); protocol_send_gcode_setting_line_int(31, g_settings.spindle_min_rpm); @@ -677,6 +680,9 @@ void protocol_send_cnc_settings(void) protocol_send_gcode_setting_line_flt(107, g_settings.delta_effector_radius); protocol_send_gcode_setting_line_flt(108, g_settings.delta_bicep_length); protocol_send_gcode_setting_line_flt(109, g_settings.delta_forearm_length); +#elif (KINEMATIC == KINEMATIC_SCARA) + protocol_send_gcode_setting_line_flt(106, g_settings.scara_arm_length); + protocol_send_gcode_setting_line_flt(107, g_settings.scara_forearm_length); #endif for (uint8_t i = 0; i < AXIS_COUNT; i++) diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index b8d6cc205..d968ae873 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -136,10 +136,10 @@ const settings_t __rom__ default_settings = .delta_forearm_length = DEFAULT_DELTA_FOREARM_LENGTH, .delta_bicep_homing_angle = DEFAULT_DELTA_BICEP_HOMING_ANGLE, #elif (KINEMATIC == KINEMATIC_SCARA) - .scara_arm_length = DEFAULT_SCARA_ARM_LENGTH, - .scara_forearm_length = DEFAULT_SCARA_FOREARM_LENGTH, - .scara_arm_homing_angle = DEFAULT_SCARA_ARM_HOMING_ANGLE, - .scara_forearm_homing_angle = DEFAULT_SCARA_FOREARM_HOMING_ANGLE, + .scara_arm_length = DEFAULT_SCARA_ARM_LENGTH, + .scara_forearm_length = DEFAULT_SCARA_FOREARM_LENGTH, + .scara_arm_homing_angle = DEFAULT_SCARA_ARM_HOMING_ANGLE, + .scara_forearm_homing_angle = DEFAULT_SCARA_FOREARM_HOMING_ANGLE, #endif #ifdef ENABLE_BACKLASH_COMPENSATION @@ -239,7 +239,8 @@ uint8_t settings_load(uint16_t address, uint8_t *__ptr, uint8_t size) return (crc ^ mcu_eeprom_getc(address)); #else - return 255; // returns error + rom_memcpy(&g_settings, &default_settings, sizeof(settings_t)); + return 0; // loads defaults #endif } @@ -478,6 +479,19 @@ uint8_t settings_change(setting_offset_t id, float value) case 28: g_settings.delta_bicep_homing_angle = value; break; +#elif (KINEMATIC == KINEMATIC_SCARA) + case 106: + g_settings.scara_arm_length = value; + break; + case 107: + g_settings.scara_forearm_length = value; + break; + case 28: + g_settings.scara_arm_homing_angle = value; + break; + case 29: + g_settings.scara_forearm_homing_angle = value; + break; #endif default: if (setting >= 100 && setting < (100 + AXIS_COUNT)) diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 125fb5909..3d9ff4f07 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -162,6 +162,12 @@ DECL_MODULE(system_menu) DECL_MENU_VAR(3, s25, STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); DECL_MENU_VAR(3, s26, STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); DECL_MENU_VAR(3, s27, STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); +#if (KINEMATIC == KINEMATIC_DELTA) + DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); +#elif (KINEMATIC == KINEMATIC_SCARA) + DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s29, STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); +#endif // append steppers settings menu DECL_MENU(4, 2, STR_AXIS); From 4a3713ae47e4cdfaabaddfa54bbe4234be8d9063 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 17:27:45 +0100 Subject: [PATCH 067/168] Update README.md --- uCNC/src/README.md | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 491daf25f..1b67d72a0 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -61,7 +61,6 @@ __NOTE__: Not all event hooks might be listed here. To find all available event | input_change | uint8_t* | ENABLE_IO_MODULES | Fires when a generic input (DIN0-7) pin changes state. Args is an uint8_t array with 2 values. The first is the inputs current values mask and the second a maks with the inputs that changed since the last time | | probe_enable | NULL | ENABLE_IO_MODULES | Fires when the probe is enabled | | probe_disable | NULL | ENABLE_IO_MODULES | Fires when the probe is disabled | -| mc_line_segment | NULL | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner | | mc_home_axis_start | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is starting. Pointer to homing_status_t struct with homming information | | mc_home_axis_finish | homing_status_t* | ENABLE_MOTION_CONTROL_MODULES | Fires once per axis when homing motion is finnished | | mc_line_segment | motion_data_t* | ENABLE_MOTION_CONTROL_MODULES | Fires when a line segment is about to be sent from the motion control to the planner. Arg is a pointer to a motion_data_t struct with the current motion block data | @@ -321,7 +320,7 @@ WEAK_EVENT_HANDLER(cnc_alarm) *Again remember. You can make a module take hover this event callback (disabling all existing listeners of this event by creating and override callback with `OVERRIDE_EVENT_HANDLER` like showned above).* -The only step left is to actually add the callback inside the core code to be executed. In this case let's lace it inside our `void cnc_alarm(int8_t code)` function like this: +The only step left is to actually add the callback inside the core code to be executed. In this case let's call it inside our `void cnc_alarm(int8_t code)` function like this: ``` void cnc_alarm(int8_t code) From dfac595dd75948de08c537a55162a50f4cb125f5 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 18:05:33 +0100 Subject: [PATCH 068/168] Create README.md --- uCNC/src/hal/tools/tools/README.md | 84 ++++++++++++++++++++++++++++++ 1 file changed, 84 insertions(+) create mode 100644 uCNC/src/hal/tools/tools/README.md diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md new file mode 100644 index 000000000..182bd6442 --- /dev/null +++ b/uCNC/src/hal/tools/tools/README.md @@ -0,0 +1,84 @@ +

+ +

+ + +# µCNC +µCNC - Universal CNC firmware for microcontrollers + +_**Jump to section**_ +* [Available tools in µCNC](#available-tools-in-µcnc) + * [spindle_pwm](#spindle_pwm) + * [µCNC creating a dummy tool](#µcnc-creating-a-dummy-tool) + +# Available tools in to µCNC + +µCNC provides several ready-to-use tools. With little to no configuration these tools a pretty much ready to use. +Some tools may provide extra functionalities like extra settings or extra G/M codes. + +## spindle_pwm + +Spindle PWM can be used with any common PWM controlled tool. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses PWM0 by default has the spindle speed control +#ifndef SPINDLE_PWM +#define SPINDLE_PWM PWM0 +#endif +// if unset uses DOUT0 by default has the spindle dir output control +#ifndef SPINDLE_PWM_DIR +#define SPINDLE_PWM_DIR DOUT0 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the spindle flood output control +#ifndef SPINDLE_PWM_COOLANT_FLOOD +#define SPINDLE_PWM_COOLANT_FLOOD DOUT2 +#endif +// if unset uses DOUT3 by default has the spindle mist output control +#ifndef SPINDLE_PWM_COOLANT_MIST +#define SPINDLE_PWM_COOLANT_MIST DOUT3 +#endif +#endif + +// if unset PWM PID sample rate is 125Hz +// this tool PID settings are as follow +// $300=Kp +// $301=Ki +// $302=Kd +#define SPINDLE_PWM_PID_SAMPLE_RATE_HZ 125 + +``` + +## laser_pwm + +Laser PWM is very similar to spindle PWM. The main difference is that this tool sets $31=1 (laser mode) on loading and restores it's value on unloading. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses PWM0 by default has the laser power control +#ifndef LASER_PWM +#define LASER_PWM PWM0 +#endif + +// if unset set PWM frequency to 8Khz to improve laser response. By default µCNC PWM pins works at 1Khz +#ifndef LASER_FREQ +#define LASER_FREQ 8000 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the air assist output control +#ifndef LASER_PWM_AIR_ASSIST +#define LASER_PWM_AIR_ASSIST DOUT2 +#endif +#endif + +// this sets the minimum power (laser will never fully turn off during engraving and prevents power up delays) +#ifndef LASER_PWM_MIN_VALUE +#define LASER_PWM_MIN_VALUE 2 +#endif + +``` From b20bbeb14e16e7d7e9c05c9f4ae015952cd66a3a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 19:39:59 +0100 Subject: [PATCH 069/168] Update README.md --- uCNC/src/hal/tools/tools/README.md | 195 ++++++++++++++++++++++++++++- 1 file changed, 192 insertions(+), 3 deletions(-) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index 182bd6442..f64a6babd 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -9,7 +9,13 @@ _**Jump to section**_ * [Available tools in µCNC](#available-tools-in-µcnc) * [spindle_pwm](#spindle_pwm) - * [µCNC creating a dummy tool](#µcnc-creating-a-dummy-tool) + * [laser_pwm](#laser_pwm) + * [laser_ppi](#laser_ppi) + * [pen_servo](#pen_servo) + * [spindle_relay](#spindle_relay) + * [spindle_besc](#spindle_besc) + * [vfd_pwm](#vfd_pwm) + # Available tools in to µCNC @@ -33,11 +39,11 @@ These are the default µCNC pins/definitions for this tool: // enables coolant pins if this option is enabled #ifdef ENABLE_COOLANT -// if unset uses DOUT2 by default has the spindle flood output control +// if unset uses DOUT2 by default has the tool flood output control #ifndef SPINDLE_PWM_COOLANT_FLOOD #define SPINDLE_PWM_COOLANT_FLOOD DOUT2 #endif -// if unset uses DOUT3 by default has the spindle mist output control +// if unset uses DOUT3 by default has the tool mist output control #ifndef SPINDLE_PWM_COOLANT_MIST #define SPINDLE_PWM_COOLANT_MIST DOUT3 #endif @@ -55,6 +61,7 @@ These are the default µCNC pins/definitions for this tool: ## laser_pwm Laser PWM is very similar to spindle PWM. The main difference is that this tool sets $31=1 (laser mode) on loading and restores it's value on unloading. +Like in Grbl, M4 - dynamic laser power is available, making the PWM output dimmer in proportion to the motion acceleration/deacceleration to improve engraving quality. These are the default µCNC pins/definitions for this tool: ``` @@ -77,8 +84,190 @@ These are the default µCNC pins/definitions for this tool: #endif // this sets the minimum power (laser will never fully turn off during engraving and prevents power up delays) +// M5 will still turn laser completely off. M3 S0 or M4 S0 will output PWM min. #ifndef LASER_PWM_MIN_VALUE #define LASER_PWM_MIN_VALUE 2 #endif ``` + + +## laser_ppi + +Laser PPI is designed to control laser in pulse per inch mode (PPI). +This is actually achieved by treating the laser output control pin as an additional stepper motor. +There are several advantages to this. The first one is that the energy of the laser is tightly coupled with the motion. That ensures that the output result will be the same regardless of the engraving speed. +There is a tradeoff. To ensure that the laser control pulse width is achieved, the maximum achievable speed might be reduced. + +Laser PPI is able to use not only generic output pins but also PWM pins by changing the configuration on tool loading. +Laser PPI has 3 working modes. + - PPI mode, by setting $32=2. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. The number of pulses will be affected by the tool S parameter. For example if you define a PPI value of 254 (254 pulses per inch) and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI output will be adjusted to 50% (or 127PPI). This is similar to the ways M4 works in laser PWM. The pulse width is fixed and is configured by setting $34 (in us-microseconds) + - PPI PW mode, by setting $32=4. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. In this case the tool S parameter will affect the pulse width set by $34. For example if you define a PPI width value of 900us and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI pulse width output will be adjusted to 50% (or 450us). + - PPI mixed mode, by setting $32=6. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. This mode makes a ratio mix of both the above mentioned modes unsing an inverse ratio defined by setting $35. For example if you define a PPI value of 254 and a width value of 900us and $35 = 0.75 (75%) and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI will be adjusted in 0.75 of 50% of the value (that translates to 37.5% or 159PPI) and pulse width output will be of (1 - 0.75) of 50% (or 788us). + +This tool also enables a few extra MCode commands that allow to directly modify settings $32, $33 and $34. These are + +``` +M126 P + +mode = 0 disables PPI mode +mode = 1 enables PPI mode +mode = 2 PPI PW mode +mode = 3 PPI mixed mode + +``` + +``` +M127 P + +``` + +``` +M128 P + +``` + +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses PWM0 by default has the laser PPI control +#ifndef LASER_PPI +#define LASER_PPI PWM0 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the air assist output control +#ifndef LASER_PPI_AIR_ASSIST +#define LASER_PPI_AIR_ASSIST DOUT2 +#endif +#endif + +``` + +## pen_servo + +Pen servo uses a SERVO type pin (Pulse width 0.5ms~2.5ms @ 50Hz) to control a small DC servo. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses SERVO0 by default has the pen servo control +#ifndef PEN_SERVO +#define PEN_SERVO SERVO0 +#endif + +// defaults the servo ouput value for the pen to be low position to 50 (0-255 range) +#ifndef PEN_SERVO_LOW +#define PEN_SERVO_LOW 50 +#endif +// defaults the servo ouput value for the pen to be mid position to 127 (0-255 range) +#ifndef PEN_SERVO_MID +#define PEN_SERVO_MID 127 +#endif +// defaults the servo ouput value for the pen to be high position to 255 (0-255 range) +#ifndef PEN_SERVO_HIGH +#define PEN_SERVO_HIGH 255 +#endif + +``` + +## spindle_relay + +Spindle relay uses relays to control a spindle tool. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses DOUT0 by default has the turn spindle on and forward output control +#ifndef SPINDLE_RELAY_FWD +#define SPINDLE_RELAY_FWD DOUT0 +#endif +// if unset uses DOUT0 by default has the turn spindle on and reverse output control +#ifndef SPINDLE_RELAY_REV +#define SPINDLE_RELAY_REV DOUT1 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the spindle flood output control +#ifndef SPINDLE_RELAY_COOLANT_FLOOD +#define SPINDLE_RELAY_COOLANT_FLOOD DOUT2 +#endif +// if unset uses DOUT3 by default has the spindle mist output control +#ifndef SPINDLE_RELAY_COOLANT_MIST +#define SPINDLE_RELAY_COOLANT_MIST DOUT3 +#endif +#endif + +``` + +## spindle_besc + +Spindle BESC uses brushless motor controlled by a BESC. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses SERVO0 by default has the BESC speed signal control +#ifndef SPINDLE_BESC_SERVO +#define SPINDLE_BESC_SERVO SERVO0 +#endif +// if unset uses DOUT0 by default has the BESC relay power on control control +#ifndef SPINDLE_BESC_POWER_RELAY +#define SPINDLE_BESC_POWER_RELAY DOUT0 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the spindle flood output control +#ifndef SPINDLE_BESC_COOLANT_FLOOD +#define SPINDLE_BESC_COOLANT_FLOOD DOUT2 +#endif +// if unset uses DOUT3 by default has the spindle mist output control +#ifndef SPINDLE_BESC_COOLANT_MIST +#define SPINDLE_BESC_COOLANT_MIST DOUT3 +#endif +#endif + +``` + +## vfd_pwm + +This is similar to spindle PWM. The main difference is that it uses an RPM feedback with an analog input. +These are the default µCNC pins/definitions for this tool: + +``` +// if unset uses PWM0 by default has the VFD PWM speed signal control +#ifndef VFD_PWM +#define VFD_PWM PWM0 +#endif +// if unset uses DOUT0 by default has the vfd dir output control +#ifndef VFD_PWM_DIR +#define VFD_PWM_DIR DOUT0 +#endif + +// enables coolant pins if this option is enabled +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the tool flood output control +#ifndef VFD_PWM_COOLANT_FLOOD +#define VFD_PWM_COOLANT_FLOOD DOUT2 +#endif +// if unset uses DOUT3 by default has the tool mist output control +#ifndef VFD_PWM_COOLANT_MIST +#define VFD_PWM_COOLANT_MIST DOUT3 +#endif +#endif + +// if unset uses ANALOG0 input by default has the VFD input speed feedback control +#ifndef VFD_PWM_ANALOG_FEEDBACK +#define VFD_PWM_ANALOG_FEEDBACK ANALOG0 +#endif + +// if unset VFD_PWM PID sample rate is 125Hz +// this tool PID settings are as follow +// $304=Kp +// $305=Ki +// $306=Kd +#ifndef VFD_PWM_PID_SAMPLE_RATE_HZ +#define VFD_PWM_PID_SAMPLE_RATE_HZ 125 +#endif + +``` \ No newline at end of file From fe8cd83934175ed610f254411651977fd5048f3b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 20:02:15 +0100 Subject: [PATCH 070/168] Update README.md --- uCNC/src/hal/tools/tools/README.md | 160 ++++++++++++++++++++++++++++- 1 file changed, 159 insertions(+), 1 deletion(-) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index f64a6babd..5973602ac 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -270,4 +270,162 @@ These are the default µCNC pins/definitions for this tool: #define VFD_PWM_PID_SAMPLE_RATE_HZ 125 #endif -``` \ No newline at end of file +``` + + +## vfd_modbus + +This tool controls a VFD using modbus communication protocol. +The modbus is supported over the softuart module that implement a pure software (bit-banging) uart emulation. + +Currently supports: + - HUANYANG type1 (tested) + - HUANYANG type2 (untested) + - YL620 (partially tested) + +These are the default µCNC pins/configurations for this tool: + +``` +// defines default coolant pins +#ifdef ENABLE_COOLANT +// if unset uses DOUT2 by default has the tool flood output control +#ifndef VFD_COOLANT_FLOOD +#define VFD_COOLANT_FLOOD DOUT1 +#endif +// if unset uses DOUT3 by default has the tool mist output control +#ifndef VFD_COOLANT_MIST +#define VFD_COOLANT_MIST DOUT2 +#endif +#endif + +// defines VFD report mode +// if false returns programmed speed +// if true return speed read from VFD (if VFD supports this) +#ifndef GET_SPINDLE_TRUE_RPM +#define GET_SPINDLE_TRUE_RPM false +#endif + +// defines default softuart pins and vfd communication settings +#ifndef VFD_TX_PIN +// uses DOUT27 as the default UART TX pin on softuart +#define VFD_TX_PIN DOUT27 +#endif +// uses DIN27 as the default UART RX pin on softuart +#ifndef VFD_RX_PIN +#define VFD_RX_PIN DIN27 +#endif +// uses a default baudrate of 9600 for the softuart +#ifndef VFD_BAUDRATE +#define VFD_BAUDRATE 9600 +#endif +// uses a default value of 100ms as a communication timeout +#ifndef VFD_TIMEOUT +#define VFD_TIMEOUT 100 +#endif +// uses a default value of 100ms as a communication retry in case of a timeout +#ifndef VFD_RETRY_DELAY_MS +#define VFD_RETRY_DELAY_MS 100 +#endif + +// by default it will put the machine on HOLD if a communication error happens with the VFD +// you can add this to override that behavior +// #define IGNORE_VFD_COM_ERRORS + +// sets the VFD communication address +#define VFD_ADDRESS 8 +// sets the number of retries in case of a communication error +#define VFD_MAX_COMMAND_RETRIES 2 + +``` + +Most VFD don't follow any type of standard regarding modbus implementation. This tool has a set of formated blocks for 3 different brands of VFD but possibly can be extended to be used with others. + +A VFD custom VFD might be added by defining the message settings and the VFD settings needed to convert frequency to speed and vice versa + +``` +/** + * + * VFD Commands are an array of 7 bytes that have the following information + * + * {tx command length, rx command length, MODBUS command type, start address high byte, start address low byte, value high byte, value low byte} + * + * A typical MODBUS command is usually 8 + * A tx command length of 0 will mute the command + * + * Some VFD do not use the standard MODBUS message format and some times the command length is different (like the Huanyang Type1) + * + * */ + +``` + +Here is the example for the HUANYANG type1 that does not use 8 byte length commands + +``` +#if (VFD_CONTROLLER == VFD_HUANYANG_TYPE1) +#define VFD_SETRPM_CMD \ + { \ + 7, 6, MODBUS_FORCE_SINGLE_COIL, 0x02, 0x00, 0x00, 0x00 \ + } +#define VFD_GETRPM_CMD \ + { \ + 8, 8, MODBUS_READ_INPUT_REGISTERS, 0x03, 0x01, 0x00, 0x00 \ + } +// sets fixed freq 400.00Hz -> 40000 +#define VFD_RPM_HZ_CMD \ + { \ + 8, 8, MODBUS_READ_COIL_STATUS, 0x03, 0x05, 0x00, 0x00 \ + } +#define VFD_CW_CMD \ + { \ + 6, 6, MODBUS_READ_HOLDING_REGISTERS, 0x01, 0x01, 0x00, 0x00 \ + } +#define VFD_CCW_CMD \ + { \ + 6, 6, MODBUS_READ_HOLDING_REGISTERS, 0x01, 0x11, 0x00, 0x00 \ + } +#define VFD_STOP_CMD \ + { \ + 6, 6, MODBUS_READ_HOLDING_REGISTERS, 0x01, 0x08, 0x00, 0x00 \ + } +#define VFD_IN_MULT g_settings.spindle_max_rpm +#define VFD_IN_DIV vfd_state.rpm_hz +#define VFD_OUT_MULT vfd_state.rpm_hz +#define VFD_OUT_DIV g_settings.spindle_max_rpm +``` + +Here is the example for the YL620 that uses 8 byte length commands + +``` +#if (VFD_CONTROLLER == VFD_YL620) +#define VFD_SETRPM_CMD \ + { \ + 8, 8, MODBUS_PRESET_SINGLE_REGISTER, 0x20, 0x01, 0x00, 0x00 \ + } +#define VFD_GETRPM_CMD \ + { \ + 8, 8, MODBUS_READ_HOLDING_REGISTERS, 0x20, 0x0B, 0x00, 0x01 \ + } +#define VFD_RPM_HZ_CMD \ + { \ + 0, MODBUS_READ_HOLDING_REGISTERS, 0xB0, 0x05, 0x00, 0x02 \ + } +#define VFD_CW_CMD \ + { \ + 8, 8, MODBUS_PRESET_SINGLE_REGISTER, 0x20, 0x00, 0x00, 0x12 \ + } +#define VFD_CCW_CMD \ + { \ + 8, 8, MODBUS_PRESET_SINGLE_REGISTER, 0x20, 0x00, 0x00, 0x22 \ + } +#define VFD_STOP_CMD \ + { \ + 8, 8, MODBUS_PRESET_SINGLE_REGISTER, 0x20, 0x00, 0x00, 0x01 \ + } +#define VFD_IN_MULT 60.0f +#define VFD_IN_DIV 10.0f +#define VFD_OUT_MULT 10.0f +#define VFD_OUT_DIV 60.0f +#endif +``` + +Each of these CMDs is then used internally to communicate with the VFD and read/write the VFD coils/registers. From f3dc351ad8174d36cca0211ccc9bdb939323534c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 20:02:44 +0100 Subject: [PATCH 071/168] Update README.md --- uCNC/src/hal/tools/tools/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index 5973602ac..58786d3ac 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -15,7 +15,7 @@ _**Jump to section**_ * [spindle_relay](#spindle_relay) * [spindle_besc](#spindle_besc) * [vfd_pwm](#vfd_pwm) - + * [vfd_modbus](#vfd_modbus) # Available tools in to µCNC From d1e707a7195a89d3e6e4953072409a1456b8f875 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 20:13:10 +0100 Subject: [PATCH 072/168] updated VFD --- uCNC/src/hal/tools/tools/README.md | 23 +++++++++++++++++++++-- uCNC/src/hal/tools/tools/vfd_modbus.c | 8 ++++++-- 2 files changed, 27 insertions(+), 4 deletions(-) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index 58786d3ac..0867357ec 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -345,18 +345,37 @@ A VFD custom VFD might be added by defining the message settings and the VFD set ``` /** * - * VFD Commands are an array of 7 bytes that have the following information + * VFD Commands are an array of 6 (if first byte is 0) or 7(otherwise) bytes that have the following information * * {tx command length, rx command length, MODBUS command type, start address high byte, start address low byte, value high byte, value low byte} * * A typical MODBUS command is usually 8 - * A tx command length of 0 will mute the command + * A tx command length of 0 will mute the command and rx length should be ommited * * Some VFD do not use the standard MODBUS message format and some times the command length is different (like the Huanyang Type1) * * */ +``` + +Let's digest the set RPM command for the HUANYANG type1 with the above information ``` +// 7 bytes +#define VFD_SETRPM_CMD \ + { \ + 7/*tx command length*/, 6/*rx command length*/, MODBUS_FORCE_SINGLE_COIL/*MODBUS command type*/, 0x02/*start address high byte*/, 0x00/*start address low byte*/, 0x00/*value high byte*/, 0x00/*value low byte*/ \ + } +``` + +Here is an example of a 6 byte command (dummy command) + +``` +// 6 bytes +#define VFD_RPM_HZ_CMD \ + { \ + 0/*tx command length (dummy command)*/, MODBUS_READ_HOLDING_REGISTERS/*MODBUS command type*/, 0xB0/*start address high byte*/, 0x05/*start address low byte*/, 0x00/*value high byte*/, 0x02/*value low byte*/ \ + } +``` Here is the example for the HUANYANG type1 that does not use 8 byte length commands diff --git a/uCNC/src/hal/tools/tools/vfd_modbus.c b/uCNC/src/hal/tools/tools/vfd_modbus.c index bc9247710..989ecca54 100644 --- a/uCNC/src/hal/tools/tools/vfd_modbus.c +++ b/uCNC/src/hal/tools/tools/vfd_modbus.c @@ -81,8 +81,12 @@ typedef struct vfd_state static vfd_state_t vfd_state; /*VFD settings*/ +#ifndef VFD_ADDRESS #define VFD_ADDRESS 8 +#endif +#ifndef VFD_MAX_COMMAND_RETRIES #define VFD_MAX_COMMAND_RETRIES 2 +#endif // choose the controller type // types available @@ -97,12 +101,12 @@ static vfd_state_t vfd_state; /** * - * VFD Commands are an array of 7 bytes that have the following information + * VFD Commands are an array of 6 (if first byte is 0 for dummy commands) or 7(otherwise) bytes that have the following information * * {tx command length, rx command length, MODBUS command type, start address high byte, start address low byte, value high byte, value low byte} * * A typical MODBUS command is usually 8 - * A tx command length of 0 will mute the command + * A tx command length of 0 will mute the command and rx length should be ommited * * Some VFD do not use the standard MODBUS message format and some times the command length is different (like the Huanyang Type1) * From 6519577cec8b068c96b3c46124c348368d9d1b45 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 1 Aug 2023 21:41:49 +0100 Subject: [PATCH 073/168] Update README.md --- uCNC/src/hal/tools/tools/README.md | 70 ++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index 0867357ec..d2d29c3f8 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -16,6 +16,7 @@ _**Jump to section**_ * [spindle_besc](#spindle_besc) * [vfd_pwm](#vfd_pwm) * [vfd_modbus](#vfd_modbus) + * [plasma_thc](#plasma_thc) # Available tools in to µCNC @@ -353,6 +354,9 @@ A VFD custom VFD might be added by defining the message settings and the VFD set * A tx command length of 0 will mute the command and rx length should be ommited * * Some VFD do not use the standard MODBUS message format and some times the command length is different (like the Huanyang Type1) + * + * Apart from defining the needed VFD commands, 4 additional definitions must be set to allow converting from tool speed to vfd speed and backward + * Usually on VFD's this is a convertion from VFD frequency to spindle RPM * * */ ``` @@ -448,3 +452,69 @@ Here is the example for the YL620 that uses 8 byte length commands ``` Each of these CMDs is then used internally to communicate with the VFD and read/write the VFD coils/registers. + +## plasma_thc + +This tool controls a plasma torch with automatic height control. +This tool also provides an additional MCode that allows to fully program the plasma startup motion pattern. +While cutting this tool is able to adjust the torch height in real time. By default these adjustments and the status of the plasma arc are controlled by some digital inputs pins (UP/DOWN/ARC_OK). This allows the tool to be controlled by an external module like the Proma THC 150. + +But these inputs can be overriden to use any custom method to control these motions/signals, like for example use an analog input to read the torch/metal voltage difference and use a completelly standalone solution (similar to linuxCNC). + +This tool is also designed to probe the initial height of the cut using the probe input. This can also be overwriten. + +These are the default µCNC pins/configurations for this tool: + +``` +// if unset uses DIN15 by default has UP input signal control +#ifndef PLASMA_UP_INPUT +#define PLASMA_UP_INPUT DIN15 +#endif + +// if unset uses DIN14 by default has DOWN input signal control +#ifndef PLASMA_DOWN_INPUT +#define PLASMA_DOWN_INPUT DIN14 +#endif + +// if unset uses DIN13 by default has ARC OK input signal control +#ifndef PLASMA_ARC_OK_INPUT +#define PLASMA_ARC_OK_INPUT DIN13 +#endif + +// if unset uses DOUT0 by default has PLASMA ON output signal control +#ifndef PLASMA_ON_OUTPUT +#define PLASMA_ON_OUTPUT DOUT0 +#endif + +// if unset uses STEPPER2 (usually used in Z axis) as the THC linear actuator. If multiple STEPPERS are used for Z this should be changed +#ifndef PLASMA_STEPPERS_MASK +#define PLASMA_STEPPERS_MASK (1 << 2) +#endif + +// if unset creates a virtual µCNC pin to be controlled be M62-M65 extension module to enable or disable THC mode (this requires module M62-M65) +#ifndef PLASMA_THC_ENABLE_PIN +#define PLASMA_THC_ENABLE_PIN 64 +#endif +``` + +Additionally a MCode command M103 is available to control the probing and arc start motion using only M3/M4 S commands. +The command has these arguments + +``` +M103 I J R K F D P L +``` + +After these parameters are set THC must be enabled via M62(synched) or M64(immediately). + +With THC enable the M3/M4 commands will do the following motions before igniting the torch. + + - check if ARC OK signal is off + - turn the torch off + - probes down until it hits the metal or fails if after the max probe distance to the metal is not found and retries + - retracts up until it looses contact or fails if after the max probe distance to the metal is not found and retries + - retracts (fast move) to the initial cut height + - turns the torch on, waits the programmed time to form the puddle and read if the arc is ok + - if arc is ok, travells at the cut feed to the final cut height + +After this the motion cut executes. During this time the THC constantly monitors the arc ok signal and halts if it fails, and the up and down signals to see if it as to adjust the cutting height. + From 5ac7ad00cbc879f45326e3e357d5bbcc6bc436c2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 2 Aug 2023 18:04:05 +0100 Subject: [PATCH 074/168] modified laser PPI - modified laser PPI and moved extended MCodes to tool - new lightweight macro HOOKS --- uCNC/cnc_config.h | 7 + uCNC/cnc_hal_config.h | 7 - uCNC/src/cnc_hal_config_helper.h | 11 +- uCNC/src/core/interpolator.c | 68 ++------- uCNC/src/core/interpolator.h | 7 +- uCNC/src/core/parser.c | 88 +---------- uCNC/src/core/parser.h | 3 - uCNC/src/hal/tools/tools/laser_ppi.c | 212 ++++++++++++++++++++++++++- uCNC/src/module.h | 14 ++ 9 files changed, 257 insertions(+), 160 deletions(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 81382af12..18ba51624 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -210,6 +210,13 @@ extern "C" // #define DEFAULT_LASER_PPI 254 // #define DEFAULT_LASER_PPI_USWIDTH 1500 +/** + * + * Enables Plasma THC capabilities + * + * **/ +// #define ENABLE_PLASMA_THC + /** * Feed overrides increments and percentage ranges * */ diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 246e75dd0..c69b503a7 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -133,13 +133,6 @@ extern "C" // #define INVERT_LASER_PPI_LOGIC #endif -/** - * - * Enables Plasma THC capabilities - * - * **/ -// #define ENABLE_PLASMA_THC - /** * * Tool pallete diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index ccfb7fd87..800752e05 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -447,7 +447,9 @@ extern "C" /*laser ppi*/ #if (TOOL_COUNT < 1) #undef ENABLE_LASER_PPI +#undef ENABLE_PLASMA_THC #endif + #ifdef ENABLE_LASER_PPI #ifndef MCU_HAS_ONESHOT_TIMER #error "The current MCU does not support ONESHOT_TIMER or the ONESHOT_TIMER is not configured" @@ -2121,8 +2123,14 @@ typedef uint16_t step_t; #endif #endif -#ifdef ENABLE_PLASMA_THC +#ifdef ENABLE_LASER_PPI +// forces modes +#ifndef ENABLE_RT_SYNC_MOTIONS +#define ENABLE_RT_SYNC_MOTIONS +#endif +#endif +#ifdef ENABLE_PLASMA_THC // forces modes #ifndef ENABLE_TOOL_PID_CONTROLLER #define ENABLE_TOOL_PID_CONTROLLER @@ -2136,7 +2144,6 @@ typedef uint16_t step_t; #ifndef ENABLE_RT_SYNC_MOTIONS #define ENABLE_RT_SYNC_MOTIONS #endif - #endif #ifdef ENABLE_TOOL_PID_CONTROLLER diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 1f4cbe664..ac09a281d 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -66,7 +66,8 @@ static volatile uint8_t itp_step_lock; #endif #ifdef ENABLE_RT_SYNC_MOTIONS -volatile int32_t itp_sync_step_counter; +// deprecated with new hooks +// volatile int32_t itp_sync_step_counter; void itp_update_feed(float feed) { @@ -96,6 +97,9 @@ bool itp_sync_ready(void) return false; } + +CREATE_HOOK(itp_rt_pre_stepbits); +CREATE_HOOK(itp_rt_stepbits); #endif static void itp_sgm_buffer_read(void); @@ -854,24 +858,6 @@ uint32_t itp_get_rt_line_number(void) } #endif -#ifdef ENABLE_LASER_PPI -// turn laser off callback -MCU_CALLBACK void laser_ppi_turnoff_cb(void) -{ -#ifndef INVERT_LASER_PPI_LOGIC - io_clear_output(LASER_PPI); -#else - io_set_output(LASER_PPI); -#endif -} -#endif - -#ifdef ENABLE_RT_SYNC_MOTIONS -void __attribute__((weak)) itp_rt_stepbits(uint8_t *stepbits, uint8_t *dirs) -{ -} -#endif - // always fires after pulse MCU_CALLBACK void mcu_step_reset_cb(void) { @@ -883,9 +869,6 @@ MCU_CALLBACK void mcu_step_cb(void) { static uint8_t stepbits = 0; static bool itp_busy = false; -#ifdef ENABLE_LASER_PPI - static uint16_t new_laser_ppi = 0; -#endif #ifdef RT_STEP_PREVENT_CONDITION if (RT_STEP_PREVENT_CONDITION) @@ -911,18 +894,7 @@ MCU_CALLBACK void mcu_step_cb(void) #if TOOL_COUNT > 0 if (itp_rt_sgm->flags & ITP_UPDATE_TOOL) { -#ifdef ENABLE_LASER_PPI - if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) - { - new_laser_ppi = itp_rt_sgm->spindle; - } - else - { -#endif - tool_set_speed(itp_rt_sgm->spindle); -#ifdef ENABLE_LASER_PPI - } -#endif + tool_set_speed(itp_rt_sgm->spindle); } #endif itp_rt_sgm->flags &= ~(ITP_UPDATE); @@ -938,28 +910,11 @@ MCU_CALLBACK void mcu_step_cb(void) } uint8_t new_stepbits = stepbits; - + io_toggle_steps(new_stepbits); // sets step bits -#ifdef ENABLE_LASER_PPI - if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) - { - if (new_stepbits & LASER_PPI_MASK) - { - if (new_laser_ppi) - { - mcu_config_timeout(&laser_ppi_turnoff_cb, new_laser_ppi); - new_laser_ppi = 0; - } - mcu_start_timeout(); -#ifndef INVERT_LASER_PPI_LOGIC - io_set_output(LASER_PPI); -#else - io_clear_output(LASER_PPI); -#endif - } - } +#ifdef ENABLE_RT_SYNC_MOTIONS + HOOK_INVOKE(itp_rt_stepbits, new_stepbits, itp_rt_sgm->flags); #endif - io_toggle_steps(new_stepbits); // if buffer empty loads one if (itp_rt_sgm == NULL) @@ -1039,12 +994,15 @@ MCU_CALLBACK void mcu_step_cb(void) } } +/* +Must put this on G33 module #ifdef ENABLE_RT_SYNC_MOTIONS if (new_stepbits && (itp_rt_sgm->flags & ITP_SYNC)) { itp_sync_step_counter++; } #endif +*/ new_stepbits = 0; itp_busy = true; @@ -1218,7 +1176,7 @@ MCU_CALLBACK void mcu_step_cb(void) static uint8_t last_dirs = 0; if (new_stepbits) { - itp_rt_stepbits(&new_stepbits, &dirs); + HOOK_INVOKE(itp_rt_pre_stepbits, &new_stepbits, &dirs); if (dirs != last_dirs) { last_dirs = dirs; diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index 3d63af062..fc92a967b 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -92,7 +92,7 @@ extern "C" float itp_get_rt_feed(void); bool itp_is_empty(void); uint8_t itp_sync(void); - + void itp_sync_spindle(void); void itp_start(bool is_synched); #if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(KINEMATICS_MOTION_BY_SEGMENTS)) @@ -102,10 +102,11 @@ extern "C" uint32_t itp_get_rt_line_number(void); #endif #ifdef ENABLE_RT_SYNC_MOTIONS - extern volatile int32_t itp_sync_step_counter; + // extern volatile int32_t itp_sync_step_counter; void itp_update_feed(float feed); bool itp_sync_ready(void); - void itp_rt_stepbits(uint8_t *stepbits, uint8_t* dirs); + DECL_HOOK(itp_rt_pre_stepbits, uint8_t *, uint8_t *); + DECL_HOOK(itp_rt_stepbits, uint8_t, uint8_t); #endif #ifdef __cplusplus diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 9d9cb6d27..6c03806ae 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -30,11 +30,6 @@ // extended codes #define M10 EXTENDED_MCODE(10) -#ifdef ENABLE_LASER_PPI -#define M126 EXTENDED_MCODE(126) -#define M127 EXTENDED_MCODE(127) -#define M128 EXTENDED_MCODE(128) -#endif #define PARSER_PARAM_SIZE (sizeof(float) * AXIS_COUNT) // parser parameters array size #define PARSER_PARAM_ADDR_OFFSET (PARSER_PARAM_SIZE + 1) // parser parameters array size + 1 crc byte @@ -64,10 +59,6 @@ static uint8_t parser_wco_counter; static float g92permanentoffset[AXIS_COUNT]; static int32_t rt_probe_step_pos[STEPPER_COUNT]; static float parser_last_pos[AXIS_COUNT]; -#ifdef ENABLE_LASER_PPI -// turn laser off callback -extern MCU_CALLBACK void laser_ppi_turnoff_cb(void); -#endif static unsigned char parser_get_next_preprocessed(bool peek); FORCEINLINE static void parser_get_comment(unsigned char start_char); @@ -1089,20 +1080,6 @@ static uint8_t parser_validate_command(parser_state_t *new_state, parser_words_t return STATUS_GCODE_VALUE_WORD_MISSING; } break; -#endif -#ifdef ENABLE_LASER_PPI - case M127: - case M128: - // prevents command execution if mode disabled - if (!(g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE))) - { - return STATUS_LASER_PPI_MODE_DISABLED; - } - case M126: - if (CHECKFLAG(cmd->words, (GCODE_WORD_P)) != (GCODE_WORD_P)) - { - return STATUS_GCODE_VALUE_WORD_MISSING; - } #endif } @@ -1165,32 +1142,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa } break; #endif -#ifdef ENABLE_LASER_PPI - case M126: - g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); - switch ((((uint8_t)words->p))) - { - case 1: - g_settings.laser_mode |= LASER_PPI_MODE; - break; - case 2: - g_settings.laser_mode |= LASER_PPI_VARPOWER_MODE; - break; - case 3: - g_settings.laser_mode |= (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); - break; - } - parser_config_ppi(); - break; - case M127: - g_settings.step_per_mm[STEPPER_COUNT - 1] = words->p * MM_INCH_MULT; - parser_config_ppi(); - break; - case M128: - g_settings.laser_ppi_uswidth = (uint16_t)words->p; - parser_config_ppi(); - break; -#endif + default: error = STATUS_GCODE_UNSUPPORTED_COMMAND; #ifdef ENABLE_PARSER_MODULES @@ -2376,19 +2328,6 @@ static uint8_t parser_mcode_word(uint8_t code, uint8_t mantissa, parser_state_t cmd->group_extended = M10; return STATUS_OK; #endif -#ifdef ENABLE_LASER_PPI - case 126: - case 127: - case 128: - if (cmd->group_extended > 0) - { - // there is a collision of custom gcode commands (only one per line can be processed) - return STATUS_GCODE_MODAL_GROUP_VIOLATION; - } - // tells the gcode validation and execution functions this is custom code(ID must be unique) - cmd->group_extended = EXTENDED_MCODE(code); - return STATUS_OK; -#endif default: return STATUS_GCODE_UNSUPPORTED_COMMAND; @@ -2624,9 +2563,6 @@ void parser_reset(bool stopgroup_only) parser_state.groups.tool_change = 1; parser_state.tool_index = g_settings.default_tool; parser_state.groups.path_mode = G61; -#ifdef ENABLE_LASER_PPI - parser_config_ppi(); -#endif #endif parser_state.groups.motion = G1; // G1 parser_state.groups.units = G21; // G21 @@ -3023,25 +2959,3 @@ void parser_machine_to_work(float *axis) } #endif } - -#ifdef ENABLE_LASER_PPI -void parser_config_ppi(void) -{ - g_settings.acceleration[STEPPER_COUNT - 1] = FLT_MAX; - if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) - { - // if previously disabled, reload default value - if (!g_settings.step_per_mm[STEPPER_COUNT - 1]) - { - g_settings.step_per_mm[STEPPER_COUNT - 1] = g_settings.laser_ppi * MM_INCH_MULT; - } - g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (g_settings.laser_ppi_uswidth * g_settings.step_per_mm[STEPPER_COUNT - 1])); - mcu_config_timeout(&laser_ppi_turnoff_cb, g_settings.laser_ppi_uswidth); - } - else - { - g_settings.step_per_mm[STEPPER_COUNT - 1] = 0; - g_settings.max_feed_rate[STEPPER_COUNT - 1] = FLT_MAX; - } -} -#endif diff --git a/uCNC/src/core/parser.h b/uCNC/src/core/parser.h index 88731db45..4d542ab4d 100644 --- a/uCNC/src/core/parser.h +++ b/uCNC/src/core/parser.h @@ -287,9 +287,6 @@ extern "C" void parser_machine_to_work(float *axis); uint8_t parser_get_float(float *value); uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); -#ifdef ENABLE_LASER_PPI - void parser_config_ppi(void); -#endif #ifdef ENABLE_PARSER_MODULES // generates a default delegate, event and handler hook diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 2e45763c1..3fd574a4e 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -36,6 +36,202 @@ #ifdef ENABLE_LASER_PPI +/** + * + * Motion and interpolator related stuff + * + * **/ + +// turn laser off callback via ONESHOT timer +MCU_CALLBACK void laser_ppi_turnoff_cb(void) +{ +#ifndef INVERT_LASER_PPI_LOGIC + io_clear_output(LASER_PPI); +#else + io_set_output(LASER_PPI); +#endif +} + +// laser ppi pulse callback called from the step ISR +static uint16_t new_laser_ppi = 0; +MCU_CALLBACK void laser_ppi_pulse(uint8_t new_stepbits, uint8_t flags) +{ + if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + { + if (new_stepbits & LASER_PPI_MASK) + { + if (new_laser_ppi) + { + mcu_config_timeout(&laser_ppi_turnoff_cb, new_laser_ppi); + new_laser_ppi = 0; + } + mcu_start_timeout(); +#ifndef INVERT_LASER_PPI_LOGIC + io_set_output(LASER_PPI); +#else + io_clear_output(LASER_PPI); +#endif + } + } +} + +// configs the parameters for laser PPI +// called by each custom laser PPI MCode and on parser reset +static void laser_ppi_config_parameters(void) +{ + g_settings.acceleration[STEPPER_COUNT - 1] = FLT_MAX; + if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + { + // if previously disabled, reload default value + if (!g_settings.step_per_mm[STEPPER_COUNT - 1]) + { + g_settings.step_per_mm[STEPPER_COUNT - 1] = g_settings.laser_ppi * MM_INCH_MULT; + } + g_settings.max_feed_rate[STEPPER_COUNT - 1] = (60000000.0f / (g_settings.laser_ppi_uswidth * g_settings.step_per_mm[STEPPER_COUNT - 1])); + mcu_config_timeout(&laser_ppi_turnoff_cb, g_settings.laser_ppi_uswidth); + } + else + { + g_settings.step_per_mm[STEPPER_COUNT - 1] = 0; + g_settings.max_feed_rate[STEPPER_COUNT - 1] = FLT_MAX; + } +} + +/** + * + * Parser extensions + * Parser extensions are optional since these can be controlled via tool options + * + * **/ + +#ifdef ENABLE_PARSER_MODULES + +bool laser_ppi_parser_reset(void *args) +{ + laser_ppi_config_parameters(); + return EVENT_CONTINUE; +} +// create event listener +CREATE_EVENT_LISTENER(parser_reset, laser_ppi_parser_reset); + +#define M126 EXTENDED_MCODE(126) +#define M127 EXTENDED_MCODE(127) +#define M128 EXTENDED_MCODE(128) + +// this just parses and acceps the code +bool laser_ppi_mcodes_parse(void *args) +{ + gcode_parse_args_t *ptr = (gcode_parse_args_t *)args; + if (ptr->word == 'M') + { + switch (ptr->code) + { + case 126: + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + } + else + { + ptr->cmd->group_extended = M126; + *(ptr->error) = STATUS_OK; + } + return EVENT_HANDLED; + case 127: + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + } + else + { + ptr->cmd->group_extended = M127; + *(ptr->error) = STATUS_OK; + } + return EVENT_HANDLED; + case 128: + if (ptr->cmd->group_extended != 0) + { + // there is a collision of custom gcode commands (only one per line can be processed) + *(ptr->error) = STATUS_GCODE_MODAL_GROUP_VIOLATION; + } + else + { + ptr->cmd->group_extended = M128; + *(ptr->error) = STATUS_OK; + } + return EVENT_HANDLED; + } + } + + // if this is not catched by this parser, just send back the error so other extenders can process it + return EVENT_CONTINUE; +} + +CREATE_EVENT_LISTENER(gcode_parse, laser_ppi_mcodes_parse); + +// this actually performs 2 steps in 1 (validation and execution) +bool laser_ppi_mcodes_exec(void *args) +{ + gcode_exec_args_t *ptr = (gcode_exec_args_t *)args; + switch (ptr->cmd->group_extended) + { + case M127: + case M128: + // prevents command execution if mode disabled + if (!(g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE))) + { + *(ptr->error) = STATUS_LASER_PPI_MODE_DISABLED; + return EVENT_HANDLED; + } + case M126: + if (CHECKFLAG(ptr->cmd->words, (GCODE_WORD_P)) != (GCODE_WORD_P)) + { + *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; + return EVENT_HANDLED; + } + break; + } + + switch (ptr->cmd->group_extended) + { + case M126: + g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); + switch ((((uint8_t)ptr->words->p))) + { + case 1: + g_settings.laser_mode |= LASER_PPI_MODE; + break; + case 2: + g_settings.laser_mode |= LASER_PPI_VARPOWER_MODE; + break; + case 3: + g_settings.laser_mode |= (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); + break; + } + laser_ppi_config_parameters(); + break; + case M127: + g_settings.step_per_mm[STEPPER_COUNT - 1] = ptr->words->p * MM_INCH_MULT; + laser_ppi_config_parameters(); + break; + case M128: + g_settings.laser_ppi_uswidth = (uint16_t)ptr->words->p; + laser_ppi_config_parameters(); + break; + } + + return EVENT_CONTINUE; +} + +CREATE_EVENT_LISTENER(gcode_exec, laser_ppi_mcodes_exec); +#endif + +/** + * Now starts the actual tool functions definitions + * These functions will then be called by the tool HAL + * **/ static void startup_code(void) { // force laser mode @@ -48,7 +244,8 @@ static void startup_code(void) #endif #endif g_settings.laser_mode |= LASER_PPI_MODE; - parser_config_ppi(); + laser_ppi_config_parameters(); + HOOK_ATTACH_CALLBACK(itp_rt_stepbits, laser_ppi_pulse); } static void shutdown_code(void) @@ -62,7 +259,8 @@ static void shutdown_code(void) #endif // restore laser mode g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); - parser_config_ppi(); + laser_ppi_config_parameters(); + HOOK_RELEASE(itp_rt_stepbits); } static void set_coolant(uint8_t value) @@ -73,6 +271,14 @@ static void set_coolant(uint8_t value) #endif } +static void set_speed(int16_t value) +{ + if (g_settings.laser_mode & (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE)) + { + new_laser_ppi = value; + } +} + static uint16_t get_speed(void) { return g_settings.step_per_mm[STEPPER_COUNT - 1]; @@ -84,7 +290,7 @@ const tool_t laser_ppi = { .pid_update = NULL, .range_speed = NULL, .get_speed = &get_speed, - .set_speed = NULL, + .set_speed = &set_speed, .set_coolant = &set_coolant}; #endif diff --git a/uCNC/src/module.h b/uCNC/src/module.h index 9f1ad3efe..fe99003f2 100644 --- a/uCNC/src/module.h +++ b/uCNC/src/module.h @@ -102,6 +102,20 @@ extern "C" void mod_init(void); +// uses VARADIC MACRO available since C99 +#define DECL_HOOK(name, ...) \ + typedef void (*name##_delegate_t)(__VA_ARGS__); \ + extern name##_delegate_t name##_cb +#define CREATE_HOOK(name) name##_delegate_t name##_cb +#define HOOK_ATTACH_CALLBACK(name, cb) name##_cb = &cb +#define HOOK_RELEASE(name) name##_cb = NULL + +#define HOOK_INVOKE(name, ...) \ + if (name##_cb) \ + { \ + name##_cb(__VA_ARGS__); \ + } + #ifdef __cplusplus } #endif From fa4895b4eee92b36d0bef4324043252045a2b297 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 3 Aug 2023 14:37:08 +0100 Subject: [PATCH 075/168] fixed itp_rt_stepbits hook - fixed itp_rt_stepbits hook calling - added RUNONCE macro to load modules in loops --- makefiles/virtual/uCNC.dev | 2 +- uCNC/src/core/interpolator.c | 36 ++++++++++++++++++++---------------- uCNC/src/module.h | 6 ++++++ 3 files changed, 27 insertions(+), 17 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 32ec8f46c..3b2c21fbc 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=81 +UnitCount=80 [VersionInfo] Major=1 diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index ac09a281d..eb67fff1c 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -882,6 +882,17 @@ MCU_CALLBACK void mcu_step_cb(void) return; } + uint8_t new_stepbits = stepbits; + io_toggle_steps(new_stepbits); + + // sets step bits +#ifdef ENABLE_RT_SYNC_MOTIONS + if (new_stepbits && itp_rt_sgm) + { + HOOK_INVOKE(itp_rt_stepbits, new_stepbits, itp_rt_sgm->flags); + } +#endif + if (itp_rt_sgm != NULL) { if (itp_rt_sgm->flags & ITP_UPDATE) @@ -909,13 +920,6 @@ MCU_CALLBACK void mcu_step_cb(void) } } - uint8_t new_stepbits = stepbits; - io_toggle_steps(new_stepbits); - // sets step bits -#ifdef ENABLE_RT_SYNC_MOTIONS - HOOK_INVOKE(itp_rt_stepbits, new_stepbits, itp_rt_sgm->flags); -#endif - // if buffer empty loads one if (itp_rt_sgm == NULL) { @@ -994,15 +998,15 @@ MCU_CALLBACK void mcu_step_cb(void) } } -/* -Must put this on G33 module -#ifdef ENABLE_RT_SYNC_MOTIONS - if (new_stepbits && (itp_rt_sgm->flags & ITP_SYNC)) - { - itp_sync_step_counter++; - } -#endif -*/ + /* + Must put this on G33 module + #ifdef ENABLE_RT_SYNC_MOTIONS + if (new_stepbits && (itp_rt_sgm->flags & ITP_SYNC)) + { + itp_sync_step_counter++; + } + #endif + */ new_stepbits = 0; itp_busy = true; diff --git a/uCNC/src/module.h b/uCNC/src/module.h index fe99003f2..ff9308bd5 100644 --- a/uCNC/src/module.h +++ b/uCNC/src/module.h @@ -116,6 +116,12 @@ extern "C" name##_cb(__VA_ARGS__); \ } +#define RUNONCE \ + static bool runonce = false; \ + if (!runonce) + +#define RUNONCE_COMPLETE() runonce = true + #ifdef __cplusplus } #endif From 91d0e4ca12c619287ef5a22145bbd7612b44797e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 3 Aug 2023 16:48:27 +0100 Subject: [PATCH 076/168] Settings extension enabled by default --- uCNC/cnc_config.h | 8 +++++++- uCNC/src/cnc_hal_config_helper.h | 4 ++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 18ba51624..86100348e 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -319,7 +319,13 @@ extern "C" // #define ENABLE_IO_MODULES // #define ENABLE_PARSER_MODULES // #define ENABLE_MOTION_CONTROL_MODULES -// #define ENABLE_SETTINGS_MODULES + + /** + * Settings extensions are enabled by default + * Uncomment to disable this extension. + * Some option might override this (like ENABLE_TOOL_PID_CONTROLLER) + * */ +// #define DISABLE_SETTINGS_MODULES /** * Report specific options diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 800752e05..35286a053 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2123,6 +2123,10 @@ typedef uint16_t step_t; #endif #endif +#ifndef DISABLE_SETTINGS_MODULES +#define ENABLE_SETTINGS_MODULES +#endif + #ifdef ENABLE_LASER_PPI // forces modes #ifndef ENABLE_RT_SYNC_MOTIONS From 447b8256ae796828ae7a31364c67c3c06675ddb5 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 3 Aug 2023 17:51:10 +0100 Subject: [PATCH 077/168] Update README.md fixed laser_ppi documentation --- uCNC/src/hal/tools/tools/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/hal/tools/tools/README.md b/uCNC/src/hal/tools/tools/README.md index d2d29c3f8..32e8cdf9f 100644 --- a/uCNC/src/hal/tools/tools/README.md +++ b/uCNC/src/hal/tools/tools/README.md @@ -104,7 +104,7 @@ Laser PPI is able to use not only generic output pins but also PWM pins by chang Laser PPI has 3 working modes. - PPI mode, by setting $32=2. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. The number of pulses will be affected by the tool S parameter. For example if you define a PPI value of 254 (254 pulses per inch) and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI output will be adjusted to 50% (or 127PPI). This is similar to the ways M4 works in laser PWM. The pulse width is fixed and is configured by setting $34 (in us-microseconds) - PPI PW mode, by setting $32=4. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. In this case the tool S parameter will affect the pulse width set by $34. For example if you define a PPI width value of 900us and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI pulse width output will be adjusted to 50% (or 450us). - - PPI mixed mode, by setting $32=6. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. This mode makes a ratio mix of both the above mentioned modes unsing an inverse ratio defined by setting $35. For example if you define a PPI value of 254 and a width value of 900us and $35 = 0.75 (75%) and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI will be adjusted in 0.75 of 50% of the value (that translates to 37.5% or 159PPI) and pulse width output will be of (1 - 0.75) of 50% (or 788us). + - PPI mixed mode, by setting $32=6. This mode will ensure that the programmed number of pulses per inch with a set width will be output and is configured by setting $33. This mode makes a ratio mix of both the above mentioned modes settings $35(PPI blend ratio) and $36(PPI width blend ratio). For example if you define a PPI value of 254 and a width value of 900us and $35 = 0.25 (25%) and $36 = 0.75 (75%) and set the S to 500 (in a range of 0-1000, or in other words 50%) the PPI will be adjusted in 0.25 of 50% of the value (reduced in 12.5% of 254 ~= 222PPI) and pulse width output will be of 0.75 of 50% (reduced in 37.5% of 900us ~= 563us). This tool also enables a few extra MCode commands that allow to directly modify settings $32, $33 and $34. These are From a78c64439314ce6ad54714331d88fe632869e3a0 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 3 Aug 2023 23:14:53 +0100 Subject: [PATCH 078/168] fixed laser PPI Mcode extensions --- uCNC/src/hal/tools/tools/laser_ppi.c | 51 ++++++++++++++++------------ 1 file changed, 30 insertions(+), 21 deletions(-) diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 3fd574a4e..85af14434 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -191,35 +191,37 @@ bool laser_ppi_mcodes_exec(void *args) *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; return EVENT_HANDLED; } + + *(ptr->error) = STATUS_OK; break; } switch (ptr->cmd->group_extended) { - case M126: - g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); - switch ((((uint8_t)ptr->words->p))) - { - case 1: - g_settings.laser_mode |= LASER_PPI_MODE; - break; - case 2: - g_settings.laser_mode |= LASER_PPI_VARPOWER_MODE; - break; - case 3: - g_settings.laser_mode |= (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); - break; - } - laser_ppi_config_parameters(); + case M126: + g_settings.laser_mode &= ~(LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); + switch ((((uint8_t)ptr->words->p))) + { + case 1: + g_settings.laser_mode |= LASER_PPI_MODE; break; - case M127: - g_settings.step_per_mm[STEPPER_COUNT - 1] = ptr->words->p * MM_INCH_MULT; - laser_ppi_config_parameters(); + case 2: + g_settings.laser_mode |= LASER_PPI_VARPOWER_MODE; break; - case M128: - g_settings.laser_ppi_uswidth = (uint16_t)ptr->words->p; - laser_ppi_config_parameters(); + case 3: + g_settings.laser_mode |= (LASER_PPI_MODE | LASER_PPI_VARPOWER_MODE); break; + } + laser_ppi_config_parameters(); + return EVENT_HANDLED; + case M127: + g_settings.laser_ppi = (uint16_t)ptr->words->p; + laser_ppi_config_parameters(); + return EVENT_HANDLED; + case M128: + g_settings.laser_ppi_uswidth = (uint16_t)ptr->words->p; + laser_ppi_config_parameters(); + return EVENT_HANDLED; } return EVENT_CONTINUE; @@ -246,6 +248,13 @@ static void startup_code(void) g_settings.laser_mode |= LASER_PPI_MODE; laser_ppi_config_parameters(); HOOK_ATTACH_CALLBACK(itp_rt_stepbits, laser_ppi_pulse); + + RUNONCE + { + ADD_EVENT_LISTENER(gcode_parse, laser_ppi_mcodes_parse); + ADD_EVENT_LISTENER(gcode_exec, laser_ppi_mcodes_exec); + RUNONCE_COMPLETE(); + } } static void shutdown_code(void) From b1856e5f9c46a7b2e39064448cf21d0619b4df40 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 4 Aug 2023 12:51:16 +0100 Subject: [PATCH 079/168] adoption of HOOK on encoder module --- uCNC/src/modules/encoder.c | 17 ++--------------- uCNC/src/modules/encoder.h | 5 +---- 2 files changed, 3 insertions(+), 19 deletions(-) diff --git a/uCNC/src/modules/encoder.c b/uCNC/src/modules/encoder.c index 927294d17..5279d8a72 100644 --- a/uCNC/src/modules/encoder.c +++ b/uCNC/src/modules/encoder.c @@ -36,18 +36,8 @@ static int32_t encoders_pos[ENCODERS]; static volatile uint32_t prev_time; static volatile uint32_t current_time; -static encoder_index_cb rpm_index_cb; bool encoder_rpm_updated; - -void encoder_attach_index_cb(encoder_index_cb callback) -{ - rpm_index_cb = callback; -} - -void encoder_dettach_index_cb(void) -{ - rpm_index_cb = NULL; -} +CREATE_HOOK(encoder_index); uint16_t encoder_get_rpm(void) { @@ -173,10 +163,7 @@ void encoders_update(uint8_t pulse, uint8_t diff) #endif { encoders_pos[RPM_ENCODER] = 0; - if (rpm_index_cb) - { - rpm_index_cb(); - } + HOOK_INVOKE(encoder_index); } } #endif diff --git a/uCNC/src/modules/encoder.h b/uCNC/src/modules/encoder.h index 89371874e..f07bc2206 100644 --- a/uCNC/src/modules/encoder.h +++ b/uCNC/src/modules/encoder.h @@ -36,17 +36,14 @@ extern "C" #define ENC6 6 #define ENC7 7 - typedef void (*encoder_index_cb)(void); - DECL_MODULE(encoder); + DECL_HOOK(encoder_index, void); int32_t encoder_get_position(uint8_t i); void encoder_print_values(void); void encoder_reset_position(uint8_t i, int32_t position); void encoders_reset_position(void); void encoders_itp_reset_rt_position(float *origin); void encoders_update(uint8_t pulse, uint8_t diff); - void encoder_attach_index_cb(encoder_index_cb callback); - void encoder_dettach_index_cb(void); uint16_t encoder_get_rpm(void); extern bool encoder_rpm_updated; From 617c15e8f1887775f4c0dbf438ca9a6979e60936 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 4 Aug 2023 14:52:50 +0100 Subject: [PATCH 080/168] Update README.md --- uCNC/src/README.md | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 491daf25f..c85cfad69 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -12,6 +12,7 @@ These files contain initialization code for all modules that extend µCNC functi _**Jump to section**_ * [Adding custom modules to µCNC](#adding-custom-modules-to-µcnc) * [µCNC existing events/delegates](#µcnc-existing-eventsdelegates) + * [µCNC existing hooks](#µcnc-existing-hooks) * [modules.h and events](#modulesh-and-events) * [Creating a new custom event listener](#creating-a-new-custom-event-listener) * [Creating a new custom event](#creating-a-new-custom-event) @@ -25,6 +26,7 @@ __NOTE__: _Version 1.4.6 implemented changes to module initialization. Also addi µCNC has implemented a module system that allows the user to perform custom actions that get executed in an event/delegate fashion style similar to what is done with C#. Multiple callbacks functions can be attached to the same event. These modules can be quite useful and perform several things like adding custom custom gcodes to perform actions, or modifying IO states if a given condition is verified. µCNC already has a few useful modules like PID controller, Encoder module, TMC drivers support and custom G/M code support. +Version 1.8 also introduces the concept of simple hooks. These hooks are simple function pointers that execute the assigned callback at that time. They are usually used inside interrupt service routines and provide a way to extend ISR's with small extra code blocks to perform certain tasks. Unlike events, simple hooks can only run a single callback. The active callback is the last one to attach to any give hook. ## µCNC existing events/delegates @@ -184,6 +186,18 @@ typedef struct } motion_data_t; ``` +## µCNC existing hooks + +These are the list of available hooks inside + +__NOTE__: Not all simple hooks may be listed here. To find all available simple hooks declarations, do a search on all files (on VSCode in Windows it's Ctrl+Shift+F) of the project of `DECL_HOOK`. You can also search for the `HOOK_INVOKE` to see what argument is being passed to the simple hook handler. + +| Event name | Argument | Enable option | Description | +| --- | --- | --- | --- | +| itp_rt_pre_stepbits | int*, int* | ENABLE_RT_SYNC_MOTIONS | Fires when the next computed step bits and dirs have been computed to be output. Args are a pointer the stepbit var and a pointer to a dirbit var | +| itp_rt_stepbits | int, int | ENABLE_RT_SYNC_MOTIONS | Fires when the setpbits have been output to the IO. Args are the stepbit mask value and the step ISR flags value | +| encoder_index | void | ENCODER_COUNT | Fires when the index of the specialized rpm encoder is triggered. Has no args | + ## modules.h and events `src/module.h` exposes a few handy macros that make event listeners, or custom events creations easy. From 4b922c674168ec3c0f1e66f16c048892de394286 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 4 Aug 2023 16:26:44 +0100 Subject: [PATCH 081/168] minor modifications to laser and plasma loading --- uCNC/src/hal/tools/tools/laser_ppi.c | 19 +++++++++------- uCNC/src/hal/tools/tools/plasma_thc.c | 31 +++++++++++---------------- uCNC/src/module.c | 4 ++++ 3 files changed, 27 insertions(+), 27 deletions(-) diff --git a/uCNC/src/hal/tools/tools/laser_ppi.c b/uCNC/src/hal/tools/tools/laser_ppi.c index 85af14434..4e1b08997 100644 --- a/uCNC/src/hal/tools/tools/laser_ppi.c +++ b/uCNC/src/hal/tools/tools/laser_ppi.c @@ -191,7 +191,7 @@ bool laser_ppi_mcodes_exec(void *args) *(ptr->error) = STATUS_GCODE_VALUE_WORD_MISSING; return EVENT_HANDLED; } - + *(ptr->error) = STATUS_OK; break; } @@ -230,6 +230,16 @@ bool laser_ppi_mcodes_exec(void *args) CREATE_EVENT_LISTENER(gcode_exec, laser_ppi_mcodes_exec); #endif +DECL_MODULE(laser_ppi) +{ + #ifdef ENABLE_PARSER_MODULES + ADD_EVENT_LISTENER(gcode_parse, laser_ppi_mcodes_parse); + ADD_EVENT_LISTENER(gcode_exec, laser_ppi_mcodes_exec); + #else + #warning "Parser extensions are not enabled. M126, M127 and M128 code extensions will not work." + #endif +} + /** * Now starts the actual tool functions definitions * These functions will then be called by the tool HAL @@ -248,13 +258,6 @@ static void startup_code(void) g_settings.laser_mode |= LASER_PPI_MODE; laser_ppi_config_parameters(); HOOK_ATTACH_CALLBACK(itp_rt_stepbits, laser_ppi_pulse); - - RUNONCE - { - ADD_EVENT_LISTENER(gcode_parse, laser_ppi_mcodes_parse); - ADD_EVENT_LISTENER(gcode_exec, laser_ppi_mcodes_exec); - RUNONCE_COMPLETE(); - } } static void shutdown_code(void) diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 7972267cb..45694fdc8 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -426,17 +426,6 @@ static void pid_update(void) } } -DECL_MODULE(plasma_thc) -{ -#ifdef ENABLE_PARSER_MODULES - ADD_EVENT_LISTENER(gcode_parse, m103_parse); - ADD_EVENT_LISTENER(gcode_exec, m103_exec); - ADD_EVENT_LISTENER(gcode_exec, plasma_virtual_pins); -#else -#error "Parser extensions are not enabled. M103 code extension will not work." -#endif -} - // uses similar status to grblhal bool plasma_protocol_send_status(void *args) { @@ -485,20 +474,24 @@ bool plasma_protocol_send_status(void *args) CREATE_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); -static void startup_code(void) +DECL_MODULE(plasma_thc) { - static bool run_once = false; + ADD_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); +#ifdef ENABLE_PARSER_MODULES + ADD_EVENT_LISTENER(gcode_parse, m103_parse); + ADD_EVENT_LISTENER(gcode_exec, m103_exec); + ADD_EVENT_LISTENER(gcode_exec, plasma_virtual_pins); +#else +#error "Parser extensions are not enabled. M103 code extension will not work." +#endif +} +static void startup_code(void) +{ // force plasma off #if ASSERT_PIN(PLASMA_ON_OUTPUT) io_clear_output(PLASMA_ON_OUTPUT); #endif - - if (!run_once) - { - ADD_EVENT_LISTENER(protocol_send_status, plasma_protocol_send_status); - run_once = true; - } } static void shutdown_code(void) diff --git a/uCNC/src/module.c b/uCNC/src/module.c index d5522d828..f44aabeff 100644 --- a/uCNC/src/module.c +++ b/uCNC/src/module.c @@ -56,6 +56,10 @@ void mod_init(void) LOAD_MODULE(tmcdriver); #endif +#ifdef ENABLE_LASER_PPI + LOAD_MODULE(laser_ppi); +#endif + #ifdef ENABLE_PLASMA_THC LOAD_MODULE(plasma_thc); #endif From 6ed0c3bc0b189df1b6c315dfc5b0c7a1815098e4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 7 Aug 2023 22:15:04 +0100 Subject: [PATCH 082/168] fixed tool helper macros --- uCNC/src/hal/tools/tool_helper.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/uCNC/src/hal/tools/tool_helper.h b/uCNC/src/hal/tools/tool_helper.h index 792a8e94b..9e2de6714 100644 --- a/uCNC/src/hal/tools/tool_helper.h +++ b/uCNC/src/hal/tools/tool_helper.h @@ -37,7 +37,7 @@ extern "C" #define SET_SPINDLE(X, Y, W, Z) \ { \ - io_set_output(Y, Z); \ + io_set_pinvalue(Y, Z); \ io_set_pwm(X, W); \ } @@ -57,8 +57,8 @@ extern "C" * */ #define SET_COOLANT(X, Y, Z) \ { \ - io_set_output(X, (Z && COOLANT_MASK)); \ - io_set_output(Y, (Z && MIST_MASK)); \ + io_set_pinvalue(X, (Z && COOLANT_MASK)); \ + io_set_pinvalue(Y, (Z && MIST_MASK)); \ } #ifdef __cplusplus From 73fab5214f9935f94226e4627dd23a77f1fa99b2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 9 Aug 2023 12:36:27 +0100 Subject: [PATCH 083/168] allow skew settings to have negative values - added #472 --- uCNC/src/interface/settings.c | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index 90b97714c..f955f9947 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -297,6 +297,12 @@ bool settings_allows_negative(setting_offset_t id) { return true; } +#endif +#ifdef ENABLE_SKEW_COMPENSATION + if (id >=37 && id <= 39) + { + return true; + } #endif return false; } From b2ec0a546176652853649affcb5d6e9a606b3590 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 9 Aug 2023 16:37:22 +0100 Subject: [PATCH 084/168] apply skew compensation fix --- uCNC/src/core/interpolator.c | 2 +- uCNC/src/core/motion_control.c | 19 +-- uCNC/src/core/parser.c | 3 +- uCNC/src/hal/kinematics/kinematic.c | 130 ++++++++++++++++++ uCNC/src/hal/kinematics/kinematic.h | 30 ++++ uCNC/src/hal/kinematics/kinematic_cartesian.c | 31 ----- uCNC/src/hal/kinematics/kinematic_corexy.c | 14 -- uCNC/src/hal/kinematics/kinematic_delta.c | 8 -- uCNC/src/hal/kinematics/kinematic_delta.h | 6 - .../hal/kinematics/kinematic_linear_delta.c | 8 -- .../hal/kinematics/kinematic_linear_delta.h | 5 - uCNC/src/interface/protocol.c | 3 +- uCNC/src/modules/system_menu.c | 5 +- 13 files changed, 171 insertions(+), 93 deletions(-) create mode 100644 uCNC/src/hal/kinematics/kinematic.c diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index eb67fff1c..ca47096c1 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -789,7 +789,7 @@ void itp_reset_rt_position(float *origin) } // sync origin and steppers position - kinematics_apply_inverse(origin, itp_rt_step_pos); + kinematics_coordinates_to_steps(origin, itp_rt_step_pos); #if STEPPERS_ENCODERS_MASK != 0 encoders_itp_reset_rt_position(origin); diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 0ebf0885e..cf002b80a 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -262,12 +262,6 @@ uint8_t mc_line(float *target, motion_data_t *block_data) target[AXIS_Z] += target_hmap_offset; #endif - // In homing mode no kinematics modifications is applied to prevent unwanted axis movements - if (!cnc_get_exec_state(EXEC_HOMING)) - { - kinematics_apply_transform(target); - } - // check travel limits (soft limits) if (!kinematics_check_boundaries(target)) { @@ -322,8 +316,9 @@ uint8_t mc_line(float *target, motion_data_t *block_data) } int32_t step_new_pos[STEPPER_COUNT]; + // converts transformed target to stepper position - kinematics_apply_inverse(target, step_new_pos); + kinematics_coordinates_to_steps(target, step_new_pos); // calculates the amount of steps performed for this motion uint32_t max_steps = 0; @@ -487,7 +482,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) h_offset = (CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_APPLY_HMAP)) ? (mc_apply_hmap(prev_target)) : 0; prev_target[AXIS_Z] += h_offset; #endif - kinematics_apply_inverse(prev_target, step_new_pos); + kinematics_coordinates_to_steps(prev_target, step_new_pos); error = mc_line_segment(step_new_pos, block_data); #ifdef ENABLE_G39_H_MAPPING // unmodify target @@ -505,7 +500,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) if (is_subsegment) { - kinematics_apply_inverse(target, step_new_pos); + kinematics_coordinates_to_steps(target, step_new_pos); } #endif error = mc_line_segment(step_new_pos, block_data); @@ -914,13 +909,12 @@ uint8_t mc_probe(float *target, uint8_t flags, motion_data_t *block_data) void mc_get_position(float *target) { memcpy(target, mc_last_target, sizeof(mc_last_target)); - kinematics_apply_reverse_transform(target); } void mc_sync_position(void) { itp_get_rt_position(mc_last_step_pos); - kinematics_apply_forward(mc_last_step_pos, mc_last_target); + kinematics_steps_to_coordinates(mc_last_step_pos, mc_last_target); parser_sync_position(); } @@ -1082,8 +1076,7 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data // store position int32_t probe_position[STEPPER_COUNT]; itp_get_rt_position(probe_position); - kinematics_apply_forward(probe_position, position); - kinematics_apply_reverse_transform(position); + kinematics_steps_to_coordinates(probe_position, position); hmap_offsets[i + H_MAPING_GRID_FACTOR * j] = position[AXIS_Z]; protocol_send_probe_result(1); diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 6c03806ae..ffed36d30 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -301,8 +301,7 @@ void parser_sync_probe(void) void parser_update_probe_pos(void) { - kinematics_apply_forward(rt_probe_step_pos, parser_parameters.last_probe_position); - kinematics_apply_reverse_transform(parser_parameters.last_probe_position); + kinematics_steps_to_coordinates(rt_probe_step_pos, parser_parameters.last_probe_position); } static uint8_t parser_grbl_command(void) diff --git a/uCNC/src/hal/kinematics/kinematic.c b/uCNC/src/hal/kinematics/kinematic.c new file mode 100644 index 000000000..e954d1f71 --- /dev/null +++ b/uCNC/src/hal/kinematics/kinematic.c @@ -0,0 +1,130 @@ +/* + Name: kinematic.c + Description: Implements all generic kinematics function calls. + + Copyright: Copyright (c) João Martins + Author: João Martins + Date: 09/08/2023 + + µCNC 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. Please see + + µCNC is distributed WITHOUT ANY WARRANTY; + Also without the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU General Public License for more details. +*/ + +#include "../../cnc.h" + +/** + * @brief Aplies a transformation to the position sent to planner. + * This is aplied only on normal and jog moves. Homing motions go directly to planner. + * + * @param axis Target in absolute coordinates + */ +void __attribute__((weak)) kinematics_apply_transform(float *axis) +{ +} + +/** + * @brief Aplies a reverse transformation to the position returned from the planner. + * This is aplied only on normal and jog moves. Homing motions go directly to planner. + * + * @param axis Target in absolute coordinates + */ +void __attribute__((weak)) kinematics_apply_reverse_transform(float *axis) +{ +} + +/** + * @brief Converts from machine absolute coordinates to step position. + * This calls kinematics_apply_inverse after applying any custom geometry transformation (like skew compensation) + * + * @param axis Position in world coordinates + * @param steps Position in steps + */ + +void kinematics_coordinates_to_steps(float *axis, int32_t *steps) +{ + // make an axis copy to preven unintended target modifications + float axis_copy[AXIS_COUNT]; + memcpy(axis_copy, axis, sizeof(axis_copy)); + // In homing mode no kinematics modifications is applied to prevent unwanted axis movements + if (!cnc_get_exec_state(EXEC_HOMING)) + { + kinematics_apply_transform(axis_copy); + +#ifdef ENABLE_SKEW_COMPENSATION + // apply correction skew factors that compensate for machine axis alignemnt + axis_copy[AXIS_X] -= axis_copy[AXIS_Y] * g_settings.skew_xy_factor; +#ifndef SKEW_COMPENSATION_XY_ONLY + axis_copy[AXIS_X] -= axis_copy[AXIS_Z] * (g_settings.skew_xy_factor - g_settings.skew_xz_factor * g_settings.skew_yz_factor); + axis_copy[AXIS_Y] -= axis_copy[AXIS_Z] * g_settings.skew_yz_factor; +#endif +#endif + } + + kinematics_apply_inverse(axis_copy, steps); +} + +/** + * @brief Converts from step position to machine absolute coordinates. + * This calls kinematics_apply_forward and then recomputes any custom geometry transformation inversion (like skew compensation) + * + * @param steps Position in steps + * @param axis Position in world coordinates + */ +void kinematics_steps_to_coordinates(int32_t *steps, float *axis) +{ + kinematics_apply_forward(steps, axis); + + // In homing mode no kinematics modifications is applied to prevent unwanted axis movements + if (!cnc_get_exec_state(EXEC_HOMING)) + { + // perform unskew of the coordinates +#ifdef ENABLE_SKEW_COMPENSATION + axis[AXIS_X] += axis[AXIS_Y] * g_settings.skew_xy_factor; +#ifndef SKEW_COMPENSATION_XY_ONLY + axis[AXIS_X] += axis[AXIS_Z] * g_settings.skew_xz_factor; + axis[AXIS_Y] += axis[AXIS_Z] * g_settings.skew_yz_factor; +#endif +#endif + + // reverse all transformation in order + kinematics_apply_reverse_transform(axis); + } +} + +// /** +// * @brief Checks the motion software limits +// * This internally calls kinematics_check_boundaries after applying machine transformations +// * This ensure that in a transformation makes an axis travell past it's limits +// * +// * @param axis Target in absolute coordinates +// * @return true If inside boundries +// * @return false If outside boundries +// */ +// bool kinematics_check_softlimits(float *axis) +// { +// // make an axis copy to preven unintended target modifications +// float axis_copy[AXIS_COUNT]; +// memcpy(axis_copy, axis, sizeof(axis_copy)); +// // In homing mode no kinematics modifications is applied to prevent unwanted axis movements +// if (!cnc_get_exec_state(EXEC_HOMING)) +// { +// kinematics_apply_transform(axis_copy); + +// #ifdef ENABLE_SKEW_COMPENSATION +// // apply correction skew factors that compensate for machine axis alignemnt +// axis_copy[AXIS_X] -= axis_copy[AXIS_Y] * g_settings.skew_xy_factor; +// #ifndef SKEW_COMPENSATION_XY_ONLY +// axis_copy[AXIS_X] -= axis_copy[AXIS_Z] * (g_settings.skew_xy_factor - g_settings.skew_xz_factor * g_settings.skew_yz_factor); +// axis_copy[AXIS_Y] -= axis_copy[AXIS_Z] * g_settings.skew_yz_factor; +// #endif +// #endif +// } + +// return kinematics_check_boundaries(axis_copy); +// } \ No newline at end of file diff --git a/uCNC/src/hal/kinematics/kinematic.h b/uCNC/src/hal/kinematics/kinematic.h index e0eb82922..cf9b19ddd 100644 --- a/uCNC/src/hal/kinematics/kinematic.h +++ b/uCNC/src/hal/kinematics/kinematic.h @@ -90,6 +90,25 @@ extern "C" */ void kinematics_apply_reverse_transform(float *axis); + /** + * @brief Converts from machine absolute coordinates to step position. + * This calls kinematics_apply_inverse after applying any custom geometry transformation (like skew compensation) + * + * @param axis Position in world coordinates + * @param steps Position in steps + */ + + void kinematics_coordinates_to_steps(float *axis, int32_t *steps); + + /** + * @brief Converts from step position to machine absolute coordinates. + * This calls kinematics_apply_forward and then recomputes any custom geometry transformation inversion (like skew compensation) + * + * @param steps Position in steps + * @param axis Position in world coordinates + */ + void kinematics_steps_to_coordinates(int32_t *steps, float *axis); + /** * @brief Checks if the desired target is inside sofware boundries * @@ -99,6 +118,17 @@ extern "C" */ bool kinematics_check_boundaries(float *axis); + // /** + // * @brief Checks the motion software limits + // * This internally calls kinematics_check_boundaries after applying machine transformations + // * This ensure that in a transformation makes an axis travell past it's limits + // * + // * @param axis Target in absolute coordinates + // * @return true If inside boundries + // * @return false If outside boundries + // */ + // bool kinematics_check_softlimits(float *axis); + #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/kinematics/kinematic_cartesian.c b/uCNC/src/hal/kinematics/kinematic_cartesian.c index 7e340382d..d68a92bc8 100644 --- a/uCNC/src/hal/kinematics/kinematic_cartesian.c +++ b/uCNC/src/hal/kinematics/kinematic_cartesian.c @@ -139,37 +139,6 @@ uint8_t kinematics_home(void) return STATUS_OK; } -void kinematics_apply_transform(float *axis) -{ - /* - Define your custom transform -*/ -#ifdef ENABLE_SKEW_COMPENSATION - // apply correction skew factors that compensate for machine axis alignemnt - axis[AXIS_X] -= axis[AXIS_Y] * g_settings.skew_xy_factor; -#ifndef SKEW_COMPENSATION_XY_ONLY - axis[AXIS_X] -= axis[AXIS_Z] * (g_settings.skew_xy_factor - g_settings.skew_xz_factor * g_settings.skew_yz_factor); - axis[AXIS_Y] -= axis[AXIS_Z] * g_settings.skew_yz_factor; -#endif -#endif -} - -void kinematics_apply_reverse_transform(float *axis) -{ - /* - Define your custom transform inverse operation -*/ - - // perform unskew of the coordinates -#ifdef ENABLE_SKEW_COMPENSATION - axis[AXIS_X] += axis[AXIS_Y] * g_settings.skew_xy_factor; -#ifndef SKEW_COMPENSATION_XY_ONLY - axis[AXIS_X] += axis[AXIS_Z] * g_settings.skew_xz_factor; - axis[AXIS_Y] += axis[AXIS_Z] * g_settings.skew_yz_factor; -#endif -#endif -} - bool kinematics_check_boundaries(float *axis) { if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) diff --git a/uCNC/src/hal/kinematics/kinematic_corexy.c b/uCNC/src/hal/kinematics/kinematic_corexy.c index 5e308a570..55d01d49b 100644 --- a/uCNC/src/hal/kinematics/kinematic_corexy.c +++ b/uCNC/src/hal/kinematics/kinematic_corexy.c @@ -150,20 +150,6 @@ uint8_t kinematics_home(void) return STATUS_OK; } -void kinematics_apply_transform(float *axis) -{ - /* - Define your custom transform - */ -} - -void kinematics_apply_reverse_transform(float *axis) -{ - /* - Define your custom transform inverse operation - */ -} - bool kinematics_check_boundaries(float *axis) { if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) diff --git a/uCNC/src/hal/kinematics/kinematic_delta.c b/uCNC/src/hal/kinematics/kinematic_delta.c index f33261d6f..973e5e5bf 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_delta.c @@ -407,14 +407,6 @@ uint8_t kinematics_home(void) return STATUS_OK; } -void kinematics_apply_transform(float *axis) -{ -} - -void kinematics_apply_reverse_transform(float *axis) -{ -} - bool kinematics_check_boundaries(float *axis) { if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) diff --git a/uCNC/src/hal/kinematics/kinematic_delta.h b/uCNC/src/hal/kinematics/kinematic_delta.h index 1b3abe316..7034e5fc6 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.h +++ b/uCNC/src/hal/kinematics/kinematic_delta.h @@ -42,12 +42,6 @@ extern "C" #define KINEMATICS_MOTION_SEGMENT_SIZE 1.0f #endif - - /* - Enable Skew compensation -*/ - //#define ENABLE_SKEW_COMPENSATION - #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.c b/uCNC/src/hal/kinematics/kinematic_linear_delta.c index 48f52ef86..11c8588b0 100644 --- a/uCNC/src/hal/kinematics/kinematic_linear_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.c @@ -210,14 +210,6 @@ uint8_t kinematics_home(void) return STATUS_OK; } -void kinematics_apply_transform(float *axis) -{ -} - -void kinematics_apply_reverse_transform(float *axis) -{ -} - bool kinematics_check_boundaries(float *axis) { if (!g_settings.soft_limits_enabled || cnc_get_exec_state(EXEC_HOMING)) diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.h b/uCNC/src/hal/kinematics/kinematic_linear_delta.h index 27f1a2a95..f475e9df4 100644 --- a/uCNC/src/hal/kinematics/kinematic_linear_delta.h +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.h @@ -62,11 +62,6 @@ extern "C" #define DELTA_ARM_MAX_ANGLE 89 #endif - /* - Enable Skew compensation -*/ - //#define ENABLE_SKEW_COMPENSATION - #ifdef __cplusplus } #endif diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index bf22c0586..a8ee8e009 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -205,8 +205,7 @@ void protocol_send_status(void) int32_t steppos[AXIS_TO_STEPPERS]; itp_get_rt_position(steppos); - kinematics_apply_forward(steppos, axis); - kinematics_apply_reverse_transform(axis); + kinematics_steps_to_coordinates(steppos, axis); float feed = itp_get_rt_feed(); // convert from mm/s to mm/m #if TOOL_COUNT > 0 uint16_t spindle = tool_get_speed(); diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 125fb5909..9674b3a05 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -136,7 +136,7 @@ DECL_MODULE(system_menu) DECL_MENU_GOTO(2, goaxis, STR_AXIS, CONST_VARG(4)); #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU_GOTO(2, goaxis, STR_KINEMATICS, CONST_VARG(5)); + DECL_MENU_GOTO(2, kinemats, STR_KINEMATICS, CONST_VARG(5)); #endif DECL_MENU(6, 2, STR_IO_CONFIG); @@ -1128,8 +1128,7 @@ static void system_menu_render_axis_position(uint8_t render_flags, system_menu_i float axis[MAX(AXIS_COUNT, 3)]; int32_t steppos[STEPPER_COUNT]; itp_get_rt_position(steppos); - kinematics_apply_forward(steppos, axis); - kinematics_apply_reverse_transform(axis); + kinematics_steps_to_coordinates(steppos, axis); // X = 0 char axis_letter = *((char *)item->action_arg); uint8_t axis_index = (axis_letter >= 'X') ? (axis_letter - 'X') : (3 + axis_letter - 'A'); From fa4839b0c2e1eb5049724d971e96c53ec7b23dc0 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 9 Aug 2023 17:05:26 +0100 Subject: [PATCH 085/168] allow software homing --- uCNC/cnc_config.h | 11 +++++++++++ uCNC/src/core/motion_control.c | 9 +++++++++ uCNC/src/interface/grbl_interface.h | 1 + 3 files changed, 21 insertions(+) diff --git a/uCNC/cnc_config.h b/uCNC/cnc_config.h index 86100348e..0ea2693b9 100644 --- a/uCNC/cnc_config.h +++ b/uCNC/cnc_config.h @@ -350,6 +350,17 @@ extern "C" // #define SET_ORIGIN_AT_HOME_POS + /** + * + * Enable this option to allow the $H to be used to perform a software homing. + * Software homing will only work if hardware limits are disabled. + * This will apply the not execute the homing search motions but it will still + * execute the pull-off motion before reset the coordinate system + * + * */ + + // #define ALLOW_SOFTWARE_HOMING + /** * If the type of machine supports skew and needs skew correction * (defined in the specified kinematics_xxx.h file) diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index cf002b80a..dd31d995b 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -719,6 +719,15 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) homing_status.status = STATUS_CRITICAL_FAIL; #endif + if (!g_settings.hard_limits_enabled) + { +#ifdef ALLOW_SOFTWARE_HOMING + return STATUS_OK; +#else + return STATUS_HARDLIMITS_DISABLED; +#endif + } + // locks limits to accept axis limit mask only or else throw error io_lock_limits(axis_limit); io_invert_limits(0); diff --git a/uCNC/src/interface/grbl_interface.h b/uCNC/src/interface/grbl_interface.h index 1ce26940b..80d5e87bc 100644 --- a/uCNC/src/interface/grbl_interface.h +++ b/uCNC/src/interface/grbl_interface.h @@ -105,6 +105,7 @@ extern "C" #define STATUS_LASER_PPI_MODE_DISABLED 54 #define STATUS_TOOL_FAILURE 55 #define STATUS_INVALID_PLANE_SELECTED 56 +#define STATUS_HARDLIMITS_DISABLED 57 #define STATUS_GCODE_EXTENDED_UNSUPPORTED 254 // deprecated #define STATUS_CRITICAL_FAIL 255 From 152f1f5627cc4dc57118fdd7d4c4de017d48e00e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 10 Aug 2023 17:55:05 +0100 Subject: [PATCH 086/168] new multi axis config - new multi axis config - new autolevel with multi axis config --- uCNC/cnc_hal_config.h | 140 +++++++- uCNC/src/cnc.h | 60 ++-- uCNC/src/cnc_hal_config_helper.h | 337 +++++------------- uCNC/src/core/interpolator.c | 114 +++--- uCNC/src/core/interpolator.h | 2 - uCNC/src/core/io_control.c | 191 +++------- uCNC/src/core/io_control.h | 1 - uCNC/src/hal/kinematics/kinematic_cartesian.c | 12 +- uCNC/src/hal/kinematics/kinematic_corexy.c | 12 +- uCNC/src/hal/kinematics/kinematic_delta.c | 6 +- .../hal/kinematics/kinematic_linear_delta.c | 6 +- uCNC/src/interface/protocol.c | 12 +- 12 files changed, 388 insertions(+), 505 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index c69b503a7..5ae152506 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -93,25 +93,133 @@ extern "C" // #define DISABLE_C_HOMING /** - * Uncomment this feature to enable up to 2 dual drive axis + * Uncomment this feature to enable multi motor axis * NOTE: If Laser PPI is enabled one of the stepper drivers position will be used by the laser controller * Usually that is STEPPER so if AXIS_COUNT=3, STEPPER3 will be used by laser PPI */ -// #define ENABLE_DUAL_DRIVE_AXIS -#ifdef ENABLE_DUAL_DRIVE_AXIS -// defines the first dual drive capable axis -// #define DUAL_DRIVE0_AXIS X -// by default this will be rewired to STEPPER6 (if available on the board) -// this can be uncommented to re-wire to an available (unused stepper other then 6) -// #define DUAL_DRIVE0_STEPPER 6 -// #define DUAL_DRIVE0_ENABLE_SELFSQUARING - -// defines the first second drive capable axis -// #define DUAL_DRIVE1_AXIS Y -// by default this will be rewired to STEPPER7 (if available on the board) -// this can be uncommented to re-wire to an available (unused stepper other then 7) -// #define DUAL_DRIVE1_STEPPER 7 -// #define DUAL_DRIVE1_ENABLE_SELFSQUARING +#define ENABLE_MULTI_STEPPER_AXIS +#ifdef ENABLE_MULTI_STEPPER_AXIS + +/** + * Configure each multi motor linear actuator. + * + * AXIS are the motion degrees of freedom of the machine in 3D space + * STEP are the stepper controller drivers that are controlled by the the board + * LINACT are the linear actuators that drive the machine motion. You can think of linear actuator as a combination of linear guide + motor + * + * Each AXIS is logically attached to a LINACT. + * AXIS_X <-> LINACT0 + * AXIS_Y <-> LINACT1 + * etc.. + * + * In some machines the coorelation between AXIS and LINACT is direct. For example cartesian machines the AXIS X motion is the result of motions of the LINACT0, AXIS Y of LINACT1, AXIS Z of LINACT2, etc. + * On Core XY kinematics the same logic as the cartesian is applied (regarding AXIS and LINACT logic) although, AXIS X and Y motions are a combination of motions of both LINACT0 and LINAXCT1. + * On Delta type machines the same logic as the cartesian is applied (regarding AXIS and LINACT logic) although, AXIS X, Y and Z are all a combination of motions of LINACT0, 1 and 2. + * + * As stated earlier LINACT is a combination of linear guide + motor. Usually a LINACT is defined as a single stepper motor. + * But it can also be composed of multiple stepper motors (2, 3, 4, etc...) + * + * To enable this just define the LINACTx_IO_MASK as a combination of STEPx_IO_MASK's + * **/ + +// defines a multi stepper linear actuator LINACT0 + #define LINACT0_IO_MASK (STEP0_IO_MASK | STEP5_IO_MASK) + +// defines a second multi stepper linear actuator LINACT1 + #define LINACT1_IO_MASK (STEP1_IO_MASK | STEP6_IO_MASK) + +// defines a second multi stepper linear actuator LINACT2 + #define LINACT2_IO_MASK (STEP2_IO_MASK | STEP7_IO_MASK) + +// there is no limit to the ammount of STEP IO that can be combined into a LINACT. For example it's possible to assign 4 independent STEP IO to a single LINACT +// #define LINACT2_IO_MASK (STEP2_IO_MASK | STEP5_IO_MASK | STEP6_IO_MASK | STEP7_IO_MASK) + +/** + * SELF SQUARING/AUTOLEVEL AXIS + * Limits switches have a mask value that is equivalent to the STEPx that it controls. + * + * By default these mask values match the corresponding AXIS, LINACT, STEP, etc... + * + * STEPx 7 6 5 4 3 2 1 0 + * STEPx_IO_MASK 128 64 32 16 8 4 2 1 + * AXISx - - C B C Z Y X + * LINACTx - - 5 4 3 2 1 0 + * LIMITx - - C B A Z&Z2 Y&Y2 X&X2 + * + * LINACT with multiple STEP IO pulse all those IO in sync, but when homing it can stop independently as it hits the correspondent limit until all motors reach the desired home position. + * To achieve that each each LIMITx_IO_MASK should be set to the corresponding STEP that it controls + * + * For example to use STEP0 and STEP6 to drive the AXIS_X/LINACT0 you need to configure the correct LINACT0_IO_MASK and then to make LIMIT_X stop STEP0 and LIMIT_X2 stop STEP6 you need + * to reassing LIMIT_X2 to STEP6 like this + * + * #define LIMIT_X2_IO_MASK STEP6_IO_MASK + * + * **/ + + #define ENABLE_X_AUTOLEVEL +#ifdef ENABLE_X_AUTOLEVEL +#define LIMIT_X2_IO_MASK STEP5_IO_MASK +#endif + + #define ENABLE_Y_AUTOLEVEL +#ifdef ENABLE_Y_AUTOLEVEL +#define LIMIT_Y2_IO_MASK STEP6_IO_MASK +#endif + + #define ENABLE_Z_AUTOLEVEL +#ifdef ENABLE_Z_AUTOLEVEL +#define LIMIT_Z2_IO_MASK STEP7_IO_MASK +#endif + +/** + * Advanced Multi-axis + * The advantage of using this mask scheme is that it's possible to defined advanced custom self squaring/planning rigs + * and complete reassing of unused axis limits to perform the task + * + * Let's assume a custom cartesian machine that has 3 axis with 5 motors and 5 limit switches with the following configuration + * + * Axis X - 1 motor/limit + * Axis Y - 2 motors/limits (self squaring) + * Axis Z - 3 motors/limits (self leveling - 3 point plane) + * + * By default, with the machine configured for a 3 axis machine 3 linear actuators are configured with one motor each. By default AXIS_X -> LINACT0 -> STEP0, AXIS_Y-> LINACT1 -> STEP1, etc... + * One possibility would be to map the connections (from STEP0 to STEP5) as X,Y,Z,Y2,Z2,Z3. + * + * Let's assume the user also wants the connections to be made in the order X,Y,Y2,Z,Z2,Z3 + * + * + * Axis X does not require any special configuration. Uses the default settings for a single linear actuator with one motor and a limit switch + * Axis Y requires a second STEPx output. Because we also want to reorder the connection we must define our custom LINACTx for the remaining axis like this + * + * // defines a custom LINACT1_IO_MASK to use STP1 and STEP2 + * #define LINACT1_IO_MASK (STEP1_IO_MASK | STEP2_IO_MASK) + * // defines a custom LINACT1_IO_MASK to use STP3, STEP4 and STEP5 + * #define LINACT2_IO_MASK (STEP3_IO_MASK | STEP4_IO_MASK | STEP5_IO_MASK) + * + * Then let's configure the limits: + * + * Limits for AXIS X does not require any special configuration. Uses the default settings for a single linear actuator with one motor and a limit switch (uses LIMIT_X) + * Limits for AXIS Y only require Limit Y2 to be reasigned to match STEP2 so in this case + * + * #define ENABLE_Y_AUTOLEVEL + * #define LIMIT_Y2_IO_MASK STEP2_IO_MASK + * + * And finally limits for AXIS Z will new to be reassined to the matching STEPx. We will also need a 3rd limit. We will use LIMIT_A since AXIS_A is not used. + * + * // enable Z selfsquare/selfplane + * #define ENABLE_Z_AUTOLEVEL + * #define LIMIT_Y_IO_MASK STEP3_IO_MASK + * #define LIMIT_Y2_IO_MASK STEP4_IO_MASK + * #define LIMIT_A_IO_MASK STEP5_IO_MASK + * + * There is still a final step that involve reassing LINACT2 limits to include the extra limit (LIMIT A) like this + * + * #define LINACT2_LIMIT_MASK (LIMIT_Y_IO_MASK | LIMIT_Y2_IO_MASK | LIMIT_A_IO_MASK) + * + * That is it. + * + * **/ + #endif /* diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index 6a88fd33a..06377d697 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -93,35 +93,37 @@ extern "C" #define FHOLD_MASK 4 #define CS_RES_MASK 8 -#define CONTROLS_MASK (ESTOP_MASK | FHOLD_MASK | CS_RES_MASK | SAFETY_DOOR_MASK) - -#define LIMIT_X_MASK 1 -#define LIMIT_Y_MASK 2 -#define LIMIT_Z_MASK 4 -#define LIMIT_A_MASK 8 -#define LIMIT_B_MASK 16 -#define LIMIT_C_MASK 32 - -#define LIMITS_MASK (LIMIT_X_MASK | LIMIT_Y_MASK | LIMIT_Z_MASK | LIMIT_A_MASK | LIMIT_B_MASK | LIMIT_C_MASK) -#define LIMITS_DELTA_MASK (LIMIT_X_MASK | LIMIT_Y_MASK | LIMIT_Z_MASK) - -#define STEP0_MASK 1 -#define STEP1_MASK 2 -#define STEP2_MASK 4 -#define STEP3_MASK 8 -#define STEP4_MASK 16 -#define STEP5_MASK 32 -#define STEP6_MASK 64 -#define STEP7_MASK 128 - -#define DIR0_MASK 1 -#define DIR1_MASK 2 -#define DIR2_MASK 4 -#define DIR3_MASK 8 -#define DIR4_MASK 16 -#define DIR5_MASK 32 -#define DIR6_MASK 64 -#define DIR7_MASK 128 +// basic step and dir IO masks +// STEPS DIRS and LIMITS can be combined to form MULTI AXIS/LIMITS combinations +/** + * Basic step and dir IO masks + * STEPS DIRS and LIMITS can be combined to form MULTI AXIS/LIMITS combinations + * + * Usually (depends on the kinematic) STEP0 is assigned to AXIS X, STEP1 is assigned to AXIS Y, etc.. + * But STEP0 can be formed by multiple STEPPERS (for example STEPPER0, STEPPER5, STEPPER6 and STEPPER7) + * + * STEP0_MASK can then be formed by a combinations of stepper IO masks like this + * + * #define STEP0_MASK (STEPPER0_IO_MASK | STEPPER5_IO_MASK | STEPPER6_IO_MASK | STEPPER7_IO_MASK) + * + * For auto-squaring LIMITS should also match this STEPx mask by merging all combined limits to form a multi-switch limit + * **/ +#define STEP_UNDEF_IO_MASK 0 +#define STEP0_IO_MASK 1 +#define STEP1_IO_MASK 2 +#define STEP2_IO_MASK 4 +#define STEP3_IO_MASK 8 +#define STEP4_IO_MASK 16 +#define STEP5_IO_MASK 32 +#define STEP6_IO_MASK 64 +#define STEP7_IO_MASK 128 + +#define LINACT0_MASK 1 +#define LINACT1_MASK 2 +#define LINACT2_MASK 4 +#define LINACT3_MASK 8 +#define LINACT4_MASK 16 +#define LINACT5_MASK 32 #include "cnc_build.h" // make the needed includes (do not change the order) diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 35286a053..aeb8a2242 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -465,27 +465,27 @@ extern "C" #if (STEPPER_COUNT == 1) #undef STEPPER_COUNT #define STEPPER_COUNT 2 -#define LASER_PPI_MASK STEP1_MASK +#define LASER_PPI_MASK STEP1_IO_MASK #elif (STEPPER_COUNT == 2) #undef STEPPER_COUNT #define STEPPER_COUNT 3 -#define LASER_PPI_MASK STEP2_MASK +#define LASER_PPI_MASK STEP2_IO_MASK #elif (STEPPER_COUNT == 3) #undef STEPPER_COUNT #define STEPPER_COUNT 4 -#define LASER_PPI_MASK STEP3_MASK +#define LASER_PPI_MASK STEP3_IO_MASK #elif (STEPPER_COUNT == 4) #undef STEPPER_COUNT #define STEPPER_COUNT 5 -#define LASER_PPI_MASK STEP4_MASK +#define LASER_PPI_MASK STEP4_IO_MASK #elif (STEPPER_COUNT == 5) #undef STEPPER_COUNT #define STEPPER_COUNT 6 -#define LASER_PPI_MASK STEP5_MASK +#define LASER_PPI_MASK STEP5_IO_MASK #elif (STEPPER_COUNT == 6) #undef STEPPER_COUNT #define STEPPER_COUNT 7 -#define LASER_PPI_MASK STEP6_MASK +#define LASER_PPI_MASK STEP6_IO_MASK #endif #ifndef LASER_PPI #define LASER_PPI UNDEF_PIN @@ -498,237 +498,6 @@ extern "C" #define LASER_PPI UNDEF_PIN #endif -#define __stepname_helper__(x) STEP##x##_MASK -#define __stepname__(x) __stepname_helper__(x) - -#define __axisname_helper__(x) AXIS_##x -#define __axisname__(x) __axisname_helper__(x) - -#define __limitname_helper__(x) LIMIT_##x##_MASK -#define __limitname__(x) __limitname_helper__(x) - -#ifdef ENABLE_DUAL_DRIVE_AXIS - -#ifndef DUAL_DRIVE0_STEPPER -#define DUAL_DRIVE0_STEPPER 6 -#endif -#ifndef DUAL_DRIVE1_STEPPER -#define DUAL_DRIVE1_STEPPER 7 -#endif -#ifndef DUAL_DRIVE2_STEPPER -#define DUAL_DRIVE2_STEPPER 6 -#endif -#ifndef DUAL_DRIVE3_STEPPER -#define DUAL_DRIVE3_STEPPER 7 -#endif - -#if (!defined(DUAL_DRIVE0_AXIS) && !defined(DUAL_DRIVE1_AXIS) && !defined(DUAL_DRIVE2_AXIS) && !defined(DUAL_DRIVE3_AXIS)) -#error "Enabling dual axis drive requires to configure at least one axis with dual drive" -#endif - -#if (STEPPER_COUNT > 0 && (DUAL_DRIVE0_STEPPER == 0 || DUAL_DRIVE1_STEPPER == 0 || DUAL_DRIVE2_STEPPER == 0 || DUAL_DRIVE3_STEPPER == 0)) -#error "Stepper 0 cannot be used as a axis drive and a dual axis drive at the same time" -#endif -#if (STEPPER_COUNT > 1 && (DUAL_DRIVE0_STEPPER == 1 || DUAL_DRIVE1_STEPPER == 1 || DUAL_DRIVE2_STEPPER == 1 || DUAL_DRIVE3_STEPPER == 1)) -#error "Stepper 1 cannot be used as a axis drive and a dual axis drive at the same time" -#endif -#if (STEPPER_COUNT > 2 && (DUAL_DRIVE0_STEPPER == 2 || DUAL_DRIVE1_STEPPER == 2 || DUAL_DRIVE2_STEPPER == 2 || DUAL_DRIVE3_STEPPER == 2)) -#error "Stepper 2 cannot be used as a axis drive and a dual axis drive at the same time" -#endif -#if (STEPPER_COUNT > 3 && (DUAL_DRIVE0_STEPPER == 3 || DUAL_DRIVE1_STEPPER == 3 || DUAL_DRIVE2_STEPPER == 3 || DUAL_DRIVE3_STEPPER == 3)) -#error "Stepper 3 cannot be used as a axis drive and a dual axis drive at the same time" -#endif -#if (STEPPER_COUNT > 4 && (DUAL_DRIVE0_STEPPER == 4 || DUAL_DRIVE1_STEPPER == 4 || DUAL_DRIVE2_STEPPER == 4 || DUAL_DRIVE3_STEPPER == 4)) -#error "Stepper 4 cannot be used as a axis drive and a dual axis drive at the same time" -#endif -#if (STEPPER_COUNT > 5 && (DUAL_DRIVE0_STEPPER == 5 || DUAL_DRIVE1_STEPPER == 5 || DUAL_DRIVE2_STEPPER == 5 || DUAL_DRIVE3_STEPPER == 5)) -#error "Stepper 5 cannot be used as a axis drive and a dual axis drive at the same time" -#endif - -// dual axis0 -#ifdef DUAL_DRIVE0_AXIS -#define AXIS_DUAL0 __axisname__(DUAL_DRIVE0_AXIS) -#define STEP_DUAL0 (1 << AXIS_DUAL0) -#ifdef DUAL_DRIVE0_ENABLE_SELFSQUARING -#define LIMIT_DUAL0_MASK (1 << AXIS_DUAL0) -#endif -#define STEP_DUAL0_MASK (1 << DUAL_DRIVE0_STEPPER) -#endif - -// dual axis1 -#ifdef DUAL_DRIVE1_AXIS -#define AXIS_DUAL1 __axisname__(DUAL_DRIVE1_AXIS) -#define STEP_DUAL1 (1 << AXIS_DUAL1) -#ifdef DUAL_DRIVE1_ENABLE_SELFSQUARING -#define LIMIT_DUAL1_MASK (1 << AXIS_DUAL1) -#endif -#define STEP_DUAL1_MASK (1 << DUAL_DRIVE1_STEPPER) -#endif - -// axis2 and 3 are only replicating axis (no self-squaring) - -// dual axis2 -#ifdef DUAL_DRIVE2_AXIS -#define AXIS_DUAL2 __axisname__(DUAL_DRIVE2_AXIS) -#define STEP_DUAL2 (1 << AXIS_DUAL2) -#define STEP_DUAL2_MASK (1 << DUAL_DRIVE2_STEPPER) -#endif - -// dual axis3 -#ifdef DUAL_DRIVE3_AXIS -#define AXIS_DUAL3 __axisname__(DUAL_DRIVE3_AXIS) -#define STEP_DUAL3 (1 << AXIS_DUAL3) -#define STEP_DUAL3_MASK (1 << DUAL_DRIVE3_STEPPER) -#endif - -#endif - -#ifndef LIMIT_DUAL0_MASK -#define LIMIT_DUAL0_MASK 0 -#endif -#ifndef LIMIT_DUAL1_MASK -#define LIMIT_DUAL1_MASK 0 -#endif - -#define LIMITS_DUAL_MASK (LIMIT_DUAL0_MASK | LIMIT_DUAL1_MASK) - -#if (STEP0_MASK == STEP_DUAL0) -#define STEP0_ITP_MASK (STEP0_MASK | STEP_DUAL0_MASK) -#elif (STEP0_MASK == STEP_DUAL1) -#define STEP0_ITP_MASK (STEP0_MASK | STEP_DUAL1_MASK) -#elif (STEP0_MASK == STEP_DUAL2) -#define STEP0_ITP_MASK (STEP0_MASK | STEP_DUAL2_MASK) -#elif (STEP0_MASK == STEP_DUAL3) -#define STEP0_ITP_MASK (STEP0_MASK | STEP_DUAL3_MASK) -#else -#define STEP0_ITP_MASK STEP0_MASK -#endif -#if (STEP1_MASK == STEP_DUAL0) -#define STEP1_ITP_MASK (STEP1_MASK | STEP_DUAL0_MASK) -#elif (STEP1_MASK == STEP_DUAL1) -#define STEP1_ITP_MASK (STEP1_MASK | STEP_DUAL1_MASK) -#elif (STEP1_MASK == STEP_DUAL2) -#define STEP1_ITP_MASK (STEP1_MASK | STEP_DUAL2_MASK) -#elif (STEP1_MASK == STEP_DUAL3) -#define STEP1_ITP_MASK (STEP1_MASK | STEP_DUAL3_MASK) -#else -#define STEP1_ITP_MASK STEP1_MASK -#endif -#if (STEP2_MASK == STEP_DUAL0) -#define STEP2_ITP_MASK (STEP2_MASK | STEP_DUAL0_MASK) -#elif (STEP2_MASK == STEP_DUAL1) -#define STEP2_ITP_MASK (STEP2_MASK | STEP_DUAL1_MASK) -#elif (STEP2_MASK == STEP_DUAL2) -#define STEP2_ITP_MASK (STEP2_MASK | STEP_DUAL2_MASK) -#elif (STEP2_MASK == STEP_DUAL3) -#define STEP2_ITP_MASK (STEP2_MASK | STEP_DUAL3_MASK) -#else -#define STEP2_ITP_MASK STEP2_MASK -#endif -#if (STEP3_MASK == STEP_DUAL0) -#define STEP3_ITP_MASK (STEP3_MASK | STEP_DUAL0_MASK) -#elif (STEP3_MASK == STEP_DUAL1) -#define STEP3_ITP_MASK (STEP3_MASK | STEP_DUAL1_MASK) -#elif (STEP3_MASK == STEP_DUAL2) -#define STEP3_ITP_MASK (STEP3_MASK | STEP_DUAL2_MASK) -#elif (STEP3_MASK == STEP_DUAL3) -#define STEP3_ITP_MASK (STEP3_MASK | STEP_DUAL3_MASK) -#else -#define STEP3_ITP_MASK STEP3_MASK -#endif -#if (STEP5_MASK == STEP_DUAL0) -#define STEP5_ITP_MASK (STEP5_MASK | STEP_DUAL0_MASK) -#elif (STEP5_MASK == STEP_DUAL1) -#define STEP5_ITP_MASK (STEP5_MASK | STEP_DUAL1_MASK) -#elif (STEP5_MASK == STEP_DUAL2) -#define STEP5_ITP_MASK (STEP5_MASK | STEP_DUAL2_MASK) -#elif (STEP5_MASK == STEP_DUAL3) -#define STEP5_ITP_MASK (STEP5_MASK | STEP_DUAL3_MASK) -#else -#define STEP5_ITP_MASK STEP5_MASK -#endif - -#ifndef STEP_DUAL0 -#define STEP_DUAL0 -1 -#endif - -#ifndef STEP_DUAL1 -#define STEP_DUAL1 -1 -#endif - -#ifndef STEP_DUAL2 -#define STEP_DUAL2 -1 -#endif - -#ifndef STEP_DUAL3 -#define STEP_DUAL3 -1 -#endif - -#if (STEPPER_COUNT < 1 && DUAL_DRIVE0_STEPPER != 0 && DUAL_DRIVE1_STEPPER != 0 && DUAL_DRIVE2_STEPPER != 0 && DUAL_DRIVE3_STEPPER != 0) -#ifdef STEP0 -#undef STEP0 -#endif -#ifdef DIR0 -#undef DIR0 -#endif -#endif -#if (STEPPER_COUNT < 2 && DUAL_DRIVE0_STEPPER != 1 && DUAL_DRIVE1_STEPPER != 1 && DUAL_DRIVE2_STEPPER != 1 && DUAL_DRIVE3_STEPPER != 1) -#ifdef STEP1 -#undef STEP1 -#endif -#ifdef DIR1 -#undef DIR1 -#endif -#endif -#if (STEPPER_COUNT < 3 && DUAL_DRIVE0_STEPPER != 2 && DUAL_DRIVE1_STEPPER != 2 && DUAL_DRIVE2_STEPPER != 2 && DUAL_DRIVE3_STEPPER != 2) -#ifdef STEP2 -#undef STEP2 -#endif -#ifdef DIR2 -#undef DIR2 -#endif -#endif -#if (STEPPER_COUNT < 4 && DUAL_DRIVE0_STEPPER != 3 && DUAL_DRIVE1_STEPPER != 3 && DUAL_DRIVE2_STEPPER != 3 && DUAL_DRIVE3_STEPPER != 3) -#ifdef STEP3 -#undef STEP3 -#endif -#ifdef DIR3 -#undef DIR3 -#endif -#endif -#if (STEPPER_COUNT < 5 && DUAL_DRIVE0_STEPPER != 4 && DUAL_DRIVE1_STEPPER != 4 && DUAL_DRIVE2_STEPPER != 4 && DUAL_DRIVE3_STEPPER != 4) -#ifdef STEP4 -#undef STEP4 -#endif -#ifdef DIR4 -#undef DIR4 -#endif -#endif -#if (STEPPER_COUNT < 6 && DUAL_DRIVE0_STEPPER != 5 && DUAL_DRIVE1_STEPPER != 5 && DUAL_DRIVE2_STEPPER != 5 && DUAL_DRIVE3_STEPPER != 5) -#ifdef STEP5 -#undef STEP5 -#endif -#ifdef DIR5 -#undef DIR5 -#endif -#endif -#if (DUAL_DRIVE0_STEPPER != 6 && DUAL_DRIVE1_STEPPER != 6 && DUAL_DRIVE2_STEPPER != 6 && DUAL_DRIVE3_STEPPER != 6) -#ifdef STEP6 -#undef STEP6 -#endif -#ifdef DIR6 -#undef DIR6 -#endif -#endif -#if (DUAL_DRIVE0_STEPPER != 7 && DUAL_DRIVE1_STEPPER != 7 && DUAL_DRIVE2_STEPPER != 7 && DUAL_DRIVE3_STEPPER != 7) -#ifdef STEP7 -#undef STEP7 -#endif -#ifdef DIR7 -#undef DIR7 -#endif -#endif - /** * final pin cleaning and configuration **/ @@ -1800,7 +1569,99 @@ extern "C" #define DIO211 UNDEF_PIN #endif - // if the pins are undefined turn on option +// set default limits and step associations +#if ASSERT_PIN(LIMIT_X) && !defined(LIMIT_X_IO_MASK) +#define LIMIT_X_IO_MASK STEP0_IO_MASK +#elif !defined(LIMIT_X_IO_MASK) +#define LIMIT_X_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_Y) && !defined(LIMIT_Y_IO_MASK) +#define LIMIT_Y_IO_MASK STEP1_IO_MASK +#elif !defined(LIMIT_Y_IO_MASK) +#define LIMIT_Y_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_Z) && !defined(LIMIT_Z_IO_MASK) +#define LIMIT_Z_IO_MASK STEP2_IO_MASK +#elif !defined(LIMIT_Z_IO_MASK) +#define LIMIT_Z_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_A) && !defined(LIMIT_A_IO_MASK) +#define LIMIT_A_IO_MASK STEP3_IO_MASK +#elif !defined(LIMIT_A_IO_MASK) +#define LIMIT_A_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_B) && !defined(LIMIT_B_IO_MASK) +#define LIMIT_B_IO_MASK STEP4_IO_MASK +#elif !defined(LIMIT_B_IO_MASK) +#define LIMIT_B_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_C) && !defined(LIMIT_C_IO_MASK) +#define LIMIT_C_IO_MASK STEP5_IO_MASK +#elif !defined(LIMIT_C_IO_MASK) +#define LIMIT_C_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_X2) && !defined(LIMIT_X2_IO_MASK) +#define LIMIT_X2_IO_MASK STEP0_IO_MASK +#elif !defined(LIMIT_X2_IO_MASK) +#define LIMIT_X2_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_Y2) && !defined(LIMIT_Y2_IO_MASK) +#define LIMIT_Y2_IO_MASK STEP1_IO_MASK +#elif !defined(LIMIT_Y2_IO_MASK) +#define LIMIT_Y2_IO_MASK STEP_UNDEF_IO_MASK +#endif +#if ASSERT_PIN(LIMIT_Z2) && !defined(LIMIT_Z2_IO_MASK) +#define LIMIT_Z2_IO_MASK STEP2_IO_MASK +#elif !defined(LIMIT_Z2_IO_MASK) +#define LIMIT_Z2_IO_MASK STEP_UNDEF_IO_MASK +#endif + +// linear actuator and step associations +#ifndef LINACT0_IO_MASK +#define LINACT0_IO_MASK STEP0_IO_MASK +#endif +#ifndef LINACT1_IO_MASK +#define LINACT1_IO_MASK STEP1_IO_MASK +#endif +#ifndef LINACT2_IO_MASK +#define LINACT2_IO_MASK STEP2_IO_MASK +#endif +#ifndef LINACT3_IO_MASK +#define LINACT3_IO_MASK STEP3_IO_MASK +#endif +#ifndef LINACT4_IO_MASK +#define LINACT4_IO_MASK STEP4_IO_MASK +#endif +#ifndef LINACT5_IO_MASK +#define LINACT5_IO_MASK STEP5_IO_MASK +#endif + +// linear actuator limits and limits association +#ifndef LINACT0_LIMIT_MASK +#define LINACT0_LIMIT_MASK (LIMIT_X_IO_MASK | LIMIT_X2_IO_MASK) +#endif +#ifndef LINACT1_LIMIT_MASK +#define LINACT1_LIMIT_MASK (LIMIT_Y_IO_MASK | LIMIT_Y2_IO_MASK) +#endif +#ifndef LINACT2_LIMIT_MASK +#define LINACT2_LIMIT_MASK (LIMIT_Z_IO_MASK | LIMIT_Z2_IO_MASK) +#endif +#ifndef LINACT3_LIMIT_MASK +#define LINACT3_LIMIT_MASK (LIMIT_A_IO_MASK) +#endif +#ifndef LINACT4_LIMIT_MASK +#define LINACT4_LIMIT_MASK (LIMIT_B_IO_MASK) +#endif +#ifndef LINACT5_LIMIT_MASK +#define LINACT5_LIMIT_MASK (LIMIT_C_IO_MASK) +#endif + +#define LIMITS_MASK (LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK | LINACT2_LIMIT_MASK | LINACT3_LIMIT_MASK | LINACT4_LIMIT_MASK | LINACT5_LIMIT_MASK) +#define LIMITS_DELTA_MASK (LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK | LINACT2_LIMIT_MASK) + +// if the pins are undefined turn on option +#define CONTROLS_MASK (ESTOP_MASK | FHOLD_MASK | CS_RES_MASK | SAFETY_DOOR_MASK) + #if (!ASSERT_PIN(ESTOP) && !ASSERT_PIN(SAFETY_DOOR) && !ASSERT_PIN(FHOLD) && !ASSERT_PIN(CS_RES) && !defined(DISABLE_ALL_CONTROLS)) #define DISABLE_ALL_CONTROLS #endif diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index eb67fff1c..0eaf12f06 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -61,9 +61,7 @@ static uint8_t prev_dss; static int16_t prev_spindle; // pointer to the segment being executed static itp_segment_t *itp_rt_sgm; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) static volatile uint8_t itp_step_lock; -#endif #ifdef ENABLE_RT_SYNC_MOTIONS // deprecated with new hooks @@ -208,9 +206,7 @@ void itp_init(void) memset(itp_blk_data, 0, sizeof(itp_blk_data)); memset(itp_sgm_data, 0, sizeof(itp_sgm_data)); itp_rt_sgm = NULL; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) itp_step_lock = 0; -#endif #endif itp_cur_plan_block = NULL; itp_needs_update = false; @@ -308,6 +304,27 @@ static float s_curve_function(float pt) } #endif +FORCEINLINE static uint8_t itp_get_linact_dirs(uint8_t mask) +{ + switch (mask) + { + case 1: + return LINACT0_IO_MASK; + case 2: + return LINACT1_IO_MASK; + case 4: + return LINACT2_IO_MASK; + case 8: + return LINACT3_IO_MASK; + case 16: + return LINACT4_IO_MASK; + case 32: + return LINACT5_IO_MASK; + } + + return 0; +} + void itp_run(void) { // conversion vars @@ -363,21 +380,9 @@ void itp_run(void) #ifdef ENABLE_BACKLASH_COMPENSATION itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->planner_flags.bit.backlash_comp; #endif - itp_blk_data[itp_blk_data_write].dirbits = itp_cur_plan_block->dirbits; -#ifdef ENABLE_DUAL_DRIVE_AXIS -#ifdef DUAL_DRIVE0_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL0) ? STEP_DUAL0_MASK : 0; -#endif -#ifdef DUAL_DRIVE1_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL1) ? STEP_DUAL1_MASK : 0; -#endif -#ifdef DUAL_DRIVE2_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL2) ? STEP_DUAL2_MASK : 0; -#endif -#ifdef DUAL_DRIVE3_AXIS - itp_blk_data[itp_blk_data_write].dirbits |= CHECKFLAG(itp_blk_data[itp_blk_data_write].dirbits, STEP_DUAL3) ? STEP_DUAL3_MASK : 0; -#endif -#endif + + // reset dirbits + itp_blk_data[itp_blk_data_write].dirbits = 0; step_t total_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; itp_blk_data[itp_blk_data_write].total_steps = total_steps << 1; @@ -391,12 +396,15 @@ void itp_run(void) #endif for (uint8_t i = 0; i < STEPPER_COUNT; i++) { + uint8_t mask = (1 << i); + // convert from motion block direction bits to LINACT bit mask + itp_blk_data[itp_blk_data_write].dirbits |= itp_get_linact_dirs(itp_cur_plan_block->dirbits & mask); itp_blk_data[itp_blk_data_write].errors[i] = total_steps; itp_blk_data[itp_blk_data_write].steps[i] = itp_cur_plan_block->steps[i] << 1; #ifdef STEP_ISR_SKIP_IDLE if (!itp_cur_plan_block->steps[i]) { - itp_blk_data[itp_blk_data_write].idle_axis |= (1 << i); + itp_blk_data[itp_blk_data_write].idle_axis |= mask; } #endif } @@ -844,12 +852,10 @@ void itp_sync_spindle(void) #endif } -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) void itp_lock_stepper(uint8_t lockmask) { itp_step_lock = lockmask; } -#endif #ifdef GCODE_PROCESS_LINE_NUMBERS uint32_t itp_get_rt_line_number(void) @@ -1022,20 +1028,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 0) { - new_stepbits |= STEP0_ITP_MASK; + new_stepbits |= LINACT0_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP0_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 0))) { #endif itp_rt_sgm->block->errors[0] += itp_rt_sgm->block->steps[0]; if (itp_rt_sgm->block->errors[0] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[0] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP0_ITP_MASK; + new_stepbits |= LINACT0_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1048,20 +1054,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 1) { - new_stepbits |= STEP1_ITP_MASK; + new_stepbits |= LINACT1_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP1_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 1))) { #endif itp_rt_sgm->block->errors[1] += itp_rt_sgm->block->steps[1]; if (itp_rt_sgm->block->errors[1] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[1] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP1_ITP_MASK; + new_stepbits |= LINACT1_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1074,20 +1080,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 2) { - new_stepbits |= STEP2_ITP_MASK; + new_stepbits |= LINACT2_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP2_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 2))) { #endif itp_rt_sgm->block->errors[2] += itp_rt_sgm->block->steps[2]; if (itp_rt_sgm->block->errors[2] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[2] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP2_ITP_MASK; + new_stepbits |= LINACT2_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1100,20 +1106,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 3) { - new_stepbits |= STEP3_ITP_MASK; + new_stepbits |= LINACT3_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP3_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 3))) { #endif itp_rt_sgm->block->errors[3] += itp_rt_sgm->block->steps[3]; if (itp_rt_sgm->block->errors[3] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[3] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP3_ITP_MASK; + new_stepbits |= LINACT3_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1126,20 +1132,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 4) { - new_stepbits |= STEP4_ITP_MASK; + new_stepbits |= LINACT4_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP4_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 4))) { #endif itp_rt_sgm->block->errors[4] += itp_rt_sgm->block->steps[4]; if (itp_rt_sgm->block->errors[4] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[4] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP4_ITP_MASK; + new_stepbits |= LINACT4_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1152,20 +1158,20 @@ MCU_CALLBACK void mcu_step_cb(void) #ifdef STEP_ISR_SKIP_MAIN if (itp_rt_sgm->block->main_stepper == 5) { - new_stepbits |= STEP5_ITP_MASK; + new_stepbits |= LINACT5_IO_MASK; } else { #endif #ifdef STEP_ISR_SKIP_IDLE - if (!(itp_rt_sgm->block->idle_axis & STEP5_MASK)) + if (!(itp_rt_sgm->block->idle_axis & (1 << 5))) { #endif itp_rt_sgm->block->errors[5] += itp_rt_sgm->block->steps[5]; if (itp_rt_sgm->block->errors[5] > itp_rt_sgm->block->total_steps) { itp_rt_sgm->block->errors[5] -= itp_rt_sgm->block->total_steps; - new_stepbits |= STEP5_ITP_MASK; + new_stepbits |= LINACT5_IO_MASK; } #ifdef STEP_ISR_SKIP_IDLE } @@ -1191,13 +1197,13 @@ MCU_CALLBACK void mcu_step_cb(void) // updates the stepper coordinates #if (STEPPER_COUNT > 0) - if (new_stepbits & STEP0_ITP_MASK) + if (new_stepbits & LINACT0_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR0_MASK) + if (dirs & LINACT0_IO_MASK) { itp_rt_step_pos[0]--; } @@ -1211,13 +1217,13 @@ MCU_CALLBACK void mcu_step_cb(void) } #endif #if (STEPPER_COUNT > 1) - if (new_stepbits & STEP1_ITP_MASK) + if (new_stepbits & LINACT1_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR1_MASK) + if (dirs & LINACT1_IO_MASK) { itp_rt_step_pos[1]--; } @@ -1231,13 +1237,13 @@ MCU_CALLBACK void mcu_step_cb(void) } #endif #if (STEPPER_COUNT > 2) - if (new_stepbits & STEP2_ITP_MASK) + if (new_stepbits & LINACT2_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR2_MASK) + if (dirs & LINACT2_IO_MASK) { itp_rt_step_pos[2]--; } @@ -1251,13 +1257,13 @@ MCU_CALLBACK void mcu_step_cb(void) } #endif #if (STEPPER_COUNT > 3) - if (new_stepbits & STEP3_ITP_MASK) + if (new_stepbits & LINACT3_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR3_MASK) + if (dirs & LINACT3_IO_MASK) { itp_rt_step_pos[3]--; } @@ -1272,13 +1278,13 @@ MCU_CALLBACK void mcu_step_cb(void) #endif #if (STEPPER_COUNT > 4) - if (new_stepbits & STEP4_ITP_MASK) + if (new_stepbits & LINACT4_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR4_MASK) + if (dirs & LINACT4_IO_MASK) { itp_rt_step_pos[4]--; } @@ -1293,13 +1299,13 @@ MCU_CALLBACK void mcu_step_cb(void) #endif #if (STEPPER_COUNT > 5) - if (new_stepbits & STEP5_ITP_MASK) + if (new_stepbits & LINACT5_IO_MASK) { #ifdef ENABLE_BACKLASH_COMPENSATION if (!itp_rt_sgm->block->backlash_comp) { #endif - if (dirs & DIR5_MASK) + if (dirs & LINACT5_IO_MASK) { itp_rt_step_pos[5]--; } @@ -1321,11 +1327,7 @@ MCU_CALLBACK void mcu_step_cb(void) mcu_disable_global_isr(); // lock isr before clearin busy flag itp_busy = false; -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(IS_DELTA_KINEMATICS)) stepbits = (new_stepbits & ~itp_step_lock); -#else - stepbits = new_stepbits; -#endif } // void itp_nomotion(uint8_t type, uint16_t delay) diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index fc92a967b..e52afd100 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -95,9 +95,7 @@ extern "C" void itp_sync_spindle(void); void itp_start(bool is_synched); -#if (defined(ENABLE_DUAL_DRIVE_AXIS) || defined(KINEMATICS_MOTION_BY_SEGMENTS)) void itp_lock_stepper(uint8_t lockmask); -#endif #ifdef GCODE_PROCESS_LINE_NUMBERS uint32_t itp_get_rt_line_number(void); #endif diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 17b786802..b6d2a3465 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -95,75 +95,34 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) { static uint8_t prev_limits = 0; uint8_t limits = io_get_limits(); - -#if (LIMITS_DUAL_MASK != 0) - static uint8_t prev_limits_dual = 0; - uint8_t limits_dual = io_get_limits_dual(); - uint8_t limit_combined = limits | limits_dual; - - if (!(limits ^ prev_limits) && !(limits_dual ^ prev_limits_dual)) - { - return; - } - prev_limits = limits; - prev_limits_dual = limits_dual; -#else - if (!(limits ^ prev_limits)) + uint8_t limits_diff = prev_limits; + limits_diff ^= limits; + if (!limits_diff) { return; } + prev_limits = limits; - uint8_t limit_combined = limits; -#endif - if (limit_combined) + + if (limits) { -#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || defined(IS_DELTA_KINEMATICS)) - if (cnc_get_exec_state((EXEC_RUN | EXEC_HOMING)) == (EXEC_RUN | EXEC_HOMING) && (io_lock_limits_mask & limit_combined)) + uint8_t limits_ref = io_lock_limits_mask; + if (cnc_get_exec_state((EXEC_RUN | EXEC_HOMING)) == (EXEC_RUN | EXEC_HOMING) && (limits_ref & limits)) { - // if homing and dual drive axis are enabled -#ifdef DUAL_DRIVE0_ENABLE_SELFSQUARING - if (limit_combined & LIMIT_DUAL0_MASK) // the limit triggered matches the first dual drive axis - { - // lock the stepper accodring to the blocked - itp_lock_stepper((limits_dual & LIMIT_DUAL0_MASK) ? STEP_DUAL0_MASK : STEP_DUAL0); - - if (limits != limits_dual) // but not both - { - return; // exits and doesn't trip the alarm - } - } -#endif -#ifdef DUAL_DRIVE1_ENABLE_SELFSQUARING - if (limit_combined & LIMIT_DUAL1_MASK) // the limit triggered matches the second dual drive axis + // changed limit is from the current mask + if((limits_diff & limits_ref)) { - itp_lock_stepper((limits_dual & LIMIT_DUAL1_MASK) ? STEP_DUAL1_MASK : STEP_DUAL1); + // lock steps on the current limits + itp_lock_stepper(limits); - if (limits != limits_dual) // but not both + if (limits != limits_ref) // current limits are all the ones marked as locked { return; // exits and doesn't trip the alarm } } -#endif -#if (defined(IS_DELTA_KINEMATICS)) - if ((limit_combined & LIMITS_DELTA_MASK)) - { - if (limit_combined != LIMITS_DELTA_MASK) - { - itp_lock_stepper(limit_combined); - return; - } - } - else - { - return; - } -#endif } -#endif -#if (defined(DUAL_DRIVE0_ENABLE_SELFSQUARING) || defined(DUAL_DRIVE1_ENABLE_SELFSQUARING) || defined(IS_DELTA_KINEMATICS)) itp_lock_stepper(0); // unlocks axis -#endif itp_stop(); cnc_set_exec_state(EXEC_LIMITS); #ifdef ENABLE_IO_ALARM_DEBUG @@ -345,90 +304,44 @@ uint8_t io_get_limits(void) uint8_t value = 0; #if ASSERT_PIN(LIMIT_X) - value |= ((io_get_input(LIMIT_X)) ? LIMIT_X_MASK : 0); + value |= ((io_get_input(LIMIT_X)) ? LIMIT_X_IO_MASK : 0); #endif #if ASSERT_PIN(LIMIT_Y) - value |= ((io_get_input(LIMIT_Y)) ? LIMIT_Y_MASK : 0); + value |= ((io_get_input(LIMIT_Y)) ? LIMIT_Y_IO_MASK : 0); #endif #if ASSERT_PIN(LIMIT_Z) - value |= ((io_get_input(LIMIT_Z)) ? LIMIT_Z_MASK : 0); + value |= ((io_get_input(LIMIT_Z)) ? LIMIT_Z_IO_MASK : 0); +#endif +#if ASSERT_PIN(LIMIT_X2) + value |= ((io_get_input(LIMIT_X2)) ? LIMIT_X2_IO_MASK : 0); +#endif +#if ASSERT_PIN(LIMIT_Y2) + value |= ((io_get_input(LIMIT_Y2)) ? LIMIT_Y2_IO_MASK : 0); +#endif +#if ASSERT_PIN(LIMIT_Z2) + value |= ((io_get_input(LIMIT_Z2)) ? LIMIT_Z2_IO_MASK : 0); #endif #if ASSERT_PIN(LIMIT_A) - value |= ((io_get_input(LIMIT_A)) ? LIMIT_A_MASK : 0); + value |= ((io_get_input(LIMIT_A)) ? LIMIT_A_IO_MASK : 0); #endif #if ASSERT_PIN(LIMIT_B) - value |= ((io_get_input(LIMIT_B)) ? LIMIT_B_MASK : 0); + value |= ((io_get_input(LIMIT_B)) ? LIMIT_B_IO_MASK : 0); #endif #if ASSERT_PIN(LIMIT_C) - value |= ((io_get_input(LIMIT_C)) ? LIMIT_C_MASK : 0); + value |= ((io_get_input(LIMIT_C)) ? LIMIT_C_IO_MASK : 0); #endif uint8_t inv = g_settings.limits_invert_mask; uint8_t result = (value ^ (inv & LIMITS_INV_MASK)); -#if LIMITS_DUAL_INV_MASK != 0 - uint8_t value2 = 0; - -#if ASSERT_PIN(LIMIT_X2) -#if !(LIMITS_DUAL_MASK & LIMIT_X_MASK) - value2 |= ((io_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); -#endif -#endif -#if ASSERT_PIN(LIMIT_Y2) -#if !(LIMITS_DUAL_MASK & LIMIT_Y_MASK) - value2 |= ((io_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); -#endif -#endif -#if ASSERT_PIN(LIMIT_Z2) -#if !(LIMITS_DUAL_MASK & LIMIT_Z_MASK) - value2 |= ((io_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); -#endif -#endif - - result |= (value2 ^ (inv & LIMITS_DUAL_INV_MASK & ~LIMITS_DUAL_MASK)); - -#endif - if (cnc_get_exec_state(EXEC_HOMING)) { result ^= io_invert_limits_mask; } -#if LIMITS_DUAL_INV_MASK - else - { - result |= io_get_limits_dual(); - } -#endif return result; } -uint8_t io_get_limits_dual(void) -{ -#if (defined(DISABLE_ALL_LIMITS) || (LIMITS_DUAL_MASK == 0)) - return 0; -#else - uint8_t value = 0; -#if ASSERT_PIN(LIMIT_X2) -#if (LIMITS_DUAL_MASK & LIMIT_X_MASK) - value |= ((io_get_input(LIMIT_X2)) ? LIMIT_X_MASK : 0); -#endif -#endif -#if ASSERT_PIN(LIMIT_Y2) -#if (LIMITS_DUAL_MASK & LIMIT_Y_MASK) - value |= ((io_get_input(LIMIT_Y2)) ? LIMIT_Y_MASK : 0); -#endif -#endif -#if ASSERT_PIN(LIMIT_Z2) -#if (LIMITS_DUAL_MASK & LIMIT_Z_MASK) - value |= ((io_get_input(LIMIT_Z2)) ? LIMIT_Z_MASK : 0); -#endif -#endif - uint8_t inv = io_invert_limits_mask & LIMITS_DUAL_MASK; - return (value ^ (g_settings.limits_invert_mask & LIMITS_DUAL_MASK & LIMITS_DUAL_INV_MASK) ^ inv); -#endif -} - uint8_t io_get_controls(void) { #ifdef DISABLE_ALL_CONTROLS @@ -508,7 +421,7 @@ void io_set_steps(uint8_t mask) #endif #if ASSERT_PIN_IO(STEP0) - if (mask & STEP0_MASK) + if (mask & STEP0_IO_MASK) { mcu_set_output(STEP0); } @@ -519,7 +432,7 @@ void io_set_steps(uint8_t mask) #endif #if ASSERT_PIN_IO(STEP1) - if (mask & STEP1_MASK) + if (mask & STEP1_IO_MASK) { mcu_set_output(STEP1); } @@ -529,7 +442,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP2) - if (mask & STEP2_MASK) + if (mask & STEP2_IO_MASK) { mcu_set_output(STEP2); } @@ -539,7 +452,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP3) - if (mask & STEP3_MASK) + if (mask & STEP3_IO_MASK) { mcu_set_output(STEP3); } @@ -549,7 +462,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP4) - if (mask & STEP4_MASK) + if (mask & STEP4_IO_MASK) { mcu_set_output(STEP4); } @@ -559,7 +472,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP5) - if (mask & STEP5_MASK) + if (mask & STEP5_IO_MASK) { mcu_set_output(STEP5); } @@ -569,7 +482,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP6) - if (mask & STEP6_MASK) + if (mask & STEP6_IO_MASK) { mcu_set_output(STEP6); } @@ -579,7 +492,7 @@ void io_set_steps(uint8_t mask) } #endif #if ASSERT_PIN_IO(STEP7) - if (mask & STEP7_MASK) + if (mask & STEP7_IO_MASK) { mcu_set_output(STEP7); } @@ -601,49 +514,49 @@ void io_toggle_steps(uint8_t mask) #endif #if ASSERT_PIN_IO(STEP0) - if (mask & STEP0_MASK) + if (mask & STEP0_IO_MASK) { mcu_toggle_output(STEP0); } #endif #if ASSERT_PIN_IO(STEP1) - if (mask & STEP1_MASK) + if (mask & STEP1_IO_MASK) { mcu_toggle_output(STEP1); } #endif #if ASSERT_PIN_IO(STEP2) - if (mask & STEP2_MASK) + if (mask & STEP2_IO_MASK) { mcu_toggle_output(STEP2); } #endif #if ASSERT_PIN_IO(STEP3) - if (mask & STEP3_MASK) + if (mask & STEP3_IO_MASK) { mcu_toggle_output(STEP3); } #endif #if ASSERT_PIN_IO(STEP4) - if (mask & STEP4_MASK) + if (mask & STEP4_IO_MASK) { mcu_toggle_output(STEP4); } #endif #if ASSERT_PIN_IO(STEP5) - if (mask & STEP5_MASK) + if (mask & STEP5_IO_MASK) { mcu_toggle_output(STEP5); } #endif #if ASSERT_PIN_IO(STEP6) - if (mask & STEP6_MASK) + if (mask & STEP6_IO_MASK) { mcu_toggle_output(STEP6); } #endif #if ASSERT_PIN_IO(STEP7) - if (mask & STEP7_MASK) + if (mask & STEP7_IO_MASK) { mcu_toggle_output(STEP7); } @@ -663,7 +576,7 @@ void io_set_dirs(uint8_t mask) #endif #if ASSERT_PIN_IO(DIR0) - if (mask & DIR0_MASK) + if (mask & STEP0_IO_MASK) { mcu_set_output(DIR0); } @@ -673,7 +586,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR1) - if (mask & DIR1_MASK) + if (mask & STEP1_IO_MASK) { mcu_set_output(DIR1); } @@ -683,7 +596,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR2) - if (mask & DIR2_MASK) + if (mask & STEP2_IO_MASK) { mcu_set_output(DIR2); } @@ -693,7 +606,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR3) - if (mask & DIR3_MASK) + if (mask & STEP3_IO_MASK) { mcu_set_output(DIR3); } @@ -703,7 +616,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR4) - if (mask & DIR4_MASK) + if (mask & STEP4_IO_MASK) { mcu_set_output(DIR4); } @@ -713,7 +626,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR5) - if (mask & DIR5_MASK) + if (mask & STEP5_IO_MASK) { mcu_set_output(DIR5); } @@ -723,7 +636,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR6) - if (mask & DIR6_MASK) + if (mask & STEP6_IO_MASK) { mcu_set_output(DIR6); } @@ -733,7 +646,7 @@ void io_set_dirs(uint8_t mask) } #endif #if ASSERT_PIN_IO(DIR7) - if (mask & DIR7_MASK) + if (mask & STEP7_IO_MASK) { mcu_set_output(DIR7); } diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index af9d6eeb4..7bad96b2a 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -63,7 +63,6 @@ extern "C" void io_lock_limits(uint8_t limitmask); void io_invert_limits(uint8_t limitmask); uint8_t io_get_limits(void); - uint8_t io_get_limits_dual(void); uint8_t io_get_controls(void); void io_enable_probe(void); void io_disable_probe(void); diff --git a/uCNC/src/hal/kinematics/kinematic_cartesian.c b/uCNC/src/hal/kinematics/kinematic_cartesian.c index 7e340382d..884071a71 100644 --- a/uCNC/src/hal/kinematics/kinematic_cartesian.c +++ b/uCNC/src/hal/kinematics/kinematic_cartesian.c @@ -50,7 +50,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_ALL_LIMITS #ifndef DISABLE_Z_HOMING #if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) - if (mc_home_axis(AXIS_Z, LIMIT_Z_MASK)) + if (mc_home_axis(AXIS_Z, LINACT2_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } @@ -59,7 +59,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_X_HOMING #if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) - if (mc_home_axis(AXIS_X, LIMIT_X_MASK)) + if (mc_home_axis(AXIS_X, LINACT0_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_X; } @@ -68,7 +68,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_Y_HOMING #if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) - if (mc_home_axis(AXIS_Y, LIMIT_Y_MASK)) + if (mc_home_axis(AXIS_Y, LINACT1_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Y; } @@ -77,7 +77,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_A_HOMING #if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_A; } @@ -86,7 +86,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_B_HOMING #if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } @@ -95,7 +95,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_C_HOMING #if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } diff --git a/uCNC/src/hal/kinematics/kinematic_corexy.c b/uCNC/src/hal/kinematics/kinematic_corexy.c index 5e308a570..54b8bf41d 100644 --- a/uCNC/src/hal/kinematics/kinematic_corexy.c +++ b/uCNC/src/hal/kinematics/kinematic_corexy.c @@ -60,7 +60,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_ALL_LIMITS #ifndef DISABLE_Z_HOMING #if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) - if (mc_home_axis(AXIS_Z, LIMIT_Z_MASK)) + if (mc_home_axis(AXIS_Z, LINACT2_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } @@ -69,7 +69,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_X_HOMING #if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) - if (mc_home_axis(AXIS_X, LIMIT_X_MASK)) + if (mc_home_axis(AXIS_X, LINACT0_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_X; } @@ -78,7 +78,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_Y_HOMING #if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) - if (mc_home_axis(AXIS_Y, LIMIT_Y_MASK)) + if (mc_home_axis(AXIS_Y, LINACT1_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Y; } @@ -87,7 +87,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_A_HOMING #if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_A; } @@ -96,7 +96,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_B_HOMING #if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } @@ -105,7 +105,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_C_HOMING #if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } diff --git a/uCNC/src/hal/kinematics/kinematic_delta.c b/uCNC/src/hal/kinematics/kinematic_delta.c index f33261d6f..23834ab74 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_delta.c @@ -342,7 +342,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_A_HOMING #if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) { return (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y | KINEMATIC_HOMING_ERROR_Z); } @@ -351,7 +351,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_B_HOMING #if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } @@ -360,7 +360,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_C_HOMING #if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.c b/uCNC/src/hal/kinematics/kinematic_linear_delta.c index 48f52ef86..8b8d43c47 100644 --- a/uCNC/src/hal/kinematics/kinematic_linear_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.c @@ -152,7 +152,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_A_HOMING #if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) + if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) { return (KINEMATIC_HOMING_ERROR_X|KINEMATIC_HOMING_ERROR_Y|KINEMATIC_HOMING_ERROR_Z); } @@ -161,7 +161,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_B_HOMING #if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) + if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } @@ -170,7 +170,7 @@ uint8_t kinematics_home(void) #ifndef DISABLE_C_HOMING #if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) + if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index bf22c0586..d8c5bb08b 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -356,32 +356,32 @@ void protocol_send_status(void) serial_putc('P'); } - if (CHECKFLAG(limits, LIMIT_X_MASK)) + if (CHECKFLAG(limits, LINACT0_LIMIT_MASK)) { serial_putc('X'); } - if (CHECKFLAG(limits, LIMIT_Y_MASK)) + if (CHECKFLAG(limits, LINACT1_LIMIT_MASK)) { serial_putc('Y'); } - if (CHECKFLAG(limits, LIMIT_Z_MASK)) + if (CHECKFLAG(limits, LINACT2_LIMIT_MASK)) { serial_putc('Z'); } - if (CHECKFLAG(limits, LIMIT_A_MASK)) + if (CHECKFLAG(limits, LINACT3_LIMIT_MASK)) { serial_putc('A'); } - if (CHECKFLAG(limits, LIMIT_B_MASK)) + if (CHECKFLAG(limits, LINACT4_LIMIT_MASK)) { serial_putc('B'); } - if (CHECKFLAG(limits, LIMIT_C_MASK)) + if (CHECKFLAG(limits, LINACT5_LIMIT_MASK)) { serial_putc('C'); } From 05f9992535cfe28bcca02ebc12840e28443e6846 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 11 Aug 2023 16:14:36 +0100 Subject: [PATCH 087/168] Multi axis homing and motion - fixed ITP for multi step linear actuators - modified homing and added support for multi axis homing in parallel - integrated backlash filtering in the rt sgm flags --- uCNC/cnc_hal_config.h | 19 +- uCNC/src/cnc.c | 4 +- uCNC/src/cnc_hal_config_helper.h | 175 +++++++++++- uCNC/src/core/interpolator.c | 258 ++++++++---------- uCNC/src/core/interpolator.h | 6 +- uCNC/src/core/io_control.c | 8 +- uCNC/src/core/io_control.h | 2 + uCNC/src/core/motion_control.c | 56 ++-- uCNC/src/core/motion_control.h | 2 +- uCNC/src/hal/kinematics/kinematic.h | 1 + uCNC/src/hal/kinematics/kinematic_cartesian.c | 67 +++-- uCNC/src/hal/kinematics/kinematic_corexy.c | 55 ++-- uCNC/src/hal/kinematics/kinematic_delta.c | 23 +- .../hal/kinematics/kinematic_linear_delta.c | 23 +- 14 files changed, 446 insertions(+), 253 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 5ae152506..e3d9c7f8e 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -92,12 +92,17 @@ extern "C" // #define DISABLE_B_HOMING // #define DISABLE_C_HOMING +/** + * Uncomment this feature to enable X and Y homing simultaneously + */ +// #define ENABLE_XY_SIMULTANEOUS_HOMING + /** * Uncomment this feature to enable multi motor axis * NOTE: If Laser PPI is enabled one of the stepper drivers position will be used by the laser controller * Usually that is STEPPER so if AXIS_COUNT=3, STEPPER3 will be used by laser PPI */ -#define ENABLE_MULTI_STEPPER_AXIS +// #define ENABLE_MULTI_STEPPER_AXIS #ifdef ENABLE_MULTI_STEPPER_AXIS /** @@ -123,13 +128,13 @@ extern "C" * **/ // defines a multi stepper linear actuator LINACT0 - #define LINACT0_IO_MASK (STEP0_IO_MASK | STEP5_IO_MASK) +// #define LINACT0_IO_MASK (STEP0_IO_MASK | STEP5_IO_MASK) // defines a second multi stepper linear actuator LINACT1 - #define LINACT1_IO_MASK (STEP1_IO_MASK | STEP6_IO_MASK) +// #define LINACT1_IO_MASK (STEP1_IO_MASK | STEP6_IO_MASK) // defines a second multi stepper linear actuator LINACT2 - #define LINACT2_IO_MASK (STEP2_IO_MASK | STEP7_IO_MASK) +// #define LINACT2_IO_MASK (STEP2_IO_MASK | STEP7_IO_MASK) // there is no limit to the ammount of STEP IO that can be combined into a LINACT. For example it's possible to assign 4 independent STEP IO to a single LINACT // #define LINACT2_IO_MASK (STEP2_IO_MASK | STEP5_IO_MASK | STEP6_IO_MASK | STEP7_IO_MASK) @@ -156,17 +161,17 @@ extern "C" * * **/ - #define ENABLE_X_AUTOLEVEL +// #define ENABLE_X_AUTOLEVEL #ifdef ENABLE_X_AUTOLEVEL #define LIMIT_X2_IO_MASK STEP5_IO_MASK #endif - #define ENABLE_Y_AUTOLEVEL +// #define ENABLE_Y_AUTOLEVEL #ifdef ENABLE_Y_AUTOLEVEL #define LIMIT_Y2_IO_MASK STEP6_IO_MASK #endif - #define ENABLE_Z_AUTOLEVEL +// #define ENABLE_Z_AUTOLEVEL #ifdef ENABLE_Z_AUTOLEVEL #define LIMIT_Z2_IO_MASK STEP7_IO_MASK #endif diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 6fce090ce..0ee0b475c 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -376,8 +376,10 @@ void cnc_home(void) { cnc_set_exec_state(EXEC_HOMING); uint8_t error = kinematics_home(); - // unlock expected limits +// unlock expected limits +#ifdef ENABLE_MULTI_STEP_HOMING io_lock_limits(0); +#endif io_invert_limits(0); if (error) { diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index aeb8a2242..1efd452f5 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -1575,27 +1575,27 @@ extern "C" #elif !defined(LIMIT_X_IO_MASK) #define LIMIT_X_IO_MASK STEP_UNDEF_IO_MASK #endif -#if ASSERT_PIN(LIMIT_Y) && !defined(LIMIT_Y_IO_MASK) +#if ASSERT_PIN(LIMIT_Y) && !defined(LIMIT_Y_IO_MASK) && (AXIS_COUNT > 1) #define LIMIT_Y_IO_MASK STEP1_IO_MASK #elif !defined(LIMIT_Y_IO_MASK) #define LIMIT_Y_IO_MASK STEP_UNDEF_IO_MASK #endif -#if ASSERT_PIN(LIMIT_Z) && !defined(LIMIT_Z_IO_MASK) +#if ASSERT_PIN(LIMIT_Z) && !defined(LIMIT_Z_IO_MASK) && (AXIS_COUNT > 2) #define LIMIT_Z_IO_MASK STEP2_IO_MASK #elif !defined(LIMIT_Z_IO_MASK) #define LIMIT_Z_IO_MASK STEP_UNDEF_IO_MASK #endif -#if ASSERT_PIN(LIMIT_A) && !defined(LIMIT_A_IO_MASK) +#if ASSERT_PIN(LIMIT_A) && !defined(LIMIT_A_IO_MASK) && (AXIS_COUNT > 3) #define LIMIT_A_IO_MASK STEP3_IO_MASK #elif !defined(LIMIT_A_IO_MASK) #define LIMIT_A_IO_MASK STEP_UNDEF_IO_MASK #endif -#if ASSERT_PIN(LIMIT_B) && !defined(LIMIT_B_IO_MASK) +#if ASSERT_PIN(LIMIT_B) && !defined(LIMIT_B_IO_MASK) && (AXIS_COUNT > 4) #define LIMIT_B_IO_MASK STEP4_IO_MASK #elif !defined(LIMIT_B_IO_MASK) #define LIMIT_B_IO_MASK STEP_UNDEF_IO_MASK #endif -#if ASSERT_PIN(LIMIT_C) && !defined(LIMIT_C_IO_MASK) +#if ASSERT_PIN(LIMIT_C) && !defined(LIMIT_C_IO_MASK) && (AXIS_COUNT > 5) #define LIMIT_C_IO_MASK STEP5_IO_MASK #elif !defined(LIMIT_C_IO_MASK) #define LIMIT_C_IO_MASK STEP_UNDEF_IO_MASK @@ -1656,6 +1656,43 @@ extern "C" #define LINACT5_LIMIT_MASK (LIMIT_C_IO_MASK) #endif +#ifndef AXIS_X +#undef LINACT0_IO_MASK +#undef LINACT0_LIMIT_MASK +#define LINACT0_IO_MASK 0 +#define LINACT0_LIMIT_MASK 0 +#endif +#ifndef AXIS_Y +#undef LINACT1_IO_MASK +#undef LINACT1_LIMIT_MASK +#define LINACT1_IO_MASK 0 +#define LINACT1_LIMIT_MASK 0 +#endif +#ifndef AXIS_Z +#undef LINACT2_IO_MASK +#undef LINACT2_LIMIT_MASK +#define LINACT2_IO_MASK 0 +#define LINACT2_LIMIT_MASK 0 +#endif +#ifndef AXIS_A +#undef LINACT3_IO_MASK +#undef LINACT3_LIMIT_MASK +#define LINACT3_IO_MASK 0 +#define LINACT3_LIMIT_MASK 0 +#endif +#ifndef AXIS_B +#undef LINACT4_IO_MASK +#undef LINACT4_LIMIT_MASK +#define LINACT4_IO_MASK 0 +#define LINACT4_LIMIT_MASK 0 +#endif +#ifndef AXIS_C +#undef LINACT5_IO_MASK +#undef LINACT5_LIMIT_MASK +#define LINACT5_IO_MASK 0 +#define LINACT5_LIMIT_MASK 0 +#endif + #define LIMITS_MASK (LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK | LINACT2_LIMIT_MASK | LINACT3_LIMIT_MASK | LINACT4_LIMIT_MASK | LINACT5_LIMIT_MASK) #define LIMITS_DELTA_MASK (LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK | LINACT2_LIMIT_MASK) @@ -1965,6 +2002,134 @@ typedef uint16_t step_t; #error "Invalid config option STATUS_AUTOMATIC_REPORT_INTERVAL must be set between 0 and 1000" #endif +#if defined(ENABLE_X_AUTOLEVEL) || defined(ENABLE_Y_AUTOLEVEL) || defined(ENABLE_Z_AUTOLEVEL) || defined(IS_DELTA_KINEMATICS) || defined(ENABLE_XY_SIMULTANEOUS_HOMING) +#define ENABLE_MULTI_STEP_HOMING +#endif + +#if defined(AXIS_X) && LINACT0_LIMIT_MASK && !defined(DISABLE_X_HOMING) +#define AXIS_X_HOMING_MASK (1 << AXIS_X) +#else +#define AXIS_X_HOMING_MASK 0 +#endif +#if defined(AXIS_Y) && LINACT1_LIMIT_MASK && !defined(DISABLE_Y_HOMING) +#define AXIS_Y_HOMING_MASK (1 << AXIS_Y) +#else +#define AXIS_Y_HOMING_MASK 0 +#endif +#if defined(AXIS_Z) && LINACT2_LIMIT_MASK && !defined(DISABLE_Z_HOMING) +#define AXIS_Z_HOMING_MASK (1 << AXIS_Z) +#else +#define AXIS_Z_HOMING_MASK 0 +#endif +#if defined(AXIS_A) && LINACT3_LIMIT_MASK && !defined(DISABLE_A_HOMING) +#define AXIS_A_HOMING_MASK (1 << AXIS_A) +#else +#define AXIS_A_HOMING_MASK 0 +#endif +#if defined(AXIS_B) && LINACT4_LIMIT_MASK && !defined(DISABLE_B_HOMING) +#define AXIS_B_HOMING_MASK (1 << AXIS_B) +#else +#define AXIS_B_HOMING_MASK 0 +#endif +#if defined(AXIS_C) && LINACT5_LIMIT_MASK && !defined(DISABLE_C_HOMING) +#define AXIS_C_HOMING_MASK (1 << AXIS_C) +#else +#define AXIS_C_HOMING_MASK 0 +#endif + +#if (LINACT0_IO_MASK & LINACT1_IO_MASK) +#error "Linear actuator 0 and 1 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT0_IO_MASK & LINACT2_IO_MASK) +#error "Linear actuator 0 and 2 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT0_IO_MASK & LINACT3_IO_MASK) +#error "Linear actuator 0 and 3 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT0_IO_MASK & LINACT4_IO_MASK) +#error "Linear actuator 0 and 4 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT0_IO_MASK & LINACT5_IO_MASK) +#error "Linear actuator 0 and 5 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT1_IO_MASK & LINACT2_IO_MASK) +#error "Linear actuator 1 and 2 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT1_IO_MASK & LINACT3_IO_MASK) +#error "Linear actuator 1 and 3 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT1_IO_MASK & LINACT4_IO_MASK) +#error "Linear actuator 1 and 4 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT1_IO_MASK & LINACT5_IO_MASK) +#error "Linear actuator 1 and 5 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT2_IO_MASK & LINACT3_IO_MASK) +#error "Linear actuator 2 and 3 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT2_IO_MASK & LINACT4_IO_MASK) +#error "Linear actuator 2 and 4 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT2_IO_MASK & LINACT5_IO_MASK) +#error "Linear actuator 2 and 5 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT3_IO_MASK & LINACT4_IO_MASK) +#error "Linear actuator 3 and 4 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT3_IO_MASK & LINACT5_IO_MASK) +#error "Linear actuator 3 and 5 have overlapped outputs and this can lead to unpredictable results" +#endif +#if (LINACT4_IO_MASK & LINACT5_IO_MASK) +#error "Linear actuator 4 and 5 have overlapped outputs and this can lead to unpredictable results" +#endif + +#if (LINACT0_LIMIT_MASK & LINACT1_LIMIT_MASK) +#error "Linear actuator 0 and 1 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT0_LIMIT_MASK & LINACT2_LIMIT_MASK) +#error "Linear actuator 0 and 2 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT0_LIMIT_MASK & LINACT3_LIMIT_MASK) +#error "Linear actuator 0 and 3 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT0_LIMIT_MASK & LINACT4_LIMIT_MASK) +#error "Linear actuator 0 and 4 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT0_LIMIT_MASK & LINACT5_LIMIT_MASK) +#error "Linear actuator 0 and 5 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT1_LIMIT_MASK & LINACT2_LIMIT_MASK) +#error "Linear actuator 1 and 2 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT1_LIMIT_MASK & LINACT3_LIMIT_MASK) +#error "Linear actuator 1 and 3 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT1_LIMIT_MASK & LINACT4_LIMIT_MASK) +#error "Linear actuator 1 and 4 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT1_LIMIT_MASK & LINACT5_LIMIT_MASK) +#error "Linear actuator 1 and 5 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT2_LIMIT_MASK & LINACT3_LIMIT_MASK) +#error "Linear actuator 2 and 3 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT2_LIMIT_MASK & LINACT4_LIMIT_MASK) +#error "Linear actuator 2 and 4 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT2_LIMIT_MASK & LINACT5_LIMIT_MASK) +#error "Linear actuator 2 and 5 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT3_LIMIT_MASK & LINACT4_LIMIT_MASK) +#error "Linear actuator 3 and 4 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT3_LIMIT_MASK & LINACT5_LIMIT_MASK) +#error "Linear actuator 3 and 5 have overlapped input limits and this can lead to unpredictable results" +#endif +#if (LINACT4_LIMIT_MASK & LINACT5_LIMIT_MASK) +#error "Linear actuator 4 and 5 have overlapped input limits and this can lead to unpredictable results" +#endif + + #ifdef MCU_HAS_I2C // defaults to master I2C diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index 0eaf12f06..aed76b062 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -61,7 +61,9 @@ static uint8_t prev_dss; static int16_t prev_spindle; // pointer to the segment being executed static itp_segment_t *itp_rt_sgm; +#ifdef ENABLE_MULTI_STEP_HOMING static volatile uint8_t itp_step_lock; +#endif #ifdef ENABLE_RT_SYNC_MOTIONS // deprecated with new hooks @@ -206,7 +208,9 @@ void itp_init(void) memset(itp_blk_data, 0, sizeof(itp_blk_data)); memset(itp_sgm_data, 0, sizeof(itp_sgm_data)); itp_rt_sgm = NULL; +#ifdef ENABLE_MULTI_STEP_HOMING itp_step_lock = 0; +#endif #endif itp_cur_plan_block = NULL; itp_needs_update = false; @@ -376,11 +380,6 @@ void itp_run(void) itp_blk_data[itp_blk_data_write].line = itp_cur_plan_block->line; #endif -// overwrites previous values -#ifdef ENABLE_BACKLASH_COMPENSATION - itp_blk_data[itp_blk_data_write].backlash_comp = itp_cur_plan_block->planner_flags.bit.backlash_comp; -#endif - // reset dirbits itp_blk_data[itp_blk_data_write].dirbits = 0; step_t total_steps = itp_cur_plan_block->steps[itp_cur_plan_block->main_stepper]; @@ -681,6 +680,14 @@ void itp_run(void) sgm->flags |= ITP_SYNC; } + // overwrites previous values +#ifdef ENABLE_BACKLASH_COMPENSATION + if (itp_cur_plan_block->planner_flags.bit.backlash_comp) + { + sgm->flags |= ITP_BACKLASH; + } +#endif + if (remaining_steps == 0) { itp_blk_buffer_write(); @@ -852,10 +859,12 @@ void itp_sync_spindle(void) #endif } +#ifdef ENABLE_MULTI_STEP_HOMING void itp_lock_stepper(uint8_t lockmask) { itp_step_lock = lockmask; } +#endif #ifdef GCODE_PROCESS_LINE_NUMBERS uint32_t itp_get_rt_line_number(void) @@ -889,18 +898,111 @@ MCU_CALLBACK void mcu_step_cb(void) } uint8_t new_stepbits = stepbits; - io_toggle_steps(new_stepbits); + uint8_t dirs = 0; - // sets step bits -#ifdef ENABLE_RT_SYNC_MOTIONS - if (new_stepbits && itp_rt_sgm) + if (itp_rt_sgm != NULL) { - HOOK_INVOKE(itp_rt_stepbits, new_stepbits, itp_rt_sgm->flags); - } + dirs = itp_rt_sgm->block->dirbits; + io_toggle_steps(new_stepbits); + + // sets step bits +#ifdef ENABLE_RT_SYNC_MOTIONS + if (new_stepbits && itp_rt_sgm) + { + HOOK_INVOKE(itp_rt_stepbits, new_stepbits, itp_rt_sgm->flags); + } +#endif + +#ifdef ENABLE_BACKLASH_COMPENSATION + // resets step bit so that they don't update the rt position + if (itp_rt_sgm->flags & ITP_BACKLASH) + { + new_stepbits = 0; + } +#endif + +// updates the stepper coordinates +#if (STEPPER_COUNT > 0) + if (new_stepbits & LINACT0_IO_MASK) + { + if (dirs & LINACT0_IO_MASK) + { + itp_rt_step_pos[0]--; + } + else + { + itp_rt_step_pos[0]++; + } + } +#endif +#if (STEPPER_COUNT > 1) + if (new_stepbits & LINACT1_IO_MASK) + { + if (dirs & LINACT1_IO_MASK) + { + itp_rt_step_pos[1]--; + } + else + { + itp_rt_step_pos[1]++; + } + } +#endif +#if (STEPPER_COUNT > 2) + if (new_stepbits & LINACT2_IO_MASK) + { + if (dirs & LINACT2_IO_MASK) + { + itp_rt_step_pos[2]--; + } + else + { + itp_rt_step_pos[2]++; + } + } +#endif +#if (STEPPER_COUNT > 3) + if (new_stepbits & LINACT3_IO_MASK) + { + if (dirs & LINACT3_IO_MASK) + { + itp_rt_step_pos[3]--; + } + else + { + itp_rt_step_pos[3]++; + } + } +#endif + +#if (STEPPER_COUNT > 4) + if (new_stepbits & LINACT4_IO_MASK) + { + if (dirs & LINACT4_IO_MASK) + { + itp_rt_step_pos[4]--; + } + else + { + itp_rt_step_pos[4]++; + } + } +#endif + +#if (STEPPER_COUNT > 5) + if (new_stepbits & LINACT5_IO_MASK) + { + if (dirs & LINACT5_IO_MASK) + { + itp_rt_step_pos[5]--; + } + else + { + itp_rt_step_pos[5]++; + } + } #endif - if (itp_rt_sgm != NULL) - { if (itp_rt_sgm->flags & ITP_UPDATE) { if (itp_rt_sgm->flags & ITP_UPDATE_ISR) @@ -1181,7 +1283,6 @@ MCU_CALLBACK void mcu_step_cb(void) #endif #endif - uint8_t dirs = itp_rt_sgm->block->dirbits; #ifdef ENABLE_RT_SYNC_MOTIONS static uint8_t last_dirs = 0; if (new_stepbits) @@ -1194,130 +1295,6 @@ MCU_CALLBACK void mcu_step_cb(void) } } #endif - -// updates the stepper coordinates -#if (STEPPER_COUNT > 0) - if (new_stepbits & LINACT0_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT0_IO_MASK) - { - itp_rt_step_pos[0]--; - } - else - { - itp_rt_step_pos[0]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif -#if (STEPPER_COUNT > 1) - if (new_stepbits & LINACT1_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT1_IO_MASK) - { - itp_rt_step_pos[1]--; - } - else - { - itp_rt_step_pos[1]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif -#if (STEPPER_COUNT > 2) - if (new_stepbits & LINACT2_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT2_IO_MASK) - { - itp_rt_step_pos[2]--; - } - else - { - itp_rt_step_pos[2]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif -#if (STEPPER_COUNT > 3) - if (new_stepbits & LINACT3_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT3_IO_MASK) - { - itp_rt_step_pos[3]--; - } - else - { - itp_rt_step_pos[3]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif - -#if (STEPPER_COUNT > 4) - if (new_stepbits & LINACT4_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT4_IO_MASK) - { - itp_rt_step_pos[4]--; - } - else - { - itp_rt_step_pos[4]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif - -#if (STEPPER_COUNT > 5) - if (new_stepbits & LINACT5_IO_MASK) - { -#ifdef ENABLE_BACKLASH_COMPENSATION - if (!itp_rt_sgm->block->backlash_comp) - { -#endif - if (dirs & LINACT5_IO_MASK) - { - itp_rt_step_pos[5]--; - } - else - { - itp_rt_step_pos[5]++; - } -#ifdef ENABLE_BACKLASH_COMPENSATION - } -#endif - } -#endif } // no step remaining discards current segment @@ -1326,8 +1303,11 @@ MCU_CALLBACK void mcu_step_cb(void) mcu_disable_global_isr(); // lock isr before clearin busy flag itp_busy = false; - +#ifdef ENABLE_MULTI_STEP_HOMING stepbits = (new_stepbits & ~itp_step_lock); +#else + stepbits = new_stepbits; +#endif } // void itp_nomotion(uint8_t type, uint16_t delay) diff --git a/uCNC/src/core/interpolator.h b/uCNC/src/core/interpolator.h index e52afd100..d23eec343 100644 --- a/uCNC/src/core/interpolator.h +++ b/uCNC/src/core/interpolator.h @@ -38,6 +38,7 @@ extern "C" #define ITP_CONST 8 #define ITP_DEACCEL 16 #define ITP_SYNC 32 +#define ITP_BACKLASH 64 // contains data of the block being executed by the pulse routine // this block has the necessary data to execute the Bresenham line algorithm @@ -55,9 +56,6 @@ extern "C" step_t errors[STEPPER_COUNT]; #ifdef GCODE_PROCESS_LINE_NUMBERS uint32_t line; -#endif -#ifdef ENABLE_BACKLASH_COMPENSATION - bool backlash_comp; #endif } itp_block_t; @@ -95,7 +93,9 @@ extern "C" void itp_sync_spindle(void); void itp_start(bool is_synched); +#ifdef ENABLE_MULTI_STEP_HOMING void itp_lock_stepper(uint8_t lockmask); +#endif #ifdef GCODE_PROCESS_LINE_NUMBERS uint32_t itp_get_rt_line_number(void); #endif diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index b6d2a3465..d2d4fc7ba 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -20,7 +20,9 @@ #include "../cnc.h" +#ifdef ENABLE_MULTI_STEP_HOMING static uint8_t io_lock_limits_mask; +#endif static uint8_t io_invert_limits_mask; #if ASSERT_PIN(PROBE) @@ -106,11 +108,12 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) if (limits) { +#ifdef ENABLE_MULTI_STEP_HOMING uint8_t limits_ref = io_lock_limits_mask; if (cnc_get_exec_state((EXEC_RUN | EXEC_HOMING)) == (EXEC_RUN | EXEC_HOMING) && (limits_ref & limits)) { // changed limit is from the current mask - if((limits_diff & limits_ref)) + if ((limits_diff & limits_ref)) { // lock steps on the current limits itp_lock_stepper(limits); @@ -123,6 +126,7 @@ MCU_IO_CALLBACK void mcu_limits_changed_cb(void) } itp_lock_stepper(0); // unlocks axis +#endif itp_stop(); cnc_set_exec_state(EXEC_LIMITS); #ifdef ENABLE_IO_ALARM_DEBUG @@ -285,10 +289,12 @@ MCU_IO_CALLBACK void mcu_inputs_changed_cb(void) } } +#ifdef ENABLE_MULTI_STEP_HOMING void io_lock_limits(uint8_t limitmask) { io_lock_limits_mask = limitmask; } +#endif void io_invert_limits(uint8_t limitmask) { diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index 7bad96b2a..b4cebff4e 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -60,7 +60,9 @@ extern "C" #endif // inputs + #ifdef ENABLE_MULTI_STEP_HOMING void io_lock_limits(uint8_t limitmask); + #endif void io_invert_limits(uint8_t limitmask); uint8_t io_get_limits(void); uint8_t io_get_controls(void); diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 0ebf0885e..7c6a59500 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -704,10 +704,9 @@ void mc_home_axis_finalize(homing_status_t *status) } #endif -uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) +uint8_t mc_home_axis(uint8_t axis_mask, uint8_t axis_limit) { float target[AXIS_COUNT]; - uint8_t axis_mask = (1 << axis); motion_data_t block_data = {0}; uint8_t limits_flags; #ifdef ENABLE_MOTION_CONTROL_MODULES @@ -724,8 +723,10 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) homing_status.status = STATUS_CRITICAL_FAIL; #endif - // locks limits to accept axis limit mask only or else throw error +// locks limits to accept axis limit mask only or else throw error +#ifdef ENABLE_MULTI_STEP_HOMING io_lock_limits(axis_limit); +#endif io_invert_limits(0); cnc_unlock(true); @@ -735,19 +736,28 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) return STATUS_CRITICAL_FAIL; } - float max_home_dist; - max_home_dist = -g_settings.max_distance[axis] * 1.5f; + // sync's the motion control with the real time position + mc_sync_position(); + mc_get_position(target); - // checks homing dir - if (g_settings.homing_dir_invert_mask & axis_mask) + // set's the homing distance for each axis + for (uint8_t i = 0; i < AXIS_COUNT; i++) { - max_home_dist = -max_home_dist; + uint8_t imask = (1 << i); + if (imask & axis_mask) + { + float max_home_dist; + max_home_dist = -g_settings.max_distance[i] * 1.5f; + + // checks homing dir + if (g_settings.homing_dir_invert_mask & axis_mask) + { + max_home_dist = -max_home_dist; + } + target[i] += max_home_dist; + } } - // sync's the motion control with the real time position - mc_sync_position(); - mc_get_position(target); - target[axis] += max_home_dist; // initializes planner block data // memset(block_data.steps, 0, sizeof(block_data.steps)); // block_data.steps[axis] = max_home_dist; @@ -782,18 +792,28 @@ uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit) return STATUS_CRITICAL_FAIL; } - // back off from switch at lower speed - max_home_dist = g_settings.homing_offset * 5.0f; - // sync's the motion control with the real time position mc_sync_position(); mc_get_position(target); - if (g_settings.homing_dir_invert_mask & axis_mask) + + // set's the homing distance for each axis + for (uint8_t i = 0; i < AXIS_COUNT; i++) { - max_home_dist = -max_home_dist; + uint8_t imask = (1 << i); + if (imask & axis_mask) + { + // back off from switch at lower speed + float max_home_dist = g_settings.homing_offset * 5.0f; + + // checks homing dir + if (g_settings.homing_dir_invert_mask & axis_mask) + { + max_home_dist = -max_home_dist; + } + target[i] += max_home_dist; + } } - target[axis] += max_home_dist; block_data.feed = g_settings.homing_slow_feed_rate; // block_data.steps[axis] = max_home_dist; // unlocks the machine for next motion (this will clear the EXEC_UNHOMED flag diff --git a/uCNC/src/core/motion_control.h b/uCNC/src/core/motion_control.h index 103e5b7a1..4a88fad9d 100644 --- a/uCNC/src/core/motion_control.h +++ b/uCNC/src/core/motion_control.h @@ -107,7 +107,7 @@ extern "C" uint8_t mc_update_tools(motion_data_t *block_data); // mixed/special motions - uint8_t mc_home_axis(uint8_t axis, uint8_t axis_limit); + uint8_t mc_home_axis(uint8_t axis_mask, uint8_t axis_limit); #ifndef DISABLE_PROBING_SUPPORT uint8_t mc_probe(float *target, uint8_t flags, motion_data_t *block_data); #endif diff --git a/uCNC/src/hal/kinematics/kinematic.h b/uCNC/src/hal/kinematics/kinematic.h index e0eb82922..e321063d5 100644 --- a/uCNC/src/hal/kinematics/kinematic.h +++ b/uCNC/src/hal/kinematics/kinematic.h @@ -37,6 +37,7 @@ extern "C" #define KINEMATIC_HOMING_ERROR_X 1 #define KINEMATIC_HOMING_ERROR_Y 2 +#define KINEMATIC_HOMING_ERROR_XY (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y) #define KINEMATIC_HOMING_ERROR_Z 4 #define KINEMATIC_HOMING_ERROR_A 8 #define KINEMATIC_HOMING_ERROR_B 16 diff --git a/uCNC/src/hal/kinematics/kinematic_cartesian.c b/uCNC/src/hal/kinematics/kinematic_cartesian.c index 884071a71..5abeff8dd 100644 --- a/uCNC/src/hal/kinematics/kinematic_cartesian.c +++ b/uCNC/src/hal/kinematics/kinematic_cartesian.c @@ -46,60 +46,71 @@ void kinematics_apply_forward(int32_t *steps, float *axis) uint8_t kinematics_home(void) { float target[AXIS_COUNT]; - + #ifndef DISABLE_ALL_LIMITS -#ifndef DISABLE_Z_HOMING -#if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) - if (mc_home_axis(AXIS_Z, LINACT2_LIMIT_MASK)) +#if AXIS_Z_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Z_HOMING_MASK, LINACT2_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } #endif -#endif -#ifndef DISABLE_X_HOMING -#if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) - if (mc_home_axis(AXIS_X, LINACT0_LIMIT_MASK)) +#ifndef ENABLE_XY_SIMULTANEOUS_HOMING + +#if AXIS_X_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK, LINACT0_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_X; } #endif + +#if AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Y_HOMING_MASK, LINACT1_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_Y; + } #endif -#ifndef DISABLE_Y_HOMING -#if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) - if (mc_home_axis(AXIS_Y, LINACT1_LIMIT_MASK)) +#else + +#if AXIS_X_HOMING_MASK != 0 && AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK | AXIS_Y_HOMING_MASK, LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_XY; + } +#elif AXIS_X_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK, LINACT0_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_X; + } +#elif AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Y_HOMING_MASK, LINACT1_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Y; } #endif + #endif -#ifndef DISABLE_A_HOMING -#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) +#if AXIS_A_HOMING_MASK != 0 + if (mc_home_axis(AXIS_A_HOMING_MASK, LINACT3_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_A; } #endif -#endif -#ifndef DISABLE_B_HOMING -#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) +#if AXIS_B_HOMING_MASK != 0 + if (mc_home_axis(AXIS_B_HOMING_MASK, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } #endif -#endif -#ifndef DISABLE_C_HOMING -#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) +#if AXIS_C_HOMING_MASK != 0 + if (mc_home_axis(AXIS_C_HOMING_MASK, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } -#endif #endif cnc_unlock(true); @@ -126,11 +137,11 @@ uint8_t kinematics_home(void) #ifdef SET_ORIGIN_AT_HOME_POS memset(target, 0, sizeof(target)); #else - for (uint8_t i = AXIS_COUNT; i != 0;) - { - i--; - target[i] = (!(g_settings.homing_dir_invert_mask & (1 << i)) ? 0 : g_settings.max_distance[i]); - } +for (uint8_t i = AXIS_COUNT; i != 0;) +{ + i--; + target[i] = (!(g_settings.homing_dir_invert_mask & (1 << i)) ? 0 : g_settings.max_distance[i]); +} #endif // reset position diff --git a/uCNC/src/hal/kinematics/kinematic_corexy.c b/uCNC/src/hal/kinematics/kinematic_corexy.c index 54b8bf41d..bda7dd7a7 100644 --- a/uCNC/src/hal/kinematics/kinematic_corexy.c +++ b/uCNC/src/hal/kinematics/kinematic_corexy.c @@ -58,58 +58,69 @@ uint8_t kinematics_home(void) float target[AXIS_COUNT]; #ifndef DISABLE_ALL_LIMITS -#ifndef DISABLE_Z_HOMING -#if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) - if (mc_home_axis(AXIS_Z, LINACT2_LIMIT_MASK)) +#if AXIS_Z_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Z_HOMING_MASK, LINACT2_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } #endif -#endif -#ifndef DISABLE_X_HOMING -#if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) - if (mc_home_axis(AXIS_X, LINACT0_LIMIT_MASK)) +#ifndef ENABLE_XY_SIMULTANEOUS_HOMING + +#if AXIS_X_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK, LINACT0_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_X; } #endif + +#if AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Y_HOMING_MASK, LINACT1_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_Y; + } #endif -#ifndef DISABLE_Y_HOMING -#if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) - if (mc_home_axis(AXIS_Y, LINACT1_LIMIT_MASK)) +#else + +#if AXIS_X_HOMING_MASK != 0 && AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK | AXIS_Y_HOMING_MASK, LINACT0_LIMIT_MASK | LINACT1_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_XY; + } +#elif AXIS_X_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK, LINACT0_LIMIT_MASK)) + { + return KINEMATIC_HOMING_ERROR_X; + } +#elif AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Y_HOMING_MASK, LINACT1_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Y; } #endif + #endif -#ifndef DISABLE_A_HOMING -#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) +#if AXIS_A_HOMING_MASK != 0 + if (mc_home_axis(AXIS_A_HOMING_MASK, LINACT3_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_A; } #endif -#endif -#ifndef DISABLE_B_HOMING -#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) +#if AXIS_B_HOMING_MASK != 0 + if (mc_home_axis(AXIS_B_HOMING_MASK, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } #endif -#endif -#ifndef DISABLE_C_HOMING -#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) +#if AXIS_C_HOMING_MASK != 0 + if (mc_home_axis(AXIS_C_HOMING_MASK, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } -#endif #endif cnc_unlock(true); diff --git a/uCNC/src/hal/kinematics/kinematic_delta.c b/uCNC/src/hal/kinematics/kinematic_delta.c index 23834ab74..cf9985e63 100644 --- a/uCNC/src/hal/kinematics/kinematic_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_delta.c @@ -335,36 +335,31 @@ uint8_t kinematics_home(void) // sync interpolator to new position (motion homing syncs remaining systems) itp_reset_rt_position(axis); - if (mc_home_axis(AXIS_Z, LIMITS_DELTA_MASK)) + if (mc_home_axis(AXIS_Z_MASK, LIMITS_DELTA_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } -#ifndef DISABLE_A_HOMING -#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) + +#if AXIS_A_HOMING_MASK != 0 + if (mc_home_axis(AXIS_A_HOMING_MASK, LINACT3_LIMIT_MASK)) { - return (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y | KINEMATIC_HOMING_ERROR_Z); + return KINEMATIC_HOMING_ERROR_A; } #endif -#endif -#ifndef DISABLE_B_HOMING -#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) +#if AXIS_B_HOMING_MASK != 0 + if (mc_home_axis(AXIS_B_HOMING_MASK, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } #endif -#endif -#ifndef DISABLE_C_HOMING -#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) +#if AXIS_C_HOMING_MASK != 0 + if (mc_home_axis(AXIS_C_HOMING_MASK, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } -#endif #endif // unlocks the machine to go to offset diff --git a/uCNC/src/hal/kinematics/kinematic_linear_delta.c b/uCNC/src/hal/kinematics/kinematic_linear_delta.c index 8b8d43c47..3fe511ba0 100644 --- a/uCNC/src/hal/kinematics/kinematic_linear_delta.c +++ b/uCNC/src/hal/kinematics/kinematic_linear_delta.c @@ -145,36 +145,31 @@ void kinematics_apply_forward(int32_t *steps, float *axis) uint8_t kinematics_home(void) { - if (mc_home_axis(AXIS_Z, LIMITS_DELTA_MASK)) + if (mc_home_axis(AXIS_Z_MASK, LIMITS_DELTA_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } -#ifndef DISABLE_A_HOMING -#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LINACT3_LIMIT_MASK)) + +#if AXIS_A_HOMING_MASK != 0 + if (mc_home_axis(AXIS_A_HOMING_MASK, LINACT3_LIMIT_MASK)) { - return (KINEMATIC_HOMING_ERROR_X|KINEMATIC_HOMING_ERROR_Y|KINEMATIC_HOMING_ERROR_Z); + return KINEMATIC_HOMING_ERROR_A; } #endif -#endif -#ifndef DISABLE_B_HOMING -#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LINACT4_LIMIT_MASK)) +#if AXIS_B_HOMING_MASK != 0 + if (mc_home_axis(AXIS_B_HOMING_MASK, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } #endif -#endif -#ifndef DISABLE_C_HOMING -#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LINACT5_LIMIT_MASK)) +#if AXIS_C_HOMING_MASK != 0 + if (mc_home_axis(AXIS_C_HOMING_MASK, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } -#endif #endif // unlocks the machine to go to offset From 12ab1db22c7179caf2e83131508d79837b6470bc Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 14 Aug 2023 09:57:46 +0100 Subject: [PATCH 088/168] generic autolevel enable option --- uCNC/cnc_hal_config.h | 26 +++++++++++++------------- uCNC/src/cnc_hal_config_helper.h | 2 +- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index e3d9c7f8e..578a528b7 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -152,28 +152,28 @@ extern "C" * LIMITx - - C B A Z&Z2 Y&Y2 X&X2 * * LINACT with multiple STEP IO pulse all those IO in sync, but when homing it can stop independently as it hits the correspondent limit until all motors reach the desired home position. - * To achieve that each each LIMITx_IO_MASK should be set to the corresponding STEP that it controls + * To achieve that each each LIMITx_IO_MASK should be set to the corresponding STEP IO MASK that it controls * * For example to use STEP0 and STEP6 to drive the AXIS_X/LINACT0 you need to configure the correct LINACT0_IO_MASK and then to make LIMIT_X stop STEP0 and LIMIT_X2 stop STEP6 you need - * to reassing LIMIT_X2 to STEP6 like this + * to reassing LIMIT_X2 to STEP6 IO MASK like this * * #define LIMIT_X2_IO_MASK STEP6_IO_MASK * * **/ -// #define ENABLE_X_AUTOLEVEL -#ifdef ENABLE_X_AUTOLEVEL -#define LIMIT_X2_IO_MASK STEP5_IO_MASK -#endif +// #define ENABLE_AXIS_AUTOLEVEL -// #define ENABLE_Y_AUTOLEVEL -#ifdef ENABLE_Y_AUTOLEVEL -#define LIMIT_Y2_IO_MASK STEP6_IO_MASK -#endif +#ifdef ENABLE_AXIS_AUTOLEVEL + +// Uncomment to modify X2 limit mask value to match the X2 motor +// #define LIMIT_X2_IO_MASK STEP5_IO_MASK + +// Uncomment to modify Y2 limit mask value to match the Y2 motor +// #define LIMIT_Y2_IO_MASK STEP6_IO_MASK + +// Uncomment to modify Y2 limit mask value to match the Y2 motor +// #define LIMIT_Z2_IO_MASK STEP7_IO_MASK -// #define ENABLE_Z_AUTOLEVEL -#ifdef ENABLE_Z_AUTOLEVEL -#define LIMIT_Z2_IO_MASK STEP7_IO_MASK #endif /** diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 1efd452f5..c55d27d03 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2002,7 +2002,7 @@ typedef uint16_t step_t; #error "Invalid config option STATUS_AUTOMATIC_REPORT_INTERVAL must be set between 0 and 1000" #endif -#if defined(ENABLE_X_AUTOLEVEL) || defined(ENABLE_Y_AUTOLEVEL) || defined(ENABLE_Z_AUTOLEVEL) || defined(IS_DELTA_KINEMATICS) || defined(ENABLE_XY_SIMULTANEOUS_HOMING) +#if defined(ENABLE_AXIS_AUTOLEVEL) || defined(IS_DELTA_KINEMATICS) || defined(ENABLE_XY_SIMULTANEOUS_HOMING) #define ENABLE_MULTI_STEP_HOMING #endif From a107cf450f59f1303d9c1a7e6779d55126ecced4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 16 Aug 2023 10:45:06 +0100 Subject: [PATCH 089/168] fixed 74hc595 redeclaration --- uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h | 3 --- uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h | 3 --- uCNC/src/modules/ic74hc595.c | 1 - 3 files changed, 7 deletions(-) diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h index 11f6e3e8f..cdac4e770 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h @@ -98,9 +98,6 @@ extern "C" //cs #define DOUT6_BIT 27 -// include the IO expander -#include "../../../modules/ic74hc595.h" - #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h index 371e5dcc5..21a242812 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h @@ -120,9 +120,6 @@ extern "C" #define DIN18_BIT 14 #define DIN18_PULLUP -// include the IO expander -#include "../../../modules/ic74hc595.h" - #ifdef __cplusplus } #endif diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index 0c069b83c..eef9e29d2 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -18,7 +18,6 @@ */ #include "../cnc.h" -#include "ic74hc595.h" #include #include From 11dd9181db43cc2aa15245c8d7bee97bf458011c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 16 Aug 2023 11:59:02 +0100 Subject: [PATCH 090/168] TMC address patch - applied #466 --- uCNC/cnc_hal_config.h | 8 ++++++++ uCNC/src/modules/tmcdriver.c | 16 ++++++++-------- 2 files changed, 16 insertions(+), 8 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index c69b503a7..6be66142f 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -344,6 +344,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER0_STALL_SENSITIVITY 10 +#define STEPPER0_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER1_HAS_TMC @@ -371,6 +372,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER1_STALL_SENSITIVITY 10 +#define STEPPER1_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER2_HAS_TMC @@ -398,6 +400,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER2_STALL_SENSITIVITY 10 +#define STEPPER2_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER3_HAS_TMC @@ -425,6 +428,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER3_STALL_SENSITIVITY 10 +#define STEPPER3_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER4_HAS_TMC @@ -452,6 +456,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER4_STALL_SENSITIVITY 10 +#define STEPPER4_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER5_HAS_TMC @@ -479,6 +484,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER5_STALL_SENSITIVITY 10 +#define STEPPER5_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER6_HAS_TMC @@ -506,6 +512,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER6_STALL_SENSITIVITY 10 +#define STEPPER6_UART_ADDRESS 0 #endif // uncomment to enable trinamic driver // #define STEPPER7_HAS_TMC @@ -533,6 +540,7 @@ extern "C" // this value must be set between 0 and 255 for TMC2209 // if driver does not support stallGuard this will be ignored #define STEPPER7_STALL_SENSITIVITY 10 +#define STEPPER7_UART_ADDRESS 0 #endif /** diff --git a/uCNC/src/modules/tmcdriver.c b/uCNC/src/modules/tmcdriver.c index da9e08cff..d826b6aec 100644 --- a/uCNC/src/modules/tmcdriver.c +++ b/uCNC/src/modules/tmcdriver.c @@ -1275,7 +1275,7 @@ DECL_MODULE(tmcdriver) #ifdef STEPPER0_HAS_TMC tmc0_driver.type = STEPPER0_DRIVER_TYPE; - tmc0_driver.slave = 0; + tmc0_driver.slave = STEPPER0_UART_ADDRESS; tmc0_driver.init = NULL; tmc0_driver.rw = &tmc0_rw; tmc0_settings.rms_current = STEPPER0_CURRENT_MA; @@ -1297,7 +1297,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER1_HAS_TMC tmc1_driver.type = STEPPER1_DRIVER_TYPE; - tmc1_driver.slave = 0; + tmc1_driver.slave = STEPPER1_UART_ADDRESS; tmc1_driver.init = NULL; tmc1_driver.rw = &tmc1_rw; tmc1_settings.rms_current = STEPPER1_CURRENT_MA; @@ -1319,7 +1319,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER2_HAS_TMC tmc2_driver.type = STEPPER2_DRIVER_TYPE; - tmc2_driver.slave = 0; + tmc2_driver.slave = STEPPER2_UART_ADDRESS; tmc2_driver.init = NULL; tmc2_driver.rw = &tmc2_rw; tmc2_settings.rms_current = STEPPER2_CURRENT_MA; @@ -1341,7 +1341,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER3_HAS_TMC tmc3_driver.type = STEPPER3_DRIVER_TYPE; - tmc3_driver.slave = 0; + tmc3_driver.slave = STEPPER3_UART_ADDRESS; tmc3_driver.init = NULL; tmc3_driver.rw = &tmc3_rw; tmc3_settings.rms_current = STEPPER3_CURRENT_MA; @@ -1363,7 +1363,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER4_HAS_TMC tmc4_driver.type = STEPPER4_DRIVER_TYPE; - tmc4_driver.slave = 0; + tmc4_driver.slave = STEPPER4_UART_ADDRESS; tmc4_driver.init = NULL; tmc4_driver.rw = &tmc4_rw; tmc4_settings.rms_current = STEPPER4_CURRENT_MA; @@ -1385,7 +1385,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER5_HAS_TMC tmc5_driver.type = STEPPER5_DRIVER_TYPE; - tmc5_driver.slave = 0; + tmc5_driver.slave = STEPPER5_UART_ADDRESS; tmc5_driver.init = NULL; tmc5_driver.rw = &tmc5_rw; tmc5_settings.rms_current = STEPPER5_CURRENT_MA; @@ -1407,7 +1407,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER6_HAS_TMC tmc6_driver.type = STEPPER6_DRIVER_TYPE; - tmc6_driver.slave = 0; + tmc6_driver.slave = STEPPER6_UART_ADDRESS; tmc6_driver.init = NULL; tmc6_driver.rw = &tmc6_rw; tmc6_settings.rms_current = STEPPER6_CURRENT_MA; @@ -1429,7 +1429,7 @@ DECL_MODULE(tmcdriver) #endif #ifdef STEPPER7_HAS_TMC tmc7_driver.type = STEPPER7_DRIVER_TYPE; - tmc7_driver.slave = 0; + tmc7_driver.slave = STEPPER7_UART_ADDRESS; tmc7_driver.init = NULL; tmc7_driver.rw = &tmc7_rw; tmc7_settings.rms_current = STEPPER7_CURRENT_MA; From 8b8632fc13d7e5a2e817aa0bef8d0641f1011e45 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 16 Aug 2023 16:47:15 +0100 Subject: [PATCH 091/168] 74HC595 testings on virtual environment --- uCNC/src/hal/mcus/virtual/mcumap_virtual.h | 32 ++++++++++++++++++++++ uCNC/src/modules/ic74hc595.c | 4 +++ uCNC/src/modules/system_menu.c | 1 + 3 files changed, 37 insertions(+) diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index a0df47bd3..d0ec44ec0 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -49,7 +49,10 @@ #define MCU_HAS_UART +//#define EMULATE_74HC595 + // joints step/dir pins +#ifndef EMULATE_74HC595 #define STEP0 1 #define DIO1 1 #define STEP1 2 @@ -98,6 +101,35 @@ #define DIO23 23 #define STEP7_EN 24 #define DIO24 24 +#else +#define IC74HC595_COUNT 4 +#define STEP0_IO_OFFSET 0 +#define STEP1_IO_OFFSET 1 +#define STEP2_IO_OFFSET 2 +#define STEP3_IO_OFFSET 3 +#define STEP4_IO_OFFSET 4 +#define STEP5_IO_OFFSET 5 +#define STEP6_IO_OFFSET 6 +#define STEP7_IO_OFFSET 7 +#define DIR0_IO_OFFSET 8 +#define DIR1_IO_OFFSET 9 +#define DIR2_IO_OFFSET 10 +#define DIR3_IO_OFFSET 11 +#define DIR4_IO_OFFSET 12 +#define DIR5_IO_OFFSET 13 +#define DIR6_IO_OFFSET 14 +#define DIR7_IO_OFFSET 15 +#define STEP0_EN_IO_OFFSET 16 +#define STEP1_EN_IO_OFFSET 17 +#define STEP2_EN_IO_OFFSET 18 +#define STEP3_EN_IO_OFFSET 19 +#define STEP4_EN_IO_OFFSET 20 +#define STEP5_EN_IO_OFFSET 21 +#define STEP6_EN_IO_OFFSET 22 +#define STEP7_EN_IO_OFFSET 23 +//#define PWM0_IO_OFFSET 24 +#define mcu_softpwm_freq_config(x) 7 +#endif #define PWM0 25 #define DIO25 25 #define PWM1 26 diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index eef9e29d2..3d7b5f900 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -176,6 +176,10 @@ FORCEINLINE void ic74hc595_set_steps(uint8_t mask) FORCEINLINE void ic74hc595_toggle_steps(uint8_t mask) { + if (!mask) + { + return; + } #if ASSERT_IO_OFFSET(STEP0_IO_OFFSET) if (mask & (1 << 0)) { diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 791a1a5bd..a4274424f 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -16,6 +16,7 @@ See the GNU General Public License for more details. */ +#include "../cnc.h" #include "system_menu.h" #include From d72f7fa0c109317e6a4cc6bfc00d49afb394a16d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 16 Aug 2023 22:26:32 +0100 Subject: [PATCH 092/168] reduced calls to IO HAL in stepgen - reduced calls to IO HAL in stepgen - fixed 74hc595 io call implicit declaration warnings --- uCNC/src/cnc.h | 2 +- uCNC/src/core/interpolator.c | 2 +- uCNC/src/core/io_control.c | 4 ++++ uCNC/src/core/io_control.h | 2 +- uCNC/src/hal/io_hal.h | 6 ++++++ uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 3 --- 6 files changed, 13 insertions(+), 6 deletions(-) diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index 6a88fd33a..0be60b11f 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -146,13 +146,13 @@ extern "C" #include "utils.h" // extension modules #include "module.h" +#include "hal/io_hal.h" #include "interface/defaults.h" #include "interface/grbl_interface.h" #include "interface/settings.h" #include "interface/serial.h" #include "interface/protocol.h" #include "core/io_control.h" -#include "core/io_control.h" #include "core/parser.h" #include "core/motion_control.h" #include "core/planner.h" diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index ca47096c1..b0d6a00e7 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -929,7 +929,7 @@ MCU_CALLBACK void mcu_step_cb(void) // loads a new segment itp_rt_sgm = &itp_sgm_data[itp_sgm_data_read]; cnc_set_exec_state(EXEC_RUN); - if (itp_rt_sgm->block != NULL) + if (itp_rt_sgm->remaining_steps) { #if (DSS_MAX_OVERSAMPLING != 0) if (itp_rt_sgm->next_dss != 0) diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 17b786802..95effb71d 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -595,6 +595,10 @@ void io_toggle_steps(uint8_t mask) // #ifdef ENABLE_IO_MODULES // EVENT_INVOKE(toggle_steps, &mask); // #endif + if (!mask) + { + return; + } #ifdef IC74HC595_HAS_STEPS ic74hc595_toggle_steps(mask); diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index af9d6eeb4..e7c403239 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -31,7 +31,7 @@ extern "C" #endif #include "../module.h" -#include "../modules/ic74hc595.h" +// #include "../modules/ic74hc595.h" #include "../hal/io_hal.h" #include #include diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index dc5212816..500f80e3c 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -7,6 +7,8 @@ extern "C" { #endif +#include "../modules/ic74hc595.h" + /*IO HAL*/ #if ASSERT_PIN_IO(STEP0) #define io1_config_output mcu_config_output(STEP0) @@ -4770,6 +4772,10 @@ extern "C" #endif /*PWM*/ +extern uint8_t g_soft_pwm_res; +extern uint8_t g_io_soft_pwm[16]; +extern uint8_t mcu_softpwm_freq_config(uint16_t freq); + #if ASSERT_PIN_IO(PWM0) #define io25_config_pwm(freq) mcu_config_pwm(PWM0, freq) #define io25_set_pwm(value) mcu_set_pwm(PWM0, value) diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index d6f1d533b..f507eb945 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2833,9 +2833,6 @@ extern "C" __indirect__(X, OUTREG)->OUT ^= (1UL << (0x1F & __indirect__(X, BIT))); \ } -#ifdef IC74HC595_HAS_PWMS - extern uint8_t mcu_softpwm_freq_config(uint16_t freq); -#endif #define mcu_config_pwm(X, Y) \ { \ ledc_timer_config_t pwmtimer = {0}; \ From e9ef57ce61fae4f72fe15544e1cc26096da110f2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 18 Aug 2023 17:50:23 +0100 Subject: [PATCH 093/168] simplify 74HC595 with new IO HAL --- uCNC/src/core/io_control.c | 360 ++++++++---------- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 61 ++-- uCNC/src/modules/ic74hc595.c | 548 ---------------------------- uCNC/src/modules/ic74hc595.h | 6 - 4 files changed, 179 insertions(+), 796 deletions(-) diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 95effb71d..5ac0cfb4f 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -503,91 +503,91 @@ void io_set_steps(uint8_t mask) // EVENT_INVOKE(set_steps, &mask); // #endif -#ifdef IC74HC595_HAS_STEPS - ic74hc595_set_steps(mask); -#endif - -#if ASSERT_PIN_IO(STEP0) +#if ASSERT_PIN(STEP0) if (mask & STEP0_MASK) { - mcu_set_output(STEP0); + io_set_output(STEP0); } else { - mcu_clear_output(STEP0); + io_clear_output(STEP0); } #endif -#if ASSERT_PIN_IO(STEP1) +#if ASSERT_PIN(STEP1) if (mask & STEP1_MASK) { - mcu_set_output(STEP1); + io_set_output(STEP1); } else { - mcu_clear_output(STEP1); + io_clear_output(STEP1); } #endif -#if ASSERT_PIN_IO(STEP2) +#if ASSERT_PIN(STEP2) if (mask & STEP2_MASK) { - mcu_set_output(STEP2); + io_set_output(STEP2); } else { - mcu_clear_output(STEP2); + io_clear_output(STEP2); } #endif -#if ASSERT_PIN_IO(STEP3) +#if ASSERT_PIN(STEP3) if (mask & STEP3_MASK) { - mcu_set_output(STEP3); + io_set_output(STEP3); } else { - mcu_clear_output(STEP3); + io_clear_output(STEP3); } #endif -#if ASSERT_PIN_IO(STEP4) +#if ASSERT_PIN(STEP4) if (mask & STEP4_MASK) { - mcu_set_output(STEP4); + io_set_output(STEP4); } else { - mcu_clear_output(STEP4); + io_clear_output(STEP4); } #endif -#if ASSERT_PIN_IO(STEP5) +#if ASSERT_PIN(STEP5) if (mask & STEP5_MASK) { - mcu_set_output(STEP5); + io_set_output(STEP5); } else { - mcu_clear_output(STEP5); + io_clear_output(STEP5); } #endif -#if ASSERT_PIN_IO(STEP6) +#if ASSERT_PIN(STEP6) if (mask & STEP6_MASK) { - mcu_set_output(STEP6); + io_set_output(STEP6); } else { - mcu_clear_output(STEP6); + io_clear_output(STEP6); } #endif -#if ASSERT_PIN_IO(STEP7) +#if ASSERT_PIN(STEP7) if (mask & STEP7_MASK) { - mcu_set_output(STEP7); + io_set_output(STEP7); } else { - mcu_clear_output(STEP7); + io_clear_output(STEP7); } #endif + +#ifdef IC74HC595_HAS_STEPS + ic74hc595_shift_io_pins(); +#endif } void io_toggle_steps(uint8_t mask) @@ -600,58 +600,58 @@ void io_toggle_steps(uint8_t mask) return; } -#ifdef IC74HC595_HAS_STEPS - ic74hc595_toggle_steps(mask); -#endif - -#if ASSERT_PIN_IO(STEP0) +#if ASSERT_PIN(STEP0) if (mask & STEP0_MASK) { - mcu_toggle_output(STEP0); + io_toggle_output(STEP0); } #endif -#if ASSERT_PIN_IO(STEP1) +#if ASSERT_PIN(STEP1) if (mask & STEP1_MASK) { - mcu_toggle_output(STEP1); + io_toggle_output(STEP1); } #endif -#if ASSERT_PIN_IO(STEP2) +#if ASSERT_PIN(STEP2) if (mask & STEP2_MASK) { - mcu_toggle_output(STEP2); + io_toggle_output(STEP2); } #endif -#if ASSERT_PIN_IO(STEP3) +#if ASSERT_PIN(STEP3) if (mask & STEP3_MASK) { - mcu_toggle_output(STEP3); + io_toggle_output(STEP3); } #endif -#if ASSERT_PIN_IO(STEP4) +#if ASSERT_PIN(STEP4) if (mask & STEP4_MASK) { - mcu_toggle_output(STEP4); + io_toggle_output(STEP4); } #endif -#if ASSERT_PIN_IO(STEP5) +#if ASSERT_PIN(STEP5) if (mask & STEP5_MASK) { - mcu_toggle_output(STEP5); + io_toggle_output(STEP5); } #endif -#if ASSERT_PIN_IO(STEP6) +#if ASSERT_PIN(STEP6) if (mask & STEP6_MASK) { - mcu_toggle_output(STEP6); + io_toggle_output(STEP6); } #endif -#if ASSERT_PIN_IO(STEP7) +#if ASSERT_PIN(STEP7) if (mask & STEP7_MASK) { - mcu_toggle_output(STEP7); + io_toggle_output(STEP7); } #endif + +#ifdef IC74HC595_HAS_STEPS + ic74hc595_shift_io_pins(); +#endif } void io_set_dirs(uint8_t mask) @@ -662,90 +662,90 @@ void io_set_dirs(uint8_t mask) // EVENT_INVOKE(set_dirs, &mask); // #endif -#ifdef IC74HC595_HAS_DIRS - ic74hc595_set_dirs(mask); -#endif - -#if ASSERT_PIN_IO(DIR0) +#if ASSERT_PIN(DIR0) if (mask & DIR0_MASK) { - mcu_set_output(DIR0); + io_set_output(DIR0); } else { - mcu_clear_output(DIR0); + io_clear_output(DIR0); } #endif -#if ASSERT_PIN_IO(DIR1) +#if ASSERT_PIN(DIR1) if (mask & DIR1_MASK) { - mcu_set_output(DIR1); + io_set_output(DIR1); } else { - mcu_clear_output(DIR1); + io_clear_output(DIR1); } #endif -#if ASSERT_PIN_IO(DIR2) +#if ASSERT_PIN(DIR2) if (mask & DIR2_MASK) { - mcu_set_output(DIR2); + io_set_output(DIR2); } else { - mcu_clear_output(DIR2); + io_clear_output(DIR2); } #endif -#if ASSERT_PIN_IO(DIR3) +#if ASSERT_PIN(DIR3) if (mask & DIR3_MASK) { - mcu_set_output(DIR3); + io_set_output(DIR3); } else { - mcu_clear_output(DIR3); + io_clear_output(DIR3); } #endif -#if ASSERT_PIN_IO(DIR4) +#if ASSERT_PIN(DIR4) if (mask & DIR4_MASK) { - mcu_set_output(DIR4); + io_set_output(DIR4); } else { - mcu_clear_output(DIR4); + io_clear_output(DIR4); } #endif -#if ASSERT_PIN_IO(DIR5) +#if ASSERT_PIN(DIR5) if (mask & DIR5_MASK) { - mcu_set_output(DIR5); + io_set_output(DIR5); } else { - mcu_clear_output(DIR5); + io_clear_output(DIR5); } #endif -#if ASSERT_PIN_IO(DIR6) +#if ASSERT_PIN(DIR6) if (mask & DIR6_MASK) { - mcu_set_output(DIR6); + io_set_output(DIR6); } else { - mcu_clear_output(DIR6); + io_clear_output(DIR6); } #endif -#if ASSERT_PIN_IO(DIR7) +#if ASSERT_PIN(DIR7) if (mask & DIR7_MASK) { - mcu_set_output(DIR7); + io_set_output(DIR7); } else { - mcu_clear_output(DIR7); + io_clear_output(DIR7); } #endif + +#ifdef IC74HC595_HAS_DIRS + ic74hc595_shift_io_pins(); +#endif } void io_enable_steppers(uint8_t mask) @@ -754,90 +754,90 @@ void io_enable_steppers(uint8_t mask) // EVENT_INVOKE(enable_steppers, &mask); // #endif -#ifdef IC74HC595_HAS_STEPS_EN - ic74hc595_enable_steppers(mask); -#endif - -#if ASSERT_PIN_IO(STEP0_EN) +#if ASSERT_PIN(STEP0_EN) if (mask & 0x01) { - mcu_set_output(STEP0_EN); + io_set_output(STEP0_EN); } else { - mcu_clear_output(STEP0_EN); + io_clear_output(STEP0_EN); } #endif -#if ASSERT_PIN_IO(STEP1_EN) +#if ASSERT_PIN(STEP1_EN) if (mask & 0x02) { - mcu_set_output(STEP1_EN); + io_set_output(STEP1_EN); } else { - mcu_clear_output(STEP1_EN); + io_clear_output(STEP1_EN); } #endif -#if ASSERT_PIN_IO(STEP2_EN) +#if ASSERT_PIN(STEP2_EN) if (mask & 0x04) { - mcu_set_output(STEP2_EN); + io_set_output(STEP2_EN); } else { - mcu_clear_output(STEP2_EN); + io_clear_output(STEP2_EN); } #endif -#if ASSERT_PIN_IO(STEP3_EN) +#if ASSERT_PIN(STEP3_EN) if (mask & 0x08) { - mcu_set_output(STEP3_EN); + io_set_output(STEP3_EN); } else { - mcu_clear_output(STEP3_EN); + io_clear_output(STEP3_EN); } #endif -#if ASSERT_PIN_IO(STEP4_EN) +#if ASSERT_PIN(STEP4_EN) if (mask & 0x10) { - mcu_set_output(STEP4_EN); + io_set_output(STEP4_EN); } else { - mcu_clear_output(STEP4_EN); + io_clear_output(STEP4_EN); } #endif -#if ASSERT_PIN_IO(STEP5_EN) +#if ASSERT_PIN(STEP5_EN) if (mask & 0x20) { - mcu_set_output(STEP5_EN); + io_set_output(STEP5_EN); } else { - mcu_clear_output(STEP5_EN); + io_clear_output(STEP5_EN); } #endif -#if ASSERT_PIN_IO(STEP6_EN) +#if ASSERT_PIN(STEP6_EN) if (mask & 0x40) { - mcu_set_output(STEP6_EN); + io_set_output(STEP6_EN); } else { - mcu_clear_output(STEP6_EN); + io_clear_output(STEP6_EN); } #endif -#if ASSERT_PIN_IO(STEP7_EN) +#if ASSERT_PIN(STEP7_EN) if (mask & 0x80) { - mcu_set_output(STEP7_EN); + io_set_output(STEP7_EN); } else { - mcu_clear_output(STEP7_EN); + io_clear_output(STEP7_EN); } #endif + +#ifdef IC74HC595_HAS_STEPS_EN + ic74hc595_shift_io_pins(); +#endif } #if defined(MCU_HAS_SOFT_PWM_TIMER) || defined(IC74HC595_HAS_PWMS) @@ -863,174 +863,114 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM0) if (pwm_counter > g_io_soft_pwm[0] || !g_io_soft_pwm[0]) { -#if ASSERT_PIN_IO(PWM0) - mcu_clear_output(PWM0); -#endif + io_clear_output(PWM0); } else { -#if ASSERT_PIN_IO(PWM0) - mcu_set_output(PWM0); -#elif ASSERT_PIN_EXTENDED(PWM0) - pwm_mask |= (1 << 0); -#endif + io_set_output(PWM0); } #endif #if ASSERT_PIN(PWM1) if (pwm_counter > g_io_soft_pwm[1] || !g_io_soft_pwm[1]) { -#if ASSERT_PIN_IO(PWM1) - mcu_clear_output(PWM1); -#endif + io_clear_output(PWM1); } else { -#if ASSERT_PIN_IO(PWM1) - mcu_set_output(PWM1); -#elif ASSERT_PIN_EXTENDED(PWM1) - pwm_mask |= (1 << 1); -#endif + io_set_output(PWM1); } #endif #if ASSERT_PIN(PWM2) if (pwm_counter > g_io_soft_pwm[2] || !g_io_soft_pwm[2]) { -#if ASSERT_PIN_IO(PWM2) - mcu_clear_output(PWM2); -#endif + io_clear_output(PWM2); } else { -#if ASSERT_PIN_IO(PWM2) - mcu_set_output(PWM2); -#elif ASSERT_PIN_EXTENDED(PWM2) - pwm_mask |= (1 << 2); -#endif + io_set_output(PWM2); } #endif #if ASSERT_PIN(PWM3) if (pwm_counter > g_io_soft_pwm[3] || !g_io_soft_pwm[3]) { -#if ASSERT_PIN_IO(PWM3) - mcu_clear_output(PWM3); -#endif + io_clear_output(PWM3); } else { -#if ASSERT_PIN_IO(PWM3) - mcu_set_output(PWM3); -#elif ASSERT_PIN_EXTENDED(PWM3) - pwm_mask |= (1 << 3); -#endif + io_set_output(PWM3); } #endif #if ASSERT_PIN(PWM4) if (pwm_counter > g_io_soft_pwm[4] || !g_io_soft_pwm[4]) { -#if ASSERT_PIN_IO(PWM4) - mcu_clear_output(PWM4); -#endif + io_clear_output(PWM4); } else { -#if ASSERT_PIN_IO(PWM4) - mcu_set_output(PWM4); -#elif ASSERT_PIN_EXTENDED(PWM4) - pwm_mask |= (1 << 4); -#endif + io_set_output(PWM4); } #endif #if ASSERT_PIN(PWM5) if (pwm_counter > g_io_soft_pwm[5] || !g_io_soft_pwm[5]) { -#if ASSERT_PIN_IO(PWM5) - mcu_clear_output(PWM5); -#endif + io_clear_output(PWM5); } else { -#if ASSERT_PIN_IO(PWM5) - mcu_set_output(PWM5); -#elif ASSERT_PIN_EXTENDED(PWM5) - pwm_mask |= (1 << 5); -#endif + io_set_output(PWM5); } #endif #if ASSERT_PIN(PWM6) if (pwm_counter > g_io_soft_pwm[6] || !g_io_soft_pwm[6]) { -#if ASSERT_PIN_IO(PWM6) - mcu_clear_output(PWM6); -#endif + io_clear_output(PWM6); } else { -#if ASSERT_PIN_IO(PWM6) - mcu_set_output(PWM6); -#elif ASSERT_PIN_EXTENDED(PWM6) - pwm_mask |= (1 << 6); -#endif + io_set_output(PWM6); } #endif #if ASSERT_PIN(PWM7) if (pwm_counter > g_io_soft_pwm[7] || !g_io_soft_pwm[7]) { -#if ASSERT_PIN_IO(PWM7) - mcu_clear_output(PWM7); -#endif + io_clear_output(PWM7); } else { -#if ASSERT_PIN_IO(PWM7) - mcu_set_output(PWM7); -#elif ASSERT_PIN_EXTENDED(PWM7) - pwm_mask |= (1 << 7); -#endif + io_set_output(PWM7); } #endif #if ASSERT_PIN(PWM8) if (pwm_counter > g_io_soft_pwm[8] || !g_io_soft_pwm[8]) { -#if ASSERT_PIN_IO(PWM8) - mcu_clear_output(PWM8); -#endif + io_clear_output(PWM8); } else { -#if ASSERT_PIN_IO(PWM8) - mcu_set_output(PWM8); -#elif ASSERT_PIN_EXTENDED(PWM8) - pwm_mask |= (1 << 8); -#endif + io_set_output(PWM8); } #endif #if ASSERT_PIN(PWM9) if (pwm_counter > g_io_soft_pwm[9] || !g_io_soft_pwm[9]) { -#if ASSERT_PIN_IO(PWM9) - mcu_clear_output(PWM9); -#endif + io_clear_output(PWM9); } else { -#if ASSERT_PIN_IO(PWM9) - mcu_set_output(PWM9); -#elif ASSERT_PIN_EXTENDED(PWM9) - pwm_mask |= (1 << 9); -#endif + io_set_output(PWM9); } #endif #if ASSERT_PIN(PWM10) if (pwm_counter > g_io_soft_pwm[10] || !g_io_soft_pwm[10]) { -#if ASSERT_PIN_IO(PWM10) - mcu_clear_output(PWM10); +#if ASSERT_PIN(PWM10) + io_clear_output(PWM10); #endif } else { -#if ASSERT_PIN_IO(PWM10) - mcu_set_output(PWM10); +#if ASSERT_PIN(PWM10) + io_set_output(PWM10); #elif ASSERT_PIN_EXTENDED(PWM10) pwm_mask |= (1 << 10); #endif @@ -1039,14 +979,14 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM11) if (pwm_counter > g_io_soft_pwm[11] || !g_io_soft_pwm[11]) { -#if ASSERT_PIN_IO(PWM11) - mcu_clear_output(PWM11); +#if ASSERT_PIN(PWM11) + io_clear_output(PWM11); #endif } else { -#if ASSERT_PIN_IO(PWM11) - mcu_set_output(PWM11); +#if ASSERT_PIN(PWM11) + io_set_output(PWM11); #elif ASSERT_PIN_EXTENDED(PWM11) pwm_mask |= (1 << 11); #endif @@ -1055,14 +995,14 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM12) if (pwm_counter > g_io_soft_pwm[12] || !g_io_soft_pwm[12]) { -#if ASSERT_PIN_IO(PWM12) - mcu_clear_output(PWM12); +#if ASSERT_PIN(PWM12) + io_clear_output(PWM12); #endif } else { -#if ASSERT_PIN_IO(PWM12) - mcu_set_output(PWM12); +#if ASSERT_PIN(PWM12) + io_set_output(PWM12); #elif ASSERT_PIN_EXTENDED(PWM12) pwm_mask |= (1 << 12); #endif @@ -1071,14 +1011,14 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM13) if (pwm_counter > g_io_soft_pwm[13] || !g_io_soft_pwm[13]) { -#if ASSERT_PIN_IO(PWM13) - mcu_clear_output(PWM13); +#if ASSERT_PIN(PWM13) + io_clear_output(PWM13); #endif } else { -#if ASSERT_PIN_IO(PWM13) - mcu_set_output(PWM13); +#if ASSERT_PIN(PWM13) + io_set_output(PWM13); #elif ASSERT_PIN_EXTENDED(PWM13) pwm_mask |= (1 << 13); #endif @@ -1087,14 +1027,14 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM14) if (pwm_counter > g_io_soft_pwm[14] || !g_io_soft_pwm[14]) { -#if ASSERT_PIN_IO(PWM14) - mcu_clear_output(PWM14); +#if ASSERT_PIN(PWM14) + io_clear_output(PWM14); #endif } else { -#if ASSERT_PIN_IO(PWM14) - mcu_set_output(PWM14); +#if ASSERT_PIN(PWM14) + io_set_output(PWM14); #elif ASSERT_PIN_EXTENDED(PWM14) pwm_mask |= (1 << 14); #endif @@ -1103,14 +1043,14 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM15) if (pwm_counter > g_io_soft_pwm[15] || !g_io_soft_pwm[15]) { -#if ASSERT_PIN_IO(PWM15) - mcu_clear_output(PWM15); +#if ASSERT_PIN(PWM15) + io_clear_output(PWM15); #endif } else { -#if ASSERT_PIN_IO(PWM15) - mcu_set_output(PWM15); +#if ASSERT_PIN(PWM15) + io_set_output(PWM15); #elif ASSERT_PIN_EXTENDED(PWM15) pwm_mask |= (1 << 15); #endif @@ -1686,6 +1626,10 @@ void io_set_pinvalue(uint8_t pin, uint8_t value) #endif } } + +#ifdef IC74HC595_HAS_DOUTS + ic74hc595_shift_io_pins(); +#endif } int16_t io_get_pinvalue(uint8_t pin) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 06a2d5e24..a8b94f888 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -73,24 +73,20 @@ static flash_eeprom_t mcu_eeprom; hw_timer_t *esp32_step_timer; #ifdef IC74HC595_CUSTOM_SHIFT_IO -static volatile uint8_t ic74hc595_update_lock; void ic74hc595_shift_io_pins(void) { - if (!ic74hc595_update_lock++) - { - do - { - uint32_t data = *((uint32_t *)&ic74hc595_io_pins[0]); - I2SREG.conf_single_data = data; - } while (--ic74hc595_update_lock); - } } #endif -#ifdef IC74HC595_HAS_PWMS -IRAM_ATTR void mcu_pwm_isr(void *arg) +#if defined(IC74HC595_CUSTOM_SHIFT_IO) && (IC74HC595_COUNT != 0) +IRAM_ATTR void io_updater(void *arg) { +#ifdef IC74HC595_HAS_PWMS io_soft_pwm_update(); +#endif + + uint32_t data = *((uint32_t *)&ic74hc595_io_pins[0]); + I2SREG.conf_single_data = data; timer_group_clr_intr_status_in_isr(PWM_TIMER_TG, PWM_TIMER_IDX); /* After the alarm has been triggered @@ -196,9 +192,26 @@ uint8_t mcu_softpwm_freq_config(uint16_t freq) void mcu_core0_tasks_init(void *arg) { -#ifdef IC74HC595_HAS_PWMS +#if defined(IC74HC595_CUSTOM_SHIFT_IO) && (IC74HC595_COUNT != 0) + // initialize PWM timer + /* Select and initialize basic parameters of the timer */ + timer_config_t pwmconfig = { + .divider = 2, + .counter_dir = TIMER_COUNT_UP, + .counter_en = TIMER_PAUSE, + .alarm_en = TIMER_ALARM_EN, + .auto_reload = true, + }; // default clock source is APB + timer_init(PWM_TIMER_TG, PWM_TIMER_IDX, &pwmconfig); + + /* Timer's counter will initially start from value below. + Also, if auto_reload is set, this value will be automatically reload on alarm */ + timer_set_counter_value(PWM_TIMER_TG, PWM_TIMER_IDX, 0x00000000ULL); + /* Configure the alarm value and the interrupt on alarm. */ + timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)157); // register PWM isr - timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, mcu_pwm_isr, NULL, 0, NULL); + timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, io_updater, NULL, 0, NULL); + timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); #endif #ifdef MCU_HAS_UART // install UART driver handler @@ -382,26 +395,6 @@ void mcu_init(void) uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif -#ifdef IC74HC595_HAS_PWMS - // initialize PWM timer - /* Select and initialize basic parameters of the timer */ - timer_config_t pwmconfig = { - .divider = 2, - .counter_dir = TIMER_COUNT_UP, - .counter_en = TIMER_PAUSE, - .alarm_en = TIMER_ALARM_EN, - .auto_reload = true, - }; // default clock source is APB - timer_init(PWM_TIMER_TG, PWM_TIMER_IDX, &pwmconfig); - - /* Timer's counter will initially start from value below. - Also, if auto_reload is set, this value will be automatically reload on alarm */ - timer_set_counter_value(PWM_TIMER_TG, PWM_TIMER_IDX, 0x00000000ULL); - /* Configure the alarm value and the interrupt on alarm. */ - timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)157); - timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); -#endif - // inititialize ITP timer timer_config_t itpconfig = {0}; itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse @@ -468,7 +461,7 @@ void mcu_init(void) i2s_set_pin(IC74HC595_I2S_PORT, &pin_config); I2SREG.clkm_conf.clka_en = 0; // Use PLL/2 as reference - I2SREG.clkm_conf.clkm_div_num = 4; // reset value of 4 + I2SREG.clkm_conf.clkm_div_num = 1; // reset value of 4 I2SREG.clkm_conf.clkm_div_a = 1; // 0 at reset, what about divide by 0? I2SREG.clkm_conf.clkm_div_b = 0; // 0 at reset diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index 3d7b5f900..f47307fce 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -88,554 +88,6 @@ void __attribute__((weak)) ic74hc595_shift_io_pins(void) } } -FORCEINLINE void ic74hc595_set_steps(uint8_t mask) -{ -#if ASSERT_IO_OFFSET(STEP0_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] |= STEP0_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] &= ~STEP0_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP1_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] |= STEP1_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] &= ~STEP1_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP2_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] |= STEP2_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] &= ~STEP2_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP3_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] |= STEP3_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] &= ~STEP3_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP4_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] |= STEP4_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] &= ~STEP4_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP5_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] |= STEP5_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] &= ~STEP5_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP6_IO_OFFSET) - if (mask & (1 << 6)) - { - ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] |= STEP6_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] &= ~STEP6_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP7_IO_OFFSET) - if (mask & (1 << 7)) - { - ic74hc595_io_pins[STEP7_IO_BYTEOFFSET] |= STEP7_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP7_IO_BYTEOFFSET] &= ~STEP7_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - -FORCEINLINE void ic74hc595_toggle_steps(uint8_t mask) -{ - if (!mask) - { - return; - } -#if ASSERT_IO_OFFSET(STEP0_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[STEP0_IO_BYTEOFFSET] ^= STEP0_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP1_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[STEP1_IO_BYTEOFFSET] ^= STEP1_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP2_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[STEP2_IO_BYTEOFFSET] ^= STEP2_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP3_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[STEP3_IO_BYTEOFFSET] ^= STEP3_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP4_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[STEP4_IO_BYTEOFFSET] ^= STEP4_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP5_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[STEP5_IO_BYTEOFFSET] ^= STEP5_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP6_IO_OFFSET) - if (mask & (1 << 6)) - { - ic74hc595_io_pins[STEP6_IO_BYTEOFFSET] ^= STEP6_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP7_IO_OFFSET) - if (mask & (1 << 7)) - { - ic74hc595_io_pins[STEP7_IO_BYTEOFFSET] ^= STEP7_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - -FORCEINLINE void ic74hc595_set_dirs(uint8_t mask) -{ -#if ASSERT_IO_OFFSET(DIR0_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[DIR0_IO_BYTEOFFSET] |= DIR0_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR0_IO_BYTEOFFSET] &= ~DIR0_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR1_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[DIR1_IO_BYTEOFFSET] |= DIR1_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR1_IO_BYTEOFFSET] &= ~DIR1_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR2_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[DIR2_IO_BYTEOFFSET] |= DIR2_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR2_IO_BYTEOFFSET] &= ~DIR2_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR3_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[DIR3_IO_BYTEOFFSET] |= DIR3_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR3_IO_BYTEOFFSET] &= ~DIR3_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR4_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[DIR4_IO_BYTEOFFSET] |= DIR4_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR4_IO_BYTEOFFSET] &= ~DIR4_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR5_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[DIR5_IO_BYTEOFFSET] |= DIR5_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR5_IO_BYTEOFFSET] &= ~DIR5_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR6_IO_OFFSET) - if (mask & (1 << 6)) - { - ic74hc595_io_pins[DIR6_IO_BYTEOFFSET] |= DIR6_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR6_IO_BYTEOFFSET] &= ~DIR6_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(DIR7_IO_OFFSET) - if (mask & (1 << 7)) - { - ic74hc595_io_pins[DIR7_IO_BYTEOFFSET] |= DIR7_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DIR7_IO_BYTEOFFSET] &= ~DIR7_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - -FORCEINLINE void ic74hc595_enable_steppers(uint8_t mask) -{ -#if ASSERT_IO_OFFSET(STEP0_EN_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[STEP0_EN_IO_BYTEOFFSET] |= STEP0_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP0_EN_IO_BYTEOFFSET] &= ~STEP0_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP1_EN_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[STEP1_EN_IO_BYTEOFFSET] |= STEP1_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP1_EN_IO_BYTEOFFSET] &= ~STEP1_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP2_EN_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[STEP2_EN_IO_BYTEOFFSET] |= STEP2_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP2_EN_IO_BYTEOFFSET] &= ~STEP2_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP3_EN_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[STEP3_EN_IO_BYTEOFFSET] |= STEP3_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP3_EN_IO_BYTEOFFSET] &= ~STEP3_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP4_EN_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[STEP4_EN_IO_BYTEOFFSET] |= STEP4_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP4_EN_IO_BYTEOFFSET] &= ~STEP4_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP5_EN_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[STEP5_EN_IO_BYTEOFFSET] |= STEP5_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP5_EN_IO_BYTEOFFSET] &= ~STEP5_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP6_EN_IO_OFFSET) - if (mask & (1 << 6)) - { - ic74hc595_io_pins[STEP6_EN_IO_BYTEOFFSET] |= STEP6_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP6_EN_IO_BYTEOFFSET] &= ~STEP6_EN_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(STEP7_EN_IO_OFFSET) - if (mask & (1 << 7)) - { - ic74hc595_io_pins[STEP7_EN_IO_BYTEOFFSET] |= STEP7_EN_IO_BITMASK; - } - else - { - ic74hc595_io_pins[STEP7_EN_IO_BYTEOFFSET] &= ~STEP7_EN_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - -FORCEINLINE void ic74hc595_set_pwms(uint16_t mask) -{ -#if ASSERT_IO_OFFSET(PWM0_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[PWM0_IO_BYTEOFFSET] |= PWM0_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM0_IO_BYTEOFFSET] &= ~PWM0_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM1_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[PWM1_IO_BYTEOFFSET] |= PWM1_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM1_IO_BYTEOFFSET] &= ~PWM1_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM2_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[PWM2_IO_BYTEOFFSET] |= PWM2_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM2_IO_BYTEOFFSET] &= ~PWM2_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM3_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[PWM3_IO_BYTEOFFSET] |= PWM3_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM3_IO_BYTEOFFSET] &= ~PWM3_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM4_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[PWM4_IO_BYTEOFFSET] |= PWM4_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM4_IO_BYTEOFFSET] &= ~PWM4_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM5_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[PWM5_IO_BYTEOFFSET] |= PWM5_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM5_IO_BYTEOFFSET] &= ~PWM5_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM6_IO_OFFSET) - if (mask & (1 << 6)) - { - ic74hc595_io_pins[PWM6_IO_BYTEOFFSET] |= PWM6_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM6_IO_BYTEOFFSET] &= ~PWM6_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM7_IO_OFFSET) - if (mask & (1 << 7)) - { - ic74hc595_io_pins[PWM7_IO_BYTEOFFSET] |= PWM7_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM7_IO_BYTEOFFSET] &= ~PWM7_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM8_IO_OFFSET) - if (mask & (1 << 8)) - { - ic74hc595_io_pins[PWM8_IO_BYTEOFFSET] |= PWM8_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM8_IO_BYTEOFFSET] &= ~PWM8_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM9_IO_OFFSET) - if (mask & (1 << 9)) - { - ic74hc595_io_pins[PWM9_IO_BYTEOFFSET] |= PWM9_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM9_IO_BYTEOFFSET] &= ~PWM9_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM10_IO_OFFSET) - if (mask & (1 << 10)) - { - ic74hc595_io_pins[PWM10_IO_BYTEOFFSET] |= PWM10_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM10_IO_BYTEOFFSET] &= ~PWM10_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM11_IO_OFFSET) - if (mask & (1 << 11)) - { - ic74hc595_io_pins[PWM11_IO_BYTEOFFSET] |= PWM11_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM11_IO_BYTEOFFSET] &= ~PWM11_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM12_IO_OFFSET) - if (mask & (1 << 12)) - { - ic74hc595_io_pins[PWM12_IO_BYTEOFFSET] |= PWM12_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM12_IO_BYTEOFFSET] &= ~PWM12_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM13_IO_OFFSET) - if (mask & (1 << 13)) - { - ic74hc595_io_pins[PWM13_IO_BYTEOFFSET] |= PWM13_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM13_IO_BYTEOFFSET] &= ~PWM13_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM14_IO_OFFSET) - if (mask & (1 << 14)) - { - ic74hc595_io_pins[PWM14_IO_BYTEOFFSET] |= PWM14_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM14_IO_BYTEOFFSET] &= ~PWM14_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(PWM15_IO_OFFSET) - if (mask & (1 << 15)) - { - ic74hc595_io_pins[PWM15_IO_BYTEOFFSET] |= PWM15_IO_BITMASK; - } - else - { - ic74hc595_io_pins[PWM15_IO_BYTEOFFSET] &= ~PWM15_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - -FORCEINLINE void ic74hc595_set_servos(uint8_t mask) -{ -#if ASSERT_IO_OFFSET(SERVO0_IO_OFFSET) - if (mask & (1 << 0)) - { - ic74hc595_io_pins[SERVO0_IO_BYTEOFFSET] |= SERVO0_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO0_IO_BYTEOFFSET] &= ~SERVO0_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(SERVO1_IO_OFFSET) - if (mask & (1 << 1)) - { - ic74hc595_io_pins[SERVO1_IO_BYTEOFFSET] |= SERVO1_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO1_IO_BYTEOFFSET] &= ~SERVO1_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(SERVO2_IO_OFFSET) - if (mask & (1 << 2)) - { - ic74hc595_io_pins[SERVO2_IO_BYTEOFFSET] |= SERVO2_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO2_IO_BYTEOFFSET] &= ~SERVO2_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(SERVO3_IO_OFFSET) - if (mask & (1 << 3)) - { - ic74hc595_io_pins[SERVO3_IO_BYTEOFFSET] |= SERVO3_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO3_IO_BYTEOFFSET] &= ~SERVO3_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(SERVO4_IO_OFFSET) - if (mask & (1 << 4)) - { - ic74hc595_io_pins[SERVO4_IO_BYTEOFFSET] |= SERVO4_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO4_IO_BYTEOFFSET] &= ~SERVO4_IO_BITMASK; - } -#endif -#if ASSERT_IO_OFFSET(SERVO5_IO_OFFSET) - if (mask & (1 << 5)) - { - ic74hc595_io_pins[SERVO5_IO_BYTEOFFSET] |= SERVO5_IO_BITMASK; - } - else - { - ic74hc595_io_pins[SERVO5_IO_BYTEOFFSET] &= ~SERVO5_IO_BITMASK; - } -#endif - - ic74hc595_shift_io_pins(); -} - FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) { switch (pin - DOUT_PINS_OFFSET) diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index 37a491219..c1ad316af 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -1535,12 +1535,6 @@ extern "C" #define ic74hc595_get_pin(pin) 0 #endif - void ic74hc595_set_steps(uint8_t mask); - void ic74hc595_toggle_steps(uint8_t mask); - void ic74hc595_set_dirs(uint8_t mask); - void ic74hc595_enable_steppers(uint8_t mask); - void ic74hc595_set_pwms(uint16_t mask); - void ic74hc595_set_servos(uint8_t mask); void ic74hc595_set_output(uint8_t pin, bool state); void ic74hc595_shift_io_pins(void); From 29c36bf04388fc71f9db760d5d20eedd026a555f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 18 Aug 2023 21:04:16 +0100 Subject: [PATCH 094/168] fixed 74HC595 concurrency issues - fixed 74HC595 concurrency issues my moving softpwm to core1 - fixed step bug introduced by change in step ISR --- uCNC/src/core/interpolator.c | 2 +- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index b0d6a00e7..ca47096c1 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -929,7 +929,7 @@ MCU_CALLBACK void mcu_step_cb(void) // loads a new segment itp_rt_sgm = &itp_sgm_data[itp_sgm_data_read]; cnc_set_exec_state(EXEC_RUN); - if (itp_rt_sgm->remaining_steps) + if (itp_rt_sgm->block != NULL) { #if (DSS_MAX_OVERSAMPLING != 0) if (itp_rt_sgm->next_dss != 0) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 06a2d5e24..823e2db11 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -196,10 +196,6 @@ uint8_t mcu_softpwm_freq_config(uint16_t freq) void mcu_core0_tasks_init(void *arg) { -#ifdef IC74HC595_HAS_PWMS - // register PWM isr - timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, mcu_pwm_isr, NULL, 0, NULL); -#endif #ifdef MCU_HAS_UART // install UART driver handler uart_driver_install(COM_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); @@ -399,6 +395,8 @@ void mcu_init(void) timer_set_counter_value(PWM_TIMER_TG, PWM_TIMER_IDX, 0x00000000ULL); /* Configure the alarm value and the interrupt on alarm. */ timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)157); + // register PWM isr + timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, mcu_pwm_isr, NULL, 0, NULL); timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); #endif @@ -468,7 +466,7 @@ void mcu_init(void) i2s_set_pin(IC74HC595_I2S_PORT, &pin_config); I2SREG.clkm_conf.clka_en = 0; // Use PLL/2 as reference - I2SREG.clkm_conf.clkm_div_num = 4; // reset value of 4 + I2SREG.clkm_conf.clkm_div_num = 2; // reset value of 4 I2SREG.clkm_conf.clkm_div_a = 1; // 0 at reset, what about divide by 0? I2SREG.clkm_conf.clkm_div_b = 0; // 0 at reset From 546d59011e2f707498f0b68380937266ce9e0f54 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 21 Aug 2023 17:57:59 +0100 Subject: [PATCH 095/168] code cleaning and ESP32 integration - removed deprecated 74hc595 function - conditional ESP32 PWM mcu functions - core0 initialization code with soft PWM --- uCNC/src/core/io_control.c | 48 - uCNC/src/hal/boards/boarddefs.h | 1 + uCNC/src/hal/io_hal.h | 1688 ++++++------------------ uCNC/src/hal/mcus/esp32/mcu_esp32.c | 144 +- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 20 +- uCNC/src/modules/ic74hc595.c | 393 ------ uCNC/src/modules/ic74hc595.h | 1 - 7 files changed, 512 insertions(+), 1783 deletions(-) diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 5ac0cfb4f..08c8eeb25 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -853,10 +853,6 @@ MCU_CALLBACK void io_soft_pwm_update(void) static uint8_t pwm_counter_last = 0; uint8_t pwm_counter = pwm_counter_last; uint8_t resolution = g_soft_pwm_res; -#ifdef IC74HC595_HAS_PWMS - static uint16_t pwm_mask_last = 0; - uint16_t pwm_mask = 0; -#endif // software PWM pwm_counter += (1 << resolution); pwm_counter_last = pwm_counter; @@ -963,105 +959,61 @@ MCU_CALLBACK void io_soft_pwm_update(void) #if ASSERT_PIN(PWM10) if (pwm_counter > g_io_soft_pwm[10] || !g_io_soft_pwm[10]) { -#if ASSERT_PIN(PWM10) io_clear_output(PWM10); -#endif } else { -#if ASSERT_PIN(PWM10) io_set_output(PWM10); -#elif ASSERT_PIN_EXTENDED(PWM10) - pwm_mask |= (1 << 10); -#endif } #endif #if ASSERT_PIN(PWM11) if (pwm_counter > g_io_soft_pwm[11] || !g_io_soft_pwm[11]) { -#if ASSERT_PIN(PWM11) io_clear_output(PWM11); -#endif } else { -#if ASSERT_PIN(PWM11) io_set_output(PWM11); -#elif ASSERT_PIN_EXTENDED(PWM11) - pwm_mask |= (1 << 11); -#endif } #endif #if ASSERT_PIN(PWM12) if (pwm_counter > g_io_soft_pwm[12] || !g_io_soft_pwm[12]) { -#if ASSERT_PIN(PWM12) io_clear_output(PWM12); -#endif } else { -#if ASSERT_PIN(PWM12) io_set_output(PWM12); -#elif ASSERT_PIN_EXTENDED(PWM12) - pwm_mask |= (1 << 12); -#endif } #endif #if ASSERT_PIN(PWM13) if (pwm_counter > g_io_soft_pwm[13] || !g_io_soft_pwm[13]) { -#if ASSERT_PIN(PWM13) io_clear_output(PWM13); -#endif } else { -#if ASSERT_PIN(PWM13) io_set_output(PWM13); -#elif ASSERT_PIN_EXTENDED(PWM13) - pwm_mask |= (1 << 13); -#endif } #endif #if ASSERT_PIN(PWM14) if (pwm_counter > g_io_soft_pwm[14] || !g_io_soft_pwm[14]) { -#if ASSERT_PIN(PWM14) io_clear_output(PWM14); -#endif } else { -#if ASSERT_PIN(PWM14) io_set_output(PWM14); -#elif ASSERT_PIN_EXTENDED(PWM14) - pwm_mask |= (1 << 14); -#endif } #endif #if ASSERT_PIN(PWM15) if (pwm_counter > g_io_soft_pwm[15] || !g_io_soft_pwm[15]) { -#if ASSERT_PIN(PWM15) io_clear_output(PWM15); -#endif } else { -#if ASSERT_PIN(PWM15) io_set_output(PWM15); -#elif ASSERT_PIN_EXTENDED(PWM15) - pwm_mask |= (1 << 15); -#endif - } -#endif - -#ifdef IC74HC595_HAS_PWMS - if (pwm_mask_last != pwm_mask) - { - ic74hc595_set_pwms(pwm_mask); - pwm_mask_last = pwm_mask; } #endif } diff --git a/uCNC/src/hal/boards/boarddefs.h b/uCNC/src/hal/boards/boarddefs.h index aa65fb4d8..12d75dfc3 100644 --- a/uCNC/src/hal/boards/boarddefs.h +++ b/uCNC/src/hal/boards/boarddefs.h @@ -164,6 +164,7 @@ extern "C" #endif #include "../../../boardmap_overrides.h" +#include "../../modules/ic74hc595.h" #include "../mcus/mcudefs.h" //configures the MCU for the selected board #ifdef __cplusplus diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index 500f80e3c..f760c4128 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -21,15 +21,9 @@ extern "C" #define io1_get_input mcu_get_input(STEP0) #elif ASSERT_PIN_EXTENDED(STEP0) #define io1_config_output -#define io1_set_output \ - ic74hc595_set_pin(STEP0); \ - ic74hc595_shift_io_pins() -#define io1_clear_output \ - ic74hc595_clear_pin(STEP0); \ - ic74hc595_shift_io_pins() -#define io1_toggle_output \ - ic74hc595_toggle_pin(STEP0); \ - ic74hc595_shift_io_pins() +#define io1_set_output ic74hc595_set_pin(STEP0) +#define io1_clear_output ic74hc595_clear_pin(STEP0) +#define io1_toggle_output ic74hc595_toggle_pin(STEP0) #define io1_get_output ic74hc595_get_pin(STEP0) #define io1_config_input #define io1_config_pullup @@ -55,15 +49,9 @@ extern "C" #define io2_get_input mcu_get_input(STEP1) #elif ASSERT_PIN_EXTENDED(STEP1) #define io2_config_output -#define io2_set_output \ - ic74hc595_set_pin(STEP1); \ - ic74hc595_shift_io_pins() -#define io2_clear_output \ - ic74hc595_clear_pin(STEP1); \ - ic74hc595_shift_io_pins() -#define io2_toggle_output \ - ic74hc595_toggle_pin(STEP1); \ - ic74hc595_shift_io_pins() +#define io2_set_output ic74hc595_set_pin(STEP1) +#define io2_clear_output ic74hc595_clear_pin(STEP1) +#define io2_toggle_output ic74hc595_toggle_pin(STEP1) #define io2_get_output ic74hc595_get_pin(STEP1) #define io2_config_input #define io2_config_pullup @@ -89,15 +77,9 @@ extern "C" #define io3_get_input mcu_get_input(STEP2) #elif ASSERT_PIN_EXTENDED(STEP2) #define io3_config_output -#define io3_set_output \ - ic74hc595_set_pin(STEP2); \ - ic74hc595_shift_io_pins() -#define io3_clear_output \ - ic74hc595_clear_pin(STEP2); \ - ic74hc595_shift_io_pins() -#define io3_toggle_output \ - ic74hc595_toggle_pin(STEP2); \ - ic74hc595_shift_io_pins() +#define io3_set_output ic74hc595_set_pin(STEP2) +#define io3_clear_output ic74hc595_clear_pin(STEP2) +#define io3_toggle_output ic74hc595_toggle_pin(STEP2) #define io3_get_output ic74hc595_get_pin(STEP2) #define io3_config_input #define io3_config_pullup @@ -123,15 +105,9 @@ extern "C" #define io4_get_input mcu_get_input(STEP3) #elif ASSERT_PIN_EXTENDED(STEP3) #define io4_config_output -#define io4_set_output \ - ic74hc595_set_pin(STEP3); \ - ic74hc595_shift_io_pins() -#define io4_clear_output \ - ic74hc595_clear_pin(STEP3); \ - ic74hc595_shift_io_pins() -#define io4_toggle_output \ - ic74hc595_toggle_pin(STEP3); \ - ic74hc595_shift_io_pins() +#define io4_set_output ic74hc595_set_pin(STEP3) +#define io4_clear_output ic74hc595_clear_pin(STEP3) +#define io4_toggle_output ic74hc595_toggle_pin(STEP3) #define io4_get_output ic74hc595_get_pin(STEP3) #define io4_config_input #define io4_config_pullup @@ -157,15 +133,9 @@ extern "C" #define io5_get_input mcu_get_input(STEP4) #elif ASSERT_PIN_EXTENDED(STEP4) #define io5_config_output -#define io5_set_output \ - ic74hc595_set_pin(STEP4); \ - ic74hc595_shift_io_pins() -#define io5_clear_output \ - ic74hc595_clear_pin(STEP4); \ - ic74hc595_shift_io_pins() -#define io5_toggle_output \ - ic74hc595_toggle_pin(STEP4); \ - ic74hc595_shift_io_pins() +#define io5_set_output ic74hc595_set_pin(STEP4) +#define io5_clear_output ic74hc595_clear_pin(STEP4) +#define io5_toggle_output ic74hc595_toggle_pin(STEP4) #define io5_get_output ic74hc595_get_pin(STEP4) #define io5_config_input #define io5_config_pullup @@ -191,15 +161,9 @@ extern "C" #define io6_get_input mcu_get_input(STEP5) #elif ASSERT_PIN_EXTENDED(STEP5) #define io6_config_output -#define io6_set_output \ - ic74hc595_set_pin(STEP5); \ - ic74hc595_shift_io_pins() -#define io6_clear_output \ - ic74hc595_clear_pin(STEP5); \ - ic74hc595_shift_io_pins() -#define io6_toggle_output \ - ic74hc595_toggle_pin(STEP5); \ - ic74hc595_shift_io_pins() +#define io6_set_output ic74hc595_set_pin(STEP5) +#define io6_clear_output ic74hc595_clear_pin(STEP5) +#define io6_toggle_output ic74hc595_toggle_pin(STEP5) #define io6_get_output ic74hc595_get_pin(STEP5) #define io6_config_input #define io6_config_pullup @@ -225,15 +189,9 @@ extern "C" #define io7_get_input mcu_get_input(STEP6) #elif ASSERT_PIN_EXTENDED(STEP6) #define io7_config_output -#define io7_set_output \ - ic74hc595_set_pin(STEP6); \ - ic74hc595_shift_io_pins() -#define io7_clear_output \ - ic74hc595_clear_pin(STEP6); \ - ic74hc595_shift_io_pins() -#define io7_toggle_output \ - ic74hc595_toggle_pin(STEP6); \ - ic74hc595_shift_io_pins() +#define io7_set_output ic74hc595_set_pin(STEP6) +#define io7_clear_output ic74hc595_clear_pin(STEP6) +#define io7_toggle_output ic74hc595_toggle_pin(STEP6) #define io7_get_output ic74hc595_get_pin(STEP6) #define io7_config_input #define io7_config_pullup @@ -259,15 +217,9 @@ extern "C" #define io8_get_input mcu_get_input(STEP7) #elif ASSERT_PIN_EXTENDED(STEP7) #define io8_config_output -#define io8_set_output \ - ic74hc595_set_pin(STEP7); \ - ic74hc595_shift_io_pins() -#define io8_clear_output \ - ic74hc595_clear_pin(STEP7); \ - ic74hc595_shift_io_pins() -#define io8_toggle_output \ - ic74hc595_toggle_pin(STEP7); \ - ic74hc595_shift_io_pins() +#define io8_set_output ic74hc595_set_pin(STEP7) +#define io8_clear_output ic74hc595_clear_pin(STEP7) +#define io8_toggle_output ic74hc595_toggle_pin(STEP7) #define io8_get_output ic74hc595_get_pin(STEP7) #define io8_config_input #define io8_config_pullup @@ -293,15 +245,9 @@ extern "C" #define io9_get_input mcu_get_input(DIR0) #elif ASSERT_PIN_EXTENDED(DIR0) #define io9_config_output -#define io9_set_output \ - ic74hc595_set_pin(DIR0); \ - ic74hc595_shift_io_pins() -#define io9_clear_output \ - ic74hc595_clear_pin(DIR0); \ - ic74hc595_shift_io_pins() -#define io9_toggle_output \ - ic74hc595_toggle_pin(DIR0); \ - ic74hc595_shift_io_pins() +#define io9_set_output ic74hc595_set_pin(DIR0) +#define io9_clear_output ic74hc595_clear_pin(DIR0) +#define io9_toggle_output ic74hc595_toggle_pin(DIR0) #define io9_get_output ic74hc595_get_pin(DIR0) #define io9_config_input #define io9_config_pullup @@ -327,15 +273,9 @@ extern "C" #define io10_get_input mcu_get_input(DIR1) #elif ASSERT_PIN_EXTENDED(DIR1) #define io10_config_output -#define io10_set_output \ - ic74hc595_set_pin(DIR1); \ - ic74hc595_shift_io_pins() -#define io10_clear_output \ - ic74hc595_clear_pin(DIR1); \ - ic74hc595_shift_io_pins() -#define io10_toggle_output \ - ic74hc595_toggle_pin(DIR1); \ - ic74hc595_shift_io_pins() +#define io10_set_output ic74hc595_set_pin(DIR1) +#define io10_clear_output ic74hc595_clear_pin(DIR1) +#define io10_toggle_output ic74hc595_toggle_pin(DIR1) #define io10_get_output ic74hc595_get_pin(DIR1) #define io10_config_input #define io10_config_pullup @@ -361,15 +301,9 @@ extern "C" #define io11_get_input mcu_get_input(DIR2) #elif ASSERT_PIN_EXTENDED(DIR2) #define io11_config_output -#define io11_set_output \ - ic74hc595_set_pin(DIR2); \ - ic74hc595_shift_io_pins() -#define io11_clear_output \ - ic74hc595_clear_pin(DIR2); \ - ic74hc595_shift_io_pins() -#define io11_toggle_output \ - ic74hc595_toggle_pin(DIR2); \ - ic74hc595_shift_io_pins() +#define io11_set_output ic74hc595_set_pin(DIR2) +#define io11_clear_output ic74hc595_clear_pin(DIR2) +#define io11_toggle_output ic74hc595_toggle_pin(DIR2) #define io11_get_output ic74hc595_get_pin(DIR2) #define io11_config_input #define io11_config_pullup @@ -395,15 +329,9 @@ extern "C" #define io12_get_input mcu_get_input(DIR3) #elif ASSERT_PIN_EXTENDED(DIR3) #define io12_config_output -#define io12_set_output \ - ic74hc595_set_pin(DIR3); \ - ic74hc595_shift_io_pins() -#define io12_clear_output \ - ic74hc595_clear_pin(DIR3); \ - ic74hc595_shift_io_pins() -#define io12_toggle_output \ - ic74hc595_toggle_pin(DIR3); \ - ic74hc595_shift_io_pins() +#define io12_set_output ic74hc595_set_pin(DIR3) +#define io12_clear_output ic74hc595_clear_pin(DIR3) +#define io12_toggle_output ic74hc595_toggle_pin(DIR3) #define io12_get_output ic74hc595_get_pin(DIR3) #define io12_config_input #define io12_config_pullup @@ -429,15 +357,9 @@ extern "C" #define io13_get_input mcu_get_input(DIR4) #elif ASSERT_PIN_EXTENDED(DIR4) #define io13_config_output -#define io13_set_output \ - ic74hc595_set_pin(DIR4); \ - ic74hc595_shift_io_pins() -#define io13_clear_output \ - ic74hc595_clear_pin(DIR4); \ - ic74hc595_shift_io_pins() -#define io13_toggle_output \ - ic74hc595_toggle_pin(DIR4); \ - ic74hc595_shift_io_pins() +#define io13_set_output ic74hc595_set_pin(DIR4) +#define io13_clear_output ic74hc595_clear_pin(DIR4) +#define io13_toggle_output ic74hc595_toggle_pin(DIR4) #define io13_get_output ic74hc595_get_pin(DIR4) #define io13_config_input #define io13_config_pullup @@ -463,15 +385,9 @@ extern "C" #define io14_get_input mcu_get_input(DIR5) #elif ASSERT_PIN_EXTENDED(DIR5) #define io14_config_output -#define io14_set_output \ - ic74hc595_set_pin(DIR5); \ - ic74hc595_shift_io_pins() -#define io14_clear_output \ - ic74hc595_clear_pin(DIR5); \ - ic74hc595_shift_io_pins() -#define io14_toggle_output \ - ic74hc595_toggle_pin(DIR5); \ - ic74hc595_shift_io_pins() +#define io14_set_output ic74hc595_set_pin(DIR5) +#define io14_clear_output ic74hc595_clear_pin(DIR5) +#define io14_toggle_output ic74hc595_toggle_pin(DIR5) #define io14_get_output ic74hc595_get_pin(DIR5) #define io14_config_input #define io14_config_pullup @@ -497,15 +413,9 @@ extern "C" #define io15_get_input mcu_get_input(DIR6) #elif ASSERT_PIN_EXTENDED(DIR6) #define io15_config_output -#define io15_set_output \ - ic74hc595_set_pin(DIR6); \ - ic74hc595_shift_io_pins() -#define io15_clear_output \ - ic74hc595_clear_pin(DIR6); \ - ic74hc595_shift_io_pins() -#define io15_toggle_output \ - ic74hc595_toggle_pin(DIR6); \ - ic74hc595_shift_io_pins() +#define io15_set_output ic74hc595_set_pin(DIR6) +#define io15_clear_output ic74hc595_clear_pin(DIR6) +#define io15_toggle_output ic74hc595_toggle_pin(DIR6) #define io15_get_output ic74hc595_get_pin(DIR6) #define io15_config_input #define io15_config_pullup @@ -531,15 +441,9 @@ extern "C" #define io16_get_input mcu_get_input(DIR7) #elif ASSERT_PIN_EXTENDED(DIR7) #define io16_config_output -#define io16_set_output \ - ic74hc595_set_pin(DIR7); \ - ic74hc595_shift_io_pins() -#define io16_clear_output \ - ic74hc595_clear_pin(DIR7); \ - ic74hc595_shift_io_pins() -#define io16_toggle_output \ - ic74hc595_toggle_pin(DIR7); \ - ic74hc595_shift_io_pins() +#define io16_set_output ic74hc595_set_pin(DIR7) +#define io16_clear_output ic74hc595_clear_pin(DIR7) +#define io16_toggle_output ic74hc595_toggle_pin(DIR7) #define io16_get_output ic74hc595_get_pin(DIR7) #define io16_config_input #define io16_config_pullup @@ -565,15 +469,9 @@ extern "C" #define io17_get_input mcu_get_input(STEP0_EN) #elif ASSERT_PIN_EXTENDED(STEP0_EN) #define io17_config_output -#define io17_set_output \ - ic74hc595_set_pin(STEP0_EN); \ - ic74hc595_shift_io_pins() -#define io17_clear_output \ - ic74hc595_clear_pin(STEP0_EN); \ - ic74hc595_shift_io_pins() -#define io17_toggle_output \ - ic74hc595_toggle_pin(STEP0_EN); \ - ic74hc595_shift_io_pins() +#define io17_set_output ic74hc595_set_pin(STEP0_EN) +#define io17_clear_output ic74hc595_clear_pin(STEP0_EN) +#define io17_toggle_output ic74hc595_toggle_pin(STEP0_EN) #define io17_get_output ic74hc595_get_pin(STEP0_EN) #define io17_config_input #define io17_config_pullup @@ -599,15 +497,9 @@ extern "C" #define io18_get_input mcu_get_input(STEP1_EN) #elif ASSERT_PIN_EXTENDED(STEP1_EN) #define io18_config_output -#define io18_set_output \ - ic74hc595_set_pin(STEP1_EN); \ - ic74hc595_shift_io_pins() -#define io18_clear_output \ - ic74hc595_clear_pin(STEP1_EN); \ - ic74hc595_shift_io_pins() -#define io18_toggle_output \ - ic74hc595_toggle_pin(STEP1_EN); \ - ic74hc595_shift_io_pins() +#define io18_set_output ic74hc595_set_pin(STEP1_EN) +#define io18_clear_output ic74hc595_clear_pin(STEP1_EN) +#define io18_toggle_output ic74hc595_toggle_pin(STEP1_EN) #define io18_get_output ic74hc595_get_pin(STEP1_EN) #define io18_config_input #define io18_config_pullup @@ -633,15 +525,9 @@ extern "C" #define io19_get_input mcu_get_input(STEP2_EN) #elif ASSERT_PIN_EXTENDED(STEP2_EN) #define io19_config_output -#define io19_set_output \ - ic74hc595_set_pin(STEP2_EN); \ - ic74hc595_shift_io_pins() -#define io19_clear_output \ - ic74hc595_clear_pin(STEP2_EN); \ - ic74hc595_shift_io_pins() -#define io19_toggle_output \ - ic74hc595_toggle_pin(STEP2_EN); \ - ic74hc595_shift_io_pins() +#define io19_set_output ic74hc595_set_pin(STEP2_EN) +#define io19_clear_output ic74hc595_clear_pin(STEP2_EN) +#define io19_toggle_output ic74hc595_toggle_pin(STEP2_EN) #define io19_get_output ic74hc595_get_pin(STEP2_EN) #define io19_config_input #define io19_config_pullup @@ -667,15 +553,9 @@ extern "C" #define io20_get_input mcu_get_input(STEP3_EN) #elif ASSERT_PIN_EXTENDED(STEP3_EN) #define io20_config_output -#define io20_set_output \ - ic74hc595_set_pin(STEP3_EN); \ - ic74hc595_shift_io_pins() -#define io20_clear_output \ - ic74hc595_clear_pin(STEP3_EN); \ - ic74hc595_shift_io_pins() -#define io20_toggle_output \ - ic74hc595_toggle_pin(STEP3_EN); \ - ic74hc595_shift_io_pins() +#define io20_set_output ic74hc595_set_pin(STEP3_EN) +#define io20_clear_output ic74hc595_clear_pin(STEP3_EN) +#define io20_toggle_output ic74hc595_toggle_pin(STEP3_EN) #define io20_get_output ic74hc595_get_pin(STEP3_EN) #define io20_config_input #define io20_config_pullup @@ -701,15 +581,9 @@ extern "C" #define io21_get_input mcu_get_input(STEP4_EN) #elif ASSERT_PIN_EXTENDED(STEP4_EN) #define io21_config_output -#define io21_set_output \ - ic74hc595_set_pin(STEP4_EN); \ - ic74hc595_shift_io_pins() -#define io21_clear_output \ - ic74hc595_clear_pin(STEP4_EN); \ - ic74hc595_shift_io_pins() -#define io21_toggle_output \ - ic74hc595_toggle_pin(STEP4_EN); \ - ic74hc595_shift_io_pins() +#define io21_set_output ic74hc595_set_pin(STEP4_EN) +#define io21_clear_output ic74hc595_clear_pin(STEP4_EN) +#define io21_toggle_output ic74hc595_toggle_pin(STEP4_EN) #define io21_get_output ic74hc595_get_pin(STEP4_EN) #define io21_config_input #define io21_config_pullup @@ -735,15 +609,9 @@ extern "C" #define io22_get_input mcu_get_input(STEP5_EN) #elif ASSERT_PIN_EXTENDED(STEP5_EN) #define io22_config_output -#define io22_set_output \ - ic74hc595_set_pin(STEP5_EN); \ - ic74hc595_shift_io_pins() -#define io22_clear_output \ - ic74hc595_clear_pin(STEP5_EN); \ - ic74hc595_shift_io_pins() -#define io22_toggle_output \ - ic74hc595_toggle_pin(STEP5_EN); \ - ic74hc595_shift_io_pins() +#define io22_set_output ic74hc595_set_pin(STEP5_EN) +#define io22_clear_output ic74hc595_clear_pin(STEP5_EN) +#define io22_toggle_output ic74hc595_toggle_pin(STEP5_EN) #define io22_get_output ic74hc595_get_pin(STEP5_EN) #define io22_config_input #define io22_config_pullup @@ -769,15 +637,9 @@ extern "C" #define io23_get_input mcu_get_input(STEP6_EN) #elif ASSERT_PIN_EXTENDED(STEP6_EN) #define io23_config_output -#define io23_set_output \ - ic74hc595_set_pin(STEP6_EN); \ - ic74hc595_shift_io_pins() -#define io23_clear_output \ - ic74hc595_clear_pin(STEP6_EN); \ - ic74hc595_shift_io_pins() -#define io23_toggle_output \ - ic74hc595_toggle_pin(STEP6_EN); \ - ic74hc595_shift_io_pins() +#define io23_set_output ic74hc595_set_pin(STEP6_EN) +#define io23_clear_output ic74hc595_clear_pin(STEP6_EN) +#define io23_toggle_output ic74hc595_toggle_pin(STEP6_EN) #define io23_get_output ic74hc595_get_pin(STEP6_EN) #define io23_config_input #define io23_config_pullup @@ -803,15 +665,9 @@ extern "C" #define io24_get_input mcu_get_input(STEP7_EN) #elif ASSERT_PIN_EXTENDED(STEP7_EN) #define io24_config_output -#define io24_set_output \ - ic74hc595_set_pin(STEP7_EN); \ - ic74hc595_shift_io_pins() -#define io24_clear_output \ - ic74hc595_clear_pin(STEP7_EN); \ - ic74hc595_shift_io_pins() -#define io24_toggle_output \ - ic74hc595_toggle_pin(STEP7_EN); \ - ic74hc595_shift_io_pins() +#define io24_set_output ic74hc595_set_pin(STEP7_EN) +#define io24_clear_output ic74hc595_clear_pin(STEP7_EN) +#define io24_toggle_output ic74hc595_toggle_pin(STEP7_EN) #define io24_get_output ic74hc595_get_pin(STEP7_EN) #define io24_config_input #define io24_config_pullup @@ -837,15 +693,9 @@ extern "C" #define io25_get_input mcu_get_input(PWM0) #elif ASSERT_PIN_EXTENDED(PWM0) #define io25_config_output -#define io25_set_output \ - ic74hc595_set_pin(PWM0); \ - ic74hc595_shift_io_pins() -#define io25_clear_output \ - ic74hc595_clear_pin(PWM0); \ - ic74hc595_shift_io_pins() -#define io25_toggle_output \ - ic74hc595_toggle_pin(PWM0); \ - ic74hc595_shift_io_pins() +#define io25_set_output ic74hc595_set_pin(PWM0) +#define io25_clear_output ic74hc595_clear_pin(PWM0) +#define io25_toggle_output ic74hc595_toggle_pin(PWM0) #define io25_get_output ic74hc595_get_pin(PWM0) #define io25_config_input #define io25_config_pullup @@ -871,15 +721,9 @@ extern "C" #define io26_get_input mcu_get_input(PWM1) #elif ASSERT_PIN_EXTENDED(PWM1) #define io26_config_output -#define io26_set_output \ - ic74hc595_set_pin(PWM1); \ - ic74hc595_shift_io_pins() -#define io26_clear_output \ - ic74hc595_clear_pin(PWM1); \ - ic74hc595_shift_io_pins() -#define io26_toggle_output \ - ic74hc595_toggle_pin(PWM1); \ - ic74hc595_shift_io_pins() +#define io26_set_output ic74hc595_set_pin(PWM1) +#define io26_clear_output ic74hc595_clear_pin(PWM1) +#define io26_toggle_output ic74hc595_toggle_pin(PWM1) #define io26_get_output ic74hc595_get_pin(PWM1) #define io26_config_input #define io26_config_pullup @@ -905,15 +749,9 @@ extern "C" #define io27_get_input mcu_get_input(PWM2) #elif ASSERT_PIN_EXTENDED(PWM2) #define io27_config_output -#define io27_set_output \ - ic74hc595_set_pin(PWM2); \ - ic74hc595_shift_io_pins() -#define io27_clear_output \ - ic74hc595_clear_pin(PWM2); \ - ic74hc595_shift_io_pins() -#define io27_toggle_output \ - ic74hc595_toggle_pin(PWM2); \ - ic74hc595_shift_io_pins() +#define io27_set_output ic74hc595_set_pin(PWM2) +#define io27_clear_output ic74hc595_clear_pin(PWM2) +#define io27_toggle_output ic74hc595_toggle_pin(PWM2) #define io27_get_output ic74hc595_get_pin(PWM2) #define io27_config_input #define io27_config_pullup @@ -939,15 +777,9 @@ extern "C" #define io28_get_input mcu_get_input(PWM3) #elif ASSERT_PIN_EXTENDED(PWM3) #define io28_config_output -#define io28_set_output \ - ic74hc595_set_pin(PWM3); \ - ic74hc595_shift_io_pins() -#define io28_clear_output \ - ic74hc595_clear_pin(PWM3); \ - ic74hc595_shift_io_pins() -#define io28_toggle_output \ - ic74hc595_toggle_pin(PWM3); \ - ic74hc595_shift_io_pins() +#define io28_set_output ic74hc595_set_pin(PWM3) +#define io28_clear_output ic74hc595_clear_pin(PWM3) +#define io28_toggle_output ic74hc595_toggle_pin(PWM3) #define io28_get_output ic74hc595_get_pin(PWM3) #define io28_config_input #define io28_config_pullup @@ -973,15 +805,9 @@ extern "C" #define io29_get_input mcu_get_input(PWM4) #elif ASSERT_PIN_EXTENDED(PWM4) #define io29_config_output -#define io29_set_output \ - ic74hc595_set_pin(PWM4); \ - ic74hc595_shift_io_pins() -#define io29_clear_output \ - ic74hc595_clear_pin(PWM4); \ - ic74hc595_shift_io_pins() -#define io29_toggle_output \ - ic74hc595_toggle_pin(PWM4); \ - ic74hc595_shift_io_pins() +#define io29_set_output ic74hc595_set_pin(PWM4) +#define io29_clear_output ic74hc595_clear_pin(PWM4) +#define io29_toggle_output ic74hc595_toggle_pin(PWM4) #define io29_get_output ic74hc595_get_pin(PWM4) #define io29_config_input #define io29_config_pullup @@ -1007,15 +833,9 @@ extern "C" #define io30_get_input mcu_get_input(PWM5) #elif ASSERT_PIN_EXTENDED(PWM5) #define io30_config_output -#define io30_set_output \ - ic74hc595_set_pin(PWM5); \ - ic74hc595_shift_io_pins() -#define io30_clear_output \ - ic74hc595_clear_pin(PWM5); \ - ic74hc595_shift_io_pins() -#define io30_toggle_output \ - ic74hc595_toggle_pin(PWM5); \ - ic74hc595_shift_io_pins() +#define io30_set_output ic74hc595_set_pin(PWM5) +#define io30_clear_output ic74hc595_clear_pin(PWM5) +#define io30_toggle_output ic74hc595_toggle_pin(PWM5) #define io30_get_output ic74hc595_get_pin(PWM5) #define io30_config_input #define io30_config_pullup @@ -1041,15 +861,9 @@ extern "C" #define io31_get_input mcu_get_input(PWM6) #elif ASSERT_PIN_EXTENDED(PWM6) #define io31_config_output -#define io31_set_output \ - ic74hc595_set_pin(PWM6); \ - ic74hc595_shift_io_pins() -#define io31_clear_output \ - ic74hc595_clear_pin(PWM6); \ - ic74hc595_shift_io_pins() -#define io31_toggle_output \ - ic74hc595_toggle_pin(PWM6); \ - ic74hc595_shift_io_pins() +#define io31_set_output ic74hc595_set_pin(PWM6) +#define io31_clear_output ic74hc595_clear_pin(PWM6) +#define io31_toggle_output ic74hc595_toggle_pin(PWM6) #define io31_get_output ic74hc595_get_pin(PWM6) #define io31_config_input #define io31_config_pullup @@ -1075,15 +889,9 @@ extern "C" #define io32_get_input mcu_get_input(PWM7) #elif ASSERT_PIN_EXTENDED(PWM7) #define io32_config_output -#define io32_set_output \ - ic74hc595_set_pin(PWM7); \ - ic74hc595_shift_io_pins() -#define io32_clear_output \ - ic74hc595_clear_pin(PWM7); \ - ic74hc595_shift_io_pins() -#define io32_toggle_output \ - ic74hc595_toggle_pin(PWM7); \ - ic74hc595_shift_io_pins() +#define io32_set_output ic74hc595_set_pin(PWM7) +#define io32_clear_output ic74hc595_clear_pin(PWM7) +#define io32_toggle_output ic74hc595_toggle_pin(PWM7) #define io32_get_output ic74hc595_get_pin(PWM7) #define io32_config_input #define io32_config_pullup @@ -1109,15 +917,9 @@ extern "C" #define io33_get_input mcu_get_input(PWM8) #elif ASSERT_PIN_EXTENDED(PWM8) #define io33_config_output -#define io33_set_output \ - ic74hc595_set_pin(PWM8); \ - ic74hc595_shift_io_pins() -#define io33_clear_output \ - ic74hc595_clear_pin(PWM8); \ - ic74hc595_shift_io_pins() -#define io33_toggle_output \ - ic74hc595_toggle_pin(PWM8); \ - ic74hc595_shift_io_pins() +#define io33_set_output ic74hc595_set_pin(PWM8) +#define io33_clear_output ic74hc595_clear_pin(PWM8) +#define io33_toggle_output ic74hc595_toggle_pin(PWM8) #define io33_get_output ic74hc595_get_pin(PWM8) #define io33_config_input #define io33_config_pullup @@ -1143,15 +945,9 @@ extern "C" #define io34_get_input mcu_get_input(PWM9) #elif ASSERT_PIN_EXTENDED(PWM9) #define io34_config_output -#define io34_set_output \ - ic74hc595_set_pin(PWM9); \ - ic74hc595_shift_io_pins() -#define io34_clear_output \ - ic74hc595_clear_pin(PWM9); \ - ic74hc595_shift_io_pins() -#define io34_toggle_output \ - ic74hc595_toggle_pin(PWM9); \ - ic74hc595_shift_io_pins() +#define io34_set_output ic74hc595_set_pin(PWM9) +#define io34_clear_output ic74hc595_clear_pin(PWM9) +#define io34_toggle_output ic74hc595_toggle_pin(PWM9) #define io34_get_output ic74hc595_get_pin(PWM9) #define io34_config_input #define io34_config_pullup @@ -1177,15 +973,9 @@ extern "C" #define io35_get_input mcu_get_input(PWM10) #elif ASSERT_PIN_EXTENDED(PWM10) #define io35_config_output -#define io35_set_output \ - ic74hc595_set_pin(PWM10); \ - ic74hc595_shift_io_pins() -#define io35_clear_output \ - ic74hc595_clear_pin(PWM10); \ - ic74hc595_shift_io_pins() -#define io35_toggle_output \ - ic74hc595_toggle_pin(PWM10); \ - ic74hc595_shift_io_pins() +#define io35_set_output ic74hc595_set_pin(PWM10) +#define io35_clear_output ic74hc595_clear_pin(PWM10) +#define io35_toggle_output ic74hc595_toggle_pin(PWM10) #define io35_get_output ic74hc595_get_pin(PWM10) #define io35_config_input #define io35_config_pullup @@ -1211,15 +1001,9 @@ extern "C" #define io36_get_input mcu_get_input(PWM11) #elif ASSERT_PIN_EXTENDED(PWM11) #define io36_config_output -#define io36_set_output \ - ic74hc595_set_pin(PWM11); \ - ic74hc595_shift_io_pins() -#define io36_clear_output \ - ic74hc595_clear_pin(PWM11); \ - ic74hc595_shift_io_pins() -#define io36_toggle_output \ - ic74hc595_toggle_pin(PWM11); \ - ic74hc595_shift_io_pins() +#define io36_set_output ic74hc595_set_pin(PWM11) +#define io36_clear_output ic74hc595_clear_pin(PWM11) +#define io36_toggle_output ic74hc595_toggle_pin(PWM11) #define io36_get_output ic74hc595_get_pin(PWM11) #define io36_config_input #define io36_config_pullup @@ -1245,15 +1029,9 @@ extern "C" #define io37_get_input mcu_get_input(PWM12) #elif ASSERT_PIN_EXTENDED(PWM12) #define io37_config_output -#define io37_set_output \ - ic74hc595_set_pin(PWM12); \ - ic74hc595_shift_io_pins() -#define io37_clear_output \ - ic74hc595_clear_pin(PWM12); \ - ic74hc595_shift_io_pins() -#define io37_toggle_output \ - ic74hc595_toggle_pin(PWM12); \ - ic74hc595_shift_io_pins() +#define io37_set_output ic74hc595_set_pin(PWM12) +#define io37_clear_output ic74hc595_clear_pin(PWM12) +#define io37_toggle_output ic74hc595_toggle_pin(PWM12) #define io37_get_output ic74hc595_get_pin(PWM12) #define io37_config_input #define io37_config_pullup @@ -1279,15 +1057,9 @@ extern "C" #define io38_get_input mcu_get_input(PWM13) #elif ASSERT_PIN_EXTENDED(PWM13) #define io38_config_output -#define io38_set_output \ - ic74hc595_set_pin(PWM13); \ - ic74hc595_shift_io_pins() -#define io38_clear_output \ - ic74hc595_clear_pin(PWM13); \ - ic74hc595_shift_io_pins() -#define io38_toggle_output \ - ic74hc595_toggle_pin(PWM13); \ - ic74hc595_shift_io_pins() +#define io38_set_output ic74hc595_set_pin(PWM13) +#define io38_clear_output ic74hc595_clear_pin(PWM13) +#define io38_toggle_output ic74hc595_toggle_pin(PWM13) #define io38_get_output ic74hc595_get_pin(PWM13) #define io38_config_input #define io38_config_pullup @@ -1313,15 +1085,9 @@ extern "C" #define io39_get_input mcu_get_input(PWM14) #elif ASSERT_PIN_EXTENDED(PWM14) #define io39_config_output -#define io39_set_output \ - ic74hc595_set_pin(PWM14); \ - ic74hc595_shift_io_pins() -#define io39_clear_output \ - ic74hc595_clear_pin(PWM14); \ - ic74hc595_shift_io_pins() -#define io39_toggle_output \ - ic74hc595_toggle_pin(PWM14); \ - ic74hc595_shift_io_pins() +#define io39_set_output ic74hc595_set_pin(PWM14) +#define io39_clear_output ic74hc595_clear_pin(PWM14) +#define io39_toggle_output ic74hc595_toggle_pin(PWM14) #define io39_get_output ic74hc595_get_pin(PWM14) #define io39_config_input #define io39_config_pullup @@ -1347,15 +1113,9 @@ extern "C" #define io40_get_input mcu_get_input(PWM15) #elif ASSERT_PIN_EXTENDED(PWM15) #define io40_config_output -#define io40_set_output \ - ic74hc595_set_pin(PWM15); \ - ic74hc595_shift_io_pins() -#define io40_clear_output \ - ic74hc595_clear_pin(PWM15); \ - ic74hc595_shift_io_pins() -#define io40_toggle_output \ - ic74hc595_toggle_pin(PWM15); \ - ic74hc595_shift_io_pins() +#define io40_set_output ic74hc595_set_pin(PWM15) +#define io40_clear_output ic74hc595_clear_pin(PWM15) +#define io40_toggle_output ic74hc595_toggle_pin(PWM15) #define io40_get_output ic74hc595_get_pin(PWM15) #define io40_config_input #define io40_config_pullup @@ -1381,15 +1141,9 @@ extern "C" #define io41_get_input mcu_get_input(SERVO0) #elif ASSERT_PIN_EXTENDED(SERVO0) #define io41_config_output -#define io41_set_output \ - ic74hc595_set_pin(SERVO0); \ - ic74hc595_shift_io_pins() -#define io41_clear_output \ - ic74hc595_clear_pin(SERVO0); \ - ic74hc595_shift_io_pins() -#define io41_toggle_output \ - ic74hc595_toggle_pin(SERVO0); \ - ic74hc595_shift_io_pins() +#define io41_set_output ic74hc595_set_pin(SERVO0) +#define io41_clear_output ic74hc595_clear_pin(SERVO0) +#define io41_toggle_output ic74hc595_toggle_pin(SERVO0) #define io41_get_output ic74hc595_get_pin(SERVO0) #define io41_config_input #define io41_config_pullup @@ -1415,15 +1169,9 @@ extern "C" #define io42_get_input mcu_get_input(SERVO1) #elif ASSERT_PIN_EXTENDED(SERVO1) #define io42_config_output -#define io42_set_output \ - ic74hc595_set_pin(SERVO1); \ - ic74hc595_shift_io_pins() -#define io42_clear_output \ - ic74hc595_clear_pin(SERVO1); \ - ic74hc595_shift_io_pins() -#define io42_toggle_output \ - ic74hc595_toggle_pin(SERVO1); \ - ic74hc595_shift_io_pins() +#define io42_set_output ic74hc595_set_pin(SERVO1) +#define io42_clear_output ic74hc595_clear_pin(SERVO1) +#define io42_toggle_output ic74hc595_toggle_pin(SERVO1) #define io42_get_output ic74hc595_get_pin(SERVO1) #define io42_config_input #define io42_config_pullup @@ -1449,15 +1197,9 @@ extern "C" #define io43_get_input mcu_get_input(SERVO2) #elif ASSERT_PIN_EXTENDED(SERVO2) #define io43_config_output -#define io43_set_output \ - ic74hc595_set_pin(SERVO2); \ - ic74hc595_shift_io_pins() -#define io43_clear_output \ - ic74hc595_clear_pin(SERVO2); \ - ic74hc595_shift_io_pins() -#define io43_toggle_output \ - ic74hc595_toggle_pin(SERVO2); \ - ic74hc595_shift_io_pins() +#define io43_set_output ic74hc595_set_pin(SERVO2) +#define io43_clear_output ic74hc595_clear_pin(SERVO2) +#define io43_toggle_output ic74hc595_toggle_pin(SERVO2) #define io43_get_output ic74hc595_get_pin(SERVO2) #define io43_config_input #define io43_config_pullup @@ -1483,15 +1225,9 @@ extern "C" #define io44_get_input mcu_get_input(SERVO3) #elif ASSERT_PIN_EXTENDED(SERVO3) #define io44_config_output -#define io44_set_output \ - ic74hc595_set_pin(SERVO3); \ - ic74hc595_shift_io_pins() -#define io44_clear_output \ - ic74hc595_clear_pin(SERVO3); \ - ic74hc595_shift_io_pins() -#define io44_toggle_output \ - ic74hc595_toggle_pin(SERVO3); \ - ic74hc595_shift_io_pins() +#define io44_set_output ic74hc595_set_pin(SERVO3) +#define io44_clear_output ic74hc595_clear_pin(SERVO3) +#define io44_toggle_output ic74hc595_toggle_pin(SERVO3) #define io44_get_output ic74hc595_get_pin(SERVO3) #define io44_config_input #define io44_config_pullup @@ -1517,15 +1253,9 @@ extern "C" #define io45_get_input mcu_get_input(SERVO4) #elif ASSERT_PIN_EXTENDED(SERVO4) #define io45_config_output -#define io45_set_output \ - ic74hc595_set_pin(SERVO4); \ - ic74hc595_shift_io_pins() -#define io45_clear_output \ - ic74hc595_clear_pin(SERVO4); \ - ic74hc595_shift_io_pins() -#define io45_toggle_output \ - ic74hc595_toggle_pin(SERVO4); \ - ic74hc595_shift_io_pins() +#define io45_set_output ic74hc595_set_pin(SERVO4) +#define io45_clear_output ic74hc595_clear_pin(SERVO4) +#define io45_toggle_output ic74hc595_toggle_pin(SERVO4) #define io45_get_output ic74hc595_get_pin(SERVO4) #define io45_config_input #define io45_config_pullup @@ -1551,15 +1281,9 @@ extern "C" #define io46_get_input mcu_get_input(SERVO5) #elif ASSERT_PIN_EXTENDED(SERVO5) #define io46_config_output -#define io46_set_output \ - ic74hc595_set_pin(SERVO5); \ - ic74hc595_shift_io_pins() -#define io46_clear_output \ - ic74hc595_clear_pin(SERVO5); \ - ic74hc595_shift_io_pins() -#define io46_toggle_output \ - ic74hc595_toggle_pin(SERVO5); \ - ic74hc595_shift_io_pins() +#define io46_set_output ic74hc595_set_pin(SERVO5) +#define io46_clear_output ic74hc595_clear_pin(SERVO5) +#define io46_toggle_output ic74hc595_toggle_pin(SERVO5) #define io46_get_output ic74hc595_get_pin(SERVO5) #define io46_config_input #define io46_config_pullup @@ -1585,15 +1309,9 @@ extern "C" #define io47_get_input mcu_get_input(DOUT0) #elif ASSERT_PIN_EXTENDED(DOUT0) #define io47_config_output -#define io47_set_output \ - ic74hc595_set_pin(DOUT0); \ - ic74hc595_shift_io_pins() -#define io47_clear_output \ - ic74hc595_clear_pin(DOUT0); \ - ic74hc595_shift_io_pins() -#define io47_toggle_output \ - ic74hc595_toggle_pin(DOUT0); \ - ic74hc595_shift_io_pins() +#define io47_set_output ic74hc595_set_pin(DOUT0) +#define io47_clear_output ic74hc595_clear_pin(DOUT0) +#define io47_toggle_output ic74hc595_toggle_pin(DOUT0) #define io47_get_output ic74hc595_get_pin(DOUT0) #define io47_config_input #define io47_config_pullup @@ -1619,15 +1337,9 @@ extern "C" #define io48_get_input mcu_get_input(DOUT1) #elif ASSERT_PIN_EXTENDED(DOUT1) #define io48_config_output -#define io48_set_output \ - ic74hc595_set_pin(DOUT1); \ - ic74hc595_shift_io_pins() -#define io48_clear_output \ - ic74hc595_clear_pin(DOUT1); \ - ic74hc595_shift_io_pins() -#define io48_toggle_output \ - ic74hc595_toggle_pin(DOUT1); \ - ic74hc595_shift_io_pins() +#define io48_set_output ic74hc595_set_pin(DOUT1) +#define io48_clear_output ic74hc595_clear_pin(DOUT1) +#define io48_toggle_output ic74hc595_toggle_pin(DOUT1) #define io48_get_output ic74hc595_get_pin(DOUT1) #define io48_config_input #define io48_config_pullup @@ -1653,15 +1365,9 @@ extern "C" #define io49_get_input mcu_get_input(DOUT2) #elif ASSERT_PIN_EXTENDED(DOUT2) #define io49_config_output -#define io49_set_output \ - ic74hc595_set_pin(DOUT2); \ - ic74hc595_shift_io_pins() -#define io49_clear_output \ - ic74hc595_clear_pin(DOUT2); \ - ic74hc595_shift_io_pins() -#define io49_toggle_output \ - ic74hc595_toggle_pin(DOUT2); \ - ic74hc595_shift_io_pins() +#define io49_set_output ic74hc595_set_pin(DOUT2) +#define io49_clear_output ic74hc595_clear_pin(DOUT2) +#define io49_toggle_output ic74hc595_toggle_pin(DOUT2) #define io49_get_output ic74hc595_get_pin(DOUT2) #define io49_config_input #define io49_config_pullup @@ -1687,15 +1393,9 @@ extern "C" #define io50_get_input mcu_get_input(DOUT3) #elif ASSERT_PIN_EXTENDED(DOUT3) #define io50_config_output -#define io50_set_output \ - ic74hc595_set_pin(DOUT3); \ - ic74hc595_shift_io_pins() -#define io50_clear_output \ - ic74hc595_clear_pin(DOUT3); \ - ic74hc595_shift_io_pins() -#define io50_toggle_output \ - ic74hc595_toggle_pin(DOUT3); \ - ic74hc595_shift_io_pins() +#define io50_set_output ic74hc595_set_pin(DOUT3) +#define io50_clear_output ic74hc595_clear_pin(DOUT3) +#define io50_toggle_output ic74hc595_toggle_pin(DOUT3) #define io50_get_output ic74hc595_get_pin(DOUT3) #define io50_config_input #define io50_config_pullup @@ -1721,15 +1421,9 @@ extern "C" #define io51_get_input mcu_get_input(DOUT4) #elif ASSERT_PIN_EXTENDED(DOUT4) #define io51_config_output -#define io51_set_output \ - ic74hc595_set_pin(DOUT4); \ - ic74hc595_shift_io_pins() -#define io51_clear_output \ - ic74hc595_clear_pin(DOUT4); \ - ic74hc595_shift_io_pins() -#define io51_toggle_output \ - ic74hc595_toggle_pin(DOUT4); \ - ic74hc595_shift_io_pins() +#define io51_set_output ic74hc595_set_pin(DOUT4) +#define io51_clear_output ic74hc595_clear_pin(DOUT4) +#define io51_toggle_output ic74hc595_toggle_pin(DOUT4) #define io51_get_output ic74hc595_get_pin(DOUT4) #define io51_config_input #define io51_config_pullup @@ -1755,15 +1449,9 @@ extern "C" #define io52_get_input mcu_get_input(DOUT5) #elif ASSERT_PIN_EXTENDED(DOUT5) #define io52_config_output -#define io52_set_output \ - ic74hc595_set_pin(DOUT5); \ - ic74hc595_shift_io_pins() -#define io52_clear_output \ - ic74hc595_clear_pin(DOUT5); \ - ic74hc595_shift_io_pins() -#define io52_toggle_output \ - ic74hc595_toggle_pin(DOUT5); \ - ic74hc595_shift_io_pins() +#define io52_set_output ic74hc595_set_pin(DOUT5) +#define io52_clear_output ic74hc595_clear_pin(DOUT5) +#define io52_toggle_output ic74hc595_toggle_pin(DOUT5) #define io52_get_output ic74hc595_get_pin(DOUT5) #define io52_config_input #define io52_config_pullup @@ -1789,15 +1477,9 @@ extern "C" #define io53_get_input mcu_get_input(DOUT6) #elif ASSERT_PIN_EXTENDED(DOUT6) #define io53_config_output -#define io53_set_output \ - ic74hc595_set_pin(DOUT6); \ - ic74hc595_shift_io_pins() -#define io53_clear_output \ - ic74hc595_clear_pin(DOUT6); \ - ic74hc595_shift_io_pins() -#define io53_toggle_output \ - ic74hc595_toggle_pin(DOUT6); \ - ic74hc595_shift_io_pins() +#define io53_set_output ic74hc595_set_pin(DOUT6) +#define io53_clear_output ic74hc595_clear_pin(DOUT6) +#define io53_toggle_output ic74hc595_toggle_pin(DOUT6) #define io53_get_output ic74hc595_get_pin(DOUT6) #define io53_config_input #define io53_config_pullup @@ -1823,15 +1505,9 @@ extern "C" #define io54_get_input mcu_get_input(DOUT7) #elif ASSERT_PIN_EXTENDED(DOUT7) #define io54_config_output -#define io54_set_output \ - ic74hc595_set_pin(DOUT7); \ - ic74hc595_shift_io_pins() -#define io54_clear_output \ - ic74hc595_clear_pin(DOUT7); \ - ic74hc595_shift_io_pins() -#define io54_toggle_output \ - ic74hc595_toggle_pin(DOUT7); \ - ic74hc595_shift_io_pins() +#define io54_set_output ic74hc595_set_pin(DOUT7) +#define io54_clear_output ic74hc595_clear_pin(DOUT7) +#define io54_toggle_output ic74hc595_toggle_pin(DOUT7) #define io54_get_output ic74hc595_get_pin(DOUT7) #define io54_config_input #define io54_config_pullup @@ -1857,15 +1533,9 @@ extern "C" #define io55_get_input mcu_get_input(DOUT8) #elif ASSERT_PIN_EXTENDED(DOUT8) #define io55_config_output -#define io55_set_output \ - ic74hc595_set_pin(DOUT8); \ - ic74hc595_shift_io_pins() -#define io55_clear_output \ - ic74hc595_clear_pin(DOUT8); \ - ic74hc595_shift_io_pins() -#define io55_toggle_output \ - ic74hc595_toggle_pin(DOUT8); \ - ic74hc595_shift_io_pins() +#define io55_set_output ic74hc595_set_pin(DOUT8) +#define io55_clear_output ic74hc595_clear_pin(DOUT8) +#define io55_toggle_output ic74hc595_toggle_pin(DOUT8) #define io55_get_output ic74hc595_get_pin(DOUT8) #define io55_config_input #define io55_config_pullup @@ -1891,15 +1561,9 @@ extern "C" #define io56_get_input mcu_get_input(DOUT9) #elif ASSERT_PIN_EXTENDED(DOUT9) #define io56_config_output -#define io56_set_output \ - ic74hc595_set_pin(DOUT9); \ - ic74hc595_shift_io_pins() -#define io56_clear_output \ - ic74hc595_clear_pin(DOUT9); \ - ic74hc595_shift_io_pins() -#define io56_toggle_output \ - ic74hc595_toggle_pin(DOUT9); \ - ic74hc595_shift_io_pins() +#define io56_set_output ic74hc595_set_pin(DOUT9) +#define io56_clear_output ic74hc595_clear_pin(DOUT9) +#define io56_toggle_output ic74hc595_toggle_pin(DOUT9) #define io56_get_output ic74hc595_get_pin(DOUT9) #define io56_config_input #define io56_config_pullup @@ -1925,15 +1589,9 @@ extern "C" #define io57_get_input mcu_get_input(DOUT10) #elif ASSERT_PIN_EXTENDED(DOUT10) #define io57_config_output -#define io57_set_output \ - ic74hc595_set_pin(DOUT10); \ - ic74hc595_shift_io_pins() -#define io57_clear_output \ - ic74hc595_clear_pin(DOUT10); \ - ic74hc595_shift_io_pins() -#define io57_toggle_output \ - ic74hc595_toggle_pin(DOUT10); \ - ic74hc595_shift_io_pins() +#define io57_set_output ic74hc595_set_pin(DOUT10) +#define io57_clear_output ic74hc595_clear_pin(DOUT10) +#define io57_toggle_output ic74hc595_toggle_pin(DOUT10) #define io57_get_output ic74hc595_get_pin(DOUT10) #define io57_config_input #define io57_config_pullup @@ -1959,15 +1617,9 @@ extern "C" #define io58_get_input mcu_get_input(DOUT11) #elif ASSERT_PIN_EXTENDED(DOUT11) #define io58_config_output -#define io58_set_output \ - ic74hc595_set_pin(DOUT11); \ - ic74hc595_shift_io_pins() -#define io58_clear_output \ - ic74hc595_clear_pin(DOUT11); \ - ic74hc595_shift_io_pins() -#define io58_toggle_output \ - ic74hc595_toggle_pin(DOUT11); \ - ic74hc595_shift_io_pins() +#define io58_set_output ic74hc595_set_pin(DOUT11) +#define io58_clear_output ic74hc595_clear_pin(DOUT11) +#define io58_toggle_output ic74hc595_toggle_pin(DOUT11) #define io58_get_output ic74hc595_get_pin(DOUT11) #define io58_config_input #define io58_config_pullup @@ -1993,15 +1645,9 @@ extern "C" #define io59_get_input mcu_get_input(DOUT12) #elif ASSERT_PIN_EXTENDED(DOUT12) #define io59_config_output -#define io59_set_output \ - ic74hc595_set_pin(DOUT12); \ - ic74hc595_shift_io_pins() -#define io59_clear_output \ - ic74hc595_clear_pin(DOUT12); \ - ic74hc595_shift_io_pins() -#define io59_toggle_output \ - ic74hc595_toggle_pin(DOUT12); \ - ic74hc595_shift_io_pins() +#define io59_set_output ic74hc595_set_pin(DOUT12) +#define io59_clear_output ic74hc595_clear_pin(DOUT12) +#define io59_toggle_output ic74hc595_toggle_pin(DOUT12) #define io59_get_output ic74hc595_get_pin(DOUT12) #define io59_config_input #define io59_config_pullup @@ -2027,15 +1673,9 @@ extern "C" #define io60_get_input mcu_get_input(DOUT13) #elif ASSERT_PIN_EXTENDED(DOUT13) #define io60_config_output -#define io60_set_output \ - ic74hc595_set_pin(DOUT13); \ - ic74hc595_shift_io_pins() -#define io60_clear_output \ - ic74hc595_clear_pin(DOUT13); \ - ic74hc595_shift_io_pins() -#define io60_toggle_output \ - ic74hc595_toggle_pin(DOUT13); \ - ic74hc595_shift_io_pins() +#define io60_set_output ic74hc595_set_pin(DOUT13) +#define io60_clear_output ic74hc595_clear_pin(DOUT13) +#define io60_toggle_output ic74hc595_toggle_pin(DOUT13) #define io60_get_output ic74hc595_get_pin(DOUT13) #define io60_config_input #define io60_config_pullup @@ -2061,15 +1701,9 @@ extern "C" #define io61_get_input mcu_get_input(DOUT14) #elif ASSERT_PIN_EXTENDED(DOUT14) #define io61_config_output -#define io61_set_output \ - ic74hc595_set_pin(DOUT14); \ - ic74hc595_shift_io_pins() -#define io61_clear_output \ - ic74hc595_clear_pin(DOUT14); \ - ic74hc595_shift_io_pins() -#define io61_toggle_output \ - ic74hc595_toggle_pin(DOUT14); \ - ic74hc595_shift_io_pins() +#define io61_set_output ic74hc595_set_pin(DOUT14) +#define io61_clear_output ic74hc595_clear_pin(DOUT14) +#define io61_toggle_output ic74hc595_toggle_pin(DOUT14) #define io61_get_output ic74hc595_get_pin(DOUT14) #define io61_config_input #define io61_config_pullup @@ -2095,15 +1729,9 @@ extern "C" #define io62_get_input mcu_get_input(DOUT15) #elif ASSERT_PIN_EXTENDED(DOUT15) #define io62_config_output -#define io62_set_output \ - ic74hc595_set_pin(DOUT15); \ - ic74hc595_shift_io_pins() -#define io62_clear_output \ - ic74hc595_clear_pin(DOUT15); \ - ic74hc595_shift_io_pins() -#define io62_toggle_output \ - ic74hc595_toggle_pin(DOUT15); \ - ic74hc595_shift_io_pins() +#define io62_set_output ic74hc595_set_pin(DOUT15) +#define io62_clear_output ic74hc595_clear_pin(DOUT15) +#define io62_toggle_output ic74hc595_toggle_pin(DOUT15) #define io62_get_output ic74hc595_get_pin(DOUT15) #define io62_config_input #define io62_config_pullup @@ -2129,15 +1757,9 @@ extern "C" #define io63_get_input mcu_get_input(DOUT16) #elif ASSERT_PIN_EXTENDED(DOUT16) #define io63_config_output -#define io63_set_output \ - ic74hc595_set_pin(DOUT16); \ - ic74hc595_shift_io_pins() -#define io63_clear_output \ - ic74hc595_clear_pin(DOUT16); \ - ic74hc595_shift_io_pins() -#define io63_toggle_output \ - ic74hc595_toggle_pin(DOUT16); \ - ic74hc595_shift_io_pins() +#define io63_set_output ic74hc595_set_pin(DOUT16) +#define io63_clear_output ic74hc595_clear_pin(DOUT16) +#define io63_toggle_output ic74hc595_toggle_pin(DOUT16) #define io63_get_output ic74hc595_get_pin(DOUT16) #define io63_config_input #define io63_config_pullup @@ -2163,15 +1785,9 @@ extern "C" #define io64_get_input mcu_get_input(DOUT17) #elif ASSERT_PIN_EXTENDED(DOUT17) #define io64_config_output -#define io64_set_output \ - ic74hc595_set_pin(DOUT17); \ - ic74hc595_shift_io_pins() -#define io64_clear_output \ - ic74hc595_clear_pin(DOUT17); \ - ic74hc595_shift_io_pins() -#define io64_toggle_output \ - ic74hc595_toggle_pin(DOUT17); \ - ic74hc595_shift_io_pins() +#define io64_set_output ic74hc595_set_pin(DOUT17) +#define io64_clear_output ic74hc595_clear_pin(DOUT17) +#define io64_toggle_output ic74hc595_toggle_pin(DOUT17) #define io64_get_output ic74hc595_get_pin(DOUT17) #define io64_config_input #define io64_config_pullup @@ -2197,15 +1813,9 @@ extern "C" #define io65_get_input mcu_get_input(DOUT18) #elif ASSERT_PIN_EXTENDED(DOUT18) #define io65_config_output -#define io65_set_output \ - ic74hc595_set_pin(DOUT18); \ - ic74hc595_shift_io_pins() -#define io65_clear_output \ - ic74hc595_clear_pin(DOUT18); \ - ic74hc595_shift_io_pins() -#define io65_toggle_output \ - ic74hc595_toggle_pin(DOUT18); \ - ic74hc595_shift_io_pins() +#define io65_set_output ic74hc595_set_pin(DOUT18) +#define io65_clear_output ic74hc595_clear_pin(DOUT18) +#define io65_toggle_output ic74hc595_toggle_pin(DOUT18) #define io65_get_output ic74hc595_get_pin(DOUT18) #define io65_config_input #define io65_config_pullup @@ -2231,15 +1841,9 @@ extern "C" #define io66_get_input mcu_get_input(DOUT19) #elif ASSERT_PIN_EXTENDED(DOUT19) #define io66_config_output -#define io66_set_output \ - ic74hc595_set_pin(DOUT19); \ - ic74hc595_shift_io_pins() -#define io66_clear_output \ - ic74hc595_clear_pin(DOUT19); \ - ic74hc595_shift_io_pins() -#define io66_toggle_output \ - ic74hc595_toggle_pin(DOUT19); \ - ic74hc595_shift_io_pins() +#define io66_set_output ic74hc595_set_pin(DOUT19) +#define io66_clear_output ic74hc595_clear_pin(DOUT19) +#define io66_toggle_output ic74hc595_toggle_pin(DOUT19) #define io66_get_output ic74hc595_get_pin(DOUT19) #define io66_config_input #define io66_config_pullup @@ -2265,15 +1869,9 @@ extern "C" #define io67_get_input mcu_get_input(DOUT20) #elif ASSERT_PIN_EXTENDED(DOUT20) #define io67_config_output -#define io67_set_output \ - ic74hc595_set_pin(DOUT20); \ - ic74hc595_shift_io_pins() -#define io67_clear_output \ - ic74hc595_clear_pin(DOUT20); \ - ic74hc595_shift_io_pins() -#define io67_toggle_output \ - ic74hc595_toggle_pin(DOUT20); \ - ic74hc595_shift_io_pins() +#define io67_set_output ic74hc595_set_pin(DOUT20) +#define io67_clear_output ic74hc595_clear_pin(DOUT20) +#define io67_toggle_output ic74hc595_toggle_pin(DOUT20) #define io67_get_output ic74hc595_get_pin(DOUT20) #define io67_config_input #define io67_config_pullup @@ -2299,15 +1897,9 @@ extern "C" #define io68_get_input mcu_get_input(DOUT21) #elif ASSERT_PIN_EXTENDED(DOUT21) #define io68_config_output -#define io68_set_output \ - ic74hc595_set_pin(DOUT21); \ - ic74hc595_shift_io_pins() -#define io68_clear_output \ - ic74hc595_clear_pin(DOUT21); \ - ic74hc595_shift_io_pins() -#define io68_toggle_output \ - ic74hc595_toggle_pin(DOUT21); \ - ic74hc595_shift_io_pins() +#define io68_set_output ic74hc595_set_pin(DOUT21) +#define io68_clear_output ic74hc595_clear_pin(DOUT21) +#define io68_toggle_output ic74hc595_toggle_pin(DOUT21) #define io68_get_output ic74hc595_get_pin(DOUT21) #define io68_config_input #define io68_config_pullup @@ -2333,15 +1925,9 @@ extern "C" #define io69_get_input mcu_get_input(DOUT22) #elif ASSERT_PIN_EXTENDED(DOUT22) #define io69_config_output -#define io69_set_output \ - ic74hc595_set_pin(DOUT22); \ - ic74hc595_shift_io_pins() -#define io69_clear_output \ - ic74hc595_clear_pin(DOUT22); \ - ic74hc595_shift_io_pins() -#define io69_toggle_output \ - ic74hc595_toggle_pin(DOUT22); \ - ic74hc595_shift_io_pins() +#define io69_set_output ic74hc595_set_pin(DOUT22) +#define io69_clear_output ic74hc595_clear_pin(DOUT22) +#define io69_toggle_output ic74hc595_toggle_pin(DOUT22) #define io69_get_output ic74hc595_get_pin(DOUT22) #define io69_config_input #define io69_config_pullup @@ -2367,15 +1953,9 @@ extern "C" #define io70_get_input mcu_get_input(DOUT23) #elif ASSERT_PIN_EXTENDED(DOUT23) #define io70_config_output -#define io70_set_output \ - ic74hc595_set_pin(DOUT23); \ - ic74hc595_shift_io_pins() -#define io70_clear_output \ - ic74hc595_clear_pin(DOUT23); \ - ic74hc595_shift_io_pins() -#define io70_toggle_output \ - ic74hc595_toggle_pin(DOUT23); \ - ic74hc595_shift_io_pins() +#define io70_set_output ic74hc595_set_pin(DOUT23) +#define io70_clear_output ic74hc595_clear_pin(DOUT23) +#define io70_toggle_output ic74hc595_toggle_pin(DOUT23) #define io70_get_output ic74hc595_get_pin(DOUT23) #define io70_config_input #define io70_config_pullup @@ -2401,15 +1981,9 @@ extern "C" #define io71_get_input mcu_get_input(DOUT24) #elif ASSERT_PIN_EXTENDED(DOUT24) #define io71_config_output -#define io71_set_output \ - ic74hc595_set_pin(DOUT24); \ - ic74hc595_shift_io_pins() -#define io71_clear_output \ - ic74hc595_clear_pin(DOUT24); \ - ic74hc595_shift_io_pins() -#define io71_toggle_output \ - ic74hc595_toggle_pin(DOUT24); \ - ic74hc595_shift_io_pins() +#define io71_set_output ic74hc595_set_pin(DOUT24) +#define io71_clear_output ic74hc595_clear_pin(DOUT24) +#define io71_toggle_output ic74hc595_toggle_pin(DOUT24) #define io71_get_output ic74hc595_get_pin(DOUT24) #define io71_config_input #define io71_config_pullup @@ -2435,15 +2009,9 @@ extern "C" #define io72_get_input mcu_get_input(DOUT25) #elif ASSERT_PIN_EXTENDED(DOUT25) #define io72_config_output -#define io72_set_output \ - ic74hc595_set_pin(DOUT25); \ - ic74hc595_shift_io_pins() -#define io72_clear_output \ - ic74hc595_clear_pin(DOUT25); \ - ic74hc595_shift_io_pins() -#define io72_toggle_output \ - ic74hc595_toggle_pin(DOUT25); \ - ic74hc595_shift_io_pins() +#define io72_set_output ic74hc595_set_pin(DOUT25) +#define io72_clear_output ic74hc595_clear_pin(DOUT25) +#define io72_toggle_output ic74hc595_toggle_pin(DOUT25) #define io72_get_output ic74hc595_get_pin(DOUT25) #define io72_config_input #define io72_config_pullup @@ -2469,15 +2037,9 @@ extern "C" #define io73_get_input mcu_get_input(DOUT26) #elif ASSERT_PIN_EXTENDED(DOUT26) #define io73_config_output -#define io73_set_output \ - ic74hc595_set_pin(DOUT26); \ - ic74hc595_shift_io_pins() -#define io73_clear_output \ - ic74hc595_clear_pin(DOUT26); \ - ic74hc595_shift_io_pins() -#define io73_toggle_output \ - ic74hc595_toggle_pin(DOUT26); \ - ic74hc595_shift_io_pins() +#define io73_set_output ic74hc595_set_pin(DOUT26) +#define io73_clear_output ic74hc595_clear_pin(DOUT26) +#define io73_toggle_output ic74hc595_toggle_pin(DOUT26) #define io73_get_output ic74hc595_get_pin(DOUT26) #define io73_config_input #define io73_config_pullup @@ -2503,15 +2065,9 @@ extern "C" #define io74_get_input mcu_get_input(DOUT27) #elif ASSERT_PIN_EXTENDED(DOUT27) #define io74_config_output -#define io74_set_output \ - ic74hc595_set_pin(DOUT27); \ - ic74hc595_shift_io_pins() -#define io74_clear_output \ - ic74hc595_clear_pin(DOUT27); \ - ic74hc595_shift_io_pins() -#define io74_toggle_output \ - ic74hc595_toggle_pin(DOUT27); \ - ic74hc595_shift_io_pins() +#define io74_set_output ic74hc595_set_pin(DOUT27) +#define io74_clear_output ic74hc595_clear_pin(DOUT27) +#define io74_toggle_output ic74hc595_toggle_pin(DOUT27) #define io74_get_output ic74hc595_get_pin(DOUT27) #define io74_config_input #define io74_config_pullup @@ -2537,15 +2093,9 @@ extern "C" #define io75_get_input mcu_get_input(DOUT28) #elif ASSERT_PIN_EXTENDED(DOUT28) #define io75_config_output -#define io75_set_output \ - ic74hc595_set_pin(DOUT28); \ - ic74hc595_shift_io_pins() -#define io75_clear_output \ - ic74hc595_clear_pin(DOUT28); \ - ic74hc595_shift_io_pins() -#define io75_toggle_output \ - ic74hc595_toggle_pin(DOUT28); \ - ic74hc595_shift_io_pins() +#define io75_set_output ic74hc595_set_pin(DOUT28) +#define io75_clear_output ic74hc595_clear_pin(DOUT28) +#define io75_toggle_output ic74hc595_toggle_pin(DOUT28) #define io75_get_output ic74hc595_get_pin(DOUT28) #define io75_config_input #define io75_config_pullup @@ -2571,15 +2121,9 @@ extern "C" #define io76_get_input mcu_get_input(DOUT29) #elif ASSERT_PIN_EXTENDED(DOUT29) #define io76_config_output -#define io76_set_output \ - ic74hc595_set_pin(DOUT29); \ - ic74hc595_shift_io_pins() -#define io76_clear_output \ - ic74hc595_clear_pin(DOUT29); \ - ic74hc595_shift_io_pins() -#define io76_toggle_output \ - ic74hc595_toggle_pin(DOUT29); \ - ic74hc595_shift_io_pins() +#define io76_set_output ic74hc595_set_pin(DOUT29) +#define io76_clear_output ic74hc595_clear_pin(DOUT29) +#define io76_toggle_output ic74hc595_toggle_pin(DOUT29) #define io76_get_output ic74hc595_get_pin(DOUT29) #define io76_config_input #define io76_config_pullup @@ -2605,15 +2149,9 @@ extern "C" #define io77_get_input mcu_get_input(DOUT30) #elif ASSERT_PIN_EXTENDED(DOUT30) #define io77_config_output -#define io77_set_output \ - ic74hc595_set_pin(DOUT30); \ - ic74hc595_shift_io_pins() -#define io77_clear_output \ - ic74hc595_clear_pin(DOUT30); \ - ic74hc595_shift_io_pins() -#define io77_toggle_output \ - ic74hc595_toggle_pin(DOUT30); \ - ic74hc595_shift_io_pins() +#define io77_set_output ic74hc595_set_pin(DOUT30) +#define io77_clear_output ic74hc595_clear_pin(DOUT30) +#define io77_toggle_output ic74hc595_toggle_pin(DOUT30) #define io77_get_output ic74hc595_get_pin(DOUT30) #define io77_config_input #define io77_config_pullup @@ -2639,15 +2177,9 @@ extern "C" #define io78_get_input mcu_get_input(DOUT31) #elif ASSERT_PIN_EXTENDED(DOUT31) #define io78_config_output -#define io78_set_output \ - ic74hc595_set_pin(DOUT31); \ - ic74hc595_shift_io_pins() -#define io78_clear_output \ - ic74hc595_clear_pin(DOUT31); \ - ic74hc595_shift_io_pins() -#define io78_toggle_output \ - ic74hc595_toggle_pin(DOUT31); \ - ic74hc595_shift_io_pins() +#define io78_set_output ic74hc595_set_pin(DOUT31) +#define io78_clear_output ic74hc595_clear_pin(DOUT31) +#define io78_toggle_output ic74hc595_toggle_pin(DOUT31) #define io78_get_output ic74hc595_get_pin(DOUT31) #define io78_config_input #define io78_config_pullup @@ -2673,15 +2205,9 @@ extern "C" #define io100_get_input mcu_get_input(LIMIT_X) #elif ASSERT_PIN_EXTENDED(LIMIT_X) #define io100_config_output -#define io100_set_output \ - ic74hc595_set_pin(LIMIT_X); \ - ic74hc595_shift_io_pins() -#define io100_clear_output \ - ic74hc595_clear_pin(LIMIT_X); \ - ic74hc595_shift_io_pins() -#define io100_toggle_output \ - ic74hc595_toggle_pin(LIMIT_X); \ - ic74hc595_shift_io_pins() +#define io100_set_output ic74hc595_set_pin(LIMIT_X) +#define io100_clear_output ic74hc595_clear_pin(LIMIT_X) +#define io100_toggle_output ic74hc595_toggle_pin(LIMIT_X) #define io100_get_output ic74hc595_get_pin(LIMIT_X) #define io100_config_input #define io100_config_pullup @@ -2707,15 +2233,9 @@ extern "C" #define io101_get_input mcu_get_input(LIMIT_Y) #elif ASSERT_PIN_EXTENDED(LIMIT_Y) #define io101_config_output -#define io101_set_output \ - ic74hc595_set_pin(LIMIT_Y); \ - ic74hc595_shift_io_pins() -#define io101_clear_output \ - ic74hc595_clear_pin(LIMIT_Y); \ - ic74hc595_shift_io_pins() -#define io101_toggle_output \ - ic74hc595_toggle_pin(LIMIT_Y); \ - ic74hc595_shift_io_pins() +#define io101_set_output ic74hc595_set_pin(LIMIT_Y) +#define io101_clear_output ic74hc595_clear_pin(LIMIT_Y) +#define io101_toggle_output ic74hc595_toggle_pin(LIMIT_Y) #define io101_get_output ic74hc595_get_pin(LIMIT_Y) #define io101_config_input #define io101_config_pullup @@ -2741,15 +2261,9 @@ extern "C" #define io102_get_input mcu_get_input(LIMIT_Z) #elif ASSERT_PIN_EXTENDED(LIMIT_Z) #define io102_config_output -#define io102_set_output \ - ic74hc595_set_pin(LIMIT_Z); \ - ic74hc595_shift_io_pins() -#define io102_clear_output \ - ic74hc595_clear_pin(LIMIT_Z); \ - ic74hc595_shift_io_pins() -#define io102_toggle_output \ - ic74hc595_toggle_pin(LIMIT_Z); \ - ic74hc595_shift_io_pins() +#define io102_set_output ic74hc595_set_pin(LIMIT_Z) +#define io102_clear_output ic74hc595_clear_pin(LIMIT_Z) +#define io102_toggle_output ic74hc595_toggle_pin(LIMIT_Z) #define io102_get_output ic74hc595_get_pin(LIMIT_Z) #define io102_config_input #define io102_config_pullup @@ -2775,15 +2289,9 @@ extern "C" #define io103_get_input mcu_get_input(LIMIT_X2) #elif ASSERT_PIN_EXTENDED(LIMIT_X2) #define io103_config_output -#define io103_set_output \ - ic74hc595_set_pin(LIMIT_X2); \ - ic74hc595_shift_io_pins() -#define io103_clear_output \ - ic74hc595_clear_pin(LIMIT_X2); \ - ic74hc595_shift_io_pins() -#define io103_toggle_output \ - ic74hc595_toggle_pin(LIMIT_X2); \ - ic74hc595_shift_io_pins() +#define io103_set_output ic74hc595_set_pin(LIMIT_X2) +#define io103_clear_output ic74hc595_clear_pin(LIMIT_X2) +#define io103_toggle_output ic74hc595_toggle_pin(LIMIT_X2) #define io103_get_output ic74hc595_get_pin(LIMIT_X2) #define io103_config_input #define io103_config_pullup @@ -2809,15 +2317,9 @@ extern "C" #define io104_get_input mcu_get_input(LIMIT_Y2) #elif ASSERT_PIN_EXTENDED(LIMIT_Y2) #define io104_config_output -#define io104_set_output \ - ic74hc595_set_pin(LIMIT_Y2); \ - ic74hc595_shift_io_pins() -#define io104_clear_output \ - ic74hc595_clear_pin(LIMIT_Y2); \ - ic74hc595_shift_io_pins() -#define io104_toggle_output \ - ic74hc595_toggle_pin(LIMIT_Y2); \ - ic74hc595_shift_io_pins() +#define io104_set_output ic74hc595_set_pin(LIMIT_Y2) +#define io104_clear_output ic74hc595_clear_pin(LIMIT_Y2) +#define io104_toggle_output ic74hc595_toggle_pin(LIMIT_Y2) #define io104_get_output ic74hc595_get_pin(LIMIT_Y2) #define io104_config_input #define io104_config_pullup @@ -2843,15 +2345,9 @@ extern "C" #define io105_get_input mcu_get_input(LIMIT_Z2) #elif ASSERT_PIN_EXTENDED(LIMIT_Z2) #define io105_config_output -#define io105_set_output \ - ic74hc595_set_pin(LIMIT_Z2); \ - ic74hc595_shift_io_pins() -#define io105_clear_output \ - ic74hc595_clear_pin(LIMIT_Z2); \ - ic74hc595_shift_io_pins() -#define io105_toggle_output \ - ic74hc595_toggle_pin(LIMIT_Z2); \ - ic74hc595_shift_io_pins() +#define io105_set_output ic74hc595_set_pin(LIMIT_Z2) +#define io105_clear_output ic74hc595_clear_pin(LIMIT_Z2) +#define io105_toggle_output ic74hc595_toggle_pin(LIMIT_Z2) #define io105_get_output ic74hc595_get_pin(LIMIT_Z2) #define io105_config_input #define io105_config_pullup @@ -2877,15 +2373,9 @@ extern "C" #define io106_get_input mcu_get_input(LIMIT_A) #elif ASSERT_PIN_EXTENDED(LIMIT_A) #define io106_config_output -#define io106_set_output \ - ic74hc595_set_pin(LIMIT_A); \ - ic74hc595_shift_io_pins() -#define io106_clear_output \ - ic74hc595_clear_pin(LIMIT_A); \ - ic74hc595_shift_io_pins() -#define io106_toggle_output \ - ic74hc595_toggle_pin(LIMIT_A); \ - ic74hc595_shift_io_pins() +#define io106_set_output ic74hc595_set_pin(LIMIT_A) +#define io106_clear_output ic74hc595_clear_pin(LIMIT_A) +#define io106_toggle_output ic74hc595_toggle_pin(LIMIT_A) #define io106_get_output ic74hc595_get_pin(LIMIT_A) #define io106_config_input #define io106_config_pullup @@ -2911,15 +2401,9 @@ extern "C" #define io107_get_input mcu_get_input(LIMIT_B) #elif ASSERT_PIN_EXTENDED(LIMIT_B) #define io107_config_output -#define io107_set_output \ - ic74hc595_set_pin(LIMIT_B); \ - ic74hc595_shift_io_pins() -#define io107_clear_output \ - ic74hc595_clear_pin(LIMIT_B); \ - ic74hc595_shift_io_pins() -#define io107_toggle_output \ - ic74hc595_toggle_pin(LIMIT_B); \ - ic74hc595_shift_io_pins() +#define io107_set_output ic74hc595_set_pin(LIMIT_B) +#define io107_clear_output ic74hc595_clear_pin(LIMIT_B) +#define io107_toggle_output ic74hc595_toggle_pin(LIMIT_B) #define io107_get_output ic74hc595_get_pin(LIMIT_B) #define io107_config_input #define io107_config_pullup @@ -2945,15 +2429,9 @@ extern "C" #define io108_get_input mcu_get_input(LIMIT_C) #elif ASSERT_PIN_EXTENDED(LIMIT_C) #define io108_config_output -#define io108_set_output \ - ic74hc595_set_pin(LIMIT_C); \ - ic74hc595_shift_io_pins() -#define io108_clear_output \ - ic74hc595_clear_pin(LIMIT_C); \ - ic74hc595_shift_io_pins() -#define io108_toggle_output \ - ic74hc595_toggle_pin(LIMIT_C); \ - ic74hc595_shift_io_pins() +#define io108_set_output ic74hc595_set_pin(LIMIT_C) +#define io108_clear_output ic74hc595_clear_pin(LIMIT_C) +#define io108_toggle_output ic74hc595_toggle_pin(LIMIT_C) #define io108_get_output ic74hc595_get_pin(LIMIT_C) #define io108_config_input #define io108_config_pullup @@ -2979,15 +2457,9 @@ extern "C" #define io109_get_input mcu_get_input(PROBE) #elif ASSERT_PIN_EXTENDED(PROBE) #define io109_config_output -#define io109_set_output \ - ic74hc595_set_pin(PROBE); \ - ic74hc595_shift_io_pins() -#define io109_clear_output \ - ic74hc595_clear_pin(PROBE); \ - ic74hc595_shift_io_pins() -#define io109_toggle_output \ - ic74hc595_toggle_pin(PROBE); \ - ic74hc595_shift_io_pins() +#define io109_set_output ic74hc595_set_pin(PROBE) +#define io109_clear_output ic74hc595_clear_pin(PROBE) +#define io109_toggle_output ic74hc595_toggle_pin(PROBE) #define io109_get_output ic74hc595_get_pin(PROBE) #define io109_config_input #define io109_config_pullup @@ -3013,15 +2485,9 @@ extern "C" #define io110_get_input mcu_get_input(ESTOP) #elif ASSERT_PIN_EXTENDED(ESTOP) #define io110_config_output -#define io110_set_output \ - ic74hc595_set_pin(ESTOP); \ - ic74hc595_shift_io_pins() -#define io110_clear_output \ - ic74hc595_clear_pin(ESTOP); \ - ic74hc595_shift_io_pins() -#define io110_toggle_output \ - ic74hc595_toggle_pin(ESTOP); \ - ic74hc595_shift_io_pins() +#define io110_set_output ic74hc595_set_pin(ESTOP) +#define io110_clear_output ic74hc595_clear_pin(ESTOP) +#define io110_toggle_output ic74hc595_toggle_pin(ESTOP) #define io110_get_output ic74hc595_get_pin(ESTOP) #define io110_config_input #define io110_config_pullup @@ -3047,15 +2513,9 @@ extern "C" #define io111_get_input mcu_get_input(SAFETY_DOOR) #elif ASSERT_PIN_EXTENDED(SAFETY_DOOR) #define io111_config_output -#define io111_set_output \ - ic74hc595_set_pin(SAFETY_DOOR); \ - ic74hc595_shift_io_pins() -#define io111_clear_output \ - ic74hc595_clear_pin(SAFETY_DOOR); \ - ic74hc595_shift_io_pins() -#define io111_toggle_output \ - ic74hc595_toggle_pin(SAFETY_DOOR); \ - ic74hc595_shift_io_pins() +#define io111_set_output ic74hc595_set_pin(SAFETY_DOOR) +#define io111_clear_output ic74hc595_clear_pin(SAFETY_DOOR) +#define io111_toggle_output ic74hc595_toggle_pin(SAFETY_DOOR) #define io111_get_output ic74hc595_get_pin(SAFETY_DOOR) #define io111_config_input #define io111_config_pullup @@ -3081,15 +2541,9 @@ extern "C" #define io112_get_input mcu_get_input(FHOLD) #elif ASSERT_PIN_EXTENDED(FHOLD) #define io112_config_output -#define io112_set_output \ - ic74hc595_set_pin(FHOLD); \ - ic74hc595_shift_io_pins() -#define io112_clear_output \ - ic74hc595_clear_pin(FHOLD); \ - ic74hc595_shift_io_pins() -#define io112_toggle_output \ - ic74hc595_toggle_pin(FHOLD); \ - ic74hc595_shift_io_pins() +#define io112_set_output ic74hc595_set_pin(FHOLD) +#define io112_clear_output ic74hc595_clear_pin(FHOLD) +#define io112_toggle_output ic74hc595_toggle_pin(FHOLD) #define io112_get_output ic74hc595_get_pin(FHOLD) #define io112_config_input #define io112_config_pullup @@ -3115,15 +2569,9 @@ extern "C" #define io113_get_input mcu_get_input(CS_RES) #elif ASSERT_PIN_EXTENDED(CS_RES) #define io113_config_output -#define io113_set_output \ - ic74hc595_set_pin(CS_RES); \ - ic74hc595_shift_io_pins() -#define io113_clear_output \ - ic74hc595_clear_pin(CS_RES); \ - ic74hc595_shift_io_pins() -#define io113_toggle_output \ - ic74hc595_toggle_pin(CS_RES); \ - ic74hc595_shift_io_pins() +#define io113_set_output ic74hc595_set_pin(CS_RES) +#define io113_clear_output ic74hc595_clear_pin(CS_RES) +#define io113_toggle_output ic74hc595_toggle_pin(CS_RES) #define io113_get_output ic74hc595_get_pin(CS_RES) #define io113_config_input #define io113_config_pullup @@ -3149,15 +2597,9 @@ extern "C" #define io114_get_input mcu_get_input(ANALOG0) #elif ASSERT_PIN_EXTENDED(ANALOG0) #define io114_config_output -#define io114_set_output \ - ic74hc595_set_pin(ANALOG0); \ - ic74hc595_shift_io_pins() -#define io114_clear_output \ - ic74hc595_clear_pin(ANALOG0); \ - ic74hc595_shift_io_pins() -#define io114_toggle_output \ - ic74hc595_toggle_pin(ANALOG0); \ - ic74hc595_shift_io_pins() +#define io114_set_output ic74hc595_set_pin(ANALOG0) +#define io114_clear_output ic74hc595_clear_pin(ANALOG0) +#define io114_toggle_output ic74hc595_toggle_pin(ANALOG0) #define io114_get_output ic74hc595_get_pin(ANALOG0) #define io114_config_input #define io114_config_pullup @@ -3183,15 +2625,9 @@ extern "C" #define io115_get_input mcu_get_input(ANALOG1) #elif ASSERT_PIN_EXTENDED(ANALOG1) #define io115_config_output -#define io115_set_output \ - ic74hc595_set_pin(ANALOG1); \ - ic74hc595_shift_io_pins() -#define io115_clear_output \ - ic74hc595_clear_pin(ANALOG1); \ - ic74hc595_shift_io_pins() -#define io115_toggle_output \ - ic74hc595_toggle_pin(ANALOG1); \ - ic74hc595_shift_io_pins() +#define io115_set_output ic74hc595_set_pin(ANALOG1) +#define io115_clear_output ic74hc595_clear_pin(ANALOG1) +#define io115_toggle_output ic74hc595_toggle_pin(ANALOG1) #define io115_get_output ic74hc595_get_pin(ANALOG1) #define io115_config_input #define io115_config_pullup @@ -3217,15 +2653,9 @@ extern "C" #define io116_get_input mcu_get_input(ANALOG2) #elif ASSERT_PIN_EXTENDED(ANALOG2) #define io116_config_output -#define io116_set_output \ - ic74hc595_set_pin(ANALOG2); \ - ic74hc595_shift_io_pins() -#define io116_clear_output \ - ic74hc595_clear_pin(ANALOG2); \ - ic74hc595_shift_io_pins() -#define io116_toggle_output \ - ic74hc595_toggle_pin(ANALOG2); \ - ic74hc595_shift_io_pins() +#define io116_set_output ic74hc595_set_pin(ANALOG2) +#define io116_clear_output ic74hc595_clear_pin(ANALOG2) +#define io116_toggle_output ic74hc595_toggle_pin(ANALOG2) #define io116_get_output ic74hc595_get_pin(ANALOG2) #define io116_config_input #define io116_config_pullup @@ -3251,15 +2681,9 @@ extern "C" #define io117_get_input mcu_get_input(ANALOG3) #elif ASSERT_PIN_EXTENDED(ANALOG3) #define io117_config_output -#define io117_set_output \ - ic74hc595_set_pin(ANALOG3); \ - ic74hc595_shift_io_pins() -#define io117_clear_output \ - ic74hc595_clear_pin(ANALOG3); \ - ic74hc595_shift_io_pins() -#define io117_toggle_output \ - ic74hc595_toggle_pin(ANALOG3); \ - ic74hc595_shift_io_pins() +#define io117_set_output ic74hc595_set_pin(ANALOG3) +#define io117_clear_output ic74hc595_clear_pin(ANALOG3) +#define io117_toggle_output ic74hc595_toggle_pin(ANALOG3) #define io117_get_output ic74hc595_get_pin(ANALOG3) #define io117_config_input #define io117_config_pullup @@ -3285,15 +2709,9 @@ extern "C" #define io118_get_input mcu_get_input(ANALOG4) #elif ASSERT_PIN_EXTENDED(ANALOG4) #define io118_config_output -#define io118_set_output \ - ic74hc595_set_pin(ANALOG4); \ - ic74hc595_shift_io_pins() -#define io118_clear_output \ - ic74hc595_clear_pin(ANALOG4); \ - ic74hc595_shift_io_pins() -#define io118_toggle_output \ - ic74hc595_toggle_pin(ANALOG4); \ - ic74hc595_shift_io_pins() +#define io118_set_output ic74hc595_set_pin(ANALOG4) +#define io118_clear_output ic74hc595_clear_pin(ANALOG4) +#define io118_toggle_output ic74hc595_toggle_pin(ANALOG4) #define io118_get_output ic74hc595_get_pin(ANALOG4) #define io118_config_input #define io118_config_pullup @@ -3319,15 +2737,9 @@ extern "C" #define io119_get_input mcu_get_input(ANALOG5) #elif ASSERT_PIN_EXTENDED(ANALOG5) #define io119_config_output -#define io119_set_output \ - ic74hc595_set_pin(ANALOG5); \ - ic74hc595_shift_io_pins() -#define io119_clear_output \ - ic74hc595_clear_pin(ANALOG5); \ - ic74hc595_shift_io_pins() -#define io119_toggle_output \ - ic74hc595_toggle_pin(ANALOG5); \ - ic74hc595_shift_io_pins() +#define io119_set_output ic74hc595_set_pin(ANALOG5) +#define io119_clear_output ic74hc595_clear_pin(ANALOG5) +#define io119_toggle_output ic74hc595_toggle_pin(ANALOG5) #define io119_get_output ic74hc595_get_pin(ANALOG5) #define io119_config_input #define io119_config_pullup @@ -3353,15 +2765,9 @@ extern "C" #define io120_get_input mcu_get_input(ANALOG6) #elif ASSERT_PIN_EXTENDED(ANALOG6) #define io120_config_output -#define io120_set_output \ - ic74hc595_set_pin(ANALOG6); \ - ic74hc595_shift_io_pins() -#define io120_clear_output \ - ic74hc595_clear_pin(ANALOG6); \ - ic74hc595_shift_io_pins() -#define io120_toggle_output \ - ic74hc595_toggle_pin(ANALOG6); \ - ic74hc595_shift_io_pins() +#define io120_set_output ic74hc595_set_pin(ANALOG6) +#define io120_clear_output ic74hc595_clear_pin(ANALOG6) +#define io120_toggle_output ic74hc595_toggle_pin(ANALOG6) #define io120_get_output ic74hc595_get_pin(ANALOG6) #define io120_config_input #define io120_config_pullup @@ -3387,15 +2793,9 @@ extern "C" #define io121_get_input mcu_get_input(ANALOG7) #elif ASSERT_PIN_EXTENDED(ANALOG7) #define io121_config_output -#define io121_set_output \ - ic74hc595_set_pin(ANALOG7); \ - ic74hc595_shift_io_pins() -#define io121_clear_output \ - ic74hc595_clear_pin(ANALOG7); \ - ic74hc595_shift_io_pins() -#define io121_toggle_output \ - ic74hc595_toggle_pin(ANALOG7); \ - ic74hc595_shift_io_pins() +#define io121_set_output ic74hc595_set_pin(ANALOG7) +#define io121_clear_output ic74hc595_clear_pin(ANALOG7) +#define io121_toggle_output ic74hc595_toggle_pin(ANALOG7) #define io121_get_output ic74hc595_get_pin(ANALOG7) #define io121_config_input #define io121_config_pullup @@ -3421,15 +2821,9 @@ extern "C" #define io122_get_input mcu_get_input(ANALOG8) #elif ASSERT_PIN_EXTENDED(ANALOG8) #define io122_config_output -#define io122_set_output \ - ic74hc595_set_pin(ANALOG8); \ - ic74hc595_shift_io_pins() -#define io122_clear_output \ - ic74hc595_clear_pin(ANALOG8); \ - ic74hc595_shift_io_pins() -#define io122_toggle_output \ - ic74hc595_toggle_pin(ANALOG8); \ - ic74hc595_shift_io_pins() +#define io122_set_output ic74hc595_set_pin(ANALOG8) +#define io122_clear_output ic74hc595_clear_pin(ANALOG8) +#define io122_toggle_output ic74hc595_toggle_pin(ANALOG8) #define io122_get_output ic74hc595_get_pin(ANALOG8) #define io122_config_input #define io122_config_pullup @@ -3455,15 +2849,9 @@ extern "C" #define io123_get_input mcu_get_input(ANALOG9) #elif ASSERT_PIN_EXTENDED(ANALOG9) #define io123_config_output -#define io123_set_output \ - ic74hc595_set_pin(ANALOG9); \ - ic74hc595_shift_io_pins() -#define io123_clear_output \ - ic74hc595_clear_pin(ANALOG9); \ - ic74hc595_shift_io_pins() -#define io123_toggle_output \ - ic74hc595_toggle_pin(ANALOG9); \ - ic74hc595_shift_io_pins() +#define io123_set_output ic74hc595_set_pin(ANALOG9) +#define io123_clear_output ic74hc595_clear_pin(ANALOG9) +#define io123_toggle_output ic74hc595_toggle_pin(ANALOG9) #define io123_get_output ic74hc595_get_pin(ANALOG9) #define io123_config_input #define io123_config_pullup @@ -3489,15 +2877,9 @@ extern "C" #define io124_get_input mcu_get_input(ANALOG10) #elif ASSERT_PIN_EXTENDED(ANALOG10) #define io124_config_output -#define io124_set_output \ - ic74hc595_set_pin(ANALOG10); \ - ic74hc595_shift_io_pins() -#define io124_clear_output \ - ic74hc595_clear_pin(ANALOG10); \ - ic74hc595_shift_io_pins() -#define io124_toggle_output \ - ic74hc595_toggle_pin(ANALOG10); \ - ic74hc595_shift_io_pins() +#define io124_set_output ic74hc595_set_pin(ANALOG10) +#define io124_clear_output ic74hc595_clear_pin(ANALOG10) +#define io124_toggle_output ic74hc595_toggle_pin(ANALOG10) #define io124_get_output ic74hc595_get_pin(ANALOG10) #define io124_config_input #define io124_config_pullup @@ -3523,15 +2905,9 @@ extern "C" #define io125_get_input mcu_get_input(ANALOG11) #elif ASSERT_PIN_EXTENDED(ANALOG11) #define io125_config_output -#define io125_set_output \ - ic74hc595_set_pin(ANALOG11); \ - ic74hc595_shift_io_pins() -#define io125_clear_output \ - ic74hc595_clear_pin(ANALOG11); \ - ic74hc595_shift_io_pins() -#define io125_toggle_output \ - ic74hc595_toggle_pin(ANALOG11); \ - ic74hc595_shift_io_pins() +#define io125_set_output ic74hc595_set_pin(ANALOG11) +#define io125_clear_output ic74hc595_clear_pin(ANALOG11) +#define io125_toggle_output ic74hc595_toggle_pin(ANALOG11) #define io125_get_output ic74hc595_get_pin(ANALOG11) #define io125_config_input #define io125_config_pullup @@ -3557,15 +2933,9 @@ extern "C" #define io126_get_input mcu_get_input(ANALOG12) #elif ASSERT_PIN_EXTENDED(ANALOG12) #define io126_config_output -#define io126_set_output \ - ic74hc595_set_pin(ANALOG12); \ - ic74hc595_shift_io_pins() -#define io126_clear_output \ - ic74hc595_clear_pin(ANALOG12); \ - ic74hc595_shift_io_pins() -#define io126_toggle_output \ - ic74hc595_toggle_pin(ANALOG12); \ - ic74hc595_shift_io_pins() +#define io126_set_output ic74hc595_set_pin(ANALOG12) +#define io126_clear_output ic74hc595_clear_pin(ANALOG12) +#define io126_toggle_output ic74hc595_toggle_pin(ANALOG12) #define io126_get_output ic74hc595_get_pin(ANALOG12) #define io126_config_input #define io126_config_pullup @@ -3591,15 +2961,9 @@ extern "C" #define io127_get_input mcu_get_input(ANALOG13) #elif ASSERT_PIN_EXTENDED(ANALOG13) #define io127_config_output -#define io127_set_output \ - ic74hc595_set_pin(ANALOG13); \ - ic74hc595_shift_io_pins() -#define io127_clear_output \ - ic74hc595_clear_pin(ANALOG13); \ - ic74hc595_shift_io_pins() -#define io127_toggle_output \ - ic74hc595_toggle_pin(ANALOG13); \ - ic74hc595_shift_io_pins() +#define io127_set_output ic74hc595_set_pin(ANALOG13) +#define io127_clear_output ic74hc595_clear_pin(ANALOG13) +#define io127_toggle_output ic74hc595_toggle_pin(ANALOG13) #define io127_get_output ic74hc595_get_pin(ANALOG13) #define io127_config_input #define io127_config_pullup @@ -3625,15 +2989,9 @@ extern "C" #define io128_get_input mcu_get_input(ANALOG14) #elif ASSERT_PIN_EXTENDED(ANALOG14) #define io128_config_output -#define io128_set_output \ - ic74hc595_set_pin(ANALOG14); \ - ic74hc595_shift_io_pins() -#define io128_clear_output \ - ic74hc595_clear_pin(ANALOG14); \ - ic74hc595_shift_io_pins() -#define io128_toggle_output \ - ic74hc595_toggle_pin(ANALOG14); \ - ic74hc595_shift_io_pins() +#define io128_set_output ic74hc595_set_pin(ANALOG14) +#define io128_clear_output ic74hc595_clear_pin(ANALOG14) +#define io128_toggle_output ic74hc595_toggle_pin(ANALOG14) #define io128_get_output ic74hc595_get_pin(ANALOG14) #define io128_config_input #define io128_config_pullup @@ -3659,15 +3017,9 @@ extern "C" #define io129_get_input mcu_get_input(ANALOG15) #elif ASSERT_PIN_EXTENDED(ANALOG15) #define io129_config_output -#define io129_set_output \ - ic74hc595_set_pin(ANALOG15); \ - ic74hc595_shift_io_pins() -#define io129_clear_output \ - ic74hc595_clear_pin(ANALOG15); \ - ic74hc595_shift_io_pins() -#define io129_toggle_output \ - ic74hc595_toggle_pin(ANALOG15); \ - ic74hc595_shift_io_pins() +#define io129_set_output ic74hc595_set_pin(ANALOG15) +#define io129_clear_output ic74hc595_clear_pin(ANALOG15) +#define io129_toggle_output ic74hc595_toggle_pin(ANALOG15) #define io129_get_output ic74hc595_get_pin(ANALOG15) #define io129_config_input #define io129_config_pullup @@ -3693,15 +3045,9 @@ extern "C" #define io130_get_input mcu_get_input(DIN0) #elif ASSERT_PIN_EXTENDED(DIN0) #define io130_config_output -#define io130_set_output \ - ic74hc595_set_pin(DIN0); \ - ic74hc595_shift_io_pins() -#define io130_clear_output \ - ic74hc595_clear_pin(DIN0); \ - ic74hc595_shift_io_pins() -#define io130_toggle_output \ - ic74hc595_toggle_pin(DIN0); \ - ic74hc595_shift_io_pins() +#define io130_set_output ic74hc595_set_pin(DIN0) +#define io130_clear_output ic74hc595_clear_pin(DIN0) +#define io130_toggle_output ic74hc595_toggle_pin(DIN0) #define io130_get_output ic74hc595_get_pin(DIN0) #define io130_config_input #define io130_config_pullup @@ -3727,15 +3073,9 @@ extern "C" #define io131_get_input mcu_get_input(DIN1) #elif ASSERT_PIN_EXTENDED(DIN1) #define io131_config_output -#define io131_set_output \ - ic74hc595_set_pin(DIN1); \ - ic74hc595_shift_io_pins() -#define io131_clear_output \ - ic74hc595_clear_pin(DIN1); \ - ic74hc595_shift_io_pins() -#define io131_toggle_output \ - ic74hc595_toggle_pin(DIN1); \ - ic74hc595_shift_io_pins() +#define io131_set_output ic74hc595_set_pin(DIN1) +#define io131_clear_output ic74hc595_clear_pin(DIN1) +#define io131_toggle_output ic74hc595_toggle_pin(DIN1) #define io131_get_output ic74hc595_get_pin(DIN1) #define io131_config_input #define io131_config_pullup @@ -3761,15 +3101,9 @@ extern "C" #define io132_get_input mcu_get_input(DIN2) #elif ASSERT_PIN_EXTENDED(DIN2) #define io132_config_output -#define io132_set_output \ - ic74hc595_set_pin(DIN2); \ - ic74hc595_shift_io_pins() -#define io132_clear_output \ - ic74hc595_clear_pin(DIN2); \ - ic74hc595_shift_io_pins() -#define io132_toggle_output \ - ic74hc595_toggle_pin(DIN2); \ - ic74hc595_shift_io_pins() +#define io132_set_output ic74hc595_set_pin(DIN2) +#define io132_clear_output ic74hc595_clear_pin(DIN2) +#define io132_toggle_output ic74hc595_toggle_pin(DIN2) #define io132_get_output ic74hc595_get_pin(DIN2) #define io132_config_input #define io132_config_pullup @@ -3795,15 +3129,9 @@ extern "C" #define io133_get_input mcu_get_input(DIN3) #elif ASSERT_PIN_EXTENDED(DIN3) #define io133_config_output -#define io133_set_output \ - ic74hc595_set_pin(DIN3); \ - ic74hc595_shift_io_pins() -#define io133_clear_output \ - ic74hc595_clear_pin(DIN3); \ - ic74hc595_shift_io_pins() -#define io133_toggle_output \ - ic74hc595_toggle_pin(DIN3); \ - ic74hc595_shift_io_pins() +#define io133_set_output ic74hc595_set_pin(DIN3) +#define io133_clear_output ic74hc595_clear_pin(DIN3) +#define io133_toggle_output ic74hc595_toggle_pin(DIN3) #define io133_get_output ic74hc595_get_pin(DIN3) #define io133_config_input #define io133_config_pullup @@ -3829,15 +3157,9 @@ extern "C" #define io134_get_input mcu_get_input(DIN4) #elif ASSERT_PIN_EXTENDED(DIN4) #define io134_config_output -#define io134_set_output \ - ic74hc595_set_pin(DIN4); \ - ic74hc595_shift_io_pins() -#define io134_clear_output \ - ic74hc595_clear_pin(DIN4); \ - ic74hc595_shift_io_pins() -#define io134_toggle_output \ - ic74hc595_toggle_pin(DIN4); \ - ic74hc595_shift_io_pins() +#define io134_set_output ic74hc595_set_pin(DIN4) +#define io134_clear_output ic74hc595_clear_pin(DIN4) +#define io134_toggle_output ic74hc595_toggle_pin(DIN4) #define io134_get_output ic74hc595_get_pin(DIN4) #define io134_config_input #define io134_config_pullup @@ -3863,15 +3185,9 @@ extern "C" #define io135_get_input mcu_get_input(DIN5) #elif ASSERT_PIN_EXTENDED(DIN5) #define io135_config_output -#define io135_set_output \ - ic74hc595_set_pin(DIN5); \ - ic74hc595_shift_io_pins() -#define io135_clear_output \ - ic74hc595_clear_pin(DIN5); \ - ic74hc595_shift_io_pins() -#define io135_toggle_output \ - ic74hc595_toggle_pin(DIN5); \ - ic74hc595_shift_io_pins() +#define io135_set_output ic74hc595_set_pin(DIN5) +#define io135_clear_output ic74hc595_clear_pin(DIN5) +#define io135_toggle_output ic74hc595_toggle_pin(DIN5) #define io135_get_output ic74hc595_get_pin(DIN5) #define io135_config_input #define io135_config_pullup @@ -3897,15 +3213,9 @@ extern "C" #define io136_get_input mcu_get_input(DIN6) #elif ASSERT_PIN_EXTENDED(DIN6) #define io136_config_output -#define io136_set_output \ - ic74hc595_set_pin(DIN6); \ - ic74hc595_shift_io_pins() -#define io136_clear_output \ - ic74hc595_clear_pin(DIN6); \ - ic74hc595_shift_io_pins() -#define io136_toggle_output \ - ic74hc595_toggle_pin(DIN6); \ - ic74hc595_shift_io_pins() +#define io136_set_output ic74hc595_set_pin(DIN6) +#define io136_clear_output ic74hc595_clear_pin(DIN6) +#define io136_toggle_output ic74hc595_toggle_pin(DIN6) #define io136_get_output ic74hc595_get_pin(DIN6) #define io136_config_input #define io136_config_pullup @@ -3931,15 +3241,9 @@ extern "C" #define io137_get_input mcu_get_input(DIN7) #elif ASSERT_PIN_EXTENDED(DIN7) #define io137_config_output -#define io137_set_output \ - ic74hc595_set_pin(DIN7); \ - ic74hc595_shift_io_pins() -#define io137_clear_output \ - ic74hc595_clear_pin(DIN7); \ - ic74hc595_shift_io_pins() -#define io137_toggle_output \ - ic74hc595_toggle_pin(DIN7); \ - ic74hc595_shift_io_pins() +#define io137_set_output ic74hc595_set_pin(DIN7) +#define io137_clear_output ic74hc595_clear_pin(DIN7) +#define io137_toggle_output ic74hc595_toggle_pin(DIN7) #define io137_get_output ic74hc595_get_pin(DIN7) #define io137_config_input #define io137_config_pullup @@ -3965,15 +3269,9 @@ extern "C" #define io138_get_input mcu_get_input(DIN8) #elif ASSERT_PIN_EXTENDED(DIN8) #define io138_config_output -#define io138_set_output \ - ic74hc595_set_pin(DIN8); \ - ic74hc595_shift_io_pins() -#define io138_clear_output \ - ic74hc595_clear_pin(DIN8); \ - ic74hc595_shift_io_pins() -#define io138_toggle_output \ - ic74hc595_toggle_pin(DIN8); \ - ic74hc595_shift_io_pins() +#define io138_set_output ic74hc595_set_pin(DIN8) +#define io138_clear_output ic74hc595_clear_pin(DIN8) +#define io138_toggle_output ic74hc595_toggle_pin(DIN8) #define io138_get_output ic74hc595_get_pin(DIN8) #define io138_config_input #define io138_config_pullup @@ -3999,15 +3297,9 @@ extern "C" #define io139_get_input mcu_get_input(DIN9) #elif ASSERT_PIN_EXTENDED(DIN9) #define io139_config_output -#define io139_set_output \ - ic74hc595_set_pin(DIN9); \ - ic74hc595_shift_io_pins() -#define io139_clear_output \ - ic74hc595_clear_pin(DIN9); \ - ic74hc595_shift_io_pins() -#define io139_toggle_output \ - ic74hc595_toggle_pin(DIN9); \ - ic74hc595_shift_io_pins() +#define io139_set_output ic74hc595_set_pin(DIN9) +#define io139_clear_output ic74hc595_clear_pin(DIN9) +#define io139_toggle_output ic74hc595_toggle_pin(DIN9) #define io139_get_output ic74hc595_get_pin(DIN9) #define io139_config_input #define io139_config_pullup @@ -4033,15 +3325,9 @@ extern "C" #define io140_get_input mcu_get_input(DIN10) #elif ASSERT_PIN_EXTENDED(DIN10) #define io140_config_output -#define io140_set_output \ - ic74hc595_set_pin(DIN10); \ - ic74hc595_shift_io_pins() -#define io140_clear_output \ - ic74hc595_clear_pin(DIN10); \ - ic74hc595_shift_io_pins() -#define io140_toggle_output \ - ic74hc595_toggle_pin(DIN10); \ - ic74hc595_shift_io_pins() +#define io140_set_output ic74hc595_set_pin(DIN10) +#define io140_clear_output ic74hc595_clear_pin(DIN10) +#define io140_toggle_output ic74hc595_toggle_pin(DIN10) #define io140_get_output ic74hc595_get_pin(DIN10) #define io140_config_input #define io140_config_pullup @@ -4067,15 +3353,9 @@ extern "C" #define io141_get_input mcu_get_input(DIN11) #elif ASSERT_PIN_EXTENDED(DIN11) #define io141_config_output -#define io141_set_output \ - ic74hc595_set_pin(DIN11); \ - ic74hc595_shift_io_pins() -#define io141_clear_output \ - ic74hc595_clear_pin(DIN11); \ - ic74hc595_shift_io_pins() -#define io141_toggle_output \ - ic74hc595_toggle_pin(DIN11); \ - ic74hc595_shift_io_pins() +#define io141_set_output ic74hc595_set_pin(DIN11) +#define io141_clear_output ic74hc595_clear_pin(DIN11) +#define io141_toggle_output ic74hc595_toggle_pin(DIN11) #define io141_get_output ic74hc595_get_pin(DIN11) #define io141_config_input #define io141_config_pullup @@ -4101,15 +3381,9 @@ extern "C" #define io142_get_input mcu_get_input(DIN12) #elif ASSERT_PIN_EXTENDED(DIN12) #define io142_config_output -#define io142_set_output \ - ic74hc595_set_pin(DIN12); \ - ic74hc595_shift_io_pins() -#define io142_clear_output \ - ic74hc595_clear_pin(DIN12); \ - ic74hc595_shift_io_pins() -#define io142_toggle_output \ - ic74hc595_toggle_pin(DIN12); \ - ic74hc595_shift_io_pins() +#define io142_set_output ic74hc595_set_pin(DIN12) +#define io142_clear_output ic74hc595_clear_pin(DIN12) +#define io142_toggle_output ic74hc595_toggle_pin(DIN12) #define io142_get_output ic74hc595_get_pin(DIN12) #define io142_config_input #define io142_config_pullup @@ -4135,15 +3409,9 @@ extern "C" #define io143_get_input mcu_get_input(DIN13) #elif ASSERT_PIN_EXTENDED(DIN13) #define io143_config_output -#define io143_set_output \ - ic74hc595_set_pin(DIN13); \ - ic74hc595_shift_io_pins() -#define io143_clear_output \ - ic74hc595_clear_pin(DIN13); \ - ic74hc595_shift_io_pins() -#define io143_toggle_output \ - ic74hc595_toggle_pin(DIN13); \ - ic74hc595_shift_io_pins() +#define io143_set_output ic74hc595_set_pin(DIN13) +#define io143_clear_output ic74hc595_clear_pin(DIN13) +#define io143_toggle_output ic74hc595_toggle_pin(DIN13) #define io143_get_output ic74hc595_get_pin(DIN13) #define io143_config_input #define io143_config_pullup @@ -4169,15 +3437,9 @@ extern "C" #define io144_get_input mcu_get_input(DIN14) #elif ASSERT_PIN_EXTENDED(DIN14) #define io144_config_output -#define io144_set_output \ - ic74hc595_set_pin(DIN14); \ - ic74hc595_shift_io_pins() -#define io144_clear_output \ - ic74hc595_clear_pin(DIN14); \ - ic74hc595_shift_io_pins() -#define io144_toggle_output \ - ic74hc595_toggle_pin(DIN14); \ - ic74hc595_shift_io_pins() +#define io144_set_output ic74hc595_set_pin(DIN14) +#define io144_clear_output ic74hc595_clear_pin(DIN14) +#define io144_toggle_output ic74hc595_toggle_pin(DIN14) #define io144_get_output ic74hc595_get_pin(DIN14) #define io144_config_input #define io144_config_pullup @@ -4203,15 +3465,9 @@ extern "C" #define io145_get_input mcu_get_input(DIN15) #elif ASSERT_PIN_EXTENDED(DIN15) #define io145_config_output -#define io145_set_output \ - ic74hc595_set_pin(DIN15); \ - ic74hc595_shift_io_pins() -#define io145_clear_output \ - ic74hc595_clear_pin(DIN15); \ - ic74hc595_shift_io_pins() -#define io145_toggle_output \ - ic74hc595_toggle_pin(DIN15); \ - ic74hc595_shift_io_pins() +#define io145_set_output ic74hc595_set_pin(DIN15) +#define io145_clear_output ic74hc595_clear_pin(DIN15) +#define io145_toggle_output ic74hc595_toggle_pin(DIN15) #define io145_get_output ic74hc595_get_pin(DIN15) #define io145_config_input #define io145_config_pullup @@ -4237,15 +3493,9 @@ extern "C" #define io146_get_input mcu_get_input(DIN16) #elif ASSERT_PIN_EXTENDED(DIN16) #define io146_config_output -#define io146_set_output \ - ic74hc595_set_pin(DIN16); \ - ic74hc595_shift_io_pins() -#define io146_clear_output \ - ic74hc595_clear_pin(DIN16); \ - ic74hc595_shift_io_pins() -#define io146_toggle_output \ - ic74hc595_toggle_pin(DIN16); \ - ic74hc595_shift_io_pins() +#define io146_set_output ic74hc595_set_pin(DIN16) +#define io146_clear_output ic74hc595_clear_pin(DIN16) +#define io146_toggle_output ic74hc595_toggle_pin(DIN16) #define io146_get_output ic74hc595_get_pin(DIN16) #define io146_config_input #define io146_config_pullup @@ -4271,15 +3521,9 @@ extern "C" #define io147_get_input mcu_get_input(DIN17) #elif ASSERT_PIN_EXTENDED(DIN17) #define io147_config_output -#define io147_set_output \ - ic74hc595_set_pin(DIN17); \ - ic74hc595_shift_io_pins() -#define io147_clear_output \ - ic74hc595_clear_pin(DIN17); \ - ic74hc595_shift_io_pins() -#define io147_toggle_output \ - ic74hc595_toggle_pin(DIN17); \ - ic74hc595_shift_io_pins() +#define io147_set_output ic74hc595_set_pin(DIN17) +#define io147_clear_output ic74hc595_clear_pin(DIN17) +#define io147_toggle_output ic74hc595_toggle_pin(DIN17) #define io147_get_output ic74hc595_get_pin(DIN17) #define io147_config_input #define io147_config_pullup @@ -4305,15 +3549,9 @@ extern "C" #define io148_get_input mcu_get_input(DIN18) #elif ASSERT_PIN_EXTENDED(DIN18) #define io148_config_output -#define io148_set_output \ - ic74hc595_set_pin(DIN18); \ - ic74hc595_shift_io_pins() -#define io148_clear_output \ - ic74hc595_clear_pin(DIN18); \ - ic74hc595_shift_io_pins() -#define io148_toggle_output \ - ic74hc595_toggle_pin(DIN18); \ - ic74hc595_shift_io_pins() +#define io148_set_output ic74hc595_set_pin(DIN18) +#define io148_clear_output ic74hc595_clear_pin(DIN18) +#define io148_toggle_output ic74hc595_toggle_pin(DIN18) #define io148_get_output ic74hc595_get_pin(DIN18) #define io148_config_input #define io148_config_pullup @@ -4339,15 +3577,9 @@ extern "C" #define io149_get_input mcu_get_input(DIN19) #elif ASSERT_PIN_EXTENDED(DIN19) #define io149_config_output -#define io149_set_output \ - ic74hc595_set_pin(DIN19); \ - ic74hc595_shift_io_pins() -#define io149_clear_output \ - ic74hc595_clear_pin(DIN19); \ - ic74hc595_shift_io_pins() -#define io149_toggle_output \ - ic74hc595_toggle_pin(DIN19); \ - ic74hc595_shift_io_pins() +#define io149_set_output ic74hc595_set_pin(DIN19) +#define io149_clear_output ic74hc595_clear_pin(DIN19) +#define io149_toggle_output ic74hc595_toggle_pin(DIN19) #define io149_get_output ic74hc595_get_pin(DIN19) #define io149_config_input #define io149_config_pullup @@ -4373,15 +3605,9 @@ extern "C" #define io150_get_input mcu_get_input(DIN20) #elif ASSERT_PIN_EXTENDED(DIN20) #define io150_config_output -#define io150_set_output \ - ic74hc595_set_pin(DIN20); \ - ic74hc595_shift_io_pins() -#define io150_clear_output \ - ic74hc595_clear_pin(DIN20); \ - ic74hc595_shift_io_pins() -#define io150_toggle_output \ - ic74hc595_toggle_pin(DIN20); \ - ic74hc595_shift_io_pins() +#define io150_set_output ic74hc595_set_pin(DIN20) +#define io150_clear_output ic74hc595_clear_pin(DIN20) +#define io150_toggle_output ic74hc595_toggle_pin(DIN20) #define io150_get_output ic74hc595_get_pin(DIN20) #define io150_config_input #define io150_config_pullup @@ -4407,15 +3633,9 @@ extern "C" #define io151_get_input mcu_get_input(DIN21) #elif ASSERT_PIN_EXTENDED(DIN21) #define io151_config_output -#define io151_set_output \ - ic74hc595_set_pin(DIN21); \ - ic74hc595_shift_io_pins() -#define io151_clear_output \ - ic74hc595_clear_pin(DIN21); \ - ic74hc595_shift_io_pins() -#define io151_toggle_output \ - ic74hc595_toggle_pin(DIN21); \ - ic74hc595_shift_io_pins() +#define io151_set_output ic74hc595_set_pin(DIN21) +#define io151_clear_output ic74hc595_clear_pin(DIN21) +#define io151_toggle_output ic74hc595_toggle_pin(DIN21) #define io151_get_output ic74hc595_get_pin(DIN21) #define io151_config_input #define io151_config_pullup @@ -4441,15 +3661,9 @@ extern "C" #define io152_get_input mcu_get_input(DIN22) #elif ASSERT_PIN_EXTENDED(DIN22) #define io152_config_output -#define io152_set_output \ - ic74hc595_set_pin(DIN22); \ - ic74hc595_shift_io_pins() -#define io152_clear_output \ - ic74hc595_clear_pin(DIN22); \ - ic74hc595_shift_io_pins() -#define io152_toggle_output \ - ic74hc595_toggle_pin(DIN22); \ - ic74hc595_shift_io_pins() +#define io152_set_output ic74hc595_set_pin(DIN22) +#define io152_clear_output ic74hc595_clear_pin(DIN22) +#define io152_toggle_output ic74hc595_toggle_pin(DIN22) #define io152_get_output ic74hc595_get_pin(DIN22) #define io152_config_input #define io152_config_pullup @@ -4475,15 +3689,9 @@ extern "C" #define io153_get_input mcu_get_input(DIN23) #elif ASSERT_PIN_EXTENDED(DIN23) #define io153_config_output -#define io153_set_output \ - ic74hc595_set_pin(DIN23); \ - ic74hc595_shift_io_pins() -#define io153_clear_output \ - ic74hc595_clear_pin(DIN23); \ - ic74hc595_shift_io_pins() -#define io153_toggle_output \ - ic74hc595_toggle_pin(DIN23); \ - ic74hc595_shift_io_pins() +#define io153_set_output ic74hc595_set_pin(DIN23) +#define io153_clear_output ic74hc595_clear_pin(DIN23) +#define io153_toggle_output ic74hc595_toggle_pin(DIN23) #define io153_get_output ic74hc595_get_pin(DIN23) #define io153_config_input #define io153_config_pullup @@ -4509,15 +3717,9 @@ extern "C" #define io154_get_input mcu_get_input(DIN24) #elif ASSERT_PIN_EXTENDED(DIN24) #define io154_config_output -#define io154_set_output \ - ic74hc595_set_pin(DIN24); \ - ic74hc595_shift_io_pins() -#define io154_clear_output \ - ic74hc595_clear_pin(DIN24); \ - ic74hc595_shift_io_pins() -#define io154_toggle_output \ - ic74hc595_toggle_pin(DIN24); \ - ic74hc595_shift_io_pins() +#define io154_set_output ic74hc595_set_pin(DIN24) +#define io154_clear_output ic74hc595_clear_pin(DIN24) +#define io154_toggle_output ic74hc595_toggle_pin(DIN24) #define io154_get_output ic74hc595_get_pin(DIN24) #define io154_config_input #define io154_config_pullup @@ -4543,15 +3745,9 @@ extern "C" #define io155_get_input mcu_get_input(DIN25) #elif ASSERT_PIN_EXTENDED(DIN25) #define io155_config_output -#define io155_set_output \ - ic74hc595_set_pin(DIN25); \ - ic74hc595_shift_io_pins() -#define io155_clear_output \ - ic74hc595_clear_pin(DIN25); \ - ic74hc595_shift_io_pins() -#define io155_toggle_output \ - ic74hc595_toggle_pin(DIN25); \ - ic74hc595_shift_io_pins() +#define io155_set_output ic74hc595_set_pin(DIN25) +#define io155_clear_output ic74hc595_clear_pin(DIN25) +#define io155_toggle_output ic74hc595_toggle_pin(DIN25) #define io155_get_output ic74hc595_get_pin(DIN25) #define io155_config_input #define io155_config_pullup @@ -4577,15 +3773,9 @@ extern "C" #define io156_get_input mcu_get_input(DIN26) #elif ASSERT_PIN_EXTENDED(DIN26) #define io156_config_output -#define io156_set_output \ - ic74hc595_set_pin(DIN26); \ - ic74hc595_shift_io_pins() -#define io156_clear_output \ - ic74hc595_clear_pin(DIN26); \ - ic74hc595_shift_io_pins() -#define io156_toggle_output \ - ic74hc595_toggle_pin(DIN26); \ - ic74hc595_shift_io_pins() +#define io156_set_output ic74hc595_set_pin(DIN26) +#define io156_clear_output ic74hc595_clear_pin(DIN26) +#define io156_toggle_output ic74hc595_toggle_pin(DIN26) #define io156_get_output ic74hc595_get_pin(DIN26) #define io156_config_input #define io156_config_pullup @@ -4611,15 +3801,9 @@ extern "C" #define io157_get_input mcu_get_input(DIN27) #elif ASSERT_PIN_EXTENDED(DIN27) #define io157_config_output -#define io157_set_output \ - ic74hc595_set_pin(DIN27); \ - ic74hc595_shift_io_pins() -#define io157_clear_output \ - ic74hc595_clear_pin(DIN27); \ - ic74hc595_shift_io_pins() -#define io157_toggle_output \ - ic74hc595_toggle_pin(DIN27); \ - ic74hc595_shift_io_pins() +#define io157_set_output ic74hc595_set_pin(DIN27) +#define io157_clear_output ic74hc595_clear_pin(DIN27) +#define io157_toggle_output ic74hc595_toggle_pin(DIN27) #define io157_get_output ic74hc595_get_pin(DIN27) #define io157_config_input #define io157_config_pullup @@ -4645,15 +3829,9 @@ extern "C" #define io158_get_input mcu_get_input(DIN28) #elif ASSERT_PIN_EXTENDED(DIN28) #define io158_config_output -#define io158_set_output \ - ic74hc595_set_pin(DIN28); \ - ic74hc595_shift_io_pins() -#define io158_clear_output \ - ic74hc595_clear_pin(DIN28); \ - ic74hc595_shift_io_pins() -#define io158_toggle_output \ - ic74hc595_toggle_pin(DIN28); \ - ic74hc595_shift_io_pins() +#define io158_set_output ic74hc595_set_pin(DIN28) +#define io158_clear_output ic74hc595_clear_pin(DIN28) +#define io158_toggle_output ic74hc595_toggle_pin(DIN28) #define io158_get_output ic74hc595_get_pin(DIN28) #define io158_config_input #define io158_config_pullup @@ -4679,15 +3857,9 @@ extern "C" #define io159_get_input mcu_get_input(DIN29) #elif ASSERT_PIN_EXTENDED(DIN29) #define io159_config_output -#define io159_set_output \ - ic74hc595_set_pin(DIN29); \ - ic74hc595_shift_io_pins() -#define io159_clear_output \ - ic74hc595_clear_pin(DIN29); \ - ic74hc595_shift_io_pins() -#define io159_toggle_output \ - ic74hc595_toggle_pin(DIN29); \ - ic74hc595_shift_io_pins() +#define io159_set_output ic74hc595_set_pin(DIN29) +#define io159_clear_output ic74hc595_clear_pin(DIN29) +#define io159_toggle_output ic74hc595_toggle_pin(DIN29) #define io159_get_output ic74hc595_get_pin(DIN29) #define io159_config_input #define io159_config_pullup @@ -4713,15 +3885,9 @@ extern "C" #define io160_get_input mcu_get_input(DIN30) #elif ASSERT_PIN_EXTENDED(DIN30) #define io160_config_output -#define io160_set_output \ - ic74hc595_set_pin(DIN30); \ - ic74hc595_shift_io_pins() -#define io160_clear_output \ - ic74hc595_clear_pin(DIN30); \ - ic74hc595_shift_io_pins() -#define io160_toggle_output \ - ic74hc595_toggle_pin(DIN30); \ - ic74hc595_shift_io_pins() +#define io160_set_output ic74hc595_set_pin(DIN30) +#define io160_clear_output ic74hc595_clear_pin(DIN30) +#define io160_toggle_output ic74hc595_toggle_pin(DIN30) #define io160_get_output ic74hc595_get_pin(DIN30) #define io160_config_input #define io160_config_pullup @@ -4747,15 +3913,9 @@ extern "C" #define io161_get_input mcu_get_input(DIN31) #elif ASSERT_PIN_EXTENDED(DIN31) #define io161_config_output -#define io161_set_output \ - ic74hc595_set_pin(DIN31); \ - ic74hc595_shift_io_pins() -#define io161_clear_output \ - ic74hc595_clear_pin(DIN31); \ - ic74hc595_shift_io_pins() -#define io161_toggle_output \ - ic74hc595_toggle_pin(DIN31); \ - ic74hc595_shift_io_pins() +#define io161_set_output ic74hc595_set_pin(DIN31) +#define io161_clear_output ic74hc595_clear_pin(DIN31) +#define io161_toggle_output ic74hc595_toggle_pin(DIN31) #define io161_get_output ic74hc595_get_pin(DIN31) #define io161_config_input #define io161_config_pullup @@ -4771,10 +3931,10 @@ extern "C" #define io161_get_input 0 #endif -/*PWM*/ -extern uint8_t g_soft_pwm_res; -extern uint8_t g_io_soft_pwm[16]; -extern uint8_t mcu_softpwm_freq_config(uint16_t freq); + /*PWM*/ + extern uint8_t g_soft_pwm_res; + extern uint8_t g_io_soft_pwm[16]; + extern uint8_t mcu_softpwm_freq_config(uint16_t freq); #if ASSERT_PIN_IO(PWM0) #define io25_config_pwm(freq) mcu_config_pwm(PWM0, freq) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 7d6409488..2aab887e3 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -75,6 +75,17 @@ hw_timer_t *esp32_step_timer; #ifdef IC74HC595_CUSTOM_SHIFT_IO void ic74hc595_shift_io_pins(void) { +#ifndef IC74HC595_HAS_PWMS + static volatile uint8_t ic74hc595_update_lock = 0; + if (!ic74hc595_update_lock++) + { + do + { + uint32_t data = *((uint32_t *)&ic74hc595_io_pins[0]); + I2SREG.conf_single_data = data; + } while (--ic74hc595_update_lock); + } +#endif } #endif @@ -121,7 +132,7 @@ IRAM_ATTR void servo_reset(void *p) io_clear_output(SERVO5); #endif #ifdef IC74HC595_HAS_SERVOS - ic74hc595_set_servos(0); + ic74hc595_shift_io_pins(); #endif } @@ -190,9 +201,54 @@ uint8_t mcu_softpwm_freq_config(uint16_t freq) } #endif -void mcu_core0_tasks_init(void *arg) +static FORCEINLINE void esp32_i2s_extender_init(void) { -#if defined(IC74HC595_CUSTOM_SHIFT_IO) && (IC74HC595_COUNT != 0) +#ifdef IC74HC595_CUSTOM_SHIFT_IO + i2s_config_t i2s_config = { + .mode = I2S_MODE_MASTER | I2S_MODE_TX, // Only TX + .sample_rate = 156250UL, // 312500KHz * 32bit * 2 channels = 20MHz + .bits_per_sample = I2S_BITS_PER_SAMPLE_32BIT, + .channel_format = I2S_CHANNEL_FMT_ONLY_LEFT, // 1-channels + .communication_format = I2S_COMM_FORMAT_STAND_I2S | I2S_COMM_FORMAT_STAND_MSB, + .dma_buf_count = 2, + .dma_buf_len = 8, + .use_apll = false, + .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1 // Interrupt level 1 + }; + + i2s_pin_config_t pin_config = { + .bck_io_num = IC74HC595_I2S_CLK, + .ws_io_num = IC74HC595_I2S_WS, + .data_out_num = IC74HC595_I2S_DATA, + .data_in_num = -1 // Not used + }; + + i2s_driver_install(IC74HC595_I2S_PORT, &i2s_config, 0, NULL); + i2s_set_pin(IC74HC595_I2S_PORT, &pin_config); + + I2SREG.clkm_conf.clka_en = 0; // Use PLL/2 as reference + I2SREG.clkm_conf.clkm_div_num = 2; // reset value of 4 + I2SREG.clkm_conf.clkm_div_a = 1; // 0 at reset, what about divide by 0? + I2SREG.clkm_conf.clkm_div_b = 0; // 0 at reset + + // + I2SREG.fifo_conf.tx_fifo_mod = 3; // 32 bits single channel data + I2SREG.conf_chan.tx_chan_mod = 3; // + I2SREG.sample_rate_conf.tx_bits_mod = 32; + + I2SREG.conf_single_data = 0; + + // Use normal clock format, (WS is aligned with the last bit) + I2SREG.conf.tx_msb_shift = 0; + I2SREG.conf.rx_msb_shift = 0; + + // Disable TX interrupts + I2SREG.int_ena.out_eof = 0; + I2SREG.int_ena.out_dscr_err = 0; + +#endif + +#if defined(IC74HC595_HAS_PWMS) // initialize PWM timer /* Select and initialize basic parameters of the timer */ timer_config_t pwmconfig = { @@ -212,7 +268,12 @@ void mcu_core0_tasks_init(void *arg) // register PWM isr timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, io_updater, NULL, 0, NULL); timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); + timer_start(PWM_TIMER_TG, PWM_TIMER_IDX); #endif +} + +void mcu_core0_tasks_init(void *arg) +{ #ifdef MCU_HAS_UART // install UART driver handler uart_driver_install(COM_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); @@ -221,6 +282,10 @@ void mcu_core0_tasks_init(void *arg) // install UART driver handler uart_driver_install(COM2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif + +#ifdef IC74HC595_HAS_PWMS + esp32_i2s_extender_init(); +#endif } void mcu_rtc_task(void *arg) @@ -294,7 +359,7 @@ void mcu_rtc_task(void *arg) } #ifdef IC74HC595_HAS_SERVOS - ic74hc595_set_servos(servomask); + ic74hc595_shift_io_pins(); #endif servo_counter++; @@ -395,27 +460,9 @@ void mcu_init(void) uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif -// #ifdef IC74HC595_HAS_PWMS -// // initialize PWM timer -// /* Select and initialize basic parameters of the timer */ -// timer_config_t pwmconfig = { -// .divider = 2, -// .counter_dir = TIMER_COUNT_UP, -// .counter_en = TIMER_PAUSE, -// .alarm_en = TIMER_ALARM_EN, -// .auto_reload = true, -// }; // default clock source is APB -// timer_init(PWM_TIMER_TG, PWM_TIMER_IDX, &pwmconfig); - -// /* Timer's counter will initially start from value below. -// Also, if auto_reload is set, this value will be automatically reload on alarm */ -// timer_set_counter_value(PWM_TIMER_TG, PWM_TIMER_IDX, 0x00000000ULL); -// /* Configure the alarm value and the interrupt on alarm. */ -// timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)157); -// // register PWM isr -// timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, io_updater, NULL, 0, NULL); -// timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); -// #endif +#ifndef IC74HC595_HAS_PWMS + esp32_i2s_extender_init(); +#endif // inititialize ITP timer timer_config_t itpconfig = {0}; @@ -459,53 +506,6 @@ void mcu_init(void) mcu_i2c_config(I2C_FREQ); #endif -#ifdef IC74HC595_CUSTOM_SHIFT_IO - i2s_config_t i2s_config = { - .mode = I2S_MODE_MASTER | I2S_MODE_TX, // Only TX - .sample_rate = 156250UL, // 312500KHz * 32bit * 2 channels = 20MHz - .bits_per_sample = I2S_BITS_PER_SAMPLE_32BIT, - .channel_format = I2S_CHANNEL_FMT_ONLY_LEFT, // 1-channels - .communication_format = I2S_COMM_FORMAT_STAND_I2S | I2S_COMM_FORMAT_STAND_MSB, - .dma_buf_count = 2, - .dma_buf_len = 8, - .use_apll = false, - .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1 // Interrupt level 1 - }; - - i2s_pin_config_t pin_config = { - .bck_io_num = IC74HC595_I2S_CLK, - .ws_io_num = IC74HC595_I2S_WS, - .data_out_num = IC74HC595_I2S_DATA, - .data_in_num = -1 // Not used - }; - - i2s_driver_install(IC74HC595_I2S_PORT, &i2s_config, 0, NULL); - i2s_set_pin(IC74HC595_I2S_PORT, &pin_config); - - I2SREG.clkm_conf.clka_en = 0; // Use PLL/2 as reference - I2SREG.clkm_conf.clkm_div_num = 2; // reset value of 4 - I2SREG.clkm_conf.clkm_div_a = 1; // 0 at reset, what about divide by 0? - I2SREG.clkm_conf.clkm_div_b = 0; // 0 at reset - - // - I2SREG.fifo_conf.tx_fifo_mod = 3; // 32 bits single channel data - I2SREG.conf_chan.tx_chan_mod = 3; // - I2SREG.sample_rate_conf.tx_bits_mod = 32; - - I2SREG.conf_single_data = 0; - - // Use normal clock format, (WS is aligned with the last bit) - I2SREG.conf.tx_msb_shift = 0; - I2SREG.conf.rx_msb_shift = 0; - - // Disable TX interrupts - I2SREG.int_ena.out_eof = 0; - I2SREG.int_ena.out_dscr_err = 0; - -#endif - - timer_start(PWM_TIMER_TG, PWM_TIMER_IDX); - esp32_wifi_bt_init(); mcu_enable_global_isr(); } diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index f507eb945..033c2c898 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2765,15 +2765,13 @@ extern "C" #define I2C_FREQ 400000UL #endif -#if(I2C_PORT==0) +#if (I2C_PORT == 0) #define I2C_REG Wire #else #define I2C_REG __helper__(Wire, I2C_PORT, ) #endif #endif - - #ifndef IC74HC595_I2S_PORT #define IC74HC595_I2S_PORT 0 #endif @@ -2800,7 +2798,7 @@ extern "C" #define mcu_config_analog(X) \ { \ mcu_config_input(X); \ - adc1_config_width(ADC_WIDTH_BIT_10); \ + adc1_config_width(ADC_WIDTH_BIT_10); \ adc1_config_channel_atten(__indirect__(X, ADC_CHANNEL), ADC_ATTEN_DB_11); \ } #define mcu_config_pullup(X) \ @@ -2832,7 +2830,7 @@ extern "C" { \ __indirect__(X, OUTREG)->OUT ^= (1UL << (0x1F & __indirect__(X, BIT))); \ } - +#ifndef IC74HC595_HAS_PWMS #define mcu_config_pwm(X, Y) \ { \ ledc_timer_config_t pwmtimer = {0}; \ @@ -2858,6 +2856,18 @@ extern "C" ledc_update_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)); \ } #define mcu_get_pwm(X) ledc_get_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)) +#else +// forces all PWM to be generated via software +#define mcu_config_pwm(X, Y) \ + { \ + g_soft_pwm_res = mcu_softpwm_freq_config(Y); \ + } +#define mcu_set_pwm(X, Y) \ + { \ + g_io_soft_pwm[X - PWM_PINS_OFFSET] = (0xFF & Y); \ + } +#define mcy_get_pwm(X) g_io_soft_pwm[X - PWM_PINS_OFFSET] +#endif #define mcu_get_analog(X) adc1_get_raw(__indirect__(X, ADC_CHANNEL)) #ifdef MCU_HAS_ONESHOT_TIMER diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index f47307fce..577585356 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -88,397 +88,4 @@ void __attribute__((weak)) ic74hc595_shift_io_pins(void) } } -FORCEINLINE void ic74hc595_set_output(uint8_t pin, bool state) -{ - switch (pin - DOUT_PINS_OFFSET) - { -#if ASSERT_IO_OFFSET(DOUT0_IO_OFFSET) - case 0: - if (state) - { - ic74hc595_io_pins[DOUT0_IO_BYTEOFFSET] |= DOUT0_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT0_IO_BYTEOFFSET] &= ~DOUT0_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT1_IO_OFFSET) - case 1: - if (state) - { - ic74hc595_io_pins[DOUT1_IO_BYTEOFFSET] |= DOUT1_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT1_IO_BYTEOFFSET] &= ~DOUT1_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT2_IO_OFFSET) - case 2: - if (state) - { - ic74hc595_io_pins[DOUT2_IO_BYTEOFFSET] |= DOUT2_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT2_IO_BYTEOFFSET] &= ~DOUT2_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT3_IO_OFFSET) - case 3: - if (state) - { - ic74hc595_io_pins[DOUT3_IO_BYTEOFFSET] |= DOUT3_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT3_IO_BYTEOFFSET] &= ~DOUT3_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT4_IO_OFFSET) - case 4: - if (state) - { - ic74hc595_io_pins[DOUT4_IO_BYTEOFFSET] |= DOUT4_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT4_IO_BYTEOFFSET] &= ~DOUT4_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT5_IO_OFFSET) - case 5: - if (state) - { - ic74hc595_io_pins[DOUT5_IO_BYTEOFFSET] |= DOUT5_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT5_IO_BYTEOFFSET] &= ~DOUT5_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT6_IO_OFFSET) - case 6: - if (state) - { - ic74hc595_io_pins[DOUT6_IO_BYTEOFFSET] |= DOUT6_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT6_IO_BYTEOFFSET] &= ~DOUT6_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT7_IO_OFFSET) - case 7: - if (state) - { - ic74hc595_io_pins[DOUT7_IO_BYTEOFFSET] |= DOUT7_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT7_IO_BYTEOFFSET] &= ~DOUT7_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT8_IO_OFFSET) - case 8: - if (state) - { - ic74hc595_io_pins[DOUT8_IO_BYTEOFFSET] |= DOUT8_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT8_IO_BYTEOFFSET] &= ~DOUT8_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT9_IO_OFFSET) - case 9: - if (state) - { - ic74hc595_io_pins[DOUT9_IO_BYTEOFFSET] |= DOUT9_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT9_IO_BYTEOFFSET] &= ~DOUT9_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT10_IO_OFFSET) - case 10: - if (state) - { - ic74hc595_io_pins[DOUT10_IO_BYTEOFFSET] |= DOUT10_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT10_IO_BYTEOFFSET] &= ~DOUT10_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT11_IO_OFFSET) - case 11: - if (state) - { - ic74hc595_io_pins[DOUT11_IO_BYTEOFFSET] |= DOUT11_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT11_IO_BYTEOFFSET] &= ~DOUT11_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT12_IO_OFFSET) - case 12: - if (state) - { - ic74hc595_io_pins[DOUT12_IO_BYTEOFFSET] |= DOUT12_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT12_IO_BYTEOFFSET] &= ~DOUT12_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT13_IO_OFFSET) - case 13: - if (state) - { - ic74hc595_io_pins[DOUT13_IO_BYTEOFFSET] |= DOUT13_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT13_IO_BYTEOFFSET] &= ~DOUT13_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT14_IO_OFFSET) - case 14: - if (state) - { - ic74hc595_io_pins[DOUT14_IO_BYTEOFFSET] |= DOUT14_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT14_IO_BYTEOFFSET] &= ~DOUT14_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT15_IO_OFFSET) - case 15: - if (state) - { - ic74hc595_io_pins[DOUT15_IO_BYTEOFFSET] |= DOUT15_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT15_IO_BYTEOFFSET] &= ~DOUT15_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT16_IO_OFFSET) - case 16: - if (state) - { - ic74hc595_io_pins[DOUT16_IO_BYTEOFFSET] |= DOUT16_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT16_IO_BYTEOFFSET] &= ~DOUT16_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT17_IO_OFFSET) - case 17: - if (state) - { - ic74hc595_io_pins[DOUT17_IO_BYTEOFFSET] |= DOUT17_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT17_IO_BYTEOFFSET] &= ~DOUT17_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT18_IO_OFFSET) - case 18: - if (state) - { - ic74hc595_io_pins[DOUT18_IO_BYTEOFFSET] |= DOUT18_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT18_IO_BYTEOFFSET] &= ~DOUT18_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT19_IO_OFFSET) - case 19: - if (state) - { - ic74hc595_io_pins[DOUT19_IO_BYTEOFFSET] |= DOUT19_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT19_IO_BYTEOFFSET] &= ~DOUT19_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT20_IO_OFFSET) - case 20: - if (state) - { - ic74hc595_io_pins[DOUT20_IO_BYTEOFFSET] |= DOUT20_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT20_IO_BYTEOFFSET] &= ~DOUT20_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT21_IO_OFFSET) - case 21: - if (state) - { - ic74hc595_io_pins[DOUT21_IO_BYTEOFFSET] |= DOUT21_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT21_IO_BYTEOFFSET] &= ~DOUT21_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT22_IO_OFFSET) - case 22: - if (state) - { - ic74hc595_io_pins[DOUT22_IO_BYTEOFFSET] |= DOUT22_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT22_IO_BYTEOFFSET] &= ~DOUT22_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT23_IO_OFFSET) - case 23: - if (state) - { - ic74hc595_io_pins[DOUT23_IO_BYTEOFFSET] |= DOUT23_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT23_IO_BYTEOFFSET] &= ~DOUT23_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT24_IO_OFFSET) - case 24: - if (state) - { - ic74hc595_io_pins[DOUT24_IO_BYTEOFFSET] |= DOUT24_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT24_IO_BYTEOFFSET] &= ~DOUT24_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT25_IO_OFFSET) - case 25: - if (state) - { - ic74hc595_io_pins[DOUT25_IO_BYTEOFFSET] |= DOUT25_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT25_IO_BYTEOFFSET] &= ~DOUT25_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT26_IO_OFFSET) - case 26: - if (state) - { - ic74hc595_io_pins[DOUT26_IO_BYTEOFFSET] |= DOUT26_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT26_IO_BYTEOFFSET] &= ~DOUT26_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT27_IO_OFFSET) - case 27: - if (state) - { - ic74hc595_io_pins[DOUT27_IO_BYTEOFFSET] |= DOUT27_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT27_IO_BYTEOFFSET] &= ~DOUT27_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT28_IO_OFFSET) - case 28: - if (state) - { - ic74hc595_io_pins[DOUT28_IO_BYTEOFFSET] |= DOUT28_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT28_IO_BYTEOFFSET] &= ~DOUT28_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT29_IO_OFFSET) - case 29: - if (state) - { - ic74hc595_io_pins[DOUT29_IO_BYTEOFFSET] |= DOUT29_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT29_IO_BYTEOFFSET] &= ~DOUT29_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT30_IO_OFFSET) - case 30: - if (state) - { - ic74hc595_io_pins[DOUT30_IO_BYTEOFFSET] |= DOUT30_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT30_IO_BYTEOFFSET] &= ~DOUT30_IO_BITMASK; - } - break; -#endif -#if ASSERT_IO_OFFSET(DOUT31_IO_OFFSET) - case 31: - if (state) - { - ic74hc595_io_pins[DOUT31_IO_BYTEOFFSET] |= DOUT31_IO_BITMASK; - } - else - { - ic74hc595_io_pins[DOUT31_IO_BYTEOFFSET] &= ~DOUT31_IO_BITMASK; - } - break; -#endif - } - - ic74hc595_shift_io_pins(); -} - #endif diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index c1ad316af..963c52797 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -1535,7 +1535,6 @@ extern "C" #define ic74hc595_get_pin(pin) 0 #endif - void ic74hc595_set_output(uint8_t pin, bool state); void ic74hc595_shift_io_pins(void); #ifdef __cplusplus From ed87aca4bcd41f849d55c7647b9668df5de47957 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 23 Aug 2023 01:08:54 +0100 Subject: [PATCH 096/168] reorganized includes for io hal - reorganized includes to prevent pin undetection at compile time - modified 74hc595 variables to volatile --- uCNC/src/cnc.h | 20 +----------------- uCNC/src/cnc_hal_config_helper.h | 24 +++++++++++++++++++++- uCNC/src/core/io_control.h | 3 --- uCNC/src/hal/boards/boarddefs.h | 1 - uCNC/src/hal/io_hal.h | 2 -- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 18 ++++++++-------- uCNC/src/hal/mcus/virtual/mcumap_virtual.h | 1 - uCNC/src/modules/ic74hc595.c | 9 +++----- uCNC/src/modules/ic74hc595.h | 2 +- 9 files changed, 37 insertions(+), 43 deletions(-) diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index 0be60b11f..0ac43e840 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -123,30 +123,12 @@ extern "C" #define DIR6_MASK 64 #define DIR7_MASK 128 -#include "cnc_build.h" -// make the needed includes (do not change the order) -// include lists of available option -#include "hal/boards/boards.h" -#include "hal/mcus/mcus.h" -#include "hal/kinematics/kinematics.h" -// user configurations -#include "../cnc_config.h" -// board and mcu configurations -#include "hal/boards/boarddefs.h" //configures the board IO and service interrupts -// machine kinematics configurations -#include "hal/kinematics/kinematicdefs.h" //configures the kinematics for the cnc machine -// machine tools configurations -#include "hal/tools/tool.h" //configures the kinematics for the cnc machine -// final HAL configurations -#include "../cnc_hal_config.h" //inicializes the HAL hardcoded connections -#include "../cnc_hal_overrides.h" //config override file -// fill remaining HAL configurations and sanity checks +// do all HAL configurations and sanity checks #include "cnc_hal_config_helper.h" // initializes core utilities (like fast math functions) #include "utils.h" // extension modules #include "module.h" -#include "hal/io_hal.h" #include "interface/defaults.h" #include "interface/grbl_interface.h" #include "interface/settings.h" diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 35286a053..d47e2e2e0 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -27,9 +27,10 @@ extern "C" // undefined pin #define UNDEF_PIN 0 // assert pin (io or extended) -#define ASSERT_PIN(X) (X != 0) #define _EVAL_DIO_(X) DIO##X #define EVAL_DIO(X) DIO##X + +#define ASSERT_PIN(X) (EVAL_DIO(X) != 0) // assert pin io #define ASSERT_PIN_IO(X) (EVAL_DIO(X) > 0) // assert pin extended @@ -37,6 +38,25 @@ extern "C" // assert pin extended offset #define ASSERT_IO_OFFSET(X) (X >= 0) +#include "cnc_build.h" +// make the needed includes (do not change the order) +// include lists of available option +#include "hal/boards/boards.h" +#include "hal/mcus/mcus.h" +#include "hal/kinematics/kinematics.h" +// user configurations +#include "../cnc_config.h" +// board and mcu configurations +#include "hal/boards/boarddefs.h" //configures the board IO and service interrupts +// machine kinematics configurations +#include "hal/kinematics/kinematicdefs.h" //configures the kinematics for the cnc machine +// machine tools configurations +#include "hal/tools/tool.h" //configures the kinematics for the cnc machine +// final HAL configurations +#include "../cnc_hal_config.h" //inicializes the HAL hardcoded connections +#include "../cnc_hal_overrides.h" //config override file +#include "modules/ic74hc595.h" // io extender + /** * * Controls limits and probe pins @@ -2156,6 +2176,8 @@ typedef uint16_t step_t; #endif #endif +#include "hal/io_hal.h" + #ifdef __cplusplus } #endif diff --git a/uCNC/src/core/io_control.h b/uCNC/src/core/io_control.h index e7c403239..902aefd81 100644 --- a/uCNC/src/core/io_control.h +++ b/uCNC/src/core/io_control.h @@ -30,9 +30,6 @@ extern "C" { #endif -#include "../module.h" -// #include "../modules/ic74hc595.h" -#include "../hal/io_hal.h" #include #include diff --git a/uCNC/src/hal/boards/boarddefs.h b/uCNC/src/hal/boards/boarddefs.h index 12d75dfc3..aa65fb4d8 100644 --- a/uCNC/src/hal/boards/boarddefs.h +++ b/uCNC/src/hal/boards/boarddefs.h @@ -164,7 +164,6 @@ extern "C" #endif #include "../../../boardmap_overrides.h" -#include "../../modules/ic74hc595.h" #include "../mcus/mcudefs.h" //configures the MCU for the selected board #ifdef __cplusplus diff --git a/uCNC/src/hal/io_hal.h b/uCNC/src/hal/io_hal.h index f760c4128..0deaaae24 100644 --- a/uCNC/src/hal/io_hal.h +++ b/uCNC/src/hal/io_hal.h @@ -7,8 +7,6 @@ extern "C" { #endif -#include "../modules/ic74hc595.h" - /*IO HAL*/ #if ASSERT_PIN_IO(STEP0) #define io1_config_output mcu_config_output(STEP0) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 2aab887e3..24c783e77 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -73,7 +73,7 @@ static flash_eeprom_t mcu_eeprom; hw_timer_t *esp32_step_timer; #ifdef IC74HC595_CUSTOM_SHIFT_IO -void ic74hc595_shift_io_pins(void) +MCU_CALLBACK void ic74hc595_shift_io_pins(void) { #ifndef IC74HC595_HAS_PWMS static volatile uint8_t ic74hc595_update_lock = 0; @@ -81,7 +81,7 @@ void ic74hc595_shift_io_pins(void) { do { - uint32_t data = *((uint32_t *)&ic74hc595_io_pins[0]); + uint32_t data = *((volatile uint32_t *)&ic74hc595_io_pins[0]); I2SREG.conf_single_data = data; } while (--ic74hc595_update_lock); } @@ -89,14 +89,14 @@ void ic74hc595_shift_io_pins(void) } #endif -#if defined(IC74HC595_CUSTOM_SHIFT_IO) && (IC74HC595_COUNT != 0) -IRAM_ATTR void io_updater(void *arg) +#ifdef IC74HC595_CUSTOM_SHIFT_IO +MCU_CALLBACK void io_updater(void *arg) { #ifdef IC74HC595_HAS_PWMS io_soft_pwm_update(); #endif - uint32_t data = *((uint32_t *)&ic74hc595_io_pins[0]); + uint32_t data = *((volatile uint32_t *)&ic74hc595_io_pins[0]); I2SREG.conf_single_data = data; timer_group_clr_intr_status_in_isr(PWM_TIMER_TG, PWM_TIMER_IDX); @@ -109,7 +109,7 @@ IRAM_ATTR void io_updater(void *arg) #if SERVOS_MASK > 0 static uint8_t mcu_servos[6]; -IRAM_ATTR void servo_reset(void *p) +MCU_CALLBACK void servo_reset(void *p) { timer_pause(SERVO_TIMER_TG, SERVO_TIMER_IDX); timer_group_clr_intr_status_in_isr(SERVO_TIMER_TG, SERVO_TIMER_IDX); @@ -162,7 +162,7 @@ void start_servo_timeout(uint8_t timeout) } #endif -IRAM_ATTR void mcu_gpio_isr(void *type) +MCU_CALLBACK void mcu_gpio_isr(void *type) { // read the address and not the pointer value because we are passing a literal integer // reading the pointer value would try to read an invalid memory address @@ -372,7 +372,7 @@ void mcu_rtc_task(void *arg) } } -IRAM_ATTR void mcu_itp_isr(void *arg) +MCU_CALLBACK void mcu_itp_isr(void *arg) { static bool resetstep = false; @@ -850,7 +850,7 @@ void mcu_eeprom_flush(void) #ifdef MCU_HAS_ONESHOT_TIMER -IRAM_ATTR void mcu_oneshot_isr(void *arg) +MCU_CALLBACK void mcu_oneshot_isr(void *arg) { timer_pause(ONESHOT_TIMER_TG, ONESHOT_TIMER_IDX); timer_group_clr_intr_status_in_isr(ONESHOT_TIMER_TG, ONESHOT_TIMER_IDX); diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index d0ec44ec0..71a1fd3b1 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -128,7 +128,6 @@ #define STEP6_EN_IO_OFFSET 22 #define STEP7_EN_IO_OFFSET 23 //#define PWM0_IO_OFFSET 24 -#define mcu_softpwm_freq_config(x) 7 #endif #define PWM0 25 #define DIO25 25 diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index 577585356..2b2272627 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -43,11 +43,10 @@ #define ic74hc595_delay() mcu_delay_cycles(IC74HC595_DELAY_CYCLES) -#if (IC74HC595_COUNT != 0) -uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; -static volatile uint8_t ic74hc595_update_lock; -void __attribute__((weak)) ic74hc595_shift_io_pins(void) +volatile uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; +MCU_CALLBACK void __attribute__((weak)) ic74hc595_shift_io_pins(void) { + static volatile uint8_t ic74hc595_update_lock = 0; uint8_t pins[IC74HC595_COUNT]; if (!ic74hc595_update_lock++) { @@ -87,5 +86,3 @@ void __attribute__((weak)) ic74hc595_shift_io_pins(void) } while (--ic74hc595_update_lock); } } - -#endif diff --git a/uCNC/src/modules/ic74hc595.h b/uCNC/src/modules/ic74hc595.h index 963c52797..65db60f7f 100644 --- a/uCNC/src/modules/ic74hc595.h +++ b/uCNC/src/modules/ic74hc595.h @@ -1523,7 +1523,7 @@ extern "C" #define __indirect__ex__(X, Y) DIO##X##_##Y #define __indirect__(X, Y) __indirect__ex__(X, Y) #endif - extern uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; + extern volatile uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; #define ic74hc595_set_pin(pin) ic74hc595_io_pins[(__indirect__(pin, IO_BYTEOFFSET))] |= (__indirect__(pin, IO_BITMASK)) #define ic74hc595_clear_pin(pin) ic74hc595_io_pins[__indirect__(pin, IO_BYTEOFFSET)] &= ~(__indirect__(pin, IO_BITMASK)) #define ic74hc595_toggle_pin(pin) ic74hc595_io_pins[(__indirect__(pin, IO_BYTEOFFSET))] ^= (__indirect__(pin, IO_BITMASK)) From ce3ef120b88d8711cf13835b64e1d3d2e5b4dce3 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 23 Aug 2023 09:30:03 +0100 Subject: [PATCH 097/168] fixed compile error --- uCNC/src/modules/ic74hc595.c | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index 2b2272627..1ac32605f 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -42,10 +42,11 @@ #endif #define ic74hc595_delay() mcu_delay_cycles(IC74HC595_DELAY_CYCLES) - +#if (IC74HC595_COUNT != 0) volatile uint8_t ic74hc595_io_pins[IC74HC595_COUNT]; MCU_CALLBACK void __attribute__((weak)) ic74hc595_shift_io_pins(void) { + static volatile uint8_t ic74hc595_update_lock = 0; uint8_t pins[IC74HC595_COUNT]; if (!ic74hc595_update_lock++) @@ -86,3 +87,8 @@ MCU_CALLBACK void __attribute__((weak)) ic74hc595_shift_io_pins(void) } while (--ic74hc595_update_lock); } } +#else +MCU_CALLBACK void __attribute__((weak)) ic74hc595_shift_io_pins(void) +{ +} +#endif From 24f072ad516c63ca122fd5bc09981dacd48e05d7 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 23 Aug 2023 11:24:36 +0100 Subject: [PATCH 098/168] fixed encoder typo --- uCNC/src/modules/encoder.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/modules/encoder.c b/uCNC/src/modules/encoder.c index 5279d8a72..e8af94a72 100644 --- a/uCNC/src/modules/encoder.c +++ b/uCNC/src/modules/encoder.c @@ -156,7 +156,7 @@ void encoders_update(uint8_t pulse, uint8_t diff) uint32_t time = mcu_micros(); prev_time = current_time; current_time = time; -#ifdef RPM_INDEX_OUTPUT +#ifdef RPM_INDEX_INPUT if (io_get_input(RPM_INDEX_INPUT)) #else if (encoders_pos[RPM_ENCODER] >= RPM_PPR) From 1eb9dd067b26ae206386d5d898d86b816bec4f12 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 24 Aug 2023 09:52:48 +0100 Subject: [PATCH 099/168] uniform uart ports naming --- .../src/hal/boards/esp32/boardmap_mks_dlc32.h | 2 +- .../hal/boards/esp32/boardmap_mks_tinybee.h | 2 +- .../hal/boards/esp32/boardmap_wemos_d1_r32.h | 2 +- .../hal/boards/esp8266/boardmap_wemos_d1.h | 2 +- .../src/hal/boards/rp2040/boardmap_rpi_pico.h | 2 +- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 20 +++++++++---------- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 8 ++++---- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 4 ++-- uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h | 16 +++++++-------- 9 files changed, 29 insertions(+), 29 deletions(-) diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h index cdac4e770..12a104f97 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_dlc32.h @@ -41,7 +41,7 @@ extern "C" #define TX_BIT 1 #define RX_PULLUP // only uncomment this if other port other then 0 is used -// #define COM_PORT 0 +// #define UART_PORT 0 #define PWM0_BIT 32 #define PWM0_CHANNEL 0 diff --git a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h index 21a242812..f6c0790de 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h +++ b/uCNC/src/hal/boards/esp32/boardmap_mks_tinybee.h @@ -41,7 +41,7 @@ extern "C" #define TX_BIT 1 #define RX_PULLUP // only uncomment this if other port other then 0 is used -// #define COM_PORT 0 +// #define UART_PORT 0 // configure the 74HC595 modules #define DOUT8_BIT 27 diff --git a/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h b/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h index 6b7d4d3ed..5ae6be9bd 100644 --- a/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h +++ b/uCNC/src/hal/boards/esp32/boardmap_wemos_d1_r32.h @@ -67,7 +67,7 @@ extern "C" #define TX_BIT 1 #define RX_PULLUP // only uncomment this if other port other then 0 is used -// #define COM_PORT 0 +// #define UART_PORT 0 // Setup PWM #define PWM0_BIT 23 // assigns PWM0 pin diff --git a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h index 6844512d0..1b882500c 100644 --- a/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h +++ b/uCNC/src/hal/boards/esp8266/boardmap_wemos_d1.h @@ -57,7 +57,7 @@ extern "C" #define TX_PORT D #define RX_PULLUP // only uncomment this if other port other then 0 is used -// #define COM_PORT 0 +// #define UART_PORT 0 // Setup PWM #define PWM0_BIT 2 // assigns PWM0 pin diff --git a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h index 5285f8976..b72f87145 100644 --- a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h +++ b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h @@ -53,7 +53,7 @@ extern "C" #define RX_PULLUP #define TX_BIT 0 // only uncomment this if other port other then 0 is used -// #define COM_PORT 0 +// #define UART_PORT 0 //forces USB #define MCU_HAS_USB diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 823e2db11..d73fa12cd 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -198,11 +198,11 @@ void mcu_core0_tasks_init(void *arg) { #ifdef MCU_HAS_UART // install UART driver handler - uart_driver_install(COM_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); + uart_driver_install(UART_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif #ifdef MCU_HAS_UART2 // install UART driver handler - uart_driver_install(COM2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); + uart_driver_install(UART2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif } @@ -360,8 +360,8 @@ void mcu_init(void) .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, .source_clk = UART_SCLK_APB}; // We won't use a buffer for sending data. - uart_param_config(COM_PORT, &uartconfig); - uart_set_pin(COM_PORT, TX_BIT, RX_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); + uart_param_config(UART_PORT, &uartconfig); + uart_set_pin(UART_PORT, TX_BIT, RX_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif #ifdef MCU_HAS_UART2 @@ -374,8 +374,8 @@ void mcu_init(void) .flow_ctrl = UART_HW_FLOWCTRL_DISABLE, .source_clk = UART_SCLK_APB}; // We won't use a buffer for sending data. - uart_param_config(COM2_PORT, &uart2config); - uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); + uart_param_config(UART2_PORT, &uart2config); + uart_set_pin(UART2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif #ifdef IC74HC595_HAS_PWMS @@ -572,7 +572,7 @@ void mcu_uart_flush(void) uint8_t r; BUFFER_READ(uart, tmp, UART_TX_BUFFER_SIZE, r); - uart_write_bytes(COM_PORT, tmp, r); + uart_write_bytes(UART_PORT, tmp, r); } } #endif @@ -599,7 +599,7 @@ void mcu_uart2_flush(void) uint8_t r; BUFFER_READ(uart2, tmp, UART2_TX_BUFFER_SIZE, r); - uart_write_bytes(COM2_PORT, tmp, r); + uart_write_bytes(UART2_PORT, tmp, r); } } #endif @@ -756,14 +756,14 @@ void mcu_dotasks(void) char rxdata[RX_BUFFER_SIZE]; int rxlen, i; #ifdef MCU_HAS_UART - rxlen = uart_read_bytes(COM_PORT, rxdata, RX_BUFFER_CAPACITY, 0); + rxlen = uart_read_bytes(UART_PORT, rxdata, RX_BUFFER_CAPACITY, 0); for (i = 0; i < rxlen; i++) { mcu_com_rx_cb((uint8_t)rxdata[i]); } #endif #if defined(MCU_HAS_UART2) - rxlen = uart_read_bytes(COM2_PORT, rxdata, RX_BUFFER_CAPACITY, 0); + rxlen = uart_read_bytes(UART2_PORT, rxdata, RX_BUFFER_CAPACITY, 0); #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) for (i = 0; i < rxlen; i++) { diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index f507eb945..f4e8e4533 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2682,14 +2682,14 @@ extern "C" #if (defined(TX) && defined(RX)) #define MCU_HAS_UART -#ifndef COM_PORT -#define COM_PORT 0 +#ifndef UART_PORT +#define UART_PORT 0 #endif #endif #if (defined(TX2) && defined(RX2)) #define MCU_HAS_UART2 -#ifndef COM2_PORT -#define COM2_PORT 0 +#ifndef UART2_PORT +#define UART2_PORT 0 #endif #ifndef BAUDRATE2 #define BAUDRATE2 BAUDRATE diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index e36ed79b7..d9b1a861c 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -989,8 +989,8 @@ extern "C" #define BOARD_HAS_CUSTOM_SYSTEM_COMMANDS #endif -#ifndef COM_PORT -#define COM_PORT 0 +#ifndef UART_PORT +#define UART_PORT 0 #endif #define MCU_HAS_ONESHOT_TIMER diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index 1a444f6ce..a418ea25b 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -994,12 +994,12 @@ extern "C" #endif #ifdef MCU_HAS_UART -#ifndef COM_PORT -#define COM_PORT 0 +#ifndef UART_PORT +#define UART_PORT 0 #endif -#if (COM_PORT == 0) +#if (UART_PORT == 0) #define COM_UART Serial1 -#elif (COM_PORT == 1) +#elif (UART_PORT == 1) #define COM_UART Serial2 #else #error "UART COM port number must be 0 or 1" @@ -1010,12 +1010,12 @@ extern "C" #ifndef BAUDRATE2 #define BAUDRATE2 BAUDRATE #endif -#ifndef COM2_PORT -#define COM2_PORT 0 +#ifndef UART2_PORT +#define UART2_PORT 0 #endif -#if (COM2_PORT == 0) +#if (UART2_PORT == 0) #define COM2_UART Serial1 -#elif (COM2_PORT == 1) +#elif (UART2_PORT == 1) #define COM2_UART Serial2 #else #error "UART2 COM port number must be 0 or 1" From c78a5ad2a3a418b627f0d69e6b5477c6d37e377d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 24 Aug 2023 12:41:34 +0100 Subject: [PATCH 100/168] moved all io generation to core0 --- uCNC/src/core/io_control.c | 4 ++ uCNC/src/hal/mcus/esp32/mcu_esp32.c | 90 +++++++++++++++++--------- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 2 +- 3 files changed, 65 insertions(+), 31 deletions(-) diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index 08c8eeb25..beda4cd80 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -1016,6 +1016,10 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM15); } #endif + +#ifdef IC74HC595_HAS_PWMS + ic74hc595_shift_io_pins(); +#endif } #endif diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 24c783e77..84176bc35 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -39,6 +39,12 @@ static volatile bool esp32_global_isr_enabled; static volatile uint32_t mcu_runtime_ms; +static volatile bool mcu_itp_timer_running; +#ifdef IC74HC595_CUSTOM_SHIFT_IO +volatile static uint32_t esp32_io_counter; +volatile static uint32_t esp32_io_counter_reload; +#endif +hw_timer_t *esp32_step_timer; void esp32_wifi_bt_init(void); void esp32_wifi_bt_flush(char *buffer); @@ -70,39 +76,43 @@ static flash_eeprom_t mcu_eeprom; #include "driver/i2s.h" #endif -hw_timer_t *esp32_step_timer; - #ifdef IC74HC595_CUSTOM_SHIFT_IO +// disable this function +// IO will be updated at a fixed rate MCU_CALLBACK void ic74hc595_shift_io_pins(void) { -#ifndef IC74HC595_HAS_PWMS - static volatile uint8_t ic74hc595_update_lock = 0; - if (!ic74hc595_update_lock++) - { - do - { - uint32_t data = *((volatile uint32_t *)&ic74hc595_io_pins[0]); - I2SREG.conf_single_data = data; - } while (--ic74hc595_update_lock); - } -#endif } #endif #ifdef IC74HC595_CUSTOM_SHIFT_IO -MCU_CALLBACK void io_updater(void *arg) +MCU_CALLBACK void esp32_io_updater(void *arg) { + static bool resetstep = false; + #ifdef IC74HC595_HAS_PWMS io_soft_pwm_update(); #endif + if (mcu_itp_timer_running) + { + if (!--esp32_io_counter) + { + if (!resetstep) + mcu_step_cb(); + else + mcu_step_reset_cb(); + resetstep = !resetstep; + esp32_io_counter = esp32_io_counter_reload; + } + } + uint32_t data = *((volatile uint32_t *)&ic74hc595_io_pins[0]); I2SREG.conf_single_data = data; - timer_group_clr_intr_status_in_isr(PWM_TIMER_TG, PWM_TIMER_IDX); + timer_group_clr_intr_status_in_isr(ITP_TIMER_TG, ITP_TIMER_IDX); /* After the alarm has been triggered we need enable it again, so it is triggered the next time */ - timer_group_enable_alarm_in_isr(PWM_TIMER_TG, PWM_TIMER_IDX); + timer_group_enable_alarm_in_isr(ITP_TIMER_TG, ITP_TIMER_IDX); } #endif @@ -246,29 +256,26 @@ static FORCEINLINE void esp32_i2s_extender_init(void) I2SREG.int_ena.out_eof = 0; I2SREG.int_ena.out_dscr_err = 0; -#endif - -#if defined(IC74HC595_HAS_PWMS) - // initialize PWM timer + // initialize ITP timer that will run at a fixed rate to update all IO /* Select and initialize basic parameters of the timer */ - timer_config_t pwmconfig = { + timer_config_t itpconfig = { .divider = 2, .counter_dir = TIMER_COUNT_UP, .counter_en = TIMER_PAUSE, .alarm_en = TIMER_ALARM_EN, .auto_reload = true, }; // default clock source is APB - timer_init(PWM_TIMER_TG, PWM_TIMER_IDX, &pwmconfig); + timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); /* Timer's counter will initially start from value below. Also, if auto_reload is set, this value will be automatically reload on alarm */ - timer_set_counter_value(PWM_TIMER_TG, PWM_TIMER_IDX, 0x00000000ULL); + timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); /* Configure the alarm value and the interrupt on alarm. */ - timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)157); + timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)160); // register PWM isr - timer_isr_register(PWM_TIMER_TG, PWM_TIMER_IDX, io_updater, NULL, 0, NULL); - timer_enable_intr(PWM_TIMER_TG, PWM_TIMER_IDX); - timer_start(PWM_TIMER_TG, PWM_TIMER_IDX); + timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); + timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); + timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); #endif } @@ -283,7 +290,7 @@ void mcu_core0_tasks_init(void *arg) uart_driver_install(COM2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif -#ifdef IC74HC595_HAS_PWMS +#ifdef IC74HC595_CUSTOM_SHIFT_IO esp32_i2s_extender_init(); #endif } @@ -372,6 +379,7 @@ void mcu_rtc_task(void *arg) } } +#ifndef IC74HC595_CUSTOM_SHIFT_IO MCU_CALLBACK void mcu_itp_isr(void *arg) { static bool resetstep = false; @@ -387,6 +395,7 @@ MCU_CALLBACK void mcu_itp_isr(void *arg) we need enable it again, so it is triggered the next time */ timer_group_enable_alarm_in_isr(ITP_TIMER_TG, ITP_TIMER_IDX); } +#endif /** * initializes the mcu @@ -464,6 +473,7 @@ void mcu_init(void) esp32_i2s_extender_init(); #endif +#ifndef IC74HC595_CUSTOM_SHIFT_IO // inititialize ITP timer timer_config_t itpconfig = {0}; itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse @@ -472,6 +482,7 @@ void mcu_init(void) itpconfig.alarm_en = TIMER_ALARM_EN; itpconfig.auto_reload = true; timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); +#endif // initialize rtc timer (currently on core 1) // moved to core 0 @@ -663,8 +674,12 @@ bool mcu_get_global_isr(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { - // up and down counter (generates half the step rate at each event) +// up and down counter (generates half the step rate at each event) +#ifndef IC74HC595_CUSTOM_SHIFT_IO uint32_t totalticks = (uint32_t)(500000.0f / frequency); +#else + uint32_t totalticks = (uint32_t)(125000.0f / frequency); +#endif *prescaller = 1; while (totalticks > 0xFFFF) { @@ -677,17 +692,22 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) float mcu_clocks_to_freq(uint16_t ticks, uint16_t prescaller) { +#ifndef IC74HC595_CUSTOM_SHIFT_IO return (500000.0f / ((float)ticks * (float)prescaller)); +#else + return (125000.0f / ((float)ticks * (float)prescaller)); +#endif } /** * starts the timer interrupt that generates the step pulses for the interpolator * */ -static volatile bool mcu_itp_timer_running; + void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) { if (!mcu_itp_timer_running) { +#ifndef IC74HC595_CUSTOM_SHIFT_IO /* Timer's counter will initially start from value below. Also, if auto_reload is set, this value will be automatically reload on alarm */ timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); @@ -698,6 +718,10 @@ void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, mcu_itp_isr, NULL, 0, NULL); timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); +#else + esp32_io_counter_reload = (uint32_t)(ticks * prescaller); + esp32_io_counter = esp32_io_counter_reload; +#endif mcu_itp_timer_running = true; } else @@ -713,9 +737,13 @@ void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller) { if (mcu_itp_timer_running) { +#ifndef IC74HC595_CUSTOM_SHIFT_IO timer_pause(ITP_TIMER_TG, ITP_TIMER_IDX); timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)ticks * prescaller); timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); +#else + esp32_io_counter_reload = (uint32_t)(ticks * prescaller); +#endif } else { @@ -730,9 +758,11 @@ void mcu_stop_itp_isr(void) { if (mcu_itp_timer_running) { +#ifndef IC74HC595_CUSTOM_SHIFT_IO // timerAlarmDisable(esp32_step_timer); timer_pause(ITP_TIMER_TG, ITP_TIMER_IDX); timer_disable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); +#endif mcu_itp_timer_running = false; } } diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 033c2c898..b8c92ce8d 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -49,7 +49,7 @@ extern "C" #endif // defines the maximum and minimum step rates #ifndef F_STEP_MAX -#define F_STEP_MAX 100000UL +#define F_STEP_MAX 125000UL #endif #ifndef F_STEP_MIN #define F_STEP_MIN 1 From e93a20f0693dee5949c4d47ebfd137604ef1c21b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 25 Aug 2023 10:38:07 +0100 Subject: [PATCH 101/168] update ESP8266 mcumap - update ESP8266 mcumap - fixed pwm tools assert pins --- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 8 +- uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h | 137 +++++++++++---------- uCNC/src/hal/tools/tools/spindle_pwm.c | 2 - uCNC/src/hal/tools/tools/vfd_pwm.c | 2 - uCNC/src/modules/system_menu.c | 2 + 5 files changed, 77 insertions(+), 74 deletions(-) diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 0c037b27c..be1ad421b 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -99,22 +99,22 @@ static IRAM_ATTR void mcu_gen_step(void) IRAM_ATTR void mcu_din_isr(void) { - io_inputs_isr(); + mcu_inputs_changed_cb(); } IRAM_ATTR void mcu_probe_isr(void) { - io_probe_isr(); + mcu_probe_changed_cb(); } IRAM_ATTR void mcu_limits_isr(void) { - io_limits_isr(); + mcu_limits_changed_cb(); } IRAM_ATTR void mcu_controls_isr(void) { - io_controls_isr(); + mcu_controls_changed_cb(); } IRAM_ATTR void mcu_rtc_isr(void *arg) diff --git a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h index d9b1a861c..db0915bd2 100644 --- a/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h +++ b/uCNC/src/hal/mcus/esp8266/mcumap_esp8266.h @@ -867,117 +867,122 @@ extern "C" #endif // ISR on change inputs -#if (defined(LIMIT_X_ISR) && defined(LIMIT_X)) -#define DIO52_ISR (LIMIT_X_ISR) +extern void mcu_din_isr(void); +extern void mcu_probe_isr(void); +extern void mcu_limits_isr(void); +extern void mcu_controls_isr(void); +#if(defined(LIMIT_X_ISR) && defined(LIMIT_X)) +#define DIO100_ISR (LIMIT_X_ISR) #define LIMIT_X_ISRCALLBACK mcu_limit_isr -#define DIO52_ISRCALLBACK mcu_limit_isr +#define DIO100_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_Y_ISR) && defined(LIMIT_Y)) -#define DIO53_ISR (LIMIT_Y_ISR) +#if(defined(LIMIT_Y_ISR) && defined(LIMIT_Y)) +#define DIO101_ISR (LIMIT_Y_ISR) #define LIMIT_Y_ISRCALLBACK mcu_limit_isr -#define DIO53_ISRCALLBACK mcu_limit_isr +#define DIO101_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_Z_ISR) && defined(LIMIT_Z)) -#define DIO54_ISR (LIMIT_Z_ISR) +#if(defined(LIMIT_Z_ISR) && defined(LIMIT_Z)) +#define DIO102_ISR (LIMIT_Z_ISR) #define LIMIT_Z_ISRCALLBACK mcu_limit_isr -#define DIO54_ISRCALLBACK mcu_limit_isr +#define DIO102_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_X2_ISR) && defined(LIMIT_X2)) -#define DIO55_ISR (LIMIT_X2_ISR) +#if(defined(LIMIT_X2_ISR) && defined(LIMIT_X2)) +#define DIO103_ISR (LIMIT_X2_ISR) #define LIMIT_X2_ISRCALLBACK mcu_limit_isr -#define DIO55_ISRCALLBACK mcu_limit_isr +#define DIO103_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_Y2_ISR) && defined(LIMIT_Y2)) -#define DIO56_ISR (LIMIT_Y2_ISR) +#if(defined(LIMIT_Y2_ISR) && defined(LIMIT_Y2)) +#define DIO104_ISR (LIMIT_Y2_ISR) #define LIMIT_Y2_ISRCALLBACK mcu_limit_isr -#define DIO56_ISRCALLBACK mcu_limit_isr +#define DIO104_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_Z2_ISR) && defined(LIMIT_Z2)) -#define DIO57_ISR (LIMIT_Z2_ISR) +#if(defined(LIMIT_Z2_ISR) && defined(LIMIT_Z2)) +#define DIO105_ISR (LIMIT_Z2_ISR) #define LIMIT_Z2_ISRCALLBACK mcu_limit_isr -#define DIO57_ISRCALLBACK mcu_limit_isr +#define DIO105_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_A_ISR) && defined(LIMIT_A)) -#define DIO58_ISR (LIMIT_A_ISR) +#if(defined(LIMIT_A_ISR) && defined(LIMIT_A)) +#define DIO106_ISR (LIMIT_A_ISR) #define LIMIT_A_ISRCALLBACK mcu_limit_isr -#define DIO58_ISRCALLBACK mcu_limit_isr +#define DIO106_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_B_ISR) && defined(LIMIT_B)) -#define DIO59_ISR (LIMIT_B_ISR) +#if(defined(LIMIT_B_ISR) && defined(LIMIT_B)) +#define DIO107_ISR (LIMIT_B_ISR) #define LIMIT_B_ISRCALLBACK mcu_limit_isr -#define DIO59_ISRCALLBACK mcu_limit_isr +#define DIO107_ISRCALLBACK mcu_limit_isr #endif -#if (defined(LIMIT_C_ISR) && defined(LIMIT_C)) -#define DIO60_ISR (LIMIT_C_ISR) +#if(defined(LIMIT_C_ISR) && defined(LIMIT_C)) +#define DIO108_ISR (LIMIT_C_ISR) #define LIMIT_C_ISRCALLBACK mcu_limit_isr -#define DIO60_ISRCALLBACK mcu_limit_isr +#define DIO108_ISRCALLBACK mcu_limit_isr #endif -#if (defined(PROBE_ISR) && defined(PROBE)) -#define DIO61_ISR (PROBE_ISR) +#if(defined(PROBE_ISR) && defined(PROBE)) +#define DIO109_ISR (PROBE_ISR) #define PROBE_ISRCALLBACK mcu_probe_isr -#define DIO61_ISRCALLBACK mcu_probe_isr +#define DIO109_ISRCALLBACK mcu_probe_isr #endif -#if (defined(ESTOP_ISR) && defined(ESTOP)) -#define DIO62_ISR (ESTOP_ISR) +#if(defined(ESTOP_ISR) && defined(ESTOP)) +#define DIO110_ISR (ESTOP_ISR) #define ESTOP_ISRCALLBACK mcu_control_isr -#define DIO62_ISRCALLBACK mcu_control_isr +#define DIO110_ISRCALLBACK mcu_control_isr #endif -#if (defined(SAFETY_DOOR_ISR) && defined(SAFETY_DOOR)) -#define DIO63_ISR (SAFETY_DOOR_ISR) +#if(defined(SAFETY_DOOR_ISR) && defined(SAFETY_DOOR)) +#define DIO111_ISR (SAFETY_DOOR_ISR) #define SAFETY_DOOR_ISRCALLBACK mcu_control_isr -#define DIO63_ISRCALLBACK mcu_control_isr +#define DIO111_ISRCALLBACK mcu_control_isr #endif -#if (defined(FHOLD_ISR) && defined(FHOLD)) -#define DIO64_ISR (FHOLD_ISR) +#if(defined(FHOLD_ISR) && defined(FHOLD)) +#define DIO112_ISR (FHOLD_ISR) #define FHOLD_ISRCALLBACK mcu_control_isr -#define DIO64_ISRCALLBACK mcu_control_isr +#define DIO112_ISRCALLBACK mcu_control_isr #endif -#if (defined(CS_RES_ISR) && defined(CS_RES)) -#define DIO65_ISR (CS_RES_ISR) +#if(defined(CS_RES_ISR) && defined(CS_RES)) +#define DIO113_ISR (CS_RES_ISR) #define CS_RES_ISRCALLBACK mcu_control_isr -#define DIO65_ISRCALLBACK mcu_control_isr +#define DIO113_ISRCALLBACK mcu_control_isr #endif -#if (defined(DIN0_ISR) && defined(DIN0)) -#define DIO82_ISR (DIN0_ISR) +#if(defined(DIN0_ISR) && defined(DIN0)) +#define DIO130_ISR (DIN0_ISR) #define DIN0_ISRCALLBACK mcu_din_isr -#define DIO82_ISRCALLBACK mcu_din_isr +#define DIO130_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN1_ISR) && defined(DIN1)) -#define DIO83_ISR (DIN1_ISR) +#if(defined(DIN1_ISR) && defined(DIN1)) +#define DIO131_ISR (DIN1_ISR) #define DIN1_ISRCALLBACK mcu_din_isr -#define DIO83_ISRCALLBACK mcu_din_isr +#define DIO131_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN2_ISR) && defined(DIN2)) -#define DIO84_ISR (DIN2_ISR) +#if(defined(DIN2_ISR) && defined(DIN2)) +#define DIO132_ISR (DIN2_ISR) #define DIN2_ISRCALLBACK mcu_din_isr -#define DIO84_ISRCALLBACK mcu_din_isr +#define DIO132_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN3_ISR) && defined(DIN3)) -#define DIO85_ISR (DIN3_ISR) +#if(defined(DIN3_ISR) && defined(DIN3)) +#define DIO133_ISR (DIN3_ISR) #define DIN3_ISRCALLBACK mcu_din_isr -#define DIO85_ISRCALLBACK mcu_din_isr +#define DIO133_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN4_ISR) && defined(DIN4)) -#define DIO86_ISR (DIN4_ISR) +#if(defined(DIN4_ISR) && defined(DIN4)) +#define DIO134_ISR (DIN4_ISR) #define DIN4_ISRCALLBACK mcu_din_isr -#define DIO86_ISRCALLBACK mcu_din_isr +#define DIO134_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN5_ISR) && defined(DIN5)) -#define DIO87_ISR (DIN5_ISR) +#if(defined(DIN5_ISR) && defined(DIN5)) +#define DIO135_ISR (DIN5_ISR) #define DIN5_ISRCALLBACK mcu_din_isr -#define DIO87_ISRCALLBACK mcu_din_isr +#define DIO135_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN6_ISR) && defined(DIN6)) -#define DIO88_ISR (DIN6_ISR) +#if(defined(DIN6_ISR) && defined(DIN6)) +#define DIO136_ISR (DIN6_ISR) #define DIN6_ISRCALLBACK mcu_din_isr -#define DIO88_ISRCALLBACK mcu_din_isr +#define DIO136_ISRCALLBACK mcu_din_isr #endif -#if (defined(DIN7_ISR) && defined(DIN7)) -#define DIO89_ISR (DIN7_ISR) +#if(defined(DIN7_ISR) && defined(DIN7)) +#define DIO137_ISR (DIN7_ISR) #define DIN7_ISRCALLBACK mcu_din_isr -#define DIO89_ISRCALLBACK __indirect__(X, ISRCALLBACK) +#define DIO137_ISRCALLBACK mcu_din_isr #endif + #if (defined(TX) && defined(RX)) #define MCU_HAS_UART #endif diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 3f182bd55..b5727be0d 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -95,8 +95,6 @@ static void set_speed(int16_t value) #if ASSERT_PIN(SPINDLE_PWM) io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); -#else - io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); #endif } diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index ac48577d5..a2aa17a93 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -91,8 +91,6 @@ static void set_speed(int16_t value) #if ASSERT_PIN(VFD_PWM) io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); -#else - io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); #endif } diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index a4274424f..57738adb3 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -97,7 +97,9 @@ DECL_MODULE(system_menu) DECL_MENU(8, 1, STR_OVERRIDES); DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); DECL_MENU_ACTION(8, ovf_100, STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); +#if (TOOL_COUNT > 0) DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); +#endif DECL_MENU_ACTION(8, ovt_100, STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); // append Jog menu From ae8a3e8d18956d7644ba0c8fff7c28fe350e8409 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 25 Aug 2023 11:07:48 +0100 Subject: [PATCH 102/168] added clamping values to step freq func --- uCNC/src/hal/mcus/avr/mcu_avr.c | 5 +---- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 5 +++++ uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 2 ++ uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 1 + uCNC/src/hal/mcus/rp2040/mcu_rp2040.c | 1 + uCNC/src/hal/mcus/samd21/mcu_samd21.c | 5 +---- uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 1 + uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 2 ++ uCNC/src/hal/mcus/virtual/mcu_virtual.c | 5 +---- uCNC/src/hal/tools/tools/laser_pwm.c | 2 -- uCNC/src/hal/tools/tools/spindle_pwm.c | 2 -- uCNC/src/hal/tools/tools/vfd_pwm.c | 2 -- 12 files changed, 15 insertions(+), 18 deletions(-) diff --git a/uCNC/src/hal/mcus/avr/mcu_avr.c b/uCNC/src/hal/mcus/avr/mcu_avr.c index 0c819bdbc..1fd7e19be 100644 --- a/uCNC/src/hal/mcus/avr/mcu_avr.c +++ b/uCNC/src/hal/mcus/avr/mcu_avr.c @@ -617,10 +617,7 @@ void mcu_uart2_flush(void) // RealTime void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { - if (frequency < F_STEP_MIN) - frequency = F_STEP_MIN; - if (frequency > F_STEP_MAX) - frequency = F_STEP_MAX; + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); uint32_t clocks = (uint32_t)floorf((float)F_CPU / frequency); *prescaller = (1 << 3); // CTC mode diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 84176bc35..c1a1dea3c 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -98,9 +98,13 @@ MCU_CALLBACK void esp32_io_updater(void *arg) if (!--esp32_io_counter) { if (!resetstep) + { mcu_step_cb(); + } else + { mcu_step_reset_cb(); + } resetstep = !resetstep; esp32_io_counter = esp32_io_counter_reload; } @@ -674,6 +678,7 @@ bool mcu_get_global_isr(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); // up and down counter (generates half the step rate at each event) #ifndef IC74HC595_CUSTOM_SHIFT_IO uint32_t totalticks = (uint32_t)(500000.0f / frequency); diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 0c037b27c..b5d519d2e 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -320,6 +320,8 @@ bool mcu_get_global_isr(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); + // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)(128000UL >> 1) / frequency); *prescaller = 0; diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index 05b06eecf..b4c8f78f8 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -663,6 +663,7 @@ void mcu_uart2_flush(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)1000000UL / frequency); // *prescaller = 0; diff --git a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c index dd188e749..8f53c1183 100644 --- a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c +++ b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c @@ -422,6 +422,7 @@ static void mcu_itp_isr(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)(1000000UL >> 1) / frequency); *prescaller = 1; diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index 191aa66df..9d54fac7f 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -841,10 +841,7 @@ void mcu_disable_global_isr(void) * */ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { - if (frequency < F_STEP_MIN) - frequency = F_STEP_MIN; - if (frequency > F_STEP_MAX) - frequency = F_STEP_MAX; + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); uint32_t clocks = (uint32_t)((F_TIMERS >> 1) / frequency); *prescaller = 0; diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 14cf75bd7..d2dd462fb 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -637,6 +637,7 @@ uint8_t mcu_get_servo(uint8_t servo) // convert step rate to clock cycles void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)(ITP_TIMER_CLOCK >> 1) / frequency); diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index bae4deb48..fdd30d6bb 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -641,6 +641,8 @@ uint8_t mcu_get_servo(uint8_t servo) // convert step rate to clock cycles void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); + // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)(TIMER_CLOCK >> 1) / frequency); *prescaller = 1; diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index b149f8f56..791560d48 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -1506,10 +1506,7 @@ void mcu_bufferClear(void) // RealTime void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *tick_reps) { - if (frequency < F_STEP_MIN) - frequency = F_STEP_MIN; - if (frequency > F_STEP_MAX) - frequency = F_STEP_MAX; + frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); *ticks = (uint16_t)floorf((F_CPU / frequency)); *tick_reps = 1; diff --git a/uCNC/src/hal/tools/tools/laser_pwm.c b/uCNC/src/hal/tools/tools/laser_pwm.c index e022edef3..05daa344f 100644 --- a/uCNC/src/hal/tools/tools/laser_pwm.c +++ b/uCNC/src/hal/tools/tools/laser_pwm.c @@ -78,8 +78,6 @@ static void set_speed(int16_t value) // speed optimized version (in AVR it's 24 instruction cycles) #if ASSERT_PIN(LASER_PWM) io_set_pwm(LASER_PWM, (uint8_t)ABS(value)); -#else - io_set_pwm(LASER_PWM, (uint8_t)ABS(value)); #endif } diff --git a/uCNC/src/hal/tools/tools/spindle_pwm.c b/uCNC/src/hal/tools/tools/spindle_pwm.c index 3f182bd55..b5727be0d 100644 --- a/uCNC/src/hal/tools/tools/spindle_pwm.c +++ b/uCNC/src/hal/tools/tools/spindle_pwm.c @@ -95,8 +95,6 @@ static void set_speed(int16_t value) #if ASSERT_PIN(SPINDLE_PWM) io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); -#else - io_set_pwm(SPINDLE_PWM, (uint8_t)ABS(value)); #endif } diff --git a/uCNC/src/hal/tools/tools/vfd_pwm.c b/uCNC/src/hal/tools/tools/vfd_pwm.c index ac48577d5..a2aa17a93 100644 --- a/uCNC/src/hal/tools/tools/vfd_pwm.c +++ b/uCNC/src/hal/tools/tools/vfd_pwm.c @@ -91,8 +91,6 @@ static void set_speed(int16_t value) #if ASSERT_PIN(VFD_PWM) io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); -#else - io_set_pwm(VFD_PWM, (uint8_t)ABS(value)); #endif } From aacf05d99ba6513342f120423233a3354bf86135 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 26 Aug 2023 10:24:06 +0100 Subject: [PATCH 103/168] apply PR486 apply #486 --- tests/gcode/{circle.ngc => circle.nc} | 0 tests/gcode/curves-as-lines.nc | 4514 +++++++++++++++++ ...on-tests-hmap.ngc => motion-tests-hmap.nc} | 0 .../{motion-tests.ngc => motion-tests.nc} | 0 ..._modes-tests.ngc => motion_modes-tests.nc} | 0 .../{override-tests.ngc => override-tests.nc} | 0 tests/gcode/{sample.ngc => sample.nc} | 0 .../{stress-tests.ngc => stress-tests.nc} | 0 uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 3 + 9 files changed, 4517 insertions(+) rename tests/gcode/{circle.ngc => circle.nc} (100%) create mode 100644 tests/gcode/curves-as-lines.nc rename tests/gcode/{motion-tests-hmap.ngc => motion-tests-hmap.nc} (100%) rename tests/gcode/{motion-tests.ngc => motion-tests.nc} (100%) rename tests/gcode/{motion_modes-tests.ngc => motion_modes-tests.nc} (100%) rename tests/gcode/{override-tests.ngc => override-tests.nc} (100%) rename tests/gcode/{sample.ngc => sample.nc} (100%) rename tests/gcode/{stress-tests.ngc => stress-tests.nc} (100%) diff --git a/tests/gcode/circle.ngc b/tests/gcode/circle.nc similarity index 100% rename from tests/gcode/circle.ngc rename to tests/gcode/circle.nc diff --git a/tests/gcode/curves-as-lines.nc b/tests/gcode/curves-as-lines.nc new file mode 100644 index 000000000..0d0a58c6f --- /dev/null +++ b/tests/gcode/curves-as-lines.nc @@ -0,0 +1,4514 @@ +G90 +G21 +G0 X0 Y0 Z0 +M3 S300 +G0 F5000.0 X4.120251 Y42.572236 +M4 S400 +G1 F5000.0 X3.008911 Y46.012061 +G1 X2.129933 Y48.902439 +G1 X1.529649 Y51.095237 +G1 X1.051086 Y53.100143 +G1 X0.687153 Y54.929221 +G1 X0.426827 Y56.595063 +G1 X0.257273 Y58.110269 +G1 X0.159498 Y59.624716 +G1 X0.138135 Y60.587212 +G1 X0.095115 Y63.358852 +G1 X0.126592 Y64.521507 +G1 X0.218465 Y65.517631 +G1 X0.562371 Y67.843985 +G1 X0.947309 Y69.936134 +G1 X1.366943 Y71.815661 +G1 X1.813492 Y73.503044 +G1 X2.328668 Y75.167717 +G1 X2.861987 Y76.659357 +G1 X3.462193 Y78.128492 +G1 X4.134131 Y79.573344 +G1 X4.811306 Y80.864277 +G1 X5.555405 Y82.132335 +G1 X6.370067 Y83.376182 +G1 X6.478940 Y83.532602 +G1 X7.394332 Y84.773698 +G1 X8.367421 Y85.967805 +G1 X9.395676 Y87.112626 +G1 X10.476566 Y88.205866 +G1 X11.607560 Y89.245225 +G1 X12.786128 Y90.228407 +G1 X14.009739 Y91.153115 +G1 X15.275862 Y92.017052 +G1 X16.581966 Y92.817920 +G1 X17.925521 Y93.553422 +G1 X19.303995 Y94.221262 +G1 X20.714859 Y94.819141 +G1 X22.155582 Y95.344763 +G1 X23.489110 Y95.757966 +G1 X24.843322 Y96.107828 +G1 X26.216316 Y96.392623 +G1 X26.686377 Y96.474209 +G1 X27.588045 Y96.617266 +G1 X28.441858 Y96.735447 +G1 X28.582691 Y96.752656 +G1 X29.470815 Y96.818699 +G1 X30.394345 Y96.829206 +G1 X31.353484 Y96.815083 +G1 X32.185687 Y96.806794 +G1 X32.722302 Y96.809546 +G1 X33.202387 Y96.808748 +G1 X33.669161 Y96.790819 +G1 X34.082001 Y96.752655 +G1 X34.991284 Y96.629845 +G1 X35.949263 Y96.470776 +G1 X36.918494 Y96.276476 +G1 X37.861535 Y96.047974 +G1 X38.064257 Y95.992520 +G1 X39.418403 Y95.579083 +G1 X40.751624 Y95.102463 +G1 X42.060112 Y94.563143 +G1 X43.340057 Y93.961602 +G1 X44.587651 Y93.298323 +G1 X45.799086 Y92.573787 +G1 X46.970552 Y91.788475 +G1 X48.098241 Y90.942869 +G1 X49.178344 Y90.037449 +G1 X50.207052 Y89.072697 +G1 X51.094439 Y88.144569 +G1 X51.933341 Y87.168166 +G1 X52.720897 Y86.143848 +G1 X53.454246 Y85.071979 +G1 X54.130527 Y83.952919 +G1 X54.153712 Y83.911865 +G1 X54.721969 Y82.833972 +G1 X55.228611 Y81.728952 +G1 X55.673582 Y80.599973 +G1 X56.056824 Y79.450201 +G1 X56.378282 Y78.282803 +G1 X56.637897 Y77.100946 +G1 X56.835614 Y75.907797 +G1 X56.971374 Y74.706523 +G1 X57.045122 Y73.500290 +G1 X57.056801 Y72.292266 +G1 X57.006353 Y71.085616 +G1 X56.893722 Y69.883508 +G1 X56.718851 Y68.689109 +G1 X56.481682 Y67.505586 +G1 X56.182160 Y66.336105 +G1 X55.820227 Y65.183833 +G1 X55.395826 Y64.051937 +G1 X54.908901 Y62.943583 +G1 X54.359395 Y61.861940 +G1 X53.747250 Y60.810172 +G1 X53.072410 Y59.791448 +G1 X52.825913 Y59.449424 +G1 X52.028679 Y58.434200 +G1 X51.170022 Y57.469182 +G1 X50.253887 Y56.557326 +G1 X49.284218 Y55.701591 +G1 X48.264962 Y54.904934 +G1 X47.200063 Y54.170312 +G1 X46.093467 Y53.500684 +G1 X44.949119 Y52.899005 +G1 X43.770964 Y52.368235 +G1 X42.615410 Y51.929402 +G1 X41.450772 Y51.558496 +G1 X40.240999 Y51.245562 +G1 X39.236338 Y51.050926 +G1 X38.443522 Y50.948254 +G1 X38.044821 Y50.917818 +G1 X37.695696 Y50.906143 +G1 X37.361262 Y50.906460 +G1 X37.006632 Y50.911996 +G1 X36.596922 Y50.915981 +G1 X36.547207 Y50.916034 +G1 X36.140824 Y50.913450 +G1 X35.798030 Y50.908035 +G1 X35.492312 Y50.903299 +G1 X35.197155 Y50.902751 +G1 X34.853036 Y50.911171 +G1 X34.461261 Y50.933084 +G1 X33.876012 Y50.995723 +G1 X33.251724 Y51.100054 +G1 X32.608596 Y51.237956 +G1 X31.966824 Y51.401310 +G1 X31.346605 Y51.581994 +G1 X30.768137 Y51.771888 +G1 X30.668638 Y51.806907 +G1 X29.641354 Y52.209397 +G1 X28.642822 Y52.677292 +G1 X27.678887 Y53.211379 +G1 X26.837521 Y53.755015 +G1 X26.033968 Y54.354597 +G1 X25.359718 Y54.930697 +G1 X24.850883 Y55.438138 +G1 X24.364125 Y56.005174 +G1 X23.904400 Y56.614798 +G1 X23.476663 Y57.250003 +G1 X23.085871 Y57.893784 +G1 X22.736978 Y58.529133 +G1 X22.434940 Y59.139044 +G1 X22.184713 Y59.706511 +G1 X22.135229 Y59.828686 +G1 X23.141413 Y59.306471 +G1 X24.208324 Y58.790249 +G1 X25.321162 Y58.305450 +G1 X26.465126 Y57.877503 +G1 X27.519651 Y57.559194 +G1 X28.480662 Y57.344910 +G1 X29.348980 Y57.224657 +G1 X30.128495 Y57.186334 +G1 X30.478994 Y57.193575 +G1 X31.386034 Y57.273431 +G1 X32.284512 Y57.431912 +G1 X33.165935 Y57.667511 +G1 X33.945282 Y57.947343 +G1 X34.697136 Y58.288531 +G1 X35.415115 Y58.689941 +G1 X36.092839 Y59.150441 +G1 X36.723929 Y59.668899 +G1 X37.302003 Y60.244181 +G1 X37.776151 Y60.815524 +G1 X38.196417 Y61.432042 +G1 X38.558009 Y62.092884 +G1 X38.856132 Y62.797201 +G1 X38.944136 Y63.052416 +G1 X39.143970 Y63.765126 +G1 X39.258712 Y64.398857 +G1 X39.305558 Y65.035684 +G1 X39.294196 Y65.517630 +G1 X39.227390 Y66.267608 +G1 X39.119429 Y66.970851 +G1 X38.958080 Y67.651215 +G1 X38.731109 Y68.332560 +G1 X38.457532 Y68.972891 +G1 X38.192625 Y69.499886 +G1 X37.775721 Y70.207300 +G1 X37.305141 Y70.872282 +G1 X36.785011 Y71.495085 +G1 X36.219455 Y72.075962 +G1 X35.612598 Y72.615165 +G1 X34.968567 Y73.112946 +G1 X34.291486 Y73.569560 +G1 X33.585481 Y73.985257 +G1 X32.854677 Y74.360292 +G1 X32.103200 Y74.694916 +G1 X31.335173 Y74.989383 +G1 X30.554724 Y75.243944 +G1 X29.765977 Y75.458854 +G1 X28.973058 Y75.634364 +G1 X28.180091 Y75.770727 +G1 X27.391202 Y75.868196 +G1 X26.610517 Y75.927024 +G1 X26.117474 Y75.944504 +G1 X25.054260 Y75.926112 +G1 X23.981542 Y75.831336 +G1 X22.904286 Y75.663050 +G1 X21.827460 Y75.424134 +G1 X20.756031 Y75.117463 +G1 X19.694968 Y74.745914 +G1 X18.649237 Y74.312365 +G1 X17.623805 Y73.819693 +G1 X16.623641 Y73.270774 +G1 X15.653712 Y72.668486 +G1 X14.718986 Y72.015705 +G1 X13.824429 Y71.315308 +G1 X12.975009 Y70.570174 +G1 X12.175694 Y69.783177 +G1 X11.738415 Y69.310250 +G1 X11.086228 Y68.523996 +G1 X10.486655 Y67.689872 +G1 X9.939299 Y66.813906 +G1 X9.443762 Y65.902128 +G1 X8.999647 Y64.960568 +G1 X8.606556 Y63.995255 +G1 X8.264093 Y63.012218 +G1 X7.971860 Y62.017488 +G1 X7.729458 Y61.017095 +G1 X7.536492 Y60.017066 +G1 X7.398267 Y59.070160 +G1 X7.335682 Y58.578944 +G1 X7.280181 Y58.153084 +G1 X7.233418 Y57.767460 +G1 X7.197047 Y57.396949 +G1 X7.172723 Y57.016430 +G1 X7.162099 Y56.600780 +G1 X7.164583 Y56.225692 +G1 X7.182392 Y55.832097 +G1 X7.214537 Y55.499240 +G1 X7.254199 Y55.196950 +G1 X7.294560 Y54.895056 +G1 X7.328800 Y54.563390 +G1 X7.343976 Y54.329377 +G1 X7.399542 Y53.625958 +G1 X7.495335 Y52.871883 +G1 X7.623287 Y52.095193 +G1 X7.775326 Y51.323932 +G1 X7.943384 Y50.586142 +G1 X8.052171 Y50.157495 +G1 X8.420406 Y48.903885 +G1 X8.858116 Y47.665336 +G1 X9.363958 Y46.448104 +G1 X9.936589 Y45.258447 +G1 X10.574665 Y44.102619 +G1 X11.276844 Y42.986878 +G1 X12.041781 Y41.917479 +G1 X12.790508 Y40.990777 +G1 X13.065832 Y40.675931 +G1 X14.048363 Y39.627353 +G1 X15.080210 Y38.627072 +G1 X16.158929 Y37.677557 +G1 X17.282074 Y36.781276 +G1 X18.447199 Y35.940696 +G1 X19.651860 Y35.158285 +G1 X20.893609 Y34.436512 +G1 X22.170003 Y33.777843 +G1 X23.478595 Y33.184748 +G1 X24.816941 Y32.659695 +G1 X26.117474 Y32.225008 +G1 X27.575647 Y31.812004 +G1 X29.054848 Y31.465527 +G1 X30.411933 Y31.217027 +G1 X31.775353 Y31.039912 +G1 X31.806411 Y31.036774 +G1 X32.291330 Y31.001179 +G1 X32.753972 Y30.970483 +G1 X32.944200 Y30.950674 +G1 X33.517347 Y30.879477 +G1 X34.073540 Y30.828377 +G1 X34.461250 Y30.816034 +G1 X34.826387 Y30.819417 +G1 X35.132035 Y30.833901 +G1 X35.405435 Y30.857668 +G1 X35.673829 Y30.888895 +G1 X35.964458 Y30.925762 +G1 X36.167931 Y30.950674 +G1 X36.637237 Y30.988830 +G1 X37.076444 Y31.007563 +G1 X37.495354 Y31.036984 +G1 X38.483844 Y31.167251 +G1 X39.485948 Y31.357560 +G1 X40.478839 Y31.594377 +G1 X41.287977 Y31.819027 +G1 X42.436421 Y32.192166 +G1 X43.556238 Y32.624832 +G1 X44.647501 Y33.114032 +G1 X45.710284 Y33.656775 +G1 X46.744660 Y34.250068 +G1 X47.750705 Y34.890919 +G1 X48.728490 Y35.576338 +G1 X49.678091 Y36.303331 +G1 X50.599581 Y37.068906 +G1 X51.493033 Y37.870072 +G1 X52.358523 Y38.703837 +G1 X53.196122 Y39.567208 +G1 X54.005906 Y40.457195 +G1 X54.787948 Y41.370803 +G1 X55.542321 Y42.305043 +G1 X56.269100 Y43.256921 +G1 X56.968358 Y44.223447 +G1 X57.401139 Y44.847835 +G1 X57.746820 Y45.379163 +G1 X58.109284 Y45.978464 +G1 X58.485646 Y46.633515 +G1 X58.873021 Y47.332093 +G1 X59.268524 Y48.061977 +G1 X59.669269 Y48.810942 +G1 X60.072372 Y49.566767 +G1 X60.515065 Y50.391509 +G1 X60.953281 Y51.193493 +G1 X61.383179 Y51.956451 +G1 X61.800919 Y52.664114 +G1 X62.166901 Y53.245772 +G1 X62.466403 Y53.685909 +G1 X62.456587 Y53.646755 +G1 X62.428386 Y53.534123 +G1 X62.383675 Y53.355260 +G1 X62.324326 Y53.117413 +G1 X62.252213 Y52.827829 +G1 X62.169209 Y52.493754 +G1 X62.077187 Y52.122436 +G1 X61.978020 Y51.721120 +G1 X61.873582 Y51.297053 +G1 X61.765746 Y50.857483 +G1 X61.656385 Y50.409656 +G1 X61.536562 Y49.916158 +G1 X61.408219 Y49.383411 +G1 X61.286721 Y48.873693 +G1 X61.175387 Y48.399842 +G1 X61.077536 Y47.974698 +G1 X60.996485 Y47.611097 +G1 X60.940174 Y47.344760 +G1 X60.933782 Y47.313039 +G1 X60.701283 Y46.100969 +G1 X60.475956 Y44.829444 +G1 X60.261335 Y43.521654 +G1 X60.060952 Y42.200788 +G1 X59.878340 Y40.890038 +G1 X59.717032 Y39.612594 +G1 X59.580562 Y38.391647 +G1 X59.524821 Y37.831475 +G1 X59.481584 Y37.131750 +G1 X59.469517 Y36.381289 +G1 X59.475883 Y35.615783 +G1 X59.487946 Y34.870925 +G1 X59.492791 Y34.418119 +G1 X59.507882 Y33.801667 +G1 X59.559517 Y33.197849 +G1 X59.573011 Y33.090693 +G1 X59.641158 Y32.517499 +G1 X59.692863 Y31.991438 +G1 X59.696461 Y31.952904 +G1 X59.823062 Y30.832531 +G1 X59.995472 Y29.674246 +G1 X60.208013 Y28.496814 +G1 X60.455005 Y27.319004 +G1 X60.730770 Y26.159580 +G1 X61.029628 Y25.037309 +G1 X61.281778 Y24.178028 +G1 X61.786097 Y22.667908 +G1 X62.365608 Y21.181660 +G1 X63.017875 Y19.722690 +G1 X63.740459 Y18.294404 +G1 X64.530920 Y16.900207 +G1 X65.386821 Y15.543506 +G1 X66.305724 Y14.227706 +G1 X67.285189 Y12.956214 +G1 X68.322779 Y11.732435 +G1 X69.416055 Y10.559775 +G1 X70.562578 Y9.441640 +G1 X71.759911 Y8.381436 +G1 X71.818636 Y8.332048 +G1 X72.863409 Y7.497311 +G1 X73.960708 Y6.701100 +G1 X75.104615 Y5.946837 +G1 X76.289210 Y5.237941 +G1 X77.508574 Y4.577835 +G1 X78.756789 Y3.969939 +G1 X80.027934 Y3.417674 +G1 X81.316092 Y2.924462 +G1 X82.615343 Y2.493724 +G1 X83.919769 Y2.128881 +G1 X85.223450 Y1.833353 +G1 X86.520467 Y1.610562 +G1 X87.804901 Y1.463929 +G1 X88.126929 Y1.439326 +G1 X88.455675 Y1.423386 +G1 X88.728550 Y1.420377 +G1 X88.982180 Y1.420984 +G1 X89.282654 Y1.414710 +G1 X89.454347 Y1.405226 +G1 X89.823390 Y1.367003 +G1 X90.143194 Y1.321265 +G1 X90.467357 Y1.287239 +G1 X90.781767 Y1.281766 +G1 X91.113331 Y1.305765 +G1 X91.410055 Y1.347052 +G1 X91.733134 Y1.389219 +G1 X91.919557 Y1.405226 +G1 X92.284034 Y1.420981 +G1 X92.601821 Y1.421812 +G1 X92.927606 Y1.421293 +G1 X93.246977 Y1.429726 +G1 X93.932703 Y1.482732 +G1 X94.665333 Y1.579446 +G1 X95.429165 Y1.713141 +G1 X96.208497 Y1.877090 +G1 X96.987627 Y2.064567 +G1 X97.750854 Y2.268844 +G1 X98.482475 Y2.483196 +G1 X99.166788 Y2.700895 +G1 X99.315168 Y2.750506 +G1 X100.574440 Y3.215148 +G1 X101.814730 Y3.751376 +G1 X103.031503 Y4.355608 +G1 X104.220226 Y5.024259 +G1 X105.376363 Y5.753747 +G1 X106.495380 Y6.540487 +G1 X107.572742 Y7.380897 +G1 X108.603914 Y8.271392 +G1 X109.584363 Y9.208389 +G1 X110.471000 Y10.145370 +G1 X111.340142 Y11.169395 +G1 X112.142428 Y12.234060 +G1 X112.877405 Y13.336215 +G1 X113.544624 Y14.472711 +G1 X114.143632 Y15.640399 +G1 X114.673980 Y16.836129 +G1 X115.135215 Y18.056752 +G1 X115.526886 Y19.299119 +G1 X115.848544 Y20.560080 +G1 X116.099736 Y21.836486 +G1 X116.280011 Y23.125188 +G1 X116.388918 Y24.423036 +G1 X116.426007 Y25.726882 +G1 X116.390826 Y27.033575 +G1 X116.282923 Y28.339966 +G1 X116.101849 Y29.642907 +G1 X115.847152 Y30.939247 +G1 X115.645470 Y31.763340 +G1 X115.304711 Y32.913230 +G1 X114.897960 Y34.035180 +G1 X114.427610 Y35.127122 +G1 X113.896054 Y36.186989 +G1 X113.305684 Y37.212711 +G1 X112.658892 Y38.202220 +G1 X111.958072 Y39.153449 +G1 X111.205614 Y40.064329 +G1 X110.403912 Y40.932792 +G1 X109.555359 Y41.756769 +G1 X108.662346 Y42.534193 +G1 X107.727266 Y43.262995 +G1 X106.752512 Y43.941107 +G1 X105.740475 Y44.566461 +G1 X104.693549 Y45.136988 +G1 X103.614126 Y45.650620 +G1 X102.504598 Y46.105289 +G1 X101.780380 Y46.364185 +G1 X100.758137 Y46.671334 +G1 X99.723437 Y46.911488 +G1 X98.679512 Y47.090166 +G1 X97.629591 Y47.212886 +G1 X96.576904 Y47.285165 +G1 X95.524682 Y47.312522 +G1 X95.332917 Y47.313101 +G1 X94.831919 Y47.313690 +G1 X94.372935 Y47.304593 +G1 X93.902240 Y47.268977 +G1 X93.815867 Y47.258911 +G1 X93.153592 Y47.160876 +G1 X92.448188 Y47.026583 +G1 X91.728817 Y46.863171 +G1 X91.024640 Y46.677781 +G1 X90.592127 Y46.549879 +G1 X89.480245 Y46.168269 +G1 X88.394817 Y45.715911 +G1 X87.438307 Y45.239279 +G1 X86.517320 Y44.696672 +G1 X85.716357 Y44.143134 +G1 X84.955013 Y43.529431 +G1 X84.335064 Y42.950872 +G1 X83.899531 Y42.494978 +G1 X83.450746 Y41.979242 +G1 X83.013195 Y41.419549 +G1 X82.611364 Y40.831785 +G1 X82.269739 Y40.231836 +G1 X82.032020 Y39.689222 +G1 X81.901466 Y39.251575 +G1 X81.841667 Y38.830906 +G1 X81.857443 Y38.468882 +G1 X81.869099 Y38.400479 +G1 X82.365924 Y38.673931 +G1 X82.926568 Y38.974839 +G1 X83.536276 Y39.289182 +G1 X84.180294 Y39.602941 +G1 X84.843865 Y39.902094 +G1 X85.512236 Y40.172621 +G1 X86.040988 Y40.359177 +G1 X86.973196 Y40.626036 +G1 X87.915686 Y40.818949 +G1 X88.779551 Y40.925288 +G1 X89.648412 Y40.961391 +G1 X90.520602 Y40.922911 +G1 X91.314987 Y40.819553 +G1 X91.919557 Y40.695202 +G1 X92.721802 Y40.467990 +G1 X93.504986 Y40.175301 +G1 X94.261644 Y39.819508 +G1 X94.984317 Y39.402987 +G1 X95.665540 Y38.928110 +G1 X96.297853 Y38.397253 +G1 X96.873793 Y37.812789 +G1 X97.342177 Y37.236937 +G1 X97.752199 Y36.620529 +G1 X98.098251 Y35.965348 +G1 X98.352616 Y35.337583 +G1 X98.545269 Y34.680588 +G1 X98.671997 Y33.995704 +G1 X98.728589 Y33.284271 +G1 X98.731297 Y33.090798 +G1 X98.696841 Y32.363334 +G1 X98.595709 Y31.636148 +G1 X98.431742 Y30.914533 +G1 X98.208784 Y30.203785 +G1 X97.930677 Y29.509197 +G1 X97.601263 Y28.836061 +G1 X97.224384 Y28.189674 +G1 X96.803882 Y27.575327 +G1 X96.343600 Y26.998315 +G1 X95.869387 Y26.485943 +G1 X95.161077 Y25.826206 +G1 X94.398679 Y25.212258 +G1 X93.589536 Y24.648067 +G1 X92.740991 Y24.137600 +G1 X91.860387 Y23.684823 +G1 X90.955066 Y23.293705 +G1 X90.032370 Y22.968212 +G1 X89.099644 Y22.712311 +G1 X88.885447 Y22.663927 +G1 X88.105993 Y22.524269 +G1 X87.368404 Y22.420057 +G1 X86.873390 Y22.356541 +G1 X86.420341 Y22.314872 +G1 X85.964847 Y22.291302 +G1 X85.462496 Y22.282087 +G1 X85.092831 Y22.282006 +G1 X84.648236 Y22.291543 +G1 X84.257348 Y22.315608 +G1 X83.881546 Y22.353988 +G1 X83.482207 Y22.406468 +G1 X83.386149 Y22.420057 +G1 X82.405351 Y22.580783 +G1 X81.383229 Y22.792102 +G1 X80.349669 Y23.054226 +G1 X79.334559 Y23.367369 +G1 X78.452890 Y23.696496 +G1 X78.266104 Y23.774777 +G1 X77.226007 Y24.258879 +G1 X76.221678 Y24.803883 +G1 X75.255237 Y25.407105 +G1 X74.328802 Y26.065860 +G1 X73.444493 Y26.777462 +G1 X72.604429 Y27.539229 +G1 X71.810730 Y28.348475 +G1 X71.065515 Y29.202515 +G1 X70.370904 Y30.098665 +G1 X69.729016 Y31.034241 +G1 X69.141970 Y32.006557 +G1 X68.611886 Y33.012929 +G1 X68.140883 Y34.050673 +G1 X67.731080 Y35.117105 +G1 X67.522922 Y35.745638 +G1 X67.202063 Y36.889121 +G1 X66.949231 Y38.040767 +G1 X66.763111 Y39.198251 +G1 X66.642390 Y40.359247 +G1 X66.585752 Y41.521428 +G1 X66.591883 Y42.682470 +G1 X66.659468 Y43.840046 +G1 X66.787192 Y44.991831 +G1 X66.973740 Y46.135498 +G1 X67.217798 Y47.268722 +G1 X67.518051 Y48.389177 +G1 X67.873185 Y49.494537 +G1 X68.281884 Y50.582477 +G1 X68.742834 Y51.650670 +G1 X69.254720 Y52.696790 +G1 X69.816228 Y53.718512 +G1 X70.426042 Y54.713510 +G1 X71.082849 Y55.679458 +G1 X71.785333 Y56.614031 +G1 X72.532179 Y57.514902 +G1 X73.322074 Y58.379745 +G1 X74.153701 Y59.206235 +G1 X75.025748 Y59.992046 +G1 X75.936898 Y60.734851 +G1 X76.885837 Y61.432326 +G1 X77.697212 Y61.972595 +G1 X78.772571 Y62.615820 +G1 X79.887261 Y63.205169 +G1 X81.035073 Y63.739607 +G1 X82.209796 Y64.218099 +G1 X83.405221 Y64.639609 +G1 X84.615137 Y65.003103 +G1 X85.833334 Y65.307544 +G1 X86.420247 Y65.432610 +G1 X87.662328 Y65.641177 +G1 X88.924816 Y65.780307 +G1 X90.197303 Y65.861668 +G1 X91.469386 Y65.896929 +G1 X92.730657 Y65.897759 +G1 X92.867707 Y65.896256 +G1 X93.938087 Y65.848909 +G1 X95.013331 Y65.734013 +G1 X96.089398 Y65.554247 +G1 X97.162249 Y65.312288 +G1 X98.227845 Y65.010814 +G1 X99.282145 Y64.652502 +G1 X100.321110 Y64.240030 +G1 X101.340700 Y63.776076 +G1 X102.336876 Y63.263317 +G1 X103.305597 Y62.704431 +G1 X104.242825 Y62.102095 +G1 X105.144520 Y61.458988 +G1 X106.006641 Y60.777787 +G1 X106.825150 Y60.061170 +G1 X107.276850 Y59.631790 +G1 X108.082537 Y58.794085 +G1 X108.841909 Y57.910930 +G1 X109.556655 Y56.988436 +G1 X110.228463 Y56.032713 +G1 X110.859022 Y55.049871 +G1 X111.450022 Y54.046021 +G1 X112.003151 Y53.027273 +G1 X112.520098 Y51.999738 +G1 X113.002553 Y50.969525 +G1 X113.026660 Y50.916148 +G1 X113.600765 Y49.550104 +G1 X114.133465 Y48.148717 +G1 X114.654261 Y46.733406 +G1 X115.248592 Y45.186046 +G1 X115.840405 Y43.811218 +G1 X116.388252 Y42.713669 +G1 X116.571640 Y42.382736 +G1 X115.460301 Y45.822561 +G1 X114.581323 Y48.712939 +G1 X113.981039 Y50.905737 +G1 X113.502475 Y52.910643 +G1 X113.138541 Y54.739721 +G1 X112.878215 Y56.405563 +G1 X112.708660 Y57.920769 +G1 X112.610884 Y59.435216 +G1 X112.589520 Y60.397712 +G1 X112.546530 Y63.169352 +G1 X112.577974 Y64.332007 +G1 X112.669820 Y65.328131 +G1 X113.013728 Y67.654485 +G1 X113.398668 Y69.746634 +G1 X113.818303 Y71.626161 +G1 X114.264853 Y73.313544 +G1 X114.780029 Y74.978217 +G1 X115.313348 Y76.469857 +G1 X115.913554 Y77.938992 +G1 X116.585492 Y79.383844 +G1 X117.262666 Y80.674777 +G1 X118.006765 Y81.942835 +G1 X118.821427 Y83.186682 +G1 X118.930300 Y83.343102 +G1 X119.845693 Y84.584198 +G1 X120.818782 Y85.778305 +G1 X121.847037 Y86.923126 +G1 X122.927928 Y88.016366 +G1 X124.058922 Y89.055725 +G1 X125.237490 Y90.038907 +G1 X126.461101 Y90.963615 +G1 X127.727224 Y91.827552 +G1 X129.033328 Y92.628420 +G1 X130.376883 Y93.363922 +G1 X131.755358 Y94.031762 +G1 X133.166222 Y94.629641 +G1 X134.606944 Y95.155263 +G1 X135.940473 Y95.568466 +G1 X137.294685 Y95.918328 +G1 X138.667679 Y96.203123 +G1 X139.137740 Y96.284709 +G1 X140.039406 Y96.427766 +G1 X140.893217 Y96.545947 +G1 X141.034050 Y96.563156 +G1 X141.922176 Y96.629199 +G1 X142.845706 Y96.639706 +G1 X143.804845 Y96.625583 +G1 X144.637050 Y96.617294 +G1 X145.173660 Y96.620046 +G1 X145.653744 Y96.619248 +G1 X146.120519 Y96.601319 +G1 X146.533360 Y96.563155 +G1 X147.442642 Y96.440345 +G1 X148.400622 Y96.281276 +G1 X149.369855 Y96.086976 +G1 X150.312897 Y95.858474 +G1 X150.515620 Y95.803020 +G1 X151.869766 Y95.389583 +G1 X153.202986 Y94.912963 +G1 X154.511473 Y94.373643 +G1 X155.791418 Y93.772102 +G1 X157.039011 Y93.108823 +G1 X158.250445 Y92.384287 +G1 X159.421911 Y91.598975 +G1 X160.549599 Y90.753369 +G1 X161.629702 Y89.847949 +G1 X162.658410 Y88.883198 +G1 X163.545796 Y87.955069 +G1 X164.384698 Y86.978666 +G1 X165.172255 Y85.954348 +G1 X165.905604 Y84.882479 +G1 X166.581885 Y83.763419 +G1 X166.605070 Y83.722365 +G1 X167.173326 Y82.644472 +G1 X167.679968 Y81.539452 +G1 X168.124939 Y80.410473 +G1 X168.508181 Y79.260701 +G1 X168.829638 Y78.093303 +G1 X169.089254 Y76.911446 +G1 X169.286970 Y75.718297 +G1 X169.422731 Y74.517023 +G1 X169.496479 Y73.310790 +G1 X169.508158 Y72.102766 +G1 X169.457710 Y70.896116 +G1 X169.345079 Y69.694008 +G1 X169.170208 Y68.499609 +G1 X168.933040 Y67.316086 +G1 X168.633518 Y66.146605 +G1 X168.271585 Y64.994333 +G1 X167.847184 Y63.862437 +G1 X167.360259 Y62.754083 +G1 X166.810752 Y61.672440 +G1 X166.198607 Y60.620672 +G1 X165.523767 Y59.601948 +G1 X165.277270 Y59.259924 +G1 X164.480036 Y58.244700 +G1 X163.621379 Y57.279682 +G1 X162.705244 Y56.367826 +G1 X161.735576 Y55.512091 +G1 X160.716319 Y54.715434 +G1 X159.651421 Y53.980812 +G1 X158.544825 Y53.311184 +G1 X157.400478 Y52.709505 +G1 X156.222323 Y52.178735 +G1 X155.066770 Y51.739902 +G1 X153.902131 Y51.368996 +G1 X152.692356 Y51.056062 +G1 X151.687696 Y50.861426 +G1 X150.894880 Y50.758754 +G1 X150.496180 Y50.728318 +G1 X150.147057 Y50.716643 +G1 X149.812623 Y50.716960 +G1 X149.457994 Y50.722496 +G1 X149.048285 Y50.726481 +G1 X148.998570 Y50.726534 +G1 X148.592183 Y50.723950 +G1 X148.249388 Y50.718535 +G1 X147.943669 Y50.713799 +G1 X147.648512 Y50.713251 +G1 X147.304393 Y50.721671 +G1 X146.912620 Y50.743584 +G1 X146.327370 Y50.806223 +G1 X145.703083 Y50.910554 +G1 X145.059955 Y51.048456 +G1 X144.418184 Y51.211810 +G1 X143.797967 Y51.392494 +G1 X143.219499 Y51.582388 +G1 X143.120000 Y51.617407 +G1 X142.092715 Y52.019897 +G1 X141.094183 Y52.487792 +G1 X140.130248 Y53.021879 +G1 X139.288883 Y53.565515 +G1 X138.485330 Y54.165097 +G1 X137.811080 Y54.741197 +G1 X137.302243 Y55.248638 +G1 X136.815484 Y55.815674 +G1 X136.355759 Y56.425298 +G1 X135.928022 Y57.060503 +G1 X135.537229 Y57.704284 +G1 X135.188337 Y58.339633 +G1 X134.886300 Y58.949544 +G1 X134.636073 Y59.517011 +G1 X134.586590 Y59.639186 +G1 X135.592772 Y59.116971 +G1 X136.659682 Y58.600749 +G1 X137.772519 Y58.115950 +G1 X138.916484 Y57.688003 +G1 X139.971008 Y57.369694 +G1 X140.932019 Y57.155410 +G1 X141.800337 Y57.035157 +G1 X142.579851 Y56.996834 +G1 X142.930350 Y57.004075 +G1 X143.837392 Y57.083931 +G1 X144.735871 Y57.242412 +G1 X145.617294 Y57.478011 +G1 X146.396642 Y57.757843 +G1 X147.148496 Y58.099031 +G1 X147.866475 Y58.500441 +G1 X148.544200 Y58.960941 +G1 X149.175289 Y59.479399 +G1 X149.753362 Y60.054681 +G1 X150.227509 Y60.626024 +G1 X150.647775 Y61.242542 +G1 X151.009365 Y61.903384 +G1 X151.307487 Y62.607701 +G1 X151.395490 Y62.862916 +G1 X151.595329 Y63.575626 +G1 X151.710071 Y64.209357 +G1 X151.756915 Y64.846184 +G1 X151.745550 Y65.328130 +G1 X151.678762 Y66.078108 +G1 X151.570807 Y66.781351 +G1 X151.409454 Y67.461715 +G1 X151.182474 Y68.143060 +G1 X150.908890 Y68.783391 +G1 X150.643980 Y69.310386 +G1 X150.227077 Y70.017800 +G1 X149.756498 Y70.682782 +G1 X149.236368 Y71.305585 +G1 X148.670812 Y71.886462 +G1 X148.063956 Y72.425665 +G1 X147.419925 Y72.923446 +G1 X146.742845 Y73.380060 +G1 X146.036840 Y73.795757 +G1 X145.306035 Y74.170792 +G1 X144.554558 Y74.505416 +G1 X143.786531 Y74.799883 +G1 X143.006082 Y75.054444 +G1 X142.217334 Y75.269354 +G1 X141.424415 Y75.444864 +G1 X140.631447 Y75.581227 +G1 X139.842559 Y75.678696 +G1 X139.061873 Y75.737524 +G1 X138.568830 Y75.755004 +G1 X137.505617 Y75.736612 +G1 X136.432899 Y75.641836 +G1 X135.355643 Y75.473550 +G1 X134.278818 Y75.234634 +G1 X133.207389 Y74.927963 +G1 X132.146326 Y74.556414 +G1 X131.100594 Y74.122865 +G1 X130.075163 Y73.630193 +G1 X129.074999 Y73.081274 +G1 X128.105070 Y72.478986 +G1 X127.170342 Y71.826205 +G1 X126.275785 Y71.125808 +G1 X125.426365 Y70.380674 +G1 X124.627049 Y69.593677 +G1 X124.189770 Y69.120750 +G1 X123.537585 Y68.334496 +G1 X122.938013 Y67.500372 +G1 X122.390658 Y66.624406 +G1 X121.895121 Y65.712628 +G1 X121.451007 Y64.771068 +G1 X121.057917 Y63.805755 +G1 X120.715454 Y62.822718 +G1 X120.423221 Y61.827988 +G1 X120.180820 Y60.827595 +G1 X119.987854 Y59.827566 +G1 X119.849630 Y58.880660 +G1 X119.787043 Y58.389444 +G1 X119.731541 Y57.963584 +G1 X119.684777 Y57.577960 +G1 X119.648405 Y57.207449 +G1 X119.624080 Y56.826930 +G1 X119.613456 Y56.411280 +G1 X119.615940 Y56.036192 +G1 X119.633757 Y55.642597 +G1 X119.665903 Y55.309740 +G1 X119.705562 Y55.007450 +G1 X119.745918 Y54.705556 +G1 X119.780156 Y54.373890 +G1 X119.795330 Y54.139877 +G1 X119.850904 Y53.436458 +G1 X119.946700 Y52.682383 +G1 X120.074651 Y51.905693 +G1 X120.226688 Y51.134432 +G1 X120.394744 Y50.396642 +G1 X120.503530 Y49.967995 +G1 X120.871765 Y48.714385 +G1 X121.309475 Y47.475836 +G1 X121.815316 Y46.258604 +G1 X122.387946 Y45.068947 +G1 X123.026022 Y43.913119 +G1 X123.728200 Y42.797378 +G1 X124.493138 Y41.727979 +G1 X125.241866 Y40.801277 +G1 X125.517190 Y40.486431 +G1 X126.499720 Y39.437853 +G1 X127.531567 Y38.437572 +G1 X128.610286 Y37.488057 +G1 X129.733431 Y36.591776 +G1 X130.898557 Y35.751196 +G1 X132.103217 Y34.968785 +G1 X133.344967 Y34.247012 +G1 X134.621361 Y33.588343 +G1 X135.929953 Y32.995248 +G1 X137.268298 Y32.470195 +G1 X138.568830 Y32.035508 +G1 X140.027007 Y31.622504 +G1 X141.506210 Y31.276027 +G1 X142.863294 Y31.027527 +G1 X144.226712 Y30.850412 +G1 X144.257770 Y30.847274 +G1 X144.742688 Y30.811679 +G1 X145.205330 Y30.780983 +G1 X145.395560 Y30.761174 +G1 X145.968705 Y30.689977 +G1 X146.524900 Y30.638877 +G1 X146.912610 Y30.626534 +G1 X147.277747 Y30.629917 +G1 X147.583395 Y30.644401 +G1 X147.856795 Y30.668168 +G1 X148.125189 Y30.699395 +G1 X148.415818 Y30.736262 +G1 X148.619290 Y30.761174 +G1 X149.088595 Y30.799330 +G1 X149.527803 Y30.818063 +G1 X149.946710 Y30.847484 +G1 X150.935201 Y30.977751 +G1 X151.937306 Y31.168060 +G1 X152.930199 Y31.404877 +G1 X153.739340 Y31.629527 +G1 X154.887783 Y32.002666 +G1 X156.007599 Y32.435332 +G1 X157.098861 Y32.924532 +G1 X158.161643 Y33.467275 +G1 X159.196019 Y34.060568 +G1 X160.202062 Y34.701419 +G1 X161.179847 Y35.386838 +G1 X162.129448 Y36.113831 +G1 X163.050938 Y36.879406 +G1 X163.944390 Y37.680572 +G1 X164.809879 Y38.514337 +G1 X165.647479 Y39.377708 +G1 X166.457263 Y40.267695 +G1 X167.239305 Y41.181303 +G1 X167.993679 Y42.115543 +G1 X168.720459 Y43.067421 +G1 X169.419719 Y44.033947 +G1 X169.852500 Y44.658335 +G1 X170.198180 Y45.189663 +G1 X170.560643 Y45.788964 +G1 X170.937005 Y46.444015 +G1 X171.324379 Y47.142593 +G1 X171.719881 Y47.872477 +G1 X172.120626 Y48.621442 +G1 X172.523729 Y49.377267 +G1 X172.966422 Y50.202009 +G1 X173.404638 Y51.003993 +G1 X173.834536 Y51.766951 +G1 X174.252276 Y52.474614 +G1 X174.618258 Y53.056272 +G1 X174.917760 Y53.496409 +G1 X174.907944 Y53.457255 +G1 X174.879743 Y53.344623 +G1 X174.835032 Y53.165760 +G1 X174.775683 Y52.927913 +G1 X174.703570 Y52.638329 +G1 X174.620566 Y52.304254 +G1 X174.528544 Y51.932936 +G1 X174.429377 Y51.531620 +G1 X174.324939 Y51.107553 +G1 X174.217103 Y50.667983 +G1 X174.107742 Y50.220156 +G1 X173.987919 Y49.726658 +G1 X173.859576 Y49.193911 +G1 X173.738078 Y48.684193 +G1 X173.626745 Y48.210342 +G1 X173.528893 Y47.785198 +G1 X173.447843 Y47.421597 +G1 X173.391532 Y47.155260 +G1 X173.385140 Y47.123539 +G1 X173.152641 Y45.911469 +G1 X172.927314 Y44.639944 +G1 X172.712692 Y43.332154 +G1 X172.512309 Y42.011288 +G1 X172.329697 Y40.700538 +G1 X172.168389 Y39.423094 +G1 X172.031920 Y38.202147 +G1 X171.976180 Y37.641975 +G1 X171.932925 Y36.942250 +G1 X171.920861 Y36.191789 +G1 X171.927242 Y35.426283 +G1 X171.939325 Y34.681425 +G1 X171.944180 Y34.228619 +G1 X171.959196 Y33.612167 +G1 X172.010891 Y33.008349 +G1 X172.024380 Y32.901193 +G1 X172.092553 Y32.327999 +G1 X172.144235 Y31.801938 +G1 X172.147830 Y31.763404 +G1 X172.274431 Y30.643031 +G1 X172.446841 Y29.484746 +G1 X172.659383 Y28.307314 +G1 X172.906375 Y27.129504 +G1 X173.182141 Y25.970080 +G1 X173.480999 Y24.847809 +G1 X173.733150 Y23.988528 +G1 X174.237468 Y22.478408 +G1 X174.816979 Y20.992160 +G1 X175.469245 Y19.533190 +G1 X176.191827 Y18.104904 +G1 X176.982288 Y16.710707 +G1 X177.838188 Y15.354006 +G1 X178.757090 Y14.038206 +G1 X179.736555 Y12.766714 +G1 X180.774144 Y11.542935 +G1 X181.867419 Y10.370275 +G1 X183.013942 Y9.252140 +G1 X184.211275 Y8.191936 +G1 X184.270000 Y8.142548 +G1 X185.314773 Y7.307811 +G1 X186.412073 Y6.511600 +G1 X187.555980 Y5.757337 +G1 X188.740575 Y5.048441 +G1 X189.959940 Y4.388335 +G1 X191.208155 Y3.780439 +G1 X192.479301 Y3.228174 +G1 X193.767459 Y2.734962 +G1 X195.066711 Y2.304224 +G1 X196.371137 Y1.939381 +G1 X197.674819 Y1.643853 +G1 X198.971837 Y1.421062 +G1 X200.256272 Y1.274429 +G1 X200.578300 Y1.249826 +G1 X200.907047 Y1.233886 +G1 X201.179923 Y1.230877 +G1 X201.433552 Y1.231484 +G1 X201.734027 Y1.225210 +G1 X201.905720 Y1.215726 +G1 X202.274763 Y1.177503 +G1 X202.594567 Y1.131765 +G1 X202.918730 Y1.097739 +G1 X203.233140 Y1.092266 +G1 X203.564704 Y1.116265 +G1 X203.861428 Y1.157552 +G1 X204.184507 Y1.199719 +G1 X204.370930 Y1.215726 +G1 X204.735407 Y1.231481 +G1 X205.053194 Y1.232312 +G1 X205.378979 Y1.231793 +G1 X205.698350 Y1.240226 +G1 X206.384076 Y1.293232 +G1 X207.116706 Y1.389946 +G1 X207.880538 Y1.523641 +G1 X208.659870 Y1.687590 +G1 X209.439000 Y1.875067 +G1 X210.202226 Y2.079344 +G1 X210.933847 Y2.293696 +G1 X211.618160 Y2.511395 +G1 X211.766540 Y2.561006 +G1 X213.025811 Y3.025648 +G1 X214.266101 Y3.561876 +G1 X215.482874 Y4.166108 +G1 X216.671597 Y4.834759 +G1 X217.827733 Y5.564247 +G1 X218.946750 Y6.350987 +G1 X220.024112 Y7.191397 +G1 X221.055284 Y8.081892 +G1 X222.035733 Y9.018889 +G1 X222.922370 Y9.955870 +G1 X223.791512 Y10.979895 +G1 X224.593798 Y12.044560 +G1 X225.328775 Y13.146715 +G1 X225.995994 Y14.283211 +G1 X226.595002 Y15.450899 +G1 X227.125350 Y16.646629 +G1 X227.586585 Y17.867252 +G1 X227.978256 Y19.109619 +G1 X228.299914 Y20.370580 +G1 X228.551106 Y21.646986 +G1 X228.731381 Y22.935688 +G1 X228.840288 Y24.233536 +G1 X228.877377 Y25.537382 +G1 X228.842196 Y26.844075 +G1 X228.734293 Y28.150466 +G1 X228.553219 Y29.453407 +G1 X228.298522 Y30.749747 +G1 X228.096840 Y31.573840 +G1 X227.756081 Y32.723730 +G1 X227.349330 Y33.845680 +G1 X226.878980 Y34.937622 +G1 X226.347424 Y35.997489 +G1 X225.757054 Y37.023211 +G1 X225.110262 Y38.012720 +G1 X224.409442 Y38.963949 +G1 X223.656984 Y39.874829 +G1 X222.855282 Y40.743292 +G1 X222.006729 Y41.567269 +G1 X221.113716 Y42.344693 +G1 X220.178636 Y43.073495 +G1 X219.203882 Y43.751607 +G1 X218.191845 Y44.376961 +G1 X217.144919 Y44.947488 +G1 X216.065496 Y45.461120 +G1 X214.955968 Y45.915789 +G1 X214.231750 Y46.174685 +G1 X213.209507 Y46.481834 +G1 X212.174809 Y46.721988 +G1 X211.130884 Y46.900666 +G1 X210.080964 Y47.023386 +G1 X209.028277 Y47.095665 +G1 X207.976055 Y47.123022 +G1 X207.784290 Y47.123601 +G1 X207.283292 Y47.124190 +G1 X206.824308 Y47.115093 +G1 X206.353613 Y47.079477 +G1 X206.267240 Y47.069411 +G1 X205.604965 Y46.971376 +G1 X204.899561 Y46.837083 +G1 X204.180190 Y46.673671 +G1 X203.476013 Y46.488281 +G1 X203.043500 Y46.360379 +G1 X201.931614 Y45.978769 +G1 X200.846185 Y45.526411 +G1 X199.889675 Y45.049779 +G1 X198.968687 Y44.507172 +G1 X198.167724 Y43.953634 +G1 X197.406380 Y43.339931 +G1 X196.786430 Y42.761372 +G1 X196.350896 Y42.305478 +G1 X195.902111 Y41.789742 +G1 X195.464561 Y41.230049 +G1 X195.062731 Y40.642285 +G1 X194.721107 Y40.042336 +G1 X194.483389 Y39.499722 +G1 X194.352836 Y39.062075 +G1 X194.293038 Y38.641406 +G1 X194.308814 Y38.279382 +G1 X194.320470 Y38.210979 +G1 X194.817295 Y38.484431 +G1 X195.377939 Y38.785339 +G1 X195.987648 Y39.099682 +G1 X196.631666 Y39.413441 +G1 X197.295237 Y39.712594 +G1 X197.963608 Y39.983121 +G1 X198.492360 Y40.169677 +G1 X199.424566 Y40.436536 +G1 X200.367056 Y40.629449 +G1 X201.230921 Y40.735788 +G1 X202.099783 Y40.771891 +G1 X202.971974 Y40.733411 +G1 X203.766360 Y40.630053 +G1 X204.370930 Y40.505702 +G1 X205.173175 Y40.278490 +G1 X205.956359 Y39.985801 +G1 X206.713017 Y39.630008 +G1 X207.435690 Y39.213487 +G1 X208.116913 Y38.738610 +G1 X208.749226 Y38.207753 +G1 X209.325166 Y37.623289 +G1 X209.793550 Y37.047437 +G1 X210.203572 Y36.431029 +G1 X210.549624 Y35.775848 +G1 X210.803989 Y35.148083 +G1 X210.996642 Y34.491088 +G1 X211.123370 Y33.806204 +G1 X211.179962 Y33.094771 +G1 X211.182670 Y32.901298 +G1 X211.148214 Y32.173834 +G1 X211.047082 Y31.446648 +G1 X210.883115 Y30.725033 +G1 X210.660157 Y30.014285 +G1 X210.382050 Y29.319697 +G1 X210.052636 Y28.646561 +G1 X209.675757 Y28.000174 +G1 X209.255255 Y27.385827 +G1 X208.794973 Y26.808815 +G1 X208.320760 Y26.296443 +G1 X207.612450 Y25.636706 +G1 X206.850052 Y25.022758 +G1 X206.040909 Y24.458567 +G1 X205.192364 Y23.948100 +G1 X204.311760 Y23.495323 +G1 X203.406439 Y23.104205 +G1 X202.483743 Y22.778712 +G1 X201.551017 Y22.522811 +G1 X201.336820 Y22.474427 +G1 X200.557364 Y22.334769 +G1 X199.819770 Y22.230557 +G1 X199.324756 Y22.167041 +G1 X198.871708 Y22.125372 +G1 X198.416214 Y22.101802 +G1 X197.913864 Y22.092587 +G1 X197.544200 Y22.092506 +G1 X197.099604 Y22.102043 +G1 X196.708717 Y22.126108 +G1 X196.332916 Y22.164488 +G1 X195.933578 Y22.216968 +G1 X195.837520 Y22.230557 +G1 X194.856719 Y22.391283 +G1 X193.834596 Y22.602602 +G1 X192.801035 Y22.864726 +G1 X191.785925 Y23.177869 +G1 X190.904256 Y23.506996 +G1 X190.717470 Y23.585277 +G1 X189.677374 Y24.069379 +G1 X188.673045 Y24.614383 +G1 X187.706603 Y25.217605 +G1 X186.780169 Y25.876360 +G1 X185.895860 Y26.587962 +G1 X185.055796 Y27.349729 +G1 X184.262097 Y28.158975 +G1 X183.516882 Y29.013015 +G1 X182.822271 Y29.909165 +G1 X182.180383 Y30.844741 +G1 X181.593337 Y31.817057 +G1 X181.063253 Y32.823429 +G1 X180.592250 Y33.861173 +G1 X180.182448 Y34.927605 +G1 X179.974290 Y35.556138 +G1 X179.653430 Y36.699621 +G1 X179.400598 Y37.851267 +G1 X179.214478 Y39.008751 +G1 X179.093757 Y40.169747 +G1 X179.037119 Y41.331928 +G1 X179.043250 Y42.492970 +G1 X179.110835 Y43.650546 +G1 X179.238559 Y44.802331 +G1 X179.425107 Y45.945998 +G1 X179.669166 Y47.079222 +G1 X179.969419 Y48.199677 +G1 X180.324553 Y49.305037 +G1 X180.733252 Y50.392977 +G1 X181.194203 Y51.461170 +G1 X181.706089 Y52.507290 +G1 X182.267597 Y53.529012 +G1 X182.877412 Y54.524010 +G1 X183.534218 Y55.489958 +G1 X184.236702 Y56.424531 +G1 X184.983549 Y57.325402 +G1 X185.773443 Y58.190245 +G1 X186.605071 Y59.016735 +G1 X187.477117 Y59.802546 +G1 X188.388266 Y60.545351 +G1 X189.337205 Y61.242826 +G1 X190.148580 Y61.783095 +G1 X191.223940 Y62.426320 +G1 X192.338631 Y63.015669 +G1 X193.486444 Y63.550107 +G1 X194.661168 Y64.028599 +G1 X195.856593 Y64.450109 +G1 X197.066510 Y64.813603 +G1 X198.284707 Y65.118044 +G1 X198.871620 Y65.243110 +G1 X200.113701 Y65.451677 +G1 X201.376189 Y65.590807 +G1 X202.648676 Y65.672168 +G1 X203.920759 Y65.707429 +G1 X205.182030 Y65.708259 +G1 X205.319080 Y65.706756 +G1 X206.389460 Y65.659409 +G1 X207.464704 Y65.544513 +G1 X208.540771 Y65.364747 +G1 X209.613622 Y65.122788 +G1 X210.679217 Y64.821314 +G1 X211.733517 Y64.463002 +G1 X212.772481 Y64.050530 +G1 X213.792071 Y63.586576 +G1 X214.788247 Y63.073817 +G1 X215.756968 Y62.514931 +G1 X216.694196 Y61.912595 +G1 X217.595890 Y61.269488 +G1 X218.458011 Y60.588287 +G1 X219.276520 Y59.871670 +G1 X219.728220 Y59.442290 +G1 X220.533907 Y58.604585 +G1 X221.293279 Y57.721430 +G1 X222.008025 Y56.798936 +G1 X222.679833 Y55.843213 +G1 X223.310392 Y54.860371 +G1 X223.901392 Y53.856521 +G1 X224.454521 Y52.837773 +G1 X224.971468 Y51.810238 +G1 X225.453923 Y50.780025 +G1 X225.478030 Y50.726648 +G1 X226.052135 Y49.360604 +G1 X226.584835 Y47.959217 +G1 X227.105631 Y46.543906 +G1 X227.699962 Y44.996546 +G1 X228.291775 Y43.621718 +G1 X228.839622 Y42.524169 +G1 X229.023010 Y42.193236 +G1 X227.911671 Y45.633061 +G1 X227.032693 Y48.523439 +G1 X226.432409 Y50.716237 +G1 X225.953845 Y52.721143 +G1 X225.589911 Y54.550221 +G1 X225.329585 Y56.216063 +G1 X225.160030 Y57.731269 +G1 X225.062254 Y59.245716 +G1 X225.040890 Y60.208212 +G1 X224.997900 Y62.979852 +G1 X225.029344 Y64.142507 +G1 X225.121190 Y65.138631 +G1 X225.465098 Y67.464985 +G1 X225.850038 Y69.557134 +G1 X226.269673 Y71.436661 +G1 X226.716223 Y73.124044 +G1 X227.231399 Y74.788717 +G1 X227.764718 Y76.280357 +G1 X228.364924 Y77.749492 +G1 X229.036862 Y79.194344 +G1 X229.714036 Y80.485277 +G1 X230.458135 Y81.753335 +G1 X231.272797 Y82.997182 +G1 X231.381670 Y83.153602 +G1 X232.297063 Y84.394698 +G1 X233.270152 Y85.588805 +G1 X234.298407 Y86.733626 +G1 X235.379298 Y87.826866 +G1 X236.510292 Y88.866225 +G1 X237.688860 Y89.849407 +G1 X238.912471 Y90.774115 +G1 X240.178594 Y91.638052 +G1 X241.484698 Y92.438920 +G1 X242.828253 Y93.174422 +G1 X244.206728 Y93.842262 +G1 X245.617592 Y94.440141 +G1 X247.058314 Y94.965763 +G1 X248.391843 Y95.378966 +G1 X249.746055 Y95.728828 +G1 X251.119049 Y96.013623 +G1 X251.589110 Y96.095209 +G1 X252.490776 Y96.238266 +G1 X253.344587 Y96.356447 +G1 X253.485420 Y96.373656 +G1 X254.373546 Y96.439699 +G1 X255.297076 Y96.450206 +G1 X256.256215 Y96.436083 +G1 X257.088420 Y96.427794 +G1 X257.625030 Y96.430546 +G1 X258.105114 Y96.429748 +G1 X258.571889 Y96.411819 +G1 X258.984730 Y96.373655 +G1 X259.894012 Y96.250845 +G1 X260.851992 Y96.091776 +G1 X261.821225 Y95.897476 +G1 X262.764267 Y95.668974 +G1 X262.966990 Y95.613520 +G1 X264.321136 Y95.200083 +G1 X265.654356 Y94.723463 +G1 X266.962843 Y94.184143 +G1 X268.242788 Y93.582602 +G1 X269.490381 Y92.919323 +G1 X270.701815 Y92.194787 +G1 X271.873281 Y91.409475 +G1 X273.000969 Y90.563869 +G1 X274.081072 Y89.658449 +G1 X275.109780 Y88.693698 +G1 X275.997166 Y87.765569 +G1 X276.836068 Y86.789166 +G1 X277.623625 Y85.764848 +G1 X278.356974 Y84.692979 +G1 X279.033255 Y83.573919 +G1 X279.056440 Y83.532865 +G1 X279.624696 Y82.454972 +G1 X280.131338 Y81.349952 +G1 X280.576309 Y80.220973 +G1 X280.959551 Y79.071201 +G1 X281.281008 Y77.903803 +G1 X281.540624 Y76.721946 +G1 X281.738340 Y75.528797 +G1 X281.874101 Y74.327523 +G1 X281.947849 Y73.121290 +G1 X281.959528 Y71.913266 +G1 X281.909080 Y70.706616 +G1 X281.796449 Y69.504508 +G1 X281.621578 Y68.310109 +G1 X281.384410 Y67.126586 +G1 X281.084888 Y65.957105 +G1 X280.722955 Y64.804833 +G1 X280.298554 Y63.672937 +G1 X279.811629 Y62.564583 +G1 X279.262122 Y61.482940 +G1 X278.649977 Y60.431172 +G1 X277.975137 Y59.412448 +G1 X277.728640 Y59.070424 +G1 X276.931406 Y58.055200 +G1 X276.072749 Y57.090182 +G1 X275.156614 Y56.178326 +G1 X274.186946 Y55.322591 +G1 X273.167689 Y54.525934 +G1 X272.102791 Y53.791312 +G1 X270.996195 Y53.121684 +G1 X269.851848 Y52.520005 +G1 X268.673693 Y51.989235 +G1 X267.518140 Y51.550402 +G1 X266.353501 Y51.179496 +G1 X265.143726 Y50.866562 +G1 X264.139066 Y50.671926 +G1 X263.346250 Y50.569254 +G1 X262.947550 Y50.538818 +G1 X262.598427 Y50.527143 +G1 X262.263993 Y50.527460 +G1 X261.909364 Y50.532996 +G1 X261.499655 Y50.536981 +G1 X261.449940 Y50.537034 +G1 X261.043553 Y50.534450 +G1 X260.700758 Y50.529035 +G1 X260.395039 Y50.524299 +G1 X260.099882 Y50.523751 +G1 X259.755763 Y50.532171 +G1 X259.363990 Y50.554084 +G1 X258.778740 Y50.616723 +G1 X258.154453 Y50.721054 +G1 X257.511325 Y50.858956 +G1 X256.869554 Y51.022310 +G1 X256.249337 Y51.202994 +G1 X255.670869 Y51.392888 +G1 X255.571370 Y51.427907 +G1 X254.544085 Y51.830397 +G1 X253.545553 Y52.298292 +G1 X252.581618 Y52.832379 +G1 X251.740253 Y53.376015 +G1 X250.936700 Y53.975597 +G1 X250.262450 Y54.551697 +G1 X249.753613 Y55.059138 +G1 X249.266854 Y55.626174 +G1 X248.807129 Y56.235798 +G1 X248.379392 Y56.871003 +G1 X247.988599 Y57.514784 +G1 X247.639707 Y58.150133 +G1 X247.337670 Y58.760044 +G1 X247.087443 Y59.327511 +G1 X247.037960 Y59.449686 +G1 X248.044142 Y58.927471 +G1 X249.111052 Y58.411249 +G1 X250.223889 Y57.926450 +G1 X251.367854 Y57.498503 +G1 X252.422378 Y57.180194 +G1 X253.383389 Y56.965910 +G1 X254.251707 Y56.845657 +G1 X255.031221 Y56.807334 +G1 X255.381720 Y56.814575 +G1 X256.288762 Y56.894431 +G1 X257.187241 Y57.052912 +G1 X258.068664 Y57.288511 +G1 X258.848012 Y57.568343 +G1 X259.599866 Y57.909531 +G1 X260.317845 Y58.310941 +G1 X260.995570 Y58.771441 +G1 X261.626659 Y59.289899 +G1 X262.204732 Y59.865181 +G1 X262.678879 Y60.436524 +G1 X263.099145 Y61.053042 +G1 X263.460735 Y61.713884 +G1 X263.758857 Y62.418201 +G1 X263.846860 Y62.673416 +G1 X264.046699 Y63.386126 +G1 X264.161441 Y64.019857 +G1 X264.208285 Y64.656684 +G1 X264.196920 Y65.138630 +G1 X264.130096 Y65.888608 +G1 X264.022132 Y66.591851 +G1 X263.860789 Y67.272215 +G1 X263.633827 Y67.953560 +G1 X263.360256 Y68.593891 +G1 X263.095350 Y69.120886 +G1 X262.678447 Y69.828300 +G1 X262.207868 Y70.493282 +G1 X261.687738 Y71.116085 +G1 X261.122182 Y71.696962 +G1 X260.515326 Y72.236165 +G1 X259.871295 Y72.733946 +G1 X259.194215 Y73.190560 +G1 X258.488210 Y73.606257 +G1 X257.757405 Y73.981292 +G1 X257.005928 Y74.315916 +G1 X256.237901 Y74.610383 +G1 X255.457452 Y74.864944 +G1 X254.668704 Y75.079854 +G1 X253.875785 Y75.255364 +G1 X253.082817 Y75.391727 +G1 X252.293929 Y75.489196 +G1 X251.513243 Y75.548024 +G1 X251.020200 Y75.565504 +G1 X249.956987 Y75.547112 +G1 X248.884269 Y75.452336 +G1 X247.807013 Y75.284050 +G1 X246.730188 Y75.045134 +G1 X245.658759 Y74.738463 +G1 X244.597696 Y74.366914 +G1 X243.551964 Y73.933365 +G1 X242.526533 Y73.440693 +G1 X241.526369 Y72.891774 +G1 X240.556440 Y72.289486 +G1 X239.621712 Y71.636705 +G1 X238.727155 Y70.936308 +G1 X237.877735 Y70.191174 +G1 X237.078419 Y69.404177 +G1 X236.641140 Y68.931250 +G1 X235.988955 Y68.144996 +G1 X235.389383 Y67.310872 +G1 X234.842028 Y66.434906 +G1 X234.346491 Y65.523128 +G1 X233.902377 Y64.581568 +G1 X233.509287 Y63.616255 +G1 X233.166824 Y62.633218 +G1 X232.874591 Y61.638488 +G1 X232.632190 Y60.638095 +G1 X232.439224 Y59.638066 +G1 X232.301000 Y58.691160 +G1 X232.238413 Y58.199944 +G1 X232.182911 Y57.774084 +G1 X232.136147 Y57.388460 +G1 X232.099775 Y57.017949 +G1 X232.075450 Y56.637430 +G1 X232.064826 Y56.221780 +G1 X232.067310 Y55.846692 +G1 X232.085127 Y55.453097 +G1 X232.117273 Y55.120240 +G1 X232.156932 Y54.817950 +G1 X232.197288 Y54.516056 +G1 X232.231526 Y54.184390 +G1 X232.246700 Y53.950377 +G1 X232.302274 Y53.246958 +G1 X232.398070 Y52.492883 +G1 X232.526021 Y51.716193 +G1 X232.678058 Y50.944932 +G1 X232.846114 Y50.207142 +G1 X232.954900 Y49.778495 +G1 X233.323135 Y48.524885 +G1 X233.760845 Y47.286336 +G1 X234.266686 Y46.069104 +G1 X234.839316 Y44.879447 +G1 X235.477392 Y43.723619 +G1 X236.179570 Y42.607878 +G1 X236.944508 Y41.538479 +G1 X237.693236 Y40.611777 +G1 X237.968560 Y40.296931 +G1 X238.951090 Y39.248353 +G1 X239.982937 Y38.248072 +G1 X241.061656 Y37.298557 +G1 X242.184801 Y36.402276 +G1 X243.349927 Y35.561696 +G1 X244.554587 Y34.779285 +G1 X245.796337 Y34.057512 +G1 X247.072731 Y33.398843 +G1 X248.381323 Y32.805748 +G1 X249.719668 Y32.280695 +G1 X251.020200 Y31.846008 +G1 X252.478377 Y31.433004 +G1 X253.957580 Y31.086527 +G1 X255.314664 Y30.838027 +G1 X256.678082 Y30.660912 +G1 X256.709140 Y30.657774 +G1 X257.194058 Y30.622179 +G1 X257.656700 Y30.591483 +G1 X257.846930 Y30.571674 +G1 X258.420075 Y30.500477 +G1 X258.976270 Y30.449377 +G1 X259.363980 Y30.437034 +G1 X259.729117 Y30.440417 +G1 X260.034765 Y30.454901 +G1 X260.308165 Y30.478668 +G1 X260.576559 Y30.509895 +G1 X260.867188 Y30.546762 +G1 X261.070660 Y30.571674 +G1 X261.539965 Y30.609830 +G1 X261.979173 Y30.628563 +G1 X262.398080 Y30.657984 +G1 X263.386571 Y30.788251 +G1 X264.388676 Y30.978560 +G1 X265.381569 Y31.215377 +G1 X266.190710 Y31.440027 +G1 X267.339153 Y31.813166 +G1 X268.458969 Y32.245832 +G1 X269.550231 Y32.735032 +G1 X270.613013 Y33.277775 +G1 X271.647389 Y33.871068 +G1 X272.653432 Y34.511919 +G1 X273.631217 Y35.197338 +G1 X274.580818 Y35.924331 +G1 X275.502308 Y36.689906 +G1 X276.395760 Y37.491072 +G1 X277.261249 Y38.324837 +G1 X278.098849 Y39.188208 +G1 X278.908633 Y40.078195 +G1 X279.690675 Y40.991803 +G1 X280.445049 Y41.926043 +G1 X281.171829 Y42.877921 +G1 X281.871089 Y43.844447 +G1 X282.303870 Y44.468835 +G1 X282.649550 Y45.000163 +G1 X283.012013 Y45.599464 +G1 X283.388375 Y46.254515 +G1 X283.775749 Y46.953093 +G1 X284.171251 Y47.682977 +G1 X284.571996 Y48.431942 +G1 X284.975099 Y49.187767 +G1 X285.417792 Y50.012509 +G1 X285.856008 Y50.814493 +G1 X286.285906 Y51.577451 +G1 X286.703646 Y52.285114 +G1 X287.069628 Y52.866772 +G1 X287.369130 Y53.306909 +G1 X287.359314 Y53.267755 +G1 X287.331113 Y53.155123 +G1 X287.286402 Y52.976260 +G1 X287.227053 Y52.738413 +G1 X287.154940 Y52.448829 +G1 X287.071936 Y52.114754 +G1 X286.979914 Y51.743436 +G1 X286.880747 Y51.342120 +G1 X286.776309 Y50.918053 +G1 X286.668473 Y50.478483 +G1 X286.559112 Y50.030656 +G1 X286.439289 Y49.537158 +G1 X286.310946 Y49.004411 +G1 X286.189448 Y48.494693 +G1 X286.078115 Y48.020842 +G1 X285.980263 Y47.595698 +G1 X285.899213 Y47.232097 +G1 X285.842902 Y46.965760 +G1 X285.836510 Y46.934039 +G1 X285.604011 Y45.721969 +G1 X285.378684 Y44.450444 +G1 X285.164062 Y43.142654 +G1 X284.963679 Y41.821788 +G1 X284.781067 Y40.511038 +G1 X284.619759 Y39.233594 +G1 X284.483290 Y38.012647 +G1 X284.427550 Y37.452475 +G1 X284.384334 Y36.752750 +G1 X284.372272 Y36.002289 +G1 X284.378637 Y35.236783 +G1 X284.390699 Y34.491925 +G1 X284.395550 Y34.039119 +G1 X284.410566 Y33.422667 +G1 X284.462261 Y32.818849 +G1 X284.475750 Y32.711693 +G1 X284.543923 Y32.138499 +G1 X284.595605 Y31.612438 +G1 X284.599200 Y31.573904 +G1 X284.725801 Y30.453531 +G1 X284.898211 Y29.295246 +G1 X285.110753 Y28.117814 +G1 X285.357745 Y26.940004 +G1 X285.633511 Y25.780580 +G1 X285.932369 Y24.658309 +G1 X286.184520 Y23.799028 +G1 X286.688838 Y22.288908 +G1 X287.268349 Y20.802660 +G1 X287.920615 Y19.343690 +G1 X288.643197 Y17.915404 +G1 X289.433658 Y16.521207 +G1 X290.289558 Y15.164506 +G1 X291.208460 Y13.848706 +G1 X292.187925 Y12.577214 +G1 X293.225514 Y11.353435 +G1 X294.318789 Y10.180775 +G1 X295.465312 Y9.062640 +G1 X296.662645 Y8.002436 +G1 X296.721370 Y7.953048 +G1 X297.766143 Y7.118311 +G1 X298.863443 Y6.322100 +G1 X300.007350 Y5.567837 +G1 X301.191945 Y4.858941 +G1 X302.411310 Y4.198835 +G1 X303.659525 Y3.590939 +G1 X304.930671 Y3.038674 +G1 X306.218829 Y2.545462 +G1 X307.518081 Y2.114724 +G1 X308.822507 Y1.749881 +G1 X310.126189 Y1.454353 +G1 X311.423207 Y1.231562 +G1 X312.707642 Y1.084929 +G1 X313.029670 Y1.060326 +G1 X313.358417 Y1.044386 +G1 X313.631293 Y1.041377 +G1 X313.884922 Y1.041984 +G1 X314.185397 Y1.035710 +G1 X314.357090 Y1.026226 +G1 X314.726133 Y0.988003 +G1 X315.045937 Y0.942265 +G1 X315.370100 Y0.908239 +G1 X315.684510 Y0.902766 +G1 X316.016074 Y0.926765 +G1 X316.312798 Y0.968052 +G1 X316.635877 Y1.010219 +G1 X316.822300 Y1.026226 +G1 X317.186777 Y1.041981 +G1 X317.504564 Y1.042812 +G1 X317.830349 Y1.042293 +G1 X318.149720 Y1.050726 +G1 X318.835446 Y1.103732 +G1 X319.568076 Y1.200446 +G1 X320.331908 Y1.334141 +G1 X321.111240 Y1.498090 +G1 X321.890370 Y1.685567 +G1 X322.653596 Y1.889844 +G1 X323.385217 Y2.104196 +G1 X324.069530 Y2.321895 +G1 X324.217910 Y2.371506 +G1 X325.477181 Y2.836148 +G1 X326.717471 Y3.372376 +G1 X327.934244 Y3.976608 +G1 X329.122967 Y4.645259 +G1 X330.279103 Y5.374747 +G1 X331.398120 Y6.161487 +G1 X332.475482 Y7.001897 +G1 X333.506654 Y7.892392 +G1 X334.487103 Y8.829389 +G1 X335.373740 Y9.766370 +G1 X336.242882 Y10.790395 +G1 X337.045168 Y11.855060 +G1 X337.780145 Y12.957215 +G1 X338.447364 Y14.093711 +G1 X339.046372 Y15.261399 +G1 X339.576720 Y16.457129 +G1 X340.037955 Y17.677752 +G1 X340.429626 Y18.920119 +G1 X340.751284 Y20.181080 +G1 X341.002476 Y21.457486 +G1 X341.182751 Y22.746188 +G1 X341.291658 Y24.044036 +G1 X341.328747 Y25.347882 +G1 X341.293566 Y26.654575 +G1 X341.185663 Y27.960966 +G1 X341.004589 Y29.263907 +G1 X340.749892 Y30.560247 +G1 X340.548210 Y31.384340 +G1 X340.207451 Y32.534230 +G1 X339.800700 Y33.656180 +G1 X339.330350 Y34.748122 +G1 X338.798794 Y35.807989 +G1 X338.208424 Y36.833711 +G1 X337.561632 Y37.823220 +G1 X336.860812 Y38.774449 +G1 X336.108354 Y39.685329 +G1 X335.306652 Y40.553792 +G1 X334.458099 Y41.377769 +G1 X333.565086 Y42.155193 +G1 X332.630006 Y42.883995 +G1 X331.655252 Y43.562107 +G1 X330.643215 Y44.187461 +G1 X329.596289 Y44.757988 +G1 X328.516866 Y45.271620 +G1 X327.407338 Y45.726289 +G1 X326.683120 Y45.985185 +G1 X325.660877 Y46.292334 +G1 X324.626179 Y46.532488 +G1 X323.582254 Y46.711166 +G1 X322.532334 Y46.833886 +G1 X321.479647 Y46.906165 +G1 X320.427425 Y46.933522 +G1 X320.235660 Y46.934101 +G1 X319.734662 Y46.934690 +G1 X319.275678 Y46.925593 +G1 X318.804983 Y46.889977 +G1 X318.718610 Y46.879911 +G1 X318.056335 Y46.781876 +G1 X317.350931 Y46.647583 +G1 X316.631560 Y46.484171 +G1 X315.927383 Y46.298781 +G1 X315.494870 Y46.170879 +G1 X314.382984 Y45.789269 +G1 X313.297555 Y45.336911 +G1 X312.341045 Y44.860279 +G1 X311.420057 Y44.317672 +G1 X310.619094 Y43.764134 +G1 X309.857750 Y43.150431 +G1 X309.237800 Y42.571872 +G1 X308.802266 Y42.115978 +G1 X308.353481 Y41.600242 +G1 X307.915931 Y41.040549 +G1 X307.514101 Y40.452785 +G1 X307.172477 Y39.852836 +G1 X306.934759 Y39.310222 +G1 X306.804206 Y38.872575 +G1 X306.744408 Y38.451906 +G1 X306.760184 Y38.089882 +G1 X306.771840 Y38.021479 +G1 X307.268665 Y38.294931 +G1 X307.829309 Y38.595839 +G1 X308.439018 Y38.910182 +G1 X309.083036 Y39.223941 +G1 X309.746607 Y39.523094 +G1 X310.414978 Y39.793621 +G1 X310.943730 Y39.980177 +G1 X311.875936 Y40.247036 +G1 X312.818426 Y40.439949 +G1 X313.682291 Y40.546288 +G1 X314.551153 Y40.582391 +G1 X315.423344 Y40.543911 +G1 X316.217730 Y40.440553 +G1 X316.822300 Y40.316202 +G1 X317.624545 Y40.088990 +G1 X318.407729 Y39.796301 +G1 X319.164387 Y39.440508 +G1 X319.887060 Y39.023987 +G1 X320.568283 Y38.549110 +G1 X321.200596 Y38.018253 +G1 X321.776536 Y37.433789 +G1 X322.244920 Y36.857937 +G1 X322.654942 Y36.241529 +G1 X323.000994 Y35.586348 +G1 X323.255359 Y34.958583 +G1 X323.448012 Y34.301588 +G1 X323.574740 Y33.616704 +G1 X323.631332 Y32.905271 +G1 X323.634040 Y32.711798 +G1 X323.599584 Y31.984334 +G1 X323.498452 Y31.257148 +G1 X323.334485 Y30.535533 +G1 X323.111527 Y29.824785 +G1 X322.833420 Y29.130197 +G1 X322.504006 Y28.457061 +G1 X322.127127 Y27.810674 +G1 X321.706625 Y27.196327 +G1 X321.246343 Y26.619315 +G1 X320.772130 Y26.106943 +G1 X320.063820 Y25.447206 +G1 X319.301422 Y24.833258 +G1 X318.492279 Y24.269067 +G1 X317.643734 Y23.758600 +G1 X316.763130 Y23.305823 +G1 X315.857809 Y22.914705 +G1 X314.935113 Y22.589212 +G1 X314.002387 Y22.333311 +G1 X313.788190 Y22.284927 +G1 X313.008734 Y22.145269 +G1 X312.271140 Y22.041057 +G1 X311.776126 Y21.977541 +G1 X311.323078 Y21.935872 +G1 X310.867584 Y21.912302 +G1 X310.365234 Y21.903087 +G1 X309.995570 Y21.903006 +G1 X309.550974 Y21.912543 +G1 X309.160087 Y21.936608 +G1 X308.784286 Y21.974988 +G1 X308.384948 Y22.027468 +G1 X308.288890 Y22.041057 +G1 X307.308089 Y22.201783 +G1 X306.285966 Y22.413102 +G1 X305.252405 Y22.675226 +G1 X304.237295 Y22.988369 +G1 X303.355626 Y23.317496 +G1 X303.168840 Y23.395777 +G1 X302.128744 Y23.879879 +G1 X301.124415 Y24.424883 +G1 X300.157973 Y25.028105 +G1 X299.231539 Y25.686860 +G1 X298.347230 Y26.398462 +G1 X297.507166 Y27.160229 +G1 X296.713467 Y27.969475 +G1 X295.968252 Y28.823515 +G1 X295.273641 Y29.719665 +G1 X294.631753 Y30.655241 +G1 X294.044707 Y31.627557 +G1 X293.514623 Y32.633929 +G1 X293.043620 Y33.671673 +G1 X292.633818 Y34.738105 +G1 X292.425660 Y35.366638 +G1 X292.104800 Y36.510121 +G1 X291.851968 Y37.661767 +G1 X291.665848 Y38.819251 +G1 X291.545127 Y39.980247 +G1 X291.488489 Y41.142428 +G1 X291.494620 Y42.303470 +G1 X291.562205 Y43.461046 +G1 X291.689929 Y44.612831 +G1 X291.876477 Y45.756498 +G1 X292.120536 Y46.889722 +G1 X292.420789 Y48.010177 +G1 X292.775923 Y49.115537 +G1 X293.184622 Y50.203477 +G1 X293.645573 Y51.271670 +G1 X294.157459 Y52.317790 +G1 X294.718967 Y53.339512 +G1 X295.328782 Y54.334510 +G1 X295.985588 Y55.300458 +G1 X296.688072 Y56.235031 +G1 X297.434919 Y57.135902 +G1 X298.224813 Y58.000745 +G1 X299.056441 Y58.827235 +G1 X299.928487 Y59.613046 +G1 X300.839636 Y60.355851 +G1 X301.788575 Y61.053326 +G1 X302.599950 Y61.593595 +G1 X303.675310 Y62.236820 +G1 X304.790001 Y62.826169 +G1 X305.937814 Y63.360607 +G1 X307.112538 Y63.839099 +G1 X308.307963 Y64.260609 +G1 X309.517880 Y64.624103 +G1 X310.736077 Y64.928544 +G1 X311.322990 Y65.053610 +G1 X312.565071 Y65.262177 +G1 X313.827559 Y65.401307 +G1 X315.100046 Y65.482668 +G1 X316.372129 Y65.517929 +G1 X317.633400 Y65.518759 +G1 X317.770450 Y65.517256 +G1 X318.840830 Y65.469909 +G1 X319.916074 Y65.355013 +G1 X320.992141 Y65.175247 +G1 X322.064992 Y64.933288 +G1 X323.130587 Y64.631814 +G1 X324.184887 Y64.273502 +G1 X325.223851 Y63.861030 +G1 X326.243441 Y63.397076 +G1 X327.239617 Y62.884317 +G1 X328.208338 Y62.325431 +G1 X329.145566 Y61.723095 +G1 X330.047260 Y61.079988 +G1 X330.909381 Y60.398787 +G1 X331.727890 Y59.682170 +G1 X332.179590 Y59.252790 +G1 X332.985277 Y58.415085 +G1 X333.744649 Y57.531930 +G1 X334.459395 Y56.609436 +G1 X335.131203 Y55.653713 +G1 X335.761762 Y54.670871 +G1 X336.352762 Y53.667021 +G1 X336.905891 Y52.648273 +G1 X337.422838 Y51.620738 +G1 X337.905293 Y50.590525 +G1 X337.929400 Y50.537148 +G1 X338.503505 Y49.171104 +G1 X339.036206 Y47.769717 +G1 X339.557002 Y46.354406 +G1 X340.151335 Y44.807046 +G1 X340.743151 Y43.432218 +G1 X341.291001 Y42.334669 +G1 X341.474390 Y42.003736 +G1 X340.363056 Y45.443561 +G1 X339.484080 Y48.333939 +G1 X338.883797 Y50.526737 +G1 X338.405234 Y52.531643 +G1 X338.041301 Y54.360721 +G1 X337.780975 Y56.026563 +G1 X337.611420 Y57.541769 +G1 X337.513644 Y59.056216 +G1 X337.492280 Y60.018712 +G1 X337.449290 Y62.790352 +G1 X337.480734 Y63.953007 +G1 X337.572580 Y64.949131 +G1 X337.916488 Y67.275485 +G1 X338.301428 Y69.367634 +G1 X338.721063 Y71.247161 +G1 X339.167613 Y72.934544 +G1 X339.682789 Y74.599217 +G1 X340.216108 Y76.090857 +G1 X340.816314 Y77.559992 +G1 X341.488252 Y79.004844 +G1 X342.165426 Y80.295777 +G1 X342.909525 Y81.563835 +G1 X343.724187 Y82.807682 +G1 X343.833060 Y82.964102 +G1 X344.748453 Y84.205198 +G1 X345.721542 Y85.399305 +G1 X346.749797 Y86.544126 +G1 X347.830688 Y87.637366 +G1 X348.961682 Y88.676725 +G1 X350.140250 Y89.659907 +G1 X351.363861 Y90.584615 +G1 X352.629984 Y91.448552 +G1 X353.936088 Y92.249420 +G1 X355.279643 Y92.984922 +G1 X356.658118 Y93.652762 +G1 X358.068982 Y94.250641 +G1 X359.509704 Y94.776263 +G1 X360.843233 Y95.189466 +G1 X362.197445 Y95.539328 +G1 X363.570439 Y95.824123 +G1 X364.040500 Y95.905709 +G1 X364.942166 Y96.048766 +G1 X365.795977 Y96.166947 +G1 X365.936810 Y96.184156 +G1 X366.824936 Y96.250199 +G1 X367.748466 Y96.260706 +G1 X368.707605 Y96.246583 +G1 X369.539810 Y96.238294 +G1 X370.076420 Y96.241046 +G1 X370.556504 Y96.240248 +G1 X371.023279 Y96.222319 +G1 X371.436120 Y96.184155 +G1 X372.345402 Y96.061345 +G1 X373.303382 Y95.902276 +G1 X374.272615 Y95.707976 +G1 X375.215657 Y95.479474 +G1 X375.418380 Y95.424020 +G1 X376.772526 Y95.010583 +G1 X378.105746 Y94.533963 +G1 X379.414233 Y93.994643 +G1 X380.694178 Y93.393102 +G1 X381.941771 Y92.729823 +G1 X383.153205 Y92.005287 +G1 X384.324671 Y91.219975 +G1 X385.452359 Y90.374369 +G1 X386.532462 Y89.468949 +G1 X387.561170 Y88.504198 +G1 X388.448556 Y87.576069 +G1 X389.287458 Y86.599666 +G1 X390.075015 Y85.575348 +G1 X390.808364 Y84.503479 +G1 X391.484645 Y83.384419 +G1 X391.507830 Y83.343365 +G1 X392.076086 Y82.265472 +G1 X392.582728 Y81.160452 +G1 X393.027699 Y80.031473 +G1 X393.410941 Y78.881701 +G1 X393.732398 Y77.714303 +G1 X393.992014 Y76.532446 +G1 X394.189730 Y75.339297 +G1 X394.325491 Y74.138023 +G1 X394.399239 Y72.931790 +G1 X394.410918 Y71.723766 +G1 X394.360470 Y70.517116 +G1 X394.247839 Y69.315008 +G1 X394.072968 Y68.120609 +G1 X393.835800 Y66.937086 +G1 X393.536278 Y65.767605 +G1 X393.174345 Y64.615333 +G1 X392.749944 Y63.483437 +G1 X392.263019 Y62.375083 +G1 X391.713512 Y61.293440 +G1 X391.101367 Y60.241672 +G1 X390.426527 Y59.222948 +G1 X390.180030 Y58.880924 +G1 X389.382796 Y57.865700 +G1 X388.524139 Y56.900682 +G1 X387.608004 Y55.988826 +G1 X386.638336 Y55.133091 +G1 X385.619079 Y54.336434 +G1 X384.554181 Y53.601812 +G1 X383.447585 Y52.932184 +G1 X382.303238 Y52.330505 +G1 X381.125083 Y51.799735 +G1 X379.969530 Y51.360902 +G1 X378.804891 Y50.989996 +G1 X377.595116 Y50.677062 +G1 X376.590456 Y50.482426 +G1 X375.797640 Y50.379754 +G1 X375.398940 Y50.349318 +G1 X375.049817 Y50.337643 +G1 X374.715383 Y50.337960 +G1 X374.360754 Y50.343496 +G1 X373.951045 Y50.347481 +G1 X373.901330 Y50.347534 +G1 X373.494943 Y50.344950 +G1 X373.152148 Y50.339535 +G1 X372.846429 Y50.334799 +G1 X372.551272 Y50.334251 +G1 X372.207153 Y50.342671 +G1 X371.815380 Y50.364584 +G1 X371.230130 Y50.427223 +G1 X370.605843 Y50.531554 +G1 X369.962715 Y50.669456 +G1 X369.320944 Y50.832810 +G1 X368.700727 Y51.013494 +G1 X368.122259 Y51.203388 +G1 X368.022760 Y51.238407 +G1 X366.995475 Y51.640897 +G1 X365.996943 Y52.108792 +G1 X365.033008 Y52.642879 +G1 X364.191643 Y53.186515 +G1 X363.388090 Y53.786097 +G1 X362.713840 Y54.362197 +G1 X362.205003 Y54.869638 +G1 X361.718244 Y55.436674 +G1 X361.258519 Y56.046298 +G1 X360.830782 Y56.681503 +G1 X360.439989 Y57.325284 +G1 X360.091097 Y57.960633 +G1 X359.789060 Y58.570544 +G1 X359.538833 Y59.138011 +G1 X359.489350 Y59.260186 +G1 X360.495532 Y58.737971 +G1 X361.562442 Y58.221749 +G1 X362.675279 Y57.736950 +G1 X363.819244 Y57.309003 +G1 X364.873768 Y56.990694 +G1 X365.834779 Y56.776410 +G1 X366.703097 Y56.656157 +G1 X367.482611 Y56.617834 +G1 X367.833110 Y56.625075 +G1 X368.740152 Y56.704931 +G1 X369.638631 Y56.863412 +G1 X370.520054 Y57.099011 +G1 X371.299402 Y57.378843 +G1 X372.051256 Y57.720031 +G1 X372.769235 Y58.121441 +G1 X373.446960 Y58.581941 +G1 X374.078049 Y59.100399 +G1 X374.656122 Y59.675681 +G1 X375.130269 Y60.247024 +G1 X375.550535 Y60.863542 +G1 X375.912125 Y61.524384 +G1 X376.210247 Y62.228701 +G1 X376.298250 Y62.483916 +G1 X376.498089 Y63.196626 +G1 X376.612831 Y63.830357 +G1 X376.659675 Y64.467184 +G1 X376.648310 Y64.949130 +G1 X376.581522 Y65.699108 +G1 X376.473567 Y66.402351 +G1 X376.312214 Y67.082715 +G1 X376.085234 Y67.764060 +G1 X375.811650 Y68.404391 +G1 X375.546740 Y68.931386 +G1 X375.129837 Y69.638800 +G1 X374.659258 Y70.303782 +G1 X374.139128 Y70.926585 +G1 X373.573572 Y71.507462 +G1 X372.966716 Y72.046665 +G1 X372.322685 Y72.544446 +G1 X371.645605 Y73.001060 +G1 X370.939600 Y73.416757 +G1 X370.208795 Y73.791792 +G1 X369.457318 Y74.126416 +G1 X368.689291 Y74.420883 +G1 X367.908842 Y74.675444 +G1 X367.120094 Y74.890354 +G1 X366.327175 Y75.065864 +G1 X365.534207 Y75.202227 +G1 X364.745319 Y75.299696 +G1 X363.964633 Y75.358524 +G1 X363.471590 Y75.376004 +G1 X362.408377 Y75.357612 +G1 X361.335659 Y75.262836 +G1 X360.258403 Y75.094550 +G1 X359.181578 Y74.855634 +G1 X358.110149 Y74.548963 +G1 X357.049086 Y74.177414 +G1 X356.003354 Y73.743865 +G1 X354.977923 Y73.251193 +G1 X353.977759 Y72.702274 +G1 X353.007830 Y72.099986 +G1 X352.073102 Y71.447205 +G1 X351.178545 Y70.746808 +G1 X350.329125 Y70.001674 +G1 X349.529809 Y69.214677 +G1 X349.092530 Y68.741750 +G1 X348.440345 Y67.955496 +G1 X347.840773 Y67.121372 +G1 X347.293418 Y66.245406 +G1 X346.797881 Y65.333628 +G1 X346.353767 Y64.392068 +G1 X345.960677 Y63.426755 +G1 X345.618214 Y62.443718 +G1 X345.325981 Y61.448988 +G1 X345.083580 Y60.448595 +G1 X344.890614 Y59.448566 +G1 X344.752390 Y58.501660 +G1 X344.689803 Y58.010444 +G1 X344.634301 Y57.584584 +G1 X344.587537 Y57.198960 +G1 X344.551165 Y56.828449 +G1 X344.526840 Y56.447930 +G1 X344.516216 Y56.032280 +G1 X344.518700 Y55.657192 +G1 X344.536517 Y55.263597 +G1 X344.568663 Y54.930740 +G1 X344.608322 Y54.628450 +G1 X344.648678 Y54.326556 +G1 X344.682916 Y53.994890 +G1 X344.698090 Y53.760877 +G1 X344.753664 Y53.057458 +G1 X344.849460 Y52.303383 +G1 X344.977411 Y51.526693 +G1 X345.129448 Y50.755432 +G1 X345.297504 Y50.017642 +G1 X345.406290 Y49.588995 +G1 X345.774525 Y48.335385 +G1 X346.212235 Y47.096836 +G1 X346.718076 Y45.879604 +G1 X347.290706 Y44.689947 +G1 X347.928782 Y43.534119 +G1 X348.630960 Y42.418378 +G1 X349.395898 Y41.348979 +G1 X350.144626 Y40.422277 +G1 X350.419950 Y40.107431 +G1 X351.402480 Y39.058853 +G1 X352.434327 Y38.058572 +G1 X353.513046 Y37.109057 +G1 X354.636191 Y36.212776 +G1 X355.801317 Y35.372196 +G1 X357.005977 Y34.589785 +G1 X358.247727 Y33.868012 +G1 X359.524121 Y33.209343 +G1 X360.832713 Y32.616248 +G1 X362.171058 Y32.091195 +G1 X363.471590 Y31.656508 +G1 X364.929767 Y31.243504 +G1 X366.408970 Y30.897027 +G1 X367.766054 Y30.648527 +G1 X369.129472 Y30.471412 +G1 X369.160530 Y30.468274 +G1 X369.645448 Y30.432679 +G1 X370.108090 Y30.401983 +G1 X370.298320 Y30.382174 +G1 X370.871465 Y30.310977 +G1 X371.427660 Y30.259877 +G1 X371.815370 Y30.247534 +G1 X372.180507 Y30.250917 +G1 X372.486155 Y30.265401 +G1 X372.759555 Y30.289168 +G1 X373.027949 Y30.320395 +G1 X373.318578 Y30.357262 +G1 X373.522050 Y30.382174 +G1 X373.991355 Y30.420330 +G1 X374.430563 Y30.439063 +G1 X374.849470 Y30.468484 +G1 X375.837961 Y30.598751 +G1 X376.840066 Y30.789060 +G1 X377.832959 Y31.025877 +G1 X378.642100 Y31.250527 +G1 X379.790543 Y31.623666 +G1 X380.910359 Y32.056332 +G1 X382.001621 Y32.545532 +G1 X383.064403 Y33.088275 +G1 X384.098779 Y33.681568 +G1 X385.104822 Y34.322419 +G1 X386.082607 Y35.007838 +G1 X387.032208 Y35.734831 +G1 X387.953698 Y36.500406 +G1 X388.847150 Y37.301572 +G1 X389.712639 Y38.135337 +G1 X390.550239 Y38.998708 +G1 X391.360023 Y39.888695 +G1 X392.142065 Y40.802303 +G1 X392.896439 Y41.736543 +G1 X393.623219 Y42.688421 +G1 X394.322479 Y43.654947 +G1 X394.755260 Y44.279335 +G1 X395.100940 Y44.810663 +G1 X395.463403 Y45.409964 +G1 X395.839765 Y46.065015 +G1 X396.227139 Y46.763593 +G1 X396.622641 Y47.493477 +G1 X397.023386 Y48.242442 +G1 X397.426489 Y48.998267 +G1 X397.869182 Y49.823009 +G1 X398.307398 Y50.624993 +G1 X398.737296 Y51.387951 +G1 X399.155036 Y52.095614 +G1 X399.521018 Y52.677272 +G1 X399.820520 Y53.117409 +G1 X399.810704 Y53.078255 +G1 X399.782503 Y52.965623 +G1 X399.737792 Y52.786760 +G1 X399.678443 Y52.548913 +G1 X399.606330 Y52.259329 +G1 X399.523326 Y51.925254 +G1 X399.431304 Y51.553936 +G1 X399.332137 Y51.152620 +G1 X399.227699 Y50.728553 +G1 X399.119863 Y50.288983 +G1 X399.010502 Y49.841156 +G1 X398.890679 Y49.347658 +G1 X398.762336 Y48.814911 +G1 X398.640838 Y48.305193 +G1 X398.529505 Y47.831342 +G1 X398.431653 Y47.406198 +G1 X398.350603 Y47.042597 +G1 X398.294292 Y46.776260 +G1 X398.287900 Y46.744539 +G1 X398.055401 Y45.532469 +G1 X397.830074 Y44.260944 +G1 X397.615452 Y42.953154 +G1 X397.415069 Y41.632288 +G1 X397.232457 Y40.321538 +G1 X397.071149 Y39.044094 +G1 X396.934680 Y37.823147 +G1 X396.878940 Y37.262975 +G1 X396.835685 Y36.563250 +G1 X396.823621 Y35.812789 +G1 X396.830002 Y35.047283 +G1 X396.842085 Y34.302425 +G1 X396.846940 Y33.849619 +G1 X396.861956 Y33.233167 +G1 X396.913651 Y32.629349 +G1 X396.927140 Y32.522193 +G1 X396.995313 Y31.948999 +G1 X397.046995 Y31.422938 +G1 X397.050590 Y31.384404 +G1 X397.177191 Y30.264031 +G1 X397.349601 Y29.105746 +G1 X397.562143 Y27.928314 +G1 X397.809135 Y26.750504 +G1 X398.084901 Y25.591080 +G1 X398.383759 Y24.468809 +G1 X398.635910 Y23.609528 +G1 X399.140228 Y22.099408 +G1 X399.719739 Y20.613160 +G1 X400.372005 Y19.154190 +G1 X401.094587 Y17.725904 +G1 X401.885048 Y16.331707 +G1 X402.740948 Y14.975006 +G1 X403.659850 Y13.659206 +G1 X404.639315 Y12.387714 +G1 X405.676904 Y11.163935 +G1 X406.770179 Y9.991275 +G1 X407.916702 Y8.873140 +G1 X409.114035 Y7.812936 +G1 X409.172760 Y7.763548 +G1 X410.217533 Y6.928811 +G1 X411.314833 Y6.132600 +G1 X412.458740 Y5.378337 +G1 X413.643335 Y4.669441 +G1 X414.862700 Y4.009335 +G1 X416.110915 Y3.401439 +G1 X417.382061 Y2.849174 +G1 X418.670219 Y2.355962 +G1 X419.969471 Y1.925224 +G1 X421.273897 Y1.560381 +G1 X422.577579 Y1.264853 +G1 X423.874597 Y1.042062 +G1 X425.159032 Y0.895429 +G1 X425.481060 Y0.870826 +G1 X425.809807 Y0.854886 +G1 X426.082683 Y0.851877 +G1 X426.336312 Y0.852484 +G1 X426.636787 Y0.846210 +G1 X426.808480 Y0.836726 +G1 X427.177523 Y0.798503 +G1 X427.497327 Y0.752765 +G1 X427.821490 Y0.718739 +G1 X428.135900 Y0.713266 +G1 X428.467464 Y0.737265 +G1 X428.764188 Y0.778552 +G1 X429.087267 Y0.820719 +G1 X429.273690 Y0.836726 +G1 X429.638167 Y0.852481 +G1 X429.955954 Y0.853312 +G1 X430.281739 Y0.852793 +G1 X430.601110 Y0.861226 +G1 X431.286836 Y0.914232 +G1 X432.019466 Y1.010946 +G1 X432.783298 Y1.144641 +G1 X433.562630 Y1.308590 +G1 X434.341760 Y1.496067 +G1 X435.104986 Y1.700344 +G1 X435.836607 Y1.914696 +G1 X436.520920 Y2.132395 +G1 X436.669300 Y2.182006 +G1 X437.928571 Y2.646648 +G1 X439.168861 Y3.182876 +G1 X440.385634 Y3.787108 +G1 X441.574357 Y4.455759 +G1 X442.730493 Y5.185247 +G1 X443.849510 Y5.971987 +G1 X444.926872 Y6.812397 +G1 X445.958044 Y7.702892 +G1 X446.938493 Y8.639889 +G1 X447.825130 Y9.576870 +G1 X448.694272 Y10.600895 +G1 X449.496558 Y11.665560 +G1 X450.231535 Y12.767715 +G1 X450.898754 Y13.904211 +G1 X451.497762 Y15.071899 +G1 X452.028110 Y16.267629 +G1 X452.489345 Y17.488252 +G1 X452.881016 Y18.730619 +G1 X453.202674 Y19.991580 +G1 X453.453866 Y21.267986 +G1 X453.634141 Y22.556688 +G1 X453.743048 Y23.854536 +G1 X453.780137 Y25.158382 +G1 X453.744956 Y26.465075 +G1 X453.637053 Y27.771466 +G1 X453.455979 Y29.074407 +G1 X453.201282 Y30.370747 +G1 X452.999600 Y31.194840 +G1 X452.658841 Y32.344730 +G1 X452.252090 Y33.466680 +G1 X451.781740 Y34.558622 +G1 X451.250184 Y35.618489 +G1 X450.659814 Y36.644211 +G1 X450.013022 Y37.633720 +G1 X449.312202 Y38.584949 +G1 X448.559744 Y39.495829 +G1 X447.758042 Y40.364292 +G1 X446.909489 Y41.188269 +G1 X446.016476 Y41.965693 +G1 X445.081396 Y42.694495 +G1 X444.106642 Y43.372607 +G1 X443.094605 Y43.997961 +G1 X442.047679 Y44.568488 +G1 X440.968256 Y45.082120 +G1 X439.858728 Y45.536789 +G1 X439.134510 Y45.795685 +G1 X438.112267 Y46.102834 +G1 X437.077569 Y46.342988 +G1 X436.033644 Y46.521666 +G1 X434.983724 Y46.644386 +G1 X433.931037 Y46.716665 +G1 X432.878815 Y46.744022 +G1 X432.687050 Y46.744601 +G1 X432.186052 Y46.745190 +G1 X431.727068 Y46.736093 +G1 X431.256373 Y46.700477 +G1 X431.170000 Y46.690411 +G1 X430.507725 Y46.592376 +G1 X429.802321 Y46.458083 +G1 X429.082950 Y46.294671 +G1 X428.378773 Y46.109281 +G1 X427.946260 Y45.981379 +G1 X426.834374 Y45.599769 +G1 X425.748945 Y45.147411 +G1 X424.792435 Y44.670779 +G1 X423.871447 Y44.128172 +G1 X423.070484 Y43.574634 +G1 X422.309140 Y42.960931 +G1 X421.689190 Y42.382372 +G1 X421.253656 Y41.926478 +G1 X420.804871 Y41.410742 +G1 X420.367321 Y40.851049 +G1 X419.965491 Y40.263285 +G1 X419.623867 Y39.663336 +G1 X419.386149 Y39.120722 +G1 X419.255596 Y38.683075 +G1 X419.195798 Y38.262406 +G1 X419.211574 Y37.900382 +G1 X419.223230 Y37.831979 +G1 X419.720055 Y38.105431 +G1 X420.280699 Y38.406339 +G1 X420.890408 Y38.720682 +G1 X421.534426 Y39.034441 +G1 X422.197997 Y39.333594 +G1 X422.866368 Y39.604121 +G1 X423.395120 Y39.790677 +G1 X424.327326 Y40.057536 +G1 X425.269816 Y40.250449 +G1 X426.133681 Y40.356788 +G1 X427.002543 Y40.392891 +G1 X427.874734 Y40.354411 +G1 X428.669120 Y40.251053 +G1 X429.273690 Y40.126702 +G1 X430.075935 Y39.899490 +G1 X430.859119 Y39.606801 +G1 X431.615777 Y39.251008 +G1 X432.338450 Y38.834487 +G1 X433.019673 Y38.359610 +G1 X433.651986 Y37.828753 +G1 X434.227926 Y37.244289 +G1 X434.696310 Y36.668437 +G1 X435.106332 Y36.052029 +G1 X435.452384 Y35.396848 +G1 X435.706749 Y34.769083 +G1 X435.899402 Y34.112088 +G1 X436.026130 Y33.427204 +G1 X436.082722 Y32.715771 +G1 X436.085430 Y32.522298 +G1 X436.050974 Y31.794834 +G1 X435.949842 Y31.067648 +G1 X435.785875 Y30.346033 +G1 X435.562917 Y29.635285 +G1 X435.284810 Y28.940697 +G1 X434.955396 Y28.267561 +G1 X434.578517 Y27.621174 +G1 X434.158015 Y27.006827 +G1 X433.697733 Y26.429815 +G1 X433.223520 Y25.917443 +G1 X432.515210 Y25.257706 +G1 X431.752812 Y24.643758 +G1 X430.943669 Y24.079567 +G1 X430.095124 Y23.569100 +G1 X429.214520 Y23.116323 +G1 X428.309199 Y22.725205 +G1 X427.386503 Y22.399712 +G1 X426.453777 Y22.143811 +G1 X426.239580 Y22.095427 +G1 X425.460124 Y21.955769 +G1 X424.722530 Y21.851557 +G1 X424.227516 Y21.788041 +G1 X423.774468 Y21.746372 +G1 X423.318974 Y21.722802 +G1 X422.816624 Y21.713587 +G1 X422.446960 Y21.713506 +G1 X422.002364 Y21.723043 +G1 X421.611477 Y21.747108 +G1 X421.235676 Y21.785488 +G1 X420.836338 Y21.837968 +G1 X420.740280 Y21.851557 +G1 X419.759479 Y22.012283 +G1 X418.737356 Y22.223602 +G1 X417.703795 Y22.485726 +G1 X416.688685 Y22.798869 +G1 X415.807016 Y23.127996 +G1 X415.620230 Y23.206277 +G1 X414.580134 Y23.690379 +G1 X413.575805 Y24.235383 +G1 X412.609363 Y24.838605 +G1 X411.682929 Y25.497360 +G1 X410.798620 Y26.208962 +G1 X409.958556 Y26.970729 +G1 X409.164857 Y27.779975 +G1 X408.419642 Y28.634015 +G1 X407.725031 Y29.530165 +G1 X407.083143 Y30.465741 +G1 X406.496097 Y31.438057 +G1 X405.966013 Y32.444429 +G1 X405.495010 Y33.482173 +G1 X405.085208 Y34.548605 +G1 X404.877050 Y35.177138 +G1 X404.556190 Y36.320621 +G1 X404.303358 Y37.472267 +G1 X404.117238 Y38.629751 +G1 X403.996517 Y39.790747 +G1 X403.939879 Y40.952928 +G1 X403.946010 Y42.113970 +G1 X404.013595 Y43.271546 +G1 X404.141319 Y44.423331 +G1 X404.327867 Y45.566998 +G1 X404.571926 Y46.700222 +G1 X404.872179 Y47.820677 +G1 X405.227313 Y48.926037 +G1 X405.636012 Y50.013977 +G1 X406.096963 Y51.082170 +G1 X406.608849 Y52.128290 +G1 X407.170357 Y53.150012 +G1 X407.780172 Y54.145010 +G1 X408.436978 Y55.110958 +G1 X409.139462 Y56.045531 +G1 X409.886309 Y56.946402 +G1 X410.676203 Y57.811245 +G1 X411.507831 Y58.637735 +G1 X412.379877 Y59.423546 +G1 X413.291026 Y60.166351 +G1 X414.239965 Y60.863826 +G1 X415.051340 Y61.404095 +G1 X416.126700 Y62.047320 +G1 X417.241391 Y62.636669 +G1 X418.389204 Y63.171107 +G1 X419.563928 Y63.649599 +G1 X420.759353 Y64.071109 +G1 X421.969270 Y64.434603 +G1 X423.187467 Y64.739044 +G1 X423.774380 Y64.864110 +G1 X425.016461 Y65.072677 +G1 X426.278949 Y65.211807 +G1 X427.551436 Y65.293168 +G1 X428.823519 Y65.328429 +G1 X430.084790 Y65.329259 +G1 X430.221840 Y65.327756 +G1 X431.292220 Y65.280409 +G1 X432.367464 Y65.165513 +G1 X433.443531 Y64.985747 +G1 X434.516382 Y64.743788 +G1 X435.581977 Y64.442314 +G1 X436.636277 Y64.084002 +G1 X437.675241 Y63.671530 +G1 X438.694831 Y63.207576 +G1 X439.691007 Y62.694817 +G1 X440.659728 Y62.135931 +G1 X441.596956 Y61.533595 +G1 X442.498650 Y60.890488 +G1 X443.360771 Y60.209287 +G1 X444.179280 Y59.492670 +G1 X444.630980 Y59.063290 +G1 X445.436667 Y58.225585 +G1 X446.196039 Y57.342430 +G1 X446.910785 Y56.419936 +G1 X447.582593 Y55.464213 +G1 X448.213152 Y54.481371 +G1 X448.804152 Y53.477521 +G1 X449.357281 Y52.458773 +G1 X449.874228 Y51.431238 +G1 X450.356683 Y50.401025 +G1 X450.380790 Y50.347648 +G1 X450.954895 Y48.981604 +G1 X451.487595 Y47.580217 +G1 X452.008391 Y46.164906 +G1 X452.602722 Y44.617546 +G1 X453.194535 Y43.242718 +G1 X453.742382 Y42.145169 +G1 X453.925770 Y41.814236 +G1 X452.814431 Y45.254061 +G1 X451.935453 Y48.144439 +G1 X451.335169 Y50.337237 +G1 X450.856605 Y52.342143 +G1 X450.492671 Y54.171221 +G1 X450.232345 Y55.837063 +G1 X450.062790 Y57.352269 +G1 X449.965014 Y58.866716 +G1 X449.943650 Y59.829212 +G1 X449.900660 Y62.600852 +G1 X449.932104 Y63.763507 +G1 X450.023950 Y64.759631 +G1 X450.367858 Y67.085985 +G1 X450.752798 Y69.178134 +G1 X451.172433 Y71.057661 +G1 X451.618983 Y72.745044 +G1 X452.134159 Y74.409717 +G1 X452.667478 Y75.901357 +G1 X453.267684 Y77.370492 +G1 X453.939622 Y78.815344 +G1 X454.616796 Y80.106277 +G1 X455.360895 Y81.374335 +G1 X456.175557 Y82.618182 +G1 X456.284430 Y82.774602 +G1 X457.199823 Y84.015698 +G1 X458.172912 Y85.209805 +G1 X459.201167 Y86.354626 +G1 X460.282058 Y87.447866 +G1 X461.413052 Y88.487225 +G1 X462.591620 Y89.470407 +G1 X463.815231 Y90.395115 +G1 X465.081354 Y91.259052 +G1 X466.387458 Y92.059920 +G1 X467.731013 Y92.795422 +G1 X469.109488 Y93.463262 +G1 X470.520352 Y94.061141 +G1 X471.961074 Y94.586763 +G1 X473.294603 Y94.999966 +G1 X474.648815 Y95.349828 +G1 X476.021809 Y95.634623 +G1 X476.491870 Y95.716209 +G1 X477.393536 Y95.859266 +G1 X478.247347 Y95.977447 +G1 X478.388180 Y95.994656 +G1 X479.276306 Y96.060699 +G1 X480.199836 Y96.071206 +G1 X481.158975 Y96.057083 +G1 X481.991180 Y96.048794 +G1 X482.527790 Y96.051546 +G1 X483.007874 Y96.050748 +G1 X483.474649 Y96.032819 +G1 X483.887490 Y95.994655 +G1 X484.796772 Y95.871845 +G1 X485.754752 Y95.712776 +G1 X486.723985 Y95.518476 +G1 X487.667027 Y95.289974 +G1 X487.869750 Y95.234520 +G1 X489.223896 Y94.821083 +G1 X490.557116 Y94.344463 +G1 X491.865603 Y93.805143 +G1 X493.145548 Y93.203602 +G1 X494.393141 Y92.540323 +G1 X495.604575 Y91.815787 +G1 X496.776041 Y91.030475 +G1 X497.903729 Y90.184869 +G1 X498.983832 Y89.279449 +G1 X500.012540 Y88.314698 +G1 X500.899926 Y87.386569 +G1 X501.738828 Y86.410166 +G1 X502.526385 Y85.385848 +G1 X503.259734 Y84.313979 +G1 X503.936015 Y83.194919 +G1 X503.959200 Y83.153865 +G1 X504.527456 Y82.075972 +G1 X505.034098 Y80.970952 +G1 X505.479069 Y79.841973 +G1 X505.862311 Y78.692201 +G1 X506.183768 Y77.524803 +G1 X506.443384 Y76.342946 +G1 X506.641100 Y75.149797 +G1 X506.776861 Y73.948523 +G1 X506.850609 Y72.742290 +G1 X506.862288 Y71.534266 +G1 X506.811840 Y70.327616 +G1 X506.699209 Y69.125508 +G1 X506.524338 Y67.931109 +G1 X506.287170 Y66.747586 +G1 X505.987648 Y65.578105 +G1 X505.625715 Y64.425833 +G1 X505.201314 Y63.293937 +G1 X504.714389 Y62.185583 +G1 X504.164882 Y61.103940 +G1 X503.552737 Y60.052172 +G1 X502.877897 Y59.033448 +G1 X502.631400 Y58.691424 +G1 X501.834166 Y57.676200 +G1 X500.975509 Y56.711182 +G1 X500.059374 Y55.799326 +G1 X499.089706 Y54.943591 +G1 X498.070449 Y54.146934 +G1 X497.005551 Y53.412312 +G1 X495.898955 Y52.742684 +G1 X494.754608 Y52.141005 +G1 X493.576453 Y51.610235 +G1 X492.420900 Y51.171402 +G1 X491.256261 Y50.800496 +G1 X490.046486 Y50.487562 +G1 X489.041826 Y50.292926 +G1 X488.249010 Y50.190254 +G1 X487.850310 Y50.159818 +G1 X487.501187 Y50.148143 +G1 X487.166753 Y50.148460 +G1 X486.812124 Y50.153996 +G1 X486.402415 Y50.157981 +G1 X486.352700 Y50.158034 +G1 X485.946313 Y50.155450 +G1 X485.603518 Y50.150035 +G1 X485.297799 Y50.145299 +G1 X485.002642 Y50.144751 +G1 X484.658523 Y50.153171 +G1 X484.266750 Y50.175084 +G1 X483.681500 Y50.237723 +G1 X483.057213 Y50.342054 +G1 X482.414085 Y50.479956 +G1 X481.772314 Y50.643310 +G1 X481.152097 Y50.823994 +G1 X480.573629 Y51.013888 +G1 X480.474130 Y51.048907 +G1 X479.446845 Y51.451397 +G1 X478.448313 Y51.919292 +G1 X477.484378 Y52.453379 +G1 X476.643013 Y52.997015 +G1 X475.839460 Y53.596597 +G1 X475.165210 Y54.172697 +G1 X474.656373 Y54.680138 +G1 X474.169614 Y55.247174 +G1 X473.709889 Y55.856798 +G1 X473.282152 Y56.492003 +G1 X472.891359 Y57.135784 +G1 X472.542467 Y57.771133 +G1 X472.240430 Y58.381044 +G1 X471.990203 Y58.948511 +G1 X471.940720 Y59.070686 +G1 X472.946902 Y58.548471 +G1 X474.013812 Y58.032249 +G1 X475.126649 Y57.547450 +G1 X476.270614 Y57.119503 +G1 X477.325138 Y56.801194 +G1 X478.286149 Y56.586910 +G1 X479.154467 Y56.466657 +G1 X479.933981 Y56.428334 +G1 X480.284480 Y56.435575 +G1 X481.191522 Y56.515431 +G1 X482.090001 Y56.673912 +G1 X482.971424 Y56.909511 +G1 X483.750772 Y57.189343 +G1 X484.502626 Y57.530531 +G1 X485.220605 Y57.931941 +G1 X485.898330 Y58.392441 +G1 X486.529419 Y58.910899 +G1 X487.107492 Y59.486181 +G1 X487.581639 Y60.057524 +G1 X488.001905 Y60.674042 +G1 X488.363495 Y61.334884 +G1 X488.661617 Y62.039201 +G1 X488.749620 Y62.294416 +G1 X488.949459 Y63.007126 +G1 X489.064201 Y63.640857 +G1 X489.111045 Y64.277684 +G1 X489.099680 Y64.759630 +G1 X489.032856 Y65.509608 +G1 X488.924892 Y66.212851 +G1 X488.763549 Y66.893215 +G1 X488.536587 Y67.574560 +G1 X488.263016 Y68.214891 +G1 X487.998110 Y68.741886 +G1 X487.581207 Y69.449300 +G1 X487.110628 Y70.114282 +G1 X486.590498 Y70.737085 +G1 X486.024942 Y71.317962 +G1 X485.418086 Y71.857165 +G1 X484.774055 Y72.354946 +G1 X484.096975 Y72.811560 +G1 X483.390970 Y73.227257 +G1 X482.660165 Y73.602292 +G1 X481.908688 Y73.936916 +G1 X481.140661 Y74.231383 +G1 X480.360212 Y74.485944 +G1 X479.571464 Y74.700854 +G1 X478.778545 Y74.876364 +G1 X477.985577 Y75.012727 +G1 X477.196689 Y75.110196 +G1 X476.416003 Y75.169024 +G1 X475.922960 Y75.186504 +G1 X474.859747 Y75.168112 +G1 X473.787029 Y75.073336 +G1 X472.709773 Y74.905050 +G1 X471.632948 Y74.666134 +G1 X470.561519 Y74.359463 +G1 X469.500456 Y73.987914 +G1 X468.454724 Y73.554365 +G1 X467.429293 Y73.061693 +G1 X466.429129 Y72.512774 +G1 X465.459200 Y71.910486 +G1 X464.524472 Y71.257705 +G1 X463.629915 Y70.557308 +G1 X462.780495 Y69.812174 +G1 X461.981179 Y69.025177 +G1 X461.543900 Y68.552250 +G1 X460.891715 Y67.765996 +G1 X460.292143 Y66.931872 +G1 X459.744788 Y66.055906 +G1 X459.249251 Y65.144128 +G1 X458.805137 Y64.202568 +G1 X458.412047 Y63.237255 +G1 X458.069584 Y62.254218 +G1 X457.777351 Y61.259488 +G1 X457.534950 Y60.259095 +G1 X457.341984 Y59.259066 +G1 X457.203760 Y58.312160 +G1 X457.141173 Y57.820944 +G1 X457.085671 Y57.395084 +G1 X457.038907 Y57.009460 +G1 X457.002535 Y56.638949 +G1 X456.978210 Y56.258430 +G1 X456.967586 Y55.842780 +G1 X456.970070 Y55.467692 +G1 X456.987887 Y55.074097 +G1 X457.020033 Y54.741240 +G1 X457.059692 Y54.438950 +G1 X457.100048 Y54.137056 +G1 X457.134286 Y53.805390 +G1 X457.149460 Y53.571377 +G1 X457.205034 Y52.867958 +G1 X457.300830 Y52.113883 +G1 X457.428781 Y51.337193 +G1 X457.580818 Y50.565932 +G1 X457.748874 Y49.828142 +G1 X457.857660 Y49.399495 +G1 X458.225895 Y48.145885 +G1 X458.663605 Y46.907336 +G1 X459.169446 Y45.690104 +G1 X459.742076 Y44.500447 +G1 X460.380152 Y43.344619 +G1 X461.082330 Y42.228878 +G1 X461.847268 Y41.159479 +G1 X462.595996 Y40.232777 +G1 X462.871320 Y39.917931 +G1 X463.853850 Y38.869353 +G1 X464.885697 Y37.869072 +G1 X465.964416 Y36.919557 +G1 X467.087561 Y36.023276 +G1 X468.252687 Y35.182696 +G1 X469.457347 Y34.400285 +G1 X470.699097 Y33.678512 +G1 X471.975491 Y33.019843 +G1 X473.284083 Y32.426748 +G1 X474.622428 Y31.901695 +G1 X475.922960 Y31.467008 +G1 X477.381137 Y31.054004 +G1 X478.860340 Y30.707527 +G1 X480.217424 Y30.459027 +G1 X481.580842 Y30.281912 +G1 X481.611900 Y30.278774 +G1 X482.096818 Y30.243179 +G1 X482.559460 Y30.212483 +G1 X482.749690 Y30.192674 +G1 X483.322835 Y30.121477 +G1 X483.879030 Y30.070377 +G1 X484.266740 Y30.058034 +G1 X484.631877 Y30.061417 +G1 X484.937525 Y30.075901 +G1 X485.210925 Y30.099668 +G1 X485.479319 Y30.130895 +G1 X485.769948 Y30.167762 +G1 X485.973420 Y30.192674 +G1 X486.442725 Y30.230830 +G1 X486.881933 Y30.249563 +G1 X487.300840 Y30.278984 +G1 X488.289331 Y30.409251 +G1 X489.291436 Y30.599560 +G1 X490.284329 Y30.836377 +G1 X491.093470 Y31.061027 +G1 X492.241913 Y31.434166 +G1 X493.361729 Y31.866832 +G1 X494.452991 Y32.356032 +G1 X495.515773 Y32.898775 +G1 X496.550149 Y33.492068 +G1 X497.556192 Y34.132919 +G1 X498.533977 Y34.818338 +G1 X499.483578 Y35.545331 +G1 X500.405068 Y36.310906 +G1 X501.298520 Y37.112072 +G1 X502.164009 Y37.945837 +G1 X503.001609 Y38.809208 +G1 X503.811393 Y39.699195 +G1 X504.593435 Y40.612803 +G1 X505.347809 Y41.547043 +G1 X506.074589 Y42.498921 +G1 X506.773849 Y43.465447 +G1 X507.206630 Y44.089835 +G1 X507.552310 Y44.621163 +G1 X507.914773 Y45.220464 +G1 X508.291135 Y45.875515 +G1 X508.678509 Y46.574093 +G1 X509.074011 Y47.303977 +G1 X509.474756 Y48.052942 +G1 X509.877859 Y48.808767 +G1 X510.320552 Y49.633509 +G1 X510.758768 Y50.435493 +G1 X511.188666 Y51.198451 +G1 X511.606406 Y51.906114 +G1 X511.972388 Y52.487772 +G1 X512.271890 Y52.927909 +G1 X512.262074 Y52.888755 +G1 X512.233873 Y52.776123 +G1 X512.189162 Y52.597260 +G1 X512.129813 Y52.359413 +G1 X512.057700 Y52.069829 +G1 X511.974696 Y51.735754 +G1 X511.882674 Y51.364436 +G1 X511.783507 Y50.963120 +G1 X511.679069 Y50.539053 +G1 X511.571233 Y50.099483 +G1 X511.461872 Y49.651656 +G1 X511.342049 Y49.158158 +G1 X511.213706 Y48.625411 +G1 X511.092208 Y48.115693 +G1 X510.980875 Y47.641842 +G1 X510.883023 Y47.216698 +G1 X510.801973 Y46.853097 +G1 X510.745662 Y46.586760 +G1 X510.739270 Y46.555039 +G1 X510.506771 Y45.342969 +G1 X510.281444 Y44.071444 +G1 X510.066822 Y42.763654 +G1 X509.866439 Y41.442788 +G1 X509.683827 Y40.132038 +G1 X509.522519 Y38.854594 +G1 X509.386050 Y37.633647 +G1 X509.330310 Y37.073475 +G1 X509.287094 Y36.373750 +G1 X509.275032 Y35.623289 +G1 X509.281397 Y34.857783 +G1 X509.293459 Y34.112925 +G1 X509.298310 Y33.660119 +G1 X509.313326 Y33.043667 +G1 X509.365021 Y32.439849 +G1 X509.378510 Y32.332693 +G1 X509.446683 Y31.759499 +G1 X509.498365 Y31.233438 +G1 X509.501960 Y31.194904 +G1 X509.628561 Y30.074531 +G1 X509.800971 Y28.916246 +G1 X510.013513 Y27.738814 +G1 X510.260505 Y26.561004 +G1 X510.536271 Y25.401580 +G1 X510.835129 Y24.279309 +G1 X511.087280 Y23.420028 +G1 X511.591598 Y21.909908 +G1 X512.171109 Y20.423660 +G1 X512.823375 Y18.964690 +G1 X513.545957 Y17.536404 +G1 X514.336418 Y16.142207 +G1 X515.192318 Y14.785506 +G1 X516.111220 Y13.469706 +G1 X517.090685 Y12.198214 +G1 X518.128274 Y10.974435 +G1 X519.221549 Y9.801775 +G1 X520.368072 Y8.683640 +G1 X521.565405 Y7.623436 +G1 X521.624130 Y7.574048 +G1 X522.668903 Y6.739311 +G1 X523.766203 Y5.943100 +G1 X524.910110 Y5.188837 +G1 X526.094705 Y4.479941 +G1 X527.314070 Y3.819835 +G1 X528.562285 Y3.211939 +G1 X529.833431 Y2.659674 +G1 X531.121589 Y2.166462 +G1 X532.420841 Y1.735724 +G1 X533.725267 Y1.370881 +G1 X535.028949 Y1.075353 +G1 X536.325967 Y0.852562 +G1 X537.610402 Y0.705929 +G1 X537.932430 Y0.681326 +G1 X538.261177 Y0.665386 +G1 X538.534053 Y0.662377 +G1 X538.787682 Y0.662984 +G1 X539.088157 Y0.656710 +G1 X539.259850 Y0.647226 +G1 X539.628893 Y0.609003 +G1 X539.948697 Y0.563265 +G1 X540.272860 Y0.529239 +G1 X540.587270 Y0.523766 +G1 X540.918834 Y0.547765 +G1 X541.215558 Y0.589052 +G1 X541.538637 Y0.631219 +G1 X541.725060 Y0.647226 +G1 X542.089537 Y0.662981 +G1 X542.407324 Y0.663812 +G1 X542.733109 Y0.663293 +G1 X543.052480 Y0.671726 +G1 X543.738206 Y0.724732 +G1 X544.470836 Y0.821446 +G1 X545.234668 Y0.955141 +G1 X546.014000 Y1.119090 +G1 X546.793130 Y1.306567 +G1 X547.556356 Y1.510844 +G1 X548.287977 Y1.725196 +G1 X548.972290 Y1.942895 +G1 X549.120670 Y1.992506 +G1 X550.379941 Y2.457148 +G1 X551.620231 Y2.993376 +G1 X552.837004 Y3.597608 +G1 X554.025727 Y4.266259 +G1 X555.181863 Y4.995747 +G1 X556.300880 Y5.782487 +G1 X557.378242 Y6.622897 +G1 X558.409414 Y7.513392 +G1 X559.389863 Y8.450389 +G1 X560.276500 Y9.387370 +G1 X561.145642 Y10.411395 +G1 X561.947928 Y11.476060 +G1 X562.682905 Y12.578215 +G1 X563.350124 Y13.714711 +G1 X563.949132 Y14.882399 +G1 X564.479480 Y16.078129 +G1 X564.940715 Y17.298752 +G1 X565.332386 Y18.541119 +G1 X565.654044 Y19.802080 +G1 X565.905236 Y21.078486 +G1 X566.085511 Y22.367188 +G1 X566.194418 Y23.665036 +G1 X566.231507 Y24.968882 +G1 X566.196326 Y26.275575 +G1 X566.088423 Y27.581966 +G1 X565.907349 Y28.884907 +G1 X565.652652 Y30.181247 +G1 X565.450970 Y31.005340 +G1 X565.110211 Y32.155230 +G1 X564.703460 Y33.277180 +G1 X564.233110 Y34.369122 +G1 X563.701554 Y35.428989 +G1 X563.111184 Y36.454711 +G1 X562.464392 Y37.444220 +G1 X561.763572 Y38.395449 +G1 X561.011114 Y39.306329 +G1 X560.209412 Y40.174792 +G1 X559.360859 Y40.998769 +G1 X558.467846 Y41.776193 +G1 X557.532766 Y42.504995 +G1 X556.558012 Y43.183107 +G1 X555.545975 Y43.808461 +G1 X554.499049 Y44.378988 +G1 X553.419626 Y44.892620 +G1 X552.310098 Y45.347289 +G1 X551.585880 Y45.606185 +G1 X550.563637 Y45.913334 +G1 X549.528939 Y46.153488 +G1 X548.485014 Y46.332166 +G1 X547.435094 Y46.454886 +G1 X546.382407 Y46.527165 +G1 X545.330185 Y46.554522 +G1 X545.138420 Y46.555101 +G1 X544.637422 Y46.555690 +G1 X544.178438 Y46.546593 +G1 X543.707743 Y46.510977 +G1 X543.621370 Y46.500911 +G1 X542.959095 Y46.402876 +G1 X542.253691 Y46.268583 +G1 X541.534320 Y46.105171 +G1 X540.830143 Y45.919781 +G1 X540.397630 Y45.791879 +G1 X539.285744 Y45.410269 +G1 X538.200315 Y44.957911 +G1 X537.243805 Y44.481279 +G1 X536.322817 Y43.938672 +G1 X535.521854 Y43.385134 +G1 X534.760510 Y42.771431 +G1 X534.140560 Y42.192872 +G1 X533.705026 Y41.736978 +G1 X533.256241 Y41.221242 +G1 X532.818691 Y40.661549 +G1 X532.416861 Y40.073785 +G1 X532.075237 Y39.473836 +G1 X531.837519 Y38.931222 +G1 X531.706966 Y38.493575 +G1 X531.647168 Y38.072906 +G1 X531.662944 Y37.710882 +G1 X531.674600 Y37.642479 +G1 X532.171425 Y37.915931 +G1 X532.732069 Y38.216839 +G1 X533.341778 Y38.531182 +G1 X533.985796 Y38.844941 +G1 X534.649367 Y39.144094 +G1 X535.317738 Y39.414621 +G1 X535.846490 Y39.601177 +G1 X536.778696 Y39.868036 +G1 X537.721186 Y40.060949 +G1 X538.585051 Y40.167288 +G1 X539.453913 Y40.203391 +G1 X540.326104 Y40.164911 +G1 X541.120490 Y40.061553 +G1 X541.725060 Y39.937202 +G1 X542.527305 Y39.709990 +G1 X543.310489 Y39.417301 +G1 X544.067147 Y39.061508 +G1 X544.789820 Y38.644987 +G1 X545.471043 Y38.170110 +G1 X546.103356 Y37.639253 +G1 X546.679296 Y37.054789 +G1 X547.147680 Y36.478937 +G1 X547.557702 Y35.862529 +G1 X547.903754 Y35.207348 +G1 X548.158119 Y34.579583 +G1 X548.350772 Y33.922588 +G1 X548.477500 Y33.237704 +G1 X548.534092 Y32.526271 +G1 X548.536800 Y32.332798 +G1 X548.502344 Y31.605334 +G1 X548.401212 Y30.878148 +G1 X548.237245 Y30.156533 +G1 X548.014287 Y29.445785 +G1 X547.736180 Y28.751197 +G1 X547.406766 Y28.078061 +G1 X547.029887 Y27.431674 +G1 X546.609385 Y26.817327 +G1 X546.149103 Y26.240315 +G1 X545.674890 Y25.727943 +G1 X544.966580 Y25.068206 +G1 X544.204182 Y24.454258 +G1 X543.395039 Y23.890067 +G1 X542.546494 Y23.379600 +G1 X541.665890 Y22.926823 +G1 X540.760569 Y22.535705 +G1 X539.837873 Y22.210212 +G1 X538.905147 Y21.954311 +G1 X538.690950 Y21.905927 +G1 X537.911494 Y21.766269 +G1 X537.173900 Y21.662057 +G1 X536.678886 Y21.598541 +G1 X536.225838 Y21.556872 +G1 X535.770344 Y21.533302 +G1 X535.267994 Y21.524087 +G1 X534.898330 Y21.524006 +G1 X534.453734 Y21.533543 +G1 X534.062847 Y21.557608 +G1 X533.687046 Y21.595988 +G1 X533.287708 Y21.648468 +G1 X533.191650 Y21.662057 +G1 X532.210849 Y21.822783 +G1 X531.188726 Y22.034102 +G1 X530.155165 Y22.296226 +G1 X529.140055 Y22.609369 +G1 X528.258386 Y22.938496 +G1 X528.071600 Y23.016777 +G1 X527.031504 Y23.500879 +G1 X526.027175 Y24.045883 +G1 X525.060733 Y24.649105 +G1 X524.134299 Y25.307860 +G1 X523.249990 Y26.019462 +G1 X522.409926 Y26.781229 +G1 X521.616227 Y27.590475 +G1 X520.871012 Y28.444515 +G1 X520.176401 Y29.340665 +G1 X519.534513 Y30.276241 +G1 X518.947467 Y31.248557 +G1 X518.417383 Y32.254929 +G1 X517.946380 Y33.292673 +G1 X517.536578 Y34.359105 +G1 X517.328420 Y34.987638 +G1 X517.007560 Y36.131121 +G1 X516.754728 Y37.282767 +G1 X516.568608 Y38.440251 +G1 X516.447887 Y39.601247 +G1 X516.391249 Y40.763428 +G1 X516.397380 Y41.924470 +G1 X516.464965 Y43.082046 +G1 X516.592689 Y44.233831 +G1 X516.779237 Y45.377498 +G1 X517.023296 Y46.510722 +G1 X517.323549 Y47.631177 +G1 X517.678683 Y48.736537 +G1 X518.087382 Y49.824477 +G1 X518.548333 Y50.892670 +G1 X519.060219 Y51.938790 +G1 X519.621727 Y52.960512 +G1 X520.231542 Y53.955510 +G1 X520.888348 Y54.921458 +G1 X521.590832 Y55.856031 +G1 X522.337679 Y56.756902 +G1 X523.127573 Y57.621745 +G1 X523.959201 Y58.448235 +G1 X524.831247 Y59.234046 +G1 X525.742396 Y59.976851 +G1 X526.691335 Y60.674326 +G1 X527.502710 Y61.214595 +G1 X528.578070 Y61.857820 +G1 X529.692761 Y62.447169 +G1 X530.840574 Y62.981607 +G1 X532.015298 Y63.460099 +G1 X533.210723 Y63.881609 +G1 X534.420640 Y64.245103 +G1 X535.638837 Y64.549544 +G1 X536.225750 Y64.674610 +G1 X537.467831 Y64.883177 +G1 X538.730319 Y65.022307 +G1 X540.002806 Y65.103668 +G1 X541.274889 Y65.138929 +G1 X542.536160 Y65.139759 +G1 X542.673210 Y65.138256 +G1 X543.743590 Y65.090909 +G1 X544.818834 Y64.976013 +G1 X545.894901 Y64.796247 +G1 X546.967752 Y64.554288 +G1 X548.033347 Y64.252814 +G1 X549.087647 Y63.894502 +G1 X550.126611 Y63.482030 +G1 X551.146201 Y63.018076 +G1 X552.142377 Y62.505317 +G1 X553.111098 Y61.946431 +G1 X554.048326 Y61.344095 +G1 X554.950020 Y60.700988 +G1 X555.812141 Y60.019787 +G1 X556.630650 Y59.303170 +G1 X557.082350 Y58.873790 +G1 X557.888037 Y58.036085 +G1 X558.647409 Y57.152930 +G1 X559.362155 Y56.230436 +G1 X560.033963 Y55.274713 +G1 X560.664522 Y54.291871 +G1 X561.255522 Y53.288021 +G1 X561.808651 Y52.269273 +G1 X562.325598 Y51.241738 +G1 X562.808053 Y50.211525 +G1 X562.832160 Y50.158148 +G1 X563.406265 Y48.792104 +G1 X563.938966 Y47.390717 +G1 X564.459762 Y45.975406 +G1 X565.054095 Y44.428046 +G1 X565.645911 Y43.053218 +G1 X566.193761 Y41.955669 +G1 X566.377150 Y41.624736 +G1 X565.265816 Y45.064561 +G1 X564.386840 Y47.954939 +G1 X563.786557 Y50.147737 +G1 X563.307994 Y52.152643 +G1 X562.944061 Y53.981721 +G1 X562.683735 Y55.647563 +G1 X562.514180 Y57.162769 +G1 X562.416404 Y58.677216 +G1 X562.395040 Y59.639712 +G1 X562.352050 Y62.411352 +G1 X562.383494 Y63.574007 +G1 X562.475340 Y64.570131 +G1 X562.819248 Y66.896485 +G1 X563.204188 Y68.988634 +G1 X563.623823 Y70.868161 +G1 X564.070373 Y72.555544 +G1 X564.585549 Y74.220217 +G1 X565.118868 Y75.711857 +G1 X565.719074 Y77.180992 +G1 X566.391012 Y78.625844 +G1 X567.068186 Y79.916777 +G1 X567.812285 Y81.184835 +G1 X568.626947 Y82.428682 +G1 X568.735820 Y82.585102 +G1 X569.651213 Y83.826198 +G1 X570.624302 Y85.020305 +G1 X571.652557 Y86.165126 +G1 X572.733448 Y87.258366 +G1 X573.864442 Y88.297725 +G1 X575.043010 Y89.280907 +G1 X576.266621 Y90.205615 +G1 X577.532744 Y91.069552 +G1 X578.838848 Y91.870420 +G1 X580.182403 Y92.605922 +G1 X581.560878 Y93.273762 +G1 X582.971742 Y93.871641 +G1 X584.412464 Y94.397263 +G1 X585.745993 Y94.810466 +G1 X587.100205 Y95.160328 +G1 X588.473199 Y95.445123 +G1 X588.943260 Y95.526709 +G1 X589.844926 Y95.669766 +G1 X590.698737 Y95.787947 +G1 X590.839570 Y95.805156 +G1 X591.727696 Y95.871199 +G1 X592.651226 Y95.881706 +G1 X593.610365 Y95.867583 +G1 X594.442570 Y95.859294 +G1 X594.979180 Y95.862046 +G1 X595.459264 Y95.861248 +G1 X595.926039 Y95.843319 +G1 X596.338880 Y95.805155 +G1 X597.248162 Y95.682345 +G1 X598.206142 Y95.523276 +G1 X599.175375 Y95.328976 +G1 X600.118417 Y95.100474 +G1 X600.321140 Y95.045020 +G1 X601.675286 Y94.631583 +G1 X603.008506 Y94.154963 +G1 X604.316993 Y93.615643 +G1 X605.596938 Y93.014102 +G1 X606.844531 Y92.350823 +G1 X608.055965 Y91.626287 +G1 X609.227431 Y90.840975 +G1 X610.355119 Y89.995369 +G1 X611.435222 Y89.089949 +G1 X612.463930 Y88.125198 +G1 X613.351316 Y87.197069 +G1 X614.190218 Y86.220666 +G1 X614.977775 Y85.196348 +G1 X615.711124 Y84.124479 +G1 X616.387405 Y83.005419 +G1 X616.410590 Y82.964365 +G1 X616.978846 Y81.886472 +G1 X617.485488 Y80.781452 +G1 X617.930459 Y79.652473 +G1 X618.313701 Y78.502701 +G1 X618.635158 Y77.335303 +G1 X618.894774 Y76.153446 +G1 X619.092490 Y74.960297 +G1 X619.228251 Y73.759023 +G1 X619.301999 Y72.552790 +G1 X619.313678 Y71.344766 +G1 X619.263230 Y70.138116 +G1 X619.150599 Y68.936008 +G1 X618.975728 Y67.741609 +G1 X618.738560 Y66.558086 +G1 X618.439038 Y65.388605 +G1 X618.077105 Y64.236333 +G1 X617.652704 Y63.104437 +G1 X617.165779 Y61.996083 +G1 X616.616272 Y60.914440 +G1 X616.004127 Y59.862672 +G1 X615.329287 Y58.843948 +G1 X615.082790 Y58.501924 +G1 X614.285556 Y57.486700 +G1 X613.426899 Y56.521682 +G1 X612.510764 Y55.609826 +G1 X611.541096 Y54.754091 +G1 X610.521839 Y53.957434 +G1 X609.456941 Y53.222812 +G1 X608.350345 Y52.553184 +G1 X607.205998 Y51.951505 +G1 X606.027843 Y51.420735 +G1 X604.872290 Y50.981902 +G1 X603.707651 Y50.610996 +G1 X602.497876 Y50.298062 +G1 X601.493216 Y50.103426 +G1 X600.700400 Y50.000754 +G1 X600.301700 Y49.970318 +G1 X599.952577 Y49.958643 +G1 X599.618143 Y49.958960 +G1 X599.263514 Y49.964496 +G1 X598.853805 Y49.968481 +G1 X598.804090 Y49.968534 +G1 X598.397703 Y49.965950 +G1 X598.054908 Y49.960535 +G1 X597.749189 Y49.955799 +G1 X597.454032 Y49.955251 +G1 X597.109913 Y49.963671 +G1 X596.718140 Y49.985584 +G1 X596.132890 Y50.048223 +G1 X595.508603 Y50.152554 +G1 X594.865475 Y50.290456 +G1 X594.223704 Y50.453810 +G1 X593.603487 Y50.634494 +G1 X593.025019 Y50.824388 +G1 X592.925520 Y50.859407 +G1 X591.898235 Y51.261897 +G1 X590.899703 Y51.729792 +G1 X589.935768 Y52.263879 +G1 X589.094403 Y52.807515 +G1 X588.290850 Y53.407097 +G1 X587.616600 Y53.983197 +G1 X587.107763 Y54.490638 +G1 X586.621004 Y55.057674 +G1 X586.161279 Y55.667298 +G1 X585.733542 Y56.302503 +G1 X585.342749 Y56.946284 +G1 X584.993857 Y57.581633 +G1 X584.691820 Y58.191544 +G1 X584.441593 Y58.759011 +G1 X584.392110 Y58.881186 +G1 X585.398292 Y58.358971 +G1 X586.465202 Y57.842749 +G1 X587.578039 Y57.357950 +G1 X588.722004 Y56.930003 +G1 X589.776528 Y56.611694 +G1 X590.737539 Y56.397410 +G1 X591.605857 Y56.277157 +G1 X592.385371 Y56.238834 +G1 X592.735870 Y56.246075 +G1 X593.642912 Y56.325931 +G1 X594.541391 Y56.484412 +G1 X595.422814 Y56.720011 +G1 X596.202162 Y56.999843 +G1 X596.954016 Y57.341031 +G1 X597.671995 Y57.742441 +G1 X598.349720 Y58.202941 +G1 X598.980809 Y58.721399 +G1 X599.558882 Y59.296681 +G1 X600.033029 Y59.868024 +G1 X600.453295 Y60.484542 +G1 X600.814885 Y61.145384 +G1 X601.113007 Y61.849701 +G1 X601.201010 Y62.104916 +G1 X601.400849 Y62.817626 +G1 X601.515591 Y63.451357 +G1 X601.562435 Y64.088184 +G1 X601.551070 Y64.570130 +G1 X601.484282 Y65.320108 +G1 X601.376327 Y66.023351 +G1 X601.214974 Y66.703715 +G1 X600.987994 Y67.385060 +G1 X600.714410 Y68.025391 +G1 X600.449500 Y68.552386 +G1 X600.032597 Y69.259800 +G1 X599.562018 Y69.924782 +G1 X599.041888 Y70.547585 +G1 X598.476332 Y71.128462 +G1 X597.869476 Y71.667665 +G1 X597.225445 Y72.165446 +G1 X596.548365 Y72.622060 +G1 X595.842360 Y73.037757 +G1 X595.111555 Y73.412792 +G1 X594.360078 Y73.747416 +G1 X593.592051 Y74.041883 +G1 X592.811602 Y74.296444 +G1 X592.022854 Y74.511354 +G1 X591.229935 Y74.686864 +G1 X590.436967 Y74.823227 +G1 X589.648079 Y74.920696 +G1 X588.867393 Y74.979524 +G1 X588.374350 Y74.997004 +G1 X587.311137 Y74.978612 +G1 X586.238419 Y74.883836 +G1 X585.161163 Y74.715550 +G1 X584.084338 Y74.476634 +G1 X583.012909 Y74.169963 +G1 X581.951846 Y73.798414 +G1 X580.906114 Y73.364865 +G1 X579.880683 Y72.872193 +G1 X578.880519 Y72.323274 +G1 X577.910590 Y71.720986 +G1 X576.975862 Y71.068205 +G1 X576.081305 Y70.367808 +G1 X575.231885 Y69.622674 +G1 X574.432569 Y68.835677 +G1 X573.995290 Y68.362750 +G1 X573.343105 Y67.576496 +G1 X572.743533 Y66.742372 +G1 X572.196178 Y65.866406 +G1 X571.700641 Y64.954628 +G1 X571.256527 Y64.013068 +G1 X570.863437 Y63.047755 +G1 X570.520974 Y62.064718 +G1 X570.228741 Y61.069988 +G1 X569.986340 Y60.069595 +G1 X569.793374 Y59.069566 +G1 X569.655150 Y58.122660 +G1 X569.592563 Y57.631444 +G1 X569.537061 Y57.205584 +G1 X569.490297 Y56.819960 +G1 X569.453925 Y56.449449 +G1 X569.429600 Y56.068930 +G1 X569.418976 Y55.653280 +G1 X569.421460 Y55.278192 +G1 X569.439277 Y54.884597 +G1 X569.471423 Y54.551740 +G1 X569.511082 Y54.249450 +G1 X569.551438 Y53.947556 +G1 X569.585676 Y53.615890 +G1 X569.600850 Y53.381877 +G1 X569.656424 Y52.678458 +G1 X569.752220 Y51.924383 +G1 X569.880171 Y51.147693 +G1 X570.032208 Y50.376432 +G1 X570.200264 Y49.638642 +G1 X570.309050 Y49.209995 +G1 X570.677285 Y47.956385 +G1 X571.114995 Y46.717836 +G1 X571.620836 Y45.500604 +G1 X572.193466 Y44.310947 +G1 X572.831542 Y43.155119 +G1 X573.533720 Y42.039378 +G1 X574.298658 Y40.969979 +G1 X575.047386 Y40.043277 +G1 X575.322710 Y39.728431 +G1 X576.305240 Y38.679853 +G1 X577.337087 Y37.679572 +G1 X578.415806 Y36.730057 +G1 X579.538951 Y35.833776 +G1 X580.704077 Y34.993196 +G1 X581.908737 Y34.210785 +G1 X583.150487 Y33.489012 +G1 X584.426881 Y32.830343 +G1 X585.735473 Y32.237248 +G1 X587.073818 Y31.712195 +G1 X588.374350 Y31.277508 +G1 X589.832527 Y30.864504 +G1 X591.311730 Y30.518027 +G1 X592.668814 Y30.269527 +G1 X594.032232 Y30.092412 +G1 X594.063290 Y30.089274 +G1 X594.548208 Y30.053679 +G1 X595.010850 Y30.022983 +G1 X595.201080 Y30.003174 +G1 X595.774225 Y29.931977 +G1 X596.330420 Y29.880877 +G1 X596.718130 Y29.868534 +G1 X597.083267 Y29.871917 +G1 X597.388915 Y29.886401 +G1 X597.662315 Y29.910168 +G1 X597.930709 Y29.941395 +G1 X598.221338 Y29.978262 +G1 X598.424810 Y30.003174 +G1 X598.894115 Y30.041330 +G1 X599.333323 Y30.060063 +G1 X599.752230 Y30.089484 +G1 X600.740721 Y30.219751 +G1 X601.742826 Y30.410060 +G1 X602.735719 Y30.646877 +G1 X603.544860 Y30.871527 +G1 X604.693303 Y31.244666 +G1 X605.813119 Y31.677332 +G1 X606.904381 Y32.166532 +G1 X607.967163 Y32.709275 +G1 X609.001539 Y33.302568 +G1 X610.007582 Y33.943419 +G1 X610.985367 Y34.628838 +G1 X611.934968 Y35.355831 +G1 X612.856458 Y36.121406 +G1 X613.749910 Y36.922572 +G1 X614.615399 Y37.756337 +G1 X615.452999 Y38.619708 +G1 X616.262783 Y39.509695 +G1 X617.044825 Y40.423303 +G1 X617.799199 Y41.357543 +G1 X618.525979 Y42.309421 +G1 X619.225239 Y43.275947 +G1 X619.658020 Y43.900335 +G1 X620.003700 Y44.431663 +G1 X620.366163 Y45.030964 +G1 X620.742525 Y45.686015 +G1 X621.129899 Y46.384593 +G1 X621.525401 Y47.114477 +G1 X621.926146 Y47.863442 +G1 X622.329249 Y48.619267 +G1 X622.771942 Y49.444009 +G1 X623.210158 Y50.245993 +G1 X623.640056 Y51.008951 +G1 X624.057796 Y51.716614 +G1 X624.423778 Y52.298272 +G1 X624.723280 Y52.738409 +G1 X624.713464 Y52.699255 +G1 X624.685263 Y52.586623 +G1 X624.640552 Y52.407760 +G1 X624.581203 Y52.169913 +G1 X624.509090 Y51.880329 +G1 X624.426086 Y51.546254 +G1 X624.334064 Y51.174936 +G1 X624.234897 Y50.773620 +G1 X624.130459 Y50.349553 +G1 X624.022623 Y49.909983 +G1 X623.913262 Y49.462156 +G1 X623.793439 Y48.968658 +G1 X623.665096 Y48.435911 +G1 X623.543598 Y47.926193 +G1 X623.432265 Y47.452342 +G1 X623.334413 Y47.027198 +G1 X623.253363 Y46.663597 +G1 X623.197052 Y46.397260 +G1 X623.190660 Y46.365539 +G1 X622.958161 Y45.153469 +G1 X622.732834 Y43.881944 +G1 X622.518212 Y42.574154 +G1 X622.317829 Y41.253288 +G1 X622.135217 Y39.942538 +G1 X621.973909 Y38.665094 +G1 X621.837440 Y37.444147 +G1 X621.781700 Y36.883975 +G1 X621.738445 Y36.184250 +G1 X621.726381 Y35.433789 +G1 X621.732762 Y34.668283 +G1 X621.744845 Y33.923425 +G1 X621.749700 Y33.470619 +G1 X621.764716 Y32.854167 +G1 X621.816411 Y32.250349 +G1 X621.829900 Y32.143193 +G1 X621.898073 Y31.569999 +G1 X621.949755 Y31.043938 +G1 X621.953350 Y31.005404 +G1 X622.079951 Y29.885031 +G1 X622.252361 Y28.726746 +G1 X622.464903 Y27.549314 +G1 X622.711895 Y26.371504 +G1 X622.987661 Y25.212080 +G1 X623.286519 Y24.089809 +G1 X623.538670 Y23.230528 +G1 X624.042988 Y21.720408 +G1 X624.622499 Y20.234160 +G1 X625.274765 Y18.775190 +G1 X625.997347 Y17.346904 +G1 X626.787808 Y15.952707 +G1 X627.643708 Y14.596006 +G1 X628.562610 Y13.280206 +G1 X629.542075 Y12.008714 +G1 X630.579664 Y10.784935 +G1 X631.672939 Y9.612275 +G1 X632.819462 Y8.494140 +G1 X634.016795 Y7.433936 +G1 X634.075520 Y7.384548 +G1 X635.120293 Y6.549811 +G1 X636.217593 Y5.753600 +G1 X637.361500 Y4.999337 +G1 X638.546095 Y4.290441 +G1 X639.765460 Y3.630335 +G1 X641.013675 Y3.022439 +G1 X642.284821 Y2.470174 +G1 X643.572979 Y1.976962 +G1 X644.872231 Y1.546224 +G1 X646.176657 Y1.181381 +G1 X647.480339 Y0.885853 +G1 X648.777357 Y0.663062 +G1 X650.061792 Y0.516429 +G1 X650.383820 Y0.491826 +G1 X650.712567 Y0.475886 +G1 X650.985443 Y0.472877 +G1 X651.239072 Y0.473484 +G1 X651.539547 Y0.467210 +G1 X651.711240 Y0.457726 +G1 X652.080283 Y0.419503 +G1 X652.400087 Y0.373765 +G1 X652.724250 Y0.339739 +G1 X653.038660 Y0.334266 +G1 X653.370224 Y0.358265 +G1 X653.666948 Y0.399552 +G1 X653.990027 Y0.441719 +G1 X654.176450 Y0.457726 +G1 X654.540927 Y0.473481 +G1 X654.858714 Y0.474312 +G1 X655.184499 Y0.473793 +G1 X655.503870 Y0.482226 +G1 X656.189596 Y0.535232 +G1 X656.922226 Y0.631946 +G1 X657.686058 Y0.765641 +G1 X658.465390 Y0.929590 +G1 X659.244520 Y1.117067 +G1 X660.007746 Y1.321344 +G1 X660.739367 Y1.535696 +G1 X661.423680 Y1.753395 +G1 X661.572060 Y1.803006 +G1 X662.831331 Y2.267648 +G1 X664.071621 Y2.803876 +G1 X665.288394 Y3.408108 +G1 X666.477117 Y4.076759 +G1 X667.633253 Y4.806247 +G1 X668.752270 Y5.592987 +G1 X669.829632 Y6.433397 +G1 X670.860804 Y7.323892 +G1 X671.841253 Y8.260889 +G1 X672.727890 Y9.197870 +G1 X673.597032 Y10.221895 +G1 X674.399318 Y11.286560 +G1 X675.134295 Y12.388715 +G1 X675.801514 Y13.525211 +G1 X676.400522 Y14.692899 +G1 X676.930870 Y15.888629 +G1 X677.392105 Y17.109252 +G1 X677.783776 Y18.351619 +G1 X678.105434 Y19.612580 +G1 X678.356626 Y20.888986 +G1 X678.536901 Y22.177688 +G1 X678.645808 Y23.475536 +G1 X678.682897 Y24.779382 +G1 X678.647716 Y26.086075 +G1 X678.539813 Y27.392466 +G1 X678.358739 Y28.695407 +G1 X678.104042 Y29.991747 +G1 X677.902360 Y30.815840 +G1 X677.561601 Y31.965730 +G1 X677.154850 Y33.087680 +G1 X676.684500 Y34.179622 +G1 X676.152944 Y35.239489 +G1 X675.562574 Y36.265211 +G1 X674.915782 Y37.254720 +G1 X674.214962 Y38.205949 +G1 X673.462504 Y39.116829 +G1 X672.660802 Y39.985292 +G1 X671.812249 Y40.809269 +G1 X670.919236 Y41.586693 +G1 X669.984156 Y42.315495 +G1 X669.009402 Y42.993607 +G1 X667.997365 Y43.618961 +G1 X666.950439 Y44.189488 +G1 X665.871016 Y44.703120 +G1 X664.761488 Y45.157789 +G1 X664.037270 Y45.416685 +G1 X663.015027 Y45.723834 +G1 X661.980329 Y45.963988 +G1 X660.936404 Y46.142666 +G1 X659.886484 Y46.265386 +G1 X658.833797 Y46.337665 +G1 X657.781575 Y46.365022 +G1 X657.589810 Y46.365601 +G1 X657.088812 Y46.366190 +G1 X656.629828 Y46.357093 +G1 X656.159133 Y46.321477 +G1 X656.072760 Y46.311411 +G1 X655.410485 Y46.213376 +G1 X654.705081 Y46.079083 +G1 X653.985710 Y45.915671 +G1 X653.281533 Y45.730281 +G1 X652.849020 Y45.602379 +G1 X651.737134 Y45.220769 +G1 X650.651705 Y44.768411 +G1 X649.695195 Y44.291779 +G1 X648.774207 Y43.749172 +G1 X647.973244 Y43.195634 +G1 X647.211900 Y42.581931 +G1 X646.591950 Y42.003372 +G1 X646.156416 Y41.547478 +G1 X645.707631 Y41.031742 +G1 X645.270081 Y40.472049 +G1 X644.868251 Y39.884285 +G1 X644.526627 Y39.284336 +G1 X644.288909 Y38.741722 +G1 X644.158356 Y38.304075 +G1 X644.098558 Y37.883406 +G1 X644.114334 Y37.521382 +G1 X644.125990 Y37.452979 +G1 X644.622815 Y37.726431 +G1 X645.183459 Y38.027339 +G1 X645.793168 Y38.341682 +G1 X646.437186 Y38.655441 +G1 X647.100757 Y38.954594 +G1 X647.769128 Y39.225121 +G1 X648.297880 Y39.411677 +G1 X649.230086 Y39.678536 +G1 X650.172576 Y39.871449 +G1 X651.036441 Y39.977788 +G1 X651.905303 Y40.013891 +G1 X652.777494 Y39.975411 +G1 X653.571880 Y39.872053 +G1 X654.176450 Y39.747702 +G1 X654.978695 Y39.520490 +G1 X655.761879 Y39.227801 +G1 X656.518537 Y38.872008 +G1 X657.241210 Y38.455487 +G1 X657.922433 Y37.980610 +G1 X658.554746 Y37.449753 +G1 X659.130686 Y36.865289 +G1 X659.599070 Y36.289437 +G1 X660.009092 Y35.673029 +G1 X660.355144 Y35.017848 +G1 X660.609509 Y34.390083 +G1 X660.802162 Y33.733088 +G1 X660.928890 Y33.048204 +G1 X660.985482 Y32.336771 +G1 X660.988190 Y32.143298 +G1 X660.953734 Y31.415834 +G1 X660.852602 Y30.688648 +G1 X660.688635 Y29.967033 +G1 X660.465677 Y29.256285 +G1 X660.187570 Y28.561697 +G1 X659.858156 Y27.888561 +G1 X659.481277 Y27.242174 +G1 X659.060775 Y26.627827 +G1 X658.600493 Y26.050815 +G1 X658.126280 Y25.538443 +G1 X657.417970 Y24.878706 +G1 X656.655572 Y24.264758 +G1 X655.846429 Y23.700567 +G1 X654.997884 Y23.190100 +G1 X654.117280 Y22.737323 +G1 X653.211959 Y22.346205 +G1 X652.289263 Y22.020712 +G1 X651.356537 Y21.764811 +G1 X651.142340 Y21.716427 +G1 X650.362884 Y21.576769 +G1 X649.625290 Y21.472557 +G1 X649.130276 Y21.409041 +G1 X648.677228 Y21.367372 +G1 X648.221734 Y21.343802 +G1 X647.719384 Y21.334587 +G1 X647.349720 Y21.334506 +G1 X646.905124 Y21.344043 +G1 X646.514237 Y21.368108 +G1 X646.138436 Y21.406488 +G1 X645.739098 Y21.458968 +G1 X645.643040 Y21.472557 +G1 X644.662239 Y21.633283 +G1 X643.640116 Y21.844602 +G1 X642.606555 Y22.106726 +G1 X641.591445 Y22.419869 +G1 X640.709776 Y22.748996 +G1 X640.522990 Y22.827277 +G1 X639.482894 Y23.311379 +G1 X638.478565 Y23.856383 +G1 X637.512123 Y24.459605 +G1 X636.585689 Y25.118360 +G1 X635.701380 Y25.829962 +G1 X634.861316 Y26.591729 +G1 X634.067617 Y27.400975 +G1 X633.322402 Y28.255015 +G1 X632.627791 Y29.151165 +G1 X631.985903 Y30.086741 +G1 X631.398857 Y31.059057 +G1 X630.868773 Y32.065429 +G1 X630.397770 Y33.103173 +G1 X629.987968 Y34.169605 +G1 X629.779810 Y34.798138 +G1 X629.458950 Y35.941621 +G1 X629.206118 Y37.093267 +G1 X629.019998 Y38.250751 +G1 X628.899277 Y39.411747 +G1 X628.842639 Y40.573928 +G1 X628.848770 Y41.734970 +G1 X628.916355 Y42.892546 +G1 X629.044079 Y44.044331 +G1 X629.230627 Y45.187998 +G1 X629.474686 Y46.321222 +G1 X629.774939 Y47.441677 +G1 X630.130073 Y48.547037 +G1 X630.538772 Y49.634977 +G1 X630.999723 Y50.703170 +G1 X631.511609 Y51.749290 +G1 X632.073117 Y52.771012 +G1 X632.682932 Y53.766010 +G1 X633.339738 Y54.731958 +G1 X634.042222 Y55.666531 +G1 X634.789069 Y56.567402 +G1 X635.578963 Y57.432245 +G1 X636.410591 Y58.258735 +G1 X637.282637 Y59.044546 +G1 X638.193786 Y59.787351 +G1 X639.142725 Y60.484826 +G1 X639.954100 Y61.025095 +G1 X641.029460 Y61.668320 +G1 X642.144151 Y62.257669 +G1 X643.291964 Y62.792107 +G1 X644.466688 Y63.270599 +G1 X645.662113 Y63.692109 +G1 X646.872030 Y64.055603 +G1 X648.090227 Y64.360044 +G1 X648.677140 Y64.485110 +G1 X649.919221 Y64.693677 +G1 X651.181709 Y64.832807 +G1 X652.454196 Y64.914168 +G1 X653.726279 Y64.949429 +G1 X654.987550 Y64.950259 +G1 X655.124600 Y64.948756 +G1 X656.194980 Y64.901409 +G1 X657.270224 Y64.786513 +G1 X658.346291 Y64.606747 +G1 X659.419142 Y64.364788 +G1 X660.484737 Y64.063314 +G1 X661.539037 Y63.705002 +G1 X662.578001 Y63.292530 +G1 X663.597591 Y62.828576 +G1 X664.593767 Y62.315817 +G1 X665.562488 Y61.756931 +G1 X666.499716 Y61.154595 +G1 X667.401410 Y60.511488 +G1 X668.263531 Y59.830287 +G1 X669.082040 Y59.113670 +G1 X669.533740 Y58.684290 +G1 X670.339427 Y57.846585 +G1 X671.098799 Y56.963430 +G1 X671.813545 Y56.040936 +G1 X672.485353 Y55.085213 +G1 X673.115912 Y54.102371 +G1 X673.706912 Y53.098521 +G1 X674.260041 Y52.079773 +G1 X674.776988 Y51.052238 +G1 X675.259443 Y50.022025 +G1 X675.283550 Y49.968648 +G1 X675.857655 Y48.602604 +G1 X676.390355 Y47.201217 +G1 X676.911151 Y45.785906 +G1 X677.505482 Y44.238546 +G1 X678.097295 Y42.863718 +G1 X678.645142 Y41.766169 +G1 X678.828530 Y41.435236 +G1 X677.717191 Y44.875061 +G1 X676.838213 Y47.765439 +G1 X676.237929 Y49.958237 +G1 X675.759365 Y51.963143 +G1 X675.395431 Y53.792221 +G1 X675.135105 Y55.458063 +G1 X674.965550 Y56.973269 +G1 X674.867774 Y58.487716 +G1 X674.846410 Y59.450212 +G1 X674.803420 Y62.221852 +G1 X674.834864 Y63.384507 +G1 X674.926710 Y64.380631 +G1 X675.270618 Y66.706985 +G1 X675.655558 Y68.799134 +G1 X676.075193 Y70.678661 +G1 X676.521743 Y72.366044 +G1 X677.036919 Y74.030717 +G1 X677.570238 Y75.522357 +G1 X678.170444 Y76.991492 +G1 X678.842382 Y78.436344 +G1 X679.519556 Y79.727277 +G1 X680.263655 Y80.995335 +G1 X681.078317 Y82.239182 +G1 X681.187190 Y82.395602 +G1 X682.102583 Y83.636698 +G1 X683.075672 Y84.830805 +G1 X684.103927 Y85.975626 +G1 X685.184818 Y87.068866 +G1 X686.315812 Y88.108225 +G1 X687.494380 Y89.091407 +G1 X688.717991 Y90.016115 +G1 X689.984114 Y90.880052 +G1 X691.290218 Y91.680920 +G1 X692.633773 Y92.416422 +G1 X694.012248 Y93.084262 +G1 X695.423112 Y93.682141 +G1 X696.863834 Y94.207763 +G1 X698.197363 Y94.620966 +G1 X699.551575 Y94.970828 +G1 X700.924569 Y95.255623 +G1 X701.394630 Y95.337209 +G1 X702.296296 Y95.480266 +G1 X703.150107 Y95.598447 +G1 X703.290940 Y95.615656 +G1 X704.179066 Y95.681699 +G1 X705.102596 Y95.692206 +G1 X706.061735 Y95.678083 +G1 X706.893940 Y95.669794 +G1 X707.430550 Y95.672546 +G1 X707.910634 Y95.671748 +G1 X708.377409 Y95.653819 +G1 X708.790250 Y95.615655 +G1 X709.699532 Y95.492845 +G1 X710.657512 Y95.333776 +G1 X711.626745 Y95.139476 +G1 X712.569787 Y94.910974 +G1 X712.772510 Y94.855520 +G1 X714.126656 Y94.442083 +G1 X715.459876 Y93.965463 +G1 X716.768363 Y93.426143 +G1 X718.048308 Y92.824602 +G1 X719.295901 Y92.161323 +G1 X720.507335 Y91.436787 +G1 X721.678801 Y90.651475 +G1 X722.806489 Y89.805869 +G1 X723.886592 Y88.900449 +G1 X724.915300 Y87.935698 +G1 X725.802686 Y87.007569 +G1 X726.641588 Y86.031166 +G1 X727.429145 Y85.006848 +G1 X728.162494 Y83.934979 +G1 X728.838775 Y82.815919 +G1 X728.861960 Y82.774865 +G1 X729.430216 Y81.696972 +G1 X729.936858 Y80.591952 +G1 X730.381829 Y79.462973 +G1 X730.765071 Y78.313201 +G1 X731.086528 Y77.145803 +G1 X731.346144 Y75.963946 +G1 X731.543860 Y74.770797 +G1 X731.679621 Y73.569523 +G1 X731.753369 Y72.363290 +G1 X731.765048 Y71.155266 +G1 X731.714600 Y69.948616 +G1 X731.601969 Y68.746508 +G1 X731.427098 Y67.552109 +G1 X731.189930 Y66.368586 +G1 X730.890408 Y65.199105 +G1 X730.528475 Y64.046833 +G1 X730.104074 Y62.914937 +G1 X729.617149 Y61.806583 +G1 X729.067642 Y60.724940 +G1 X728.455497 Y59.673172 +G1 X727.780657 Y58.654448 +G1 X727.534160 Y58.312424 +G1 X726.736926 Y57.297200 +G1 X725.878269 Y56.332182 +G1 X724.962134 Y55.420326 +G1 X723.992466 Y54.564591 +G1 X722.973209 Y53.767934 +G1 X721.908311 Y53.033312 +G1 X720.801715 Y52.363684 +G1 X719.657368 Y51.762005 +G1 X718.479213 Y51.231235 +G1 X717.323660 Y50.792402 +G1 X716.159021 Y50.421496 +G1 X714.949246 Y50.108562 +G1 X713.944586 Y49.913926 +G1 X713.151770 Y49.811254 +G1 X712.753070 Y49.780818 +G1 X712.403947 Y49.769143 +G1 X712.069513 Y49.769460 +G1 X711.714884 Y49.774996 +G1 X711.305175 Y49.778981 +G1 X711.255460 Y49.779034 +G1 X710.849073 Y49.776450 +G1 X710.506278 Y49.771035 +G1 X710.200559 Y49.766299 +G1 X709.905402 Y49.765751 +G1 X709.561283 Y49.774171 +G1 X709.169510 Y49.796084 +G1 X708.584260 Y49.858723 +G1 X707.959973 Y49.963054 +G1 X707.316845 Y50.100956 +G1 X706.675074 Y50.264310 +G1 X706.054857 Y50.444994 +G1 X705.476389 Y50.634888 +G1 X705.376890 Y50.669907 +G1 X704.349605 Y51.072397 +G1 X703.351073 Y51.540292 +G1 X702.387138 Y52.074379 +G1 X701.545773 Y52.618015 +G1 X700.742220 Y53.217597 +G1 X700.067970 Y53.793697 +G1 X699.559133 Y54.301138 +G1 X699.072374 Y54.868174 +G1 X698.612649 Y55.477798 +G1 X698.184912 Y56.113003 +G1 X697.794119 Y56.756784 +G1 X697.445227 Y57.392133 +G1 X697.143190 Y58.002044 +G1 X696.892963 Y58.569511 +G1 X696.843480 Y58.691686 +G1 X697.849662 Y58.169471 +G1 X698.916572 Y57.653249 +G1 X700.029409 Y57.168450 +G1 X701.173374 Y56.740503 +G1 X702.227898 Y56.422194 +G1 X703.188909 Y56.207910 +G1 X704.057227 Y56.087657 +G1 X704.836741 Y56.049334 +G1 X705.187240 Y56.056575 +G1 X706.094282 Y56.136431 +G1 X706.992761 Y56.294912 +G1 X707.874184 Y56.530511 +G1 X708.653532 Y56.810343 +G1 X709.405386 Y57.151531 +G1 X710.123365 Y57.552941 +G1 X710.801090 Y58.013441 +G1 X711.432179 Y58.531899 +G1 X712.010252 Y59.107181 +G1 X712.484399 Y59.678524 +G1 X712.904665 Y60.295042 +G1 X713.266255 Y60.955884 +G1 X713.564377 Y61.660201 +G1 X713.652380 Y61.915416 +G1 X713.852219 Y62.628126 +G1 X713.966961 Y63.261857 +G1 X714.013805 Y63.898684 +G1 X714.002440 Y64.380630 +G1 X713.935652 Y65.130608 +G1 X713.827697 Y65.833851 +G1 X713.666344 Y66.514215 +G1 X713.439364 Y67.195560 +G1 X713.165780 Y67.835891 +G1 X712.900870 Y68.362886 +G1 X712.483967 Y69.070300 +G1 X712.013388 Y69.735282 +G1 X711.493258 Y70.358085 +G1 X710.927702 Y70.938962 +G1 X710.320846 Y71.478165 +G1 X709.676815 Y71.975946 +G1 X708.999735 Y72.432560 +G1 X708.293730 Y72.848257 +G1 X707.562925 Y73.223292 +G1 X706.811448 Y73.557916 +G1 X706.043421 Y73.852383 +G1 X705.262972 Y74.106944 +G1 X704.474224 Y74.321854 +G1 X703.681305 Y74.497364 +G1 X702.888337 Y74.633727 +G1 X702.099449 Y74.731196 +G1 X701.318763 Y74.790024 +G1 X700.825720 Y74.807504 +G1 X699.762507 Y74.789112 +G1 X698.689789 Y74.694336 +G1 X697.612533 Y74.526050 +G1 X696.535708 Y74.287134 +G1 X695.464279 Y73.980463 +G1 X694.403216 Y73.608914 +G1 X693.357484 Y73.175365 +G1 X692.332053 Y72.682693 +G1 X691.331889 Y72.133774 +G1 X690.361960 Y71.531486 +G1 X689.427232 Y70.878705 +G1 X688.532675 Y70.178308 +G1 X687.683255 Y69.433174 +G1 X686.883939 Y68.646177 +G1 X686.446660 Y68.173250 +G1 X685.794475 Y67.386996 +G1 X685.194903 Y66.552872 +G1 X684.647548 Y65.676906 +G1 X684.152011 Y64.765128 +G1 X683.707897 Y63.823568 +G1 X683.314807 Y62.858255 +G1 X682.972344 Y61.875218 +G1 X682.680111 Y60.880488 +G1 X682.437710 Y59.880095 +G1 X682.244744 Y58.880066 +G1 X682.106520 Y57.933160 +G1 X682.043933 Y57.441944 +G1 X681.988431 Y57.016084 +G1 X681.941667 Y56.630460 +G1 X681.905295 Y56.259949 +G1 X681.880970 Y55.879430 +G1 X681.870346 Y55.463780 +G1 X681.872830 Y55.088692 +G1 X681.890647 Y54.695097 +G1 X681.922793 Y54.362240 +G1 X681.962452 Y54.059950 +G1 X682.002808 Y53.758056 +G1 X682.037046 Y53.426390 +G1 X682.052220 Y53.192377 +G1 X682.107794 Y52.488958 +G1 X682.203590 Y51.734883 +G1 X682.331541 Y50.958193 +G1 X682.483578 Y50.186932 +G1 X682.651634 Y49.449142 +G1 X682.760420 Y49.020495 +G1 X683.128655 Y47.766885 +G1 X683.566365 Y46.528336 +G1 X684.072206 Y45.311104 +G1 X684.644836 Y44.121447 +G1 X685.282912 Y42.965619 +G1 X685.985090 Y41.849878 +G1 X686.750028 Y40.780479 +G1 X687.498756 Y39.853777 +G1 X687.774080 Y39.538931 +G1 X688.756610 Y38.490353 +G1 X689.788457 Y37.490072 +G1 X690.867176 Y36.540557 +G1 X691.990321 Y35.644276 +G1 X693.155447 Y34.803696 +G1 X694.360107 Y34.021285 +G1 X695.601857 Y33.299512 +G1 X696.878251 Y32.640843 +G1 X698.186843 Y32.047748 +G1 X699.525188 Y31.522695 +G1 X700.825720 Y31.088008 +G1 X702.283897 Y30.675004 +G1 X703.763100 Y30.328527 +G1 X705.120184 Y30.080027 +G1 X706.483602 Y29.902912 +G1 X706.514660 Y29.899774 +G1 X706.999578 Y29.864179 +G1 X707.462220 Y29.833483 +G1 X707.652450 Y29.813674 +G1 X708.225595 Y29.742477 +G1 X708.781790 Y29.691377 +G1 X709.169500 Y29.679034 +G1 X709.534637 Y29.682417 +G1 X709.840285 Y29.696901 +G1 X710.113685 Y29.720668 +G1 X710.382079 Y29.751895 +G1 X710.672708 Y29.788762 +G1 X710.876180 Y29.813674 +G1 X711.345485 Y29.851830 +G1 X711.784693 Y29.870563 +G1 X712.203600 Y29.899984 +G1 X713.192091 Y30.030251 +G1 X714.194196 Y30.220560 +G1 X715.187089 Y30.457377 +G1 X715.996230 Y30.682027 +G1 X717.144673 Y31.055166 +G1 X718.264489 Y31.487832 +G1 X719.355751 Y31.977032 +G1 X720.418533 Y32.519775 +G1 X721.452909 Y33.113068 +G1 X722.458952 Y33.753919 +G1 X723.436737 Y34.439338 +G1 X724.386338 Y35.166331 +G1 X725.307828 Y35.931906 +G1 X726.201280 Y36.733072 +G1 X727.066769 Y37.566837 +G1 X727.904369 Y38.430208 +G1 X728.714153 Y39.320195 +G1 X729.496195 Y40.233803 +G1 X730.250569 Y41.168043 +G1 X730.977349 Y42.119921 +G1 X731.676609 Y43.086447 +G1 X732.109390 Y43.710835 +G1 X732.455070 Y44.242163 +G1 X732.817533 Y44.841464 +G1 X733.193895 Y45.496515 +G1 X733.581269 Y46.195093 +G1 X733.976771 Y46.924977 +G1 X734.377516 Y47.673942 +G1 X734.780619 Y48.429767 +G1 X735.223312 Y49.254509 +G1 X735.661528 Y50.056493 +G1 X736.091426 Y50.819451 +G1 X736.509166 Y51.527114 +G1 X736.875148 Y52.108772 +G1 X737.174650 Y52.548909 +G1 X737.164834 Y52.509755 +G1 X737.136633 Y52.397123 +G1 X737.091922 Y52.218260 +G1 X737.032573 Y51.980413 +G1 X736.960460 Y51.690829 +G1 X736.877456 Y51.356754 +G1 X736.785434 Y50.985436 +G1 X736.686267 Y50.584120 +G1 X736.581829 Y50.160053 +G1 X736.473993 Y49.720483 +G1 X736.364632 Y49.272656 +G1 X736.244809 Y48.779158 +G1 X736.116466 Y48.246411 +G1 X735.994968 Y47.736693 +G1 X735.883635 Y47.262842 +G1 X735.785783 Y46.837698 +G1 X735.704733 Y46.474097 +G1 X735.648422 Y46.207760 +G1 X735.642030 Y46.176039 +G1 X735.409531 Y44.963969 +G1 X735.184204 Y43.692444 +G1 X734.969582 Y42.384654 +G1 X734.769199 Y41.063788 +G1 X734.586587 Y39.753038 +G1 X734.425279 Y38.475594 +G1 X734.288810 Y37.254647 +G1 X734.233070 Y36.694475 +G1 X734.189815 Y35.994750 +G1 X734.177751 Y35.244289 +G1 X734.184132 Y34.478783 +G1 X734.196215 Y33.733925 +G1 X734.201070 Y33.281119 +G1 X734.216086 Y32.664667 +G1 X734.267781 Y32.060849 +G1 X734.281270 Y31.953693 +G1 X734.349443 Y31.380499 +G1 X734.401125 Y30.854438 +G1 X734.404720 Y30.815904 +G1 X734.531321 Y29.695531 +G1 X734.703731 Y28.537246 +G1 X734.916273 Y27.359814 +G1 X735.163265 Y26.182004 +G1 X735.439031 Y25.022580 +G1 X735.737889 Y23.900309 +G1 X735.990040 Y23.041028 +G1 X736.494358 Y21.530908 +G1 X737.073869 Y20.044660 +G1 X737.726135 Y18.585690 +G1 X738.448717 Y17.157404 +G1 X739.239178 Y15.763207 +G1 X740.095078 Y14.406506 +G1 X741.013980 Y13.090706 +G1 X741.993445 Y11.819214 +G1 X743.031034 Y10.595435 +G1 X744.124309 Y9.422775 +G1 X745.270832 Y8.304640 +G1 X746.468165 Y7.244436 +G1 X746.526890 Y7.195048 +G1 X747.571663 Y6.360311 +G1 X748.668963 Y5.564100 +G1 X749.812870 Y4.809837 +G1 X750.997465 Y4.100941 +G1 X752.216830 Y3.440835 +G1 X753.465045 Y2.832939 +G1 X754.736191 Y2.280674 +G1 X756.024349 Y1.787462 +G1 X757.323601 Y1.356724 +G1 X758.628027 Y0.991881 +G1 X759.931709 Y0.696353 +G1 X761.228727 Y0.473562 +G1 X762.513162 Y0.326929 +G1 X762.835190 Y0.302326 +G1 X763.163937 Y0.286386 +G1 X763.436813 Y0.283377 +G1 X763.690442 Y0.283984 +G1 X763.990917 Y0.277710 +G1 X764.162610 Y0.268226 +G1 X764.531653 Y0.230003 +G1 X764.851457 Y0.184265 +G1 X765.175620 Y0.150239 +G1 X765.490030 Y0.144766 +G1 X765.821594 Y0.168765 +G1 X766.118318 Y0.210052 +G1 X766.441397 Y0.252219 +G1 X766.627820 Y0.268226 +G1 X766.992297 Y0.283981 +G1 X767.310084 Y0.284812 +G1 X767.635869 Y0.284293 +G1 X767.955240 Y0.292726 +G1 X768.640966 Y0.345732 +G1 X769.373596 Y0.442446 +G1 X770.137428 Y0.576141 +G1 X770.916760 Y0.740090 +G1 X771.695890 Y0.927567 +G1 X772.459116 Y1.131844 +G1 X773.190737 Y1.346196 +G1 X773.875050 Y1.563895 +G1 X774.023430 Y1.613506 +G1 X775.282701 Y2.078148 +G1 X776.522991 Y2.614376 +G1 X777.739764 Y3.218608 +G1 X778.928487 Y3.887259 +G1 X780.084623 Y4.616747 +G1 X781.203640 Y5.403487 +G1 X782.281002 Y6.243897 +G1 X783.312174 Y7.134392 +G1 X784.292623 Y8.071389 +G1 X785.179260 Y9.008370 +G1 X786.048402 Y10.032395 +G1 X786.850688 Y11.097060 +G1 X787.585665 Y12.199215 +G1 X788.252884 Y13.335711 +G1 X788.851892 Y14.503399 +G1 X789.382240 Y15.699129 +G1 X789.843475 Y16.919752 +G1 X790.235146 Y18.162119 +G1 X790.556804 Y19.423080 +G1 X790.807996 Y20.699486 +G1 X790.988271 Y21.988188 +G1 X791.097178 Y23.286036 +G1 X791.134267 Y24.589882 +G1 X791.099086 Y25.896575 +G1 X790.991183 Y27.202966 +G1 X790.810109 Y28.505907 +G1 X790.555412 Y29.802247 +G1 X790.353730 Y30.626340 +G1 X790.012971 Y31.776230 +G1 X789.606220 Y32.898180 +G1 X789.135870 Y33.990122 +G1 X788.604314 Y35.049989 +G1 X788.013944 Y36.075711 +G1 X787.367152 Y37.065220 +G1 X786.666332 Y38.016449 +G1 X785.913874 Y38.927329 +G1 X785.112172 Y39.795792 +G1 X784.263619 Y40.619769 +G1 X783.370606 Y41.397193 +G1 X782.435526 Y42.125995 +G1 X781.460772 Y42.804107 +G1 X780.448735 Y43.429461 +G1 X779.401809 Y43.999988 +G1 X778.322386 Y44.513620 +G1 X777.212858 Y44.968289 +G1 X776.488640 Y45.227185 +G1 X775.466397 Y45.534334 +G1 X774.431699 Y45.774488 +G1 X773.387774 Y45.953166 +G1 X772.337854 Y46.075886 +G1 X771.285167 Y46.148165 +G1 X770.232945 Y46.175522 +G1 X770.041180 Y46.176101 +G1 X769.540182 Y46.176690 +G1 X769.081198 Y46.167593 +G1 X768.610503 Y46.131977 +G1 X768.524130 Y46.121911 +G1 X767.861855 Y46.023876 +G1 X767.156451 Y45.889583 +G1 X766.437080 Y45.726171 +G1 X765.732903 Y45.540781 +G1 X765.300390 Y45.412879 +G1 X764.188504 Y45.031269 +G1 X763.103075 Y44.578911 +G1 X762.146565 Y44.102279 +G1 X761.225577 Y43.559672 +G1 X760.424614 Y43.006134 +G1 X759.663270 Y42.392431 +G1 X759.043320 Y41.813872 +G1 X758.607786 Y41.357978 +G1 X758.159001 Y40.842242 +G1 X757.721451 Y40.282549 +G1 X757.319621 Y39.694785 +G1 X756.977997 Y39.094836 +G1 X756.740279 Y38.552222 +G1 X756.609726 Y38.114575 +G1 X756.549928 Y37.693906 +G1 X756.565704 Y37.331882 +G1 X756.577360 Y37.263479 +G1 X757.074185 Y37.536931 +G1 X757.634829 Y37.837839 +G1 X758.244538 Y38.152182 +G1 X758.888556 Y38.465941 +G1 X759.552127 Y38.765094 +G1 X760.220498 Y39.035621 +G1 X760.749250 Y39.222177 +G1 X761.681456 Y39.489036 +G1 X762.623946 Y39.681949 +G1 X763.487811 Y39.788288 +G1 X764.356673 Y39.824391 +G1 X765.228864 Y39.785911 +G1 X766.023250 Y39.682553 +G1 X766.627820 Y39.558202 +G1 X767.430065 Y39.330990 +G1 X768.213249 Y39.038301 +G1 X768.969907 Y38.682508 +G1 X769.692580 Y38.265987 +G1 X770.373803 Y37.791110 +G1 X771.006116 Y37.260253 +G1 X771.582056 Y36.675789 +G1 X772.050440 Y36.099937 +G1 X772.460462 Y35.483529 +G1 X772.806514 Y34.828348 +G1 X773.060879 Y34.200583 +G1 X773.253532 Y33.543588 +G1 X773.380260 Y32.858704 +G1 X773.436852 Y32.147271 +G1 X773.439560 Y31.953798 +G1 X773.405104 Y31.226334 +G1 X773.303972 Y30.499148 +G1 X773.140005 Y29.777533 +G1 X772.917047 Y29.066785 +G1 X772.638940 Y28.372197 +G1 X772.309526 Y27.699061 +G1 X771.932647 Y27.052674 +G1 X771.512145 Y26.438327 +G1 X771.051863 Y25.861315 +G1 X770.577650 Y25.348943 +G1 X769.869340 Y24.689206 +G1 X769.106942 Y24.075258 +G1 X768.297799 Y23.511067 +G1 X767.449254 Y23.000600 +G1 X766.568650 Y22.547823 +G1 X765.663329 Y22.156705 +G1 X764.740633 Y21.831212 +G1 X763.807907 Y21.575311 +G1 X763.593710 Y21.526927 +G1 X762.814254 Y21.387269 +G1 X762.076660 Y21.283057 +G1 X761.581646 Y21.219541 +G1 X761.128598 Y21.177872 +G1 X760.673104 Y21.154302 +G1 X760.170754 Y21.145087 +G1 X759.801090 Y21.145006 +G1 X759.356494 Y21.154543 +G1 X758.965607 Y21.178608 +G1 X758.589806 Y21.216988 +G1 X758.190468 Y21.269468 +G1 X758.094410 Y21.283057 +G1 X757.113609 Y21.443783 +G1 X756.091486 Y21.655102 +G1 X755.057925 Y21.917226 +G1 X754.042815 Y22.230369 +G1 X753.161146 Y22.559496 +G1 X752.974360 Y22.637777 +G1 X751.934264 Y23.121879 +G1 X750.929935 Y23.666883 +G1 X749.963493 Y24.270105 +G1 X749.037059 Y24.928860 +G1 X748.152750 Y25.640462 +G1 X747.312686 Y26.402229 +G1 X746.518987 Y27.211475 +G1 X745.773772 Y28.065515 +G1 X745.079161 Y28.961665 +G1 X744.437273 Y29.897241 +G1 X743.850227 Y30.869557 +G1 X743.320143 Y31.875929 +G1 X742.849140 Y32.913673 +G1 X742.439338 Y33.980105 +G1 X742.231180 Y34.608638 +G1 X741.910320 Y35.752121 +G1 X741.657488 Y36.903767 +G1 X741.471368 Y38.061251 +G1 X741.350647 Y39.222247 +G1 X741.294009 Y40.384428 +G1 X741.300140 Y41.545470 +G1 X741.367725 Y42.703046 +G1 X741.495449 Y43.854831 +G1 X741.681997 Y44.998498 +G1 X741.926056 Y46.131722 +G1 X742.226309 Y47.252177 +G1 X742.581443 Y48.357537 +G1 X742.990142 Y49.445477 +G1 X743.451093 Y50.513670 +G1 X743.962979 Y51.559790 +G1 X744.524487 Y52.581512 +G1 X745.134302 Y53.576510 +G1 X745.791108 Y54.542458 +G1 X746.493592 Y55.477031 +G1 X747.240439 Y56.377902 +G1 X748.030333 Y57.242745 +G1 X748.861961 Y58.069235 +G1 X749.734007 Y58.855046 +G1 X750.645156 Y59.597851 +G1 X751.594095 Y60.295326 +G1 X752.405470 Y60.835595 +G1 X753.480830 Y61.478820 +G1 X754.595521 Y62.068169 +G1 X755.743334 Y62.602607 +G1 X756.918058 Y63.081099 +G1 X758.113483 Y63.502609 +G1 X759.323400 Y63.866103 +G1 X760.541597 Y64.170544 +G1 X761.128510 Y64.295610 +G1 X762.370591 Y64.504177 +G1 X763.633079 Y64.643307 +G1 X764.905566 Y64.724668 +G1 X766.177649 Y64.759929 +G1 X767.438920 Y64.760759 +G1 X767.575970 Y64.759256 +G1 X768.646350 Y64.711909 +G1 X769.721594 Y64.597013 +G1 X770.797661 Y64.417247 +G1 X771.870512 Y64.175288 +G1 X772.936107 Y63.873814 +G1 X773.990407 Y63.515502 +G1 X775.029371 Y63.103030 +G1 X776.048961 Y62.639076 +G1 X777.045137 Y62.126317 +G1 X778.013858 Y61.567431 +G1 X778.951086 Y60.965095 +G1 X779.852780 Y60.321988 +G1 X780.714901 Y59.640787 +G1 X781.533410 Y58.924170 +G1 X781.985110 Y58.494790 +G1 X782.790797 Y57.657085 +G1 X783.550169 Y56.773930 +G1 X784.264915 Y55.851436 +G1 X784.936723 Y54.895713 +G1 X785.567282 Y53.912871 +G1 X786.158282 Y52.909021 +G1 X786.711411 Y51.890273 +G1 X787.228358 Y50.862738 +G1 X787.710813 Y49.832525 +G1 X787.734920 Y49.779148 +G1 X788.309025 Y48.413104 +G1 X788.841725 Y47.011717 +G1 X789.362521 Y45.596406 +G1 X789.956852 Y44.049046 +G1 X790.548665 Y42.674218 +G1 X791.096512 Y41.576669 +G1 X791.279900 Y41.245736 diff --git a/tests/gcode/motion-tests-hmap.ngc b/tests/gcode/motion-tests-hmap.nc similarity index 100% rename from tests/gcode/motion-tests-hmap.ngc rename to tests/gcode/motion-tests-hmap.nc diff --git a/tests/gcode/motion-tests.ngc b/tests/gcode/motion-tests.nc similarity index 100% rename from tests/gcode/motion-tests.ngc rename to tests/gcode/motion-tests.nc diff --git a/tests/gcode/motion_modes-tests.ngc b/tests/gcode/motion_modes-tests.nc similarity index 100% rename from tests/gcode/motion_modes-tests.ngc rename to tests/gcode/motion_modes-tests.nc diff --git a/tests/gcode/override-tests.ngc b/tests/gcode/override-tests.nc similarity index 100% rename from tests/gcode/override-tests.ngc rename to tests/gcode/override-tests.nc diff --git a/tests/gcode/sample.ngc b/tests/gcode/sample.nc similarity index 100% rename from tests/gcode/sample.ngc rename to tests/gcode/sample.nc diff --git a/tests/gcode/stress-tests.ngc b/tests/gcode/stress-tests.nc similarity index 100% rename from tests/gcode/stress-tests.ngc rename to tests/gcode/stress-tests.nc diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 14cf75bd7..e422ce64e 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -416,6 +416,9 @@ void mcu_clocks_init() DWT->CYCCNT = 0; DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; } + + //free some jtag pins + AFIO->MAPR |= (2<<24); } void mcu_usart_init(void) From 98a7433fb871dbdda596f261a6366b839c2a3990 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 26 Aug 2023 12:53:35 +0100 Subject: [PATCH 104/168] Update mcu_esp32.c --- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index c1a1dea3c..232915a97 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -263,7 +263,7 @@ static FORCEINLINE void esp32_i2s_extender_init(void) // initialize ITP timer that will run at a fixed rate to update all IO /* Select and initialize basic parameters of the timer */ timer_config_t itpconfig = { - .divider = 2, + .divider = getApbFrequency() / 1000000UL, .counter_dir = TIMER_COUNT_UP, .counter_en = TIMER_PAUSE, .alarm_en = TIMER_ALARM_EN, @@ -275,7 +275,7 @@ static FORCEINLINE void esp32_i2s_extender_init(void) Also, if auto_reload is set, this value will be automatically reload on alarm */ timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); /* Configure the alarm value and the interrupt on alarm. */ - timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)160); + timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)4); // register PWM isr timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); From a61ae5d250dd1485abb18a3ec13341479032a11e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 26 Aug 2023 13:56:27 +0100 Subject: [PATCH 105/168] cleaned code --- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 4 ---- 1 file changed, 4 deletions(-) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 232915a97..767bdb9df 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -473,10 +473,6 @@ void mcu_init(void) uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif -#ifndef IC74HC595_HAS_PWMS - esp32_i2s_extender_init(); -#endif - #ifndef IC74HC595_CUSTOM_SHIFT_IO // inititialize ITP timer timer_config_t itpconfig = {0}; From f941fe7d609e842f339165d7ce9c6cbbf74a7db2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 3 Sep 2023 00:44:59 +0100 Subject: [PATCH 106/168] fixed hold issue on version1.8 - fixed hold issue on version1.8 that keeps generating steps until the end of the motion --- uCNC/src/core/interpolator.c | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index ca47096c1..f9617f5de 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -559,13 +559,14 @@ void itp_run(void) if (current_speed <= 0) { + // speed can't be negative + current_speed = 0; + itp_cur_plan_block->entry_feed_sqr = 0; + if (cnc_get_exec_state(EXEC_HOLD)) { return; } - - // speed can't be negative - current_speed = 0; } partial_distance += current_speed * integrator; @@ -660,7 +661,7 @@ void itp_run(void) #endif remaining_steps -= segm_steps; - if (remaining_steps == accel_until) // resets float additions error + if (remaining_steps == accel_until && !cnc_get_exec_state(EXEC_HOLD)) // resets float additions error { itp_cur_plan_block->entry_feed_sqr = fast_flt_pow2(junction_speed); } From f2b49fdbd9ac440a704b0e36dbece43d074cce46 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 4 Sep 2023 20:49:14 +0100 Subject: [PATCH 107/168] modified ESP32 I2S extender modified ESP32 I2S extender - allow mixed mode PWM (both hardware and software pins) - if no software PWM pins are used then use normal step generation ISR --- uCNC/src/core/interpolator.c | 9 +-- uCNC/src/core/io_control.c | 33 +++++----- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 83 +++++++++++++------------- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 24 +------- 4 files changed, 66 insertions(+), 83 deletions(-) diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index ca47096c1..f9617f5de 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -559,13 +559,14 @@ void itp_run(void) if (current_speed <= 0) { + // speed can't be negative + current_speed = 0; + itp_cur_plan_block->entry_feed_sqr = 0; + if (cnc_get_exec_state(EXEC_HOLD)) { return; } - - // speed can't be negative - current_speed = 0; } partial_distance += current_speed * integrator; @@ -660,7 +661,7 @@ void itp_run(void) #endif remaining_steps -= segm_steps; - if (remaining_steps == accel_until) // resets float additions error + if (remaining_steps == accel_until && !cnc_get_exec_state(EXEC_HOLD)) // resets float additions error { itp_cur_plan_block->entry_feed_sqr = fast_flt_pow2(junction_speed); } diff --git a/uCNC/src/core/io_control.c b/uCNC/src/core/io_control.c index beda4cd80..cd568387d 100644 --- a/uCNC/src/core/io_control.c +++ b/uCNC/src/core/io_control.c @@ -856,7 +856,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) // software PWM pwm_counter += (1 << resolution); pwm_counter_last = pwm_counter; -#if ASSERT_PIN(PWM0) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM0))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM0))) if (pwm_counter > g_io_soft_pwm[0] || !g_io_soft_pwm[0]) { io_clear_output(PWM0); @@ -866,7 +866,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM0); } #endif -#if ASSERT_PIN(PWM1) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM1))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM1))) if (pwm_counter > g_io_soft_pwm[1] || !g_io_soft_pwm[1]) { io_clear_output(PWM1); @@ -876,7 +876,8 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM1); } #endif -#if ASSERT_PIN(PWM2) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM2))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM2))) + if (pwm_counter > g_io_soft_pwm[2] || !g_io_soft_pwm[2]) { io_clear_output(PWM2); @@ -886,7 +887,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM2); } #endif -#if ASSERT_PIN(PWM3) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM3))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM3))) if (pwm_counter > g_io_soft_pwm[3] || !g_io_soft_pwm[3]) { io_clear_output(PWM3); @@ -896,7 +897,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM3); } #endif -#if ASSERT_PIN(PWM4) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM4))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM4))) if (pwm_counter > g_io_soft_pwm[4] || !g_io_soft_pwm[4]) { io_clear_output(PWM4); @@ -906,7 +907,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM4); } #endif -#if ASSERT_PIN(PWM5) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM5))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM5))) if (pwm_counter > g_io_soft_pwm[5] || !g_io_soft_pwm[5]) { io_clear_output(PWM5); @@ -916,7 +917,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM5); } #endif -#if ASSERT_PIN(PWM6) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM6))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM6))) if (pwm_counter > g_io_soft_pwm[6] || !g_io_soft_pwm[6]) { io_clear_output(PWM6); @@ -926,7 +927,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM6); } #endif -#if ASSERT_PIN(PWM7) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM7))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM7))) if (pwm_counter > g_io_soft_pwm[7] || !g_io_soft_pwm[7]) { io_clear_output(PWM7); @@ -936,7 +937,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM7); } #endif -#if ASSERT_PIN(PWM8) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM8))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM8))) if (pwm_counter > g_io_soft_pwm[8] || !g_io_soft_pwm[8]) { io_clear_output(PWM8); @@ -946,7 +947,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM8); } #endif -#if ASSERT_PIN(PWM9) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM9))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM9))) if (pwm_counter > g_io_soft_pwm[9] || !g_io_soft_pwm[9]) { io_clear_output(PWM9); @@ -956,7 +957,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM9); } #endif -#if ASSERT_PIN(PWM10) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM10))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM10))) if (pwm_counter > g_io_soft_pwm[10] || !g_io_soft_pwm[10]) { io_clear_output(PWM10); @@ -966,7 +967,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM10); } #endif -#if ASSERT_PIN(PWM11) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM11))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM11))) if (pwm_counter > g_io_soft_pwm[11] || !g_io_soft_pwm[11]) { io_clear_output(PWM11); @@ -976,7 +977,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM11); } #endif -#if ASSERT_PIN(PWM12) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM12))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM12))) if (pwm_counter > g_io_soft_pwm[12] || !g_io_soft_pwm[12]) { io_clear_output(PWM12); @@ -986,7 +987,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM12); } #endif -#if ASSERT_PIN(PWM13) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM13))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM13))) if (pwm_counter > g_io_soft_pwm[13] || !g_io_soft_pwm[13]) { io_clear_output(PWM13); @@ -996,7 +997,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM13); } #endif -#if ASSERT_PIN(PWM14) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM14))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM14))) if (pwm_counter > g_io_soft_pwm[14] || !g_io_soft_pwm[14]) { io_clear_output(PWM14); @@ -1006,7 +1007,7 @@ MCU_CALLBACK void io_soft_pwm_update(void) io_set_output(PWM14); } #endif -#if ASSERT_PIN(PWM15) +#if ((defined(IC74HC595_HAS_PWMS) && ASSERT_PIN_EXTENDED(PWM15))||(defined(MCU_HAS_SOFT_PWM_TIMER) && ASSERT_PIN(PWM15))) if (pwm_counter > g_io_soft_pwm[15] || !g_io_soft_pwm[15]) { io_clear_output(PWM15); diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 767bdb9df..ff24ad9a6 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -81,17 +81,17 @@ static flash_eeprom_t mcu_eeprom; // IO will be updated at a fixed rate MCU_CALLBACK void ic74hc595_shift_io_pins(void) { +#ifndef IC74HC595_HAS_PWMS + I2SREG.conf_single_data = *((volatile uint32_t *)&ic74hc595_io_pins[0]); +#endif } #endif -#ifdef IC74HC595_CUSTOM_SHIFT_IO +#ifdef IC74HC595_HAS_PWMS MCU_CALLBACK void esp32_io_updater(void *arg) { static bool resetstep = false; - -#ifdef IC74HC595_HAS_PWMS io_soft_pwm_update(); -#endif if (mcu_itp_timer_running) { @@ -118,7 +118,6 @@ MCU_CALLBACK void esp32_io_updater(void *arg) we need enable it again, so it is triggered the next time */ timer_group_enable_alarm_in_isr(ITP_TIMER_TG, ITP_TIMER_IDX); } - #endif #if SERVOS_MASK > 0 @@ -202,22 +201,18 @@ MCU_CALLBACK void mcu_gpio_isr(void *type) #ifdef IC74HC595_HAS_PWMS uint8_t mcu_softpwm_freq_config(uint16_t freq) { - // keeps 8 bit resolution up to 1KHz + // keeps 7 bit resolution up to 1KHz // reduces bit resolution for higher frequencies - // determines the bit resolution (8 - esp32_pwm_res); + // determines the bit resolution (7 - esp32_pwm_res); uint8_t res = (uint8_t)MAX((int8_t)ceilf(log2(freq * 0.001f)), 0); - freq >>= res; - // timer base frequency is APB clock/2 - // it's then divided by 256 - timer_set_alarm_value(PWM_TIMER_TG, PWM_TIMER_IDX, (uint64_t)roundf((float)(getApbFrequency() >> 9) / (float)freq)); return res; } #endif +#ifdef IC74HC595_CUSTOM_SHIFT_IO static FORCEINLINE void esp32_i2s_extender_init(void) { -#ifdef IC74HC595_CUSTOM_SHIFT_IO i2s_config_t i2s_config = { .mode = I2S_MODE_MASTER | I2S_MODE_TX, // Only TX .sample_rate = 156250UL, // 312500KHz * 32bit * 2 channels = 20MHz @@ -259,29 +254,8 @@ static FORCEINLINE void esp32_i2s_extender_init(void) // Disable TX interrupts I2SREG.int_ena.out_eof = 0; I2SREG.int_ena.out_dscr_err = 0; - - // initialize ITP timer that will run at a fixed rate to update all IO - /* Select and initialize basic parameters of the timer */ - timer_config_t itpconfig = { - .divider = getApbFrequency() / 1000000UL, - .counter_dir = TIMER_COUNT_UP, - .counter_en = TIMER_PAUSE, - .alarm_en = TIMER_ALARM_EN, - .auto_reload = true, - }; // default clock source is APB - timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); - - /* Timer's counter will initially start from value below. - Also, if auto_reload is set, this value will be automatically reload on alarm */ - timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); - /* Configure the alarm value and the interrupt on alarm. */ - timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)4); - // register PWM isr - timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); - timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); - timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); -#endif } +#endif void mcu_core0_tasks_init(void *arg) { @@ -294,9 +268,32 @@ void mcu_core0_tasks_init(void *arg) uart_driver_install(COM2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif +#ifdef IC74HC595_HAS_PWMS #ifdef IC74HC595_CUSTOM_SHIFT_IO esp32_i2s_extender_init(); #endif + + // initialize ITP timer that will run at a fixed rate to update all IO + /* Select and initialize basic parameters of the timer */ + timer_config_t itpconfig = {0}; + itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse + itpconfig.counter_dir = TIMER_COUNT_UP; + itpconfig.counter_en = TIMER_PAUSE; + itpconfig.intr_type = TIMER_INTR_MAX; + itpconfig.alarm_en = TIMER_ALARM_EN; + itpconfig.auto_reload = true; + timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); + + /* Timer's counter will initially start from value below. + Also, if auto_reload is set, this value will be automatically reload on alarm */ + timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); + /* Configure the alarm value and the interrupt on alarm. */ + timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)8); + // register PWM isr + timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); + timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); + timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); +#endif } void mcu_rtc_task(void *arg) @@ -383,7 +380,7 @@ void mcu_rtc_task(void *arg) } } -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS MCU_CALLBACK void mcu_itp_isr(void *arg) { static bool resetstep = false; @@ -473,12 +470,16 @@ void mcu_init(void) uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS +#ifdef IC74HC595_CUSTOM_SHIFT_IO + esp32_i2s_extender_init(); +#endif // inititialize ITP timer timer_config_t itpconfig = {0}; itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse itpconfig.counter_dir = TIMER_COUNT_UP; itpconfig.counter_en = TIMER_PAUSE; + itpconfig.intr_type = TIMER_INTR_MAX; itpconfig.alarm_en = TIMER_ALARM_EN; itpconfig.auto_reload = true; timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); @@ -676,7 +677,7 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); // up and down counter (generates half the step rate at each event) -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS uint32_t totalticks = (uint32_t)(500000.0f / frequency); #else uint32_t totalticks = (uint32_t)(125000.0f / frequency); @@ -693,7 +694,7 @@ void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) float mcu_clocks_to_freq(uint16_t ticks, uint16_t prescaller) { -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS return (500000.0f / ((float)ticks * (float)prescaller)); #else return (125000.0f / ((float)ticks * (float)prescaller)); @@ -708,7 +709,7 @@ void mcu_start_itp_isr(uint16_t ticks, uint16_t prescaller) { if (!mcu_itp_timer_running) { -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS /* Timer's counter will initially start from value below. Also, if auto_reload is set, this value will be automatically reload on alarm */ timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); @@ -738,7 +739,7 @@ void mcu_change_itp_isr(uint16_t ticks, uint16_t prescaller) { if (mcu_itp_timer_running) { -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS timer_pause(ITP_TIMER_TG, ITP_TIMER_IDX); timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)ticks * prescaller); timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); @@ -759,7 +760,7 @@ void mcu_stop_itp_isr(void) { if (mcu_itp_timer_running) { -#ifndef IC74HC595_CUSTOM_SHIFT_IO +#ifndef IC74HC595_HAS_PWMS // timerAlarmDisable(esp32_step_timer); timer_pause(ITP_TIMER_TG, ITP_TIMER_IDX); timer_disable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index b8c92ce8d..382fb095e 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -28,9 +28,7 @@ extern "C" #include "driver/timer.h" #include "driver/gpio.h" #include "driver/adc.h" -#ifndef IC74HC595_HAS_PWMS #include "driver/ledc.h" -#endif /* Generates all the interface definitions. @@ -49,7 +47,7 @@ extern "C" #endif // defines the maximum and minimum step rates #ifndef F_STEP_MAX -#define F_STEP_MAX 125000UL +#define F_STEP_MAX 62500UL #endif #ifndef F_STEP_MIN #define F_STEP_MIN 1 @@ -2705,12 +2703,6 @@ extern "C" #define MCU_HAS_BLUETOOTH #endif -#ifndef PWM_TIMER -#define PWM_TIMER 0 -#endif -#define PWM_TIMER_TG (PWM_TIMER & 0x01) -#define PWM_TIMER_IDX ((PWM_TIMER >> 1) & 0x01) - #ifndef SERVO_TIMER #define SERVO_TIMER 3 #endif @@ -2830,7 +2822,7 @@ extern "C" { \ __indirect__(X, OUTREG)->OUT ^= (1UL << (0x1F & __indirect__(X, BIT))); \ } -#ifndef IC74HC595_HAS_PWMS + #define mcu_config_pwm(X, Y) \ { \ ledc_timer_config_t pwmtimer = {0}; \ @@ -2856,18 +2848,6 @@ extern "C" ledc_update_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)); \ } #define mcu_get_pwm(X) ledc_get_duty(__indirect__(X, SPEEDMODE), __indirect__(X, LEDCCHANNEL)) -#else -// forces all PWM to be generated via software -#define mcu_config_pwm(X, Y) \ - { \ - g_soft_pwm_res = mcu_softpwm_freq_config(Y); \ - } -#define mcu_set_pwm(X, Y) \ - { \ - g_io_soft_pwm[X - PWM_PINS_OFFSET] = (0xFF & Y); \ - } -#define mcy_get_pwm(X) g_io_soft_pwm[X - PWM_PINS_OFFSET] -#endif #define mcu_get_analog(X) adc1_get_raw(__indirect__(X, ADC_CHANNEL)) #ifdef MCU_HAS_ONESHOT_TIMER From 341c18acaf3cf406f70d4b86d3f6a96fc07a5b97 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 13 Sep 2023 12:15:18 +0100 Subject: [PATCH 108/168] experimenting with ESP-IDF - experimenting with ESP-IDF using Arduino Core custom compilation as component with better timer ISR tunning settings --- dependencies.lock | 9 + min_spiffs.csv | 7 + sdkconfig.defaults | 2075 +++++++++++++++++++++++++++ uCNC/src/hal/boards/esp32/esp32.ini | 9 +- 4 files changed, 2096 insertions(+), 4 deletions(-) create mode 100644 dependencies.lock create mode 100644 min_spiffs.csv create mode 100644 sdkconfig.defaults diff --git a/dependencies.lock b/dependencies.lock new file mode 100644 index 000000000..7a46da17a --- /dev/null +++ b/dependencies.lock @@ -0,0 +1,9 @@ +dependencies: + idf: + component_hash: null + source: + type: idf + version: 4.4.4 +manifest_hash: dcf4d39b94252de130019eadceb989d72b0dbc26b552cfdcbb50f6da531d2b92 +target: esp32 +version: 1.0.0 diff --git a/min_spiffs.csv b/min_spiffs.csv new file mode 100644 index 000000000..080f491d1 --- /dev/null +++ b/min_spiffs.csv @@ -0,0 +1,7 @@ +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x5000, +otadata, data, ota, 0xe000, 0x2000, +app0, app, ota_0, 0x10000, 0x1E0000, +app1, app, ota_1, 0x1F0000,0x1E0000, +spiffs, data, spiffs, 0x3D0000,0x20000, +coredump, data, coredump,0x3F0000,0x10000, \ No newline at end of file diff --git a/sdkconfig.defaults b/sdkconfig.defaults new file mode 100644 index 000000000..8c47901d7 --- /dev/null +++ b/sdkconfig.defaults @@ -0,0 +1,2075 @@ +# +# Automatically generated file. DO NOT EDIT. +# Espressif IoT Development Framework (ESP-IDF) Project Configuration +# +CONFIG_IDF_CMAKE=y +CONFIG_IDF_TARGET_ARCH_XTENSA=y +CONFIG_IDF_TARGET="esp32" +CONFIG_IDF_TARGET_ESP32=y +CONFIG_IDF_FIRMWARE_CHIP_ID=0x0000 + +# +# SDK tool configuration +# +CONFIG_SDK_TOOLPREFIX="xtensa-esp32-elf-" +# CONFIG_SDK_TOOLCHAIN_SUPPORTS_TIME_WIDE_64_BITS is not set +# end of SDK tool configuration + +# +# Build type +# +CONFIG_APP_BUILD_TYPE_APP_2NDBOOT=y +# CONFIG_APP_BUILD_TYPE_ELF_RAM is not set +CONFIG_APP_BUILD_GENERATE_BINARIES=y +CONFIG_APP_BUILD_BOOTLOADER=y +CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y +# end of Build type + +# +# Application manager +# +CONFIG_APP_COMPILE_TIME_DATE=y +# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set +# CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR is not set +# CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set +CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 +# end of Application manager + +# +# Bootloader config +# +CONFIG_BOOTLOADER_OFFSET_IN_FLASH=0x1000 +CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y +# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_DEBUG is not set +# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_PERF is not set +# CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_NONE is not set +CONFIG_BOOTLOADER_LOG_LEVEL_NONE=y +# CONFIG_BOOTLOADER_LOG_LEVEL_ERROR is not set +# CONFIG_BOOTLOADER_LOG_LEVEL_WARN is not set +# CONFIG_BOOTLOADER_LOG_LEVEL_INFO is not set +# CONFIG_BOOTLOADER_LOG_LEVEL_DEBUG is not set +# CONFIG_BOOTLOADER_LOG_LEVEL_VERBOSE is not set +CONFIG_BOOTLOADER_LOG_LEVEL=0 +# CONFIG_BOOTLOADER_SPI_CUSTOM_WP_PIN is not set +CONFIG_BOOTLOADER_SPI_WP_PIN=7 +CONFIG_BOOTLOADER_VDDSDIO_BOOST_1_9V=y +# CONFIG_BOOTLOADER_FACTORY_RESET is not set +# CONFIG_BOOTLOADER_APP_TEST is not set +CONFIG_BOOTLOADER_REGION_PROTECTION_ENABLE=y +CONFIG_BOOTLOADER_WDT_ENABLE=y +# CONFIG_BOOTLOADER_WDT_DISABLE_IN_USER_CODE is not set +CONFIG_BOOTLOADER_WDT_TIME_MS=9000 +CONFIG_BOOTLOADER_APP_ROLLBACK_ENABLE=y +# CONFIG_BOOTLOADER_APP_ANTI_ROLLBACK is not set +CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP=y +# CONFIG_BOOTLOADER_SKIP_VALIDATE_ON_POWER_ON is not set +# CONFIG_BOOTLOADER_SKIP_VALIDATE_ALWAYS is not set +CONFIG_BOOTLOADER_RESERVE_RTC_SIZE=0x10 +# CONFIG_BOOTLOADER_CUSTOM_RESERVE_RTC is not set +CONFIG_BOOTLOADER_FLASH_XMC_SUPPORT=y +# end of Bootloader config + +# +# Security features +# +# CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set +# CONFIG_SECURE_BOOT is not set +# CONFIG_SECURE_FLASH_ENC_ENABLED is not set +# end of Security features + +# +# Serial flasher config +# +CONFIG_ESPTOOLPY_BAUD_OTHER_VAL=115200 +# CONFIG_ESPTOOLPY_NO_STUB is not set +CONFIG_ESPTOOLPY_FLASHMODE_QIO=y +# CONFIG_ESPTOOLPY_FLASHMODE_QOUT is not set +# CONFIG_ESPTOOLPY_FLASHMODE_DIO is not set +# CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set +CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y +CONFIG_ESPTOOLPY_FLASHMODE="dio" +CONFIG_ESPTOOLPY_FLASHFREQ_80M=y +# CONFIG_ESPTOOLPY_FLASHFREQ_40M is not set +# CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set +# CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set +CONFIG_ESPTOOLPY_FLASHFREQ="80m" +# CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set +# CONFIG_ESPTOOLPY_FLASHSIZE_2MB is not set +CONFIG_ESPTOOLPY_FLASHSIZE_4MB=y +# CONFIG_ESPTOOLPY_FLASHSIZE_8MB is not set +# CONFIG_ESPTOOLPY_FLASHSIZE_16MB is not set +# CONFIG_ESPTOOLPY_FLASHSIZE_32MB is not set +# CONFIG_ESPTOOLPY_FLASHSIZE_64MB is not set +# CONFIG_ESPTOOLPY_FLASHSIZE_128MB is not set +CONFIG_ESPTOOLPY_FLASHSIZE="4MB" +CONFIG_ESPTOOLPY_FLASHSIZE_DETECT=y +CONFIG_ESPTOOLPY_BEFORE_RESET=y +# CONFIG_ESPTOOLPY_BEFORE_NORESET is not set +CONFIG_ESPTOOLPY_BEFORE="default_reset" +CONFIG_ESPTOOLPY_AFTER_RESET=y +# CONFIG_ESPTOOLPY_AFTER_NORESET is not set +CONFIG_ESPTOOLPY_AFTER="hard_reset" +# CONFIG_ESPTOOLPY_MONITOR_BAUD_CONSOLE is not set +# CONFIG_ESPTOOLPY_MONITOR_BAUD_9600B is not set +# CONFIG_ESPTOOLPY_MONITOR_BAUD_57600B is not set +CONFIG_ESPTOOLPY_MONITOR_BAUD_115200B=y +# CONFIG_ESPTOOLPY_MONITOR_BAUD_230400B is not set +# CONFIG_ESPTOOLPY_MONITOR_BAUD_921600B is not set +# CONFIG_ESPTOOLPY_MONITOR_BAUD_2MB is not set +# CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER is not set +CONFIG_ESPTOOLPY_MONITOR_BAUD_OTHER_VAL=115200 +CONFIG_ESPTOOLPY_MONITOR_BAUD=115200 +# end of Serial flasher config + +# +# Partition Table +# +CONFIG_PARTITION_TABLE_SINGLE_APP=y +# CONFIG_PARTITION_TABLE_SINGLE_APP_LARGE is not set +# CONFIG_PARTITION_TABLE_TWO_OTA is not set +# CONFIG_PARTITION_TABLE_CUSTOM is not set +CONFIG_PARTITION_TABLE_CUSTOM_FILENAME="partitions.csv" +CONFIG_PARTITION_TABLE_FILENAME="partitions_singleapp_coredump.csv" +CONFIG_PARTITION_TABLE_OFFSET=0x8000 +CONFIG_PARTITION_TABLE_MD5=y +# end of Partition Table + +CONFIG_LIB_BUILDER_FLASHMODE="qio" +CONFIG_LIB_BUILDER_FLASHFREQ="80m" +CONFIG_LIB_BUILDER_COMPILE=y + +# +# ESP RainMaker Config +# +# CONFIG_ESP_RMAKER_NO_CLAIM is not set +CONFIG_ESP_RMAKER_ASSISTED_CLAIM=y +CONFIG_ESP_RMAKER_USE_NVS=y +CONFIG_ESP_RMAKER_CLAIM_TYPE=2 +CONFIG_ESP_RMAKER_MQTT_HOST="a1p72mufdu6064-ats.iot.us-east-1.amazonaws.com" +CONFIG_ESP_RMAKER_MQTT_USE_BASIC_INGEST_TOPICS=y +CONFIG_ESP_RMAKER_MQTT_ENABLE_BUDGETING=y +CONFIG_ESP_RMAKER_MQTT_DEFAULT_BUDGET=100 +CONFIG_ESP_RMAKER_MQTT_MAX_BUDGET=1024 +CONFIG_ESP_RMAKER_MQTT_BUDGET_REVIVE_PERIOD=5 +CONFIG_ESP_RMAKER_MQTT_BUDGET_REVIVE_COUNT=1 +CONFIG_ESP_RMAKER_MAX_PARAM_DATA_SIZE=1024 +# CONFIG_ESP_RMAKER_DISABLE_USER_MAPPING_PROV is not set +CONFIG_ESP_RMAKER_USER_ID_CHECK=y +# CONFIG_RMAKER_NAME_PARAM_CB is not set +# CONFIG_ESP_RMAKER_LOCAL_CTRL_ENABLE is not set +CONFIG_ESP_RMAKER_CONSOLE_UART_NUM_0=y +# CONFIG_ESP_RMAKER_CONSOLE_UART_NUM_1 is not set +CONFIG_ESP_RMAKER_CONSOLE_UART_NUM=0 +CONFIG_ESP_RMAKER_USE_CERT_BUNDLE=y + +# +# ESP RainMaker OTA Config +# +CONFIG_ESP_RMAKER_OTA_AUTOFETCH=y +CONFIG_ESP_RMAKER_OTA_AUTOFETCH_PERIOD=0 +# CONFIG_ESP_RMAKER_SKIP_COMMON_NAME_CHECK is not set +CONFIG_ESP_RMAKER_SKIP_VERSION_CHECK=y +# CONFIG_ESP_RMAKER_SKIP_SECURE_VERSION_CHECK is not set +# CONFIG_ESP_RMAKER_SKIP_PROJECT_NAME_CHECK is not set +CONFIG_ESP_RMAKER_OTA_HTTP_RX_BUFFER_SIZE=1024 +CONFIG_ESP_RMAKER_OTA_ROLLBACK_WAIT_PERIOD=90 +# CONFIG_ESP_RMAKER_OTA_DISABLE_AUTO_REBOOT is not set +CONFIG_ESP_RMAKER_OTA_TIME_SUPPORT=y +# end of ESP RainMaker OTA Config + +# +# ESP RainMaker Scheduling +# +CONFIG_ESP_RMAKER_SCHEDULING_MAX_SCHEDULES=10 +# end of ESP RainMaker Scheduling + +# +# ESP RainMaker Scenes +# +CONFIG_ESP_RMAKER_SCENES_MAX_SCENES=10 +# CONFIG_ESP_RMAKER_SCENES_DEACTIVATE_SUPPORT is not set +# end of ESP RainMaker Scenes + +# +# ESP RainMaker Command-Response +# +CONFIG_ESP_RMAKER_CMD_RESP_ENABLE=y +# CONFIG_ESP_RMAKER_CMD_RESP_TEST_ENABLE is not set +# end of ESP RainMaker Command-Response +# end of ESP RainMaker Config + +# +# Arduino Configuration +# +CONFIG_ARDUINO_VARIANT="esp32" +CONFIG_ENABLE_ARDUINO_DEPENDS=y +CONFIG_AUTOSTART_ARDUINO=y +# CONFIG_ARDUINO_RUN_CORE0 is not set +CONFIG_ARDUINO_RUN_CORE1=y +# CONFIG_ARDUINO_RUN_NO_AFFINITY is not set +CONFIG_ARDUINO_RUNNING_CORE=1 +CONFIG_ARDUINO_LOOP_STACK_SIZE=8192 +# CONFIG_ARDUINO_EVENT_RUN_CORE0 is not set +CONFIG_ARDUINO_EVENT_RUN_CORE1=y +# CONFIG_ARDUINO_EVENT_RUN_NO_AFFINITY is not set +CONFIG_ARDUINO_EVENT_RUNNING_CORE=1 +# CONFIG_ARDUINO_SERIAL_EVENT_RUN_CORE0 is not set +# CONFIG_ARDUINO_SERIAL_EVENT_RUN_CORE1 is not set +CONFIG_ARDUINO_SERIAL_EVENT_RUN_NO_AFFINITY=y +CONFIG_ARDUINO_SERIAL_EVENT_TASK_RUNNING_CORE=-1 +CONFIG_ARDUINO_SERIAL_EVENT_TASK_STACK_SIZE=2048 +CONFIG_ARDUINO_SERIAL_EVENT_TASK_PRIORITY=24 +CONFIG_ARDUINO_UDP_RUN_CORE0=y +# CONFIG_ARDUINO_UDP_RUN_CORE1 is not set +# CONFIG_ARDUINO_UDP_RUN_NO_AFFINITY is not set +CONFIG_ARDUINO_UDP_RUNNING_CORE=0 +CONFIG_ARDUINO_UDP_TASK_PRIORITY=3 +# CONFIG_ARDUINO_ISR_IRAM is not set +# CONFIG_DISABLE_HAL_LOCKS is not set + +# +# Debug Log Configuration +# +# CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_NONE is not set +CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_ERROR=y +# CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_WARN is not set +# CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_INFO is not set +# CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_DEBUG is not set +# CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_VERBOSE is not set +CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL=1 +# CONFIG_ARDUHAL_LOG_COLORS is not set +CONFIG_ARDUHAL_ESP_LOG=y +# end of Debug Log Configuration + +CONFIG_ARDUHAL_PARTITION_SCHEME_DEFAULT=y +# CONFIG_ARDUHAL_PARTITION_SCHEME_MINIMAL is not set +# CONFIG_ARDUHAL_PARTITION_SCHEME_NO_OTA is not set +# CONFIG_ARDUHAL_PARTITION_SCHEME_HUGE_APP is not set +# CONFIG_ARDUHAL_PARTITION_SCHEME_MIN_SPIFFS is not set +CONFIG_ARDUHAL_PARTITION_SCHEME="default" +# CONFIG_AUTOCONNECT_WIFI is not set +# CONFIG_ARDUINO_SELECTIVE_COMPILATION is not set +# end of Arduino Configuration + +# +# Arduino TinyUSB +# +# end of Arduino TinyUSB + +# +# ESP Speech Recognition +# +CONFIG_USE_AFE=y +CONFIG_AFE_INTERFACE_V1=y +# CONFIG_USE_WAKENET is not set +# CONFIG_USE_MULTINET is not set +# end of ESP Speech Recognition + +# +# Compiler options +# +# CONFIG_COMPILER_OPTIMIZATION_DEFAULT is not set +CONFIG_COMPILER_OPTIMIZATION_SIZE=y +# CONFIG_COMPILER_OPTIMIZATION_PERF is not set +# CONFIG_COMPILER_OPTIMIZATION_NONE is not set +CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y +# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set +# CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE is not set +CONFIG_COMPILER_OPTIMIZATION_ASSERTION_LEVEL=2 +# CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT is not set +CONFIG_COMPILER_HIDE_PATHS_MACROS=y +CONFIG_COMPILER_CXX_EXCEPTIONS=y +CONFIG_COMPILER_CXX_EXCEPTIONS_EMG_POOL_SIZE=0 +# CONFIG_COMPILER_CXX_RTTI is not set +# CONFIG_COMPILER_STACK_CHECK_MODE_NONE is not set +CONFIG_COMPILER_STACK_CHECK_MODE_NORM=y +# CONFIG_COMPILER_STACK_CHECK_MODE_STRONG is not set +# CONFIG_COMPILER_STACK_CHECK_MODE_ALL is not set +CONFIG_COMPILER_STACK_CHECK=y +CONFIG_COMPILER_WARN_WRITE_STRINGS=y +# CONFIG_COMPILER_DISABLE_GCC8_WARNINGS is not set +# CONFIG_COMPILER_DUMP_RTL_FILES is not set +# end of Compiler options + +# +# Component config +# + +# +# Application Level Tracing +# +# CONFIG_APPTRACE_DEST_JTAG is not set +CONFIG_APPTRACE_DEST_NONE=y +CONFIG_APPTRACE_LOCK_ENABLE=y +# end of Application Level Tracing + +# +# ESP-ASIO +# +# CONFIG_ASIO_SSL_SUPPORT is not set +# end of ESP-ASIO + +# +# Bluetooth +# +CONFIG_BT_ENABLED=y + +# +# Bluetooth controller +# +# CONFIG_BTDM_CTRL_MODE_BLE_ONLY is not set +# CONFIG_BTDM_CTRL_MODE_BR_EDR_ONLY is not set +CONFIG_BTDM_CTRL_MODE_BTDM=y +CONFIG_BTDM_CTRL_BLE_MAX_CONN=3 +CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN=2 +CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN=0 +# CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_HCI is not set +CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_PCM=y +CONFIG_BTDM_CTRL_BR_EDR_SCO_DATA_PATH_EFF=1 +CONFIG_BTDM_CTRL_PCM_ROLE_EDGE_CONFIG=y +CONFIG_BTDM_CTRL_PCM_ROLE_MASTER=y +# CONFIG_BTDM_CTRL_PCM_ROLE_SLAVE is not set +CONFIG_BTDM_CTRL_PCM_POLAR_FALLING_EDGE=y +# CONFIG_BTDM_CTRL_PCM_POLAR_RISING_EDGE is not set +CONFIG_BTDM_CTRL_PCM_ROLE_EFF=0 +CONFIG_BTDM_CTRL_PCM_POLAR_EFF=0 +# CONFIG_BTDM_CTRL_AUTO_LATENCY is not set +CONFIG_BTDM_CTRL_LEGACY_AUTH_VENDOR_EVT=y +CONFIG_BTDM_CTRL_LEGACY_AUTH_VENDOR_EVT_EFF=y +CONFIG_BTDM_CTRL_BLE_MAX_CONN_EFF=3 +CONFIG_BTDM_CTRL_BR_EDR_MAX_ACL_CONN_EFF=2 +CONFIG_BTDM_CTRL_BR_EDR_MAX_SYNC_CONN_EFF=0 +CONFIG_BTDM_CTRL_PINNED_TO_CORE_0=y +# CONFIG_BTDM_CTRL_PINNED_TO_CORE_1 is not set +CONFIG_BTDM_CTRL_PINNED_TO_CORE=0 +CONFIG_BTDM_CTRL_HCI_MODE_VHCI=y +# CONFIG_BTDM_CTRL_HCI_MODE_UART_H4 is not set + +# +# MODEM SLEEP Options +# +CONFIG_BTDM_CTRL_MODEM_SLEEP=y +CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_ORIG=y +# CONFIG_BTDM_CTRL_MODEM_SLEEP_MODE_EVED is not set +CONFIG_BTDM_CTRL_LPCLK_SEL_MAIN_XTAL=y +# end of MODEM SLEEP Options + +CONFIG_BTDM_BLE_DEFAULT_SCA_250PPM=y +CONFIG_BTDM_BLE_SLEEP_CLOCK_ACCURACY_INDEX_EFF=1 +CONFIG_BTDM_BLE_SCAN_DUPL=y +CONFIG_BTDM_SCAN_DUPL_TYPE_DEVICE=y +# CONFIG_BTDM_SCAN_DUPL_TYPE_DATA is not set +# CONFIG_BTDM_SCAN_DUPL_TYPE_DATA_DEVICE is not set +CONFIG_BTDM_SCAN_DUPL_TYPE=0 +CONFIG_BTDM_SCAN_DUPL_CACHE_SIZE=20 +CONFIG_BTDM_BLE_MESH_SCAN_DUPL_EN=y +CONFIG_BTDM_MESH_DUPL_SCAN_CACHE_SIZE=100 +CONFIG_BTDM_CTRL_FULL_SCAN_SUPPORTED=y +CONFIG_BTDM_BLE_ADV_REPORT_FLOW_CTRL_SUPP=y +CONFIG_BTDM_BLE_ADV_REPORT_FLOW_CTRL_NUM=100 +CONFIG_BTDM_BLE_ADV_REPORT_DISCARD_THRSHOLD=20 +CONFIG_BTDM_RESERVE_DRAM=0xdb5c +CONFIG_BTDM_CTRL_HLI=y +# end of Bluetooth controller + +CONFIG_BT_BLUEDROID_ENABLED=y +# CONFIG_BT_NIMBLE_ENABLED is not set +# CONFIG_BT_CONTROLLER_ONLY is not set + +# +# Bluedroid Options +# +CONFIG_BT_BTC_TASK_STACK_SIZE=8192 +CONFIG_BT_BLUEDROID_PINNED_TO_CORE_0=y +# CONFIG_BT_BLUEDROID_PINNED_TO_CORE_1 is not set +CONFIG_BT_BLUEDROID_PINNED_TO_CORE=0 +CONFIG_BT_BTU_TASK_STACK_SIZE=8192 +# CONFIG_BT_BLUEDROID_MEM_DEBUG is not set +CONFIG_BT_CLASSIC_ENABLED=y +CONFIG_BT_A2DP_ENABLE=y +CONFIG_BT_SPP_ENABLED=y +CONFIG_BT_HFP_ENABLE=y +CONFIG_BT_HFP_CLIENT_ENABLE=y +# CONFIG_BT_HFP_AG_ENABLE is not set +CONFIG_BT_HFP_AUDIO_DATA_PATH_PCM=y +# CONFIG_BT_HFP_AUDIO_DATA_PATH_HCI is not set +# CONFIG_BT_HID_ENABLED is not set +CONFIG_BT_SSP_ENABLED=y +CONFIG_BT_BLE_ENABLED=y +CONFIG_BT_GATTS_ENABLE=y +# CONFIG_BT_GATTS_PPCP_CHAR_GAP is not set +# CONFIG_BT_BLE_BLUFI_ENABLE is not set +CONFIG_BT_GATT_MAX_SR_PROFILES=8 +CONFIG_BT_GATT_MAX_SR_ATTRIBUTES=100 +# CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MANUAL is not set +CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_AUTO=y +CONFIG_BT_GATTS_SEND_SERVICE_CHANGE_MODE=0 +CONFIG_BT_GATTC_ENABLE=y +CONFIG_BT_GATTC_MAX_CACHE_CHAR=40 +# CONFIG_BT_GATTC_CACHE_NVS_FLASH is not set +CONFIG_BT_GATTC_CONNECT_RETRY_COUNT=3 +CONFIG_BT_BLE_SMP_ENABLE=y +# CONFIG_BT_SMP_SLAVE_CON_PARAMS_UPD_ENABLE is not set +CONFIG_BT_STACK_NO_LOG=y +CONFIG_BT_ACL_CONNECTIONS=4 +CONFIG_BT_MULTI_CONNECTION_ENBALE=y +# CONFIG_BT_ALLOCATION_FROM_SPIRAM_FIRST is not set +CONFIG_BT_BLE_DYNAMIC_ENV_MEMORY=y +# CONFIG_BT_BLE_HOST_QUEUE_CONG_CHECK is not set +CONFIG_BT_SMP_ENABLE=y +# CONFIG_BT_BLE_ACT_SCAN_REP_ADV_SCAN is not set +CONFIG_BT_BLE_ESTAB_LINK_CONN_TOUT=30 +CONFIG_BT_MAX_DEVICE_NAME_LEN=32 +# CONFIG_BT_BLE_RPA_SUPPORTED is not set +# end of Bluedroid Options +# end of Bluetooth + +CONFIG_BLE_MESH=y +CONFIG_BLE_MESH_HCI_5_0=y +CONFIG_BLE_MESH_USE_DUPLICATE_SCAN=y +CONFIG_BLE_MESH_MEM_ALLOC_MODE_INTERNAL=y +# CONFIG_BLE_MESH_MEM_ALLOC_MODE_EXTERNAL is not set +# CONFIG_BLE_MESH_MEM_ALLOC_MODE_DEFAULT is not set +# CONFIG_BLE_MESH_FREERTOS_STATIC_ALLOC is not set +CONFIG_BLE_MESH_DEINIT=y + +# +# BLE Mesh and BLE coexistence support +# +# CONFIG_BLE_MESH_SUPPORT_BLE_ADV is not set +# CONFIG_BLE_MESH_SUPPORT_BLE_SCAN is not set +# end of BLE Mesh and BLE coexistence support + +# CONFIG_BLE_MESH_FAST_PROV is not set +# CONFIG_BLE_MESH_NODE is not set +# CONFIG_BLE_MESH_PROVISIONER is not set +CONFIG_BLE_MESH_PROV=y +CONFIG_BLE_MESH_PB_ADV=y +# CONFIG_BLE_MESH_PB_GATT is not set +CONFIG_BLE_MESH_PROXY=y +# CONFIG_BLE_MESH_GATT_PROXY_CLIENT is not set +CONFIG_BLE_MESH_NET_BUF_POOL_USAGE=y +# CONFIG_BLE_MESH_SETTINGS is not set +CONFIG_BLE_MESH_SUBNET_COUNT=3 +CONFIG_BLE_MESH_APP_KEY_COUNT=3 +CONFIG_BLE_MESH_MODEL_KEY_COUNT=3 +CONFIG_BLE_MESH_MODEL_GROUP_COUNT=3 +CONFIG_BLE_MESH_LABEL_COUNT=3 +CONFIG_BLE_MESH_CRPL=10 +CONFIG_BLE_MESH_MSG_CACHE_SIZE=10 +CONFIG_BLE_MESH_ADV_BUF_COUNT=60 +CONFIG_BLE_MESH_IVU_DIVIDER=4 +# CONFIG_BLE_MESH_IVU_RECOVERY_IVI is not set +CONFIG_BLE_MESH_TX_SEG_MSG_COUNT=1 +CONFIG_BLE_MESH_RX_SEG_MSG_COUNT=1 +CONFIG_BLE_MESH_RX_SDU_MAX=384 +CONFIG_BLE_MESH_TX_SEG_MAX=32 +# CONFIG_BLE_MESH_FRIEND is not set +# CONFIG_BLE_MESH_NO_LOG is not set + +# +# BLE Mesh STACK DEBUG LOG LEVEL +# +# CONFIG_BLE_MESH_TRACE_LEVEL_NONE is not set +# CONFIG_BLE_MESH_TRACE_LEVEL_ERROR is not set +CONFIG_BLE_MESH_TRACE_LEVEL_WARNING=y +# CONFIG_BLE_MESH_TRACE_LEVEL_INFO is not set +# CONFIG_BLE_MESH_TRACE_LEVEL_DEBUG is not set +# CONFIG_BLE_MESH_TRACE_LEVEL_VERBOSE is not set +CONFIG_BLE_MESH_STACK_TRACE_LEVEL=2 +# end of BLE Mesh STACK DEBUG LOG LEVEL + +# +# BLE Mesh NET BUF DEBUG LOG LEVEL +# +# CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_NONE is not set +# CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_ERROR is not set +CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_WARNING=y +# CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_INFO is not set +# CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_DEBUG is not set +# CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL_VERBOSE is not set +CONFIG_BLE_MESH_NET_BUF_TRACE_LEVEL=2 +# end of BLE Mesh NET BUF DEBUG LOG LEVEL + +CONFIG_BLE_MESH_CLIENT_MSG_TIMEOUT=4000 + +# +# Support for BLE Mesh Foundation models +# +# CONFIG_BLE_MESH_CFG_CLI is not set +# CONFIG_BLE_MESH_HEALTH_CLI is not set +CONFIG_BLE_MESH_HEALTH_SRV=y +# end of Support for BLE Mesh Foundation models + +# +# Support for BLE Mesh Client/Server models +# +# CONFIG_BLE_MESH_GENERIC_ONOFF_CLI is not set +# CONFIG_BLE_MESH_GENERIC_LEVEL_CLI is not set +# CONFIG_BLE_MESH_GENERIC_DEF_TRANS_TIME_CLI is not set +# CONFIG_BLE_MESH_GENERIC_POWER_ONOFF_CLI is not set +# CONFIG_BLE_MESH_GENERIC_POWER_LEVEL_CLI is not set +# CONFIG_BLE_MESH_GENERIC_BATTERY_CLI is not set +# CONFIG_BLE_MESH_GENERIC_LOCATION_CLI is not set +# CONFIG_BLE_MESH_GENERIC_PROPERTY_CLI is not set +# CONFIG_BLE_MESH_SENSOR_CLI is not set +# CONFIG_BLE_MESH_TIME_CLI is not set +# CONFIG_BLE_MESH_SCENE_CLI is not set +# CONFIG_BLE_MESH_SCHEDULER_CLI is not set +# CONFIG_BLE_MESH_LIGHT_LIGHTNESS_CLI is not set +# CONFIG_BLE_MESH_LIGHT_CTL_CLI is not set +# CONFIG_BLE_MESH_LIGHT_HSL_CLI is not set +# CONFIG_BLE_MESH_LIGHT_XYL_CLI is not set +# CONFIG_BLE_MESH_LIGHT_LC_CLI is not set +CONFIG_BLE_MESH_GENERIC_SERVER=y +CONFIG_BLE_MESH_SENSOR_SERVER=y +CONFIG_BLE_MESH_TIME_SCENE_SERVER=y +CONFIG_BLE_MESH_LIGHTING_SERVER=y +# end of Support for BLE Mesh Client/Server models + +# CONFIG_BLE_MESH_IV_UPDATE_TEST is not set +CONFIG_BLE_MESH_DISCARD_OLD_SEQ_AUTH=y + +# +# BLE Mesh specific test option +# +# CONFIG_BLE_MESH_SELF_TEST is not set +# CONFIG_BLE_MESH_SHELL is not set +# CONFIG_BLE_MESH_DEBUG is not set +# end of BLE Mesh specific test option + +# +# CoAP Configuration +# +CONFIG_COAP_MBEDTLS_PSK=y +# CONFIG_COAP_MBEDTLS_PKI is not set +# CONFIG_COAP_MBEDTLS_DEBUG is not set +CONFIG_COAP_LOG_DEFAULT_LEVEL=0 +# end of CoAP Configuration + +# +# Driver configurations +# + +# +# ADC configuration +# +# CONFIG_ADC_FORCE_XPD_FSM is not set +CONFIG_ADC_DISABLE_DAC=y +# end of ADC configuration + +# +# MCPWM configuration +# +# CONFIG_MCPWM_ISR_IN_IRAM is not set +# end of MCPWM configuration + +# +# SPI configuration +# +# CONFIG_SPI_MASTER_IN_IRAM is not set +# CONFIG_SPI_MASTER_ISR_IN_IRAM is not set +# CONFIG_SPI_SLAVE_IN_IRAM is not set +# CONFIG_SPI_SLAVE_ISR_IN_IRAM is not set +# end of SPI configuration + +# +# TWAI configuration +# +# CONFIG_TWAI_ISR_IN_IRAM is not set +CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC=y +CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST=y +CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID=y +CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT=y +# end of TWAI configuration + +# +# UART configuration +# +# CONFIG_UART_ISR_IN_IRAM is not set +# end of UART configuration + +# +# RTCIO configuration +# +# CONFIG_RTCIO_SUPPORT_RTC_GPIO_DESC is not set +# end of RTCIO configuration + +# +# GPIO Configuration +# +# CONFIG_GPIO_ESP32_SUPPORT_SWITCH_SLP_PULL is not set +# end of GPIO Configuration + +# +# GDMA Configuration +# +# CONFIG_GDMA_CTRL_FUNC_IN_IRAM is not set +# CONFIG_GDMA_ISR_IRAM_SAFE is not set +# end of GDMA Configuration +# end of Driver configurations + +# +# eFuse Bit Manager +# +# CONFIG_EFUSE_CUSTOM_TABLE is not set +# CONFIG_EFUSE_VIRTUAL is not set +# CONFIG_EFUSE_CODE_SCHEME_COMPAT_NONE is not set +CONFIG_EFUSE_CODE_SCHEME_COMPAT_3_4=y +# CONFIG_EFUSE_CODE_SCHEME_COMPAT_REPEAT is not set +CONFIG_EFUSE_MAX_BLK_LEN=192 +# end of eFuse Bit Manager + +# +# ESP-TLS +# +CONFIG_ESP_TLS_USING_MBEDTLS=y +# CONFIG_ESP_TLS_USE_SECURE_ELEMENT is not set +# CONFIG_ESP_TLS_CLIENT_SESSION_TICKETS is not set +CONFIG_ESP_TLS_SERVER=y +# CONFIG_ESP_TLS_SERVER_SESSION_TICKETS is not set +# CONFIG_ESP_TLS_SERVER_MIN_AUTH_MODE_OPTIONAL is not set +# CONFIG_ESP_TLS_PSK_VERIFICATION is not set +# CONFIG_ESP_TLS_INSECURE is not set +# end of ESP-TLS + +# +# ESP32-specific +# +CONFIG_ESP32_ECO3_CACHE_LOCK_FIX=y +CONFIG_ESP32_REV_MIN_0=y +# CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_2 is not set +# CONFIG_ESP32_REV_MIN_3 is not set +CONFIG_ESP32_REV_MIN=0 +CONFIG_ESP32_DPORT_WORKAROUND=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_160=y +# CONFIG_ESP32_DEFAULT_CPU_FREQ_240 is not set +CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ=160 +CONFIG_ESP32_SPIRAM_SUPPORT=y + +# +# SPI RAM config +# +CONFIG_SPIRAM_TYPE_AUTO=y +# CONFIG_SPIRAM_TYPE_ESPPSRAM16 is not set +# CONFIG_SPIRAM_TYPE_ESPPSRAM32 is not set +# CONFIG_SPIRAM_TYPE_ESPPSRAM64 is not set +CONFIG_SPIRAM_SIZE=-1 +# CONFIG_SPIRAM_SPEED_40M is not set +CONFIG_SPIRAM_SPEED_80M=y +CONFIG_SPIRAM=y +# CONFIG_SPIRAM_BOOT_INIT is not set +# CONFIG_SPIRAM_USE_MEMMAP is not set +# CONFIG_SPIRAM_USE_CAPS_ALLOC is not set +CONFIG_SPIRAM_USE_MALLOC=y +CONFIG_SPIRAM_MALLOC_ALWAYSINTERNAL=4096 +# CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP is not set +CONFIG_SPIRAM_MALLOC_RESERVE_INTERNAL=0 +# CONFIG_SPIRAM_ALLOW_BSS_SEG_EXTERNAL_MEMORY is not set +# CONFIG_SPIRAM_ALLOW_NOINIT_SEG_EXTERNAL_MEMORY is not set +CONFIG_SPIRAM_CACHE_WORKAROUND=y + +# +# SPIRAM cache workaround debugging +# +CONFIG_SPIRAM_CACHE_WORKAROUND_STRATEGY_MEMW=y +# CONFIG_SPIRAM_CACHE_WORKAROUND_STRATEGY_DUPLDST is not set +# CONFIG_SPIRAM_CACHE_WORKAROUND_STRATEGY_NOPS is not set +# end of SPIRAM cache workaround debugging + +# +# SPIRAM workaround libraries placement +# +CONFIG_SPIRAM_CACHE_LIBJMP_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBMATH_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBNUMPARSER_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBIO_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBTIME_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBCHAR_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBMEM_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBSTR_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBRAND_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBENV_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBFILE_IN_IRAM=y +CONFIG_SPIRAM_CACHE_LIBMISC_IN_IRAM=y +# end of SPIRAM workaround libraries placement + +CONFIG_SPIRAM_BANKSWITCH_ENABLE=y +CONFIG_SPIRAM_BANKSWITCH_RESERVE=8 +# CONFIG_SPIRAM_ALLOW_STACK_EXTERNAL_MEMORY is not set +CONFIG_SPIRAM_OCCUPY_HSPI_HOST=y +# CONFIG_SPIRAM_OCCUPY_VSPI_HOST is not set +# CONFIG_SPIRAM_OCCUPY_NO_HOST is not set + +# +# PSRAM clock and cs IO for ESP32-DOWD +# +CONFIG_D0WD_PSRAM_CLK_IO=17 +CONFIG_D0WD_PSRAM_CS_IO=16 +# end of PSRAM clock and cs IO for ESP32-DOWD + +# +# PSRAM clock and cs IO for ESP32-D2WD +# +CONFIG_D2WD_PSRAM_CLK_IO=9 +CONFIG_D2WD_PSRAM_CS_IO=10 +# end of PSRAM clock and cs IO for ESP32-D2WD + +# +# PSRAM clock and cs IO for ESP32-PICO +# +CONFIG_PICO_PSRAM_CS_IO=10 +# end of PSRAM clock and cs IO for ESP32-PICO + +# CONFIG_SPIRAM_2T_MODE is not set +# end of SPI RAM config + +# CONFIG_ESP32_TRAX is not set +CONFIG_ESP32_TRACEMEM_RESERVE_DRAM=0x0 +CONFIG_ESP32_ULP_COPROC_ENABLED=y +CONFIG_ESP32_ULP_COPROC_RESERVE_MEM=512 +CONFIG_ESP32_DEBUG_OCDAWARE=y +CONFIG_ESP32_BROWNOUT_DET=y +CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_0=y +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_1 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_2 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_3 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_4 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_5 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_6 is not set +# CONFIG_ESP32_BROWNOUT_DET_LVL_SEL_7 is not set +CONFIG_ESP32_BROWNOUT_DET_LVL=0 +CONFIG_ESP32_TIME_SYSCALL_USE_RTC_FRC1=y +# CONFIG_ESP32_TIME_SYSCALL_USE_RTC is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_FRC1 is not set +# CONFIG_ESP32_TIME_SYSCALL_USE_NONE is not set +CONFIG_ESP32_RTC_CLK_SRC_INT_RC=y +# CONFIG_ESP32_RTC_CLK_SRC_EXT_CRYS is not set +# CONFIG_ESP32_RTC_CLK_SRC_EXT_OSC is not set +# CONFIG_ESP32_RTC_CLK_SRC_INT_8MD256 is not set +CONFIG_ESP32_RTC_CLK_CAL_CYCLES=1024 +CONFIG_ESP32_DEEP_SLEEP_WAKEUP_DELAY=2000 +# CONFIG_ESP32_XTAL_FREQ_40 is not set +# CONFIG_ESP32_XTAL_FREQ_26 is not set +CONFIG_ESP32_XTAL_FREQ_AUTO=y +CONFIG_ESP32_XTAL_FREQ=0 +# CONFIG_ESP32_DISABLE_BASIC_ROM_CONSOLE is not set +# CONFIG_ESP32_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set +# CONFIG_ESP32_COMPATIBLE_PRE_V3_1_BOOTLOADERS is not set +# CONFIG_ESP32_USE_FIXED_STATIC_RAM_SIZE is not set +CONFIG_ESP32_DPORT_DIS_INTERRUPT_LVL=5 +# end of ESP32-specific + +# +# ADC-Calibration +# +CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y +CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y +CONFIG_ADC_CAL_LUT_ENABLE=y +# end of ADC-Calibration + +# +# Common ESP-related +# +CONFIG_ESP_ERR_TO_NAME_LOOKUP=y +# end of Common ESP-related + +# +# Ethernet +# +CONFIG_ETH_ENABLED=y +CONFIG_ETH_USE_ESP32_EMAC=y +CONFIG_ETH_PHY_INTERFACE_RMII=y +CONFIG_ETH_RMII_CLK_INPUT=y +# CONFIG_ETH_RMII_CLK_OUTPUT is not set +CONFIG_ETH_RMII_CLK_IN_GPIO=0 +CONFIG_ETH_DMA_BUFFER_SIZE=512 +CONFIG_ETH_DMA_RX_BUFFER_NUM=10 +CONFIG_ETH_DMA_TX_BUFFER_NUM=10 +CONFIG_ETH_USE_SPI_ETHERNET=y +CONFIG_ETH_SPI_ETHERNET_DM9051=y +CONFIG_ETH_SPI_ETHERNET_W5500=y +# CONFIG_ETH_SPI_ETHERNET_KSZ8851SNL is not set +# CONFIG_ETH_USE_OPENETH is not set +# end of Ethernet + +# +# Event Loop Library +# +# CONFIG_ESP_EVENT_LOOP_PROFILING is not set +CONFIG_ESP_EVENT_POST_FROM_ISR=y +CONFIG_ESP_EVENT_POST_FROM_IRAM_ISR=y +# end of Event Loop Library + +# +# GDB Stub +# +# end of GDB Stub + +# +# ESP HTTP client +# +CONFIG_ESP_HTTP_CLIENT_ENABLE_HTTPS=y +CONFIG_ESP_HTTP_CLIENT_ENABLE_BASIC_AUTH=y +CONFIG_ESP_HTTP_CLIENT_ENABLE_DIGEST_AUTH=y +# end of ESP HTTP client + +# +# HTTP Server +# +CONFIG_HTTPD_MAX_REQ_HDR_LEN=1024 +CONFIG_HTTPD_MAX_URI_LEN=512 +CONFIG_HTTPD_ERR_RESP_NO_DELAY=y +CONFIG_HTTPD_PURGE_BUF_LEN=32 +# CONFIG_HTTPD_LOG_PURGE_DATA is not set +CONFIG_HTTPD_WS_SUPPORT=y +# end of HTTP Server + +# +# ESP HTTPS OTA +# +# CONFIG_OTA_ALLOW_HTTP is not set +# end of ESP HTTPS OTA + +# +# ESP HTTPS server +# +CONFIG_ESP_HTTPS_SERVER_ENABLE=y +# end of ESP HTTPS server + +# +# Hardware Settings +# + +# +# MAC Config +# +CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y +CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y +CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y +CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y +# CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO is not set +CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR=y +CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=4 +# end of MAC Config + +# +# Sleep Config +# +CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y +# CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set +CONFIG_ESP_SLEEP_PSRAM_LEAKAGE_WORKAROUND=y +CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y +# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set +# end of Sleep Config + +# +# RTC Clock Config +# +# end of RTC Clock Config +# end of Hardware Settings + +# +# IPC (Inter-Processor Call) +# +CONFIG_ESP_IPC_TASK_STACK_SIZE=1024 +CONFIG_ESP_IPC_USES_CALLERS_PRIORITY=y +CONFIG_ESP_IPC_ISR_ENABLE=y +# end of IPC (Inter-Processor Call) + +# +# LCD and Touch Panel +# + +# +# LCD Peripheral Configuration +# +CONFIG_LCD_PANEL_IO_FORMAT_BUF_SIZE=32 +# end of LCD Peripheral Configuration +# end of LCD and Touch Panel + +# +# ESP NETIF Adapter +# +CONFIG_ESP_NETIF_IP_LOST_TIMER_INTERVAL=120 +CONFIG_ESP_NETIF_TCPIP_LWIP=y +# CONFIG_ESP_NETIF_LOOPBACK is not set +CONFIG_ESP_NETIF_TCPIP_ADAPTER_COMPATIBLE_LAYER=y +# end of ESP NETIF Adapter + +# +# PHY +# +CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y +# CONFIG_ESP_PHY_INIT_DATA_IN_PARTITION is not set +CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 +CONFIG_ESP_PHY_MAX_TX_POWER=20 +CONFIG_ESP_PHY_REDUCE_TX_POWER=y +# end of PHY + +# +# Power Management +# +# CONFIG_PM_ENABLE is not set +# end of Power Management + +# +# ESP Ringbuf +# +# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set +# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set +# end of ESP Ringbuf + +# +# ESP System Settings +# +# CONFIG_ESP_SYSTEM_PANIC_PRINT_HALT is not set +CONFIG_ESP_SYSTEM_PANIC_PRINT_REBOOT=y +# CONFIG_ESP_SYSTEM_PANIC_SILENT_REBOOT is not set +# CONFIG_ESP_SYSTEM_PANIC_GDBSTUB is not set +# CONFIG_ESP_SYSTEM_GDBSTUB_RUNTIME is not set + +# +# Memory protection +# +# end of Memory protection + +CONFIG_ESP_SYSTEM_EVENT_QUEUE_SIZE=32 +CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=2048 +CONFIG_ESP_MAIN_TASK_STACK_SIZE=4096 +CONFIG_ESP_MAIN_TASK_AFFINITY_CPU0=y +# CONFIG_ESP_MAIN_TASK_AFFINITY_CPU1 is not set +# CONFIG_ESP_MAIN_TASK_AFFINITY_NO_AFFINITY is not set +CONFIG_ESP_MAIN_TASK_AFFINITY=0x0 +CONFIG_ESP_MINIMAL_SHARED_STACK_SIZE=2048 +CONFIG_ESP_CONSOLE_UART_DEFAULT=y +# CONFIG_ESP_CONSOLE_UART_CUSTOM is not set +# CONFIG_ESP_CONSOLE_NONE is not set +CONFIG_ESP_CONSOLE_UART=y +CONFIG_ESP_CONSOLE_MULTIPLE_UART=y +CONFIG_ESP_CONSOLE_UART_NUM=0 +CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200 +CONFIG_ESP_INT_WDT=y +CONFIG_ESP_INT_WDT_TIMEOUT_MS=300 +CONFIG_ESP_INT_WDT_CHECK_CPU1=y +CONFIG_ESP_TASK_WDT=y +CONFIG_ESP_TASK_WDT_PANIC=y +CONFIG_ESP_TASK_WDT_TIMEOUT_S=5 +CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y +# CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU1 is not set +# CONFIG_ESP_PANIC_HANDLER_IRAM is not set +# CONFIG_ESP_DEBUG_STUBS_ENABLE is not set +CONFIG_ESP_SYSTEM_CHECK_INT_LEVEL_5=y +# end of ESP System Settings + +# +# High resolution timer (esp_timer) +# +# CONFIG_ESP_TIMER_PROFILING is not set +CONFIG_ESP_TIME_FUNCS_USE_RTC_TIMER=y +CONFIG_ESP_TIME_FUNCS_USE_ESP_TIMER=y +CONFIG_ESP_TIMER_TASK_STACK_SIZE=4096 +CONFIG_ESP_TIMER_INTERRUPT_LEVEL=3 +# CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD is not set +CONFIG_ESP_TIMER_SUPPORTS_ISR_DISPATCH_METHOD=y +# CONFIG_ESP_TIMER_IMPL_FRC2 is not set +CONFIG_ESP_TIMER_IMPL_TG0_LAC=y +# end of High resolution timer (esp_timer) + +# +# Wi-Fi +# +CONFIG_ESP32_WIFI_ENABLED=y +CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE=y +CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM=8 +CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=32 +CONFIG_ESP32_WIFI_STATIC_TX_BUFFER=y +CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=0 +CONFIG_ESP32_WIFI_STATIC_TX_BUFFER_NUM=8 +CONFIG_ESP32_WIFI_CACHE_TX_BUFFER_NUM=16 +CONFIG_ESP32_WIFI_CSI_ENABLED=y +CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED=y +CONFIG_ESP32_WIFI_TX_BA_WIN=6 +CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED=y +CONFIG_ESP32_WIFI_RX_BA_WIN=6 +# CONFIG_ESP32_WIFI_AMSDU_TX_ENABLED is not set +CONFIG_ESP32_WIFI_NVS_ENABLED=y +CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y +# CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set +CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 +CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32 +# CONFIG_ESP32_WIFI_IRAM_OPT is not set +# CONFIG_ESP32_WIFI_RX_IRAM_OPT is not set +CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y +# CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set +# CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set +# CONFIG_ESP_WIFI_GMAC_SUPPORT is not set +CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y +# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set +CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 +# end of Wi-Fi + +# +# Core dump +# +CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH=y +# CONFIG_ESP_COREDUMP_ENABLE_TO_UART is not set +# CONFIG_ESP_COREDUMP_ENABLE_TO_NONE is not set +# CONFIG_ESP_COREDUMP_DATA_FORMAT_BIN is not set +CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y +CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y +# CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set +CONFIG_ESP_COREDUMP_CHECK_BOOT=y +CONFIG_ESP_COREDUMP_ENABLE=y +CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 +# end of Core dump + +# +# FAT Filesystem support +# +# CONFIG_FATFS_CODEPAGE_DYNAMIC is not set +# CONFIG_FATFS_CODEPAGE_437 is not set +# CONFIG_FATFS_CODEPAGE_720 is not set +# CONFIG_FATFS_CODEPAGE_737 is not set +# CONFIG_FATFS_CODEPAGE_771 is not set +# CONFIG_FATFS_CODEPAGE_775 is not set +CONFIG_FATFS_CODEPAGE_850=y +# CONFIG_FATFS_CODEPAGE_852 is not set +# CONFIG_FATFS_CODEPAGE_855 is not set +# CONFIG_FATFS_CODEPAGE_857 is not set +# CONFIG_FATFS_CODEPAGE_860 is not set +# CONFIG_FATFS_CODEPAGE_861 is not set +# CONFIG_FATFS_CODEPAGE_862 is not set +# CONFIG_FATFS_CODEPAGE_863 is not set +# CONFIG_FATFS_CODEPAGE_864 is not set +# CONFIG_FATFS_CODEPAGE_865 is not set +# CONFIG_FATFS_CODEPAGE_866 is not set +# CONFIG_FATFS_CODEPAGE_869 is not set +# CONFIG_FATFS_CODEPAGE_932 is not set +# CONFIG_FATFS_CODEPAGE_936 is not set +# CONFIG_FATFS_CODEPAGE_949 is not set +# CONFIG_FATFS_CODEPAGE_950 is not set +CONFIG_FATFS_CODEPAGE=850 +# CONFIG_FATFS_LFN_NONE is not set +# CONFIG_FATFS_LFN_HEAP is not set +CONFIG_FATFS_LFN_STACK=y +CONFIG_FATFS_MAX_LFN=255 +# CONFIG_FATFS_API_ENCODING_ANSI_OEM is not set +# CONFIG_FATFS_API_ENCODING_UTF_16 is not set +CONFIG_FATFS_API_ENCODING_UTF_8=y +CONFIG_FATFS_FS_LOCK=0 +CONFIG_FATFS_TIMEOUT_MS=10000 +CONFIG_FATFS_PER_FILE_CACHE=y +CONFIG_FATFS_ALLOC_PREFER_EXTRAM=y +# CONFIG_FATFS_USE_FASTSEEK is not set +# end of FAT Filesystem support + +# +# Modbus configuration +# +CONFIG_FMB_COMM_MODE_TCP_EN=y +CONFIG_FMB_TCP_PORT_DEFAULT=502 +CONFIG_FMB_TCP_PORT_MAX_CONN=5 +CONFIG_FMB_TCP_CONNECTION_TOUT_SEC=20 +CONFIG_FMB_COMM_MODE_RTU_EN=y +CONFIG_FMB_COMM_MODE_ASCII_EN=y +CONFIG_FMB_MASTER_TIMEOUT_MS_RESPOND=150 +CONFIG_FMB_MASTER_DELAY_MS_CONVERT=200 +CONFIG_FMB_QUEUE_LENGTH=20 +CONFIG_FMB_PORT_TASK_STACK_SIZE=4096 +CONFIG_FMB_SERIAL_BUF_SIZE=256 +CONFIG_FMB_SERIAL_ASCII_BITS_PER_SYMB=8 +CONFIG_FMB_SERIAL_ASCII_TIMEOUT_RESPOND_MS=1000 +CONFIG_FMB_PORT_TASK_PRIO=10 +# CONFIG_FMB_PORT_TASK_AFFINITY_NO_AFFINITY is not set +CONFIG_FMB_PORT_TASK_AFFINITY_CPU0=y +# CONFIG_FMB_PORT_TASK_AFFINITY_CPU1 is not set +CONFIG_FMB_PORT_TASK_AFFINITY=0x0 +# CONFIG_FMB_CONTROLLER_SLAVE_ID_SUPPORT is not set +CONFIG_FMB_CONTROLLER_NOTIFY_TIMEOUT=20 +CONFIG_FMB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 +CONFIG_FMB_CONTROLLER_STACK_SIZE=4096 +CONFIG_FMB_EVENT_QUEUE_TIMEOUT=20 +CONFIG_FMB_TIMER_PORT_ENABLED=y +# CONFIG_FMB_TIMER_USE_ISR_DISPATCH_METHOD is not set +# end of Modbus configuration + +# +# FreeRTOS +# +# CONFIG_FREERTOS_UNICORE is not set +CONFIG_FREERTOS_NO_AFFINITY=0x7FFFFFFF +CONFIG_FREERTOS_TICK_SUPPORT_CORETIMER=y +CONFIG_FREERTOS_CORETIMER_0=y +# CONFIG_FREERTOS_CORETIMER_1 is not set +CONFIG_FREERTOS_SYSTICK_USES_CCOUNT=y +CONFIG_FREERTOS_HZ=1000 +# CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION is not set +# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set +# CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set +CONFIG_FREERTOS_CHECK_STACKOVERFLOW_CANARY=y +CONFIG_FREERTOS_WATCHPOINT_END_OF_STACK=y +CONFIG_FREERTOS_INTERRUPT_BACKTRACE=y +CONFIG_FREERTOS_THREAD_LOCAL_STORAGE_POINTERS=1 +CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y +# CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE is not set +# CONFIG_FREERTOS_ASSERT_DISABLE is not set +CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1024 +CONFIG_FREERTOS_ISR_STACKSIZE=2096 +# CONFIG_FREERTOS_LEGACY_HOOKS is not set +CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 +CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y +# CONFIG_FREERTOS_ENABLE_STATIC_TASK_CLEAN_UP is not set +CONFIG_FREERTOS_TIMER_TASK_PRIORITY=1 +CONFIG_FREERTOS_TIMER_TASK_STACK_DEPTH=2048 +CONFIG_FREERTOS_TIMER_QUEUE_LENGTH=10 +CONFIG_FREERTOS_QUEUE_REGISTRY_SIZE=0 +# CONFIG_FREERTOS_USE_TRACE_FACILITY is not set +# CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS is not set +CONFIG_FREERTOS_CHECK_MUTEX_GIVEN_BY_OWNER=y +# CONFIG_FREERTOS_CHECK_PORT_CRITICAL_COMPLIANCE is not set +# CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH is not set +CONFIG_FREERTOS_DEBUG_OCDAWARE=y +CONFIG_FREERTOS_FPU_IN_ISR=y +CONFIG_FREERTOS_ENABLE_TASK_SNAPSHOT=y +# CONFIG_FREERTOS_PLACE_SNAPSHOT_FUNS_INTO_FLASH is not set +# end of FreeRTOS + +# +# Hardware Abstraction Layer (HAL) and Low Level (LL) +# +CONFIG_HAL_ASSERTION_EQUALS_SYSTEM=y +# CONFIG_HAL_ASSERTION_DISABLE is not set +# CONFIG_HAL_ASSERTION_SILIENT is not set +# CONFIG_HAL_ASSERTION_ENABLE is not set +CONFIG_HAL_DEFAULT_ASSERTION_LEVEL=2 +# end of Hardware Abstraction Layer (HAL) and Low Level (LL) + +# +# Heap memory debugging +# +# CONFIG_HEAP_POISONING_DISABLED is not set +CONFIG_HEAP_POISONING_LIGHT=y +# CONFIG_HEAP_POISONING_COMPREHENSIVE is not set +CONFIG_HEAP_TRACING_OFF=y +# CONFIG_HEAP_TRACING_STANDALONE is not set +# CONFIG_HEAP_TRACING_TOHOST is not set +# CONFIG_HEAP_TASK_TRACKING is not set +# CONFIG_HEAP_ABORT_WHEN_ALLOCATION_FAILS is not set +# end of Heap memory debugging + +# +# jsmn +# +# CONFIG_JSMN_PARENT_LINKS is not set +# CONFIG_JSMN_STRICT is not set +# end of jsmn + +# +# libsodium +# +# end of libsodium + +# +# Log output +# +# CONFIG_LOG_DEFAULT_LEVEL_NONE is not set +CONFIG_LOG_DEFAULT_LEVEL_ERROR=y +# CONFIG_LOG_DEFAULT_LEVEL_WARN is not set +# CONFIG_LOG_DEFAULT_LEVEL_INFO is not set +# CONFIG_LOG_DEFAULT_LEVEL_DEBUG is not set +# CONFIG_LOG_DEFAULT_LEVEL_VERBOSE is not set +CONFIG_LOG_DEFAULT_LEVEL=1 +CONFIG_LOG_MAXIMUM_EQUALS_DEFAULT=y +# CONFIG_LOG_MAXIMUM_LEVEL_WARN is not set +# CONFIG_LOG_MAXIMUM_LEVEL_INFO is not set +# CONFIG_LOG_MAXIMUM_LEVEL_DEBUG is not set +# CONFIG_LOG_MAXIMUM_LEVEL_VERBOSE is not set +CONFIG_LOG_MAXIMUM_LEVEL=1 +# CONFIG_LOG_COLORS is not set +CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y +# CONFIG_LOG_TIMESTAMP_SOURCE_SYSTEM is not set +# end of Log output + +# +# LWIP +# +CONFIG_LWIP_LOCAL_HOSTNAME="espressif" +# CONFIG_LWIP_NETIF_API is not set +# CONFIG_LWIP_TCPIP_CORE_LOCKING is not set +CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y +# CONFIG_LWIP_L2_TO_L3_COPY is not set +# CONFIG_LWIP_IRAM_OPTIMIZATION is not set +CONFIG_LWIP_TIMERS_ONDEMAND=y +CONFIG_LWIP_MAX_SOCKETS=16 +# CONFIG_LWIP_USE_ONLY_LWIP_SELECT is not set +# CONFIG_LWIP_SO_LINGER is not set +CONFIG_LWIP_SO_REUSE=y +CONFIG_LWIP_SO_REUSE_RXTOALL=y +CONFIG_LWIP_SO_RCVBUF=y +# CONFIG_LWIP_NETBUF_RECVINFO is not set +CONFIG_LWIP_IP4_FRAG=y +CONFIG_LWIP_IP6_FRAG=y +# CONFIG_LWIP_IP4_REASSEMBLY is not set +# CONFIG_LWIP_IP6_REASSEMBLY is not set +# CONFIG_LWIP_IP_FORWARD is not set +# CONFIG_LWIP_STATS is not set +CONFIG_LWIP_ETHARP_TRUST_IP_MAC=y +CONFIG_LWIP_ESP_GRATUITOUS_ARP=y +CONFIG_LWIP_GARP_TMR_INTERVAL=60 +CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 +# CONFIG_LWIP_DHCP_DOES_ARP_CHECK is not set +# CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set +CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y +CONFIG_LWIP_DHCP_RESTORE_LAST_IP=y +CONFIG_LWIP_DHCP_OPTIONS_LEN=128 + +# +# DHCP server +# +CONFIG_LWIP_DHCPS=y +CONFIG_LWIP_DHCPS_LEASE_UNIT=60 +CONFIG_LWIP_DHCPS_MAX_STATION_NUM=8 +# end of DHCP server + +# CONFIG_LWIP_AUTOIP is not set +CONFIG_LWIP_IPV6=y +CONFIG_LWIP_IPV6_AUTOCONFIG=y +CONFIG_LWIP_IPV6_NUM_ADDRESSES=3 +# CONFIG_LWIP_IPV6_FORWARD is not set +CONFIG_LWIP_IPV6_RDNSS_MAX_DNS_SERVERS=0 +# CONFIG_LWIP_IPV6_DHCP6 is not set +# CONFIG_LWIP_NETIF_STATUS_CALLBACK is not set +CONFIG_LWIP_NETIF_LOOPBACK=y +CONFIG_LWIP_LOOPBACK_MAX_PBUFS=8 + +# +# TCP +# +CONFIG_LWIP_MAX_ACTIVE_TCP=16 +CONFIG_LWIP_MAX_LISTENING_TCP=16 +CONFIG_LWIP_TCP_HIGH_SPEED_RETRANSMISSION=y +CONFIG_LWIP_TCP_MAXRTX=12 +CONFIG_LWIP_TCP_SYNMAXRTX=6 +CONFIG_LWIP_TCP_MSS=1436 +CONFIG_LWIP_TCP_TMR_INTERVAL=250 +CONFIG_LWIP_TCP_MSL=60000 +CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 +CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 +CONFIG_LWIP_TCP_WND_DEFAULT=5744 +CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 +CONFIG_LWIP_TCP_QUEUE_OOSEQ=y +# CONFIG_LWIP_TCP_SACK_OUT is not set +# CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set +CONFIG_LWIP_TCP_OVERSIZE_MSS=y +# CONFIG_LWIP_TCP_OVERSIZE_QUARTER_MSS is not set +# CONFIG_LWIP_TCP_OVERSIZE_DISABLE is not set +CONFIG_LWIP_TCP_RTO_TIME=3000 +# end of TCP + +# +# UDP +# +CONFIG_LWIP_MAX_UDP_PCBS=16 +CONFIG_LWIP_UDP_RECVMBOX_SIZE=6 +# end of UDP + +# +# Checksums +# +# CONFIG_LWIP_CHECKSUM_CHECK_IP is not set +# CONFIG_LWIP_CHECKSUM_CHECK_UDP is not set +CONFIG_LWIP_CHECKSUM_CHECK_ICMP=y +# end of Checksums + +CONFIG_LWIP_TCPIP_TASK_STACK_SIZE=2560 +# CONFIG_LWIP_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set +CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU0=y +# CONFIG_LWIP_TCPIP_TASK_AFFINITY_CPU1 is not set +CONFIG_LWIP_TCPIP_TASK_AFFINITY=0x0 +# CONFIG_LWIP_PPP_SUPPORT is not set +CONFIG_LWIP_IPV6_MEMP_NUM_ND6_QUEUE=3 +CONFIG_LWIP_IPV6_ND6_NUM_NEIGHBORS=5 +# CONFIG_LWIP_SLIP_SUPPORT is not set + +# +# ICMP +# +CONFIG_LWIP_ICMP=y +# CONFIG_LWIP_MULTICAST_PING is not set +# CONFIG_LWIP_BROADCAST_PING is not set +# end of ICMP + +# +# LWIP RAW API +# +CONFIG_LWIP_MAX_RAW_PCBS=16 +# end of LWIP RAW API + +# +# SNTP +# +CONFIG_LWIP_SNTP_MAX_SERVERS=3 +CONFIG_LWIP_DHCP_GET_NTP_SRV=y +CONFIG_LWIP_DHCP_MAX_NTP_SERVERS=1 +CONFIG_LWIP_SNTP_UPDATE_DELAY=10800000 +# end of SNTP + +CONFIG_LWIP_ESP_LWIP_ASSERT=y + +# +# Hooks +# +# CONFIG_LWIP_HOOK_TCP_ISN_NONE is not set +CONFIG_LWIP_HOOK_TCP_ISN_DEFAULT=y +# CONFIG_LWIP_HOOK_TCP_ISN_CUSTOM is not set +CONFIG_LWIP_HOOK_IP6_ROUTE_NONE=y +# CONFIG_LWIP_HOOK_IP6_ROUTE_DEFAULT is not set +# CONFIG_LWIP_HOOK_IP6_ROUTE_CUSTOM is not set +CONFIG_LWIP_HOOK_ND6_GET_GW_NONE=y +# CONFIG_LWIP_HOOK_ND6_GET_GW_DEFAULT is not set +# CONFIG_LWIP_HOOK_ND6_GET_GW_CUSTOM is not set +CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_NONE=y +# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_DEFAULT is not set +# CONFIG_LWIP_HOOK_NETCONN_EXT_RESOLVE_CUSTOM is not set +# end of Hooks + +# CONFIG_LWIP_DEBUG is not set +# end of LWIP + +# +# mbedTLS +# +CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y +# CONFIG_MBEDTLS_EXTERNAL_MEM_ALLOC is not set +# CONFIG_MBEDTLS_DEFAULT_MEM_ALLOC is not set +# CONFIG_MBEDTLS_CUSTOM_MEM_ALLOC is not set +CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN=16384 +# CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN is not set +# CONFIG_MBEDTLS_DEBUG is not set + +# +# mbedTLS v2.28.x related +# +# CONFIG_MBEDTLS_SSL_VARIABLE_BUFFER_LENGTH is not set +# CONFIG_MBEDTLS_X509_TRUSTED_CERT_CALLBACK is not set +# CONFIG_MBEDTLS_SSL_CONTEXT_SERIALIZATION is not set +CONFIG_MBEDTLS_SSL_KEEP_PEER_CERTIFICATE=y + +# +# DTLS-based configurations +# +# CONFIG_MBEDTLS_SSL_DTLS_CONNECTION_ID is not set +# CONFIG_MBEDTLS_SSL_DTLS_SRTP is not set +# end of DTLS-based configurations +# end of mbedTLS v2.28.x related + +# +# Certificate Bundle +# +CONFIG_MBEDTLS_CERTIFICATE_BUNDLE=y +CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y +# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set +# CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set +# CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set +CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 +# end of Certificate Bundle + +# CONFIG_MBEDTLS_ECP_RESTARTABLE is not set +# CONFIG_MBEDTLS_CMAC_C is not set +CONFIG_MBEDTLS_HARDWARE_AES=y +CONFIG_MBEDTLS_HARDWARE_MPI=y +CONFIG_MBEDTLS_HARDWARE_SHA=y +CONFIG_MBEDTLS_ROM_MD5=y +# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set +# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set +CONFIG_MBEDTLS_HAVE_TIME=y +# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set +CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y +CONFIG_MBEDTLS_SHA512_C=y +CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y +# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set +# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set +# CONFIG_MBEDTLS_TLS_DISABLED is not set +CONFIG_MBEDTLS_TLS_SERVER=y +CONFIG_MBEDTLS_TLS_CLIENT=y +CONFIG_MBEDTLS_TLS_ENABLED=y + +# +# TLS Key Exchange Methods +# +CONFIG_MBEDTLS_PSK_MODES=y +CONFIG_MBEDTLS_KEY_EXCHANGE_PSK=y +CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_PSK=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_PSK=y +CONFIG_MBEDTLS_KEY_EXCHANGE_RSA_PSK=y +CONFIG_MBEDTLS_KEY_EXCHANGE_RSA=y +CONFIG_MBEDTLS_KEY_EXCHANGE_DHE_RSA=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ELLIPTIC_CURVE=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_RSA=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ECDHE_ECDSA=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_ECDSA=y +CONFIG_MBEDTLS_KEY_EXCHANGE_ECDH_RSA=y +# end of TLS Key Exchange Methods + +CONFIG_MBEDTLS_SSL_RENEGOTIATION=y +# CONFIG_MBEDTLS_SSL_PROTO_SSL3 is not set +CONFIG_MBEDTLS_SSL_PROTO_TLS1=y +CONFIG_MBEDTLS_SSL_PROTO_TLS1_1=y +CONFIG_MBEDTLS_SSL_PROTO_TLS1_2=y +# CONFIG_MBEDTLS_SSL_PROTO_GMTSSL1_1 is not set +CONFIG_MBEDTLS_SSL_PROTO_DTLS=y +CONFIG_MBEDTLS_SSL_ALPN=y +CONFIG_MBEDTLS_CLIENT_SSL_SESSION_TICKETS=y +CONFIG_MBEDTLS_X509_CHECK_KEY_USAGE=y +CONFIG_MBEDTLS_X509_CHECK_EXTENDED_KEY_USAGE=y +CONFIG_MBEDTLS_SERVER_SSL_SESSION_TICKETS=y + +# +# Symmetric Ciphers +# +CONFIG_MBEDTLS_AES_C=y +CONFIG_MBEDTLS_CAMELLIA_C=y +# CONFIG_MBEDTLS_DES_C is not set +CONFIG_MBEDTLS_RC4_DISABLED=y +# CONFIG_MBEDTLS_RC4_ENABLED_NO_DEFAULT is not set +# CONFIG_MBEDTLS_RC4_ENABLED is not set +# CONFIG_MBEDTLS_BLOWFISH_C is not set +# CONFIG_MBEDTLS_XTEA_C is not set +CONFIG_MBEDTLS_CCM_C=y +CONFIG_MBEDTLS_GCM_C=y +# CONFIG_MBEDTLS_NIST_KW_C is not set +# end of Symmetric Ciphers + +# CONFIG_MBEDTLS_RIPEMD160_C is not set + +# +# Certificates +# +CONFIG_MBEDTLS_PEM_PARSE_C=y +CONFIG_MBEDTLS_PEM_WRITE_C=y +CONFIG_MBEDTLS_X509_CRL_PARSE_C=y +CONFIG_MBEDTLS_X509_CSR_PARSE_C=y +# end of Certificates + +CONFIG_MBEDTLS_ECP_C=y +CONFIG_MBEDTLS_ECDH_C=y +CONFIG_MBEDTLS_ECDSA_C=y +# CONFIG_MBEDTLS_ECJPAKE_C is not set +CONFIG_MBEDTLS_ECP_DP_SECP192R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP224R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP256R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP384R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP521R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP192K1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP224K1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_SECP256K1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_BP256R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y +CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y +CONFIG_MBEDTLS_ECP_NIST_OPTIM=y +# CONFIG_MBEDTLS_POLY1305_C is not set +# CONFIG_MBEDTLS_CHACHA20_C is not set +# CONFIG_MBEDTLS_HKDF_C is not set +# CONFIG_MBEDTLS_THREADING_C is not set +# CONFIG_MBEDTLS_LARGE_KEY_SOFTWARE_MPI is not set +# CONFIG_MBEDTLS_SECURITY_RISKS is not set +# end of mbedTLS + +# +# mDNS +# +CONFIG_MDNS_MAX_SERVICES=10 +CONFIG_MDNS_TASK_PRIORITY=1 +CONFIG_MDNS_TASK_STACK_SIZE=4096 +# CONFIG_MDNS_TASK_AFFINITY_NO_AFFINITY is not set +CONFIG_MDNS_TASK_AFFINITY_CPU0=y +# CONFIG_MDNS_TASK_AFFINITY_CPU1 is not set +CONFIG_MDNS_TASK_AFFINITY=0x0 +CONFIG_MDNS_SERVICE_ADD_TIMEOUT_MS=2000 +# CONFIG_MDNS_STRICT_MODE is not set +CONFIG_MDNS_TIMER_PERIOD_MS=100 +# CONFIG_MDNS_NETWORKING_SOCKET is not set +CONFIG_MDNS_MULTIPLE_INSTANCE=y +# end of mDNS + +# +# ESP-MQTT Configurations +# +CONFIG_MQTT_PROTOCOL_311=y +CONFIG_MQTT_TRANSPORT_SSL=y +CONFIG_MQTT_TRANSPORT_WEBSOCKET=y +CONFIG_MQTT_TRANSPORT_WEBSOCKET_SECURE=y +# CONFIG_MQTT_MSG_ID_INCREMENTAL is not set +# CONFIG_MQTT_SKIP_PUBLISH_IF_DISCONNECTED is not set +# CONFIG_MQTT_REPORT_DELETED_MESSAGES is not set +# CONFIG_MQTT_USE_CUSTOM_CONFIG is not set +# CONFIG_MQTT_TASK_CORE_SELECTION_ENABLED is not set +# CONFIG_MQTT_CUSTOM_OUTBOX is not set +# end of ESP-MQTT Configurations + +# +# Newlib +# +CONFIG_NEWLIB_STDOUT_LINE_ENDING_CRLF=y +# CONFIG_NEWLIB_STDOUT_LINE_ENDING_LF is not set +# CONFIG_NEWLIB_STDOUT_LINE_ENDING_CR is not set +# CONFIG_NEWLIB_STDIN_LINE_ENDING_CRLF is not set +# CONFIG_NEWLIB_STDIN_LINE_ENDING_LF is not set +CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y +# CONFIG_NEWLIB_NANO_FORMAT is not set +# end of Newlib + +# +# NVS +# +# CONFIG_NVS_ASSERT_ERROR_CHECK is not set +# end of NVS + +# +# OpenSSL +# +# CONFIG_OPENSSL_DEBUG is not set +CONFIG_OPENSSL_ERROR_STACK=y +CONFIG_OPENSSL_ASSERT_DO_NOTHING=y +# CONFIG_OPENSSL_ASSERT_EXIT is not set +# end of OpenSSL + +# +# OpenThread +# +# CONFIG_OPENTHREAD_ENABLED is not set +# end of OpenThread + +# +# PThreads +# +CONFIG_PTHREAD_TASK_PRIO_DEFAULT=5 +CONFIG_PTHREAD_TASK_STACK_SIZE_DEFAULT=2048 +CONFIG_PTHREAD_STACK_MIN=768 +CONFIG_PTHREAD_DEFAULT_CORE_NO_AFFINITY=y +# CONFIG_PTHREAD_DEFAULT_CORE_0 is not set +# CONFIG_PTHREAD_DEFAULT_CORE_1 is not set +CONFIG_PTHREAD_TASK_CORE_DEFAULT=-1 +CONFIG_PTHREAD_TASK_NAME_DEFAULT="pthread" +# end of PThreads + +# +# SPI Flash driver +# +# CONFIG_SPI_FLASH_VERIFY_WRITE is not set +# CONFIG_SPI_FLASH_ENABLE_COUNTERS is not set +CONFIG_SPI_FLASH_ROM_DRIVER_PATCH=y +CONFIG_SPI_FLASH_DANGEROUS_WRITE_ABORTS=y +# CONFIG_SPI_FLASH_DANGEROUS_WRITE_FAILS is not set +# CONFIG_SPI_FLASH_DANGEROUS_WRITE_ALLOWED is not set +# CONFIG_SPI_FLASH_USE_LEGACY_IMPL is not set +# CONFIG_SPI_FLASH_SHARE_SPI1_BUS is not set +# CONFIG_SPI_FLASH_BYPASS_BLOCK_ERASE is not set +CONFIG_SPI_FLASH_YIELD_DURING_ERASE=y +CONFIG_SPI_FLASH_ERASE_YIELD_DURATION_MS=10 +CONFIG_SPI_FLASH_ERASE_YIELD_TICKS=2 +CONFIG_SPI_FLASH_WRITE_CHUNK_SIZE=4096 +# CONFIG_SPI_FLASH_SIZE_OVERRIDE is not set +# CONFIG_SPI_FLASH_CHECK_ERASE_TIMEOUT_DISABLED is not set +# CONFIG_SPI_FLASH_OVERRIDE_CHIP_DRIVER_LIST is not set + +# +# Auto-detect flash chips +# +CONFIG_SPI_FLASH_SUPPORT_ISSI_CHIP=y +CONFIG_SPI_FLASH_SUPPORT_MXIC_CHIP=y +CONFIG_SPI_FLASH_SUPPORT_GD_CHIP=y +CONFIG_SPI_FLASH_SUPPORT_WINBOND_CHIP=y +# CONFIG_SPI_FLASH_SUPPORT_BOYA_CHIP is not set +# CONFIG_SPI_FLASH_SUPPORT_TH_CHIP is not set +# end of Auto-detect flash chips + +CONFIG_SPI_FLASH_ENABLE_ENCRYPTED_READ_WRITE=y +# end of SPI Flash driver + +# +# SPIFFS Configuration +# +CONFIG_SPIFFS_MAX_PARTITIONS=3 + +# +# SPIFFS Cache Configuration +# +CONFIG_SPIFFS_CACHE=y +CONFIG_SPIFFS_CACHE_WR=y +# CONFIG_SPIFFS_CACHE_STATS is not set +# end of SPIFFS Cache Configuration + +CONFIG_SPIFFS_PAGE_CHECK=y +CONFIG_SPIFFS_GC_MAX_RUNS=10 +# CONFIG_SPIFFS_GC_STATS is not set +CONFIG_SPIFFS_PAGE_SIZE=256 +CONFIG_SPIFFS_OBJ_NAME_LEN=32 +# CONFIG_SPIFFS_FOLLOW_SYMLINKS is not set +CONFIG_SPIFFS_USE_MAGIC=y +CONFIG_SPIFFS_USE_MAGIC_LENGTH=y +CONFIG_SPIFFS_META_LENGTH=4 +CONFIG_SPIFFS_USE_MTIME=y + +# +# Debug Configuration +# +# CONFIG_SPIFFS_DBG is not set +# CONFIG_SPIFFS_API_DBG is not set +# CONFIG_SPIFFS_GC_DBG is not set +# CONFIG_SPIFFS_CACHE_DBG is not set +# CONFIG_SPIFFS_CHECK_DBG is not set +# CONFIG_SPIFFS_TEST_VISUALISATION is not set +# end of Debug Configuration +# end of SPIFFS Configuration + +# +# TCP Transport +# + +# +# Websocket +# +CONFIG_WS_TRANSPORT=y +CONFIG_WS_BUFFER_SIZE=1024 +# end of Websocket +# end of TCP Transport + +# +# Unity unit testing library +# +CONFIG_UNITY_ENABLE_FLOAT=y +CONFIG_UNITY_ENABLE_DOUBLE=y +# CONFIG_UNITY_ENABLE_64BIT is not set +# CONFIG_UNITY_ENABLE_COLOR is not set +CONFIG_UNITY_ENABLE_IDF_TEST_RUNNER=y +# CONFIG_UNITY_ENABLE_FIXTURE is not set +# CONFIG_UNITY_ENABLE_BACKTRACE_ON_FAIL is not set +# end of Unity unit testing library + +# +# Virtual file system +# +CONFIG_VFS_SUPPORT_IO=y +CONFIG_VFS_SUPPORT_DIR=y +CONFIG_VFS_SUPPORT_SELECT=y +CONFIG_VFS_SUPPRESS_SELECT_DEBUG_OUTPUT=y +CONFIG_VFS_SUPPORT_TERMIOS=y + +# +# Host File System I/O (Semihosting) +# +CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +# end of Host File System I/O (Semihosting) +# end of Virtual file system + +# +# Wear Levelling +# +# CONFIG_WL_SECTOR_SIZE_512 is not set +CONFIG_WL_SECTOR_SIZE_4096=y +CONFIG_WL_SECTOR_SIZE=4096 +# end of Wear Levelling + +# +# Wi-Fi Provisioning Manager +# +CONFIG_WIFI_PROV_SCAN_MAX_ENTRIES=16 +CONFIG_WIFI_PROV_AUTOSTOP_TIMEOUT=30 +# CONFIG_WIFI_PROV_BLE_BONDING is not set +# CONFIG_WIFI_PROV_BLE_FORCE_ENCRYPTION is not set +# CONFIG_WIFI_PROV_KEEP_BLE_ON_AFTER_PROV is not set +# end of Wi-Fi Provisioning Manager + +# +# Supplicant +# +CONFIG_WPA_MBEDTLS_CRYPTO=y +# CONFIG_WPA_WAPI_PSK is not set +# CONFIG_WPA_SUITE_B_192 is not set +# CONFIG_WPA_DEBUG_PRINT is not set +# CONFIG_WPA_TESTING_OPTIONS is not set +# CONFIG_WPA_WPS_STRICT is not set +# CONFIG_WPA_11KV_SUPPORT is not set +# CONFIG_WPA_MBO_SUPPORT is not set +# CONFIG_WPA_DPP_SUPPORT is not set +# end of Supplicant + +# +# Diagnostics +# +CONFIG_DIAG_LOG_MSG_ARG_FORMAT_TLV=y +# CONFIG_DIAG_LOG_MSG_ARG_FORMAT_STRING is not set +CONFIG_DIAG_LOG_MSG_ARG_MAX_SIZE=64 +CONFIG_DIAG_LOG_DROP_WIFI_LOGS=y +CONFIG_DIAG_ENABLE_METRICS=y +CONFIG_DIAG_METRICS_MAX_COUNT=20 +CONFIG_DIAG_ENABLE_HEAP_METRICS=y +CONFIG_DIAG_ENABLE_WIFI_METRICS=y +CONFIG_DIAG_ENABLE_VARIABLES=y +CONFIG_DIAG_VARIABLES_MAX_COUNT=20 +CONFIG_DIAG_ENABLE_NETWORK_VARIABLES=y +# CONFIG_DIAG_MORE_NETWORK_VARS is not set +# end of Diagnostics + +# +# ESP Insights +# +CONFIG_ESP_INSIGHTS_ENABLED=y +# CONFIG_ESP_INSIGHTS_DEBUG_ENABLED is not set +CONFIG_ESP_INSIGHTS_COREDUMP_ENABLE=y +# CONFIG_ESP_INSIGHTS_TRANSPORT_MQTT is not set +CONFIG_ESP_INSIGHTS_TRANSPORT_HTTPS=y +CONFIG_ESP_INSIGHTS_TRANSPORT_HTTPS_HOST="https://client.insights.espressif.com" +CONFIG_ESP_INSIGHTS_CLOUD_POST_MIN_INTERVAL_SEC=60 +CONFIG_ESP_INSIGHTS_CLOUD_POST_MAX_INTERVAL_SEC=240 +# end of ESP Insights + +# +# ESP RainMaker Common +# +CONFIG_ESP_RMAKER_LIB_ESP_MQTT=y +# CONFIG_ESP_RMAKER_LIB_AWS_IOT is not set +CONFIG_ESP_RMAKER_MQTT_GLUE_LIB=1 +CONFIG_ESP_RMAKER_MQTT_PORT_443=y +# CONFIG_ESP_RMAKER_MQTT_PORT_8883 is not set +CONFIG_ESP_RMAKER_MQTT_PORT=1 +# CONFIG_ESP_RMAKER_MQTT_PERSISTENT_SESSION is not set +CONFIG_ESP_RMAKER_MQTT_SEND_USERNAME=y +CONFIG_ESP_RMAKER_MQTT_PRODUCT_NAME="RMDev" +CONFIG_ESP_RMAKER_MQTT_PRODUCT_VERSION="1x0" +CONFIG_ESP_RMAKER_MQTT_PRODUCT_SKU="EX00" +CONFIG_ESP_RMAKER_MQTT_USE_CERT_BUNDLE=y +CONFIG_ESP_RMAKER_MAX_MQTT_SUBSCRIPTIONS=10 +CONFIG_ESP_RMAKER_WORK_QUEUE_TASK_STACK=4096 +CONFIG_ESP_RMAKER_WORK_QUEUE_TASK_PRIORITY=5 +CONFIG_ESP_RMAKER_FACTORY_PARTITION_NAME="fctry" +CONFIG_ESP_RMAKER_FACTORY_NAMESPACE="rmaker_creds" +CONFIG_ESP_RMAKER_DEF_TIMEZONE="Asia/Shanghai" +CONFIG_ESP_RMAKER_SNTP_SERVER_NAME="pool.ntp.org" +CONFIG_ESP_RMAKER_MAX_COMMANDS=10 +# end of ESP RainMaker Common + +# +# RTC Store +# +CONFIG_RTC_STORE_DATA_SIZE=3072 +CONFIG_RTC_STORE_CRITICAL_DATA_SIZE=2048 +CONFIG_RTC_STORE_REPORTING_WATERMARK_PERCENT=80 +# CONFIG_RTC_STORE_OVERWRITE_NON_CRITICAL_DATA is not set +# end of RTC Store + +# +# GPIO Button +# +CONFIG_IO_GLITCH_FILTER_TIME_MS=50 +# end of GPIO Button + +# +# WS2812 RGB LED +# +# CONFIG_WS2812_LED_ENABLE is not set +# end of WS2812 RGB LED + +# +# Camera configuration +# +CONFIG_OV7670_SUPPORT=y +CONFIG_OV7725_SUPPORT=y +CONFIG_NT99141_SUPPORT=y +CONFIG_OV2640_SUPPORT=y +CONFIG_OV3660_SUPPORT=y +CONFIG_OV5640_SUPPORT=y +CONFIG_GC2145_SUPPORT=y +CONFIG_GC032A_SUPPORT=y +CONFIG_GC0308_SUPPORT=y +CONFIG_BF3005_SUPPORT=y +CONFIG_BF20A6_SUPPORT=y +# CONFIG_SC101IOT_SUPPORT is not set +CONFIG_SC030IOT_SUPPORT=y +# CONFIG_SC031GS_SUPPORT is not set +# CONFIG_SCCB_HARDWARE_I2C_PORT0 is not set +CONFIG_SCCB_HARDWARE_I2C_PORT1=y +CONFIG_SCCB_CLK_FREQ=100000 +# CONFIG_GC_SENSOR_WINDOWING_MODE is not set +CONFIG_GC_SENSOR_SUBSAMPLE_MODE=y +CONFIG_CAMERA_TASK_STACK_SIZE=2048 +CONFIG_CAMERA_CORE0=y +# CONFIG_CAMERA_CORE1 is not set +# CONFIG_CAMERA_NO_AFFINITY is not set +CONFIG_CAMERA_DMA_BUFFER_SIZE_MAX=32768 +# end of Camera configuration + +# +# LittleFS +# +CONFIG_LITTLEFS_MAX_PARTITIONS=3 +CONFIG_LITTLEFS_PAGE_SIZE=256 +CONFIG_LITTLEFS_OBJ_NAME_LEN=64 +CONFIG_LITTLEFS_READ_SIZE=128 +CONFIG_LITTLEFS_WRITE_SIZE=128 +CONFIG_LITTLEFS_LOOKAHEAD_SIZE=128 +CONFIG_LITTLEFS_CACHE_SIZE=512 +CONFIG_LITTLEFS_BLOCK_CYCLES=512 +CONFIG_LITTLEFS_USE_MTIME=y +# CONFIG_LITTLEFS_USE_ONLY_HASH is not set +# CONFIG_LITTLEFS_HUMAN_READABLE is not set +CONFIG_LITTLEFS_MTIME_USE_SECONDS=y +# CONFIG_LITTLEFS_MTIME_USE_NONCE is not set +# CONFIG_LITTLEFS_SPIFFS_COMPAT is not set +# CONFIG_LITTLEFS_FLUSH_FILE_EVERY_WRITE is not set +# end of LittleFS + +# +# DSP Library +# +CONFIG_DSP_OPTIMIZATIONS_SUPPORTED=y +# CONFIG_DSP_ANSI is not set +CONFIG_DSP_OPTIMIZED=y +CONFIG_DSP_OPTIMIZATION=1 +# CONFIG_DSP_MAX_FFT_SIZE_512 is not set +# CONFIG_DSP_MAX_FFT_SIZE_1024 is not set +# CONFIG_DSP_MAX_FFT_SIZE_2048 is not set +CONFIG_DSP_MAX_FFT_SIZE_4096=y +# CONFIG_DSP_MAX_FFT_SIZE_8192 is not set +# CONFIG_DSP_MAX_FFT_SIZE_16384 is not set +# CONFIG_DSP_MAX_FFT_SIZE_32768 is not set +CONFIG_DSP_MAX_FFT_SIZE=4096 +# end of DSP Library + +# +# ESP Secure Cert Manager +# +# CONFIG_ESP_SECURE_CERT_SUPPORT_LEGACY_FORMATS is not set +# end of ESP Secure Cert Manager +# end of Component config + +# +# Compatibility options +# +# CONFIG_LEGACY_INCLUDE_COMMON_HEADERS is not set +# end of Compatibility options + +# Deprecated options for backward compatibility +CONFIG_TOOLPREFIX="xtensa-esp32-elf-" +CONFIG_LOG_BOOTLOADER_LEVEL_NONE=y +# CONFIG_LOG_BOOTLOADER_LEVEL_ERROR is not set +# CONFIG_LOG_BOOTLOADER_LEVEL_WARN is not set +# CONFIG_LOG_BOOTLOADER_LEVEL_INFO is not set +# CONFIG_LOG_BOOTLOADER_LEVEL_DEBUG is not set +# CONFIG_LOG_BOOTLOADER_LEVEL_VERBOSE is not set +CONFIG_LOG_BOOTLOADER_LEVEL=0 +CONFIG_APP_ROLLBACK_ENABLE=y +# CONFIG_APP_ANTI_ROLLBACK is not set +# CONFIG_FLASH_ENCRYPTION_ENABLED is not set +CONFIG_FLASHMODE_QIO=y +# CONFIG_FLASHMODE_QOUT is not set +# CONFIG_FLASHMODE_DIO is not set +# CONFIG_FLASHMODE_DOUT is not set +# CONFIG_MONITOR_BAUD_9600B is not set +# CONFIG_MONITOR_BAUD_57600B is not set +CONFIG_MONITOR_BAUD_115200B=y +# CONFIG_MONITOR_BAUD_230400B is not set +# CONFIG_MONITOR_BAUD_921600B is not set +# CONFIG_MONITOR_BAUD_2MB is not set +# CONFIG_MONITOR_BAUD_OTHER is not set +CONFIG_MONITOR_BAUD_OTHER_VAL=115200 +CONFIG_MONITOR_BAUD=115200 +# CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG is not set +CONFIG_COMPILER_OPTIMIZATION_LEVEL_RELEASE=y +CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y +# CONFIG_OPTIMIZATION_ASSERTIONS_SILENT is not set +# CONFIG_OPTIMIZATION_ASSERTIONS_DISABLED is not set +CONFIG_OPTIMIZATION_ASSERTION_LEVEL=2 +CONFIG_CXX_EXCEPTIONS=y +CONFIG_CXX_EXCEPTIONS_EMG_POOL_SIZE=0 +# CONFIG_STACK_CHECK_NONE is not set +CONFIG_STACK_CHECK_NORM=y +# CONFIG_STACK_CHECK_STRONG is not set +# CONFIG_STACK_CHECK_ALL is not set +CONFIG_STACK_CHECK=y +CONFIG_WARN_WRITE_STRINGS=y +# CONFIG_DISABLE_GCC8_WARNINGS is not set +# CONFIG_ESP32_APPTRACE_DEST_TRAX is not set +CONFIG_ESP32_APPTRACE_DEST_NONE=y +CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y +# CONFIG_BTDM_CONTROLLER_MODE_BLE_ONLY is not set +# CONFIG_BTDM_CONTROLLER_MODE_BR_EDR_ONLY is not set +CONFIG_BTDM_CONTROLLER_MODE_BTDM=y +CONFIG_BTDM_CONTROLLER_BLE_MAX_CONN=3 +CONFIG_BTDM_CONTROLLER_BR_EDR_MAX_ACL_CONN=2 +CONFIG_BTDM_CONTROLLER_BR_EDR_MAX_SYNC_CONN=0 +CONFIG_BTDM_CONTROLLER_BLE_MAX_CONN_EFF=3 +CONFIG_BTDM_CONTROLLER_BR_EDR_MAX_ACL_CONN_EFF=2 +CONFIG_BTDM_CONTROLLER_BR_EDR_MAX_SYNC_CONN_EFF=0 +CONFIG_BTDM_CONTROLLER_PINNED_TO_CORE=0 +CONFIG_BTDM_CONTROLLER_HCI_MODE_VHCI=y +# CONFIG_BTDM_CONTROLLER_HCI_MODE_UART_H4 is not set +CONFIG_BTDM_CONTROLLER_MODEM_SLEEP=y +CONFIG_BLE_SCAN_DUPLICATE=y +CONFIG_SCAN_DUPLICATE_BY_DEVICE_ADDR=y +# CONFIG_SCAN_DUPLICATE_BY_ADV_DATA is not set +# CONFIG_SCAN_DUPLICATE_BY_ADV_DATA_AND_DEVICE_ADDR is not set +CONFIG_SCAN_DUPLICATE_TYPE=0 +CONFIG_DUPLICATE_SCAN_CACHE_SIZE=20 +CONFIG_BLE_MESH_SCAN_DUPLICATE_EN=y +CONFIG_MESH_DUPLICATE_SCAN_CACHE_SIZE=100 +CONFIG_BTDM_CONTROLLER_FULL_SCAN_SUPPORTED=y +CONFIG_BLE_ADV_REPORT_FLOW_CONTROL_SUPPORTED=y +CONFIG_BLE_ADV_REPORT_FLOW_CONTROL_NUM=100 +CONFIG_BLE_ADV_REPORT_DISCARD_THRSHOLD=20 +CONFIG_BLUEDROID_ENABLED=y +# CONFIG_NIMBLE_ENABLED is not set +CONFIG_BTC_TASK_STACK_SIZE=8192 +CONFIG_BLUEDROID_PINNED_TO_CORE_0=y +# CONFIG_BLUEDROID_PINNED_TO_CORE_1 is not set +CONFIG_BLUEDROID_PINNED_TO_CORE=0 +CONFIG_BTU_TASK_STACK_SIZE=8192 +# CONFIG_BLUEDROID_MEM_DEBUG is not set +CONFIG_CLASSIC_BT_ENABLED=y +CONFIG_A2DP_ENABLE=y +CONFIG_HFP_ENABLE=y +CONFIG_HFP_CLIENT_ENABLE=y +# CONFIG_HFP_AG_ENABLE is not set +CONFIG_HFP_AUDIO_DATA_PATH_PCM=y +# CONFIG_HFP_AUDIO_DATA_PATH_HCI is not set +CONFIG_GATTS_ENABLE=y +# CONFIG_GATTS_SEND_SERVICE_CHANGE_MANUAL is not set +CONFIG_GATTS_SEND_SERVICE_CHANGE_AUTO=y +CONFIG_GATTS_SEND_SERVICE_CHANGE_MODE=0 +CONFIG_GATTC_ENABLE=y +# CONFIG_GATTC_CACHE_NVS_FLASH is not set +CONFIG_BLE_SMP_ENABLE=y +# CONFIG_SMP_SLAVE_CON_PARAMS_UPD_ENABLE is not set +# CONFIG_BLE_HOST_QUEUE_CONGESTION_CHECK is not set +CONFIG_SMP_ENABLE=y +# CONFIG_BLE_ACTIVE_SCAN_REPORT_ADV_SCAN_RSP_INDIVIDUALLY is not set +CONFIG_BLE_ESTABLISH_LINK_CONNECTION_TIMEOUT=30 +# CONFIG_BLE_MESH_ALLOC_FROM_PSRAM_FIRST is not set +CONFIG_ADC2_DISABLE_DAC=y +CONFIG_SPIRAM_SUPPORT=y +# CONFIG_WIFI_LWIP_ALLOCATION_FROM_SPIRAM_FIRST is not set +CONFIG_TRACEMEM_RESERVE_DRAM=0x0 +CONFIG_ULP_COPROC_ENABLED=y +CONFIG_ULP_COPROC_RESERVE_MEM=512 +CONFIG_BROWNOUT_DET=y +CONFIG_BROWNOUT_DET_LVL_SEL_0=y +# CONFIG_BROWNOUT_DET_LVL_SEL_1 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_2 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_3 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_4 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_5 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_6 is not set +# CONFIG_BROWNOUT_DET_LVL_SEL_7 is not set +CONFIG_BROWNOUT_DET_LVL=0 +CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC=y +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_EXTERNAL_OSC is not set +# CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_8MD256 is not set +# CONFIG_DISABLE_BASIC_ROM_CONSOLE is not set +# CONFIG_COMPATIBLE_PRE_V2_1_BOOTLOADERS is not set +# CONFIG_EVENT_LOOP_PROFILING is not set +CONFIG_POST_EVENTS_FROM_ISR=y +CONFIG_POST_EVENTS_FROM_IRAM_ISR=y +# CONFIG_TWO_UNIVERSAL_MAC_ADDRESS is not set +CONFIG_FOUR_UNIVERSAL_MAC_ADDRESS=y +CONFIG_NUMBER_OF_UNIVERSAL_MAC_ADDRESS=4 +# CONFIG_ESP32C3_LIGHTSLEEP_GPIO_RESET_WORKAROUND is not set +CONFIG_IPC_TASK_STACK_SIZE=1024 +CONFIG_ESP32_PHY_CALIBRATION_AND_DATA_STORAGE=y +# CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION is not set +CONFIG_ESP32_PHY_MAX_WIFI_TX_POWER=20 +CONFIG_ESP32_PHY_MAX_TX_POWER=20 +CONFIG_ESP32_REDUCE_PHY_TX_POWER=y +# CONFIG_ESP32S2_PANIC_PRINT_HALT is not set +CONFIG_ESP32S2_PANIC_PRINT_REBOOT=y +# CONFIG_ESP32S2_PANIC_SILENT_REBOOT is not set +# CONFIG_ESP32S2_PANIC_GDBSTUB is not set +CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32 +CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2048 +CONFIG_MAIN_TASK_STACK_SIZE=4096 +CONFIG_CONSOLE_UART_DEFAULT=y +# CONFIG_CONSOLE_UART_CUSTOM is not set +# CONFIG_ESP_CONSOLE_UART_NONE is not set +CONFIG_CONSOLE_UART=y +CONFIG_CONSOLE_UART_NUM=0 +CONFIG_CONSOLE_UART_BAUDRATE=115200 +CONFIG_INT_WDT=y +CONFIG_INT_WDT_TIMEOUT_MS=300 +CONFIG_INT_WDT_CHECK_CPU1=y +CONFIG_TASK_WDT=y +CONFIG_TASK_WDT_PANIC=y +CONFIG_TASK_WDT_TIMEOUT_S=5 +CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y +# CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1 is not set +# CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set +CONFIG_TIMER_TASK_STACK_SIZE=4096 +CONFIG_SW_COEXIST_ENABLE=y +CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH=y +# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set +# CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE is not set +# CONFIG_ESP32_COREDUMP_DATA_FORMAT_BIN is not set +CONFIG_ESP32_COREDUMP_DATA_FORMAT_ELF=y +CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y +# CONFIG_ESP32_COREDUMP_CHECKSUM_SHA256 is not set +CONFIG_ESP32_ENABLE_COREDUMP=y +CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 +CONFIG_MB_MASTER_TIMEOUT_MS_RESPOND=150 +CONFIG_MB_MASTER_DELAY_MS_CONVERT=200 +CONFIG_MB_QUEUE_LENGTH=20 +CONFIG_MB_SERIAL_TASK_STACK_SIZE=4096 +CONFIG_MB_SERIAL_BUF_SIZE=256 +CONFIG_MB_SERIAL_TASK_PRIO=10 +# CONFIG_MB_CONTROLLER_SLAVE_ID_SUPPORT is not set +CONFIG_MB_CONTROLLER_NOTIFY_TIMEOUT=20 +CONFIG_MB_CONTROLLER_NOTIFY_QUEUE_SIZE=20 +CONFIG_MB_CONTROLLER_STACK_SIZE=4096 +CONFIG_MB_EVENT_QUEUE_TIMEOUT=20 +CONFIG_MB_TIMER_PORT_ENABLED=y +# CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set +CONFIG_TIMER_TASK_PRIORITY=1 +CONFIG_TIMER_TASK_STACK_DEPTH=2048 +CONFIG_TIMER_QUEUE_LENGTH=10 +# CONFIG_L2_TO_L3_COPY is not set +# CONFIG_USE_ONLY_LWIP_SELECT is not set +CONFIG_ESP_GRATUITOUS_ARP=y +CONFIG_GARP_TMR_INTERVAL=60 +CONFIG_TCPIP_RECVMBOX_SIZE=32 +CONFIG_TCP_MAXRTX=12 +CONFIG_TCP_SYNMAXRTX=6 +CONFIG_TCP_MSS=1436 +CONFIG_TCP_MSL=60000 +CONFIG_TCP_SND_BUF_DEFAULT=5744 +CONFIG_TCP_WND_DEFAULT=5744 +CONFIG_TCP_RECVMBOX_SIZE=6 +CONFIG_TCP_QUEUE_OOSEQ=y +# CONFIG_ESP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set +CONFIG_TCP_OVERSIZE_MSS=y +# CONFIG_TCP_OVERSIZE_QUARTER_MSS is not set +# CONFIG_TCP_OVERSIZE_DISABLE is not set +CONFIG_UDP_RECVMBOX_SIZE=6 +CONFIG_TCPIP_TASK_STACK_SIZE=2560 +# CONFIG_TCPIP_TASK_AFFINITY_NO_AFFINITY is not set +CONFIG_TCPIP_TASK_AFFINITY_CPU0=y +# CONFIG_TCPIP_TASK_AFFINITY_CPU1 is not set +CONFIG_TCPIP_TASK_AFFINITY=0x0 +# CONFIG_PPP_SUPPORT is not set +CONFIG_ESP32_PTHREAD_TASK_PRIO_DEFAULT=5 +CONFIG_ESP32_PTHREAD_TASK_STACK_SIZE_DEFAULT=2048 +CONFIG_ESP32_PTHREAD_STACK_MIN=768 +CONFIG_ESP32_DEFAULT_PTHREAD_CORE_NO_AFFINITY=y +# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_0 is not set +# CONFIG_ESP32_DEFAULT_PTHREAD_CORE_1 is not set +CONFIG_ESP32_PTHREAD_TASK_CORE_DEFAULT=-1 +CONFIG_ESP32_PTHREAD_TASK_NAME_DEFAULT="pthread" +CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y +# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_FAILS is not set +# CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ALLOWED is not set +CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y +CONFIG_SUPPORT_TERMIOS=y +CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +# End of deprecated options diff --git a/uCNC/src/hal/boards/esp32/esp32.ini b/uCNC/src/hal/boards/esp32/esp32.ini index 1827aad18..e2762daf8 100644 --- a/uCNC/src/hal/boards/esp32/esp32.ini +++ b/uCNC/src/hal/boards/esp32/esp32.ini @@ -4,13 +4,16 @@ [common_esp32] platform = espressif32 -framework = arduino -board = wemos_d1_uno32 +framework = arduino, espidf +board = esp32dev ; build_src_filter = +<*>- build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DENABLE_WIFI -DENABLE_BLUETOOTH -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE board_build.f_flash = 80000000L board_build.f_cpu = 240000000L board_build.partitions = min_spiffs.csv +monitor_filters=esp32_exception_decoder +upload_speed = 921600 +lib_deps = SPI, Wifi, Wire, WebServer, HTTPUpdatedServer, BluetoothSerial [env:d1_r32] extends = common_esp32 @@ -19,10 +22,8 @@ build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 [env:mks_tinybee] extends = common_esp32 -board = esp32dev build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE [env:mks_dlc32] extends = common_esp32 -board = esp32dev build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 From 7719ece1081dc052bcd4d54a133db82ae372f080 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 13 Sep 2023 12:23:15 +0100 Subject: [PATCH 109/168] swap SERVO and ITP timers --- uCNC/src/hal/mcus/esp32/mcumap_esp32.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h index 382fb095e..93bbdb90b 100644 --- a/uCNC/src/hal/mcus/esp32/mcumap_esp32.h +++ b/uCNC/src/hal/mcus/esp32/mcumap_esp32.h @@ -2704,13 +2704,13 @@ extern "C" #endif #ifndef SERVO_TIMER -#define SERVO_TIMER 3 +#define SERVO_TIMER 1 #endif #define SERVO_TIMER_TG (SERVO_TIMER & 0x01) #define SERVO_TIMER_IDX ((SERVO_TIMER >> 1) & 0x01) #ifndef ITP_TIMER -#define ITP_TIMER 1 +#define ITP_TIMER 3 #endif #define ITP_TIMER_TG (ITP_TIMER & 0x01) #define ITP_TIMER_IDX ((ITP_TIMER >> 1) & 0x01) From b1f9763fd2b42de24cac991c524044ca1b0f15c4 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 13 Sep 2023 17:15:59 +0100 Subject: [PATCH 110/168] fixed #492 - fixed #492 --- makefiles/virtual/uCNC.dev | 4 ++-- uCNC/src/cnc.c | 14 ++++++++++++++ uCNC/src/core/interpolator.c | 10 ---------- 3 files changed, 16 insertions(+), 12 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 3b2c21fbc..526cbcf62 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=80 +UnitCount=81 [VersionInfo] Major=1 @@ -951,7 +951,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit81] -FileName=..\..\uCNC\src\modules\M62-M65\parser_m62_m65.c +FileName=..\..\uCNC\src\hal\kinematics\kinematic.c CompileCpp=0 Folder= Compile=1 diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 6fce090ce..23d6735b9 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -941,6 +941,20 @@ bool cnc_check_interlocking(void) } #endif + // end of JOG + if (cnc_get_exec_state(EXEC_JOG | EXEC_HOLD) == EXEC_JOG) + { + if (itp_is_empty() && planner_buffer_is_empty()) + { + cnc_clear_exec_state(EXEC_JOG); + } + } + + if (itp_is_empty() && planner_buffer_is_empty()) + { + cnc_clear_exec_state(EXEC_RUN); + } + return true; } diff --git a/uCNC/src/core/interpolator.c b/uCNC/src/core/interpolator.c index f9617f5de..397f33093 100644 --- a/uCNC/src/core/interpolator.c +++ b/uCNC/src/core/interpolator.c @@ -713,15 +713,6 @@ void itp_stop(void) cnc_set_exec_state(EXEC_UNHOMED); } - // end of JOG - if (CHECKFLAG(state, (EXEC_JOG | EXEC_HOLD)) == EXEC_JOG) - { - if (itp_is_empty() && planner_buffer_is_empty()) - { - cnc_clear_exec_state(EXEC_JOG); - } - } - io_set_steps(g_settings.step_invert_mask); #if TOOL_COUNT > 0 if (g_settings.laser_mode) @@ -731,7 +722,6 @@ void itp_stop(void) #endif mcu_stop_itp_isr(); - cnc_clear_exec_state(EXEC_RUN); } void itp_stop_tools(void) From bf76c5b86d7f82b0ae99980ba43ef73d089cde26 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 14 Sep 2023 01:09:59 +0100 Subject: [PATCH 111/168] moved I2S to core 1 - moved all I2S to core 1 - core 0 now only runs RTC and WIFI and BT - patched issue #494 - added build options for ESP-IDF versions --- uCNC/src/core/parser.c | 8 +-- uCNC/src/hal/boards/esp32/esp32.ini | 21 +++++++- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 76 +++++++++++++++++++---------- 3 files changed, 72 insertions(+), 33 deletions(-) diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index ffed36d30..f8ceb1ad4 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -70,7 +70,7 @@ static uint8_t parse_grbl_exec_code(uint8_t code); static uint8_t parser_fetch_command(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); static uint8_t parser_validate_command(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); static uint8_t parser_grbl_command(void); -FORCEINLINE static uint8_t parser_gcode_command(void); +FORCEINLINE static uint8_t parser_gcode_command(bool is_jogging); static void parser_discard_command(void); #ifdef ENABLE_CANNED_CYCLES uint8_t parser_exec_command_block(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); @@ -187,7 +187,7 @@ uint8_t parser_read_command(void) return STATUS_SYSTEM_GC_LOCK; } - return parser_gcode_command(); + return parser_gcode_command(is_jogging); } void parser_get_modes(uint8_t *modalgroups, uint16_t *feed, uint16_t *spindle, uint8_t *coolant) @@ -1792,7 +1792,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa /* Parse the next gcode line available in the buffer and send it to the motion controller */ -static uint8_t parser_gcode_command(void) +static uint8_t parser_gcode_command(bool is_jogging) { uint8_t result = 0; // initializes new state @@ -1829,7 +1829,7 @@ static uint8_t parser_gcode_command(void) } // if is jog motion state is not preserved - if (!cnc_get_exec_state(EXEC_JOG)) + if (!is_jogging) { // if everything went ok updates the parser modal groups and position memcpy(&parser_state, &next_state, sizeof(parser_state_t)); diff --git a/uCNC/src/hal/boards/esp32/esp32.ini b/uCNC/src/hal/boards/esp32/esp32.ini index e2762daf8..e7ea7895d 100644 --- a/uCNC/src/hal/boards/esp32/esp32.ini +++ b/uCNC/src/hal/boards/esp32/esp32.ini @@ -4,7 +4,7 @@ [common_esp32] platform = espressif32 -framework = arduino, espidf +framework = arduino board = esp32dev ; build_src_filter = +<*>- build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DENABLE_WIFI -DENABLE_BLUETOOTH -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE @@ -13,7 +13,11 @@ board_build.f_cpu = 240000000L board_build.partitions = min_spiffs.csv monitor_filters=esp32_exception_decoder upload_speed = 921600 -lib_deps = SPI, Wifi, Wire, WebServer, HTTPUpdatedServer, BluetoothSerial + +[common_esp32_idf] +extends = common_esp32 +framework = arduino, espidf +lib_deps = SPI, Wifi, Wire, WebServer, HTTPUpdatedServer, BluetoothSerial [env:d1_r32] extends = common_esp32 @@ -27,3 +31,16 @@ build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE [env:mks_dlc32] extends = common_esp32 build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 + +[env:espidf_d1_r32] +extends = common_esp32_idf +board = wemos_d1_uno32 +build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 + +[env:espidf_mks_tinybee] +extends = common_esp32_idf +build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_MKS_TINYBEE + +[env:espidf_mks_dlc32] +extends = common_esp32_idf +build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_MKS_DLC32 diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index ff24ad9a6..238398780 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -268,32 +268,32 @@ void mcu_core0_tasks_init(void *arg) uart_driver_install(COM2_PORT, RX_BUFFER_CAPACITY * 2, 0, 0, NULL, 0); #endif -#ifdef IC74HC595_HAS_PWMS -#ifdef IC74HC595_CUSTOM_SHIFT_IO - esp32_i2s_extender_init(); -#endif - - // initialize ITP timer that will run at a fixed rate to update all IO - /* Select and initialize basic parameters of the timer */ - timer_config_t itpconfig = {0}; - itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse - itpconfig.counter_dir = TIMER_COUNT_UP; - itpconfig.counter_en = TIMER_PAUSE; - itpconfig.intr_type = TIMER_INTR_MAX; - itpconfig.alarm_en = TIMER_ALARM_EN; - itpconfig.auto_reload = true; - timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); - - /* Timer's counter will initially start from value below. - Also, if auto_reload is set, this value will be automatically reload on alarm */ - timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); - /* Configure the alarm value and the interrupt on alarm. */ - timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)8); - // register PWM isr - timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); - timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); - timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); -#endif + // #ifdef IC74HC595_HAS_PWMS + // #ifdef IC74HC595_CUSTOM_SHIFT_IO + // esp32_i2s_extender_init(); + // #endif + + // // initialize ITP timer that will run at a fixed rate to update all IO + // /* Select and initialize basic parameters of the timer */ + // timer_config_t itpconfig = {0}; + // itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse + // itpconfig.counter_dir = TIMER_COUNT_UP; + // itpconfig.counter_en = TIMER_PAUSE; + // itpconfig.intr_type = TIMER_INTR_MAX; + // itpconfig.alarm_en = TIMER_ALARM_EN; + // itpconfig.auto_reload = true; + // timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); + + // /* Timer's counter will initially start from value below. + // Also, if auto_reload is set, this value will be automatically reload on alarm */ + // timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); + // /* Configure the alarm value and the interrupt on alarm. */ + // timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)8); + // // register PWM isr + // timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); + // timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); + // timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); + // #endif } void mcu_rtc_task(void *arg) @@ -470,10 +470,32 @@ void mcu_init(void) uart_set_pin(COM2_PORT, TX2_BIT, RX2_BIT, UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE); #endif -#ifndef IC74HC595_HAS_PWMS #ifdef IC74HC595_CUSTOM_SHIFT_IO esp32_i2s_extender_init(); #endif + +#ifdef IC74HC595_HAS_PWMS + // initialize ITP timer that will run at a fixed rate to update all IO + /* Select and initialize basic parameters of the timer */ + timer_config_t itpconfig = {0}; + itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse + itpconfig.counter_dir = TIMER_COUNT_UP; + itpconfig.counter_en = TIMER_PAUSE; + itpconfig.intr_type = TIMER_INTR_MAX; + itpconfig.alarm_en = TIMER_ALARM_EN; + itpconfig.auto_reload = true; + timer_init(ITP_TIMER_TG, ITP_TIMER_IDX, &itpconfig); + + /* Timer's counter will initially start from value below. + Also, if auto_reload is set, this value will be automatically reload on alarm */ + timer_set_counter_value(ITP_TIMER_TG, ITP_TIMER_IDX, 0x00000000ULL); + /* Configure the alarm value and the interrupt on alarm. */ + timer_set_alarm_value(ITP_TIMER_TG, ITP_TIMER_IDX, (uint64_t)8); + // register PWM isr + timer_isr_register(ITP_TIMER_TG, ITP_TIMER_IDX, esp32_io_updater, NULL, 0, NULL); + timer_enable_intr(ITP_TIMER_TG, ITP_TIMER_IDX); + timer_start(ITP_TIMER_TG, ITP_TIMER_IDX); +#else // inititialize ITP timer timer_config_t itpconfig = {0}; itpconfig.divider = getApbFrequency() / 1000000UL; // 1us per pulse From d95c20e4587d44f431c38e8549ee6eae3cbdb29a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 25 Sep 2023 14:55:51 +0100 Subject: [PATCH 112/168] patches #499 #501 #507 and #508 - applied patches #499 #501 #507 and #508 --- uCNC/src/cnc.c | 5 +++++ uCNC/src/cnc.h | 1 + uCNC/src/cnc_hal_config_helper.h | 11 +++++++++++ uCNC/src/modules/language/language_en.h | 15 +++++++++++++++ uCNC/src/modules/system_menu.c | 8 ++++---- 5 files changed, 36 insertions(+), 4 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 23d6735b9..c8152387b 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -412,6 +412,11 @@ bool cnc_has_alarm() return (cnc_get_exec_state(EXEC_KILL) || (cnc_state.alarm != EXEC_ALARM_NOALARM)); } +uint8_t cnc_get_alarm(void) +{ + return cnc_state.alarm; +} + void cnc_stop(void) { itp_stop(); diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index 0ac43e840..abca7045d 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -158,6 +158,7 @@ extern "C" void cnc_home(void); void cnc_alarm(int8_t code); bool cnc_has_alarm(); + uint8_t cnc_get_alarm(void); void cnc_stop(void); uint8_t cnc_unlock(bool force); void cnc_delay_ms(uint32_t miliseconds); diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index d47e2e2e0..a8f8eae9d 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -656,6 +656,17 @@ extern "C" #else #define STEP3_ITP_MASK STEP3_MASK #endif +#if (STEP4_MASK == STEP_DUAL0) +#define STEP4_ITP_MASK (STEP4_MASK | STEP_DUAL0_MASK) +#elif (STEP4_MASK == STEP_DUAL1) +#define STEP4_ITP_MASK (STEP4_MASK | STEP_DUAL1_MASK) +#elif (STEP4_MASK == STEP_DUAL2) +#define STEP4_ITP_MASK (STEP4_MASK | STEP_DUAL2_MASK) +#elif (STEP4_MASK == STEP_DUAL3) +#define STEP4_ITP_MASK (STEP4_MASK | STEP_DUAL3_MASK) +#else +#define STEP4_ITP_MASK STEP4_MASK +#endif #if (STEP5_MASK == STEP_DUAL0) #define STEP5_ITP_MASK (STEP5_MASK | STEP_DUAL0_MASK) #elif (STEP5_MASK == STEP_DUAL1) diff --git a/uCNC/src/modules/language/language_en.h b/uCNC/src/modules/language/language_en.h index c264aa956..c32352f2b 100644 --- a/uCNC/src/modules/language/language_en.h +++ b/uCNC/src/modules/language/language_en.h @@ -63,6 +63,21 @@ extern "C" #define STR_SETTINGS_LOADED "Settings loaded" #define STR_SETTINGS_SAVED "Settings saved" #define STR_SETTINGS_RESET "Settings reset" +// alarms +#define STR_ALARM_0 "Unknowned" +#define STR_ALARM_1 "Hard limits hit" +#define STR_ALARM_2 "Soft limits hit" +#define STR_ALARM_3 "Aborted by user" +#define STR_ALARM_4 "Probe hit" +#define STR_ALARM_5 "Probe no hit" +#define STR_ALARM_6 "Home reset" +#define STR_ALARM_7 "Door opened" +#define STR_ALARM_8 "Limits in contact" +#define STR_ALARM_9 "Failed home find" +#define STR_ALARM_10 "Failed autolevel" +#define STR_ALARM_11 "Limits are active" +#define STR_ALARM_12 "Tool sync fail" +#define STR_ALARM_13 "Limits tripped" #ifdef __cplusplus } diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 57738adb3..25314af47 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -266,10 +266,10 @@ void system_menu_action(uint8_t action) int16_t currentindex = g_system_menu.current_index; // kill alarm is active - if (cnc_get_exec_state(EXEC_ALARM)) + if (cnc_get_exec_state(EXEC_INTERLOCKING_FAIL) || cnc_has_alarm()) { // never go idle - g_system_menu.action_timeout = UINT32_MAX; + g_system_menu.action_timeout = mcu_millis() + SYSTEM_MENU_MODAL_POPUP_MS; g_system_menu.flags |= SYSTEM_MENU_MODE_REDRAW; // leave. ignore all actions return; @@ -413,7 +413,7 @@ void system_menu_render(void) g_system_menu.flags &= ~SYSTEM_MENU_MODE_REDRAW; uint8_t item_index = 0; - if (cnc_get_exec_state(EXEC_ALARM)) + if (cnc_get_exec_state(EXEC_INTERLOCKING_FAIL) || cnc_has_alarm()) { system_menu_render_alarm(); return; @@ -736,7 +736,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) else if (g_system_menu.flags & SYSTEM_MENU_MODE_SIMPLE_EDIT) { // one jog command at time - if (serial_get_rx_freebytes() > 32 && !cnc_get_exec_state(EXEC_RUN)) + if (serial_get_rx_freebytes() > 32) { char buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); From 748770113d53d2bc2fa514b99924bfc53994b181 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 26 Sep 2023 17:40:55 +0100 Subject: [PATCH 113/168] added Z alias for 2 axis machines --- uCNC/cnc_hal_config.h | 13 +++- uCNC/src/cnc_hal_config_helper.h | 11 ++++ uCNC/src/core/motion_control.c | 32 +++++----- uCNC/src/core/parser.c | 6 +- uCNC/src/hal/mcus/virtual/mcu_virtual.c | 84 +++++++++++++------------ uCNC/src/hal/tools/tools/plasma_thc.c | 8 +-- uCNC/src/interface/protocol.c | 4 ++ 7 files changed, 96 insertions(+), 62 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 366f66082..986fd3f8b 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -74,11 +74,22 @@ extern "C" #define FHOLD_PULLUP_ENABLE #define CS_RES_PULLUP_ENABLE + +/** + * Uncomment this to use Y axis as a Z axis alias on 2 axis machines + * This allows the Gcode to expect X and Z coordinates in the parser + * **/ +// #define USE_Y_AS_Z_ALIAS + /** * Uncomment this feature to enable tool length compensation */ -#if (!defined(AXIS_TOOL) && defined(AXIS_Z)) +#ifndef AXIS_TOOL +#ifdef AXIS_Z #define AXIS_TOOL AXIS_Z +#elif ((AXIS_COUNT == 2) && defined(USE_Y_AS_Z_ALIAS)) +#define AXIS_TOOL AXIS_Y +#endif #endif /** diff --git a/uCNC/src/cnc_hal_config_helper.h b/uCNC/src/cnc_hal_config_helper.h index 7d5fb08b9..b1ac80f9f 100644 --- a/uCNC/src/cnc_hal_config_helper.h +++ b/uCNC/src/cnc_hal_config_helper.h @@ -2149,6 +2149,10 @@ typedef uint16_t step_t; #error "Linear actuator 4 and 5 have overlapped input limits and this can lead to unpredictable results" #endif +#if ((AXIS_COUNT != 2) && defined(USE_Y_AS_Z_ALIAS)) +#error "Y axis can only be used as a Z alias in 2 axis machines." +#endif + #ifdef MCU_HAS_I2C @@ -2169,6 +2173,13 @@ typedef uint16_t step_t; #endif #endif +#ifndef AXIS_TOOL +#ifdef ENABLE_G39_H_MAPPING +#undef ENABLE_G39_H_MAPPING +#warning "ENABLE_G39_H_MAPPING disabled via because AXIS_TOOL is not defined" +#endif +#endif + #ifndef DISABLE_SETTINGS_MODULES #define ENABLE_SETTINGS_MODULES #endif diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index 4a6b37bec..d366fd45e 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -259,7 +259,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) #ifdef ENABLE_G39_H_MAPPING // modify the gcode with Hmap float target_hmap_offset = (CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_APPLY_HMAP)) ? (mc_apply_hmap(target)) : 0; - target[AXIS_Z] += target_hmap_offset; + target[AXIS_TOOL] += target_hmap_offset; #endif // check travel limits (soft limits) @@ -267,7 +267,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) { #ifdef ENABLE_G39_H_MAPPING // unmodify target - target[AXIS_Z] -= target_hmap_offset; + target[AXIS_TOOL] -= target_hmap_offset; #endif if (cnc_get_exec_state(EXEC_JOG)) @@ -286,7 +286,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) #ifdef ENABLE_G39_H_MAPPING // modify the gcode with Hmap float h_offset = (CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_APPLY_HMAP)) ? (mc_apply_hmap(prev_target)) : 0; - prev_target[AXIS_Z] += h_offset; + prev_target[AXIS_TOOL] += h_offset; #endif // calculates the traveled distance @@ -302,7 +302,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) // remove the hmap postion of the motion #ifdef ENABLE_G39_H_MAPPING - motion_segment[AXIS_Z] += (h_offset - target_hmap_offset); + motion_segment[AXIS_TOOL] += (h_offset - target_hmap_offset); #endif // no motion. bail out. @@ -310,7 +310,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) { #ifdef ENABLE_G39_H_MAPPING // unmodify target - target[AXIS_Z] -= target_hmap_offset; + target[AXIS_TOOL] -= target_hmap_offset; #endif return STATUS_OK; } @@ -349,7 +349,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) { #ifdef ENABLE_G39_H_MAPPING // unmodify target - target[AXIS_Z] -= target_hmap_offset; + target[AXIS_TOOL] -= target_hmap_offset; #endif return STATUS_OK; } @@ -464,7 +464,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) #ifdef ENABLE_G39_H_MAPPING // unmodify target - prev_target[AXIS_Z] -= h_offset; + prev_target[AXIS_TOOL] -= h_offset; #endif } @@ -480,13 +480,13 @@ uint8_t mc_line(float *target, motion_data_t *block_data) #ifdef ENABLE_G39_H_MAPPING h_offset = (CHECKFLAG(block_data->motion_mode, MOTIONCONTROL_MODE_APPLY_HMAP)) ? (mc_apply_hmap(prev_target)) : 0; - prev_target[AXIS_Z] += h_offset; + prev_target[AXIS_TOOL] += h_offset; #endif kinematics_coordinates_to_steps(prev_target, step_new_pos); error = mc_line_segment(step_new_pos, block_data); #ifdef ENABLE_G39_H_MAPPING // unmodify target - prev_target[AXIS_Z] -= h_offset; + prev_target[AXIS_TOOL] -= h_offset; #endif if (error) { @@ -507,7 +507,7 @@ uint8_t mc_line(float *target, motion_data_t *block_data) #ifdef ENABLE_G39_H_MAPPING // unmodify target - target[AXIS_Z] -= target_hmap_offset; + target[AXIS_TOOL] -= target_hmap_offset; #endif // stores the new position for the next motion @@ -1076,9 +1076,9 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data { block_data->feed = FLT_MAX; // retract if needed - if (position[AXIS_Z] < (target[AXIS_Z] + retract_h)) + if (position[AXIS_TOOL] < (target[AXIS_TOOL] + retract_h)) { - position[AXIS_Z] = (target[AXIS_Z] + retract_h); + position[AXIS_TOOL] = (target[AXIS_TOOL] + retract_h); error = mc_line(position, block_data); if (error != STATUS_OK) { @@ -1106,7 +1106,7 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data int32_t probe_position[STEPPER_COUNT]; itp_get_rt_position(probe_position); kinematics_steps_to_coordinates(probe_position, position); - hmap_offsets[i + H_MAPING_GRID_FACTOR * j] = position[AXIS_Z]; + hmap_offsets[i + H_MAPING_GRID_FACTOR * j] = position[AXIS_TOOL]; protocol_send_probe_result(1); // update to new target @@ -1118,9 +1118,9 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data block_data->feed = FLT_MAX; // fast retract if needed - if (position[AXIS_Z] < (target[AXIS_Z] + retract_h)) + if (position[AXIS_TOOL] < (target[AXIS_TOOL] + retract_h)) { - position[AXIS_Z] = (target[AXIS_Z] + retract_h); + position[AXIS_TOOL] = (target[AXIS_TOOL] + retract_h); error = mc_line(position, block_data); if (error != STATUS_OK) { @@ -1140,7 +1140,7 @@ uint8_t mc_build_hmap(float *target, float *offset, float retract_h, motion_data // move to 1st point at feed speed block_data->feed = feed; - position[AXIS_Z] = hmap_offsets[0]; + position[AXIS_TOOL] = hmap_offsets[0]; error = mc_line(position, block_data); if (error != STATUS_OK) { diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index f8ceb1ad4..b3b8c5424 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -1326,7 +1326,7 @@ uint8_t parser_exec_command(parser_state_t *new_state, parser_words_t *words, pa parser_parameters.tool_length_offset = 0; if (new_state->groups.tlo_mode == G43) { - parser_parameters.tool_length_offset = words->xyzabc[AXIS_Z]; + parser_parameters.tool_length_offset = words->xyzabc[AXIS_TOOL]; CLEARFLAG(cmd->words, GCODE_WORD_Z); words->xyzabc[AXIS_TOOL] = 0; // resets parameter so it it doen't do anything else } @@ -2362,6 +2362,9 @@ static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa #endif #ifdef AXIS_Y case 'Y': +#if ((AXIS_COUNT == 2) && defined(USE_Y_AS_Z_ALIAS)) + case 'Z': +#endif new_words |= GCODE_WORD_Y; words->xyzabc[AXIS_Y] = value; break; @@ -2371,6 +2374,7 @@ static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa new_words |= GCODE_WORD_Z; words->xyzabc[AXIS_Z] = value; break; + #endif #ifdef AXIS_A case 'A': diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 791560d48..022231cc4 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -726,34 +726,34 @@ DWORD WINAPI virtualconsoleserver(LPVOID lpParam) unsigned char c = getchar(); switch (c) { -// case '"': -// virtualmap.special_inputs ^= (1 << (ESTOP - LIMIT_X)); -// mcu_controls_changed_cb(); -// break; -// case '%': -// virtualmap.special_inputs ^= (1 << (LIMIT_X - LIMIT_X)); -// mcu_limits_changed_cb(); -// break; -// case '&': -// virtualmap.special_inputs ^= (1 << (LIMIT_Y - LIMIT_X)); -// mcu_limits_changed_cb(); -// break; -// case '/': -// virtualmap.special_inputs ^= (1 << (LIMIT_Z - LIMIT_X)); -// mcu_limits_changed_cb(); -// break; - // case '[': - // virtualmap.special_inputs ^= (1 << (LIMIT_X2 - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case ']': - // virtualmap.special_inputs ^= (1 << (LIMIT_Y2 - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case '}': - // virtualmap.special_inputs ^= (1 << (SAFETY_DOOR - LIMIT_X)); - // mcu_controls_changed_cb(); - // break; + // case '"': + // virtualmap.special_inputs ^= (1 << (ESTOP - LIMIT_X)); + // mcu_controls_changed_cb(); + // break; + // case '%': + // virtualmap.special_inputs ^= (1 << (LIMIT_X - LIMIT_X)); + // mcu_limits_changed_cb(); + // break; + // case '&': + // virtualmap.special_inputs ^= (1 << (LIMIT_Y - LIMIT_X)); + // mcu_limits_changed_cb(); + // break; + // case '/': + // virtualmap.special_inputs ^= (1 << (LIMIT_Z - LIMIT_X)); + // mcu_limits_changed_cb(); + // break; + // case '[': + // virtualmap.special_inputs ^= (1 << (LIMIT_X2 - LIMIT_X)); + // mcu_limits_changed_cb(); + // break; + // case ']': + // virtualmap.special_inputs ^= (1 << (LIMIT_Y2 - LIMIT_X)); + // mcu_limits_changed_cb(); + // break; + // case '}': + // virtualmap.special_inputs ^= (1 << (SAFETY_DOOR - LIMIT_X)); + // mcu_controls_changed_cb(); + // break; default: mcu_com_rx_cb(c); break; @@ -1244,7 +1244,7 @@ uint8_t mcu_get_pin_offset(uint8_t pin) { if (pin >= 1 && pin <= 24) { - return pin; + return pin - 1; } else if (pin >= 47 && pin <= 78) { @@ -1434,20 +1434,22 @@ bool mcu_tx_ready(void) return mcu_tx_empty; } -void mcu_uart_putc(uint8_t c){ +void mcu_uart_putc(uint8_t c) +{ // #ifdef ENABLE_SYNC_TX // com_send(c, 1); // #endif putchar(c); } - void mcu_uart_flush(void){ - // #ifndef ENABLE_SYNC_TX - // uint8_t i = (mcu_com_tx_buffer_write < TX_BUFFER_HALF) ? 0 : TX_BUFFER_HALF; - // com_send(&mcu_com_tx_buffer[i], strlen(&mcu_com_tx_buffer[i])); - // #endif - } +void mcu_uart_flush(void) +{ + // #ifndef ENABLE_SYNC_TX + // uint8_t i = (mcu_com_tx_buffer_write < TX_BUFFER_HALF) ? 0 : TX_BUFFER_HALF; + // com_send(&mcu_com_tx_buffer[i], strlen(&mcu_com_tx_buffer[i])); + // #endif +} -//void mcu_putc(char c) +// void mcu_putc(char c) //{ // static int buff_index = 0; // if (c != 0) @@ -1467,7 +1469,7 @@ void mcu_uart_putc(uint8_t c){ // } // mcu_tx_empty = true; // mcu_tx_enabled = true; -//} +// } char mcu_getc(void) { @@ -1651,9 +1653,11 @@ void mcu_config_input_isr(int pin) { } -int main (void) { +int main(void) +{ cnc_init(); - for(;;) { + for (;;) + { cnc_run(); } } diff --git a/uCNC/src/hal/tools/tools/plasma_thc.c b/uCNC/src/hal/tools/tools/plasma_thc.c index 45694fdc8..593d4479d 100644 --- a/uCNC/src/hal/tools/tools/plasma_thc.c +++ b/uCNC/src/hal/tools/tools/plasma_thc.c @@ -164,7 +164,7 @@ bool plasma_thc_probe_and_start(void) mc_get_position(pos); // modify target to probe depth - pos[AXIS_Z] += plasma_start_params.probe_depth; + pos[AXIS_TOOL] += plasma_start_params.probe_depth; // probe feed speed block.feed = plasma_start_params.probe_feed; // similar to G38.2 @@ -172,14 +172,14 @@ bool plasma_thc_probe_and_start(void) { // modify target to probe depth mc_get_position(pos); - pos[AXIS_Z] -= plasma_start_params.probe_depth * 0.5; + pos[AXIS_TOOL] -= plasma_start_params.probe_depth * 0.5; block.feed = plasma_start_params.probe_feed * 0.5f; // half speed // similar to G38.4 if (mc_probe(pos, 1, &block) == STATUS_PROBE_SUCCESS) { // modify target to torch start height mc_get_position(pos); - pos[AXIS_Z] += plasma_start_params.retract_height; + pos[AXIS_TOOL] += plasma_start_params.retract_height; // rapid feed block.feed = FLT_MAX; mc_line(pos, &block); @@ -193,7 +193,7 @@ bool plasma_thc_probe_and_start(void) if (plasma_thc_arc_ok()) { mc_get_position(pos); - pos[AXIS_Z] -= plasma_start_params.cut_depth; + pos[AXIS_TOOL] -= plasma_start_params.cut_depth; // rapid feed block.feed = plasma_start_params.cut_feed; mc_line(pos, &block); diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 35fdbdba3..b2d64df96 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -362,7 +362,11 @@ void protocol_send_status(void) if (CHECKFLAG(limits, LINACT1_LIMIT_MASK)) { + #if ((AXIS_COUNT == 2) && defined(USE_Y_AS_Z_ALIAS)) + serial_putc('Z'); + #else serial_putc('Y'); + #endif } if (CHECKFLAG(limits, LINACT2_LIMIT_MASK)) From b256dc5a58f2cf57b6313cd2ef8ea696e5080bf0 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Sep 2023 10:32:45 +0100 Subject: [PATCH 114/168] Applied #511 Applied #511 --- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 9 +++------ uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 4 ++++ uCNC/src/hal/mcus/samd21/mcu_samd21.c | 4 ++++ uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 4 ++++ uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 4 ++++ 5 files changed, 19 insertions(+), 6 deletions(-) diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index aebede043..71c04a8c6 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -60,21 +60,18 @@ extern "C" DECL_BUFFER(uint8_t, usb, USB_TX_BUFFER_SIZE); void mcu_usb_flush(void) { -#ifdef MCU_HAS_USB -#ifdef USE_ARDUINO_CDC + while (!BUFFER_EMPTY(usb)) { char tmp[USB_TX_BUFFER_SIZE]; uint8_t r; BUFFER_READ(usb, tmp, USB_TX_BUFFER_SIZE, r); +#ifdef MCU_HAS_USB UsbSerial.write(tmp, r); UsbSerial.flushTX(); - } -#else - tusb_cdc_flush(); -#endif #endif + } } void mcu_usb_putc(uint8_t c) diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index b4c8f78f8..4e4523695 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -789,6 +789,10 @@ void mcu_usb_flush(void) while (!tusb_cdc_write_available()) { mcu_dotasks(); // tinyusb device task + if (!tusb_cdc_connected) + { + return; + } } } #endif diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index 9d54fac7f..d815344f4 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -756,6 +756,10 @@ void mcu_usb_putc(uint8_t c) if (!tusb_cdc_write_available()) { mcu_usb_flush(); + if (!tusb_cdc_connected) + { + return; + } } tusb_cdc_write(c); } diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 54c6c2c23..18ec17f65 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -488,6 +488,10 @@ void mcu_usb_flush(void) while (!tusb_cdc_write_available()) { mcu_dotasks(); // tinyusb device task + if (!tusb_cdc_connected) + { + return; + } } } #endif diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index fdd30d6bb..7e0efef5a 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -497,6 +497,10 @@ void mcu_usb_flush(void) while (!tusb_cdc_write_available()) { mcu_dotasks(); // tinyusb device task + if (!tusb_cdc_connected) + { + return; + } } } #endif From d07884250efda905d0cc70d47c69624966b33441 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Sep 2023 11:41:07 +0100 Subject: [PATCH 115/168] modified delays and re-entrant code - modified cnc delay to run dotasks instead of only io_dotasks - prevent re-entrant code inside dotasks events --- uCNC/src/cnc.c | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 6ae545480..9326afd2a 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -74,13 +74,26 @@ WEAK_EVENT_HANDLER(rtc_tick) // event_cnc_dotasks_handler WEAK_EVENT_HANDLER(cnc_dotasks) { - DEFAULT_EVENT_HANDLER(cnc_dotasks); + // prevent re-entrancy + static bool running = false; + if (!running) + { + running = true; + DEFAULT_EVENT_HANDLER(cnc_dotasks); + running = false; + } } // event_cnc_dotasks_handler WEAK_EVENT_HANDLER(cnc_io_dotasks) { - DEFAULT_EVENT_HANDLER(cnc_io_dotasks); + // prevent re-entrancy + static bool running = false; + if (!running) + { + running = true; + DEFAULT_EVENT_HANDLER(cnc_io_dotasks); + } } // event_cnc_stop_handler @@ -257,13 +270,13 @@ bool cnc_dotasks(void) tool_pid_update(); #endif - if (!lock_itp) - { - lock_itp = true; #ifdef ENABLE_MAIN_LOOP_MODULES - EVENT_INVOKE(cnc_dotasks, NULL); + EVENT_INVOKE(cnc_dotasks, NULL); #endif + if (!lock_itp) + { + lock_itp = true; itp_run(); lock_itp = false; } @@ -573,7 +586,7 @@ void cnc_delay_ms(uint32_t miliseconds) uint32_t t_start = mcu_millis(); while ((mcu_millis() - t_start) < miliseconds) { - cnc_io_dotasks(); + cnc_dotasks(); } } From 12d1b0d3f5333f58dd6e7f5e10500accde509d55 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Sep 2023 15:35:00 +0100 Subject: [PATCH 116/168] dotasks redesign - redesign the main loop tasks to prevent re-entrant code on the event callbacks - force interlocking check before getting the alarm to force alarm code refresh if alarm condition is triggered by ISR --- uCNC/src/cnc.c | 37 ++++++++++++----------- uCNC/src/hal/kinematics/kinematic_scara.c | 36 ++++++++-------------- uCNC/src/hal/kinematics/kinematics.c | 0 3 files changed, 32 insertions(+), 41 deletions(-) create mode 100644 uCNC/src/hal/kinematics/kinematics.c diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 9326afd2a..2c77f07aa 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -74,26 +74,13 @@ WEAK_EVENT_HANDLER(rtc_tick) // event_cnc_dotasks_handler WEAK_EVENT_HANDLER(cnc_dotasks) { - // prevent re-entrancy - static bool running = false; - if (!running) - { - running = true; - DEFAULT_EVENT_HANDLER(cnc_dotasks); - running = false; - } + DEFAULT_EVENT_HANDLER(cnc_dotasks); } // event_cnc_dotasks_handler WEAK_EVENT_HANDLER(cnc_io_dotasks) { - // prevent re-entrancy - static bool running = false; - if (!running) - { - running = true; - DEFAULT_EVENT_HANDLER(cnc_io_dotasks); - } + DEFAULT_EVENT_HANDLER(cnc_io_dotasks); } // event_cnc_stop_handler @@ -271,7 +258,14 @@ bool cnc_dotasks(void) #endif #ifdef ENABLE_MAIN_LOOP_MODULES - EVENT_INVOKE(cnc_dotasks, NULL); + // prevent re-entrancy + static bool running = false; + if (!running) + { + running = true; + EVENT_INVOKE(cnc_dotasks, NULL); + running = false; + } #endif if (!lock_itp) @@ -429,6 +423,8 @@ bool cnc_has_alarm() uint8_t cnc_get_alarm(void) { + // force interlocking check to set alarm code in case this as not yet been set + cnc_check_interlocking(); return cnc_state.alarm; } @@ -1019,7 +1015,14 @@ static void cnc_io_dotasks(void) } #ifdef ENABLE_MAIN_LOOP_MODULES - EVENT_INVOKE(cnc_io_dotasks, NULL); + // prevent re-entrancy + static bool running = false; + if (!running) + { + running = true; + EVENT_INVOKE(cnc_io_dotasks, NULL); + running = false; + } #endif } diff --git a/uCNC/src/hal/kinematics/kinematic_scara.c b/uCNC/src/hal/kinematics/kinematic_scara.c index d8c4893c2..13a1f7a48 100644 --- a/uCNC/src/hal/kinematics/kinematic_scara.c +++ b/uCNC/src/hal/kinematics/kinematic_scara.c @@ -93,58 +93,46 @@ uint8_t kinematics_home(void) float target[AXIS_COUNT]; #ifndef DISABLE_ALL_LIMITS -#ifndef DISABLE_Z_HOMING -#if (defined(AXIS_Z) && (ASSERT_PIN(LIMIT_Z) || ASSERT_PIN(LIMIT_Z2))) - if (mc_home_axis(AXIS_Z, LIMIT_Z_MASK)) +#if AXIS_Z_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Z_HOMING_MASK, LINACT2_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Z; } #endif -#endif -#ifndef DISABLE_X_HOMING -#if (defined(AXIS_X) && (ASSERT_PIN(LIMIT_X) || ASSERT_PIN(LIMIT_X2))) - if (mc_home_axis(AXIS_X, LIMIT_X_MASK)) +#if AXIS_X_HOMING_MASK != 0 + if (mc_home_axis(AXIS_X_HOMING_MASK, LINACT0_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_X; } #endif -#endif -#ifndef DISABLE_Y_HOMING -#if (defined(AXIS_Y) && (ASSERT_PIN(LIMIT_Y) || ASSERT_PIN(LIMIT_Y2))) - if (mc_home_axis(AXIS_Y, LIMIT_Y_MASK)) +#if AXIS_Y_HOMING_MASK != 0 + if (mc_home_axis(AXIS_Y_HOMING_MASK, LINACT1_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_Y; } #endif -#endif -#ifndef DISABLE_A_HOMING -#if (defined(AXIS_A) && ASSERT_PIN(LIMIT_A)) - if (mc_home_axis(AXIS_A, LIMIT_A_MASK)) +#if AXIS_A_HOMING_MASK != 0 + if (mc_home_axis(AXIS_A_HOMING_MASK, LINACT3_LIMIT_MASK)) { return (KINEMATIC_HOMING_ERROR_X | KINEMATIC_HOMING_ERROR_Y | KINEMATIC_HOMING_ERROR_Z); } #endif -#endif -#ifndef DISABLE_B_HOMING -#if (defined(AXIS_B) && ASSERT_PIN(LIMIT_B)) - if (mc_home_axis(AXIS_B, LIMIT_B_MASK)) +#if AXIS_B_HOMING_MASK != 0 + if (mc_home_axis(AXIS_B_HOMING_MASK, LINACT4_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_B; } #endif -#endif -#ifndef DISABLE_C_HOMING -#if (defined(AXIS_C) && ASSERT_PIN(LIMIT_C)) - if (mc_home_axis(AXIS_C, LIMIT_C_MASK)) +#if AXIS_C_HOMING_MASK != 0 + if (mc_home_axis(AXIS_C_HOMING_MASK, LINACT5_LIMIT_MASK)) { return KINEMATIC_HOMING_ERROR_C; } -#endif #endif cnc_unlock(true); diff --git a/uCNC/src/hal/kinematics/kinematics.c b/uCNC/src/hal/kinematics/kinematics.c new file mode 100644 index 000000000..e69de29bb From b33c5e50073d723114f75165dbf1539b7b6f1ff7 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Sep 2023 15:45:22 +0100 Subject: [PATCH 117/168] updated comments --- uCNC/cnc_hal_config.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/uCNC/cnc_hal_config.h b/uCNC/cnc_hal_config.h index 986fd3f8b..fecc9aadd 100644 --- a/uCNC/cnc_hal_config.h +++ b/uCNC/cnc_hal_config.h @@ -166,7 +166,7 @@ extern "C" * To achieve that each each LIMITx_IO_MASK should be set to the corresponding STEP IO MASK that it controls * * For example to use STEP0 and STEP6 to drive the AXIS_X/LINACT0 you need to configure the correct LINACT0_IO_MASK and then to make LIMIT_X stop STEP0 and LIMIT_X2 stop STEP6 you need - * to reassing LIMIT_X2 to STEP6 IO MASK like this + * to reassign LIMIT_X2 to STEP6 IO MASK do it like this * * #define LIMIT_X2_IO_MASK STEP6_IO_MASK * @@ -217,21 +217,21 @@ extern "C" * Limits for AXIS X does not require any special configuration. Uses the default settings for a single linear actuator with one motor and a limit switch (uses LIMIT_X) * Limits for AXIS Y only require Limit Y2 to be reasigned to match STEP2 so in this case * - * #define ENABLE_Y_AUTOLEVEL * #define LIMIT_Y2_IO_MASK STEP2_IO_MASK * - * And finally limits for AXIS Z will new to be reassined to the matching STEPx. We will also need a 3rd limit. We will use LIMIT_A since AXIS_A is not used. + * And finally limits for AXIS Z will new to be reassigned to the matching STEPx. We will also need a 3rd limit. We will use LIMIT_A since AXIS_A is not used. * * // enable Z selfsquare/selfplane - * #define ENABLE_Z_AUTOLEVEL * #define LIMIT_Y_IO_MASK STEP3_IO_MASK * #define LIMIT_Y2_IO_MASK STEP4_IO_MASK * #define LIMIT_A_IO_MASK STEP5_IO_MASK * - * There is still a final step that involve reassing LINACT2 limits to include the extra limit (LIMIT A) like this + * There is still a final step that involve reassign LINACT2 limits to include the extra limit (LIMIT A) like this * * #define LINACT2_LIMIT_MASK (LIMIT_Y_IO_MASK | LIMIT_Y2_IO_MASK | LIMIT_A_IO_MASK) * + * Also remember that ENABLE_AXIS_AUTOLEVEL should be enabled for this to work + * * That is it. * * **/ From 05cc2f09b610891bbb4ae81089813a102091aa22 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 29 Sep 2023 17:17:07 +0100 Subject: [PATCH 118/168] reduce flash size for UNO board --- uCNC/src/hal/boards/avr/avr.ini | 22 ++++++++++++---------- uCNC/src/hal/kinematics/kinematics.c | 0 2 files changed, 12 insertions(+), 10 deletions(-) delete mode 100644 uCNC/src/hal/kinematics/kinematics.c diff --git a/uCNC/src/hal/boards/avr/avr.ini b/uCNC/src/hal/boards/avr/avr.ini index 35d6bf2ab..f651af70e 100644 --- a/uCNC/src/hal/boards/avr/avr.ini +++ b/uCNC/src/hal/boards/avr/avr.ini @@ -13,26 +13,28 @@ debug_build_flags = -Og -g3 -ggdb3 -gdwarf-2 build_flags = ${common.build_flags} -mcall-prologues -mrelax -flto -fno-fat-lto-objects -fno-tree-scev-cprop -Wl,--relax lib_ignore = EEPROM, SPI, Wire -[env:uno] +[atmega328p] extends = common_avr board = uno -build_flags = ${common_avr.build_flags} -D BOARD=BOARD_UNO +;saves a bit of flash +build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES + +[env:uno] +extends = atmega328p +build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_UNO [env:uno_shield_v3] -extends = common_avr -board = uno -build_flags = ${common_avr.build_flags} -D BOARD=BOARD_UNO_SHIELD_V3 +extends = atmega328p +build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_UNO_SHIELD_V3 [env:x_controller] -extends = common_avr -board = uno -build_flags = ${common_avr.build_flags} -D BOARD=BOARD_X_CONTROLLER +extends = atmega328p +build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_X_CONTROLLER [env:mks_dlc] extends = common_avr -board = uno board_build.f_cpu = 20000000UL -build_flags = ${common_avr.build_flags} -D BOARD=BOARD_MKS_DLC +build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_MKS_DLC [env:ramps14] extends = common_avr diff --git a/uCNC/src/hal/kinematics/kinematics.c b/uCNC/src/hal/kinematics/kinematics.c deleted file mode 100644 index e69de29bb..000000000 From 415a92ab1ae668249819d60f60cce9688566b149 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 1 Oct 2023 18:23:23 +0100 Subject: [PATCH 119/168] Applied #515 --- uCNC/src/modules/language/language_en.h | 1 + uCNC/src/modules/system_menu.c | 13 ++++++++----- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/uCNC/src/modules/language/language_en.h b/uCNC/src/modules/language/language_en.h index c32352f2b..4cf773cee 100644 --- a/uCNC/src/modules/language/language_en.h +++ b/uCNC/src/modules/language/language_en.h @@ -21,6 +21,7 @@ extern "C" #define STR_SAVE_SETTINGS "Save settings" #define STR_RESET_SETTINGS "Reset settings" #define STR_IO_CONFIG "IO config" +#define STR_OTHER "Other" #define STR_G64_FACT "G64 fact:" #define STR_ARC_TOL "Arc tol:" #define STR_HOMING "Homing" diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 25314af47..a06c6ad8d 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -128,12 +128,7 @@ DECL_MODULE(system_menu) DECL_MENU(2, 1, STR_SETTINGS); // settings menu - DECL_MENU_ACTION(2, set_load, STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); - DECL_MENU_ACTION(2, set_save, STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); - DECL_MENU_ACTION(2, set_reset, STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); DECL_MENU_GOTO(2, ioconfig, STR_IO_CONFIG, CONST_VARG(6)); - DECL_MENU_VAR(2, s11, STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(2, s12, STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); DECL_MENU_GOTO(2, gohome, STR_HOMING, CONST_VARG(3)); #if (AXIS_COUNT > 0) DECL_MENU_GOTO(2, goaxis, STR_AXIS, CONST_VARG(4)); @@ -141,6 +136,14 @@ DECL_MODULE(system_menu) #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) DECL_MENU_GOTO(2, kinemats, STR_KINEMATICS, CONST_VARG(5)); #endif + DECL_MENU_GOTO(2, other_config, STR_OTHER, CONST_VARG(9)); + DECL_MENU_ACTION(2, set_load, STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); + DECL_MENU_ACTION(2, set_save, STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); + DECL_MENU_ACTION(2, set_reset, STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); + + DECL_MENU(9, 2, STR_OTHER); + DECL_MENU_VAR(9, s11, STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s12, STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); DECL_MENU(6, 2, STR_IO_CONFIG); DECL_MENU_VAR(6, s2, STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); From b86e65dcaea0ecd7134ba760a6f8cc4f0660bc19 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 1 Oct 2023 19:17:54 +0100 Subject: [PATCH 120/168] fix missing encoder declaration --- uCNC/src/cnc.h | 1 + 1 file changed, 1 insertion(+) diff --git a/uCNC/src/cnc.h b/uCNC/src/cnc.h index b2de4f39e..45778b3e2 100644 --- a/uCNC/src/cnc.h +++ b/uCNC/src/cnc.h @@ -141,6 +141,7 @@ extern "C" #include "core/motion_control.h" #include "core/planner.h" #include "core/interpolator.h" +#include "modules/encoder.h" /** * From 404c9232c6d26d879201f49ef08d328793b45858 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 2 Oct 2023 23:55:32 +0100 Subject: [PATCH 121/168] Added some readmes --- uCNC/src/hal/mcus/esp32/README.md | 2 ++ uCNC/src/modules/system_menu.md | 46 +++++++++++++++++++++++++++++++ 2 files changed, 48 insertions(+) create mode 100644 uCNC/src/modules/system_menu.md diff --git a/uCNC/src/hal/mcus/esp32/README.md b/uCNC/src/hal/mcus/esp32/README.md index 1418315fd..c9ef25f0a 100644 --- a/uCNC/src/hal/mcus/esp32/README.md +++ b/uCNC/src/hal/mcus/esp32/README.md @@ -8,6 +8,8 @@ _µCNC for ESP32 can be built this way_ 4. Edit ```cnc_config.h file``` and ```cnc_hal_config.h file``` to fit your needs and board. 5. If needed edit the platformio.ini file environment for your board. Compile the sketch and upload it to your board. +**Note** ESP32 boards build environments are available in two flavors. Regular Arduino and an ESPIDF with Arduino as a component that has some optimized options for low latency timer ISR. + ## Method two - Arduino IDE (easiest) 1. Get [Arduino IDE](https://www.arduino.cc/en/software) and install it. diff --git a/uCNC/src/modules/system_menu.md b/uCNC/src/modules/system_menu.md new file mode 100644 index 000000000..6b3e9c4ef --- /dev/null +++ b/uCNC/src/modules/system_menu.md @@ -0,0 +1,46 @@ +

+ +

+ + +# µCNC +µCNC - Universal CNC firmware for microcontrollers + +## System menu + +System menu is a module that acts an integrated manager to control displays and handle user actions for the several screens that are presented to the user. +Extension modules can make use of the system menu to add custom menus for the user. +All generated menus can be translated. + +### Screens and overridable functions + +System menus have a set of overridable functions that can be customized to fit the screen format and display capabilities that can be broken in to two types: + - Custom screens (like the startup screen, the idle screen and the alarm screen, and popups) + - Structured screens (like menu screens) + +Each custom screen can be taylored to best fit a particular display format. +Menu screens are rendered in a different way. A menu screen is composed of a head section, a nav back element, then each menu entry item or a single item in edit mode and in the end a footer section. Menu items can be filtered so that only visible elements are rendered depending on were the user is inside the current menu. + +Only the the overrided screens and render callbacks will be displayed. All others will not generate any display feedback. + +### User actions and menu interactions + +System menu works by calling two main funtions inside the main loop. These are ´system_menu_action´ and ´system_menu_render´ (the calling of these functions must be done by the module that makes use of the system menu, like for example the display menu). + +´system_menu_action´ - receives a value that indicates a user action and sets the current navigation internal logic (page, selected item, etc...). Currently the system module handles 4 different actions: + - No action (when there is no user activity) + - User selected and item/or enter edit mode/or execute action + - User moved to the next item/or increment in edit mode + - User moved to the previous item/or decrement in edit mode +Custom actions can also be taylored to menu items, extending the range of user actions depending on the type of feedback system that is used (rotary knobs, keyboards, touch screens, etc..). + +´system_menu_render´ - renders the screen (if it's on a custom screen), according to the current menu page, type, position, etc. Menu items can navigate to other menu pages or also have fully custom rendered screens. + +There are several built in simple actions that are available via system menu module like calling serial commands, calling real time commands, navigate through the system menu, and utility functions like converting numbers and number arrays to strings to be rendered. + +### Static and dynamic menus + +It's possible to generate both static and dynamic menus. +Static menus are declarated in a static way. Menus are composed by a menu page that can contain multiple menu items. Menu items can perform several actions like navigate to other pages, execute code, edit variables, etc.. +In some cases static menus are not possible. For example when navigating though an SD card file system. In this case it's possible to generate dynamic menus. Dynamic menu pages can have custom action and render actions, to allow the content to be rendered/generated live. + From e11f7bd72c5d320b221a0dced695ecc77c6d4b77 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 2 Oct 2023 23:57:09 +0100 Subject: [PATCH 122/168] Update system_menu.md --- uCNC/src/modules/system_menu.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/uCNC/src/modules/system_menu.md b/uCNC/src/modules/system_menu.md index 6b3e9c4ef..1d4e48a34 100644 --- a/uCNC/src/modules/system_menu.md +++ b/uCNC/src/modules/system_menu.md @@ -25,16 +25,16 @@ Only the the overrided screens and render callbacks will be displayed. All other ### User actions and menu interactions -System menu works by calling two main funtions inside the main loop. These are ´system_menu_action´ and ´system_menu_render´ (the calling of these functions must be done by the module that makes use of the system menu, like for example the display menu). +System menu works by calling two main funtions inside the main loop. These are ´´´system_menu_action´´´ and ´´´system_menu_render´´´ (the calling of these functions must be done by the module that makes use of the system menu, like for example the display menu). -´system_menu_action´ - receives a value that indicates a user action and sets the current navigation internal logic (page, selected item, etc...). Currently the system module handles 4 different actions: +´´´system_menu_action´´´ - receives a value that indicates a user action and sets the current navigation internal logic (page, selected item, etc...). Currently the system module handles 4 different actions: - No action (when there is no user activity) - User selected and item/or enter edit mode/or execute action - User moved to the next item/or increment in edit mode - User moved to the previous item/or decrement in edit mode Custom actions can also be taylored to menu items, extending the range of user actions depending on the type of feedback system that is used (rotary knobs, keyboards, touch screens, etc..). -´system_menu_render´ - renders the screen (if it's on a custom screen), according to the current menu page, type, position, etc. Menu items can navigate to other menu pages or also have fully custom rendered screens. +´´´system_menu_render´´´ - renders the screen (if it's on a custom screen), according to the current menu page, type, position, etc. Menu items can navigate to other menu pages or also have fully custom rendered screens. There are several built in simple actions that are available via system menu module like calling serial commands, calling real time commands, navigate through the system menu, and utility functions like converting numbers and number arrays to strings to be rendered. From 888d4ea5ab442521376671f108a54ef0a8b7e0c3 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 2 Oct 2023 23:59:54 +0100 Subject: [PATCH 123/168] Update system_menu.md --- uCNC/src/modules/system_menu.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/uCNC/src/modules/system_menu.md b/uCNC/src/modules/system_menu.md index 1d4e48a34..57543b44a 100644 --- a/uCNC/src/modules/system_menu.md +++ b/uCNC/src/modules/system_menu.md @@ -25,16 +25,16 @@ Only the the overrided screens and render callbacks will be displayed. All other ### User actions and menu interactions -System menu works by calling two main funtions inside the main loop. These are ´´´system_menu_action´´´ and ´´´system_menu_render´´´ (the calling of these functions must be done by the module that makes use of the system menu, like for example the display menu). +System menu works by calling two main funtions inside the main loop. These are `system_menu_action` and `system_menu_render` (the calling of these functions must be done by the module that makes use of the system menu, like for example the display menu). -´´´system_menu_action´´´ - receives a value that indicates a user action and sets the current navigation internal logic (page, selected item, etc...). Currently the system module handles 4 different actions: +`system_menu_action` - receives a value that indicates a user action and sets the current navigation internal logic (page, selected item, etc...). Currently the system module handles 4 different actions: - No action (when there is no user activity) - User selected and item/or enter edit mode/or execute action - User moved to the next item/or increment in edit mode - User moved to the previous item/or decrement in edit mode Custom actions can also be taylored to menu items, extending the range of user actions depending on the type of feedback system that is used (rotary knobs, keyboards, touch screens, etc..). -´´´system_menu_render´´´ - renders the screen (if it's on a custom screen), according to the current menu page, type, position, etc. Menu items can navigate to other menu pages or also have fully custom rendered screens. +`system_menu_render` - renders the screen (if it's on a custom screen), according to the current menu page, type, position, etc. Menu items can navigate to other menu pages or also have fully custom rendered screens. There are several built in simple actions that are available via system menu module like calling serial commands, calling real time commands, navigate through the system menu, and utility functions like converting numbers and number arrays to strings to be rendered. From 44441cf7a587fe7297992d5630c5fd217269634a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 4 Oct 2023 17:54:43 +0100 Subject: [PATCH 124/168] fixed sticky RUN state after alarm - applied fix #520 --- uCNC/src/cnc.c | 1 + 1 file changed, 1 insertion(+) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 2c77f07aa..c33bc50b0 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -437,6 +437,7 @@ void cnc_stop(void) #ifdef ENABLE_MAIN_LOOP_MODULES EVENT_INVOKE(cnc_stop, NULL); #endif + cnc_clear_exec_state(EXEC_RUN); } uint8_t cnc_unlock(bool force) From 44c1fa4b23905377268efc7c5137fbdeb7312791 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 9 Oct 2023 00:13:47 +0100 Subject: [PATCH 125/168] modify serial to deal with multiple streams --- uCNC/src/README.md | 8 +- uCNC/src/cnc.c | 20 +- uCNC/src/core/parser.c | 46 +-- uCNC/src/core/parser.h | 6 +- uCNC/src/hal/boards/avr/avr.ini | 2 +- uCNC/src/hal/mcus/README.md | 8 +- uCNC/src/hal/mcus/avr/mcu_avr.c | 40 +- uCNC/src/hal/mcus/esp32/esp32_arduino.cpp | 30 +- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 6 +- uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp | 22 +- uCNC/src/hal/mcus/esp8266/mcu_esp8266.c | 2 +- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 4 +- uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 12 +- uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h | 2 +- uCNC/src/hal/mcus/mcu.c | 79 ++-- uCNC/src/hal/mcus/mcu.h | 38 +- uCNC/src/hal/mcus/rp2040/mcu_rp2040.c | 2 +- uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp | 32 +- uCNC/src/hal/mcus/samd21/mcu_samd21.c | 8 +- uCNC/src/hal/mcus/samd21/mcumap_samd21.h | 2 +- uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 6 +- uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h | 2 +- uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 6 +- uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h | 2 +- uCNC/src/hal/mcus/virtual/mcu_virtual.c | 218 ++++++----- uCNC/src/hal/mcus/virtual/mcumap_virtual.h | 2 +- uCNC/src/interface/protocol.c | 14 +- uCNC/src/interface/protocol.h | 4 +- uCNC/src/interface/serial.c | 358 ++++++++---------- uCNC/src/interface/serial.h | 43 ++- uCNC/src/interface/settings.c | 6 +- uCNC/src/interface/settings.h | 2 +- uCNC/src/modules/softuart.c | 2 +- uCNC/src/modules/system_menu.c | 54 +-- uCNC/src/modules/system_menu.h | 22 +- uCNC/src/utils.h | 8 +- 36 files changed, 592 insertions(+), 526 deletions(-) diff --git a/uCNC/src/README.md b/uCNC/src/README.md index 0aff6bff1..946a3ce56 100644 --- a/uCNC/src/README.md +++ b/uCNC/src/README.md @@ -42,7 +42,7 @@ __NOTE__: Not all event hooks might be listed here. To find all available event | gcode_before_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires before a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | | gcode_after_motion | gcode_exec_args_t* | ENABLE_PARSER_MODULES | Fires after a motion group command is executed (G0, G1, G2, etc...). Arg is a pointer to a gcode_exec_args_t struct | | grbl_cmd | grbl_cmd_args_t* | ENABLE_PARSER_MODULES | Fires when a custom/unknown '$' grbl type command is received. Arg is a pointer to a grbl_cmd_args_t struct | -| parse_token | NULL | ENABLE_PARSER_MODULES | Fires when a custom/unknown token/char is received for further processing | +| parse_token | NULL | ENABLE_PARSER_MODULES | Fires when a custom/unknown token/uint8_t is received for further processing | | parser_get_modes | uint8_t * | ENABLE_PARSER_MODULES | Fires when $G command is issued and the active modal states array is being requested (can be used to modify the active modes with extended gcodes). Arg is a pointer to an uint8_t array with the parser motion groups current values | | parser_reset | NULL | ENABLE_PARSER_MODULES | Fires on parser reset | | cnc_reset | NULL | ENABLE_MAIN_LOOP_MODULES | Fires when µCNC resets | @@ -88,7 +88,7 @@ gcode_parse_args_t* - Pointer to a struct of type gcode_parse_args_t. The gcode_ ``` typedef struct gcode_parse_args_ { - unsigned char word; // This is the GCode word being parsed (usually 'G' or 'M') + uint8_t word; // This is the GCode word being parsed (usually 'G' or 'M') uint8_t code; // This is the GCode word argument converted to uint8_t format (example 98) uint8_t error; // The parser current error code (STATUS_GCODE_EXTENDED_UNSUPPORTED) float value; // This is the actual GCode word argument parsed as float. Useful if code has mantissa or is bigger then 255 (example 98.1) @@ -123,9 +123,9 @@ grbl_cmd_args_t* - Pointer to a struct of type grbl_cmd_args_t. The grbl_cmd_arg typedef struct grbl_cmd_args_ { uint8_t *error; // current parser error state - unsigned char *cmd; // pointer to the command string + uint8_t *cmd; // pointer to the command string uint8_t len; // command string length - char next_char; // next char to be read + uint8_t next_char; // next uint8_t to be read } grbl_cmd_args_t; ``` diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index c33bc50b0..8e01fb91a 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -126,7 +126,7 @@ void cnc_run(void) // tries to reset. If fails jumps to error while (cnc_unlock(false) != UNLOCK_ERROR) { - serial_select(SERIAL_UART); + // serial_select(SERIAL_UART); cnc_state.loop_state = LOOP_RUNNING; do @@ -150,7 +150,7 @@ void cnc_run(void) do { - if (!serial_rx_is_empty()) + if (!serial_available()) { if (serial_getc() == EOL) { @@ -174,7 +174,7 @@ bool cnc_exec_cmd(void) uint32_t exec_time; #endif // process gcode commands - if (!serial_rx_is_empty()) + if (serial_available()) { uint8_t error = 0; // protocol_echo(); @@ -182,7 +182,7 @@ bool cnc_exec_cmd(void) switch (c) { case OVF: - serial_rx_clear(); + serial_clear(); error = STATUS_OVERFLOW; break; case EOL: // not necessary but faster to catch empty lines and windows newline (CR+LF) @@ -597,7 +597,7 @@ void cnc_reset(void) cnc_state.alarm = EXEC_ALARM_NOALARM; // clear all systems - serial_rx_clear(); + serial_clear(); itp_clear(); planner_clear(); kinematics_init(); @@ -1029,9 +1029,9 @@ static void cnc_io_dotasks(void) void cnc_run_startup_blocks(void) { - serial_select(SERIAL_N0); - cnc_exec_cmd(); - serial_select(SERIAL_N1); - cnc_exec_cmd(); - serial_select(SERIAL_UART); + // serial_select(SERIAL_N0); + // cnc_exec_cmd(); + // serial_select(SERIAL_N1); + // cnc_exec_cmd(); + // serial_select(SERIAL_UART); } diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index b3b8c5424..472b8f191 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -60,12 +60,12 @@ static float g92permanentoffset[AXIS_COUNT]; static int32_t rt_probe_step_pos[STEPPER_COUNT]; static float parser_last_pos[AXIS_COUNT]; -static unsigned char parser_get_next_preprocessed(bool peek); -FORCEINLINE static void parser_get_comment(unsigned char start_char); -FORCEINLINE static uint8_t parser_get_token(unsigned char *word, float *value); +static uint8_t parser_get_next_preprocessed(bool peek); +FORCEINLINE static void parser_get_comment(uint8_t start_char); +FORCEINLINE static uint8_t parser_get_token(uint8_t *word, float *value); FORCEINLINE static uint8_t parser_gcode_word(uint8_t code, uint8_t mantissa, parser_state_t *new_state, parser_cmd_explicit_t *cmd); FORCEINLINE static uint8_t parser_mcode_word(uint8_t code, uint8_t mantissa, parser_state_t *new_state, parser_cmd_explicit_t *cmd); -FORCEINLINE static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa, parser_words_t *words, parser_cmd_explicit_t *cmd); +FORCEINLINE static uint8_t parser_letter_word(uint8_t c, float value, uint8_t mantissa, parser_words_t *words, parser_cmd_explicit_t *cmd); static uint8_t parse_grbl_exec_code(uint8_t code); static uint8_t parser_fetch_command(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); static uint8_t parser_validate_command(parser_state_t *new_state, parser_words_t *words, parser_cmd_explicit_t *cmd); @@ -152,7 +152,7 @@ void parser_init(void) uint8_t parser_read_command(void) { uint8_t error = STATUS_OK; - unsigned char c = serial_peek(); + uint8_t c = serial_peek(); if (c == '$') { @@ -307,8 +307,8 @@ void parser_update_probe_pos(void) static uint8_t parser_grbl_command(void) { serial_getc(); // eat $ - unsigned char c = serial_peek(); - unsigned char grbl_cmd_str[GRBL_CMD_MAX_LEN + 1]; + uint8_t c = serial_peek(); + uint8_t grbl_cmd_str[GRBL_CMD_MAX_LEN + 1]; uint8_t grbl_cmd_len = 0; // if not IDLE @@ -377,7 +377,7 @@ static uint8_t parser_grbl_command(void) { float val = 0; setting_offset_t setting_num = 0; - serial_ungetc(); + //serial_ungetc(); error = parser_get_float(&val); if (!error) { @@ -457,7 +457,7 @@ static uint8_t parser_grbl_command(void) // everything ok reverts string and saves it do { - serial_ungetc(); + //serial_ungetc(); } while (serial_peek() != '='); serial_getc(); settings_save_startup_gcode(block_address); @@ -537,7 +537,7 @@ static uint8_t parser_grbl_command(void) } #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS - if (mcu_custom_grbl_cmd((char *)grbl_cmd_str, grbl_cmd_len, c) == STATUS_OK) + if (mcu_custom_grbl_cmd((uint8_t *)grbl_cmd_str, grbl_cmd_len, c) == STATUS_OK) { return STATUS_OK; } @@ -659,7 +659,7 @@ static uint8_t parser_fetch_command(parser_state_t *new_state, parser_words_t *w uint8_t wordcount = 0; for (;;) { - unsigned char word = 0; + uint8_t word = 0; float value = 0; // this flushes leading white chars and also takes care of processing comments parser_get_next_preprocessed(true); @@ -1849,7 +1849,7 @@ uint8_t parser_get_float(float *value) uint8_t fpcount = 0; uint8_t result = NUMBER_UNDEF; - unsigned char c = parser_get_next_preprocessed(true); + uint8_t c = parser_get_next_preprocessed(true); *value = 0; @@ -1945,7 +1945,7 @@ uint8_t parser_get_float(float *value) */ #define COMMENT_OK 1 #define COMMENT_NOTOK 2 -static void parser_get_comment(unsigned char start_char) +static void parser_get_comment(uint8_t start_char) { uint8_t comment_end = 0; #ifdef PROCESS_COMMENTS @@ -1953,7 +1953,7 @@ static void parser_get_comment(unsigned char start_char) #endif for (;;) { - unsigned char c = serial_peek(); + uint8_t c = serial_peek(); switch (c) { // case '(': //error under RS274NGC (commented for Grbl compatibility) @@ -2011,11 +2011,11 @@ static void parser_get_comment(unsigned char start_char) } } -static uint8_t parser_get_token(unsigned char *word, float *value) +static uint8_t parser_get_token(uint8_t *word, float *value) { - unsigned char c = serial_getc(); + uint8_t c = serial_getc(); - // if other char starts tokenization + // if other uint8_t starts tokenization if (c >= 'a' && c <= 'z') { c -= 32; // uppercase @@ -2032,7 +2032,7 @@ static uint8_t parser_get_token(unsigned char *word, float *value) #ifdef ECHO_CMD serial_putc(c); #endif - if (c >= 'A' && c <= 'Z') // invalid recognized char + if (c >= 'A' && c <= 'Z') // invalid recognized uint8_t { if (!parser_get_float(value)) { @@ -2341,7 +2341,7 @@ static uint8_t parser_mcode_word(uint8_t code, uint8_t mantissa, parser_state_t return STATUS_OK; } -static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa, parser_words_t *words, parser_cmd_explicit_t *cmd) +static uint8_t parser_letter_word(uint8_t c, float value, uint8_t mantissa, parser_words_t *words, parser_cmd_explicit_t *cmd) { uint16_t new_words = cmd->words; switch (c) @@ -2492,7 +2492,7 @@ static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa #endif break; default: - if (c >= 'A' && c <= 'Z') // invalid recognized char + if (c >= 'A' && c <= 'Z') // invalid recognized uint8_t { return STATUS_GCODE_UNUSED_WORDS; } @@ -2509,9 +2509,9 @@ static uint8_t parser_letter_word(unsigned char c, float value, uint8_t mantissa return STATUS_OK; } -static unsigned char parser_get_next_preprocessed(bool peek) +static uint8_t parser_get_next_preprocessed(bool peek) { - unsigned char c = serial_peek(); + uint8_t c = serial_peek(); while (c == ' ' || c == '(' || c == ';') { @@ -2533,7 +2533,7 @@ static unsigned char parser_get_next_preprocessed(bool peek) static void parser_discard_command(void) { - unsigned char c = '@'; + uint8_t c = '@'; #ifdef ECHO_CMD serial_putc(c); #endif diff --git a/uCNC/src/core/parser.h b/uCNC/src/core/parser.h index 4d542ab4d..8ef555e8d 100644 --- a/uCNC/src/core/parser.h +++ b/uCNC/src/core/parser.h @@ -292,7 +292,7 @@ extern "C" // generates a default delegate, event and handler hook typedef struct gcode_parse_args_ { - unsigned char word; + uint8_t word; uint8_t code; uint8_t* error; float value; @@ -328,9 +328,9 @@ extern "C" typedef struct grbl_cmd_args_ { uint8_t *error; - unsigned char *cmd; + uint8_t *cmd; uint8_t len; - char next_char; + uint8_t next_char; } grbl_cmd_args_t; DECL_EVENT_HANDLER(grbl_cmd); diff --git a/uCNC/src/hal/boards/avr/avr.ini b/uCNC/src/hal/boards/avr/avr.ini index f651af70e..4a3496bc2 100644 --- a/uCNC/src/hal/boards/avr/avr.ini +++ b/uCNC/src/hal/boards/avr/avr.ini @@ -17,7 +17,7 @@ lib_ignore = EEPROM, SPI, Wire extends = common_avr board = uno ;saves a bit of flash -build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES +build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES -D DISABLE_MULTISTRTEAM_SERIAL [env:uno] extends = atmega328p diff --git a/uCNC/src/hal/mcus/README.md b/uCNC/src/hal/mcus/README.md index 16e7c0fc3..e06e47148 100644 --- a/uCNC/src/hal/mcus/README.md +++ b/uCNC/src/hal/mcus/README.md @@ -313,7 +313,7 @@ Before creating a custom HAL for a custom board/microcontroller the microcontrol #define __romstr__ #endif #ifndef __romarr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #endif #ifndef rom_strptr #define rom_strptr * @@ -771,11 +771,11 @@ Before creating a custom HAL for a custom board/microcontroller the microcontrol #endif #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS - uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char); + uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char); #endif /** - * sends a char either via uart (hardware, software USB CDC, Wifi or BT) + * sends a uint8_t either via uart (hardware, software USB CDC, Wifi or BT) * can be defined either as a function or a macro call * */ #ifndef mcu_putc @@ -862,7 +862,7 @@ Also internally **AT LEAST** these macros need to be defined - use a 1ms interrupt timer or RTC to generate the running time and call `mcu_rtc_cb(uint32_t millis)`. `mcu_dotasks()` **MUST NOT BE CALLED HERE** - - if a hardware communications has events or ISR, the ISR must call `mcu_com_rx_cb(unsigned char c)` with the received char, or if handled internally by library or RTOS send every received char in the buffer through `mcu_com_rx_cb(unsigned char c)`. + - if a hardware communications has events or ISR, the ISR must call `mcu_com_rx_cb(uint8_t c)` with the received uint8_t, or if handled internally by library or RTOS send every received uint8_t in the buffer through `mcu_com_rx_cb(uint8_t c)`. - if interruptible inputs are used they appropriately call mcu_limits_changed_cb(), mcu_controls_changed_cb(), mcu_probe_changed_cb() and mcu_inputs_changed_cb() diff --git a/uCNC/src/hal/mcus/avr/mcu_avr.c b/uCNC/src/hal/mcus/avr/mcu_avr.c index 1fd7e19be..bc82979bc 100644 --- a/uCNC/src/hal/mcus/avr/mcu_avr.c +++ b/uCNC/src/hal/mcus/avr/mcu_avr.c @@ -372,10 +372,21 @@ ISR(PCINT2_vect, ISR_BLOCK) // input pin on change service routine #endif #ifdef MCU_HAS_UART +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); ISR(COM_RX_vect, ISR_BLOCK) { #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(COM_INREG); + uint8_t c = COM_INREG; + if (mcu_com_rx_cb(COM_INREG)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb(COM_INREG); #endif @@ -384,16 +395,16 @@ ISR(COM_RX_vect, ISR_BLOCK) #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); ISR(COM_TX_vect, ISR_BLOCK) { - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { CLEARBIT(UCSRB_REG, UDRIE_BIT); return; } uint8_t c; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); COM_OUTREG = c; } @@ -571,13 +582,30 @@ uint8_t mcu_get_servo(uint8_t servo) #ifdef MCU_HAS_UART +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) diff --git a/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp b/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp index 9f0d2a539..f1065072b 100644 --- a/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp +++ b/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp @@ -62,9 +62,9 @@ uint16_t bt_settings_offset; WebServer httpServer(80); HTTPUpdateServer httpUpdater; -const char *update_path = "/firmware"; -const char *update_username = WIFI_USER; -const char *update_password = WIFI_PASS; +const uint8_t *update_path = "/firmware"; +const uint8_t *update_username = WIFI_USER; +const uint8_t *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -73,8 +73,8 @@ typedef struct { uint8_t wifi_on; uint8_t wifi_mode; - char ssid[WIFI_SSID_MAX_LEN]; - char pass[WIFI_SSID_MAX_LEN]; + uint8_t ssid[WIFI_SSID_MAX_LEN]; + uint8_t pass[WIFI_SSID_MAX_LEN]; } wifi_settings_t; uint16_t wifi_settings_offset; @@ -86,15 +86,15 @@ extern "C" #include "../../../cnc.h" #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS - uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char) + uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char) { - char str[64]; - char arg[ARG_MAX_LEN]; - char has_arg = (next_char == '='); + uint8_t str[64]; + uint8_t arg[ARG_MAX_LEN]; + uint8_t has_arg = (next_char == '='); memset(arg, 0, sizeof(arg)); if (has_arg) { - char c = serial_getc(); + uint8_t c = serial_getc(); uint8_t i = 0; while (c) { @@ -322,7 +322,7 @@ extern "C" #ifdef ENABLE_WIFI static uint32_t next_info = 30000; static bool connected = false; - char str[64]; + uint8_t str[64]; if (!wifi_settings.wifi_on) { @@ -484,14 +484,14 @@ extern "C" } #endif - unsigned char esp32_wifi_bt_read(void) + uint8_t esp32_wifi_bt_read(void) { #ifdef ENABLE_WIFI if (esp32_wifi_clientok()) { if (serverClient.available() > 0) { - return (unsigned char)serverClient.read(); + return (uint8_t)serverClient.read(); } } #endif @@ -499,11 +499,11 @@ extern "C" #ifdef ENABLE_BLUETOOTH if (SerialBT.hasClient()) { - return (unsigned char)SerialBT.read(); + return (uint8_t)SerialBT.read(); } #endif - return (unsigned char)0; + return (uint8_t)0; } bool esp32_wifi_bt_rx_ready(void) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 4c35dfdba..6b25b2ae4 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -47,7 +47,7 @@ volatile static uint32_t esp32_io_counter_reload; hw_timer_t *esp32_step_timer; void esp32_wifi_bt_init(void); -void esp32_wifi_bt_flush(char *buffer); +void esp32_wifi_bt_flush(uint8_t *buffer); void esp32_wifi_bt_process(void); #ifndef FLASH_EEPROM_SIZE @@ -599,7 +599,7 @@ uint8_t mcu_get_pwm(uint8_t pwm) /*UART*/ /** - * sends a char either via uart (hardware, software or USB virtual COM port) + * sends a uint8_t either via uart (hardware, software or USB virtual COM port) * can be defined either as a function or a macro call * */ #ifdef MCU_HAS_UART @@ -824,7 +824,7 @@ void mcu_dotasks(void) esp_task_wdt_reset(); // loop through received data - char rxdata[RX_BUFFER_SIZE]; + uint8_t rxdata[RX_BUFFER_SIZE]; int rxlen, i; #ifdef MCU_HAS_UART rxlen = uart_read_bytes(UART_PORT, rxdata, RX_BUFFER_CAPACITY, 0); diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp index fe98d74a4..9bde157f3 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp @@ -48,9 +48,9 @@ ESP8266WebServer httpServer(80); ESP8266HTTPUpdateServer httpUpdater; -const char *update_path = "/firmware"; -const char *update_username = WIFI_USER; -const char *update_password = WIFI_PASS; +const uint8_t *update_path = "/firmware"; +const uint8_t *update_username = WIFI_USER; +const uint8_t *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -59,8 +59,8 @@ typedef struct { uint8_t wifi_on; uint8_t wifi_mode; - char ssid[WIFI_SSID_MAX_LEN]; - char pass[WIFI_SSID_MAX_LEN]; + uint8_t ssid[WIFI_SSID_MAX_LEN]; + uint8_t pass[WIFI_SSID_MAX_LEN]; } wifi_settings_t; uint16_t wifi_settings_offset; @@ -72,15 +72,15 @@ extern "C" #include "../../../cnc.h" #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS - uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char) + uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char) { - char str[64]; - char arg[ARG_MAX_LEN]; - char has_arg = (next_char == '='); + uint8_t str[64]; + uint8_t arg[ARG_MAX_LEN]; + uint8_t has_arg = (next_char == '='); memset(arg, 0, sizeof(arg)); if (has_arg) { - char c = serial_getc(); + uint8_t c = serial_getc(); uint8_t i = 0; while (c) { @@ -284,7 +284,7 @@ extern "C" #ifdef ENABLE_WIFI static uint32_t next_info = 30000; static bool connected = false; - char str[64]; + uint8_t str[64]; if (!wifi_settings.wifi_on) { diff --git a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c index 2355838cc..06c1473eb 100644 --- a/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c +++ b/uCNC/src/hal/mcus/esp8266/mcu_esp8266.c @@ -154,7 +154,7 @@ IRAM_ATTR void mcu_itp_isr(void) // CLEAR_PERI_REG_MASK(UART_INT_ENA(0), UART_RXFIFO_FULL_INT_ENA | UART_RXFIFO_TOUT_INT_ENA); // WRITE_PERI_REG(UART_INT_CLR(0), (READ_PERI_REG(UART_INT_ST(0)) & (UART_RXFIFO_FULL_INT_ST | UART_RXFIFO_TOUT_INT_ST))); // uint8_t fifo_len = (READ_PERI_REG(UART_STATUS(0)) >> UART_RXFIFO_CNT_S) & UART_RXFIFO_CNT; -// unsigned char c = 0; +// uint8_t c = 0; // for (uint8_t i = 0; i < fifo_len; i++) // { diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index 71c04a8c6..428e00fdc 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -63,7 +63,7 @@ extern "C" while (!BUFFER_EMPTY(usb)) { - char tmp[USB_TX_BUFFER_SIZE]; + uint8_t tmp[USB_TX_BUFFER_SIZE]; uint8_t r; BUFFER_READ(usb, tmp, USB_TX_BUFFER_SIZE, r); @@ -83,7 +83,7 @@ extern "C" BUFFER_ENQUEUE(usb, &c); } - char mcu_usb_getc(void) + uint8_t mcu_usb_getc(void) { int16_t c = UsbSerial.read(); return (uint8_t)((c >= 0) ? c : 0); diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index 4e4523695..febf0394d 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -26,7 +26,7 @@ #ifdef USE_ARDUINO_CDC extern void mcu_usb_dotasks(void); extern void mcu_usb_init(void); -extern char mcu_usb_getc(void); +extern uint8_t mcu_usb_getc(void); extern uint8_t mcu_usb_available(void); extern uint8_t mcu_usb_tx_available(void); #else @@ -256,7 +256,7 @@ void MCU_COM_ISR(void) if (irqstatus == UART_IIR_INTID_RDA) { - unsigned char c = (unsigned char)(COM_INREG & UART_RBR_MASKBIT); + uint8_t c = (uint8_t)(COM_INREG & UART_RBR_MASKBIT); #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -311,7 +311,7 @@ void MCU_COM2_ISR(void) if (irqstatus == UART_IIR_INTID_RDA) { - unsigned char c = (unsigned char)(COM2_INREG & UART_RBR_MASKBIT); + uint8_t c = (uint8_t)(COM2_INREG & UART_RBR_MASKBIT); #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -569,7 +569,7 @@ uint8_t mcu_get_servo(uint8_t servo) #endif /** - * sends a char either via uart (hardware, software or USB virtual COM port) + * sends a uint8_t either via uart (hardware, software or USB virtual COM port) * can be defined either as a function or a macro call * */ #ifdef MCU_HAS_UART @@ -811,7 +811,7 @@ void mcu_dotasks() mcu_usb_dotasks(); while (mcu_usb_available()) { - unsigned char c = (unsigned char)mcu_usb_getc(); + uint8_t c = (uint8_t)mcu_usb_getc(); #ifndef DETACH_USB_FROM_MAIN_PROTOCOL mcu_com_rx_cb(c); #else @@ -823,7 +823,7 @@ void mcu_dotasks() while (tusb_cdc_available()) { - unsigned char c = (unsigned char)tusb_cdc_read(); + uint8_t c = (uint8_t)tusb_cdc_read(); #ifndef DETACH_USB_FROM_MAIN_PROTOCOL mcu_com_rx_cb(c); #else diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index ed64b3fed..dc1de7871 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -60,7 +60,7 @@ extern "C" // defines special mcu to access flash strings and arrays #define __rom__ #define __romstr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/hal/mcus/mcu.c b/uCNC/src/hal/mcus/mcu.c index 4da909a20..158722476 100644 --- a/uCNC/src/hal/mcus/mcu.c +++ b/uCNC/src/hal/mcus/mcu.c @@ -717,49 +717,56 @@ void __attribute__((weak)) mcu_io_init(void) } #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS -uint8_t __attribute__((weak)) mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char) +uint8_t __attribute__((weak)) mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char) { return STATUS_INVALID_STATEMENT; } #endif -void mcu_putc(uint8_t c) +// ISR +// New uint8_t handle strategy +// All ascii will be sent to buffer and processed later (including comments) +MCU_RX_CALLBACK bool mcu_com_rx_cb(uint8_t c) { - // USB, WiFi and BT have usually dedicated buffers -#if defined(MCU_HAS_USB) && !defined(DETACH_USB_FROM_MAIN_PROTOCOL) - mcu_usb_putc(c); -#endif -#if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) - mcu_bt_putc(c); -#endif -#if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_uart_putc(c); -#endif -#if defined(MCU_HAS_UART2) && !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_uart2_putc(c); -#endif -#if defined(MCU_HAS_WIFI) && !defined(DETACH_WIFI_FROM_MAIN_PROTOCOL) - mcu_wifi_putc(c); -#endif -} + static bool is_grbl_cmd = false; + if (c < ((uint8_t)0x7F)) // ascii (all bellow DEL) + { + switch (c) + { + case CMD_CODE_REPORT: +#if STATUS_AUTOMATIC_REPORT_INTERVAL >= 100 + return false; +#endif + case CMD_CODE_RESET: + case CMD_CODE_FEED_HOLD: + cnc_call_rt_command((uint8_t)c); + return false; + case '\n': + case '\r': + case 0: + // EOL marker + is_grbl_cmd = false; + break; + case '$': + is_grbl_cmd = true; + break; + case CMD_CODE_CYCLE_START: + if (!is_grbl_cmd) + { + cnc_call_rt_command(CMD_CODE_CYCLE_START); + return false; + } + break; + } -void mcu_flush(void) -{ -#if defined(MCU_HAS_USB) && !defined(DETACH_USB_FROM_MAIN_PROTOCOL) - mcu_usb_flush(); -#endif -#if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) - mcu_bt_flush(); -#endif -#if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_uart_flush(); -#endif -#if defined(MCU_HAS_UART2) && !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_uart2_flush(); -#endif -#if defined(MCU_HAS_WIFI) && !defined(DETACH_WIFI_FROM_MAIN_PROTOCOL) - mcu_wifi_flush(); -#endif + } + else // extended ascii (plus CMD_CODE_CYCLE_START and DEL) + { + cnc_call_rt_command((uint8_t)c); + return false; + } + + return true; } #if (defined(MCU_HAS_I2C)) diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index e24590124..fbbb5c223 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -45,6 +45,13 @@ extern "C" #define F_STEP_MAX 30000 #endif +#define STREAM_UART 1 +#define STREAM_UART2 2 +#define STREAM_USB 4 +#define STREAM_WIFI 8 +#define STREAM_BTH 16 +#define STREAM_BOARDCAST 255 + // defines special mcu to access flash strings and arrays #ifndef __rom__ #define __rom__ @@ -53,7 +60,7 @@ extern "C" #define __romstr__ #endif #ifndef __romarr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #endif #ifndef rom_strptr #define rom_strptr * @@ -77,7 +84,7 @@ extern "C" MCU_CALLBACK void mcu_step_cb(void); MCU_CALLBACK void mcu_step_reset_cb(void); - MCU_RX_CALLBACK void mcu_com_rx_cb(uint8_t c); + MCU_RX_CALLBACK bool mcu_com_rx_cb(uint8_t c); MCU_CALLBACK void mcu_rtc_cb(uint32_t millis); MCU_IO_CALLBACK void mcu_controls_changed_cb(void); MCU_IO_CALLBACK void mcu_limits_changed_cb(void); @@ -511,22 +518,19 @@ extern "C" #endif #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS - uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char); + uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char); #endif -/** - * sends a char either via uart (hardware, software USB CDC, Wifi or BT) - * can be defined either as a function or a macro call - * */ -#ifndef mcu_putc - void mcu_putc(uint8_t c); -#endif + /** + * sends a uint8_t either via uart (hardware, software USB CDC, Wifi or BT) + * can be defined either as a function or a macro call + * */ + -#ifndef mcu_flush - void mcu_flush(void); -#endif #ifdef MCU_HAS_USB + uint8_t mcu_usb_getc(bool peek); + uint8_t mcu_usb_available(void); void mcu_usb_putc(uint8_t c); void mcu_usb_flush(void); #ifdef DETACH_USB_FROM_MAIN_PROTOCOL @@ -535,6 +539,9 @@ extern "C" #endif #ifdef MCU_HAS_UART + uint8_t mcu_uart_getc(bool peek); + uint8_t mcu_uart_available(void); + void mcu_uart_clear(void); void mcu_uart_putc(uint8_t c); void mcu_uart_flush(void); #ifdef DETACH_UART_FROM_MAIN_PROTOCOL @@ -543,6 +550,8 @@ extern "C" #endif #ifdef MCU_HAS_UART2 + uint8_t mcu_uart2_getc(void); + uint8_t mcu_uart2_available(void); void mcu_uart2_putc(uint8_t c); void mcu_uart2_flush(void); #ifdef DETACH_UART2_FROM_MAIN_PROTOCOL @@ -551,6 +560,8 @@ extern "C" #endif #ifdef MCU_HAS_WIFI + uint8_t mcu_wifi_getc(void); + uint8_t mcu_wifi_available(void); void mcu_wifi_putc(uint8_t c); void mcu_wifi_flush(void); #ifdef DETACH_WIFI_FROM_MAIN_PROTOCOL @@ -559,6 +570,7 @@ extern "C" #endif #ifdef MCU_HAS_BLUETOOTH + uint8_t mcu_bt_getc(void); void mcu_bt_putc(uint8_t c); void mcu_bt_flush(void); #ifdef DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL diff --git a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c index 8f53c1183..c5f637983 100644 --- a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c +++ b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c @@ -27,7 +27,7 @@ static volatile bool rp2040_global_isr_enabled; extern void rp2040_uart_init(int baud); extern void rp2040_uart_flush(void); -extern void rp2040_uart_write(char c); +extern void rp2040_uart_write(uint8_t c); extern bool rp2040_uart_rx_ready(void); extern bool rp2040_uart_tx_ready(void); extern void rp2040_uart_process(void); diff --git a/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp b/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp index 22d7401b7..e415bec2e 100644 --- a/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp +++ b/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp @@ -66,9 +66,9 @@ uint16_t bt_settings_offset; WebServer httpServer(80); HTTPUpdateServer httpUpdater; -const char *update_path = "/firmware"; -const char *update_username = WIFI_USER; -const char *update_password = WIFI_PASS; +const uint8_t *update_path = "/firmware"; +const uint8_t *update_username = WIFI_USER; +const uint8_t *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -77,8 +77,8 @@ typedef struct { uint8_t wifi_on; uint8_t wifi_mode; - char ssid[WIFI_SSID_MAX_LEN]; - char pass[WIFI_PASS_MAX_LEN]; + uint8_t ssid[WIFI_SSID_MAX_LEN]; + uint8_t pass[WIFI_PASS_MAX_LEN]; } wifi_settings_t; uint16_t wifi_settings_offset; @@ -86,15 +86,15 @@ wifi_settings_t wifi_settings; #endif #ifdef BOARD_HAS_CUSTOM_SYSTEM_COMMANDS -uint8_t mcu_custom_grbl_cmd(char *grbl_cmd_str, uint8_t grbl_cmd_len, char next_char) +uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t next_char) { - char str[128]; - char arg[ARG_MAX_LEN]; - char has_arg = (next_char == '='); + uint8_t str[128]; + uint8_t arg[ARG_MAX_LEN]; + uint8_t has_arg = (next_char == '='); memset(arg, 0, sizeof(arg)); if (has_arg) { - char c = serial_getc(); + uint8_t c = serial_getc(); uint8_t i = 0; while (c) { @@ -322,7 +322,7 @@ bool rp2040_wifi_clientok(void) #ifdef ENABLE_WIFI static uint32_t next_info = 30000; static bool connected = false; - char str[128]; + uint8_t str[128]; if (!wifi_settings.wifi_on) { @@ -477,23 +477,23 @@ void mcu_bt_flush(void) } #endif -unsigned char rp2040_wifi_bt_read(void) +uint8_t rp2040_wifi_bt_read(void) { #ifdef ENABLE_WIFI if (rp2040_wifi_clientok()) { if (serverClient.available() > 0) { - return (unsigned char)serverClient.read(); + return (uint8_t)serverClient.read(); } } #endif #ifdef ENABLE_BLUETOOTH - return (unsigned char)SerialBT.read(); + return (uint8_t)SerialBT.read(); #endif - return (unsigned char)0; + return (uint8_t)0; } bool rp2040_wifi_bt_rx_ready(void) @@ -586,7 +586,7 @@ extern "C" { while (!BUFFER_EMPTY(usb)) { - char tmp[USB_TX_BUFFER_SIZE]; + uint8_t tmp[USB_TX_BUFFER_SIZE]; uint8_t r; BUFFER_READ(usb, tmp, USB_TX_BUFFER_SIZE, r); diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index d815344f4..476b7619e 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -218,7 +218,7 @@ void mcu_com_isr() if (COM_UART->USART.INTFLAG.bit.RXC && COM_UART->USART.INTENSET.bit.RXC) { COM_UART->USART.INTFLAG.bit.RXC = 1; - unsigned char c = (0xff & COM_INREG); + uint8_t c = (0xff & COM_INREG); #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -254,7 +254,7 @@ void mcu_com2_isr() if (COM2_UART->USART.INTFLAG.bit.RXC && COM2_UART->USART.INTENSET.bit.RXC) { COM2_UART->USART.INTFLAG.bit.RXC = 1; - unsigned char c = (0xff & COM2_INREG); + uint8_t c = (0xff & COM2_INREG); #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -737,7 +737,7 @@ uint8_t mcu_get_pwm(uint8_t pwm) #endif /** - * checks if the serial hardware of the MCU is ready do send the next char + * checks if the serial hardware of the MCU is ready do send the next uint8_t * */ #ifndef mcu_tx_ready bool mcu_tx_ready(void) @@ -747,7 +747,7 @@ bool mcu_tx_ready(void) #endif /** - * sends a char either via uart (hardware, software or USB virtual COM_UART port) + * sends a uint8_t either via uart (hardware, software or USB virtual COM_UART port) * can be defined either as a function or a macro call * */ #ifdef MCU_HAS_USB diff --git a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h index 2fdd8680f..27dc8a382 100644 --- a/uCNC/src/hal/mcus/samd21/mcumap_samd21.h +++ b/uCNC/src/hal/mcus/samd21/mcumap_samd21.h @@ -64,7 +64,7 @@ extern "C" // defines special mcu to access flash strings and arrays #define __rom__ #define __romstr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 18ec17f65..962c8a51b 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -83,7 +83,7 @@ void MCU_SERIAL_ISR(void) { if (COM_UART->SR & USART_SR_RXNE) { - unsigned char c = COM_INREG; + uint8_t c = COM_INREG; #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -118,7 +118,7 @@ void MCU_SERIAL2_ISR(void) { if (COM2_UART->SR & USART_SR_RXNE) { - unsigned char c = COM2_INREG; + uint8_t c = COM2_INREG; #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -735,7 +735,7 @@ void mcu_dotasks() while (tusb_cdc_available()) { - unsigned char c = (unsigned char)tusb_cdc_read(); + uint8_t c = (uint8_t)tusb_cdc_read(); #if !defined(DETACH_USB_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else diff --git a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h index ccbe90d68..0358441bf 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h +++ b/uCNC/src/hal/mcus/stm32f1x/mcumap_stm32f1x.h @@ -50,7 +50,7 @@ extern "C" // defines special mcu to access flash strings and arrays #define __rom__ #define __romstr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index 7e0efef5a..41f7adc15 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -86,7 +86,7 @@ void MCU_SERIAL_ISR(void) { if (COM_UART->SR & USART_SR_RXNE) { - unsigned char c = COM_INREG; + uint8_t c = COM_INREG; #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -121,7 +121,7 @@ void MCU_SERIAL2_ISR(void) { if (COM2_UART->SR & USART_SR_RXNE) { - unsigned char c = COM2_INREG; + uint8_t c = COM2_INREG; #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else @@ -729,7 +729,7 @@ void mcu_dotasks() while (tusb_cdc_available()) { - unsigned char c = (unsigned char)tusb_cdc_read(); + uint8_t c = (uint8_t)tusb_cdc_read(); #if !defined(DETACH_USB_FROM_MAIN_PROTOCOL) mcu_com_rx_cb(c); #else diff --git a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h index f79805205..3f9fc676f 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h +++ b/uCNC/src/hal/mcus/stm32f4x/mcumap_stm32f4x.h @@ -51,7 +51,7 @@ extern "C" // defines special mcu to access flash strings and arrays #define __rom__ #define __romstr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 022231cc4..45ab0f46f 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -7,8 +7,8 @@ void itp_step_isr(); void itp_step_reset_isr(); serial.h - void serial_rx_isr(char c); - char serial_tx_isr(); + void serial_rx_isr(uint8_t c); + uint8_t serial_tx_isr(); trigger_control.h void dio_limits_isr(uint8_t limits); void io_controls_isr(uint8_t controls); @@ -241,7 +241,7 @@ void ioserver(void *args) // Send a message to the pipe server. cbToWrite = sizeof(VIRTUAL_MAP); - char lpvMessage[sizeof(VIRTUAL_MAP)]; + uint8_t lpvMessage[sizeof(VIRTUAL_MAP)]; do { memcpy(lpvMessage, &virtualmap, sizeof(VIRTUAL_MAP)); @@ -310,9 +310,11 @@ void ioserver(void *args) * */ HANDLE rxReady, rxThread; HANDLE txReady, txThread; +HANDLE txReady, txThread, txFree; HANDLE bufferMutex; -char com_buffer[256]; -char mcu_tx_buffer[256]; +HANDLE bufferMutexDone; +uint8_t com_buffer[256]; +uint8_t mcu_tx_buffer[256]; volatile bool mcu_tx_empty; volatile bool mcu_tx_enabled; @@ -331,7 +333,7 @@ DWORD WINAPI socketserver(LPVOID lpParam) struct addrinfo hints; int iSendResult; - char recvbuf[256]; + uint8_t recvbuf[256]; int recvbuflen = 256; // Initialize Winsock @@ -449,7 +451,7 @@ DWORD WINAPI socketserver(LPVOID lpParam) void socketclient(void) { DWORD dwWaitResult; - char buffer[256]; + uint8_t buffer[256]; int iSendResult; int iResult; @@ -504,8 +506,8 @@ void socketclient(void) #ifdef USESERIAL volatile HANDLE hComm = NULL; -unsigned char ComPortName[] = "\\\\.\\" str(WIN_COM_NAME); -unsigned char ComParams[] = "baud=" str(BAUDRATE) " parity=N data=8 stop=1"; +uint8_t ComPortName[] = "\\\\.\\" str(WIN_COM_NAME); +uint8_t ComParams[] = "baud=" str(BAUDRATE) " parity=N data=8 stop=1"; DWORD WINAPI virtualserialserver(LPVOID lpParam) { @@ -596,7 +598,7 @@ DWORD WINAPI virtualserialserver(LPVOID lpParam) // Status event is stored in the event flag // specified in the original WaitCommEvent call. // Deal with the status event as appropriate. - char recvbuf[256]; + uint8_t recvbuf[256]; int recvbuflen = 256; DWORD dwRead = 0; switch (dwCommEvent) @@ -645,7 +647,7 @@ void virtualserialclient(void) { DWORD dwWaitResult; OVERLAPPED osWrite = {0}; - char buffer[256]; + uint8_t buffer[256]; int iSendResult; int iResult; @@ -703,7 +705,8 @@ void virtualserialclient(void) #endif #ifdef USECONSOLE - +DECL_BUFFER(uint8_t, uart_rx, 128); +DECL_BUFFER(uint8_t, uart_tx, 64); DWORD WINAPI virtualconsoleserver(LPVOID lpParam) { WSADATA wsaData; @@ -715,7 +718,7 @@ DWORD WINAPI virtualconsoleserver(LPVOID lpParam) struct addrinfo hints; int iSendResult; - char recvbuf[256]; + uint8_t recvbuf[256]; int recvbuflen = 256; memset(recvbuf, 0, sizeof(recvbuf)); @@ -723,39 +726,19 @@ DWORD WINAPI virtualconsoleserver(LPVOID lpParam) // Receive until the peer shuts down the connection do { - unsigned char c = getchar(); + uint8_t c = getchar(); switch (c) { - // case '"': - // virtualmap.special_inputs ^= (1 << (ESTOP - LIMIT_X)); - // mcu_controls_changed_cb(); - // break; - // case '%': - // virtualmap.special_inputs ^= (1 << (LIMIT_X - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case '&': - // virtualmap.special_inputs ^= (1 << (LIMIT_Y - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case '/': - // virtualmap.special_inputs ^= (1 << (LIMIT_Z - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case '[': - // virtualmap.special_inputs ^= (1 << (LIMIT_X2 - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case ']': - // virtualmap.special_inputs ^= (1 << (LIMIT_Y2 - LIMIT_X)); - // mcu_limits_changed_cb(); - // break; - // case '}': - // virtualmap.special_inputs ^= (1 << (SAFETY_DOOR - LIMIT_X)); - // mcu_controls_changed_cb(); - // break; default: - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + BUFFER_ENQUEUE(uart_rx, &c); + } break; } @@ -771,10 +754,10 @@ void virtualconsoleclient(void) while (1) { + SetEvent(txFree); dwWaitResult = WaitForSingleObject( txReady, // event handle INFINITE); // indefinite wait - switch (dwWaitResult) { // Event object was signaled @@ -792,6 +775,7 @@ void virtualconsoleclient(void) { putchar(com_buffer[k]); } + memset(com_buffer, 0, 256); break; // The thread got ownership of an abandoned mutex @@ -805,7 +789,7 @@ void virtualconsoleclient(void) // An error occurred default: printf("Serial client thread error (%d)\n", (int)GetLastError()); - return 0; + return; } memset(com_buffer, 0, 256); @@ -871,6 +855,19 @@ void com_init(void) return; } + txFree = CreateEvent( + NULL, // default security attributes + FALSE, // manual-reset event + FALSE, // initial state is nonsignaled + TEXT("txFree") // object name + ); + + if (txFree == NULL) + { + printf("CreateEvent failed (%d)\n", GetLastError()); + return; + } + rxThread = CreateThread( NULL, // default security attributes 0, // use default stack size @@ -918,28 +915,37 @@ void com_init(void) void com_send(char *buff, int len) { - DWORD dwWaitResult; - dwWaitResult = WaitForSingleObject( - bufferMutex, // handle to mutex - INFINITE); // no time-out interval - mcu_tx_empty = false; + DWORD dwWaitResult = WaitForSingleObject( + txFree, // event handle + INFINITE); // indefinite wait switch (dwWaitResult) { // The thread got ownership of the mutex case WAIT_OBJECT_0: - memcpy(com_buffer, buff, len); - ReleaseMutex(bufferMutex); - mcu_tx_empty = true; - break; + + dwWaitResult = WaitForSingleObject( + bufferMutex, // handle to mutex + INFINITE); // no time-out interval + mcu_tx_empty = false; + switch (dwWaitResult) + { + // The thread got ownership of the mutex + case WAIT_OBJECT_0: + memcpy(com_buffer, buff, len); + ReleaseMutex(bufferMutex); + mcu_tx_empty = true; + break; - // The thread got ownership of an abandoned mutex - case WAIT_ABANDONED: - printf("Wait error (%d)\n", (int)GetLastError()); - return; - } + // The thread got ownership of an abandoned mutex + case WAIT_ABANDONED: + printf("Wait error (%d)\n", (int)GetLastError()); + return; + } - SetEvent(txReady); - sleep(1); + SetEvent(txReady); + break; + } + // sleep(1); } // UART communication @@ -967,7 +973,7 @@ volatile unsigned long *pulse_counter_ptr; volatile unsigned long integrator_counter = 0; volatile bool pulse_enabled = false; volatile bool send_char = false; -volatile unsigned char uart_char; +volatile uint8_t uart_char; uint8_t pwms[16]; @@ -977,7 +983,7 @@ pthread_t thread_idout; pthread_t thread_timer_id; pthread_t thread_step_id; -void mcu_rx_isr(unsigned char c) +void mcu_rx_isr(uint8_t c) { if (c) { @@ -999,7 +1005,7 @@ void mcu_tx_isr(void) // #else // for (;;) // { -// unsigned char c = getch(); +// uint8_t c = getch(); // if (c != 0) // { // uart_char = c; @@ -1127,7 +1133,7 @@ void ticksimul(void) { // FILE *infile = fopen("inputs.txt", "r"); - // char inputs[255]; + // uint8_t inputs[255]; // if (infile != NULL) //checks input file // { @@ -1434,22 +1440,60 @@ bool mcu_tx_ready(void) return mcu_tx_empty; } +uint8_t mcu_uart_getc() +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - // #ifdef ENABLE_SYNC_TX - // com_send(c, 1); - // #endif - putchar(c); + while (BUFFER_FULL(uart_tx)) + { + mcu_uart_flush(); + } + BUFFER_ENQUEUE(uart_tx, &c); } + void mcu_uart_flush(void) { - // #ifndef ENABLE_SYNC_TX - // uint8_t i = (mcu_com_tx_buffer_write < TX_BUFFER_HALF) ? 0 : TX_BUFFER_HALF; - // com_send(&mcu_com_tx_buffer[i], strlen(&mcu_com_tx_buffer[i])); - // #endif + uint8_t buff[64]; + int len = 0; + BUFFER_READ(uart_tx, buff, 64, len); + com_send(buff, len); +#if ASSERT_PIN(ACTIVITY_LED) + io_toggle_output(ACTIVITY_LED); +#endif } -// void mcu_putc(char c) +// void mcu_uart_putc(uint8_t c) +// { +// // #ifdef ENABLE_SYNC_TX +// // com_send(c, 1); +// // #endif +// putchar(c); +// } +// void mcu_uart_flush(void) +// { +// // #ifndef ENABLE_SYNC_TX +// // uint8_t i = (mcu_com_tx_buffer_write < TX_BUFFER_HALF) ? 0 : TX_BUFFER_HALF; +// // com_send(&mcu_com_tx_buffer[i], strlen(&mcu_com_tx_buffer[i])); +// // #endif +// } + +// void mcu_putc(uint8_t c) //{ // static int buff_index = 0; // if (c != 0) @@ -1471,9 +1515,9 @@ void mcu_uart_flush(void) // mcu_tx_enabled = true; // } -char mcu_getc(void) +uint8_t mcu_getc(void) { - char c = 0; + uint8_t c = 0; if (g_mcu_buffertail != g_mcu_bufferhead) { c = g_mcu_combuffer[g_mcu_buffertail]; @@ -1491,7 +1535,7 @@ char mcu_getc(void) return c; } -char mcu_peek(void) +uint8_t mcu_peek(void) { if (g_mcu_buffercount == 0) return 0; @@ -1500,7 +1544,7 @@ char mcu_peek(void) void mcu_bufferClear(void) { - memset(&g_mcu_combuffer, 0, sizeof(char) * COM_BUFFER_SIZE); + memset(&g_mcu_combuffer, 0, sizeof(uint8_t) * COM_BUFFER_SIZE); g_mcu_buffertail = 0; g_mcu_bufferhead = 0; } @@ -1553,10 +1597,10 @@ void mcu_stop_itp_isr(void) pulse_enabled = false; } -void mcu_printfp(const char *__fmt, ...) +void mcu_printfp(const uint8_t *__fmt, ...) { - char buffer[50]; - char *newfmt = strcpy((char *)&buffer, __fmt); + uint8_t buffer[50]; + uint8_t *newfmt = strcpy((uint8_t *)&buffer, __fmt); va_list __ap; va_start(__ap, __fmt); vprintf(newfmt, __ap); @@ -1574,18 +1618,18 @@ void virtual_delay_us(uint16_t delay) } while (elapsed < delay); } -void mcu_loadDummyPayload(const char *__fmt, ...) +void mcu_loadDummyPayload(const uint8_t *__fmt, ...) { - char buffer[30]; - char payload[50]; - char *newfmt = strcpy((char *)&buffer, __fmt); + uint8_t buffer[30]; + uint8_t payload[50]; + uint8_t *newfmt = strcpy((uint8_t *)&buffer, __fmt); va_list __ap; va_start(__ap, __fmt); - vsprintf((char *)&payload, newfmt, __ap); + vsprintf((uint8_t *)&payload, newfmt, __ap); va_end(__ap); g_mcu_bufferhead = strlen(payload); memset(&g_mcu_combuffer, 0, g_mcu_bufferhead); - strcpy((char *)&g_mcu_combuffer, payload); + strcpy((uint8_t *)&g_mcu_combuffer, payload); g_mcu_buffertail = 0; g_mcu_buffercount++; } diff --git a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h index 71a1fd3b1..f6ddb75ee 100644 --- a/uCNC/src/hal/mcus/virtual/mcumap_virtual.h +++ b/uCNC/src/hal/mcus/virtual/mcumap_virtual.h @@ -29,7 +29,7 @@ #endif #define __rom__ #define __romstr__ -#define __romarr__ const char +#define __romarr__ const uint8_t #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index b2d64df96..181f86c51 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -70,17 +70,17 @@ void protocol_send_alarm(int8_t alarm) protocol_send_newline(); } -void protocol_send_string(const char *__s) +void protocol_send_string(const uint8_t *__s) { - unsigned char c = (unsigned char)rom_strptr(__s++); + uint8_t c = (uint8_t)rom_strptr(__s++); do { serial_putc(c); - c = (unsigned char)rom_strptr(__s++); + c = (uint8_t)rom_strptr(__s++); } while (c != 0); } -void protocol_send_feedback(const char *__s) +void protocol_send_feedback(const uint8_t *__s) { protocol_send_string(MSG_START); protocol_send_string(__s); @@ -399,7 +399,7 @@ void protocol_send_status(void) protocol_send_string(MSG_STATUS_BUF); serial_print_int((uint32_t)planner_get_buffer_freeblocks()); serial_putc(','); - serial_print_int((uint32_t)serial_get_rx_freebytes()); + serial_print_int((uint32_t)serial_freebytes()); } serial_putc('>'); @@ -473,7 +473,7 @@ void protocol_send_probe_result(uint8_t val) protocol_send_newline(); } -static void protocol_send_parser_modalstate(unsigned char word, uint8_t val, uint8_t mantissa) +static void protocol_send_parser_modalstate(uint8_t word, uint8_t val, uint8_t mantissa) { serial_putc(word); serial_print_int(val); @@ -568,7 +568,7 @@ void protocol_send_gcode_setting_line_flt(setting_offset_t setting, float value) void protocol_send_start_blocks(void) { protocol_busy = true; - unsigned char c = 0; + uint8_t c = 0; uint16_t address = STARTUP_BLOCK0_ADDRESS_OFFSET; protocol_send_string(__romstr__("$N0=")); for (;;) diff --git a/uCNC/src/interface/protocol.h b/uCNC/src/interface/protocol.h index 7230dd837..158f18eb8 100644 --- a/uCNC/src/interface/protocol.h +++ b/uCNC/src/interface/protocol.h @@ -33,8 +33,8 @@ extern "C" void protocol_send_alarm(int8_t alarm); void protocol_send_status(void); DECL_EVENT_HANDLER(protocol_send_status); - void protocol_send_string(const char *__s); - void protocol_send_feedback(const char *__s); + void protocol_send_string(const uint8_t *__s); + void protocol_send_feedback(const uint8_t *__s); void protocol_send_probe_result(uint8_t val); void protocol_send_gcode_coordsys(void); void protocol_send_gcode_modes(void); diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 88f4e90ab..9b6ed587b 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -1,10 +1,21 @@ /* Name: serial.c Description: Serial communication basic read/write functions µCNC. + The serial has been completelly redesigned to allow multiple stream sources of code. + Streams are prority based. + Priority is as follows + UART + UART2 + USB + WIFI + BT + Others + + Copyright: Copyright (c) João Martins Author: João Martins - Date: 30/12/2019 + Date: 07-10-2023 µCNC is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -19,173 +30,202 @@ #include #include "../cnc.h" -static unsigned char serial_rx_buffer[RX_BUFFER_SIZE]; -static uint8_t serial_rx_read; -static volatile uint8_t serial_rx_write; -static volatile uint8_t serial_rx_overflow; +static serial_stream_t *serial_stream; +static serial_stream_t *current_stream; -static uint8_t serial_read_select; -static uint16_t serial_read_index; - -// static void serial_rx_clear(); +#if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) +DECL_SERIAL_STREAM(uart_serial_stream, mcu_uart_getc, mcu_uart_available, mcu_uart_clear, mcu_uart_putc, mcu_uart_flush); +#endif +#if defined(MCU_HAS_UART2) && !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) +DECL_SERIAL_STREAM(uart2_serial_stream, mcu_uart2_getc, mcu_uart2_available, mcu_uart2_clear, mcu_uart2_putc, mcu_uart2_flush); +#endif +#if defined(MCU_HAS_USB) && !defined(DETACH_USB_FROM_MAIN_PROTOCOL) +DECL_SERIAL_STREAM(usb_serial_stream, mcu_usb_getc, mcu_usb_available, mcu_usb_clear, mcu_usb_putc, mcu_usb_flush); +#endif +#if defined(MCU_HAS_WIFI) && !defined(DETACH_WIFI_FROM_MAIN_PROTOCOL) +DECL_SERIAL_STREAM(wifi_serial_stream, mcu_wifi_getc, mcu_wifi_available, mcu_wifi_clear, mcu_wifi_putc, mcu_wifi_flush); +#endif +#if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) +DECL_SERIAL_STREAM(bt_serial_stream, mcu_bt_getc, mcu_bt_available, mcu_bt_clear, mcu_bt_putc, mcu_bt_flush); +#endif void serial_init(void) { #ifdef FORCE_GLOBALS_TO_0 - serial_rx_write = 0; - serial_rx_read = 0; - memset(serial_rx_buffer, 0, sizeof(serial_rx_buffer)); + serial_stream = NULL; +#endif + +#if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) + serial_stream_register(&uart_serial_stream); +#endif +#if defined(MCU_HAS_UART2) && !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) + serial_stream_register(&uart2_serial_stream); +#endif +#if defined(MCU_HAS_USB) && !defined(DETACH_USB_FROM_MAIN_PROTOCOL) + serial_stream_register(&usb_serial_stream); +#endif +#if defined(MCU_HAS_WIFI) && !defined(DETACH_WIFI_FROM_MAIN_PROTOCOL) + serial_stream_register(&wifi_serial_stream); #endif +#if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) + serial_stream_register(&bt_serial_stream); +#endif + current_stream = serial_stream; } -bool serial_rx_is_empty(void) +void serial_stream_register(serial_stream_t *stream) { - switch (serial_read_select) + if (serial_stream == NULL) { - case SERIAL_UART: - return (serial_rx_write == serial_rx_read); - case SERIAL_N0: - case SERIAL_N1: - return false; + serial_stream = stream; + serial_stream->next = NULL; + } + else + { + serial_stream_t *p = serial_stream; + while (p->next != NULL) + { + p = p->next; + } + p->next = stream; + p->next->next = NULL; } - - return true; } -unsigned char serial_getc(void) +static uint8_t serial_peek_buffer; +void serial_stream_change(serial_stream_t *stream) { - unsigned char c; - switch (serial_read_select) + serial_peek_buffer = 0; + if (stream != NULL) { - case SERIAL_UART: - while (serial_rx_write == serial_rx_read) - { - cnc_dotasks(); - } + current_stream = stream; + return; + } - c = serial_rx_buffer[serial_rx_read]; - if (++serial_rx_read == RX_BUFFER_SIZE) - { - serial_rx_read = 0; - } + current_stream = current_stream->next; - switch (c) - { - case '\r': - case '\n': - case EOL: - return EOL; - case '\t': - return ' '; - } - - return c; - break; - case SERIAL_N0: - case SERIAL_N1: - c = mcu_eeprom_getc(serial_read_index++); - if (c > 0 && c < 128) - { - serial_putc(c); - } - else - { - c = 0; - serial_putc(':'); - serial_read_select = SERIAL_UART; // resets the serial select - } - return c; + if (!current_stream) + { + current_stream = serial_stream; } - - return EOL; } -void serial_ungetc(void) +uint8_t serial_getc(void) { - if (--serial_rx_read == 0xFF) + uint8_t peek = serial_peek_buffer; + if (peek) { - serial_rx_read = RX_BUFFER_SIZE - 1; + serial_peek_buffer = 0; + return peek; } -} -void serial_select(uint8_t source) -{ - serial_read_select = source; - switch (serial_read_select) + while (!current_stream->stream_available()) + ; + peek = current_stream->stream_getc(); + switch (peek) { - case SERIAL_N0: - serial_putc('>'); - serial_read_index = STARTUP_BLOCK0_ADDRESS_OFFSET; - break; - case SERIAL_N1: - serial_putc('>'); - serial_read_index = STARTUP_BLOCK1_ADDRESS_OFFSET; - break; + case '\n': + case '\r': + case 0: + return EOL; + case '\t': + return ' '; } + return peek; } -unsigned char serial_peek(void) +uint8_t serial_peek(void) { - unsigned char c; - switch (serial_read_select) - { - case SERIAL_UART: - while (serial_rx_write == serial_rx_read) - { - cnc_dotasks(); - } - c = serial_rx_buffer[serial_rx_read]; - switch (c) - { - case '\r': - case '\n': - case EOL: - return EOL; - case '\t': - return ' '; - default: - return c; - } - break; - case SERIAL_N0: - case SERIAL_N1: - c = mcu_eeprom_getc(serial_read_index); - return (c > 0 && c < 128) ? c : 0; - } - return EOL; + uint8_t peek = serial_getc(); + serial_peek_buffer = peek; + + return peek; } -void serial_inject_cmd(const char *__s) +uint8_t serial_available(void) { - unsigned char c; - do - { - c = (unsigned char)*__s++; - mcu_com_rx_cb(c); - } while (c); + return current_stream->stream_available(); +} + +uint8_t serial_freebytes(void) +{ + return (RX_BUFFER_SIZE - serial_available()); +} + +void serial_clear(void) +{ + current_stream->stream_clear(); +} + +#ifndef DISABLE_MULTISTRTEAM_SERIAL +static bool serial_broadcast_enabled; +#endif +void serial_broadcast(bool enable) +{ +#ifndef DISABLE_MULTISTRTEAM_SERIAL + serial_broadcast_enabled = enable; +#endif } static uint8_t serial_tx_count; -void serial_putc(unsigned char c) +void serial_putc(uint8_t c) { serial_tx_count++; - mcu_putc(c); +#ifndef DISABLE_MULTISTRTEAM_SERIAL + if (!serial_broadcast_enabled) + { + current_stream->stream_putc(c); + } + else + { + serial_stream_t *p = serial_stream; + while (p) + { + p->stream_putc(c); + p = p->next; + } + } +#else + serial_stream->stream_putc(c); +#endif + if (c == '\n') { serial_tx_count = 0; - mcu_flush(); + serial_flush(); } #if ASSERT_PIN(ACTIVITY_LED) io_toggle_output(ACTIVITY_LED); #endif } +void serial_flush(void) +{ +#ifndef DISABLE_MULTISTRTEAM_SERIAL + if (!serial_broadcast_enabled) + { + current_stream->stream_flush(); + } + else + { + serial_stream_t *p = serial_stream; + while (p) + { + p->stream_flush(); + p = p->next; + } + } +#else + serial_stream->stream_flush(); +#endif +} + uint8_t serial_tx_busy(void) { return serial_tx_count; } -void print_str(print_cb cb, const char *__s) +void print_str(print_cb cb, const uint8_t *__s) { while (*__s) { @@ -199,7 +239,7 @@ void print_bytes(print_cb cb, const uint8_t *data, uint8_t count) { cb(' '); uint8_t up = *data >> 4; - char c = (up > 9) ? ('a' + up - 10) : ('0' + up); + uint8_t c = (up > 9) ? ('a' + up - 10) : ('0' + up); cb(c); up = *data & 0x0F; c = (up > 9) ? ('a' + up - 10) : ('0' + up); @@ -216,7 +256,7 @@ void print_int(print_cb cb, int32_t num) return; } - unsigned char buffer[11]; + uint8_t buffer[11]; uint8_t i = 0; if (num < 0) @@ -325,83 +365,3 @@ void print_fltarr(print_cb cb, float *arr, uint8_t count) } while (--i); } } - -// ISR -// New char handle strategy -// All ascii will be sent to buffer and processed later (including comments) -MCU_RX_CALLBACK void mcu_com_rx_cb(unsigned char c) -{ - static bool is_grbl_cmd = false; - uint8_t write; - if (c < ((unsigned char)0x7F)) // ascii (all bellow DEL) - { - switch (c) - { - case CMD_CODE_REPORT: -#if STATUS_AUTOMATIC_REPORT_INTERVAL >= 100 - return; -#endif - case CMD_CODE_RESET: - case CMD_CODE_FEED_HOLD: - cnc_call_rt_command((uint8_t)c); - return; - case '\n': - case '\r': - case 0: - // EOL marker - is_grbl_cmd = false; - break; - case '$': - is_grbl_cmd = true; - break; - case CMD_CODE_CYCLE_START: - if (!is_grbl_cmd) - { - cnc_call_rt_command(CMD_CODE_CYCLE_START); - return; - } - break; - } - - if (serial_rx_overflow) - { - c = OVF; - } - write = serial_rx_write; - serial_rx_buffer[write] = c; - if (++write == RX_BUFFER_SIZE) - { - write = 0; - } - if (write == serial_rx_read) - { - serial_rx_overflow++; - } - - serial_rx_write = write; - return; - } - else // extended ascii (plus CMD_CODE_CYCLE_START and DEL) - { - cnc_call_rt_command((uint8_t)c); - } -} - -void serial_rx_clear(void) -{ - serial_rx_write = 0; - serial_rx_read = 0; - serial_rx_overflow = 0; - memset(serial_rx_buffer, 0, RX_BUFFER_SIZE); -} - -uint8_t serial_get_rx_freebytes(void) -{ - uint16_t buf = serial_rx_write; - if (serial_rx_read > buf) - { - buf += RX_BUFFER_SIZE; - } - - return (uint8_t)(RX_BUFFER_CAPACITY - (buf - serial_rx_read)); -} diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index c0529b436..c45478692 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -24,12 +24,13 @@ extern "C" { #endif +#include #include #include #include -#define EOL 0x00 // end of line char -#define OVF 0x15 // overflow char +#define EOL 0x00 // end of line uint8_t +#define OVF 0x15 // overflow uint8_t #define SAFEMARGIN 2 #ifndef RX_BUFFER_CAPACITY #define RX_BUFFER_CAPACITY 128 @@ -40,21 +41,37 @@ extern "C" #define SERIAL_N0 1 #define SERIAL_N1 2 + typedef struct serial_stream_ + { + uint8_t (*stream_getc)(void); + uint8_t (*stream_available)(void); + void (*stream_clear)(void); + void (*stream_putc)(uint8_t); + void (*stream_flush)(void); + struct serial_stream_ *next; + } serial_stream_t; + + #define DECL_SERIAL_STREAM(name, getc_cb, available_cb, clear_cb, putc_cb, flush_cb) serial_stream_t name = {&getc_cb, &available_cb, &clear_cb, &putc_cb, &flush_cb, NULL} + void serial_init(); - bool serial_rx_is_empty(void); - unsigned char serial_getc(void); - void serial_ungetc(void); - unsigned char serial_peek(void); - void serial_inject_cmd(const char *__s); - void serial_rx_clear(void); - void serial_select(uint8_t source); + void serial_stream_register(serial_stream_t *stream); + void serial_stream_change(serial_stream_t *stream); - void serial_putc(unsigned char c); + void serial_broadcast(bool enable); + void serial_putc(uint8_t c); + void serial_flush(void); uint8_t serial_tx_busy(void); + + uint8_t serial_getc(void); + uint8_t serial_peek(void); + uint8_t serial_available(void); + uint8_t serial_freebytes(void); + void serial_clear(void); + // printing utils - typedef void (*print_cb)(unsigned char); - void print_str(print_cb cb, const char *__s); + typedef void (*print_cb)(uint8_t); + void print_str(print_cb cb, const uint8_t *__s); void print_bytes(print_cb cb, const uint8_t *data, uint8_t count); void print_int(print_cb cb, int32_t num); void print_flt(print_cb cb, float num); @@ -70,8 +87,6 @@ extern "C" #define serial_print_intarr(arr, count) print_intarr(serial_putc, arr, count) #define serial_print_fltarr(arr, count) print_fltarr(serial_putc, arr, count) - uint8_t serial_get_rx_freebytes(void); - #ifdef __cplusplus } #endif diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index bf63aca14..a0bdd12e8 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -186,7 +186,7 @@ WEAK_EVENT_HANDLER(settings_erase) void settings_init(void) { - const char version[3] = SETTINGS_VERSION; + const uint8_t version[3] = SETTINGS_VERSION; uint8_t error = settings_load(SETTINGS_ADDRESS_OFFSET, (uint8_t *)&g_settings, (uint8_t)sizeof(settings_t)); if (!error) @@ -598,7 +598,7 @@ bool settings_check_startup_gcode(uint16_t address) #ifndef RAM_ONLY_SETTINGS uint8_t size = (RX_BUFFER_SIZE - 1); // defined in serial.h uint8_t crc = 0; - unsigned char c; + uint8_t c; uint16_t cmd_address = address; // pre-checks command valid crc @@ -630,7 +630,7 @@ void settings_save_startup_gcode(uint16_t address) #ifndef RAM_ONLY_SETTINGS uint8_t size = (RX_BUFFER_SIZE - 1); uint8_t crc = 0; - unsigned char c; + uint8_t c; do { c = serial_getc(); diff --git a/uCNC/src/interface/settings.h b/uCNC/src/interface/settings.h index 6c396048a..b8826f7ad 100644 --- a/uCNC/src/interface/settings.h +++ b/uCNC/src/interface/settings.h @@ -31,7 +31,7 @@ extern "C" typedef struct { - char version[3]; + uint8_t version[3]; float max_step_rate; // step delay not used uint8_t step_invert_mask; diff --git a/uCNC/src/modules/softuart.c b/uCNC/src/modules/softuart.c index a2422a113..f042be786 100644 --- a/uCNC/src/modules/softuart.c +++ b/uCNC/src/modules/softuart.c @@ -50,7 +50,7 @@ void softuart_putc(softuart_port_t *port, uint8_t c) int16_t softuart_getc(softuart_port_t *port, uint32_t ms_timeout) { - unsigned char val = 0; + uint8_t val = 0; if (!port) { diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index a06c6ad8d..d3eddbf21 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -436,7 +436,7 @@ void system_menu_render(void) // renders header if (!item_index) { - char buff[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t buff[SYSTEM_MENU_MAX_STR_LEN]; rom_strcpy(buff, menu_page->page_label); system_menu_render_header(buff); } @@ -469,7 +469,7 @@ void system_menu_render(void) } } -void system_menu_show_modal_popup(uint32_t timeout, const char *__s) +void system_menu_show_modal_popup(uint32_t timeout, const uint8_t *__s) { // prevents redraw g_system_menu.flags &= ~(SYSTEM_MENU_MODE_REDRAW | SYSTEM_MENU_MODE_DELAYED_REDRAW); @@ -647,7 +647,7 @@ bool system_menu_action_rt_cmd(uint8_t action, system_menu_item_t *item) if (action == SYSTEM_MENU_ACTION_SELECT && item) { cnc_call_rt_command((uint8_t)VARG_CONST(item->action_arg)); - char buffer[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; rom_strcpy(buffer, __romstr__(STR_RT_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); return true; @@ -659,10 +659,10 @@ bool system_menu_action_serial_cmd(uint8_t action, system_menu_item_t *item) { if (action == SYSTEM_MENU_ACTION_SELECT && item) { - if (serial_get_rx_freebytes() > 20) + if (serial_freebytes() > 20) { - serial_inject_cmd((const char *)item->action_arg); - char buffer[SYSTEM_MENU_MAX_STR_LEN]; + //serial_inject_cmd((const uint8_t *)item->action_arg); + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; rom_strcpy(buffer, __romstr__(STR_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); } @@ -685,7 +685,7 @@ static bool system_menu_action_overrides(uint8_t action, system_menu_item_t *ite } else if (g_system_menu.flags & SYSTEM_MENU_MODE_SIMPLE_EDIT) { - char override = (char)VARG_CONST(item->action_arg); + uint8_t override = (uint8_t)VARG_CONST(item->action_arg); switch (action) { case SYSTEM_MENU_ACTION_NEXT: @@ -739,17 +739,17 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) else if (g_system_menu.flags & SYSTEM_MENU_MODE_SIMPLE_EDIT) { // one jog command at time - if (serial_get_rx_freebytes() > 32) + if (serial_freebytes() > 32) { - char buffer[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); rom_strcpy(buffer, __romstr__("$J=G91")); - char *ptr = buffer; + uint8_t *ptr = buffer; // search for the end of string while (*++ptr) ; // replaces the axis letter - *ptr++ = *((char *)item->action_arg); + *ptr++ = *((uint8_t *)item->action_arg); switch (action) { case SYSTEM_MENU_ACTION_NEXT: @@ -770,7 +770,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) while (*++ptr) ; *ptr++ = '\r'; - serial_inject_cmd(buffer); + //serial_inject_cmd(buffer); } return true; } @@ -779,7 +779,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) static bool system_menu_action_settings_cmd(uint8_t action, system_menu_item_t *item) { - char buffer[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; if (action == SYSTEM_MENU_ACTION_SELECT) { @@ -1018,7 +1018,7 @@ bool system_menu_action_edit(uint8_t action, system_menu_item_t *item) * These can be overriten by the display to perform the rendering of the menu content * **/ -void __attribute__((weak)) system_menu_render_header(const char *__s) +void __attribute__((weak)) system_menu_render_header(const uint8_t *__s) { // render the menu header } @@ -1077,7 +1077,7 @@ void __attribute__((weak)) system_menu_render_alarm(void) // render alarm screen } -void __attribute__((weak)) system_menu_render_modal_popup(const char *__s) +void __attribute__((weak)) system_menu_render_modal_popup(const uint8_t *__s) { // renders the modal popup message } @@ -1085,12 +1085,12 @@ void __attribute__((weak)) system_menu_render_modal_popup(const char *__s) /** * Helper µCNC render callbacks * **/ -void __attribute__((weak)) system_menu_item_render_label(uint8_t item_index, const char *label) +void __attribute__((weak)) system_menu_item_render_label(uint8_t item_index, const uint8_t *label) { // this is were the display renders the item label } -void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, const char *label) +void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, const uint8_t *label) { // this is were the display renders the item variable } @@ -1098,8 +1098,8 @@ void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, con void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *item) { uint8_t vartype = (uint8_t)VARG_CONST(item->render_arg); - char buffer[SYSTEM_MENU_MAX_STR_LEN]; - char *buff_ptr = buffer; + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t *buff_ptr = buffer; switch (vartype) { case VAR_TYPE_BOOLEAN: @@ -1122,11 +1122,11 @@ void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *i system_menu_flt_to_str(buffer, *((float *)item->argptr)); break; default: - buff_ptr = (char *)item->argptr; + buff_ptr = (uint8_t *)item->argptr; break; } - system_menu_item_render_arg(render_flags, (const char *)buff_ptr); + system_menu_item_render_arg(render_flags, (const uint8_t *)buff_ptr); } static void system_menu_render_axis_position(uint8_t render_flags, system_menu_item_t *item) @@ -1142,12 +1142,12 @@ static void system_menu_render_axis_position(uint8_t render_flags, system_menu_i itp_get_rt_position(steppos); kinematics_steps_to_coordinates(steppos, axis); // X = 0 - char axis_letter = *((char *)item->action_arg); + uint8_t axis_letter = *((uint8_t *)item->action_arg); uint8_t axis_index = (axis_letter >= 'X') ? (axis_letter - 'X') : (3 + axis_letter - 'A'); - char buffer[SYSTEM_MENU_MAX_STR_LEN]; + uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); - char *buff_ptr = buffer; + uint8_t *buff_ptr = buffer; system_menu_flt_to_str(buff_ptr, axis[axis_index]); system_menu_item_render_arg(render_flags, buffer); @@ -1159,13 +1159,13 @@ static void system_menu_render_axis_position(uint8_t render_flags, system_menu_i * Helper µCNC to display variables * **/ -char *system_menu_var_to_str_set_buffer_ptr; -void system_menu_var_to_str_set_buffer(char *ptr) +uint8_t *system_menu_var_to_str_set_buffer_ptr; +void system_menu_var_to_str_set_buffer(uint8_t *ptr) { system_menu_var_to_str_set_buffer_ptr = ptr; } -void system_menu_var_to_str(unsigned char c) +void system_menu_var_to_str(uint8_t c) { *system_menu_var_to_str_set_buffer_ptr = c; *(++system_menu_var_to_str_set_buffer_ptr) = 0; diff --git a/uCNC/src/modules/system_menu.h b/uCNC/src/modules/system_menu.h index c972bddef..3050a5579 100644 --- a/uCNC/src/modules/system_menu.h +++ b/uCNC/src/modules/system_menu.h @@ -96,7 +96,7 @@ extern "C" struct system_menu_item_ { - const char *label; + const uint8_t *label; void *argptr; system_menu_item_render_cb item_render; void *render_arg; @@ -114,7 +114,7 @@ extern "C" { uint8_t menu_id; uint8_t parent_id; - const char *page_label; + const uint8_t *page_label; system_menu_page_render_cb page_render; system_menu_page_action_cb page_action; system_menu_index_t *items_index; @@ -150,7 +150,7 @@ extern "C" #define DECL_MENU_ACTION(menu_id, name, strvalue, action_cb, action_cb_arg) DECL_MENU_ENTRY(menu_id, name, strvalue, NULL, NULL, NULL, action_cb, action_cb_arg) #define DECL_MENU(id, parentid, label) \ - static const char m##id##_label[] __rom__ = label; \ + static const uint8_t m##id##_label[] __rom__ = label; \ static system_menu_page_t m##id = {.menu_id = id, .parent_id = parentid, .page_label = m##id##_label, .page_render = NULL, .page_action = NULL, .items_index = NULL, .extended = NULL}; \ system_menu_append(&m##id) #define DECL_DYNAMIC_MENU(id, parentid, render_cb, action_cb) \ @@ -167,7 +167,7 @@ extern "C" void system_menu_go_idle(void); void system_menu_action(uint8_t action); void system_menu_render(void); - void system_menu_show_modal_popup(uint32_t timeout, const char *__s); + void system_menu_show_modal_popup(uint32_t timeout, const uint8_t *__s); void system_menu_action_timeout(uint32_t delay); void system_menu_append(system_menu_page_t *newpage); @@ -179,7 +179,7 @@ extern "C" /** * Overridable functions to be implemented for the display to render the system menu * **/ - void system_menu_render_header(const char *__s); + void system_menu_render_header(const uint8_t *__s); bool system_menu_render_menu_item_filter(uint8_t item_index); void system_menu_render_menu_item(uint8_t render_flags, const system_menu_item_t *item); void system_menu_render_nav_back(bool is_hover); @@ -187,7 +187,7 @@ extern "C" void system_menu_render_startup(void); void system_menu_render_idle(void); void system_menu_render_alarm(void); - void system_menu_render_modal_popup(const char *__s); + void system_menu_render_modal_popup(const uint8_t *__s); /** * Helper µCNC action callbacks @@ -203,17 +203,17 @@ extern "C" * **/ // these should be implemented on the display side // one to render label and the other to render the label variable argument - void system_menu_item_render_label(uint8_t render_flags, const char *label); - void system_menu_item_render_arg(uint8_t render_flags, const char *label); + void system_menu_item_render_label(uint8_t render_flags, const uint8_t *label); + void system_menu_item_render_arg(uint8_t render_flags, const uint8_t *label); // generic menu item argument renderer void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *item); /** * Helper µCNC to display variables * **/ - extern char *system_menu_var_to_str_set_buffer_ptr; - void system_menu_var_to_str_set_buffer(char *ptr); - void system_menu_var_to_str(unsigned char c); + extern uint8_t *system_menu_var_to_str_set_buffer_ptr; + void system_menu_var_to_str_set_buffer(uint8_t *ptr); + void system_menu_var_to_str(uint8_t c); #define system_menu_int_to_str(buf_ptr, var) \ system_menu_var_to_str_set_buffer(buf_ptr); \ diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index 431d32891..91c571160 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -244,8 +244,8 @@ extern "C" #define BUFFER_READ_AVAILABLE(buffer) (buffer.count) #define BUFFER_EMPTY(buffer) (!buffer.count) #define BUFFER_FULL(buffer) (buffer.count == buffer##_size) -#define BUFFER_PEEK(buffer) (&buffer##_bufferdata[buffer.tail]) -#define BUFFER_PULL(buffer) \ +#define BUFFER_PEEK(buffer) (buffer##_bufferdata[buffer.tail]) +#define BUFFER_REMOVE(buffer) \ { \ uint8_t count, tail; \ __ATOMIC__ \ @@ -263,7 +263,7 @@ extern "C" __ATOMIC__ \ { \ buffer.tail = tail; \ - buffer.count++; \ + buffer.count--; \ } \ } \ p; \ @@ -292,7 +292,7 @@ extern "C" } \ } -#define BUFFER_PUSH(buffer) \ +#define BUFFER_STORE(buffer) \ { \ if (!BUFFER_FULL(buffer)) \ { \ From 4d84242be3389d5facfcdf00d073787e8d8a55a8 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 9 Oct 2023 15:11:57 +0100 Subject: [PATCH 126/168] applied fix #525 --- uCNC/src/interface/protocol.c | 26 +++++++++++--------------- 1 file changed, 11 insertions(+), 15 deletions(-) diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index b2d64df96..f78d66f31 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -362,11 +362,11 @@ void protocol_send_status(void) if (CHECKFLAG(limits, LINACT1_LIMIT_MASK)) { - #if ((AXIS_COUNT == 2) && defined(USE_Y_AS_Z_ALIAS)) +#if ((AXIS_COUNT == 2) && defined(USE_Y_AS_Z_ALIAS)) serial_putc('Z'); - #else +#else serial_putc('Y'); - #endif +#endif } if (CHECKFLAG(limits, LINACT2_LIMIT_MASK)) @@ -720,43 +720,39 @@ void protocol_send_cnc_settings(void) void protocol_send_pins_states(void) { protocol_busy = true; - for (uint8_t i = 0; i < 161; i++) + for (uint8_t i = 0; i < (DIN_PINS_OFFSET + 32); i++) { + i = (i != (DOUT_PINS_OFFSET + 32)) ? i : 100; int16_t val = io_get_pinvalue(i); if (val >= 0) { if (i < 100) { - if (i < 24) + if (i < PWM_PINS_OFFSET) { protocol_send_string(__romstr__("[SO:")); } - else if (i < 40) + else if (i < SERVO_PINS_OFFSET) { protocol_send_string(__romstr__("[P:")); } - else if (i < 46) + else if (i < DOUT_PINS_OFFSET) { protocol_send_string(__romstr__("[SV:")); } - else if (i < 78) + else if (i < (DOUT_PINS_OFFSET + 32)) { protocol_send_string(__romstr__("[O:")); } - - else - { - i = 100; // jumps to inputs - } } if (i >= 100) { - if (i < 114) + if (i < ANALOG_PINS_OFFSET) { protocol_send_string(__romstr__("[SI:")); } - else if (i < 130) + else if (i < DIN_PINS_OFFSET) { protocol_send_string(__romstr__("[A:")); } From d3fc18e3c6a6e867e2e585db69de593460217d4c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 9 Oct 2023 15:38:27 +0100 Subject: [PATCH 127/168] applied fix #527 --- uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h | 4 ++++ uCNC/src/hal/boards/rp2040/rp2040.ini | 1 + uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h | 8 ++++---- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h index b72f87145..8410f1d19 100644 --- a/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h +++ b/uCNC/src/hal/boards/rp2040/boardmap_rpi_pico.h @@ -43,6 +43,10 @@ extern "C" #define LIMIT_Y_BIT 9 #define LIMIT_X_BIT 5 +#define LIMIT_Z_PULLUP +#define LIMIT_Y_PULLUP +#define LIMIT_X_PULLUP + // Setup control input pins // #define ESTOP_BIT 0 // #define ESTOP_PORT A diff --git a/uCNC/src/hal/boards/rp2040/rp2040.ini b/uCNC/src/hal/boards/rp2040/rp2040.ini index edc918de7..290857ba8 100644 --- a/uCNC/src/hal/boards/rp2040/rp2040.ini +++ b/uCNC/src/hal/boards/rp2040/rp2040.ini @@ -16,6 +16,7 @@ board_build.mcu = rp2040 board_build.f_cpu = 133000000L ; lib_deps = adafruit/Adafruit TinyUSB Library@^2.0.3 ; build_flags = -DUSE_TINYUSB +debug_tool = cmsis-dap [env:rpi_pico] extends = common_rp2040 diff --git a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h index a418ea25b..843a3331d 100644 --- a/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h +++ b/uCNC/src/hal/mcus/rp2040/mcumap_rp2040.h @@ -974,7 +974,7 @@ extern "C" #if (defined(DIN7_ISR) && defined(DIN7)) #define DIO89_ISR (DIN7_ISR) #define DIN7_ISRCALLBACK mcu_din_isr -#define DIO89_ISRCALLBACK __indirect__(X, ISRCALLBACK) +#define DIO89_ISRCALLBACK mcu_din_isr #endif #if (defined(TX) && defined(RX)) @@ -1141,10 +1141,10 @@ extern "C" #define mcu_config_input(X) pinMode(__indirect__(X, BIT), INPUT) #define mcu_config_analog(X) mcu_config_input(X) #define mcu_config_pullup(X) pinMode(__indirect__(X, BIT), INPUT_PULLUP) -#define mcu_config_input_isr(X) attachInterrupt(digitalPinToInterrupt(__indirect__(X, BIT)), __indirect__(X, ISRCALLBACK), CHANGE) +#define mcu_config_input_isr(X) attachInterrupt(digitalPinToInterrupt(__indirect__(X, BIT)), mcu_din_isr, CHANGE) -#define mcu_get_input(X) CHECKFLAG(sio_hw->gpio_in, __indirect__(X, BIT)) -#define mcu_get_output(X) CHECKFLAG(sio_hw->gpio_out, __indirect__(X, BIT)) +#define mcu_get_input(X) CHECKBIT(sio_hw->gpio_in, __indirect__(X, BIT)) +#define mcu_get_output(X) CHECKBIT(sio_hw->gpio_out, __indirect__(X, BIT)) #define mcu_set_output(X) ({ sio_hw->gpio_set = (1UL << __indirect__(X, BIT)); }) #define mcu_clear_output(X) ({ sio_hw->gpio_clr = (1UL << __indirect__(X, BIT)); }) #define mcu_toggle_output(X) ({ sio_hw->gpio_togl = (1UL << __indirect__(X, BIT)); }) From 72cc38f96d1d727d18f2e5b8f3208ea79cec2592 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 9 Oct 2023 18:09:51 +0100 Subject: [PATCH 128/168] modify serial to deal with multiple streams --- uCNC/src/core/parser.c | 45 +++++++++++++++++++++++---------- uCNC/src/hal/boards/avr/avr.ini | 2 +- uCNC/src/hal/mcus/mcu.h | 4 +-- uCNC/src/interface/serial.c | 31 +++++++++++++---------- 4 files changed, 52 insertions(+), 30 deletions(-) diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 472b8f191..e679be36d 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -330,7 +330,7 @@ static uint8_t parser_grbl_command(void) do { - c = serial_getc(); + c = serial_peek(); // toupper if (c >= 'a' && c <= 'z') { @@ -339,8 +339,14 @@ static uint8_t parser_grbl_command(void) if (!(c >= 'A' && c <= 'Z')) { + if (c < '0' || c > '9' || grbl_cmd_len) // replaces old ungetc + { + serial_getc(); + } break; } + + serial_getc(); grbl_cmd_str[grbl_cmd_len++] = c; } while ((grbl_cmd_len < GRBL_CMD_MAX_LEN)); @@ -444,23 +450,34 @@ static uint8_t parser_grbl_command(void) return STATUS_INVALID_STATEMENT; } - error = parser_fetch_command(&next_state, &words, &cmd); - if (error) - { - return error; - } - error = parser_validate_command(&next_state, &words, &cmd); + settings_save_startup_gcode(block_address); + // run startup block + if (error) { + // the Gcode is not valid then erase the startup block + mcu_eeprom_putc(block_address, 0); return error; } - // everything ok reverts string and saves it - do - { - //serial_ungetc(); - } while (serial_peek() != '='); - serial_getc(); - settings_save_startup_gcode(block_address); + // error = parser_fetch_command(&next_state, &words, &cmd); + // if (error) + // { + // // the Gcode is not valid then erase the startup block + // mcu_eeprom_putc(block_address, 0); + // return error; + // } + // error = parser_validate_command(&next_state, &words, &cmd); + // if (error) + // { + // return error; + // } + // // everything ok reverts string and saves it + // do + // { + // //serial_ungetc(); + // } while (serial_peek() != '='); + // serial_getc(); + return STATUS_OK; case EOL: return GRBL_SEND_STARTUP_BLOCKS; diff --git a/uCNC/src/hal/boards/avr/avr.ini b/uCNC/src/hal/boards/avr/avr.ini index 4a3496bc2..333e1ba6c 100644 --- a/uCNC/src/hal/boards/avr/avr.ini +++ b/uCNC/src/hal/boards/avr/avr.ini @@ -17,7 +17,7 @@ lib_ignore = EEPROM, SPI, Wire extends = common_avr board = uno ;saves a bit of flash -build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES -D DISABLE_MULTISTRTEAM_SERIAL +build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES -D DISABLE_MULTISTREAM_SERIAL [env:uno] extends = atmega328p diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index fbbb5c223..919d21a3a 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -529,7 +529,7 @@ extern "C" #ifdef MCU_HAS_USB - uint8_t mcu_usb_getc(bool peek); + uint8_t mcu_usb_getc(void); uint8_t mcu_usb_available(void); void mcu_usb_putc(uint8_t c); void mcu_usb_flush(void); @@ -539,7 +539,7 @@ extern "C" #endif #ifdef MCU_HAS_UART - uint8_t mcu_uart_getc(bool peek); + uint8_t mcu_uart_getc(void); uint8_t mcu_uart_available(void); void mcu_uart_clear(void); void mcu_uart_putc(uint8_t c); diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 9b6ed587b..af02efaca 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -111,17 +111,30 @@ void serial_stream_change(serial_stream_t *stream) } uint8_t serial_getc(void) +{ + uint8_t peek = serial_peek(); + serial_peek_buffer = 0; + return peek; +} + +static FORCEINLINE uint8_t _serial_peek(void) { uint8_t peek = serial_peek_buffer; if (peek) { - serial_peek_buffer = 0; return peek; } while (!current_stream->stream_available()) ; peek = current_stream->stream_getc(); + serial_peek_buffer = peek; + return peek; +} + +uint8_t serial_peek(void) +{ + uint8_t peek = _serial_peek(); switch (peek) { case '\n': @@ -134,14 +147,6 @@ uint8_t serial_getc(void) return peek; } -uint8_t serial_peek(void) -{ - uint8_t peek = serial_getc(); - serial_peek_buffer = peek; - - return peek; -} - uint8_t serial_available(void) { return current_stream->stream_available(); @@ -157,12 +162,12 @@ void serial_clear(void) current_stream->stream_clear(); } -#ifndef DISABLE_MULTISTRTEAM_SERIAL +#ifndef DISABLE_MULTISTREAM_SERIAL static bool serial_broadcast_enabled; #endif void serial_broadcast(bool enable) { -#ifndef DISABLE_MULTISTRTEAM_SERIAL +#ifndef DISABLE_MULTISTREAM_SERIAL serial_broadcast_enabled = enable; #endif } @@ -171,7 +176,7 @@ static uint8_t serial_tx_count; void serial_putc(uint8_t c) { serial_tx_count++; -#ifndef DISABLE_MULTISTRTEAM_SERIAL +#ifndef DISABLE_MULTISTREAM_SERIAL if (!serial_broadcast_enabled) { current_stream->stream_putc(c); @@ -201,7 +206,7 @@ void serial_putc(uint8_t c) void serial_flush(void) { -#ifndef DISABLE_MULTISTRTEAM_SERIAL +#ifndef DISABLE_MULTISTREAM_SERIAL if (!serial_broadcast_enabled) { current_stream->stream_flush(); From 3494d04eae2b54b0885f85399fd27719d821cead Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 9 Oct 2023 23:07:47 +0100 Subject: [PATCH 129/168] Update system_menu.c --- uCNC/src/modules/system_menu.c | 192 ++++++++++++++++----------------- 1 file changed, 96 insertions(+), 96 deletions(-) diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index d3eddbf21..9dc7a5900 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -86,169 +86,169 @@ DECL_MODULE(system_menu) DECL_MENU(1, 0, STR_MAIN_MENU); // main menu entries - DECL_MENU_ACTION(1, hold, STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); - DECL_MENU_ACTION(1, resume, STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); - DECL_MENU_ACTION(1, unlock, STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); - DECL_MENU_ACTION(1, home, STR_HOME, system_menu_action_serial_cmd, "$H\r"); - DECL_MENU_GOTO(1, jog, STR_JOG, CONST_VARG(7)); - DECL_MENU_GOTO(1, overrides, STR_OVERRIDES, CONST_VARG(8)); - DECL_MENU_GOTO(1, settings, STR_SETTINGS, CONST_VARG(2)); + DECL_MENU_ACTION(1, hold, (uint8_t*)STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); + DECL_MENU_ACTION(1, resume, (uint8_t*)STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); + DECL_MENU_ACTION(1, unlock, (uint8_t*)STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); + DECL_MENU_ACTION(1, home, (uint8_t*)STR_HOME, system_menu_action_serial_cmd, "$H\r"); + DECL_MENU_GOTO(1, jog, (uint8_t*)STR_JOG, CONST_VARG(7)); + DECL_MENU_GOTO(1, overrides, (uint8_t*)STR_OVERRIDES, CONST_VARG(8)); + DECL_MENU_GOTO(1, settings, (uint8_t*)STR_SETTINGS, CONST_VARG(2)); DECL_MENU(8, 1, STR_OVERRIDES); - DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); - DECL_MENU_ACTION(8, ovf_100, STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, (uint8_t*)STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); + DECL_MENU_ACTION(8, ovf_100, (uint8_t*)STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); #if (TOOL_COUNT > 0) - DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, (uint8_t*)STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); #endif - DECL_MENU_ACTION(8, ovt_100, STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); + DECL_MENU_ACTION(8, ovt_100, (uint8_t*)STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); // append Jog menu // default initial distance DECL_MENU(7, 1, STR_JOG); - DECL_MENU_ENTRY(7, jogx, STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); + DECL_MENU_ENTRY(7, jogx, (uint8_t*)STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); #if (AXIS_COUNT > 1) - DECL_MENU_ENTRY(7, jogy, STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); + DECL_MENU_ENTRY(7, jogy, (uint8_t*)STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); #endif #if (AXIS_COUNT > 2) - DECL_MENU_ENTRY(7, jogz, STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); + DECL_MENU_ENTRY(7, jogz, (uint8_t*)STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); #endif #if (AXIS_COUNT > 3) - DECL_MENU_ENTRY(7, joga, STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); + DECL_MENU_ENTRY(7, joga, (uint8_t*)STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); #endif #if (AXIS_COUNT > 4) - DECL_MENU_ENTRY(7, jogb, STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); + DECL_MENU_ENTRY(7, jogb, (uint8_t*)STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); #endif #if (AXIS_COUNT > 5) - DECL_MENU_ENTRY(7, jogc, STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); + DECL_MENU_ENTRY(7, jogc, (uint8_t*)STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); #endif - DECL_MENU_VAR(7, jogdist, STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); - DECL_MENU_VAR(7, jogfeed, STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogdist, (uint8_t*)STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogfeed, (uint8_t*)STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); // append settings menu DECL_MENU(2, 1, STR_SETTINGS); // settings menu - DECL_MENU_GOTO(2, ioconfig, STR_IO_CONFIG, CONST_VARG(6)); - DECL_MENU_GOTO(2, gohome, STR_HOMING, CONST_VARG(3)); + DECL_MENU_GOTO(2, ioconfig, (uint8_t*)STR_IO_CONFIG, CONST_VARG(6)); + DECL_MENU_GOTO(2, gohome, (uint8_t*)STR_HOMING, CONST_VARG(3)); #if (AXIS_COUNT > 0) - DECL_MENU_GOTO(2, goaxis, STR_AXIS, CONST_VARG(4)); + DECL_MENU_GOTO(2, goaxis, (uint8_t*)STR_AXIS, CONST_VARG(4)); #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU_GOTO(2, kinemats, STR_KINEMATICS, CONST_VARG(5)); + DECL_MENU_GOTO(2, kinemats, (uint8_t*)STR_KINEMATICS, CONST_VARG(5)); #endif - DECL_MENU_GOTO(2, other_config, STR_OTHER, CONST_VARG(9)); - DECL_MENU_ACTION(2, set_load, STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); - DECL_MENU_ACTION(2, set_save, STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); - DECL_MENU_ACTION(2, set_reset, STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); + DECL_MENU_GOTO(2, other_config, (uint8_t*)STR_OTHER, CONST_VARG(9)); + DECL_MENU_ACTION(2, set_load, (uint8_t*)STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); + DECL_MENU_ACTION(2, set_save, (uint8_t*)STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); + DECL_MENU_ACTION(2, set_reset, (uint8_t*)STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); DECL_MENU(9, 2, STR_OTHER); - DECL_MENU_VAR(9, s11, STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(9, s12, STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s11, (uint8_t*)STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s12, (uint8_t*)STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); DECL_MENU(6, 2, STR_IO_CONFIG); - DECL_MENU_VAR(6, s2, STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s3, STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s4, STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s5, STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s6, STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(6, s7, STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s2, (uint8_t*)STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s3, (uint8_t*)STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s4, (uint8_t*)STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s5, (uint8_t*)STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s6, (uint8_t*)STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(6, s7, (uint8_t*)STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); #if ENCODERS > 0 - DECL_MENU_VAR(6, s8, STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s9, STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s8, (uint8_t*)STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s9, (uint8_t*)STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); #endif // append homing settings menu DECL_MENU(3, 2, STR_HOMING); - DECL_MENU_VAR(3, s20, STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s21, STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s22, STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s23, STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s24, STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s25, STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s26, STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s27, STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s20, (uint8_t*)STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s21, (uint8_t*)STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s22, (uint8_t*)STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s23, (uint8_t*)STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s24, (uint8_t*)STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s25, (uint8_t*)STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s26, (uint8_t*)STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s27, (uint8_t*)STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); #if (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, (uint8_t*)STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_SCARA) - DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s29, STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, (uint8_t*)STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s29, (uint8_t*)STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); #endif // append steppers settings menu DECL_MENU(4, 2, STR_AXIS); - DECL_MENU_VAR(4, s100, STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s110, STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s120, STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s130, STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s100, (uint8_t*)STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s110, (uint8_t*)STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s120, (uint8_t*)STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s130, (uint8_t*)STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s140, STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s140, (uint8_t*)STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); #endif #if (AXIS_COUNT > 1) - DECL_MENU_VAR(4, s101, STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s111, STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s121, STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s131, STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s101, (uint8_t*)STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s111, (uint8_t*)STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s121, (uint8_t*)STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s131, (uint8_t*)STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s141, STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s141, (uint8_t*)STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 2) - DECL_MENU_VAR(4, s102, STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s112, STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s122, STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s132, STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s102, (uint8_t*)STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s112, (uint8_t*)STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s122, (uint8_t*)STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s132, (uint8_t*)STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s142, STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s142, (uint8_t*)STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 3) - DECL_MENU_VAR(4, s103, STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s113, STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s123, STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s133, STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s103, (uint8_t*)STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s113, (uint8_t*)STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s123, (uint8_t*)STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s133, (uint8_t*)STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s143, STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s143, (uint8_t*)STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 4) - DECL_MENU_VAR(4, s104, STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s114, STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s124, STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s134, STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s104, (uint8_t*)STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s114, (uint8_t*)STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s124, (uint8_t*)STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s134, (uint8_t*)STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s144, STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s144, (uint8_t*)STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 5) - DECL_MENU_VAR(4, s105, STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s115, STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s125, STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s135, STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s105, (uint8_t*)STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s115, (uint8_t*)STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s125, (uint8_t*)STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s135, (uint8_t*)STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMENSATION - DECL_MENU_VAR(4, s145, STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s145, (uint8_t*)STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); #endif #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU(5, 2, STR_KINEMATICS); + DECL_MENU(5, 2, (uint8_t*)STR_KINEMATICS); #ifdef ENABLE_SKEW_COMPENSATION - DECL_MENU_VAR(5, s37, STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s37, (uint8_t*)STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); #ifndef SKEW_COMPENSATION_XY_ONLY - DECL_MENU_VAR(5, s38, STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s39, STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s38, (uint8_t*)STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s39, (uint8_t*)STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); #endif #endif #if (KINEMATIC == KINEMATIC_LINEAR_DELTA) - DECL_MENU_VAR(5, s106, STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, (uint8_t*)STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, (uint8_t*)STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(5, s106, STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s108, STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s109, STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s28, STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, (uint8_t*)STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, (uint8_t*)STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s108, (uint8_t*)STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s109, (uint8_t*)STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s28, (uint8_t*)STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #endif #endif @@ -437,7 +437,7 @@ void system_menu_render(void) if (!item_index) { uint8_t buff[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy(buff, menu_page->page_label); + rom_strcpy((char*)buff, (const char*)menu_page->page_label); system_menu_render_header(buff); } @@ -648,7 +648,7 @@ bool system_menu_action_rt_cmd(uint8_t action, system_menu_item_t *item) { cnc_call_rt_command((uint8_t)VARG_CONST(item->action_arg)); uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy(buffer, __romstr__(STR_RT_CMD_SENT)); + rom_strcpy((char*)buffer, __romstr__(STR_RT_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); return true; } @@ -663,7 +663,7 @@ bool system_menu_action_serial_cmd(uint8_t action, system_menu_item_t *item) { //serial_inject_cmd((const uint8_t *)item->action_arg); uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy(buffer, __romstr__(STR_CMD_SENT)); + rom_strcpy((char*)buffer, __romstr__(STR_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); } return true; @@ -743,7 +743,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) { uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); - rom_strcpy(buffer, __romstr__("$J=G91")); + rom_strcpy((char*)buffer, __romstr__("$J=G91")); uint8_t *ptr = buffer; // search for the end of string while (*++ptr) @@ -788,15 +788,15 @@ static bool system_menu_action_settings_cmd(uint8_t action, system_menu_item_t * { case 0: settings_init(); - rom_strcpy(buffer, __romstr__(STR_SETTINGS_LOADED)); + rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_LOADED)); break; case 1: settings_save(SETTINGS_ADDRESS_OFFSET, (uint8_t *)&g_settings, (uint8_t)sizeof(settings_t)); - rom_strcpy(buffer, __romstr__(STR_SETTINGS_SAVED)); + rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_SAVED)); break; case 2: settings_reset(false); - rom_strcpy(buffer, __romstr__(STR_SETTINGS_RESET)); + rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_RESET)); break; default: break; From 6fb119ba0dc69f589b6698504fd29396b6c80e07 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 10:58:08 +0100 Subject: [PATCH 130/168] improved code for simple stream (UNO) --- uCNC/src/cnc.c | 12 +++-- uCNC/src/core/parser.c | 39 ++++++-------- uCNC/src/hal/mcus/mcu.h | 16 ++++++ uCNC/src/hal/mcus/virtual/mcu_virtual.c | 52 +++++++++--------- uCNC/src/interface/protocol.c | 4 +- uCNC/src/interface/protocol.h | 4 +- uCNC/src/interface/serial.c | 70 ++++++++++++++++++++++--- uCNC/src/interface/serial.h | 3 +- 8 files changed, 132 insertions(+), 68 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 8e01fb91a..d508649ea 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -1029,9 +1029,11 @@ static void cnc_io_dotasks(void) void cnc_run_startup_blocks(void) { - // serial_select(SERIAL_N0); - // cnc_exec_cmd(); - // serial_select(SERIAL_N1); - // cnc_exec_cmd(); - // serial_select(SERIAL_UART); + serial_broadcast(true); + serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); + cnc_exec_cmd(); + serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); + cnc_exec_cmd(); + serial_broadcast(false); + serial_stream_change(NULL); } diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index e679be36d..2dd8c4151 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -345,7 +345,7 @@ static uint8_t parser_grbl_command(void) } break; } - + serial_getc(); grbl_cmd_str[grbl_cmd_len++] = c; } while ((grbl_cmd_len < GRBL_CMD_MAX_LEN)); @@ -383,7 +383,7 @@ static uint8_t parser_grbl_command(void) { float val = 0; setting_offset_t setting_num = 0; - //serial_ungetc(); + // serial_ungetc(); error = parser_get_float(&val); if (!error) { @@ -452,33 +452,24 @@ static uint8_t parser_grbl_command(void) settings_save_startup_gcode(block_address); // run startup block + serial_broadcast(true); + serial_stream_eeprom(block_address); + error = parser_fetch_command(&next_state, &words, &cmd); + if (error == STATUS_OK) + { + error = parser_validate_command(&next_state, &words, &cmd); + } - if (error) + serial_broadcast(false); + serial_stream_change(NULL); + + if (error != STATUS_OK) { // the Gcode is not valid then erase the startup block mcu_eeprom_putc(block_address, 0); - return error; } - // error = parser_fetch_command(&next_state, &words, &cmd); - // if (error) - // { - // // the Gcode is not valid then erase the startup block - // mcu_eeprom_putc(block_address, 0); - // return error; - // } - // error = parser_validate_command(&next_state, &words, &cmd); - // if (error) - // { - // return error; - // } - // // everything ok reverts string and saves it - // do - // { - // //serial_ungetc(); - // } while (serial_peek() != '='); - // serial_getc(); - - return STATUS_OK; + + return error; case EOL: return GRBL_SEND_STARTUP_BLOCKS; } diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index 919d21a3a..0671cccb8 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -578,6 +578,22 @@ extern "C" #endif #endif +#ifndef mcu_getc +#define mcu_getc (&mcu_uart_getc) +#endif +#ifndef mcu_available +#define mcu_available (&mcu_uart_available) +#endif +#ifndef mcu_clear +#define mcu_clear (&mcu_uart_clear) +#endif +#ifndef mcu_putc +#define mcu_putc (&mcu_uart_putc) +#endif +#ifndef mcu_flush +#define mcu_flush (&mcu_uart_flush) +#endif + #ifdef __cplusplus } #endif diff --git a/uCNC/src/hal/mcus/virtual/mcu_virtual.c b/uCNC/src/hal/mcus/virtual/mcu_virtual.c index 45ab0f46f..ce96478a3 100644 --- a/uCNC/src/hal/mcus/virtual/mcu_virtual.c +++ b/uCNC/src/hal/mcus/virtual/mcu_virtual.c @@ -1515,32 +1515,32 @@ void mcu_uart_flush(void) // mcu_tx_enabled = true; // } -uint8_t mcu_getc(void) -{ - uint8_t c = 0; - if (g_mcu_buffertail != g_mcu_bufferhead) - { - c = g_mcu_combuffer[g_mcu_buffertail]; - if (++g_mcu_buffertail == COM_BUFFER_SIZE) - { - g_mcu_buffertail = 0; - } - - if (c == '\n') - { - g_mcu_buffercount--; - } - } - - return c; -} - -uint8_t mcu_peek(void) -{ - if (g_mcu_buffercount == 0) - return 0; - return g_mcu_combuffer[g_mcu_buffertail]; -} +//uint8_t mcu_getc(void) +//{ +// uint8_t c = 0; +// if (g_mcu_buffertail != g_mcu_bufferhead) +// { +// c = g_mcu_combuffer[g_mcu_buffertail]; +// if (++g_mcu_buffertail == COM_BUFFER_SIZE) +// { +// g_mcu_buffertail = 0; +// } +// +// if (c == '\n') +// { +// g_mcu_buffercount--; +// } +// } +// +// return c; +//} +// +//uint8_t mcu_peek(void) +//{ +// if (g_mcu_buffercount == 0) +// return 0; +// return g_mcu_combuffer[g_mcu_buffertail]; +//} void mcu_bufferClear(void) { diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 181f86c51..27a4f8208 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -70,7 +70,7 @@ void protocol_send_alarm(int8_t alarm) protocol_send_newline(); } -void protocol_send_string(const uint8_t *__s) +void protocol_send_string(const char *__s) { uint8_t c = (uint8_t)rom_strptr(__s++); do @@ -80,7 +80,7 @@ void protocol_send_string(const uint8_t *__s) } while (c != 0); } -void protocol_send_feedback(const uint8_t *__s) +void protocol_send_feedback(const char *__s) { protocol_send_string(MSG_START); protocol_send_string(__s); diff --git a/uCNC/src/interface/protocol.h b/uCNC/src/interface/protocol.h index 158f18eb8..7230dd837 100644 --- a/uCNC/src/interface/protocol.h +++ b/uCNC/src/interface/protocol.h @@ -33,8 +33,8 @@ extern "C" void protocol_send_alarm(int8_t alarm); void protocol_send_status(void); DECL_EVENT_HANDLER(protocol_send_status); - void protocol_send_string(const uint8_t *__s); - void protocol_send_feedback(const uint8_t *__s); + void protocol_send_string(const char *__s); + void protocol_send_feedback(const char *__s); void protocol_send_probe_result(uint8_t val); void protocol_send_gcode_coordsys(void); void protocol_send_gcode_modes(void); diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index af02efaca..002caffde 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -30,6 +30,11 @@ #include #include "../cnc.h" +static uint8_t (*stream_getc)(void); +uint8_t (*stream_available)(void); +void (*stream_clear)(void); + +#ifndef DISABLE_MULTISTREAM_SERIAL static serial_stream_t *serial_stream; static serial_stream_t *current_stream; @@ -48,13 +53,21 @@ DECL_SERIAL_STREAM(wifi_serial_stream, mcu_wifi_getc, mcu_wifi_available, mcu_wi #if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) DECL_SERIAL_STREAM(bt_serial_stream, mcu_bt_getc, mcu_bt_available, mcu_bt_clear, mcu_bt_putc, mcu_bt_flush); #endif +#else +// if not multistreaming +void (*stream_putc)(uint8_t); +void (*stream_flush)(void); + +#endif + +static uint8_t serial_peek_buffer; void serial_init(void) { #ifdef FORCE_GLOBALS_TO_0 serial_stream = NULL; #endif - +#ifndef DISABLE_MULTISTREAM_SERIAL #if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) serial_stream_register(&uart_serial_stream); #endif @@ -70,9 +83,13 @@ void serial_init(void) #if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) serial_stream_register(&bt_serial_stream); #endif - current_stream = serial_stream; +current_stream = serial_stream; +#else +serial_stream_change(NULL); +#endif } +#ifndef DISABLE_MULTISTREAM_SERIAL void serial_stream_register(serial_stream_t *stream) { if (serial_stream == NULL) @@ -92,9 +109,19 @@ void serial_stream_register(serial_stream_t *stream) } } -static uint8_t serial_peek_buffer; +// on cleanup sets the correct stdin streams +void stream_stdin(uint8_t *p) +{ + stream_getc = current_stream->stream_getc; + stream_available = current_stream->stream_available; + stream_clear = current_stream->stream_clear; +} +#endif + void serial_stream_change(serial_stream_t *stream) { +#ifndef DISABLE_MULTISTREAM_SERIAL + uint8_t cleanup __attribute__((__cleanup__(stream_stdin))) = 0; serial_peek_buffer = 0; if (stream != NULL) { @@ -108,6 +135,24 @@ void serial_stream_change(serial_stream_t *stream) { current_stream = serial_stream; } +#else + stream_getc = mcu_getc; + stream_available = mcu_available; + stream_clear = mcu_clear; +#endif +} + +static uint16_t stream_eeprom_address; +static uint8_t stream_eeprom_getc(void) +{ + return mcu_eeprom_getc(stream_eeprom_address++); +} + +void serial_stream_eeprom(uint16_t address) +{ + stream_eeprom_address = address; + stream_getc = &stream_eeprom_getc; + stream_available = NULL; } uint8_t serial_getc(void) @@ -125,9 +170,9 @@ static FORCEINLINE uint8_t _serial_peek(void) return peek; } - while (!current_stream->stream_available()) + while (!serial_available()) ; - peek = current_stream->stream_getc(); + peek = stream_getc(); serial_peek_buffer = peek; return peek; } @@ -149,7 +194,12 @@ uint8_t serial_peek(void) uint8_t serial_available(void) { - return current_stream->stream_available(); + if (!stream_available) + { + // if undef allow to continue + return 1; + } + return stream_available(); } uint8_t serial_freebytes(void) @@ -159,7 +209,11 @@ uint8_t serial_freebytes(void) void serial_clear(void) { +#ifndef DISABLE_MULTISTREAM_SERIAL current_stream->stream_clear(); +#else + mcu_clear(); +#endif } #ifndef DISABLE_MULTISTREAM_SERIAL @@ -191,7 +245,7 @@ void serial_putc(uint8_t c) } } #else - serial_stream->stream_putc(c); + mcu_putc(c); #endif if (c == '\n') @@ -221,7 +275,7 @@ void serial_flush(void) } } #else - serial_stream->stream_flush(); + mcu_flush(); #endif } diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index c45478692..1314cd3be 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -57,6 +57,7 @@ extern "C" void serial_stream_register(serial_stream_t *stream); void serial_stream_change(serial_stream_t *stream); + void serial_stream_eeprom(uint16_t address); void serial_broadcast(bool enable); void serial_putc(uint8_t c); @@ -66,8 +67,8 @@ extern "C" uint8_t serial_getc(void); uint8_t serial_peek(void); uint8_t serial_available(void); - uint8_t serial_freebytes(void); void serial_clear(void); + uint8_t serial_freebytes(void); // printing utils typedef void (*print_cb)(uint8_t); From 44797bda2f1fe488b1ed0d9a327e2cd8ae9c71b8 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 12:10:13 +0100 Subject: [PATCH 131/168] fixed null char reading from eeprom --- makefiles/virtual/uCNC.dev | 2 +- uCNC/src/cnc.c | 14 ++++++++++---- uCNC/src/core/parser.c | 6 +++--- uCNC/src/interface/serial.c | 4 ++++ uCNC/src/interface/settings.c | 16 +++++++++++----- 5 files changed, 29 insertions(+), 13 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 526cbcf62..72bcd7b76 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -9,7 +9,7 @@ Libs= PrivateResource= ResourceIncludes= MakeIncludes= -Compiler=-DWIN_INTERFACE=2 -DENABLE_EXTRA_SYSTEM_CMDS -DWIN_COM_NAME=COM11 -DBOARD=BOARD_VIRTUAL -DMCU=MCU_VIRTUAL_WIN_@@_ +Compiler=-DWIN_INTERFACE=2 -DENABLE_EXTRA_SYSTEM_CMDS -DWIN_COM_NAME=COM11 -DBOARD=BOARD_VIRTUAL -DMCU=MCU_VIRTUAL -DDISABLE_MULTISTREAM_SERIAL_@@_ CppCompiler=_@@_ Linker=-lws2_32_@@_ IsCpp=0 diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index d508649ea..6c115064a 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -1030,10 +1030,16 @@ static void cnc_io_dotasks(void) void cnc_run_startup_blocks(void) { serial_broadcast(true); - serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); - cnc_exec_cmd(); - serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); - cnc_exec_cmd(); + if (settings_check_startup_gcode(STARTUP_BLOCK0_ADDRESS_OFFSET)) + { + serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); + cnc_exec_cmd(); + } + if (settings_check_startup_gcode(STARTUP_BLOCK1_ADDRESS_OFFSET)) + { + serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); + cnc_exec_cmd(); + } serial_broadcast(false); serial_stream_change(NULL); } diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 2dd8c4151..6df0bfa48 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -669,8 +669,7 @@ static uint8_t parser_fetch_command(parser_state_t *new_state, parser_words_t *w { uint8_t word = 0; float value = 0; - // this flushes leading white chars and also takes care of processing comments - parser_get_next_preprocessed(true); + #ifdef ECHO_CMD if (!wordcount) { @@ -2021,7 +2020,8 @@ static void parser_get_comment(uint8_t start_char) static uint8_t parser_get_token(uint8_t *word, float *value) { - uint8_t c = serial_getc(); + // this flushes leading white chars and also takes care of processing comments + uint8_t c = parser_get_next_preprocessed(false); // if other uint8_t starts tokenization if (c >= 'a' && c <= 'z') diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 002caffde..06a254d8b 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -173,6 +173,10 @@ static FORCEINLINE uint8_t _serial_peek(void) while (!serial_available()) ; peek = stream_getc(); + // prevents null char reading from eeprom + if(!peek) { + peek = '\n'; + } serial_peek_buffer = peek; return peek; } diff --git a/uCNC/src/interface/settings.c b/uCNC/src/interface/settings.c index a0bdd12e8..f993209bf 100644 --- a/uCNC/src/interface/settings.c +++ b/uCNC/src/interface/settings.c @@ -305,7 +305,7 @@ bool settings_allows_negative(setting_offset_t id) } #endif #ifdef ENABLE_SKEW_COMPENSATION - if (id >=37 && id <= 39) + if (id >= 37 && id <= 39) { return true; } @@ -595,6 +595,9 @@ void settings_erase(uint16_t address, uint8_t size) bool settings_check_startup_gcode(uint16_t address) { + serial_putc('>'); + serial_putc(':'); + #ifndef RAM_ONLY_SETTINGS uint8_t size = (RX_BUFFER_SIZE - 1); // defined in serial.h uint8_t crc = 0; @@ -615,14 +618,16 @@ bool settings_check_startup_gcode(uint16_t address) if (crc ^ mcu_eeprom_getc(cmd_address)) { - serial_putc('>'); - serial_putc(':'); protocol_send_error(STATUS_SETTING_READ_FAIL); settings_erase(address, 1); return false; } -#endif + return true; +#else + protocol_send_ok(); + return false; +#endif } void settings_save_startup_gcode(uint16_t address) @@ -635,7 +640,8 @@ void settings_save_startup_gcode(uint16_t address) { c = serial_getc(); crc = crc7(c, crc); - mcu_eeprom_putc(address++, (uint8_t)c); + mcu_eeprom_putc(address, (uint8_t)c); + address++; size--; } while (size && c); From b509e556f9df210c44c1ef555e5d5c21ce08f954 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 15:00:44 +0100 Subject: [PATCH 132/168] updated ESP32 --- uCNC/src/hal/mcus/avr/mcu_avr.c | 34 +++- uCNC/src/hal/mcus/esp32/esp32_arduino.cpp | 180 ++++++++++++++-------- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 78 ++++++++-- uCNC/src/hal/mcus/mcu.h | 7 +- 4 files changed, 222 insertions(+), 77 deletions(-) diff --git a/uCNC/src/hal/mcus/avr/mcu_avr.c b/uCNC/src/hal/mcus/avr/mcu_avr.c index bc82979bc..2dc3f534e 100644 --- a/uCNC/src/hal/mcus/avr/mcu_avr.c +++ b/uCNC/src/hal/mcus/avr/mcu_avr.c @@ -377,7 +377,7 @@ ISR(COM_RX_vect, ISR_BLOCK) { #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) uint8_t c = COM_INREG; - if (mcu_com_rx_cb(COM_INREG)) + if (mcu_com_rx_cb(c)) { if (BUFFER_FULL(uart_rx)) { @@ -411,12 +411,23 @@ ISR(COM_TX_vect, ISR_BLOCK) #endif #if defined(MCU_HAS_UART2) +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); ISR(COM2_RX_vect, ISR_BLOCK) { #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(COM2_INREG); + uint8_t c = COM2_INREG; + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } #else - mcu_uart2_rx_cb(COM2_INREG); + mcu_uart_rx_cb(COM2_INREG); #endif } @@ -621,6 +632,23 @@ void mcu_uart_flush(void) #endif #ifdef MCU_HAS_UART2 +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} + void mcu_uart2_putc(uint8_t c) { while (BUFFER_FULL(uart2)) diff --git a/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp b/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp index f1065072b..bdf87ff1b 100644 --- a/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp +++ b/uCNC/src/hal/mcus/esp32/esp32_arduino.cpp @@ -62,9 +62,9 @@ uint16_t bt_settings_offset; WebServer httpServer(80); HTTPUpdateServer httpUpdater; -const uint8_t *update_path = "/firmware"; -const uint8_t *update_username = WIFI_USER; -const uint8_t *update_password = WIFI_PASS; +const char *update_path = "/firmware"; +const char *update_username = WIFI_USER; +const char *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -108,9 +108,9 @@ extern "C" } #ifdef ENABLE_BLUETOOTH - if (!strncmp(grbl_cmd_str, "BTH", 3)) + if (!strncmp((const char*)grbl_cmd_str, "BTH", 3)) { - if (!strcmp(&grbl_cmd_str[3], "ON")) + if (!strcmp((const char*)&grbl_cmd_str[3], "ON")) { SerialBT.begin(BOARD_NAME); protocol_send_feedback("Bluetooth enabled"); @@ -120,7 +120,7 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[3], "OFF")) + if (!strcmp((const char*)&grbl_cmd_str[3], "OFF")) { SerialBT.end(); protocol_send_feedback("Bluetooth disabled"); @@ -132,35 +132,35 @@ extern "C" } #endif #ifdef ENABLE_WIFI - if (!strncmp(grbl_cmd_str, "WIFI", 4)) + if (!strncmp((const char*)grbl_cmd_str, "WIFI", 4)) { - if (!strcmp(&grbl_cmd_str[4], "ON")) + if (!strcmp((const char*)&grbl_cmd_str[4], "ON")) { WiFi.disconnect(); switch (wifi_settings.wifi_mode) { case 1: WiFi.mode(WIFI_STA); - WiFi.begin(wifi_settings.ssid, wifi_settings.pass); + WiFi.begin((char*)wifi_settings.ssid, (char*)wifi_settings.pass); protocol_send_feedback("Trying to connect to WiFi"); break; case 2: WiFi.mode(WIFI_AP); - WiFi.softAP(BOARD_NAME, wifi_settings.pass); + WiFi.softAP(BOARD_NAME, (char*)wifi_settings.pass); protocol_send_feedback("AP started"); protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; default: WiFi.mode(WIFI_AP_STA); - WiFi.begin(wifi_settings.ssid, wifi_settings.pass); + WiFi.begin((char*)wifi_settings.ssid, (char*)wifi_settings.pass); protocol_send_feedback("Trying to connect to WiFi"); - WiFi.softAP(BOARD_NAME, wifi_settings.pass); + WiFi.softAP(BOARD_NAME, (char*)wifi_settings.pass); protocol_send_feedback("AP started"); protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; } @@ -169,7 +169,7 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "OFF")) + if (!strcmp((const char*)&grbl_cmd_str[4], "OFF")) { WiFi.disconnect(); wifi_settings.wifi_on = 0; @@ -177,29 +177,29 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SSID")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SSID")) { if (has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char*)arg); if (len > WIFI_SSID_MAX_LEN) { protocol_send_feedback("WiFi SSID is too long"); } memset(wifi_settings.ssid, 0, sizeof(wifi_settings.ssid)); - strcpy(wifi_settings.ssid, arg); + strcpy((char*)wifi_settings.ssid, (const char*)arg); settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); protocol_send_feedback("WiFi SSID modified"); } else { - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char*)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SCAN")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SCAN")) { // Serial.println("[MSG:Scanning Networks]"); protocol_send_feedback("Scanning Networks"); @@ -212,26 +212,26 @@ extern "C" } // print the list of networks seen: - sprintf(str, "%d available networks", numSsid); - protocol_send_feedback(str); + sprintf((char*)str, "%d available networks", numSsid); + protocol_send_feedback((const char*)str); // print the network number and name for each network found: for (int netid = 0; netid < numSsid; netid++) { - sprintf(str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid).c_str(), WiFi.RSSI(netid)); - protocol_send_feedback(str); + sprintf((char*)str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid).c_str(), WiFi.RSSI(netid)); + protocol_send_feedback((const char*)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SAVE")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SAVE")) { settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); protocol_send_feedback("WiFi settings saved"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "RESET")) + if (!strcmp((const char*)&grbl_cmd_str[4], "RESET")) { settings_erase(wifi_settings_offset, sizeof(wifi_settings_t)); memset(&wifi_settings, 0, sizeof(wifi_settings_t)); @@ -239,11 +239,11 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "MODE")) + if (!strcmp((const char*)&grbl_cmd_str[4], "MODE")) { if (has_arg) { - int mode = atoi(arg) - 1; + int mode = atoi((const char*)arg) - 1; if (mode >= 0) { wifi_settings.wifi_mode = mode; @@ -269,38 +269,38 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "PASS") && has_arg) + if (!strcmp((const char*)&grbl_cmd_str[4], "PASS") && has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char*)arg); if (len > WIFI_SSID_MAX_LEN) { protocol_send_feedback("WiFi pass is too long"); } memset(wifi_settings.pass, 0, sizeof(wifi_settings.pass)); - strcpy(wifi_settings.pass, arg); + strcpy((char*)wifi_settings.pass, (const char*)arg); protocol_send_feedback("WiFi password modified"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "IP")) + if (!strcmp((const char*)&grbl_cmd_str[4], "IP")) { if (wifi_settings.wifi_on) { switch (wifi_settings.wifi_mode) { case 1: - sprintf(str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); - sprintf(str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); + sprintf((char*)str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; case 2: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; default: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; } } @@ -345,10 +345,10 @@ extern "C" { connected = true; protocol_send_feedback("Connected to WiFi"); - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); - sprintf(str, "IP>%s", WiFi.localIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char*)str); + sprintf((char*)str, "IP>%s", WiFi.localIP().toString().c_str()); + protocol_send_feedback((const char*)str); } if (server.hasClient()) @@ -417,33 +417,52 @@ extern "C" #ifndef WIFI_TX_BUFFER_SIZE #define WIFI_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, wifi, WIFI_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, wifi_rx, RX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, wifi_tx, WIFI_TX_BUFFER_SIZE); + + uint8_t mcu_wifi_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(wifi_rx, &c); + return c; + } + + uint8_t mcu_wifi_available(void) + { + return BUFFER_READ_AVAILABLE(wifi_rx); + } + + void mcu_wifi_clear(void) + { + BUFFER_CLEAR(wifi_rx); + } + void mcu_wifi_putc(uint8_t c) { - while (BUFFER_FULL(wifi)) + while (BUFFER_FULL(wifi_tx)) { mcu_wifi_flush(); } - BUFFER_ENQUEUE(wifi, &c); + BUFFER_ENQUEUE(wifi_tx, &c); } void mcu_wifi_flush(void) { if (esp32_wifi_clientok()) { - while (!BUFFER_EMPTY(wifi)) + while (!BUFFER_EMPTY(wifi_tx)) { uint8_t tmp[WIFI_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(wifi, tmp, WIFI_TX_BUFFER_SIZE, r); + BUFFER_READ(wifi_tx, tmp, WIFI_TX_BUFFER_SIZE, r); serverClient.write(tmp, r); } } else { // no client (discard) - BUFFER_CLEAR(wifi); + BUFFER_CLEAR(wifi_tx); } } #endif @@ -452,26 +471,45 @@ extern "C" #ifndef BLUETOOTH_TX_BUFFER_SIZE #define BLUETOOTH_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, bluetooth, BLUETOOTH_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, bt_rx, RX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, bt_tx, BLUETOOTH_TX_BUFFER_SIZE); + + uint8_t mcu_bt_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(bt_rx, &c); + return c; + } + + uint8_t mcu_bt_available(void) + { + return BUFFER_READ_AVAILABLE(bt_rx); + } + + void mcu_bt_clear(void) + { + BUFFER_CLEAR(bt_rx); + } + void mcu_bt_putc(uint8_t c) { - while (BUFFER_FULL(bluetooth)) + while (BUFFER_FULL(bt_tx)) { mcu_bt_flush(); } - BUFFER_ENQUEUE(bluetooth, &c); + BUFFER_ENQUEUE(bt_tx, &c); } void mcu_bt_flush(void) { if (SerialBT.hasClient()) { - while (!BUFFER_EMPTY(bluetooth)) + while (!BUFFER_EMPTY(bt_tx)) { uint8_t tmp[BLUETOOTH_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(bluetooth, tmp, BLUETOOTH_TX_BUFFER_SIZE, r); + BUFFER_READ(bt_tx, tmp, BLUETOOTH_TX_BUFFER_SIZE, r); SerialBT.write(tmp, r); SerialBT.flush(); } @@ -479,7 +517,7 @@ extern "C" else { // no client (discard) - BUFFER_CLEAR(bluetooth); + BUFFER_CLEAR(bt_tx); } } #endif @@ -532,7 +570,17 @@ extern "C" { esp_task_wdt_reset(); #ifndef DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)SerialBT.read()); + uint8_t c = SerialBT.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(bt_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(bt_rx)) = c; + BUFFER_STORE(bt_rx); + } #else mcu_bt_rx_cb((uint8_t)SerialBT.read()); #endif @@ -547,7 +595,17 @@ extern "C" { esp_task_wdt_reset(); #ifndef DETACH_WIFI_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)serverClient.read()); + uint8_t c = serverClient.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(wifi_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(wifi_rx)) = c; + BUFFER_STORE(wifi_rx); + } #else mcu_wifi_rx_cb((uint8_t)serverClient.read()); #endif diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 6b25b2ae4..3f9fc3c8e 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -607,22 +607,39 @@ uint8_t mcu_get_pwm(uint8_t pwm) #define UART_TX_BUFFER_SIZE 64 #endif DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } + void mcu_uart_flush(void) { - while (!BUFFER_EMPTY(uart)) + while (!BUFFER_EMPTY(uart_tx)) { uint8_t tmp[UART_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(uart, tmp, UART_TX_BUFFER_SIZE, r); + BUFFER_READ(uart_tx, tmp, UART_TX_BUFFER_SIZE, r); uart_write_bytes(UART_PORT, tmp, r); } } @@ -632,24 +649,43 @@ void mcu_uart_flush(void) #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); + +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} + void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart2_flush(void) { - while (!BUFFER_EMPTY(uart2)) + while (!BUFFER_EMPTY(uart2_tx)) { uint8_t tmp[UART2_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(uart2, tmp, UART2_TX_BUFFER_SIZE, r); + BUFFER_READ(uart2_tx, tmp, UART2_TX_BUFFER_SIZE, r); uart_write_bytes(UART2_PORT, tmp, r); } } @@ -830,7 +866,17 @@ void mcu_dotasks(void) rxlen = uart_read_bytes(UART_PORT, rxdata, RX_BUFFER_CAPACITY, 0); for (i = 0; i < rxlen; i++) { - mcu_com_rx_cb((uint8_t)rxdata[i]); + uint8_t c = (uint8_t)rxdata[i]; + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } } #endif #if defined(MCU_HAS_UART2) @@ -838,7 +884,17 @@ void mcu_dotasks(void) #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) for (i = 0; i < rxlen; i++) { - mcu_com_rx_cb((uint8_t)rxdata[i]); + uint8_t c = (uint8_t)rxdata[i]; + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } } #else for (i = 0; i < rxlen; i++) diff --git a/uCNC/src/hal/mcus/mcu.h b/uCNC/src/hal/mcus/mcu.h index 0671cccb8..dc980382d 100644 --- a/uCNC/src/hal/mcus/mcu.h +++ b/uCNC/src/hal/mcus/mcu.h @@ -526,11 +526,10 @@ extern "C" * can be defined either as a function or a macro call * */ - - #ifdef MCU_HAS_USB uint8_t mcu_usb_getc(void); uint8_t mcu_usb_available(void); + void mcu_usb_clear(void); void mcu_usb_putc(uint8_t c); void mcu_usb_flush(void); #ifdef DETACH_USB_FROM_MAIN_PROTOCOL @@ -552,6 +551,7 @@ extern "C" #ifdef MCU_HAS_UART2 uint8_t mcu_uart2_getc(void); uint8_t mcu_uart2_available(void); + void mcu_uart2_clear(void); void mcu_uart2_putc(uint8_t c); void mcu_uart2_flush(void); #ifdef DETACH_UART2_FROM_MAIN_PROTOCOL @@ -562,6 +562,7 @@ extern "C" #ifdef MCU_HAS_WIFI uint8_t mcu_wifi_getc(void); uint8_t mcu_wifi_available(void); + void mcu_wifi_clear(void); void mcu_wifi_putc(uint8_t c); void mcu_wifi_flush(void); #ifdef DETACH_WIFI_FROM_MAIN_PROTOCOL @@ -571,6 +572,8 @@ extern "C" #ifdef MCU_HAS_BLUETOOTH uint8_t mcu_bt_getc(void); + uint8_t mcu_bt_available(void); + void mcu_bt_clear(void); void mcu_bt_putc(uint8_t c); void mcu_bt_flush(void); #ifdef DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL From 8880a54d37114608521837e0ccea3c7f60e23e83 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 15:24:59 +0100 Subject: [PATCH 133/168] Modified ESP8266 --- uCNC/src/hal/mcus/esp32/mcu_esp32.c | 4 +- uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp | 210 +++++++++++------- 2 files changed, 136 insertions(+), 78 deletions(-) diff --git a/uCNC/src/hal/mcus/esp32/mcu_esp32.c b/uCNC/src/hal/mcus/esp32/mcu_esp32.c index 3f9fc3c8e..3d70a8b3b 100644 --- a/uCNC/src/hal/mcus/esp32/mcu_esp32.c +++ b/uCNC/src/hal/mcus/esp32/mcu_esp32.c @@ -606,7 +606,7 @@ uint8_t mcu_get_pwm(uint8_t pwm) #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); uint8_t mcu_uart_getc(void) { @@ -614,6 +614,8 @@ uint8_t mcu_uart_getc(void) BUFFER_DEQUEUE(uart_rx, &c); return c; } + +uint8_t mcu_uart_available(void) { return BUFFER_READ_AVAILABLE(uart_rx); } diff --git a/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp b/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp index 9bde157f3..3d38c4d52 100644 --- a/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp +++ b/uCNC/src/hal/mcus/esp8266/esp8266_arduino.cpp @@ -48,9 +48,9 @@ ESP8266WebServer httpServer(80); ESP8266HTTPUpdateServer httpUpdater; -const uint8_t *update_path = "/firmware"; -const uint8_t *update_username = WIFI_USER; -const uint8_t *update_password = WIFI_PASS; +const char *update_path = "/firmware"; +const char *update_username = WIFI_USER; +const char *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -59,8 +59,8 @@ typedef struct { uint8_t wifi_on; uint8_t wifi_mode; - uint8_t ssid[WIFI_SSID_MAX_LEN]; - uint8_t pass[WIFI_SSID_MAX_LEN]; + char ssid[WIFI_SSID_MAX_LEN]; + char pass[WIFI_SSID_MAX_LEN]; } wifi_settings_t; uint16_t wifi_settings_offset; @@ -94,9 +94,9 @@ extern "C" } #ifdef ENABLE_WIFI - if (!strncmp(grbl_cmd_str, "WIFI", 4)) + if (!strncmp((const char*)grbl_cmd_str, "WIFI", 4)) { - if (!strcmp(&grbl_cmd_str[4], "ON")) + if (!strcmp((const char *)&grbl_cmd_str[4], "ON")) { WiFi.disconnect(); switch (wifi_settings.wifi_mode) @@ -104,25 +104,25 @@ extern "C" case 1: WiFi.mode(WIFI_STA); WiFi.begin(wifi_settings.ssid, wifi_settings.pass); - protocol_send_feedback("Trying to connect to WiFi"); + protocol_send_feedback((const char *)"Trying to connect to WiFi"); break; case 2: WiFi.mode(WIFI_AP); WiFi.softAP(BOARD_NAME, wifi_settings.pass); - protocol_send_feedback("AP started"); - protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char *)"AP started"); + protocol_send_feedback((const char *)"SSID>" BOARD_NAME); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); break; default: WiFi.mode(WIFI_AP_STA); WiFi.begin(wifi_settings.ssid, wifi_settings.pass); - protocol_send_feedback("Trying to connect to WiFi"); + protocol_send_feedback((const char *)"Trying to connect to WiFi"); WiFi.softAP(BOARD_NAME, wifi_settings.pass); - protocol_send_feedback("AP started"); - protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char *)"AP started"); + protocol_send_feedback((const char *)"SSID>" BOARD_NAME); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); break; } @@ -131,7 +131,7 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "OFF")) + if (!strcmp((const char *)&grbl_cmd_str[4], "OFF")) { WiFi.disconnect(); wifi_settings.wifi_on = 0; @@ -139,136 +139,136 @@ extern "C" return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SSID")) + if (!strcmp((const char *)&grbl_cmd_str[4], "SSID")) { if (has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char *)arg); if (len > WIFI_SSID_MAX_LEN) { - protocol_send_feedback("WiFi SSID is too long"); + protocol_send_feedback((const char *)"WiFi SSID is too long"); } memset(wifi_settings.ssid, 0, sizeof(wifi_settings.ssid)); - strcpy(wifi_settings.ssid, arg); + strcpy((char *)wifi_settings.ssid, (const char*)arg); settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi SSID modified"); + protocol_send_feedback((const char *)"WiFi SSID modified"); } else { - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char *)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SCAN")) + if (!strcmp((const char *)&grbl_cmd_str[4], "SCAN")) { // Serial.println("[MSG:Scanning Networks]"); - protocol_send_feedback("Scanning Networks"); + protocol_send_feedback((const char *)"Scanning Networks"); int numSsid = WiFi.scanNetworks(); if (numSsid == -1) { - protocol_send_feedback("Failed to scan!"); + protocol_send_feedback((const char *)"Failed to scan!"); while (true) ; } // print the list of networks seen: - sprintf(str, "%d available networks", numSsid); - protocol_send_feedback(str); + sprintf((char*)str, "%d available networks", numSsid); + protocol_send_feedback((const char *)str); // print the network number and name for each network found: for (int netid = 0; netid < numSsid; netid++) { - sprintf(str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid).c_str(), WiFi.RSSI(netid)); - protocol_send_feedback(str); + sprintf((char*)str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid).c_str(), WiFi.RSSI(netid)); + protocol_send_feedback((const char *)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SAVE")) + if (!strcmp((const char *)&grbl_cmd_str[4], "SAVE")) { settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi settings saved"); + protocol_send_feedback((const char *)"WiFi settings saved"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "RESET")) + if (!strcmp((const char *)&grbl_cmd_str[4], "RESET")) { settings_erase(wifi_settings_offset, sizeof(wifi_settings_t)); memset(&wifi_settings, 0, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi settings deleted"); + protocol_send_feedback((const char *)"WiFi settings deleted"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "MODE")) + if (!strcmp((const char *)&grbl_cmd_str[4], "MODE")) { if (has_arg) { - int mode = atoi(arg) - 1; + int mode = atoi((const char*)arg) - 1; if (mode >= 0) { wifi_settings.wifi_mode = mode; } else { - protocol_send_feedback("Invalid value. STA+AP(1), STA(2), AP(3)"); + protocol_send_feedback((const char *)"Invalid value. STA+AP(1), STA(2), AP(3)"); } } switch (wifi_settings.wifi_mode) { case 0: - protocol_send_feedback("WiFi mode>STA+AP"); + protocol_send_feedback((const char *)"WiFi mode>STA+AP"); break; case 1: - protocol_send_feedback("WiFi mode>STA"); + protocol_send_feedback((const char *)"WiFi mode>STA"); break; case 2: - protocol_send_feedback("WiFi mode>AP"); + protocol_send_feedback((const char *)"WiFi mode>AP"); break; } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "PASS") && has_arg) + if (!strcmp((const char *)&grbl_cmd_str[4], "PASS") && has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char *)arg); if (len > WIFI_SSID_MAX_LEN) { - protocol_send_feedback("WiFi pass is too long"); + protocol_send_feedback((const char *)"WiFi pass is too long"); } memset(wifi_settings.pass, 0, sizeof(wifi_settings.pass)); - strcpy(wifi_settings.pass, arg); - protocol_send_feedback("WiFi password modified"); + strcpy((char *)wifi_settings.pass, (const char*)arg); + protocol_send_feedback((const char *)"WiFi password modified"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "IP")) + if (!strcmp((const char *)&grbl_cmd_str[4], "IP")) { if (wifi_settings.wifi_on) { switch (wifi_settings.wifi_mode) { case 1: - sprintf(str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); - sprintf(str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); + sprintf((char*)str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); break; case 2: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); break; default: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char *)str); break; } } else { - protocol_send_feedback("WiFi is off"); + protocol_send_feedback((const char *)"WiFi is off"); } return STATUS_OK; @@ -299,18 +299,18 @@ extern "C" return false; } next_info = mcu_millis() + 30000; - protocol_send_feedback("Disconnected from WiFi"); + protocol_send_feedback((const char *)"Disconnected from WiFi"); return false; } if (!connected) { connected = true; - protocol_send_feedback("Connected to WiFi"); - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); - sprintf(str, "IP>%s", WiFi.localIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char *)"Connected to WiFi"); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char *)str); + sprintf((char*)str, "IP>%s", WiFi.localIP().toString().c_str()); + protocol_send_feedback((const char *)str); } if (server.hasClient()) @@ -366,25 +366,43 @@ extern "C" #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); + uint8_t mcu_uart_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; + } + + uint8_t mcu_uart_available(void) + { + return BUFFER_READ_AVAILABLE(uart_rx); + } + + void mcu_uart_clear(void) + { + BUFFER_CLEAR(uart_rx); + } + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) { - while (!BUFFER_EMPTY(uart)) + while (!BUFFER_EMPTY(uart_tx)) { uint8_t tmp[UART_TX_BUFFER_SIZE]; uint8_t r; uint8_t max = (uint8_t)MIN(Serial.availableForWrite(), UART_TX_BUFFER_SIZE); - BUFFER_READ(uart, tmp, max, r); + BUFFER_READ(uart_tx, tmp, max, r); Serial.write(tmp, r); Serial.flush(); } @@ -395,34 +413,52 @@ extern "C" #ifndef WIFI_TX_BUFFER_SIZE #define WIFI_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, wifi, WIFI_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, wifi_rx, RX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, wifi_tx, WIFI_TX_BUFFER_SIZE); + + uint8_t mcu_wifi_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(wifi_tx, &c); + return c; + } + + uint8_t mcu_wifi_available(void) + { + return BUFFER_READ_AVAILABLE(wifi_tx); + } + + void mcu_wifi_clear(void) + { + BUFFER_CLEAR(wifi_tx); + } void mcu_wifi_putc(uint8_t c) { - while (BUFFER_FULL(wifi)) + while (BUFFER_FULL(wifi_tx)) { mcu_wifi_flush(); } - BUFFER_ENQUEUE(wifi, &c); + BUFFER_ENQUEUE(wifi_tx, &c); } void mcu_wifi_flush(void) { if (esp8266_wifi_clientok()) { - while (!BUFFER_EMPTY(wifi)) + while (!BUFFER_EMPTY(wifi_tx)) { uint8_t tmp[WIFI_TX_BUFFER_SIZE]; uint8_t r; uint8_t max = (uint8_t)MIN(serverClient.availableForWrite(), WIFI_TX_BUFFER_SIZE); - BUFFER_READ(wifi, tmp, max, r); + BUFFER_READ(wifi_tx, tmp, max, r); serverClient.write(tmp, r); } } else { // no client (discard) - BUFFER_CLEAR(wifi); + BUFFER_CLEAR(wifi_tx); } } #endif @@ -445,7 +481,17 @@ extern "C" { system_soft_wdt_feed(); #ifndef DETACH_UART_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)Serial.read()); + uint8_t c = (uint8_t)Serial.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb((uint8_t)Serial.read()); #endif @@ -459,7 +505,17 @@ extern "C" { system_soft_wdt_feed(); #ifndef DETACH_WIFI_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)serverClient.read()); + uint8_t c = (uint8_t)serverClient.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(wifi_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(wifi_rx)) = c; + BUFFER_STORE(wifi_rx); + } #else mcu_wifi_rx_cb((uint8_t)serverClient.read()); #endif @@ -475,7 +531,7 @@ extern "C" #include "esp_peri.h" extern "C" { - #include "../../../cnc.h" +#include "../../../cnc.h" void esp8266_spi_init(uint32_t freq, uint8_t mode) { SPI.begin(); From da6a4ed330f922e6396b10cb8135719f144a223d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 15:52:29 +0100 Subject: [PATCH 134/168] Modified LPC176x --- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 46 ++++++-- uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 101 +++++++++++++----- 2 files changed, 108 insertions(+), 39 deletions(-) diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index 428e00fdc..01f552088 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -32,9 +32,30 @@ extern "C" { #include "../../../cnc.h" #ifdef USE_ARDUINO_CDC + DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + void mcu_usb_dotasks(void) { MSC_RunDeferredCommands(); + while (UsbSerial.available() > 0) + { +#ifndef DETACH_USB_FROM_MAIN_PROTOCOL + uint8_t c = (uint8_t)UsbSerial.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } + +#else + mcu_usb_rx_cb((uint8_t)UsbSerial.read()); +#endif + } } void mcu_usb_init(void) @@ -57,18 +78,19 @@ extern "C" #ifndef USB_TX_BUFFER_SIZE #define USB_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, usb, USB_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); + void mcu_usb_flush(void) { - while (!BUFFER_EMPTY(usb)) + while (!BUFFER_EMPTY(usb_tx)) { uint8_t tmp[USB_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(usb, tmp, USB_TX_BUFFER_SIZE, r); + BUFFER_READ(usb_tx, tmp, USB_TX_BUFFER_SIZE, r); #ifdef MCU_HAS_USB - UsbSerial.write(tmp, r); + UsbSerial.write((char *)tmp, r); UsbSerial.flushTX(); #endif } @@ -76,28 +98,30 @@ extern "C" void mcu_usb_putc(uint8_t c) { - while (BUFFER_FULL(usb)) + while (BUFFER_FULL(usb_tx)) { mcu_usb_flush(); } - BUFFER_ENQUEUE(usb, &c); + BUFFER_ENQUEUE(usb_tx, &c); } uint8_t mcu_usb_getc(void) { - int16_t c = UsbSerial.read(); - return (uint8_t)((c >= 0) ? c : 0); + uint8_t c = 0; + BUFFER_DEQUEUE(usb_rx, &c); + return c; } uint8_t mcu_usb_available(void) { - return UsbSerial.available(); + return BUFFER_READ_AVAILABLE(usb_rx); } - uint8_t mcu_usb_tx_available(void) + void mcu_usb_clear(void) { - return (UsbSerial.availableForWrite() | (UsbSerial.host_connected ? 0 : 1)); + BUFFER_CLEAR(usb_rx); } + #endif } #endif diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index febf0394d..2ea85907f 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -26,9 +26,6 @@ #ifdef USE_ARDUINO_CDC extern void mcu_usb_dotasks(void); extern void mcu_usb_init(void); -extern uint8_t mcu_usb_getc(void); -extern uint8_t mcu_usb_available(void); -extern uint8_t mcu_usb_tx_available(void); #else #include #endif @@ -231,7 +228,9 @@ void mcu_clocks_init(void) #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + void MCU_COM_ISR(void) { __ATOMIC_FORCEON__ @@ -258,7 +257,17 @@ void MCU_COM_ISR(void) { uint8_t c = (uint8_t)(COM_INREG & UART_RBR_MASKBIT); #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } + #else mcu_uart_rx_cb(c); #endif @@ -269,13 +278,13 @@ void MCU_COM_ISR(void) // UART_IntConfig(COM_USART, UART_INTCFG_THRE, DISABLE); mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { COM_UART->IER &= ~UART_IER_THREINT_EN; return; } uint8_t c = 0; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); COM_OUTREG = c; } } @@ -286,7 +295,8 @@ void MCU_COM_ISR(void) #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); void MCU_COM2_ISR(void) { __ATOMIC_FORCEON__ @@ -313,7 +323,16 @@ void MCU_COM2_ISR(void) { uint8_t c = (uint8_t)(COM2_INREG & UART_RBR_MASKBIT); #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } #else mcu_uart2_rx_cb(c); #endif @@ -322,13 +341,13 @@ void MCU_COM2_ISR(void) if (irqstatus == UART_IIR_INTID_THRE) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart2)) + if (BUFFER_EMPTY(uart2_tx)) { COM2_UART->IER &= ~UART_IER_THREINT_EN; return; } uint8_t c; - BUFFER_DEQUEUE(uart2, &c); + BUFFER_DEQUEUE(uart2_tx, &c); COM2_OUTREG = c; } } @@ -573,25 +592,43 @@ uint8_t mcu_get_servo(uint8_t servo) * can be defined either as a function or a macro call * */ #ifdef MCU_HAS_UART + +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) { if (!(COM_UART->IER & UART_IER_THREINT_EN)) // not ready start flushing { - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { return; } uint8_t c = 0; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); while (!CHECKBIT(COM_UART->LSR, 5)) ; COM_OUTREG = c; @@ -604,25 +641,42 @@ void mcu_uart_flush(void) #endif #ifdef MCU_HAS_UART2 +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} + void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart2_flush(void) { if (!(COM2_UART->IER & UART_IER_THREINT_EN)) // not ready start flushing { - if (BUFFER_EMPTY(uart2)) + if (BUFFER_EMPTY(uart2_tx)) { return; } uint8_t c = 0; - BUFFER_DEQUEUE(uart2, &c); + BUFFER_DEQUEUE(uart2_tx, &c); while (!CHECKBIT(COM2_UART->LSR, 5)) ; COM2_OUTREG = c; @@ -809,15 +863,6 @@ void mcu_dotasks() #ifdef USE_ARDUINO_CDC mcu_usb_flush(); mcu_usb_dotasks(); - while (mcu_usb_available()) - { - uint8_t c = (uint8_t)mcu_usb_getc(); -#ifndef DETACH_USB_FROM_MAIN_PROTOCOL - mcu_com_rx_cb(c); -#else - mcu_usb_rx_cb(c); -#endif - } #else tusb_cdc_task(); // tinyusb device task From 4fc9373b1a79fce673a0c126009d1ad7f3e2071c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 17:30:03 +0100 Subject: [PATCH 135/168] Modified RP2040 --- uCNC/src/hal/mcus/rp2040/mcu_rp2040.c | 4 - uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp | 357 ++++++++++++++------ 2 files changed, 255 insertions(+), 106 deletions(-) diff --git a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c index c5f637983..170b1d7e9 100644 --- a/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c +++ b/uCNC/src/hal/mcus/rp2040/mcu_rp2040.c @@ -26,10 +26,6 @@ static volatile bool rp2040_global_isr_enabled; extern void rp2040_uart_init(int baud); -extern void rp2040_uart_flush(void); -extern void rp2040_uart_write(uint8_t c); -extern bool rp2040_uart_rx_ready(void); -extern bool rp2040_uart_tx_ready(void); extern void rp2040_uart_process(void); extern void rp2040_eeprom_init(int size); diff --git a/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp b/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp index e415bec2e..bd8fdd258 100644 --- a/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp +++ b/uCNC/src/hal/mcus/rp2040/rp2040_arduino.cpp @@ -66,9 +66,9 @@ uint16_t bt_settings_offset; WebServer httpServer(80); HTTPUpdateServer httpUpdater; -const uint8_t *update_path = "/firmware"; -const uint8_t *update_username = WIFI_USER; -const uint8_t *update_password = WIFI_PASS; +const char *update_path = "/firmware"; +const char *update_username = WIFI_USER; +const char *update_password = WIFI_PASS; #define MAX_SRV_CLIENTS 1 WiFiServer server(WIFI_PORT); WiFiClient serverClient; @@ -77,8 +77,8 @@ typedef struct { uint8_t wifi_on; uint8_t wifi_mode; - uint8_t ssid[WIFI_SSID_MAX_LEN]; - uint8_t pass[WIFI_PASS_MAX_LEN]; + char ssid[WIFI_SSID_MAX_LEN]; + char pass[WIFI_PASS_MAX_LEN]; } wifi_settings_t; uint16_t wifi_settings_offset; @@ -108,22 +108,22 @@ uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t } #ifdef ENABLE_BLUETOOTH - if (!strncmp(grbl_cmd_str, "BTH", 3)) + if (!strncmp((const char*)grbl_cmd_str, "BTH", 3)) { - if (!strcmp(&grbl_cmd_str[3], "ON")) + if (!strcmp((const char*)&grbl_cmd_str[3], "ON")) { SerialBT.begin(BAUDRATE, SERIAL_8N1); - protocol_send_feedback("Bluetooth enabled"); + protocol_send_feedback((const char*)"Bluetooth enabled"); bt_on = 1; settings_save(bt_settings_offset, &bt_on, 1); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[3], "OFF")) + if (!strcmp((const char*)&grbl_cmd_str[3], "OFF")) { SerialBT.end(); - protocol_send_feedback("Bluetooth disabled"); + protocol_send_feedback((const char*)"Bluetooth disabled"); bt_on = 0; settings_save(bt_settings_offset, &bt_on, 1); @@ -132,9 +132,9 @@ uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t } #endif #ifdef ENABLE_WIFI - if (!strncmp(grbl_cmd_str, "WIFI", 4)) + if (!strncmp((const char*)grbl_cmd_str, "WIFI", 4)) { - if (!strcmp(&grbl_cmd_str[4], "ON")) + if (!strcmp((const char*)&grbl_cmd_str[4], "ON")) { WiFi.disconnect(); switch (wifi_settings.wifi_mode) @@ -142,25 +142,25 @@ uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t case 1: WiFi.mode(WIFI_STA); WiFi.begin(wifi_settings.ssid, wifi_settings.pass); - protocol_send_feedback("Trying to connect to WiFi"); + protocol_send_feedback((const char*)"Trying to connect to WiFi"); break; case 2: WiFi.mode(WIFI_AP); WiFi.softAP(BOARD_NAME, wifi_settings.pass); - protocol_send_feedback("AP started"); - protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char*)"AP started"); + protocol_send_feedback((const char*)"SSID>" BOARD_NAME); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; default: WiFi.mode(WIFI_AP_STA); WiFi.begin(wifi_settings.ssid, wifi_settings.pass); - protocol_send_feedback("Trying to connect to WiFi"); + protocol_send_feedback((const char*)"Trying to connect to WiFi"); WiFi.softAP(BOARD_NAME, wifi_settings.pass); - protocol_send_feedback("AP started"); - protocol_send_feedback("SSID>" BOARD_NAME); - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char*)"AP started"); + protocol_send_feedback((const char*)"SSID>" BOARD_NAME); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; } @@ -169,7 +169,7 @@ uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "OFF")) + if (!strcmp((const char*)&grbl_cmd_str[4], "OFF")) { WiFi.disconnect(); wifi_settings.wifi_on = 0; @@ -177,136 +177,136 @@ uint8_t mcu_custom_grbl_cmd(uint8_t *grbl_cmd_str, uint8_t grbl_cmd_len, uint8_t return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SSID")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SSID")) { if (has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char*)arg); if (len > WIFI_SSID_MAX_LEN) { - protocol_send_feedback("WiFi SSID is too long"); + protocol_send_feedback((const char*)"WiFi SSID is too long"); } memset(wifi_settings.ssid, 0, sizeof(wifi_settings.ssid)); - strcpy(wifi_settings.ssid, arg); + strcpy(wifi_settings.ssid, (const char*)arg); settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi SSID modified"); + protocol_send_feedback((const char*)"WiFi SSID modified"); } else { - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char*)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SCAN")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SCAN")) { // Serial.println("[MSG:Scanning Networks]"); - protocol_send_feedback("Scanning Networks"); + protocol_send_feedback((const char*)"Scanning Networks"); int numSsid = WiFi.scanNetworks(); if (numSsid == -1) { - protocol_send_feedback("Failed to scan!"); + protocol_send_feedback((const char*)"Failed to scan!"); while (true) ; } // print the list of networks seen: - sprintf(str, "%d available networks", numSsid); - protocol_send_feedback(str); + sprintf((char*)str, "%d available networks", numSsid); + protocol_send_feedback((const char*)str); // print the network number and name for each network found: for (int netid = 0; netid < numSsid; netid++) { - sprintf(str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid), WiFi.RSSI(netid)); - protocol_send_feedback(str); + sprintf((char*)str, "%d) %s\tSignal: %ddBm", netid, WiFi.SSID(netid), WiFi.RSSI(netid)); + protocol_send_feedback((const char*)str); } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "SAVE")) + if (!strcmp((const char*)&grbl_cmd_str[4], "SAVE")) { settings_save(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi settings saved"); + protocol_send_feedback((const char*)"WiFi settings saved"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "RESET")) + if (!strcmp((const char*)&grbl_cmd_str[4], "RESET")) { settings_erase(wifi_settings_offset, sizeof(wifi_settings_t)); memset(&wifi_settings, 0, sizeof(wifi_settings_t)); - protocol_send_feedback("WiFi settings deleted"); + protocol_send_feedback((const char*)"WiFi settings deleted"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "MODE")) + if (!strcmp((const char*)&grbl_cmd_str[4], "MODE")) { if (has_arg) { - int mode = atoi(arg) - 1; + int mode = atoi((const char*)arg) - 1; if (mode >= 0) { wifi_settings.wifi_mode = mode; } else { - protocol_send_feedback("Invalid value. STA+AP(1), STA(2), AP(3)"); + protocol_send_feedback((const char*)"Invalid value. STA+AP(1), STA(2), AP(3)"); } } switch (wifi_settings.wifi_mode) { case 0: - protocol_send_feedback("WiFi mode>STA+AP"); + protocol_send_feedback((const char*)"WiFi mode>STA+AP"); break; case 1: - protocol_send_feedback("WiFi mode>STA"); + protocol_send_feedback((const char*)"WiFi mode>STA"); break; case 2: - protocol_send_feedback("WiFi mode>AP"); + protocol_send_feedback((const char*)"WiFi mode>AP"); break; } return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "PASS") && has_arg) + if (!strcmp((const char*)&grbl_cmd_str[4], "PASS") && has_arg) { - uint8_t len = strlen(arg); + uint8_t len = strlen((const char*)arg); if (len > WIFI_PASS_MAX_LEN) { - protocol_send_feedback("WiFi pass is too long"); + protocol_send_feedback((const char*)"WiFi pass is too long"); } memset(wifi_settings.pass, 0, sizeof(wifi_settings.pass)); - strcpy(wifi_settings.pass, arg); - protocol_send_feedback("WiFi password modified"); + strcpy(wifi_settings.pass, (const char*)arg); + protocol_send_feedback((const char*)"WiFi password modified"); return STATUS_OK; } - if (!strcmp(&grbl_cmd_str[4], "IP")) + if (!strcmp((const char*)&grbl_cmd_str[4], "IP")) { if (wifi_settings.wifi_on) { switch (wifi_settings.wifi_mode) { case 1: - sprintf(str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); - sprintf(str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "STA IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); + sprintf((char*)str, "AP IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; case 2: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; default: - sprintf(str, "IP>%s", WiFi.softAPIP().toString().c_str()); - protocol_send_feedback(str); + sprintf((char*)str, "IP>%s", WiFi.softAPIP().toString().c_str()); + protocol_send_feedback((const char*)str); break; } } else { - protocol_send_feedback("WiFi is off"); + protocol_send_feedback((const char*)"WiFi is off"); } return STATUS_OK; @@ -337,18 +337,18 @@ bool rp2040_wifi_clientok(void) return false; } next_info = millis() + 30000; - protocol_send_feedback("Disconnected from WiFi"); + protocol_send_feedback((const char*)"Disconnected from WiFi"); return false; } if (!connected) { connected = true; - protocol_send_feedback("Connected to WiFi"); - sprintf(str, "SSID>%s", wifi_settings.ssid); - protocol_send_feedback(str); - sprintf(str, "IP>%s", WiFi.localIP().toString().c_str()); - protocol_send_feedback(str); + protocol_send_feedback((const char*)"Connected to WiFi"); + sprintf((char*)str, "SSID>%s", wifi_settings.ssid); + protocol_send_feedback((const char*)str); + sprintf((char*)str, "IP>%s", WiFi.localIP().toString().c_str()); + protocol_send_feedback((const char*)str); } if (server.hasClient()) @@ -379,8 +379,8 @@ void rp2040_wifi_bt_init(void) { #ifdef ENABLE_WIFI wifi_settings = {0}; - memcpy(wifi_settings.ssid, BOARD_NAME, strlen(BOARD_NAME)); - memcpy(wifi_settings.pass, WIFI_PASS, strlen(WIFI_PASS)); + memcpy(wifi_settings.ssid, BOARD_NAME, strlen((const char*)BOARD_NAME)); + memcpy(wifi_settings.pass, WIFI_PASS, strlen((const char*)WIFI_PASS)); wifi_settings_offset = settings_register_external_setting(sizeof(wifi_settings_t)); if (settings_load(wifi_settings_offset, (uint8_t *)&wifi_settings, sizeof(wifi_settings_t))) @@ -418,33 +418,52 @@ void rp2040_wifi_bt_init(void) #ifndef WIFI_TX_BUFFER_SIZE #define WIFI_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, wifi, WIFI_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, wifi_tx, WIFI_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, wifi_rx, RX_BUFFER_SIZE); + +uint8_t mcu_wifi_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(wifi_rx, &c); + return c; +} + +uint8_t mcu_wifi_available(void) +{ + return BUFFER_READ_AVAILABLE(wifi_rx); +} + +void mcu_wifi_clear(void) +{ + BUFFER_CLEAR(wifi_rx); +} + void mcu_wifi_putc(uint8_t c) { - while (BUFFER_FULL(wifi)) + while (BUFFER_FULL(wifi_tx)) { mcu_wifi_flush(); } - BUFFER_ENQUEUE(wifi, &c); + BUFFER_ENQUEUE(wifi_tx, &c); } void mcu_wifi_flush(void) { if (rp2040_wifi_clientok()) { - while (!BUFFER_EMPTY(wifi)) + while (!BUFFER_EMPTY(wifi_tx)) { uint8_t tmp[WIFI_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(wifi, tmp, WIFI_TX_BUFFER_SIZE, r); + BUFFER_READ(wifi_tx, tmp, WIFI_TX_BUFFER_SIZE, r); serverClient.write(tmp, r); } } else { // no client (discard) - BUFFER_CLEAR(wifi); + BUFFER_CLEAR(wifi_tx); } } #endif @@ -453,24 +472,43 @@ void mcu_wifi_flush(void) #ifndef BLUETOOTH_TX_BUFFER_SIZE #define BLUETOOTH_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, bluetooth, BLUETOOTH_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, bt_tx, BLUETOOTH_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, bt_rx, RX_BUFFER_SIZE); + +uint8_t mcu_bt_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(bt_rx, &c); + return c; +} + +uint8_t mcu_bt_available(void) +{ + return BUFFER_READ_AVAILABLE(bt_rx); +} + +void mcu_bt_clear(void) +{ + BUFFER_CLEAR(bt_rx); +} + void mcu_bt_putc(uint8_t c) { - while (BUFFER_FULL(bluetooth)) + while (BUFFER_FULL(bt_tx)) { mcu_bt_flush(); } - BUFFER_ENQUEUE(bluetooth, &c); + BUFFER_ENQUEUE(bt_tx, &c); } void mcu_bt_flush(void) { - while (!BUFFER_EMPTY(bluetooth)) + while (!BUFFER_EMPTY(bt_tx)) { uint8_t tmp[BLUETOOTH_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(bluetooth, tmp, BLUETOOTH_TX_BUFFER_SIZE, r); + BUFFER_READ(bt_tx, tmp, BLUETOOTH_TX_BUFFER_SIZE, r); SerialBT.write(tmp, r); SerialBT.flush(); } @@ -517,12 +555,25 @@ bool rp2040_wifi_bt_rx_ready(void) void rp2040_wifi_bt_process(void) { #ifdef ENABLE_WIFI + DECL_BUFFER(uint8_t, wifi_rx, RX_BUFFER_SIZE); + if (rp2040_wifi_clientok()) { while (serverClient.available() > 0) { #ifndef DETACH_WIFI_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)serverClient.read()); + uint8_t c = (uint8_t)serverClient.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(wifi_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(wifi_rx)) = c; + BUFFER_STORE(wifi_rx); + } + #else mcu_wifi_rx_cb((uint8_t)serverClient.read()); #endif @@ -533,10 +584,23 @@ void rp2040_wifi_bt_process(void) #endif #ifdef ENABLE_BLUETOOTH + DECL_BUFFER(uint8_t, bt_rx, RX_BUFFER_SIZE); + while (SerialBT.available() > 0) { #ifndef DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)SerialBT.read()); + uint8_t c = (uint8_t)SerialBT.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(bt_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(bt_rx)) = c; + BUFFER_STORE(bt_rx); + } + #else mcu_bt_rx_cb((uint8_t)SerialBT.read()); #endif @@ -572,24 +636,43 @@ extern "C" #ifndef USB_TX_BUFFER_SIZE #define USB_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, usb, USB_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + + uint8_t mcu_usb_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(usb_rx, &c); + return c; + } + + uint8_t mcu_usb_available(void) + { + return BUFFER_READ_AVAILABLE(usb_rx); + } + + void mcu_usb_clear(void) + { + BUFFER_CLEAR(usb_rx); + } + void mcu_usb_putc(uint8_t c) { - while (BUFFER_FULL(usb)) + while (BUFFER_FULL(usb_tx)) { mcu_usb_flush(); } - BUFFER_ENQUEUE(usb, &c); + BUFFER_ENQUEUE(usb_tx, &c); } void mcu_usb_flush(void) { - while (!BUFFER_EMPTY(usb)) + while (!BUFFER_EMPTY(usb_tx)) { uint8_t tmp[USB_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(usb, tmp, USB_TX_BUFFER_SIZE, r); + BUFFER_READ(usb_tx, tmp, USB_TX_BUFFER_SIZE, r); Serial.write(tmp, r); Serial.flush(); } @@ -600,24 +683,43 @@ extern "C" #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + + uint8_t mcu_uart_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; + } + + uint8_t mcu_uart_available(void) + { + return BUFFER_READ_AVAILABLE(uart_rx); + } + + void mcu_uart_clear(void) + { + BUFFER_CLEAR(uart_rx); + } + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) { - while (!BUFFER_EMPTY(uart)) + while (!BUFFER_EMPTY(uart_tx)) { uint8_t tmp[UART_TX_BUFFER_SIZE]; uint8_t r = 0; - BUFFER_READ(uart, tmp, UART_TX_BUFFER_SIZE, r); + BUFFER_READ(uart_tx, tmp, UART_TX_BUFFER_SIZE, r); COM_UART.write(tmp, r); COM_UART.flush(); } @@ -628,24 +730,43 @@ extern "C" #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif - DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); + DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); + + uint8_t mcu_uart2_getc(void) + { + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; + } + + uint8_t mcu_uart2_available(void) + { + return BUFFER_READ_AVAILABLE(uart2_rx); + } + + void mcu_uart2_clear(void) + { + BUFFER_CLEAR(uart2_rx); + } + void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart2_flush(void) { - while (!BUFFER_EMPTY(uart2)) + while (!BUFFER_EMPTY(uart2_tx)) { uint8_t tmp[UART2_TX_BUFFER_SIZE]; uint8_t r; - BUFFER_READ(uart2, tmp, UART2_TX_BUFFER_SIZE, r); + BUFFER_READ(uart2_tx, tmp, UART2_TX_BUFFER_SIZE, r); COM2_UART.write(tmp, r); COM2_UART.flush(); } @@ -670,7 +791,18 @@ extern "C" while (Serial.available() > 0) { #ifndef DETACH_USB_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)Serial.read()); + uint8_t c = (uint8_t)Serial.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } + #else mcu_usb_rx_cb((uint8_t)Serial.read()); #endif @@ -681,7 +813,17 @@ extern "C" while (COM_UART.available() > 0) { #ifndef DETACH_UART_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)COM_UART.read()); + uint8_t c = (uint8_t)COM_UART.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb((uint8_t)COM_UART.read()); #endif @@ -692,7 +834,18 @@ extern "C" while (COM2_UART.available() > 0) { #ifndef DETACH_UART2_FROM_MAIN_PROTOCOL - mcu_com_rx_cb((uint8_t)COM2_UART.read()); + uint8_t c = (uint8_t)COM2_UART.read(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } + #else mcu_uart2_rx_cb((uint8_t)COM2_UART.read()); #endif @@ -734,7 +887,7 @@ extern "C" { if (!EEPROM.commit()) { - protocol_send_feedback(" EEPROM write error"); + protocol_send_feedback((const char*)" EEPROM write error"); } } } From bd18c3e8a1f251f945c7b5eeae927acae0b42e1f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 17:39:45 +0100 Subject: [PATCH 136/168] Modified SAMD21 --- uCNC/src/hal/mcus/samd21/mcu_samd21.c | 110 +++++++++++++++++++++++--- 1 file changed, 97 insertions(+), 13 deletions(-) diff --git a/uCNC/src/hal/mcus/samd21/mcu_samd21.c b/uCNC/src/hal/mcus/samd21/mcu_samd21.c index 476b7619e..07565f5f4 100644 --- a/uCNC/src/hal/mcus/samd21/mcu_samd21.c +++ b/uCNC/src/hal/mcus/samd21/mcu_samd21.c @@ -210,7 +210,9 @@ void MCU_ITP_ISR(void) #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + void mcu_com_isr() { __ATOMIC_FORCEON__ @@ -220,7 +222,16 @@ void mcu_com_isr() COM_UART->USART.INTFLAG.bit.RXC = 1; uint8_t c = (0xff & COM_INREG); #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb(c); #endif @@ -228,14 +239,14 @@ void mcu_com_isr() if (COM_UART->USART.INTFLAG.bit.DRE && COM_UART->USART.INTENSET.bit.DRE) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { COM_UART->USART.INTENCLR.reg = SERCOM_USART_INTENCLR_DRE; return; } uint8_t c; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); COM_OUTREG = c; } } @@ -246,7 +257,9 @@ void mcu_com_isr() #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); + void mcu_com2_isr() { __ATOMIC_FORCEON__ @@ -256,7 +269,16 @@ void mcu_com2_isr() COM2_UART->USART.INTFLAG.bit.RXC = 1; uint8_t c = (0xff & COM2_INREG); #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } #else mcu_uart2_rx_cb(c); #endif @@ -265,13 +287,13 @@ void mcu_com2_isr() { // keeps sending chars until null is found mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart2)) + if (BUFFER_EMPTY(uart2_tx)) { COM2_UART->USART.INTENCLR.reg = SERCOM_USART_INTENCLR_DRE; return; } uint8_t c; - BUFFER_DEQUEUE(uart2, &c); + BUFFER_DEQUEUE(uart2_tx, &c); COM2_OUTREG = c; } } @@ -751,6 +773,25 @@ bool mcu_tx_ready(void) * can be defined either as a function or a macro call * */ #ifdef MCU_HAS_USB +DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + +uint8_t mcu_usb_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(usb_rx, &c); + return c; +} + +uint8_t mcu_usb_available(void) +{ + return BUFFER_READ_AVAILABLE(usb_rx); +} + +void mcu_usb_clear(void) +{ + BUFFER_CLEAR(usb_rx); +} + void mcu_usb_putc(uint8_t c) { if (!tusb_cdc_write_available()) @@ -775,13 +816,30 @@ void mcu_usb_flush(void) #endif #ifdef MCU_HAS_UART +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) @@ -797,13 +855,30 @@ void mcu_uart_flush(void) #endif #ifdef MCU_HAS_UART2 +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} + void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart_flush(void) @@ -1025,7 +1100,16 @@ void mcu_dotasks(void) { uint8_t c = (uint8_t)tusb_cdc_read(); #ifndef DETACH_USB_FROM_MAIN_PROTOCOL - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } #else mcu_usb_rx_cb(c); #endif From a21f9831171f5e923e93e392093d6921c95df387 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 17:45:48 +0100 Subject: [PATCH 137/168] Modified STM32F1 --- uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c | 113 +++++++++++++++++++--- 1 file changed, 98 insertions(+), 15 deletions(-) diff --git a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c index 962c8a51b..63e81343c 100644 --- a/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c +++ b/uCNC/src/hal/mcus/stm32f1x/mcu_stm32f1x.c @@ -76,7 +76,9 @@ volatile bool stm32_global_isr_enabled; #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + void MCU_SERIAL_ISR(void) { __ATOMIC_FORCEON__ @@ -85,7 +87,16 @@ void MCU_SERIAL_ISR(void) { uint8_t c = COM_INREG; #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb(c); #endif @@ -94,13 +105,13 @@ void MCU_SERIAL_ISR(void) if ((COM_UART->SR & USART_SR_TXE) && (COM_UART->CR1 & USART_CR1_TXEIE)) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { COM_UART->CR1 &= ~(USART_CR1_TXEIE); return; } uint8_t c; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); COM_OUTREG = c; } } @@ -111,7 +122,9 @@ void MCU_SERIAL_ISR(void) #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); + void MCU_SERIAL2_ISR(void) { __ATOMIC_FORCEON__ @@ -120,7 +133,16 @@ void MCU_SERIAL2_ISR(void) { uint8_t c = COM2_INREG; #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } #else mcu_uart2_rx_cb(c); #endif @@ -129,13 +151,13 @@ void MCU_SERIAL2_ISR(void) if ((COM2_UART->SR & USART_SR_TXE) && (COM2_UART->CR1 & USART_CR1_TXEIE)) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart2)) + if (BUFFER_EMPTY(uart2_tx)) { COM2_UART->CR1 &= ~(USART_CR1_TXEIE); return; } uint8_t c; - BUFFER_DEQUEUE(uart2, &c); + BUFFER_DEQUEUE(uart2_tx, &c); COM2_OUTREG = c; } } @@ -417,8 +439,8 @@ void mcu_clocks_init() DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; } - //free some jtag pins - AFIO->MAPR |= (2<<24); + // free some jtag pins + AFIO->MAPR |= (2 << 24); } void mcu_usart_init(void) @@ -473,6 +495,24 @@ void mcu_usart_init(void) } #ifdef MCU_HAS_USB +DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); +uint8_t mcu_usb_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(usb_rx, &c); + return c; +} + +uint8_t mcu_usb_available(void) +{ + return BUFFER_READ_AVAILABLE(usb_rx); +} + +void mcu_usb_clear(void) +{ + BUFFER_CLEAR(usb_rx); +} + void mcu_usb_putc(uint8_t c) { if (!tusb_cdc_write_available()) @@ -498,13 +538,30 @@ void mcu_usb_flush(void) #ifdef MCU_HAS_UART +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} + void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) @@ -523,13 +580,30 @@ void mcu_uart_flush(void) #ifdef MCU_HAS_UART2 +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} + void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart2_flush(void) @@ -737,7 +811,16 @@ void mcu_dotasks() { uint8_t c = (uint8_t)tusb_cdc_read(); #if !defined(DETACH_USB_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } #else mcu_usb_rx_cb(c); #endif From 8784242a428ea2f01896b94e6f808233d5152301 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 17:55:26 +0100 Subject: [PATCH 138/168] Modified STM32F4 --- uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c | 110 +++++++++++++++++++--- 1 file changed, 96 insertions(+), 14 deletions(-) diff --git a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c index 41f7adc15..cceb5a376 100644 --- a/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c +++ b/uCNC/src/hal/mcus/stm32f4x/mcu_stm32f4x.c @@ -79,7 +79,9 @@ volatile bool stm32_global_isr_enabled; #ifndef UART_TX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_tx, UART_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart_rx, RX_BUFFER_SIZE); + void MCU_SERIAL_ISR(void) { __ATOMIC_FORCEON__ @@ -88,7 +90,16 @@ void MCU_SERIAL_ISR(void) { uint8_t c = COM_INREG; #if !defined(DETACH_UART_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart_rx)) = c; + BUFFER_STORE(uart_rx); + } #else mcu_uart_rx_cb(c); #endif @@ -97,13 +108,13 @@ void MCU_SERIAL_ISR(void) if ((COM_UART->SR & USART_SR_TXE) && (COM_UART->CR1 & USART_CR1_TXEIE)) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart)) + if (BUFFER_EMPTY(uart_tx)) { COM_UART->CR1 &= ~(USART_CR1_TXEIE); return; } uint8_t c; - BUFFER_DEQUEUE(uart, &c); + BUFFER_DEQUEUE(uart_tx, &c); COM_OUTREG = c; } } @@ -114,7 +125,9 @@ void MCU_SERIAL_ISR(void) #ifndef UART2_TX_BUFFER_SIZE #define UART2_TX_BUFFER_SIZE 64 #endif -DECL_BUFFER(uint8_t, uart2, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_tx, UART2_TX_BUFFER_SIZE); +DECL_BUFFER(uint8_t, uart2_rx, RX_BUFFER_SIZE); + void MCU_SERIAL2_ISR(void) { __ATOMIC_FORCEON__ @@ -123,7 +136,16 @@ void MCU_SERIAL2_ISR(void) { uint8_t c = COM2_INREG; #if !defined(DETACH_UART2_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(uart2_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(uart2_rx)) = c; + BUFFER_STORE(uart2_rx); + } #else mcu_uart2_rx_cb(c); #endif @@ -132,13 +154,13 @@ void MCU_SERIAL2_ISR(void) if ((COM2_UART->SR & USART_SR_TXE) && (COM2_UART->CR1 & USART_CR1_TXEIE)) { mcu_enable_global_isr(); - if (BUFFER_EMPTY(uart2)) + if (BUFFER_EMPTY(uart2_tx)) { COM2_UART->CR1 &= ~(USART_CR1_TXEIE); return; } uint8_t c; - BUFFER_DEQUEUE(uart2, &c); + BUFFER_DEQUEUE(uart2_tx, &c); COM2_OUTREG = c; } } @@ -482,6 +504,25 @@ void mcu_usart_init(void) } #ifdef MCU_HAS_USB +DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + +uint8_t mcu_usb_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(usb_rx, &c); + return c; +} + +uint8_t mcu_usb_available(void) +{ + return BUFFER_READ_AVAILABLE(usb_rx); +} + +void mcu_usb_clear(void) +{ + BUFFER_CLEAR(usb_rx); +} + void mcu_usb_putc(uint8_t c) { if (!tusb_cdc_write_available()) @@ -506,14 +547,30 @@ void mcu_usb_flush(void) #endif #ifdef MCU_HAS_UART +uint8_t mcu_uart_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart_rx, &c); + return c; +} + +uint8_t mcu_uart_available(void) +{ + return BUFFER_READ_AVAILABLE(uart_rx); +} + +void mcu_uart_clear(void) +{ + BUFFER_CLEAR(uart_rx); +} void mcu_uart_putc(uint8_t c) { - while (BUFFER_FULL(uart)) + while (BUFFER_FULL(uart_tx)) { mcu_uart_flush(); } - BUFFER_ENQUEUE(uart, &c); + BUFFER_ENQUEUE(uart_tx, &c); } void mcu_uart_flush(void) @@ -531,14 +588,30 @@ void mcu_uart_flush(void) #endif #ifdef MCU_HAS_UART2 +uint8_t mcu_uart2_getc(void) +{ + uint8_t c = 0; + BUFFER_DEQUEUE(uart2_rx, &c); + return c; +} + +uint8_t mcu_uart2_available(void) +{ + return BUFFER_READ_AVAILABLE(uart2_rx); +} + +void mcu_uart2_clear(void) +{ + BUFFER_CLEAR(uart2_rx); +} void mcu_uart2_putc(uint8_t c) { - while (BUFFER_FULL(uart2)) + while (BUFFER_FULL(uart2_tx)) { mcu_uart2_flush(); } - BUFFER_ENQUEUE(uart2, &c); + BUFFER_ENQUEUE(uart2_tx, &c); } void mcu_uart2_flush(void) @@ -646,7 +719,7 @@ uint8_t mcu_get_servo(uint8_t servo) void mcu_freq_to_clocks(float frequency, uint16_t *ticks, uint16_t *prescaller) { frequency = CLAMP((float)F_STEP_MIN, frequency, (float)F_STEP_MAX); - + // up and down counter (generates half the step rate at each event) uint32_t totalticks = (uint32_t)((float)(TIMER_CLOCK >> 1) / frequency); *prescaller = 1; @@ -731,7 +804,16 @@ void mcu_dotasks() { uint8_t c = (uint8_t)tusb_cdc_read(); #if !defined(DETACH_USB_FROM_MAIN_PROTOCOL) - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } #else mcu_usb_rx_cb(c); #endif From 42595a2f226492c6f3ea4298eba1f5fa072aa2cc Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 18:39:42 +0100 Subject: [PATCH 139/168] Update lpc176x_arduino.cpp --- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index 01f552088..08428989b 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -32,6 +32,11 @@ extern "C" { #include "../../../cnc.h" #ifdef USE_ARDUINO_CDC +#ifndef USB_TX_BUFFER_SIZE +#define USB_TX_BUFFER_SIZE 64 +#endif + + DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); void mcu_usb_dotasks(void) @@ -39,8 +44,8 @@ extern "C" MSC_RunDeferredCommands(); while (UsbSerial.available() > 0) { -#ifndef DETACH_USB_FROM_MAIN_PROTOCOL uint8_t c = (uint8_t)UsbSerial.read(); +#ifndef DETACH_USB_FROM_MAIN_PROTOCOL if (mcu_com_rx_cb(c)) { if (BUFFER_FULL(usb_rx)) @@ -53,7 +58,7 @@ extern "C" } #else - mcu_usb_rx_cb((uint8_t)UsbSerial.read()); + mcu_usb_rx_cb(c); #endif } } @@ -75,11 +80,6 @@ extern "C" UsbSerial.begin(BAUDRATE); } -#ifndef USB_TX_BUFFER_SIZE -#define USB_TX_BUFFER_SIZE 64 -#endif - DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); - void mcu_usb_flush(void) { From 98cba31929cc19e42703d938cb23de87b5181730 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 10 Oct 2023 19:17:53 +0100 Subject: [PATCH 140/168] fixed soft reset --- uCNC/src/cnc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 6c115064a..5566bfc28 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -150,7 +150,7 @@ void cnc_run(void) do { - if (!serial_available()) + if (serial_available()) { if (serial_getc() == EOL) { From dcd0adbcca31bee48e061a7443bbc0301f65a8e2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 11 Oct 2023 00:04:53 +0100 Subject: [PATCH 141/168] implementing multistream --- uCNC/src/cnc.c | 5 ++-- uCNC/src/hal/boards/rp2040/rp2040.ini | 2 ++ uCNC/src/interface/protocol.c | 10 +++++++- uCNC/src/interface/serial.c | 35 ++++++++++++++++++++++++--- 4 files changed, 46 insertions(+), 6 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 5566bfc28..fd1501ae8 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -610,6 +610,7 @@ void cnc_reset(void) #ifdef ENABLE_MAIN_LOOP_MODULES EVENT_INVOKE(cnc_reset, NULL); #endif + serial_broadcast(true); protocol_send_string(MSG_STARTUP); } @@ -1029,17 +1030,17 @@ static void cnc_io_dotasks(void) void cnc_run_startup_blocks(void) { - serial_broadcast(true); if (settings_check_startup_gcode(STARTUP_BLOCK0_ADDRESS_OFFSET)) { + serial_broadcast(true); serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); cnc_exec_cmd(); } if (settings_check_startup_gcode(STARTUP_BLOCK1_ADDRESS_OFFSET)) { + serial_broadcast(true); serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); cnc_exec_cmd(); } - serial_broadcast(false); serial_stream_change(NULL); } diff --git a/uCNC/src/hal/boards/rp2040/rp2040.ini b/uCNC/src/hal/boards/rp2040/rp2040.ini index edc918de7..057134d42 100644 --- a/uCNC/src/hal/boards/rp2040/rp2040.ini +++ b/uCNC/src/hal/boards/rp2040/rp2040.ini @@ -16,6 +16,8 @@ board_build.mcu = rp2040 board_build.f_cpu = 133000000L ; lib_deps = adafruit/Adafruit TinyUSB Library@^2.0.3 ; build_flags = -DUSE_TINYUSB +debug_tool = cmsis-dap +upload_port = cmsis-dap [env:rpi_pico] extends = common_rp2040 diff --git a/uCNC/src/interface/protocol.c b/uCNC/src/interface/protocol.c index 27a4f8208..7b247666a 100644 --- a/uCNC/src/interface/protocol.c +++ b/uCNC/src/interface/protocol.c @@ -48,6 +48,7 @@ WEAK_EVENT_HANDLER(protocol_send_gcode_modes) static void protocol_send_newline(void) { protocol_send_string(MSG_EOL); + serial_broadcast(false); } void protocol_send_ok(void) @@ -65,6 +66,7 @@ void protocol_send_error(uint8_t error) void protocol_send_alarm(int8_t alarm) { + serial_broadcast(true); protocol_send_string(MSG_ALARM); serial_print_int(alarm); protocol_send_newline(); @@ -82,9 +84,11 @@ void protocol_send_string(const char *__s) void protocol_send_feedback(const char *__s) { + serial_broadcast(true); protocol_send_string(MSG_START); protocol_send_string(__s); - protocol_send_string(MSG_END); + serial_putc(']'); + protocol_send_newline(); } void protocol_send_ip(uint32_t ip) @@ -201,6 +205,8 @@ void protocol_send_status(void) return; } + serial_broadcast(true); + float axis[MAX(AXIS_COUNT, 3)]; int32_t steppos[AXIS_TO_STEPPERS]; @@ -495,6 +501,8 @@ void protocol_send_gcode_modes(void) parser_get_modes(modalgroups, &feed, &spindle, &coolant); + serial_broadcast(true); + protocol_send_string(__romstr__("[GC:")); protocol_send_parser_modalstate('G', modalgroups[0], modalgroups[12]); diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 06a254d8b..5a25843de 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -83,9 +83,10 @@ void serial_init(void) #if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) serial_stream_register(&bt_serial_stream); #endif -current_stream = serial_stream; + + serial_stream_change(serial_stream); #else -serial_stream_change(NULL); + serial_stream_change(NULL); #endif } @@ -129,6 +130,7 @@ void serial_stream_change(serial_stream_t *stream) return; } + // starts by the prioritary and test one by one until one that as characters available is found current_stream = current_stream->next; if (!current_stream) @@ -174,7 +176,8 @@ static FORCEINLINE uint8_t _serial_peek(void) ; peek = stream_getc(); // prevents null char reading from eeprom - if(!peek) { + if (!peek) + { peek = '\n'; } serial_peek_buffer = peek; @@ -198,12 +201,38 @@ uint8_t serial_peek(void) uint8_t serial_available(void) { +#ifndef DISABLE_MULTISTREAM_SERIAL + if (!stream_available) + { + // if undef allow to continue + return 1; + } + + uint8_t count = stream_available(); + if (!count) + { + serial_stream_t *p = serial_stream; + while (p) + { + if(p->stream_available()){ + serial_stream_change(p); + break; + } + p = p->next; + } + + count = stream_available(); + } + + return count; +#else if (!stream_available) { // if undef allow to continue return 1; } return stream_available(); +#endif } uint8_t serial_freebytes(void) From 85c4b5db15df0449dd36f735e0b3d0caa33a29cf Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 11 Oct 2023 10:04:56 +0100 Subject: [PATCH 142/168] multistream working --- uCNC/src/cnc.c | 7 +++++-- uCNC/src/core/parser.c | 1 + uCNC/src/hal/boards/stm32/stm32.ini | 2 +- uCNC/src/interface/serial.c | 21 +++++++-------------- 4 files changed, 14 insertions(+), 17 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index fd1501ae8..cd62ac3f0 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -1030,17 +1030,20 @@ static void cnc_io_dotasks(void) void cnc_run_startup_blocks(void) { + serial_broadcast(true); if (settings_check_startup_gcode(STARTUP_BLOCK0_ADDRESS_OFFSET)) { - serial_broadcast(true); serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); cnc_exec_cmd(); } + + serial_broadcast(true); if (settings_check_startup_gcode(STARTUP_BLOCK1_ADDRESS_OFFSET)) { - serial_broadcast(true); serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); cnc_exec_cmd(); } + + // reset streams serial_stream_change(NULL); } diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 6df0bfa48..99508ba67 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -461,6 +461,7 @@ static uint8_t parser_grbl_command(void) } serial_broadcast(false); + // reset streams serial_stream_change(NULL); if (error != STATUS_OK) diff --git a/uCNC/src/hal/boards/stm32/stm32.ini b/uCNC/src/hal/boards/stm32/stm32.ini index 0ee7cea08..aa5691a5a 100644 --- a/uCNC/src/hal/boards/stm32/stm32.ini +++ b/uCNC/src/hal/boards/stm32/stm32.ini @@ -5,7 +5,7 @@ [common_stm32] platform = ststm32 ; debug with st-link -upload_protocol = dfu +upload_protocol = cmsis-dap debug_tool = cmsis-dap platform_packages = platformio/tool-openocd debug_build_flags = -Og -g3 -ggdb3 -gdwarf-2 diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 5a25843de..b8a9f228c 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -82,12 +82,10 @@ void serial_init(void) #endif #if defined(MCU_HAS_BLUETOOTH) && !defined(DETACH_BLUETOOTH_FROM_MAIN_PROTOCOL) serial_stream_register(&bt_serial_stream); +#endif #endif - serial_stream_change(serial_stream); -#else serial_stream_change(NULL); -#endif } #ifndef DISABLE_MULTISTREAM_SERIAL @@ -131,12 +129,7 @@ void serial_stream_change(serial_stream_t *stream) } // starts by the prioritary and test one by one until one that as characters available is found - current_stream = current_stream->next; - - if (!current_stream) - { - current_stream = serial_stream; - } + current_stream = serial_stream; #else stream_getc = mcu_getc; stream_available = mcu_available; @@ -208,20 +201,20 @@ uint8_t serial_available(void) return 1; } - uint8_t count = stream_available(); + uint8_t count = (!stream_available) ? 0 : stream_available(); if (!count) { serial_stream_t *p = serial_stream; while (p) { - if(p->stream_available()){ + count = (!p->stream_available) ? 0 : p->stream_available(); + if (count) + { serial_stream_change(p); - break; + return count; } p = p->next; } - - count = stream_available(); } return count; From 0d6a82b45e2316597d6695e56ebfd08857b86ccc Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 11 Oct 2023 12:23:32 +0100 Subject: [PATCH 143/168] System menu stream integration --- uCNC/src/interface/grbl_interface.h | 1 + uCNC/src/modules/language/language_en.h | 1 + uCNC/src/modules/system_menu.c | 212 +++++++++++++----------- uCNC/src/modules/system_menu.h | 2 + 4 files changed, 118 insertions(+), 98 deletions(-) diff --git a/uCNC/src/interface/grbl_interface.h b/uCNC/src/interface/grbl_interface.h index 80d5e87bc..a87aa5c74 100644 --- a/uCNC/src/interface/grbl_interface.h +++ b/uCNC/src/interface/grbl_interface.h @@ -106,6 +106,7 @@ extern "C" #define STATUS_TOOL_FAILURE 55 #define STATUS_INVALID_PLANE_SELECTED 56 #define STATUS_HARDLIMITS_DISABLED 57 +#define STATUS_STREAM_FAILED 253 #define STATUS_GCODE_EXTENDED_UNSUPPORTED 254 // deprecated #define STATUS_CRITICAL_FAIL 255 diff --git a/uCNC/src/modules/language/language_en.h b/uCNC/src/modules/language/language_en.h index 4cf773cee..2dc82a79c 100644 --- a/uCNC/src/modules/language/language_en.h +++ b/uCNC/src/modules/language/language_en.h @@ -61,6 +61,7 @@ extern "C" #define STR_TOOL_100 "Tool 100%:" #define STR_RT_CMD_SENT "RT command sent" #define STR_CMD_SENT "Command sent" +#define STR_CMD_NOTSENT "ERROR\nCommand not sent" #define STR_SETTINGS_LOADED "Settings loaded" #define STR_SETTINGS_SAVED "Settings saved" #define STR_SETTINGS_RESET "Settings reset" diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 9dc7a5900..41fe0ad66 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -86,169 +86,169 @@ DECL_MODULE(system_menu) DECL_MENU(1, 0, STR_MAIN_MENU); // main menu entries - DECL_MENU_ACTION(1, hold, (uint8_t*)STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); - DECL_MENU_ACTION(1, resume, (uint8_t*)STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); - DECL_MENU_ACTION(1, unlock, (uint8_t*)STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); - DECL_MENU_ACTION(1, home, (uint8_t*)STR_HOME, system_menu_action_serial_cmd, "$H\r"); - DECL_MENU_GOTO(1, jog, (uint8_t*)STR_JOG, CONST_VARG(7)); - DECL_MENU_GOTO(1, overrides, (uint8_t*)STR_OVERRIDES, CONST_VARG(8)); - DECL_MENU_GOTO(1, settings, (uint8_t*)STR_SETTINGS, CONST_VARG(2)); + DECL_MENU_ACTION(1, hold, (uint8_t *)STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); + DECL_MENU_ACTION(1, resume, (uint8_t *)STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); + DECL_MENU_ACTION(1, unlock, (uint8_t *)STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); + DECL_MENU_ACTION(1, home, (uint8_t *)STR_HOME, system_menu_action_serial_cmd, "$H\r"); + DECL_MENU_GOTO(1, jog, (uint8_t *)STR_JOG, CONST_VARG(7)); + DECL_MENU_GOTO(1, overrides, (uint8_t *)STR_OVERRIDES, CONST_VARG(8)); + DECL_MENU_GOTO(1, settings, (uint8_t *)STR_SETTINGS, CONST_VARG(2)); DECL_MENU(8, 1, STR_OVERRIDES); - DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, (uint8_t*)STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); - DECL_MENU_ACTION(8, ovf_100, (uint8_t*)STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, (uint8_t *)STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); + DECL_MENU_ACTION(8, ovf_100, (uint8_t *)STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); #if (TOOL_COUNT > 0) - DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, (uint8_t*)STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, (uint8_t *)STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); #endif - DECL_MENU_ACTION(8, ovt_100, (uint8_t*)STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); + DECL_MENU_ACTION(8, ovt_100, (uint8_t *)STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); // append Jog menu // default initial distance DECL_MENU(7, 1, STR_JOG); - DECL_MENU_ENTRY(7, jogx, (uint8_t*)STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); + DECL_MENU_ENTRY(7, jogx, (uint8_t *)STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); #if (AXIS_COUNT > 1) - DECL_MENU_ENTRY(7, jogy, (uint8_t*)STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); + DECL_MENU_ENTRY(7, jogy, (uint8_t *)STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); #endif #if (AXIS_COUNT > 2) - DECL_MENU_ENTRY(7, jogz, (uint8_t*)STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); + DECL_MENU_ENTRY(7, jogz, (uint8_t *)STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); #endif #if (AXIS_COUNT > 3) - DECL_MENU_ENTRY(7, joga, (uint8_t*)STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); + DECL_MENU_ENTRY(7, joga, (uint8_t *)STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); #endif #if (AXIS_COUNT > 4) - DECL_MENU_ENTRY(7, jogb, (uint8_t*)STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); + DECL_MENU_ENTRY(7, jogb, (uint8_t *)STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); #endif #if (AXIS_COUNT > 5) - DECL_MENU_ENTRY(7, jogc, (uint8_t*)STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); + DECL_MENU_ENTRY(7, jogc, (uint8_t *)STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); #endif - DECL_MENU_VAR(7, jogdist, (uint8_t*)STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); - DECL_MENU_VAR(7, jogfeed, (uint8_t*)STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogdist, (uint8_t *)STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogfeed, (uint8_t *)STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); // append settings menu DECL_MENU(2, 1, STR_SETTINGS); // settings menu - DECL_MENU_GOTO(2, ioconfig, (uint8_t*)STR_IO_CONFIG, CONST_VARG(6)); - DECL_MENU_GOTO(2, gohome, (uint8_t*)STR_HOMING, CONST_VARG(3)); + DECL_MENU_GOTO(2, ioconfig, (uint8_t *)STR_IO_CONFIG, CONST_VARG(6)); + DECL_MENU_GOTO(2, gohome, (uint8_t *)STR_HOMING, CONST_VARG(3)); #if (AXIS_COUNT > 0) - DECL_MENU_GOTO(2, goaxis, (uint8_t*)STR_AXIS, CONST_VARG(4)); + DECL_MENU_GOTO(2, goaxis, (uint8_t *)STR_AXIS, CONST_VARG(4)); #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU_GOTO(2, kinemats, (uint8_t*)STR_KINEMATICS, CONST_VARG(5)); + DECL_MENU_GOTO(2, kinemats, (uint8_t *)STR_KINEMATICS, CONST_VARG(5)); #endif - DECL_MENU_GOTO(2, other_config, (uint8_t*)STR_OTHER, CONST_VARG(9)); - DECL_MENU_ACTION(2, set_load, (uint8_t*)STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); - DECL_MENU_ACTION(2, set_save, (uint8_t*)STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); - DECL_MENU_ACTION(2, set_reset, (uint8_t*)STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); + DECL_MENU_GOTO(2, other_config, (uint8_t *)STR_OTHER, CONST_VARG(9)); + DECL_MENU_ACTION(2, set_load, (uint8_t *)STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); + DECL_MENU_ACTION(2, set_save, (uint8_t *)STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); + DECL_MENU_ACTION(2, set_reset, (uint8_t *)STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); DECL_MENU(9, 2, STR_OTHER); - DECL_MENU_VAR(9, s11, (uint8_t*)STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(9, s12, (uint8_t*)STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s11, (uint8_t *)STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s12, (uint8_t *)STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); DECL_MENU(6, 2, STR_IO_CONFIG); - DECL_MENU_VAR(6, s2, (uint8_t*)STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s3, (uint8_t*)STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s4, (uint8_t*)STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s5, (uint8_t*)STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s6, (uint8_t*)STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(6, s7, (uint8_t*)STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s2, (uint8_t *)STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s3, (uint8_t *)STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s4, (uint8_t *)STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s5, (uint8_t *)STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s6, (uint8_t *)STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(6, s7, (uint8_t *)STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); #if ENCODERS > 0 - DECL_MENU_VAR(6, s8, (uint8_t*)STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s9, (uint8_t*)STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s8, (uint8_t *)STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s9, (uint8_t *)STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); #endif // append homing settings menu DECL_MENU(3, 2, STR_HOMING); - DECL_MENU_VAR(3, s20, (uint8_t*)STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s21, (uint8_t*)STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s22, (uint8_t*)STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s23, (uint8_t*)STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s24, (uint8_t*)STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s25, (uint8_t*)STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s26, (uint8_t*)STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s27, (uint8_t*)STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s20, (uint8_t *)STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s21, (uint8_t *)STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s22, (uint8_t *)STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s23, (uint8_t *)STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s24, (uint8_t *)STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s25, (uint8_t *)STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s26, (uint8_t *)STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s27, (uint8_t *)STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); #if (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(3, s28, (uint8_t*)STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, (uint8_t *)STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_SCARA) - DECL_MENU_VAR(3, s28, (uint8_t*)STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s29, (uint8_t*)STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, (uint8_t *)STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s29, (uint8_t *)STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); #endif // append steppers settings menu DECL_MENU(4, 2, STR_AXIS); - DECL_MENU_VAR(4, s100, (uint8_t*)STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s110, (uint8_t*)STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s120, (uint8_t*)STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s130, (uint8_t*)STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s100, (uint8_t *)STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s110, (uint8_t *)STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s120, (uint8_t *)STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s130, (uint8_t *)STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s140, (uint8_t*)STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s140, (uint8_t *)STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); #endif #if (AXIS_COUNT > 1) - DECL_MENU_VAR(4, s101, (uint8_t*)STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s111, (uint8_t*)STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s121, (uint8_t*)STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s131, (uint8_t*)STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s101, (uint8_t *)STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s111, (uint8_t *)STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s121, (uint8_t *)STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s131, (uint8_t *)STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s141, (uint8_t*)STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s141, (uint8_t *)STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 2) - DECL_MENU_VAR(4, s102, (uint8_t*)STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s112, (uint8_t*)STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s122, (uint8_t*)STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s132, (uint8_t*)STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s102, (uint8_t *)STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s112, (uint8_t *)STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s122, (uint8_t *)STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s132, (uint8_t *)STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s142, (uint8_t*)STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s142, (uint8_t *)STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 3) - DECL_MENU_VAR(4, s103, (uint8_t*)STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s113, (uint8_t*)STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s123, (uint8_t*)STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s133, (uint8_t*)STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s103, (uint8_t *)STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s113, (uint8_t *)STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s123, (uint8_t *)STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s133, (uint8_t *)STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s143, (uint8_t*)STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s143, (uint8_t *)STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 4) - DECL_MENU_VAR(4, s104, (uint8_t*)STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s114, (uint8_t*)STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s124, (uint8_t*)STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s134, (uint8_t*)STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s104, (uint8_t *)STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s114, (uint8_t *)STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s124, (uint8_t *)STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s134, (uint8_t *)STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s144, (uint8_t*)STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s144, (uint8_t *)STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 5) - DECL_MENU_VAR(4, s105, (uint8_t*)STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s115, (uint8_t*)STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s125, (uint8_t*)STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s135, (uint8_t*)STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s105, (uint8_t *)STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s115, (uint8_t *)STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s125, (uint8_t *)STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s135, (uint8_t *)STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMENSATION - DECL_MENU_VAR(4, s145, (uint8_t*)STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s145, (uint8_t *)STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); #endif #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU(5, 2, (uint8_t*)STR_KINEMATICS); + DECL_MENU(5, 2, (uint8_t *)STR_KINEMATICS); #ifdef ENABLE_SKEW_COMPENSATION - DECL_MENU_VAR(5, s37, (uint8_t*)STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s37, (uint8_t *)STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); #ifndef SKEW_COMPENSATION_XY_ONLY - DECL_MENU_VAR(5, s38, (uint8_t*)STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s39, (uint8_t*)STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s38, (uint8_t *)STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s39, (uint8_t *)STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); #endif #endif #if (KINEMATIC == KINEMATIC_LINEAR_DELTA) - DECL_MENU_VAR(5, s106, (uint8_t*)STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, (uint8_t*)STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, (uint8_t *)STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, (uint8_t *)STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(5, s106, (uint8_t*)STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, (uint8_t*)STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s108, (uint8_t*)STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s109, (uint8_t*)STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s28, (uint8_t*)STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, (uint8_t *)STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, (uint8_t *)STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s108, (uint8_t *)STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s109, (uint8_t *)STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s28, (uint8_t *)STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #endif #endif @@ -437,7 +437,7 @@ void system_menu_render(void) if (!item_index) { uint8_t buff[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy((char*)buff, (const char*)menu_page->page_label); + rom_strcpy((char *)buff, (const char *)menu_page->page_label); system_menu_render_header(buff); } @@ -648,7 +648,7 @@ bool system_menu_action_rt_cmd(uint8_t action, system_menu_item_t *item) { cnc_call_rt_command((uint8_t)VARG_CONST(item->action_arg)); uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy((char*)buffer, __romstr__(STR_RT_CMD_SENT)); + rom_strcpy((char *)buffer, __romstr__(STR_RT_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); return true; } @@ -661,9 +661,15 @@ bool system_menu_action_serial_cmd(uint8_t action, system_menu_item_t *item) { if (serial_freebytes() > 20) { - //serial_inject_cmd((const uint8_t *)item->action_arg); uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - rom_strcpy((char*)buffer, __romstr__(STR_CMD_SENT)); + if (system_menu_send_cmd((const uint8_t *)item->action_arg) == STATUS_OK) + { + rom_strcpy((char *)buffer, __romstr__(STR_CMD_SENT)); + } + else{ + rom_strcpy((char *)buffer, __romstr__(STR_CMD_NOTSENT)); + } + system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); } return true; @@ -743,7 +749,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) { uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); - rom_strcpy((char*)buffer, __romstr__("$J=G91")); + rom_strcpy((char *)buffer, __romstr__("$J=G91")); uint8_t *ptr = buffer; // search for the end of string while (*++ptr) @@ -770,7 +776,11 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) while (*++ptr) ; *ptr++ = '\r'; - //serial_inject_cmd(buffer); + if (system_menu_send_cmd(buffer) != STATUS_OK) + { + rom_strcpy((char *)buffer, __romstr__(STR_CMD_NOTSENT)); + system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); + } } return true; } @@ -788,15 +798,15 @@ static bool system_menu_action_settings_cmd(uint8_t action, system_menu_item_t * { case 0: settings_init(); - rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_LOADED)); + rom_strcpy((char *)buffer, __romstr__(STR_SETTINGS_LOADED)); break; case 1: settings_save(SETTINGS_ADDRESS_OFFSET, (uint8_t *)&g_settings, (uint8_t)sizeof(settings_t)); - rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_SAVED)); + rom_strcpy((char *)buffer, __romstr__(STR_SETTINGS_SAVED)); break; case 2: settings_reset(false); - rom_strcpy((char*)buffer, __romstr__(STR_SETTINGS_RESET)); + rom_strcpy((char *)buffer, __romstr__(STR_SETTINGS_RESET)); break; default: break; @@ -1082,6 +1092,12 @@ void __attribute__((weak)) system_menu_render_modal_popup(const uint8_t *__s) // renders the modal popup message } +// this needs to be implemented using a serial stream +uint8_t __attribute__((weak)) system_menu_send_cmd(const uint8_t *__s) +{ + return STATUS_STREAM_FAILED; +} + /** * Helper µCNC render callbacks * **/ diff --git a/uCNC/src/modules/system_menu.h b/uCNC/src/modules/system_menu.h index 3050a5579..cd37b4dee 100644 --- a/uCNC/src/modules/system_menu.h +++ b/uCNC/src/modules/system_menu.h @@ -188,6 +188,8 @@ extern "C" void system_menu_render_idle(void); void system_menu_render_alarm(void); void system_menu_render_modal_popup(const uint8_t *__s); + // this needs to be implemented using a serial stream + uint8_t system_menu_send_cmd(const uint8_t *__s); /** * Helper µCNC action callbacks From fc38d2bf25ecb7543ffc6c45fe9688475d99c4b8 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 11 Oct 2023 15:55:16 +0100 Subject: [PATCH 144/168] added readonly stream function - added readonly stream function (used for modules that only send commands) --- uCNC/src/interface/serial.c | 28 ++++++++++++++++++++++------ uCNC/src/interface/serial.h | 15 ++++++++------- 2 files changed, 30 insertions(+), 13 deletions(-) diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index b8a9f228c..5d0d7fc46 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -30,9 +30,9 @@ #include #include "../cnc.h" -static uint8_t (*stream_getc)(void); -uint8_t (*stream_available)(void); -void (*stream_clear)(void); +static stream_getc_cb stream_getc; +static stream_available_cb stream_available; +static stream_clear_cb stream_clear; #ifndef DISABLE_MULTISTREAM_SERIAL static serial_stream_t *serial_stream; @@ -137,6 +137,13 @@ void serial_stream_change(serial_stream_t *stream) #endif } +void serial_stream_readonly(stream_getc_cb getc_cb, stream_available_cb available_cb, stream_clear_cb clear_cb) +{ + stream_getc = getc_cb; + stream_available = available_cb; + stream_clear = clear_cb; +} + static uint16_t stream_eeprom_address; static uint8_t stream_eeprom_getc(void) { @@ -146,8 +153,7 @@ static uint8_t stream_eeprom_getc(void) void serial_stream_eeprom(uint16_t address) { stream_eeprom_address = address; - stream_getc = &stream_eeprom_getc; - stream_available = NULL; + serial_stream_readonly(&stream_eeprom_getc, NULL, NULL); } uint8_t serial_getc(void) @@ -167,6 +173,13 @@ static FORCEINLINE uint8_t _serial_peek(void) while (!serial_available()) ; +#ifndef DISABLE_MULTISTREAM_SERIAL + if (!stream_getc) + { + // if getc not defined return overflow to force multiple overflow errors + return OVF; + } +#endif peek = stream_getc(); // prevents null char reading from eeprom if (!peek) @@ -236,7 +249,10 @@ uint8_t serial_freebytes(void) void serial_clear(void) { #ifndef DISABLE_MULTISTREAM_SERIAL - current_stream->stream_clear(); + if (stream_clear) + { + stream_clear(); + } #else mcu_clear(); #endif diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index 1314cd3be..8ec827a7c 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -37,26 +37,27 @@ extern "C" #endif #define RX_BUFFER_SIZE (RX_BUFFER_CAPACITY + SAFEMARGIN) // buffer sizes -#define SERIAL_UART 0 -#define SERIAL_N0 1 -#define SERIAL_N1 2 + typedef uint8_t (*stream_getc_cb)(void); + typedef uint8_t (*stream_available_cb)(void); + typedef void (*stream_clear_cb)(void); typedef struct serial_stream_ { - uint8_t (*stream_getc)(void); - uint8_t (*stream_available)(void); - void (*stream_clear)(void); + stream_getc_cb stream_getc; + stream_available_cb stream_available; + stream_clear_cb stream_clear; void (*stream_putc)(uint8_t); void (*stream_flush)(void); struct serial_stream_ *next; } serial_stream_t; - #define DECL_SERIAL_STREAM(name, getc_cb, available_cb, clear_cb, putc_cb, flush_cb) serial_stream_t name = {&getc_cb, &available_cb, &clear_cb, &putc_cb, &flush_cb, NULL} +#define DECL_SERIAL_STREAM(name, getc_cb, available_cb, clear_cb, putc_cb, flush_cb) serial_stream_t name = {&getc_cb, &available_cb, &clear_cb, &putc_cb, &flush_cb, NULL} void serial_init(); void serial_stream_register(serial_stream_t *stream); void serial_stream_change(serial_stream_t *stream); + void serial_stream_readonly(stream_getc_cb getc_cb, stream_available_cb available_cb, stream_clear_cb clear_cb); void serial_stream_eeprom(uint16_t address); void serial_broadcast(bool enable); From bbba5066207869eaf99470bbc4c555cb13ac83d1 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Thu, 12 Oct 2023 18:00:29 +0100 Subject: [PATCH 145/168] multitream fixes - fixed module extension error - prevent infinite loop on serial_available wait - recoded USB on LPC176x - serial stream renaming --- uCNC/src/core/motion_control.c | 2 +- uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp | 91 ++++-------- uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c | 130 ++++++++++++++---- uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h | 2 +- uCNC/src/interface/serial.c | 33 +++-- uCNC/src/utils.h | 57 ++++---- 6 files changed, 175 insertions(+), 140 deletions(-) diff --git a/uCNC/src/core/motion_control.c b/uCNC/src/core/motion_control.c index d366fd45e..3b2edc8a8 100644 --- a/uCNC/src/core/motion_control.c +++ b/uCNC/src/core/motion_control.c @@ -705,7 +705,7 @@ uint8_t mc_home_axis(uint8_t axis_mask, uint8_t axis_limit) motion_data_t block_data = {0}; uint8_t limits_flags; #ifdef ENABLE_MOTION_CONTROL_MODULES - homing_status_t homing_status __attribute__((__cleanup__(mc_home_axis_finalize))) = {axis, axis_limit, STATUS_OK}; + homing_status_t homing_status __attribute__((__cleanup__(mc_home_axis_finalize))) = {axis_mask, axis_limit, STATUS_OK}; #endif #ifdef ENABLE_G39_H_MAPPING diff --git a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp index 08428989b..bf89c5d24 100644 --- a/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp +++ b/uCNC/src/hal/mcus/lpc176x/lpc176x_arduino.cpp @@ -27,43 +27,39 @@ #include #include #include +#include extern "C" { #include "../../../cnc.h" #ifdef USE_ARDUINO_CDC -#ifndef USB_TX_BUFFER_SIZE -#define USB_TX_BUFFER_SIZE 64 -#endif + void lpc176x_usb_dotasks(void) + { + MSC_RunDeferredCommands(); + } - DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); - DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + bool lpc176x_usb_available(void) + { + return (UsbSerial.available() > 0); + } - void mcu_usb_dotasks(void) + uint8_t lpc176x_usb_getc(void) { - MSC_RunDeferredCommands(); - while (UsbSerial.available() > 0) - { - uint8_t c = (uint8_t)UsbSerial.read(); -#ifndef DETACH_USB_FROM_MAIN_PROTOCOL - if (mcu_com_rx_cb(c)) - { - if (BUFFER_FULL(usb_rx)) - { - c = OVF; - } + return (uint8_t)UsbSerial.read(); + } - *(BUFFER_NEXT_FREE(usb_rx)) = c; - BUFFER_STORE(usb_rx); - } + void lpc176x_usb_putc(uint8_t c) + { + char a = (char)c; + UsbSerial.write(&a, 1); + } -#else - mcu_usb_rx_cb(c); -#endif - } + void lpc176x_usb_write(uint8_t* ptr, uint8_t len) + { + UsbSerial.write((char*)ptr, len); } - void mcu_usb_init(void) + void lpc176x_usb_init(void) { USB_Init(); // USB Initialization USB_Connect(false); // USB clear connection @@ -72,54 +68,13 @@ extern "C" while (!USB_Configuration && usb_timeout > mcu_millis()) { mcu_delay_us(50); - mcu_usb_dotasks(); + MSC_RunDeferredCommands(); #if ASSERT_PIN(ACTIVITY_LED) io_toggle_output(ACTIVITY_LED); // Flash quickly during USB initialization #endif } UsbSerial.begin(BAUDRATE); - } - - void mcu_usb_flush(void) - { - - while (!BUFFER_EMPTY(usb_tx)) - { - uint8_t tmp[USB_TX_BUFFER_SIZE]; - uint8_t r; - - BUFFER_READ(usb_tx, tmp, USB_TX_BUFFER_SIZE, r); -#ifdef MCU_HAS_USB - UsbSerial.write((char *)tmp, r); - UsbSerial.flushTX(); -#endif - } - } - - void mcu_usb_putc(uint8_t c) - { - while (BUFFER_FULL(usb_tx)) - { - mcu_usb_flush(); - } - BUFFER_ENQUEUE(usb_tx, &c); - } - - uint8_t mcu_usb_getc(void) - { - uint8_t c = 0; - BUFFER_DEQUEUE(usb_rx, &c); - return c; - } - - uint8_t mcu_usb_available(void) - { - return BUFFER_READ_AVAILABLE(usb_rx); - } - - void mcu_usb_clear(void) - { - BUFFER_CLEAR(usb_rx); +// // BUFFER_CLEAR(usb_rx); } #endif diff --git a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c index 2ea85907f..7b465f7f2 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c +++ b/uCNC/src/hal/mcus/lpc176x/mcu_lpc176x.c @@ -24,8 +24,12 @@ #ifdef MCU_HAS_USB #ifdef USE_ARDUINO_CDC -extern void mcu_usb_dotasks(void); -extern void mcu_usb_init(void); +extern void lpc176x_usb_dotasks(void); +extern bool lpc176x_usb_available(void); +extern uint8_t lpc176x_usb_getc(void); +extern void lpc176x_usb_putc(uint8_t c); +extern void lpc176x_usb_init(void); +extern void lpc176x_usb_write(uint8_t *ptr, uint8_t len); #else #include #endif @@ -36,7 +40,8 @@ extern void mcu_usb_init(void); * Increments every millisecond * Can count up to almost 50 days **/ -static volatile uint32_t mcu_runtime_ms; +// provided by the framework +extern volatile uint64_t _millis; volatile bool lpc_global_isr_enabled; // define the mcu internal servo variables @@ -172,10 +177,8 @@ void MCU_SERVO_ISR(void) void MCU_RTC_ISR(void) { mcu_disable_global_isr(); - uint32_t millis = mcu_runtime_ms; - millis++; - mcu_runtime_ms = millis; - mcu_rtc_cb(millis); + _millis++; + mcu_rtc_cb((uint32_t)_millis); mcu_enable_global_isr(); } @@ -354,17 +357,6 @@ void MCU_COM2_ISR(void) } #endif -#ifdef MCU_HAS_USB -#ifndef USE_ARDUINO_CDC -void USB_IRQHandler(void) -{ - mcu_disable_global_isr(); - tusb_cdc_isr_handler(); - mcu_enable_global_isr(); -} -#endif -#endif - void mcu_usart_init(void) { #ifdef MCU_HAS_UART @@ -415,7 +407,7 @@ void mcu_usart_init(void) #ifdef MCU_HAS_USB #ifdef USE_ARDUINO_CDC - mcu_usb_init(); + lpc176x_usb_init(); #else // // // configure USB as Virtual COM port LPC_PINCON->PINSEL1 &= ~((3 << 26) | (3 << 28)); /* P0.29 D+, P0.30 D- */ @@ -803,8 +795,7 @@ void mcu_stop_itp_isr(void) * */ uint32_t mcu_millis() { - uint32_t val = mcu_runtime_ms; - return val; + return (uint32_t)_millis; } /** @@ -813,7 +804,7 @@ uint32_t mcu_millis() * */ uint32_t mcu_micros() { - return ((mcu_runtime_ms * 1000) + ((SysTick->LOAD - SysTick->VAL) / (F_CPU / 1000000))); + return ((mcu_millis() * 1000) + ((SysTick->LOAD - SysTick->VAL) / (F_CPU / 1000000))); } #ifndef mcu_delay_us @@ -827,7 +818,16 @@ void mcu_delay_us(uint16_t delay) #endif #ifdef MCU_HAS_USB +DECL_BUFFER(uint8_t, usb_rx, RX_BUFFER_SIZE); + #ifndef USE_ARDUINO_CDC +void USB_IRQHandler(void) +{ + mcu_disable_global_isr(); + tusb_cdc_isr_handler(); + mcu_enable_global_isr(); +} + void mcu_usb_putc(uint8_t c) { if (!tusb_cdc_write_available()) @@ -849,7 +849,57 @@ void mcu_usb_flush(void) } } } +#else +#ifndef USB_TX_BUFFER_SIZE +#define USB_TX_BUFFER_SIZE 64 +#endif + +DECL_BUFFER(uint8_t, usb_tx, USB_TX_BUFFER_SIZE); +void mcu_usb_flush(void) +{ + while (!BUFFER_EMPTY(usb_tx)) + { + // use this of char is not 8bits + // uint8_t c = 0; + // BUFFER_DEQUEUE(usb_tx, &c); + // lpc176x_usb_putc(c); + + // bulk sending + uint8_t tmp[USB_TX_BUFFER_SIZE]; + uint8_t r; + + BUFFER_READ(usb_tx, tmp, USB_TX_BUFFER_SIZE, r); + lpc176x_usb_write(tmp, r); + } +} + +void mcu_usb_putc(uint8_t c) +{ + while (BUFFER_FULL(usb_tx)) + { + mcu_usb_flush(); + } + BUFFER_ENQUEUE(usb_tx, &c); +} #endif + +uint8_t mcu_usb_getc(void) +{ + char c = BUFFER_PEEK(usb_rx); + BUFFER_REMOVE(usb_rx); + return (uint8_t)c; +} + +uint8_t mcu_usb_available(void) +{ + return BUFFER_READ_AVAILABLE(usb_rx); +} + +void mcu_usb_clear(void) +{ + BUFFER_CLEAR(usb_rx); +} + #endif /** @@ -861,8 +911,25 @@ void mcu_dotasks() { #ifdef MCU_HAS_USB #ifdef USE_ARDUINO_CDC - mcu_usb_flush(); - mcu_usb_dotasks(); + lpc176x_usb_dotasks(); +#ifndef DETACH_USB_FROM_MAIN_PROTOCOL + while (lpc176x_usb_available()) + { + uint8_t c = lpc176x_usb_getc(); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } + } +#else + mcu_usb_rx_cb(c); +#endif #else tusb_cdc_task(); // tinyusb device task @@ -870,7 +937,16 @@ void mcu_dotasks() { uint8_t c = (uint8_t)tusb_cdc_read(); #ifndef DETACH_USB_FROM_MAIN_PROTOCOL - mcu_com_rx_cb(c); + if (mcu_com_rx_cb(c)) + { + if (BUFFER_FULL(usb_rx)) + { + c = OVF; + } + + *(BUFFER_NEXT_FREE(usb_rx)) = c; + BUFFER_STORE(usb_rx); + } #else mcu_usb_rx_cb(c); #endif @@ -932,10 +1008,6 @@ static void mcu_i2c_write_stop(bool *stop) } } -static void mcu_i2c_reset() -{ -} - static uint8_t mcu_i2c_write(uint8_t data, bool send_start, bool send_stop) { bool stop __attribute__((__cleanup__(mcu_i2c_write_stop))) = send_stop; diff --git a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h index dc1de7871..ed64b3fed 100644 --- a/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h +++ b/uCNC/src/hal/mcus/lpc176x/mcumap_lpc176x.h @@ -60,7 +60,7 @@ extern "C" // defines special mcu to access flash strings and arrays #define __rom__ #define __romstr__ -#define __romarr__ const uint8_t +#define __romarr__ const char #define rom_strptr * #define rom_strcpy strcpy #define rom_strncpy strncpy diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 5d0d7fc46..479e846b0 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -35,7 +35,7 @@ static stream_available_cb stream_available; static stream_clear_cb stream_clear; #ifndef DISABLE_MULTISTREAM_SERIAL -static serial_stream_t *serial_stream; +static serial_stream_t *default_stream; static serial_stream_t *current_stream; #if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) @@ -65,7 +65,7 @@ static uint8_t serial_peek_buffer; void serial_init(void) { #ifdef FORCE_GLOBALS_TO_0 - serial_stream = NULL; + default_stream = NULL; #endif #ifndef DISABLE_MULTISTREAM_SERIAL #if defined(MCU_HAS_UART) && !defined(DETACH_UART_FROM_MAIN_PROTOCOL) @@ -91,14 +91,14 @@ void serial_init(void) #ifndef DISABLE_MULTISTREAM_SERIAL void serial_stream_register(serial_stream_t *stream) { - if (serial_stream == NULL) + if (default_stream == NULL) { - serial_stream = stream; - serial_stream->next = NULL; + default_stream = stream; + default_stream->next = NULL; } else { - serial_stream_t *p = serial_stream; + serial_stream_t *p = default_stream; while (p->next != NULL) { p = p->next; @@ -129,7 +129,7 @@ void serial_stream_change(serial_stream_t *stream) } // starts by the prioritary and test one by one until one that as characters available is found - current_stream = serial_stream; + current_stream = default_stream; #else stream_getc = mcu_getc; stream_available = mcu_available; @@ -172,7 +172,10 @@ static FORCEINLINE uint8_t _serial_peek(void) } while (!serial_available()) - ; + { + mcu_dotasks(); + } + #ifndef DISABLE_MULTISTREAM_SERIAL if (!stream_getc) { @@ -208,19 +211,19 @@ uint8_t serial_peek(void) uint8_t serial_available(void) { #ifndef DISABLE_MULTISTREAM_SERIAL - if (!stream_available) + if (stream_available == NULL) { // if undef allow to continue return 1; } - uint8_t count = (!stream_available) ? 0 : stream_available(); + uint8_t count = stream_available(); if (!count) { - serial_stream_t *p = serial_stream; - while (p) + serial_stream_t *p = default_stream; + while (p != NULL) { - count = (!p->stream_available) ? 0 : p->stream_available(); + count = (!(p->stream_available)) ? 0 : p->stream_available(); if (count) { serial_stream_change(p); @@ -279,7 +282,7 @@ void serial_putc(uint8_t c) } else { - serial_stream_t *p = serial_stream; + serial_stream_t *p = default_stream; while (p) { p->stream_putc(c); @@ -309,7 +312,7 @@ void serial_flush(void) } else { - serial_stream_t *p = serial_stream; + serial_stream_t *p = default_stream; while (p) { p->stream_flush(); diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index 91c571160..fa0ab6f2d 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -245,28 +245,26 @@ extern "C" #define BUFFER_EMPTY(buffer) (!buffer.count) #define BUFFER_FULL(buffer) (buffer.count == buffer##_size) #define BUFFER_PEEK(buffer) (buffer##_bufferdata[buffer.tail]) -#define BUFFER_REMOVE(buffer) \ - { \ - uint8_t count, tail; \ - __ATOMIC__ \ - { \ - tail = buffer.tail; \ - } \ - void *p = &buffer##_bufferdata[tail]; \ - if (!BUFFER_EMPTY(buffer)) \ - { \ - tail++; \ - if (tail >= buffer##_size) \ - { \ - tail = 0; \ - } \ - __ATOMIC__ \ - { \ - buffer.tail = tail; \ - buffer.count--; \ - } \ - } \ - p; \ +#define BUFFER_REMOVE(buffer) \ + { \ + uint8_t tail; \ + __ATOMIC__ \ + { \ + tail = buffer.tail; \ + } \ + if (!BUFFER_EMPTY(buffer)) \ + { \ + tail++; \ + if (tail >= buffer##_size) \ + { \ + tail = 0; \ + } \ + __ATOMIC__ \ + { \ + buffer.tail = tail; \ + buffer.count--; \ + } \ + } \ } #define BUFFER_DEQUEUE(buffer, ptr) \ @@ -292,7 +290,7 @@ extern "C" } \ } -#define BUFFER_STORE(buffer) \ +#define BUFFER_STORE(buffer) \ { \ if (!BUFFER_FULL(buffer)) \ { \ @@ -423,9 +421,16 @@ extern "C" } \ }) -#define BUFFER_CLEAR(buffer) ({__ATOMIC__{buffer##_bufferdata[0] = 0;buffer.tail = 0;buffer.head = 0;buffer.count = 0; \ - } \ - }) +#define BUFFER_CLEAR(buffer) \ + { \ + __ATOMIC__ \ + { \ + buffer##_bufferdata[0] = 0; \ + buffer.tail = 0; \ + buffer.head = 0; \ + buffer.count = 0; \ + } \ + } #ifdef __cplusplus } From ceb6d7a339d986acaee860f6b48cba22ffe7f0ff Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 13 Oct 2023 00:21:48 +0100 Subject: [PATCH 146/168] small fixes to utils and serial --- uCNC/src/interface/serial.h | 2 +- uCNC/src/utils.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index 8ec827a7c..d7d350e92 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -51,7 +51,7 @@ extern "C" struct serial_stream_ *next; } serial_stream_t; -#define DECL_SERIAL_STREAM(name, getc_cb, available_cb, clear_cb, putc_cb, flush_cb) serial_stream_t name = {&getc_cb, &available_cb, &clear_cb, &putc_cb, &flush_cb, NULL} +#define DECL_SERIAL_STREAM(name, getc_cb, available_cb, clear_cb, putc_cb, flush_cb) serial_stream_t name = {getc_cb, available_cb, clear_cb, putc_cb, flush_cb, NULL} void serial_init(); diff --git a/uCNC/src/utils.h b/uCNC/src/utils.h index fa0ab6f2d..f34000b99 100644 --- a/uCNC/src/utils.h +++ b/uCNC/src/utils.h @@ -247,7 +247,7 @@ extern "C" #define BUFFER_PEEK(buffer) (buffer##_bufferdata[buffer.tail]) #define BUFFER_REMOVE(buffer) \ { \ - uint8_t tail; \ + uint8_t tail; \ __ATOMIC__ \ { \ tail = buffer.tail; \ @@ -337,7 +337,6 @@ extern "C" #define BUFFER_NEXT_FREE(buffer) (&buffer##_bufferdata[buffer.head]) #define BUFFER_WRITE(buffer, ptr, len, written) ({ \ - written = 0; \ uint8_t count, head; \ __ATOMIC__ \ { \ @@ -345,6 +344,7 @@ extern "C" count = buffer.count; \ } \ count = MIN(buffer##_size - count, len); \ + written = 0; \ if (count) \ { \ uint8_t avail = (buffer##_size - head); \ @@ -378,7 +378,6 @@ extern "C" }) #define BUFFER_READ(buffer, ptr, len, read) ({ \ - read = 0; \ uint8_t count, tail; \ __ATOMIC__ \ { \ @@ -389,6 +388,7 @@ extern "C" { \ count = len; \ } \ + read = 0; \ if (count) \ { \ uint8_t avail = buffer##_size - tail; \ From d4f363f7fb5625b7f2d81df308744b2b4c8967a8 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 13 Oct 2023 00:36:43 +0100 Subject: [PATCH 147/168] Update grbl_interface.h --- uCNC/src/interface/grbl_interface.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/interface/grbl_interface.h b/uCNC/src/interface/grbl_interface.h index a87aa5c74..4f0f6460d 100644 --- a/uCNC/src/interface/grbl_interface.h +++ b/uCNC/src/interface/grbl_interface.h @@ -106,7 +106,7 @@ extern "C" #define STATUS_TOOL_FAILURE 55 #define STATUS_INVALID_PLANE_SELECTED 56 #define STATUS_HARDLIMITS_DISABLED 57 -#define STATUS_STREAM_FAILED 253 +#define STATUS_STREAM_FAILED 58 #define STATUS_GCODE_EXTENDED_UNSUPPORTED 254 // deprecated #define STATUS_CRITICAL_FAIL 255 From 3923f21b037084283d5a7e8951eab074e1c3308b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 13 Oct 2023 07:46:17 +0100 Subject: [PATCH 148/168] recoded string functions to char instead of uint8 --- uCNC/src/interface/serial.c | 18 +-- uCNC/src/interface/serial.h | 10 +- uCNC/src/modules/softuart.c | 4 +- uCNC/src/modules/softuart.h | 2 +- uCNC/src/modules/system_menu.c | 227 +++++++++++++++++---------------- uCNC/src/modules/system_menu.h | 28 ++-- 6 files changed, 145 insertions(+), 144 deletions(-) diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index 479e846b0..d9a865e7c 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -156,16 +156,16 @@ void serial_stream_eeprom(uint16_t address) serial_stream_readonly(&stream_eeprom_getc, NULL, NULL); } -uint8_t serial_getc(void) +char serial_getc(void) { uint8_t peek = serial_peek(); serial_peek_buffer = 0; return peek; } -static FORCEINLINE uint8_t _serial_peek(void) +static FORCEINLINE char _serial_peek(void) { - uint8_t peek = serial_peek_buffer; + char peek = serial_peek_buffer; if (peek) { return peek; @@ -175,7 +175,7 @@ static FORCEINLINE uint8_t _serial_peek(void) { mcu_dotasks(); } - + #ifndef DISABLE_MULTISTREAM_SERIAL if (!stream_getc) { @@ -183,7 +183,7 @@ static FORCEINLINE uint8_t _serial_peek(void) return OVF; } #endif - peek = stream_getc(); + peek = (char)stream_getc(); // prevents null char reading from eeprom if (!peek) { @@ -193,7 +193,7 @@ static FORCEINLINE uint8_t _serial_peek(void) return peek; } -uint8_t serial_peek(void) +char serial_peek(void) { uint8_t peek = _serial_peek(); switch (peek) @@ -272,7 +272,7 @@ void serial_broadcast(bool enable) } static uint8_t serial_tx_count; -void serial_putc(uint8_t c) +void serial_putc(char c) { serial_tx_count++; #ifndef DISABLE_MULTISTREAM_SERIAL @@ -285,7 +285,7 @@ void serial_putc(uint8_t c) serial_stream_t *p = default_stream; while (p) { - p->stream_putc(c); + p->stream_putc((uint8_t)c); p = p->next; } } @@ -329,7 +329,7 @@ uint8_t serial_tx_busy(void) return serial_tx_count; } -void print_str(print_cb cb, const uint8_t *__s) +void print_str(print_cb cb, const char *__s) { while (*__s) { diff --git a/uCNC/src/interface/serial.h b/uCNC/src/interface/serial.h index d7d350e92..a33feeb1b 100644 --- a/uCNC/src/interface/serial.h +++ b/uCNC/src/interface/serial.h @@ -61,19 +61,19 @@ extern "C" void serial_stream_eeprom(uint16_t address); void serial_broadcast(bool enable); - void serial_putc(uint8_t c); + void serial_putc(char c); void serial_flush(void); uint8_t serial_tx_busy(void); - uint8_t serial_getc(void); - uint8_t serial_peek(void); + char serial_getc(void); + char serial_peek(void); uint8_t serial_available(void); void serial_clear(void); uint8_t serial_freebytes(void); // printing utils - typedef void (*print_cb)(uint8_t); - void print_str(print_cb cb, const uint8_t *__s); + typedef void (*print_cb)(char); + void print_str(print_cb cb, const char *__s); void print_bytes(print_cb cb, const uint8_t *data, uint8_t count); void print_int(print_cb cb, int32_t num); void print_flt(print_cb cb, float num); diff --git a/uCNC/src/modules/softuart.c b/uCNC/src/modules/softuart.c index f042be786..f4eee6fb4 100644 --- a/uCNC/src/modules/softuart.c +++ b/uCNC/src/modules/softuart.c @@ -17,7 +17,7 @@ */ #include "softuart.h" -void softuart_putc(softuart_port_t *port, uint8_t c) +void softuart_putc(softuart_port_t *port, char c) { if (!port) { @@ -50,7 +50,7 @@ void softuart_putc(softuart_port_t *port, uint8_t c) int16_t softuart_getc(softuart_port_t *port, uint32_t ms_timeout) { - uint8_t val = 0; + char val = 0; if (!port) { diff --git a/uCNC/src/modules/softuart.h b/uCNC/src/modules/softuart.h index e1b8103fd..9ff8b7c2e 100644 --- a/uCNC/src/modules/softuart.h +++ b/uCNC/src/modules/softuart.h @@ -56,7 +56,7 @@ extern "C" void NAME##_waithalf(void) { mcu_delay_cycles(F_CPU / 2 / BAUD); } \ __attribute__((used)) softuart_port_t NAME = {.wait = &NAME##_wait, .waithalf = &NAME##_waithalf, .tx = &NAME##_tx, .rx = &NAME##_rx}; - void softuart_putc(softuart_port_t *port, uint8_t c); + void softuart_putc(softuart_port_t *port, char c); int16_t softuart_getc(softuart_port_t *port, uint32_t ms_timeout); #ifdef __cplusplus diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 41fe0ad66..a190d10c6 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -86,169 +86,169 @@ DECL_MODULE(system_menu) DECL_MENU(1, 0, STR_MAIN_MENU); // main menu entries - DECL_MENU_ACTION(1, hold, (uint8_t *)STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); - DECL_MENU_ACTION(1, resume, (uint8_t *)STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); - DECL_MENU_ACTION(1, unlock, (uint8_t *)STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); - DECL_MENU_ACTION(1, home, (uint8_t *)STR_HOME, system_menu_action_serial_cmd, "$H\r"); - DECL_MENU_GOTO(1, jog, (uint8_t *)STR_JOG, CONST_VARG(7)); - DECL_MENU_GOTO(1, overrides, (uint8_t *)STR_OVERRIDES, CONST_VARG(8)); - DECL_MENU_GOTO(1, settings, (uint8_t *)STR_SETTINGS, CONST_VARG(2)); + DECL_MENU_ACTION(1, hold, STR_HOLD, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_HOLD)); + DECL_MENU_ACTION(1, resume, STR_RESUME, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_CYCLE_START)); + DECL_MENU_ACTION(1, unlock, STR_UNLOCK, system_menu_action_serial_cmd, "$X\r"); + DECL_MENU_ACTION(1, home, STR_HOME, system_menu_action_serial_cmd, "$H\r"); + DECL_MENU_GOTO(1, jog, STR_JOG, CONST_VARG(7)); + DECL_MENU_GOTO(1, overrides, STR_OVERRIDES, CONST_VARG(8)); + DECL_MENU_GOTO(1, settings, STR_SETTINGS, CONST_VARG(2)); DECL_MENU(8, 1, STR_OVERRIDES); - DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, (uint8_t *)STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); - DECL_MENU_ACTION(8, ovf_100, (uint8_t *)STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovf, STR_FEED_OVR, &g_planner_state.feed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('f')); + DECL_MENU_ACTION(8, ovf_100, STR_FEED_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_FEED_100)); #if (TOOL_COUNT > 0) - DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, (uint8_t *)STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); + DECL_MENU_VAR_CUSTOM_EDIT(8, ovt, STR_TOOL_OVR, &g_planner_state.spindle_speed_override, VAR_TYPE_UINT8, system_menu_action_overrides, CONST_VARG('s')); #endif - DECL_MENU_ACTION(8, ovt_100, (uint8_t *)STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); + DECL_MENU_ACTION(8, ovt_100, STR_TOOL_100, system_menu_action_rt_cmd, CONST_VARG(CMD_CODE_SPINDLE_100)); // append Jog menu // default initial distance DECL_MENU(7, 1, STR_JOG); - DECL_MENU_ENTRY(7, jogx, (uint8_t *)STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); + DECL_MENU_ENTRY(7, jogx, STR_JOG_AXIS("X"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "X"); #if (AXIS_COUNT > 1) - DECL_MENU_ENTRY(7, jogy, (uint8_t *)STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); + DECL_MENU_ENTRY(7, jogy, STR_JOG_AXIS("Y"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Y"); #endif #if (AXIS_COUNT > 2) - DECL_MENU_ENTRY(7, jogz, (uint8_t *)STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); + DECL_MENU_ENTRY(7, jogz, STR_JOG_AXIS("Z"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "Z"); #endif #if (AXIS_COUNT > 3) - DECL_MENU_ENTRY(7, joga, (uint8_t *)STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); + DECL_MENU_ENTRY(7, joga, STR_JOG_AXIS("A"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "A"); #endif #if (AXIS_COUNT > 4) - DECL_MENU_ENTRY(7, jogb, (uint8_t *)STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); + DECL_MENU_ENTRY(7, jogb, STR_JOG_AXIS("B"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "B"); #endif #if (AXIS_COUNT > 5) - DECL_MENU_ENTRY(7, jogc, (uint8_t *)STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); + DECL_MENU_ENTRY(7, jogc, STR_JOG_AXIS("C"), NULL, system_menu_render_axis_position, NULL, system_menu_action_jog, "C"); #endif - DECL_MENU_VAR(7, jogdist, (uint8_t *)STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); - DECL_MENU_VAR(7, jogfeed, (uint8_t *)STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogdist, STR_JOG_DIST, &jog_distance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(7, jogfeed, STR_JOG_FEED, &jog_feed, VAR_TYPE_FLOAT); // append settings menu DECL_MENU(2, 1, STR_SETTINGS); // settings menu - DECL_MENU_GOTO(2, ioconfig, (uint8_t *)STR_IO_CONFIG, CONST_VARG(6)); - DECL_MENU_GOTO(2, gohome, (uint8_t *)STR_HOMING, CONST_VARG(3)); + DECL_MENU_GOTO(2, ioconfig, STR_IO_CONFIG, CONST_VARG(6)); + DECL_MENU_GOTO(2, gohome, STR_HOMING, CONST_VARG(3)); #if (AXIS_COUNT > 0) - DECL_MENU_GOTO(2, goaxis, (uint8_t *)STR_AXIS, CONST_VARG(4)); + DECL_MENU_GOTO(2, goaxis, STR_AXIS, CONST_VARG(4)); #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU_GOTO(2, kinemats, (uint8_t *)STR_KINEMATICS, CONST_VARG(5)); + DECL_MENU_GOTO(2, kinemats, STR_KINEMATICS, CONST_VARG(5)); #endif - DECL_MENU_GOTO(2, other_config, (uint8_t *)STR_OTHER, CONST_VARG(9)); - DECL_MENU_ACTION(2, set_load, (uint8_t *)STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); - DECL_MENU_ACTION(2, set_save, (uint8_t *)STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); - DECL_MENU_ACTION(2, set_reset, (uint8_t *)STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); + DECL_MENU_GOTO(2, other_config, STR_OTHER, CONST_VARG(9)); + DECL_MENU_ACTION(2, set_load, STR_LOAD_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(0)); + DECL_MENU_ACTION(2, set_save, STR_SAVE_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(1)); + DECL_MENU_ACTION(2, set_reset, STR_RESET_SETTINGS, system_menu_action_settings_cmd, CONST_VARG(2)); DECL_MENU(9, 2, STR_OTHER); - DECL_MENU_VAR(9, s11, (uint8_t *)STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(9, s12, (uint8_t *)STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s11, STR_G64_FACT, &g_settings.g64_angle_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(9, s12, STR_ARC_TOL, &g_settings.arc_tolerance, VAR_TYPE_FLOAT); DECL_MENU(6, 2, STR_IO_CONFIG); - DECL_MENU_VAR(6, s2, (uint8_t *)STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s3, (uint8_t *)STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s4, (uint8_t *)STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s5, (uint8_t *)STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s6, (uint8_t *)STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(6, s7, (uint8_t *)STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s2, STR_STEP_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s3, STR_DIR_INV, &g_settings.dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s4, STR_ENABLE_INV, &g_settings.step_enable_invert, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s5, STR_LIMITS_INV, &g_settings.limits_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s6, STR_PROBE_INV, &g_settings.probe_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(6, s7, STR_CONTROL_INV, &g_settings.control_invert_mask, VAR_TYPE_UINT8); #if ENCODERS > 0 - DECL_MENU_VAR(6, s8, (uint8_t *)STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); - DECL_MENU_VAR(6, s9, (uint8_t *)STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s8, STR_ENC_P_INV, &g_settings.encoders_pulse_invert_mask, VAR_TYPE_UINT8); + DECL_MENU_VAR(6, s9, STR_ENC_D_INV, &g_settings.encoders_dir_invert_mask, VAR_TYPE_UINT8); #endif // append homing settings menu DECL_MENU(3, 2, STR_HOMING); - DECL_MENU_VAR(3, s20, (uint8_t *)STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s21, (uint8_t *)STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s22, (uint8_t *)STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s23, (uint8_t *)STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s24, (uint8_t *)STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s25, (uint8_t *)STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s26, (uint8_t *)STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); - DECL_MENU_VAR(3, s27, (uint8_t *)STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s20, STR_SOFTLIMITS, &g_settings.soft_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s21, STR_HARDLIMITS, &g_settings.hard_limits_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s22, STR_ENABLE_HOMING, &g_settings.homing_enabled, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s23, STR_DIR_INV_MASK, &g_settings.homing_dir_invert_mask, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s24, STR_SLOW_FEED, &g_settings.homing_slow_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s25, STR_FAST_FEED, &g_settings.homing_fast_feed_rate, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s26, STR_DEBOUNCEMS, &g_settings.debounce_ms, VAR_TYPE_BOOLEAN); + DECL_MENU_VAR(3, s27, STR_OFFSET, &g_settings.homing_offset, VAR_TYPE_FLOAT); #if (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(3, s28, (uint8_t *)STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_SCARA) - DECL_MENU_VAR(3, s28, (uint8_t *)STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); - DECL_MENU_VAR(3, s29, (uint8_t *)STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s28, STR_OFFSET, &g_settings.scara_arm_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(3, s29, STR_OFFSET, &g_settings.scara_forearm_homing_angle, VAR_TYPE_FLOAT); #endif // append steppers settings menu DECL_MENU(4, 2, STR_AXIS); - DECL_MENU_VAR(4, s100, (uint8_t *)STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s110, (uint8_t *)STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s120, (uint8_t *)STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s130, (uint8_t *)STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s100, STR_STEPMM("X"), &g_settings.step_per_mm[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s110, STR_VMAX("X"), &g_settings.max_feed_rate[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s120, STR_ACCEL("X"), &g_settings.acceleration[0], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s130, STR_MAX_DIST("X"), &g_settings.max_distance[0], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s140, (uint8_t *)STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s140, STR_BACKLASH("X"), &g_settings.backlash_steps[0], VAR_TYPE_UINT16); #endif #if (AXIS_COUNT > 1) - DECL_MENU_VAR(4, s101, (uint8_t *)STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s111, (uint8_t *)STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s121, (uint8_t *)STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s131, (uint8_t *)STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s101, STR_STEPMM("Y"), &g_settings.step_per_mm[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s111, STR_VMAX("Y"), &g_settings.max_feed_rate[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s121, STR_ACCEL("Y"), &g_settings.acceleration[1], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s131, STR_MAX_DIST("Y"), &g_settings.max_distance[1], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s141, (uint8_t *)STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s141, STR_BACKLASH("Y"), &g_settings.backlash_steps[1], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 2) - DECL_MENU_VAR(4, s102, (uint8_t *)STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s112, (uint8_t *)STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s122, (uint8_t *)STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s132, (uint8_t *)STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s102, STR_STEPMM("Z"), &g_settings.step_per_mm[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s112, STR_VMAX("Z"), &g_settings.max_feed_rate[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s122, STR_ACCEL("Z"), &g_settings.acceleration[2], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s132, STR_MAX_DIST("Z"), &g_settings.max_distance[2], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s142, (uint8_t *)STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s142, STR_BACKLASH("Z"), &g_settings.backlash_steps[2], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 3) - DECL_MENU_VAR(4, s103, (uint8_t *)STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s113, (uint8_t *)STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s123, (uint8_t *)STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s133, (uint8_t *)STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s103, STR_STEPMM("A"), &g_settings.step_per_mm[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s113, STR_VMAX("A"), &g_settings.max_feed_rate[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s123, STR_ACCEL("A"), &g_settings.acceleration[3], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s133, STR_MAX_DIST("A"), &g_settings.max_distance[3], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s143, (uint8_t *)STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s143, STR_BACKLASH("A"), &g_settings.backlash_steps[3], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 4) - DECL_MENU_VAR(4, s104, (uint8_t *)STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s114, (uint8_t *)STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s124, (uint8_t *)STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s134, (uint8_t *)STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s104, STR_STEPMM("B"), &g_settings.step_per_mm[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s114, STR_VMAX("B"), &g_settings.max_feed_rate[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s124, STR_ACCEL("B"), &g_settings.acceleration[4], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s134, STR_MAX_DIST("B"), &g_settings.max_distance[4], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMPENSATION - DECL_MENU_VAR(4, s144, (uint8_t *)STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s144, STR_BACKLASH("B"), &g_settings.backlash_steps[4], VAR_TYPE_UINT16); #endif #endif #if (AXIS_COUNT > 5) - DECL_MENU_VAR(4, s105, (uint8_t *)STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s115, (uint8_t *)STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s125, (uint8_t *)STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); - DECL_MENU_VAR(4, s135, (uint8_t *)STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s105, STR_STEPMM("C"), &g_settings.step_per_mm[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s115, STR_VMAX("C"), &g_settings.max_feed_rate[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s125, STR_ACCEL("C"), &g_settings.acceleration[5], VAR_TYPE_FLOAT); + DECL_MENU_VAR(4, s135, STR_MAX_DIST("C"), &g_settings.max_distance[5], VAR_TYPE_FLOAT); #ifdef ENABLE_BACKLASH_COMENSATION - DECL_MENU_VAR(4, s145, (uint8_t *)STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); + DECL_MENU_VAR(4, s145, STR_BACKLASH("C"), &g_settings.backlash_steps[5], VAR_TYPE_UINT16); #endif #endif #if (defined(ENABLE_SKEW_COMPENSATION) || (KINEMATIC == KINEMATIC_LINEAR_DELTA) || (KINEMATIC == KINEMATIC_DELTA)) - DECL_MENU(5, 2, (uint8_t *)STR_KINEMATICS); + DECL_MENU(5, 2, STR_KINEMATICS); #ifdef ENABLE_SKEW_COMPENSATION - DECL_MENU_VAR(5, s37, (uint8_t *)STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s37, STR_SKEW_FACTOR("XY"), &g_settings.skew_xy_factor, VAR_TYPE_FLOAT); #ifndef SKEW_COMPENSATION_XY_ONLY - DECL_MENU_VAR(5, s38, (uint8_t *)STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s39, (uint8_t *)STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s38, STR_SKEW_FACTOR("XZ"), &g_settings.skew_xz_factor, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s39, STR_SKEW_FACTOR("YZ"), &g_settings.skew_yz_factor, VAR_TYPE_FLOAT); #endif #endif #if (KINEMATIC == KINEMATIC_LINEAR_DELTA) - DECL_MENU_VAR(5, s106, (uint8_t *)STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, (uint8_t *)STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, STR_ARM_LEN, &g_settings.delta_arm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, STR_BASE_RAD, &g_settings.delta_armbase_radius, VAR_TYPE_FLOAT); #elif (KINEMATIC == KINEMATIC_DELTA) - DECL_MENU_VAR(5, s106, (uint8_t *)STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s107, (uint8_t *)STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s108, (uint8_t *)STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s109, (uint8_t *)STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); - DECL_MENU_VAR(5, s28, (uint8_t *)STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s106, STR_BASE_RAD, &g_settings.delta_base_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s107, STR_EFF_RAD, &g_settings.delta_effector_radius, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s108, STR_BICEP_LEN, &g_settings.delta_bicep_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s109, STR_FARM_LEN, &g_settings.delta_forearm_length, VAR_TYPE_FLOAT); + DECL_MENU_VAR(5, s28, STR_HOME_ANG, &g_settings.delta_bicep_homing_angle, VAR_TYPE_FLOAT); #endif #endif @@ -436,7 +436,7 @@ void system_menu_render(void) // renders header if (!item_index) { - uint8_t buff[SYSTEM_MENU_MAX_STR_LEN]; + char buff[SYSTEM_MENU_MAX_STR_LEN]; rom_strcpy((char *)buff, (const char *)menu_page->page_label); system_menu_render_header(buff); } @@ -469,7 +469,7 @@ void system_menu_render(void) } } -void system_menu_show_modal_popup(uint32_t timeout, const uint8_t *__s) +void system_menu_show_modal_popup(uint32_t timeout, const char *__s) { // prevents redraw g_system_menu.flags &= ~(SYSTEM_MENU_MODE_REDRAW | SYSTEM_MENU_MODE_DELAYED_REDRAW); @@ -647,7 +647,7 @@ bool system_menu_action_rt_cmd(uint8_t action, system_menu_item_t *item) if (action == SYSTEM_MENU_ACTION_SELECT && item) { cnc_call_rt_command((uint8_t)VARG_CONST(item->action_arg)); - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; + char buffer[SYSTEM_MENU_MAX_STR_LEN]; rom_strcpy((char *)buffer, __romstr__(STR_RT_CMD_SENT)); system_menu_show_modal_popup(SYSTEM_MENU_MODAL_POPUP_MS, buffer); return true; @@ -661,12 +661,13 @@ bool system_menu_action_serial_cmd(uint8_t action, system_menu_item_t *item) { if (serial_freebytes() > 20) { - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - if (system_menu_send_cmd((const uint8_t *)item->action_arg) == STATUS_OK) + char buffer[SYSTEM_MENU_MAX_STR_LEN]; + if (system_menu_send_cmd((const char *)item->action_arg) == STATUS_OK) { rom_strcpy((char *)buffer, __romstr__(STR_CMD_SENT)); } - else{ + else + { rom_strcpy((char *)buffer, __romstr__(STR_CMD_NOTSENT)); } @@ -747,10 +748,10 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) // one jog command at time if (serial_freebytes() > 32) { - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; + char buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); rom_strcpy((char *)buffer, __romstr__("$J=G91")); - uint8_t *ptr = buffer; + char *ptr = buffer; // search for the end of string while (*++ptr) ; @@ -789,7 +790,7 @@ static bool system_menu_action_jog(uint8_t action, system_menu_item_t *item) static bool system_menu_action_settings_cmd(uint8_t action, system_menu_item_t *item) { - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; + char buffer[SYSTEM_MENU_MAX_STR_LEN]; if (action == SYSTEM_MENU_ACTION_SELECT) { @@ -1028,7 +1029,7 @@ bool system_menu_action_edit(uint8_t action, system_menu_item_t *item) * These can be overriten by the display to perform the rendering of the menu content * **/ -void __attribute__((weak)) system_menu_render_header(const uint8_t *__s) +void __attribute__((weak)) system_menu_render_header(const char *__s) { // render the menu header } @@ -1087,13 +1088,13 @@ void __attribute__((weak)) system_menu_render_alarm(void) // render alarm screen } -void __attribute__((weak)) system_menu_render_modal_popup(const uint8_t *__s) +void __attribute__((weak)) system_menu_render_modal_popup(const char *__s) { // renders the modal popup message } // this needs to be implemented using a serial stream -uint8_t __attribute__((weak)) system_menu_send_cmd(const uint8_t *__s) +uint8_t __attribute__((weak)) system_menu_send_cmd(const char *__s) { return STATUS_STREAM_FAILED; } @@ -1101,12 +1102,12 @@ uint8_t __attribute__((weak)) system_menu_send_cmd(const uint8_t *__s) /** * Helper µCNC render callbacks * **/ -void __attribute__((weak)) system_menu_item_render_label(uint8_t item_index, const uint8_t *label) +void __attribute__((weak)) system_menu_item_render_label(uint8_t item_index, const char *label) { // this is were the display renders the item label } -void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, const uint8_t *label) +void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, const char *label) { // this is were the display renders the item variable } @@ -1114,8 +1115,8 @@ void __attribute__((weak)) system_menu_item_render_arg(uint8_t render_flags, con void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *item) { uint8_t vartype = (uint8_t)VARG_CONST(item->render_arg); - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; - uint8_t *buff_ptr = buffer; + char buffer[SYSTEM_MENU_MAX_STR_LEN]; + char *buff_ptr = buffer; switch (vartype) { case VAR_TYPE_BOOLEAN: @@ -1138,11 +1139,11 @@ void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *i system_menu_flt_to_str(buffer, *((float *)item->argptr)); break; default: - buff_ptr = (uint8_t *)item->argptr; + buff_ptr = item->argptr; break; } - system_menu_item_render_arg(render_flags, (const uint8_t *)buff_ptr); + system_menu_item_render_arg(render_flags, (const char *)buff_ptr); } static void system_menu_render_axis_position(uint8_t render_flags, system_menu_item_t *item) @@ -1158,12 +1159,12 @@ static void system_menu_render_axis_position(uint8_t render_flags, system_menu_i itp_get_rt_position(steppos); kinematics_steps_to_coordinates(steppos, axis); // X = 0 - uint8_t axis_letter = *((uint8_t *)item->action_arg); + char axis_letter = *((char *)item->action_arg); uint8_t axis_index = (axis_letter >= 'X') ? (axis_letter - 'X') : (3 + axis_letter - 'A'); - uint8_t buffer[SYSTEM_MENU_MAX_STR_LEN]; + char buffer[SYSTEM_MENU_MAX_STR_LEN]; memset(buffer, 0, SYSTEM_MENU_MAX_STR_LEN); - uint8_t *buff_ptr = buffer; + char *buff_ptr = buffer; system_menu_flt_to_str(buff_ptr, axis[axis_index]); system_menu_item_render_arg(render_flags, buffer); @@ -1175,13 +1176,13 @@ static void system_menu_render_axis_position(uint8_t render_flags, system_menu_i * Helper µCNC to display variables * **/ -uint8_t *system_menu_var_to_str_set_buffer_ptr; -void system_menu_var_to_str_set_buffer(uint8_t *ptr) +char *system_menu_var_to_str_set_buffer_ptr; +void system_menu_var_to_str_set_buffer(char *ptr) { system_menu_var_to_str_set_buffer_ptr = ptr; } -void system_menu_var_to_str(uint8_t c) +void system_menu_var_to_str(char c) { *system_menu_var_to_str_set_buffer_ptr = c; *(++system_menu_var_to_str_set_buffer_ptr) = 0; diff --git a/uCNC/src/modules/system_menu.h b/uCNC/src/modules/system_menu.h index cd37b4dee..00042446f 100644 --- a/uCNC/src/modules/system_menu.h +++ b/uCNC/src/modules/system_menu.h @@ -96,12 +96,12 @@ extern "C" struct system_menu_item_ { - const uint8_t *label; + const char *label; void *argptr; system_menu_item_render_cb item_render; - void *render_arg; + const void *render_arg; system_menu_item_action_cb item_action; - void *action_arg; + const void *action_arg; }; typedef struct system_menu_index_ @@ -114,7 +114,7 @@ extern "C" { uint8_t menu_id; uint8_t parent_id; - const uint8_t *page_label; + const char *page_label; system_menu_page_render_cb page_render; system_menu_page_action_cb page_action; system_menu_index_t *items_index; @@ -150,7 +150,7 @@ extern "C" #define DECL_MENU_ACTION(menu_id, name, strvalue, action_cb, action_cb_arg) DECL_MENU_ENTRY(menu_id, name, strvalue, NULL, NULL, NULL, action_cb, action_cb_arg) #define DECL_MENU(id, parentid, label) \ - static const uint8_t m##id##_label[] __rom__ = label; \ + static const char m##id##_label[] __rom__ = label; \ static system_menu_page_t m##id = {.menu_id = id, .parent_id = parentid, .page_label = m##id##_label, .page_render = NULL, .page_action = NULL, .items_index = NULL, .extended = NULL}; \ system_menu_append(&m##id) #define DECL_DYNAMIC_MENU(id, parentid, render_cb, action_cb) \ @@ -167,7 +167,7 @@ extern "C" void system_menu_go_idle(void); void system_menu_action(uint8_t action); void system_menu_render(void); - void system_menu_show_modal_popup(uint32_t timeout, const uint8_t *__s); + void system_menu_show_modal_popup(uint32_t timeout, const char *__s); void system_menu_action_timeout(uint32_t delay); void system_menu_append(system_menu_page_t *newpage); @@ -179,7 +179,7 @@ extern "C" /** * Overridable functions to be implemented for the display to render the system menu * **/ - void system_menu_render_header(const uint8_t *__s); + void system_menu_render_header(const char *__s); bool system_menu_render_menu_item_filter(uint8_t item_index); void system_menu_render_menu_item(uint8_t render_flags, const system_menu_item_t *item); void system_menu_render_nav_back(bool is_hover); @@ -187,9 +187,9 @@ extern "C" void system_menu_render_startup(void); void system_menu_render_idle(void); void system_menu_render_alarm(void); - void system_menu_render_modal_popup(const uint8_t *__s); + void system_menu_render_modal_popup(const char *__s); // this needs to be implemented using a serial stream - uint8_t system_menu_send_cmd(const uint8_t *__s); + uint8_t system_menu_send_cmd(const char *__s); /** * Helper µCNC action callbacks @@ -205,17 +205,17 @@ extern "C" * **/ // these should be implemented on the display side // one to render label and the other to render the label variable argument - void system_menu_item_render_label(uint8_t render_flags, const uint8_t *label); - void system_menu_item_render_arg(uint8_t render_flags, const uint8_t *label); + void system_menu_item_render_label(uint8_t render_flags, const char *label); + void system_menu_item_render_arg(uint8_t render_flags, const char *label); // generic menu item argument renderer void system_menu_item_render_var_arg(uint8_t render_flags, system_menu_item_t *item); /** * Helper µCNC to display variables * **/ - extern uint8_t *system_menu_var_to_str_set_buffer_ptr; - void system_menu_var_to_str_set_buffer(uint8_t *ptr); - void system_menu_var_to_str(uint8_t c); + extern char *system_menu_var_to_str_set_buffer_ptr; + void system_menu_var_to_str_set_buffer(char *ptr); + void system_menu_var_to_str(char c); #define system_menu_int_to_str(buf_ptr, var) \ system_menu_var_to_str_set_buffer(buf_ptr); \ From dbc052ea4f01538bbacfdd082605a4f86195ab7a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Fri, 13 Oct 2023 10:36:56 +0100 Subject: [PATCH 149/168] fixed serial for undef stream output functions --- makefiles/virtual/uCNC.dev | 1138 ++++++++++++++++++++++++++++++++++- uCNC/src/interface/serial.c | 20 +- 2 files changed, 1140 insertions(+), 18 deletions(-) diff --git a/makefiles/virtual/uCNC.dev b/makefiles/virtual/uCNC.dev index 72bcd7b76..8c6be53e2 100644 --- a/makefiles/virtual/uCNC.dev +++ b/makefiles/virtual/uCNC.dev @@ -4,14 +4,14 @@ Name=uCNCVirt Type=1 Ver=2 ObjFiles= -Includes=C:\Users\JCEM\Documents\GitHub\uCNC\src;C:\Users\JCEM\Documents\GitHub\uCNC\makefiles\virtual;C:\Users\jcmartins\.platformio\packages\toolchain-gccmingw32\i686-w64-mingw32\include\ +Includes=C:\Users\jcmartins\Downloads\GitHub\uCNC\src;C:\Users\jcmartins\Downloads\GitHub\uCNC\makefiles\virtual;C:\Users\jcmartins\.platformio\packages\toolchain-gccmingw32\i686-w64-mingw32\include\ Libs= PrivateResource= ResourceIncludes= MakeIncludes= -Compiler=-DWIN_INTERFACE=2 -DENABLE_EXTRA_SYSTEM_CMDS -DWIN_COM_NAME=COM11 -DBOARD=BOARD_VIRTUAL -DMCU=MCU_VIRTUAL -DDISABLE_MULTISTREAM_SERIAL_@@_ +Compiler=-DWIN_INTERFACE=2 -DENABLE_EXTRA_SYSTEM_CMDS -DWIN_COM_NAME=COM11 -DBOARD=BOARD_VIRTUAL -DMCU=MCU_VIRTUAL_@@_ CppCompiler=_@@_ -Linker=-lws2_32_@@_ +Linker=-lws2_32 -lSDL2main -lSDL2_@@_ IsCpp=0 Icon= ExeOutput= @@ -29,7 +29,7 @@ IncludeVersionInfo=0 SupportXPThemes=0 CompilerSet=1 CompilerSettings=000000e0a0000000001000000 -UnitCount=81 +UnitCount=202 [VersionInfo] Major=1 @@ -831,7 +831,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit131] -FileName=clib\u8x8_d_s1d15e06.c +FileName=clib\u8x8_d_pcf8814_hx1230.c CompileCpp=0 Folder= Compile=1 @@ -841,7 +841,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit147] -FileName=clib\u8x8_d_ssd1306_96x40.c +FileName=clib\u8x8_d_ssd1306_96x16.c CompileCpp=0 Folder= Compile=1 @@ -851,7 +851,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit148] -FileName=clib\u8x8_d_ssd1306_128x32.c +FileName=clib\u8x8_d_ssd1306_96x40.c CompileCpp=0 Folder= Compile=1 @@ -861,7 +861,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit149] -FileName=clib\u8x8_d_ssd1306_128x64_noname.c +FileName=clib\u8x8_d_ssd1306_128x32.c CompileCpp=0 Folder= Compile=1 @@ -871,7 +871,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit173] -FileName=clib\u8x8_d_st7920.c +FileName=clib\u8x8_d_st7588.c CompileCpp=0 Folder= Compile=1 @@ -881,7 +881,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit174] -FileName=clib\u8x8_d_st75160.c +FileName=clib\u8x8_d_st7920.c CompileCpp=0 Folder= Compile=1 @@ -891,7 +891,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit175] -FileName=clib\u8x8_d_st75256.c +FileName=clib\u8x8_d_st75160.c CompileCpp=0 Folder= Compile=1 @@ -901,7 +901,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit198] -FileName=clib\u8x8_string.c +FileName=clib\u8x8_setup.c CompileCpp=0 Folder= Compile=1 @@ -911,7 +911,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit199] -FileName=clib\u8x8_u8toa.c +FileName=clib\u8x8_string.c CompileCpp=0 Folder= Compile=1 @@ -921,7 +921,7 @@ OverrideBuildCmd=0 BuildCmd= [Unit200] -FileName=clib\u8x8_u16toa.c +FileName=clib\u8x8_u8toa.c CompileCpp=0 Folder= Compile=1 @@ -960,3 +960,1113 @@ Priority=1000 OverrideBuildCmd=0 BuildCmd= +[Unit82] +FileName=clib\mui.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit83] +FileName=clib\mui.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit84] +FileName=clib\mui_u8g2.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit85] +FileName=clib\mui_u8g2.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit86] +FileName=clib\u8g2.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit87] +FileName=clib\u8g2_bitmap.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit88] +FileName=clib\u8g2_box.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit89] +FileName=clib\u8g2_buffer.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit90] +FileName=clib\u8g2_button.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit91] +FileName=clib\u8g2_circle.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit92] +FileName=clib\u8g2_cleardisplay.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit93] +FileName=clib\u8g2_d_memory.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit94] +FileName=clib\u8g2_d_setup.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit95] +FileName=clib\u8g2_font.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit96] +FileName=clib\u8g2_fonts.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit97] +FileName=clib\u8g2_hvline.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit98] +FileName=clib\u8g2_input_value.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit99] +FileName=clib\u8g2_intersection.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit100] +FileName=clib\u8g2_kerning.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit101] +FileName=clib\u8g2_line.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit102] +FileName=clib\u8g2_ll_hvline.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit103] +FileName=clib\u8g2_message.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit104] +FileName=clib\u8g2_polygon.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit105] +FileName=clib\u8g2_selection_list.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit106] +FileName=clib\u8g2_setup.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit107] +FileName=clib\u8log.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit108] +FileName=clib\u8log_u8g2.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit109] +FileName=clib\u8log_u8x8.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit110] +FileName=clib\u8x8.h +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit111] +FileName=clib\u8x8_8x8.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit112] +FileName=clib\u8x8_byte.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit113] +FileName=clib\u8x8_cad.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit114] +FileName=clib\u8x8_capture.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit115] +FileName=clib\u8x8_d_a2printer.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit116] +FileName=clib\u8x8_d_gp1247ai.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit117] +FileName=clib\u8x8_d_gp1287ai.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit118] +FileName=clib\u8x8_d_gu800.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit119] +FileName=clib\u8x8_d_hd44102.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit120] +FileName=clib\u8x8_d_il3820_296x128.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit121] +FileName=clib\u8x8_d_ist3020.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit122] +FileName=clib\u8x8_d_ist3088.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit123] +FileName=clib\u8x8_d_ist7920.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit124] +FileName=clib\u8x8_d_ks0108.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit125] +FileName=clib\u8x8_d_lc7981.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit126] +FileName=clib\u8x8_d_ld7032_60x32.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit127] +FileName=clib\u8x8_d_ls013b7dh03.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit128] +FileName=clib\u8x8_d_max7219.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit129] +FileName=clib\u8x8_d_pcd8544_84x48.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit130] +FileName=clib\u8x8_d_pcf8812.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit132] +FileName=clib\u8x8_d_s1d15e06.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit133] +FileName=clib\u8x8_d_s1d15721.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit134] +FileName=clib\u8x8_d_sbn1661.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit135] +FileName=clib\u8x8_d_sdl_128x64.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit136] +FileName=clib\u8x8_d_sed1330.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit137] +FileName=clib\u8x8_d_sh1106_64x32.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit138] +FileName=clib\u8x8_d_sh1106_72x40.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit139] +FileName=clib\u8x8_d_sh1107.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit140] +FileName=clib\u8x8_d_sh1108.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit141] +FileName=clib\u8x8_d_sh1122.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit142] +FileName=clib\u8x8_d_ssd1305.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit143] +FileName=clib\u8x8_d_ssd1306_48x64.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit144] +FileName=clib\u8x8_d_ssd1306_64x32.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit145] +FileName=clib\u8x8_d_ssd1306_64x48.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit146] +FileName=clib\u8x8_d_ssd1306_72x40.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit150] +FileName=clib\u8x8_d_ssd1306_128x64_noname.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit151] +FileName=clib\u8x8_d_ssd1306_2040x16.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit152] +FileName=clib\u8x8_d_ssd1309.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit153] +FileName=clib\u8x8_d_ssd1316.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit154] +FileName=clib\u8x8_d_ssd1317.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit155] +FileName=clib\u8x8_d_ssd1318.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit156] +FileName=clib\u8x8_d_ssd1320.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit157] +FileName=clib\u8x8_d_ssd1322.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit158] +FileName=clib\u8x8_d_ssd1325.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit159] +FileName=clib\u8x8_d_ssd1326.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit160] +FileName=clib\u8x8_d_ssd1327.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit161] +FileName=clib\u8x8_d_ssd1329.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit162] +FileName=clib\u8x8_d_ssd1606_172x72.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit163] +FileName=clib\u8x8_d_ssd1607_200x200.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit164] +FileName=clib\u8x8_d_st7511.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit165] +FileName=clib\u8x8_d_st7528.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit166] +FileName=clib\u8x8_d_st7565.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit167] +FileName=clib\u8x8_d_st7567.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit168] +FileName=clib\u8x8_d_st7571.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit169] +FileName=clib\u8x8_d_st7586s_erc240160.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit170] +FileName=clib\u8x8_d_st7586s_jlx384160.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit171] +FileName=clib\u8x8_d_st7586s_s028hn118a.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit172] +FileName=clib\u8x8_d_st7586s_ymc240160.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit176] +FileName=clib\u8x8_d_st75256.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit177] +FileName=clib\u8x8_d_st75320.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit178] +FileName=clib\u8x8_d_stdio.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit179] +FileName=clib\u8x8_d_t6963.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit180] +FileName=clib\u8x8_d_uc1601.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit181] +FileName=clib\u8x8_d_uc1604.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit182] +FileName=clib\u8x8_d_uc1608.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit183] +FileName=clib\u8x8_d_uc1609.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit184] +FileName=clib\u8x8_d_uc1610.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit185] +FileName=clib\u8x8_d_uc1611.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit186] +FileName=clib\u8x8_d_uc1617.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit187] +FileName=clib\u8x8_d_uc1638.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit188] +FileName=clib\u8x8_d_uc1701_dogs102.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit189] +FileName=clib\u8x8_d_uc1701_mini12864.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit190] +FileName=clib\u8x8_debounce.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit191] +FileName=clib\u8x8_display.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit192] +FileName=clib\u8x8_fonts.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit193] +FileName=clib\u8x8_gpio.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit194] +FileName=clib\u8x8_input_value.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit195] +FileName=clib\u8x8_message.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit196] +FileName=clib\u8x8_sdl_key.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit197] +FileName=clib\u8x8_selection_list.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit201] +FileName=clib\u8x8_u16toa.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + +[Unit202] +FileName=..\..\uCNC\src\modules\graphic_display\graphic_display.c +CompileCpp=0 +Folder= +Compile=1 +Link=1 +Priority=1000 +OverrideBuildCmd=0 +BuildCmd= + diff --git a/uCNC/src/interface/serial.c b/uCNC/src/interface/serial.c index d9a865e7c..ca4110524 100644 --- a/uCNC/src/interface/serial.c +++ b/uCNC/src/interface/serial.c @@ -278,14 +278,20 @@ void serial_putc(char c) #ifndef DISABLE_MULTISTREAM_SERIAL if (!serial_broadcast_enabled) { - current_stream->stream_putc(c); + if (current_stream->stream_putc) + { + current_stream->stream_putc(c); + } } else { serial_stream_t *p = default_stream; while (p) { - p->stream_putc((uint8_t)c); + if (p->stream_putc) + { + p->stream_putc((uint8_t)c); + } p = p->next; } } @@ -308,14 +314,20 @@ void serial_flush(void) #ifndef DISABLE_MULTISTREAM_SERIAL if (!serial_broadcast_enabled) { - current_stream->stream_flush(); + if (current_stream->stream_flush) + { + current_stream->stream_flush(); + } } else { serial_stream_t *p = default_stream; while (p) { - p->stream_flush(); + if (p->stream_flush) + { + p->stream_flush(); + } p = p->next; } } From fd162ab47df98dedf9edc6beaf43a61e98c1f37e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 14 Oct 2023 18:28:52 +0100 Subject: [PATCH 150/168] PIO environments renaming - PIO environments renaming - some switch/case fallthrough fixes --- platformio.ini | 2 +- uCNC/src/hal/boards/avr/avr.ini | 24 +++---- uCNC/src/hal/boards/esp32/esp32.ini | 86 +++++++++++++++++++------ uCNC/src/hal/boards/esp8266/esp8266.ini | 2 +- uCNC/src/hal/boards/lpc176x/lpc176x.ini | 6 +- uCNC/src/hal/boards/rp2040/rp2040.ini | 4 +- uCNC/src/hal/boards/samd21/samd21.ini | 6 +- uCNC/src/hal/boards/stm32/stm32.ini | 30 +++++---- uCNC/src/modules/ic74hc595.c | 2 +- uCNC/src/modules/system_menu.c | 2 + uCNC/src/modules/tmc.c | 1 + 11 files changed, 110 insertions(+), 55 deletions(-) diff --git a/platformio.ini b/platformio.ini index 1da7f9a56..36a714bbc 100644 --- a/platformio.ini +++ b/platformio.ini @@ -11,7 +11,7 @@ [platformio] include_dir=uCNC src_dir=uCNC -default_envs = uno, ramps14, rambo, arduinoM0, bluepill_f103c8, blackpill_f401cc, d1, re_arm, d1_r32, rpi_pico_w +default_envs = AVR-UNO, AVR-MEGA2560-RAMPS-V1_4, AVR-RAMBO, SAMD21-Wemos-M0, STM32F1-Bluepill-F103C8, STM32F4-Blackpill-F401CC, ESP8266-Wemos-D1-R2, LPC176X-RE-ARM, ESP32-Wemos-D1-R32-WIFI, RP2040-PICO-W extra_configs = uCNC/src/hal/boards/avr/avr.ini uCNC/src/hal/boards/samd21/samd21.ini diff --git a/uCNC/src/hal/boards/avr/avr.ini b/uCNC/src/hal/boards/avr/avr.ini index 333e1ba6c..38759aae2 100644 --- a/uCNC/src/hal/boards/avr/avr.ini +++ b/uCNC/src/hal/boards/avr/avr.ini @@ -11,7 +11,7 @@ extra_scripts = avr_compiler.py ; debug_tool = simavr debug_build_flags = -Og -g3 -ggdb3 -gdwarf-2 build_flags = ${common.build_flags} -mcall-prologues -mrelax -flto -fno-fat-lto-objects -fno-tree-scev-cprop -Wl,--relax -lib_ignore = EEPROM, SPI, Wire +; lib_ignore = EEPROM, SPI, Wire [atmega328p] extends = common_avr @@ -19,39 +19,39 @@ board = uno ;saves a bit of flash build_flags = ${common_avr.build_flags} -D DISABLE_SETTINGS_MODULES -D DISABLE_MULTISTREAM_SERIAL -[env:uno] +[env:AVR-UNO] extends = atmega328p build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_UNO -[env:uno_shield_v3] +[env:AVR-CNC-Shield-V3] extends = atmega328p build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_UNO_SHIELD_V3 -[env:x_controller] +[env:AVR-X-Controller] extends = atmega328p build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_X_CONTROLLER -[env:mks_dlc] +[env:AVR-MKS-DLC] extends = common_avr board_build.f_cpu = 20000000UL build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_MKS_DLC -[env:ramps14] +[env:AVR-MEGA2560-RAMPS-V1_4] extends = common_avr board = megaatmega2560 build_flags = ${common_avr.build_flags} -D BOARD=BOARD_RAMPS14 -[env:ramps14mirror] -extends = common_avr -board = megaatmega2560 -build_flags = ${common_avr.build_flags} -D BOARD=BOARD_RAMPS14_MIRROR +; [env:ramps14mirror] +; extends = common_avr +; board = megaatmega2560 +; build_flags = ${common_avr.build_flags} -D BOARD=BOARD_RAMPS14_MIRROR -[env:mks_gen_l_v1] +[env:AVR-MKS-GEN-L-V1] extends = common_avr board = megaatmega2560 build_flags = ${common_avr.build_flags} -D BOARD=BOARD_MKS_GEN_L_V1 -[env:rambo] +[env:AVR-RAMBO] extends = common_avr board = megaatmega2560 build_flags = ${common_avr.build_flags} -D BOARD=BOARD_RAMBO14 diff --git a/uCNC/src/hal/boards/esp32/esp32.ini b/uCNC/src/hal/boards/esp32/esp32.ini index e7ea7895d..64bb89b98 100644 --- a/uCNC/src/hal/boards/esp32/esp32.ini +++ b/uCNC/src/hal/boards/esp32/esp32.ini @@ -7,40 +7,88 @@ platform = espressif32 framework = arduino board = esp32dev ; build_src_filter = +<*>- -build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DENABLE_WIFI -DENABLE_BLUETOOTH -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE +build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE board_build.f_flash = 80000000L board_build.f_cpu = 240000000L board_build.partitions = min_spiffs.csv monitor_filters=esp32_exception_decoder upload_speed = 921600 +lib_deps = SPI, Wire -[common_esp32_idf] +################## +# Arduino builds # +################## + +[env:ESP32-Wemos-D1-R32-WIFI] extends = common_esp32 -framework = arduino, espidf -lib_deps = SPI, Wifi, Wire, WebServer, HTTPUpdatedServer, BluetoothSerial +board = wemos_d1_uno32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer -[env:d1_r32] +[env:ESP32-Wemos-D1-R32-BLUETOOTH] extends = common_esp32 board = wemos_d1_uno32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial + +[env:ESP32-MKS-DLC32-WIFI] +extends = common_esp32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer + +[env:ESP32-MKS-DLC32-BLUETOOTH] +extends = common_esp32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial + +[env:ESP32-MKS-TINYBEE-WIFI] +extends = common_esp32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer -[env:mks_tinybee] +[env:ESP32-MKS-TINYBEE-BLUETOOTH] extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial -[env:mks_dlc32] +################# +# ESPIDF builds # +################# + +[env:ESP32IDF-Wemos-D1-R32-WIFI] extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 +framework = arduino, espidf +board = wemos_d1_uno32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer -[env:espidf_d1_r32] -extends = common_esp32_idf +[env:ESP32IDF-Wemos-D1-R32-BLUETOOTH] +extends = common_esp32 +framework = arduino, espidf board = wemos_d1_uno32 -build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial + +[env:ESP32IDF-MKS-DLC32-WIFI] +extends = common_esp32 +framework = arduino, espidf +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer + +[env:ESP32IDF-MKS-DLC32-BLUETOOTH] +extends = common_esp32 +framework = arduino, espidf +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial -[env:espidf_mks_tinybee] -extends = common_esp32_idf -build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_MKS_TINYBEE +[env:ESP32IDF-MKS-TINYBEE-WIFI] +extends = common_esp32 +framework = arduino, espidf +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -DENABLE_WIFI +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer -[env:espidf_mks_dlc32] -extends = common_esp32_idf -build_flags = ${common_esp32_idf.build_flags} -DBOARD=BOARD_MKS_DLC32 +[env:ESP32IDF-MKS-TINYBEE-BLUETOOTH] +extends = common_esp32 +framework = arduino, espidf +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -ENABLE_BLUETOOTH +lib_deps = SPI, Wire, BluetoothSerial diff --git a/uCNC/src/hal/boards/esp8266/esp8266.ini b/uCNC/src/hal/boards/esp8266/esp8266.ini index 80e7d93bf..2deec9412 100644 --- a/uCNC/src/hal/boards/esp8266/esp8266.ini +++ b/uCNC/src/hal/boards/esp8266/esp8266.ini @@ -2,7 +2,7 @@ # ESP8266 Boards # ################## -[env:d1] +[env:ESP8266-Wemos-D1-R2] platform = espressif8266 framework = arduino board = d1 diff --git a/uCNC/src/hal/boards/lpc176x/lpc176x.ini b/uCNC/src/hal/boards/lpc176x/lpc176x.ini index d6af83432..6d00d3b9a 100644 --- a/uCNC/src/hal/boards/lpc176x/lpc176x.ini +++ b/uCNC/src/hal/boards/lpc176x/lpc176x.ini @@ -11,17 +11,17 @@ lib_ldf_mode = off lib_compat_mode = strict build_flags = ${common.build_flags} -D NXP_LPC17xx -D USE_ARDUINO_CDC -[env:re_arm] +[env:LPC176X-RE-ARM] extends = common_lpc176x board = nxp_lpc1768 build_flags = ${common_lpc176x.build_flags} -D BOARD=BOARD_RE_ARM -[env:mks_base_v13] +[env:LPC176X-MKS-BASE-V1_3] extends = common_lpc176x board = nxp_lpc1768 build_flags = ${common_lpc176x.build_flags} -D BOARD=BOARD_MKS_BASE13 -[env:skr_v14_turbo] +[env:LPC176X-SKR-v1_4-TURBO] extends = common_lpc176x board = nxp_lpc1768 build_flags = ${common_lpc176x.build_flags} -D BOARD=BOARD_SKR_V14_TURBO diff --git a/uCNC/src/hal/boards/rp2040/rp2040.ini b/uCNC/src/hal/boards/rp2040/rp2040.ini index 057134d42..60c1dc9e3 100644 --- a/uCNC/src/hal/boards/rp2040/rp2040.ini +++ b/uCNC/src/hal/boards/rp2040/rp2040.ini @@ -19,13 +19,13 @@ board_build.f_cpu = 133000000L debug_tool = cmsis-dap upload_port = cmsis-dap -[env:rpi_pico] +[env:RP2040-PICO] extends = common_rp2040 board = rpipico lib_ignore = HTTPUpdateServer, LittleFS, WiFi, WebServer, WiFi, SerialBT, DNSServer, Hash build_flags = -DBOARD=BOARD_RPI_PICO -[env:rpi_pico_w] +[env:RP2040-PICO-W] extends = common_rp2040 board = rpipicow build_flags = -DBOARD=BOARD_RPI_PICO_W -DENABLE_WIFI -DENABLE_BLUETOOTH -DPIO_FRAMEWORK_ARDUINO_ENABLE_BLUETOOTH diff --git a/uCNC/src/hal/boards/samd21/samd21.ini b/uCNC/src/hal/boards/samd21/samd21.ini index 6e8d524ef..30ccd4ad6 100644 --- a/uCNC/src/hal/boards/samd21/samd21.ini +++ b/uCNC/src/hal/boards/samd21/samd21.ini @@ -19,12 +19,14 @@ lib_deps = https://github.com/Paciente8159/uCNC-tinyusb.git#v0.15.4 ; load ; monitor reset init -[env:arduinoM0] +[env:SAMD21-Wemos-M0] extends = common_samd21 build_flags = ${common_samd21.build_flags} -D BOARD=BOARD_MZERO board_build.offset = 0x2000 board_upload.offset_address = 0x00002000 -[env:arduinoZero] +[env:SAMD21-Arduino-Zero] extends = common_samd21 build_flags = ${common_samd21.build_flags} -D BOARD=BOARD_ZERO +board_build.offset = 0x4000 +board_upload.offset_address = 0x00004000 diff --git a/uCNC/src/hal/boards/stm32/stm32.ini b/uCNC/src/hal/boards/stm32/stm32.ini index aa5691a5a..ec37b6738 100644 --- a/uCNC/src/hal/boards/stm32/stm32.ini +++ b/uCNC/src/hal/boards/stm32/stm32.ini @@ -15,39 +15,41 @@ debug_init_cmds = monitor reset init build_flags = ${common.build_flags} -D HAL_TIM_MODULE_DISABLED -D HAL_EXTI_MODULE_DISABLED -D HAL_UART_MODULE_ONLY lib_deps = https://github.com/Paciente8159/uCNC-tinyusb.git#v0.15.4 -lib_ignore = EEPROM, SPI, Wire +; lib_ignore = EEPROM, SPI, Wire -[env:bluepill_f103c8] +[env:STM32F1-Bluepill-F103C8] extends = common_stm32 board = bluepill_f103c8 build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_BLUEPILL -DFLASH_SIZE=0x10000UL -[env:bluepill_f103c8_clone] +[env:STM32F1-Bluepill-F103C8-CLONE] extends = common_stm32 board = bluepill_f103c8 build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_BLUEPILL -DFLASH_SIZE=0x10000UL ; uncomment if it's a bluepill clone upload_flags = -c set CPUTAPID 0x2ba01477 -[env:blackpill_f401cc] +[env:STM32F1-MKS-Robin-Nano-V1_2] +extends = common_stm32 +board = genericSTM32F103VE +board_build.offset = 0x7000 +board_upload.offset_address = 0x08007000 +board_build.f_cpu = 72000000L +build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_MKS_ROBIN_NANO_V1_2 + +[env:STM32F4-Blackpill-F401CC] extends = common_stm32 board = blackpill_f401cc +upload_protocol = dfu build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_BLACKPILL -[env:blackpill_f411ce] +[env:STM32F4-Blackpill-F411CE] extends = common_stm32 board = blackpill_f411ce +upload_protocol = dfu build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_BLACKPILL -[env:mks_robin_nano_v1_2] -extends = common_stm32 -board = genericSTM32F103VE -board_build.offset = 0x7000 -board_upload.offset_address = 0x08007000 -board_build.f_cpu = 72000000L -build_flags = ${common_stm32.build_flags} -D BOARD=BOARD_MKS_ROBIN_NANO_V1_2 - -[env:skr_pro_v1_2] +[env:STM32F4-SKR-Pro-V1_2] extends = common_stm32 board = black_f407zg board_build.offset = 0x8000 diff --git a/uCNC/src/modules/ic74hc595.c b/uCNC/src/modules/ic74hc595.c index 1ac32605f..8e4e3c0c8 100644 --- a/uCNC/src/modules/ic74hc595.c +++ b/uCNC/src/modules/ic74hc595.c @@ -53,7 +53,7 @@ MCU_CALLBACK void __attribute__((weak)) ic74hc595_shift_io_pins(void) { do { - memcpy(pins, ic74hc595_io_pins, IC74HC595_COUNT); + memcpy(pins, (const void*)ic74hc595_io_pins, IC74HC595_COUNT); mcu_clear_output(IC74HC595_LATCH); for (uint8_t i = IC74HC595_COUNT; i != 0;) { diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index a190d10c6..8f2e6cf6c 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -1013,10 +1013,12 @@ bool system_menu_action_edit(uint8_t action, system_menu_item_t *item) case VAR_TYPE_INT16: case VAR_TYPE_UINT16: g_system_menu.current_multiplier = CLAMP(-1, currentmult, 4); + break; case VAR_TYPE_INT32: case VAR_TYPE_UINT32: case VAR_TYPE_FLOAT: g_system_menu.current_multiplier = CLAMP(-1, currentmult, 9); + break; } } diff --git a/uCNC/src/modules/tmc.c b/uCNC/src/modules/tmc.c index ab27eebe8..ccb99e55e 100644 --- a/uCNC/src/modules/tmc.c +++ b/uCNC/src/modules/tmc.c @@ -219,6 +219,7 @@ uint32_t tmc_write_register(tmc_driver_t *driver, uint8_t address, uint32_t val) val >>= 8; data[1] = (uint8_t)(val & 0xFF); driver->rw(data, 5, 5); + break; default: return TMC_WRITE_ERROR; } From 56575f2a9e1944f7c93fac6d8cb34b349ef1e484 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 14 Oct 2023 18:44:13 +0100 Subject: [PATCH 151/168] Fixed build option for STM32 --- uCNC/src/hal/boards/stm32/stm32.ini | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/uCNC/src/hal/boards/stm32/stm32.ini b/uCNC/src/hal/boards/stm32/stm32.ini index ec37b6738..1272c3968 100644 --- a/uCNC/src/hal/boards/stm32/stm32.ini +++ b/uCNC/src/hal/boards/stm32/stm32.ini @@ -15,7 +15,8 @@ debug_init_cmds = monitor reset init build_flags = ${common.build_flags} -D HAL_TIM_MODULE_DISABLED -D HAL_EXTI_MODULE_DISABLED -D HAL_UART_MODULE_ONLY lib_deps = https://github.com/Paciente8159/uCNC-tinyusb.git#v0.15.4 -; lib_ignore = EEPROM, SPI, Wire +lib_ignore = EEPROM +;, SPI, Wire [env:STM32F1-Bluepill-F103C8] extends = common_stm32 From d0e9f6ff8b807e2c636ad0dec8173a4460139eb2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 14 Oct 2023 18:50:21 +0100 Subject: [PATCH 152/168] Update esp32.ini --- uCNC/src/hal/boards/esp32/esp32.ini | 69 ++++++----------------------- 1 file changed, 14 insertions(+), 55 deletions(-) diff --git a/uCNC/src/hal/boards/esp32/esp32.ini b/uCNC/src/hal/boards/esp32/esp32.ini index 64bb89b98..0aea2c33e 100644 --- a/uCNC/src/hal/boards/esp32/esp32.ini +++ b/uCNC/src/hal/boards/esp32/esp32.ini @@ -7,88 +7,47 @@ platform = espressif32 framework = arduino board = esp32dev ; build_src_filter = +<*>- -build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE +build_flags = -mlongcalls -Wno-frame-address -ffunction-sections -fdata-sections -ggdb -Os -freorder-blocks -Wwrite-strings -fstack-protector -fstrict-volatile-bitfields -Wall -fno-jump-tables -fno-tree-switch-conversion -std=gnu++11 -fexceptions -MMD -c -DUSE_ARDUINO_EEPROM_LIBRARY -DCORE_DEBUG_LEVEL=ARDUHAL_LOG_LEVEL_NONE -DENABLE_WIFI -DENABLE_BLUETOOTH board_build.f_flash = 80000000L board_build.f_cpu = 240000000L board_build.partitions = min_spiffs.csv monitor_filters=esp32_exception_decoder upload_speed = 921600 -lib_deps = SPI, Wire +lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer, BluetoothSerial ################## # Arduino builds # ################## -[env:ESP32-Wemos-D1-R32-WIFI] +[env:ESP32-Wemos-D1-R32] extends = common_esp32 board = wemos_d1_uno32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -[env:ESP32-Wemos-D1-R32-BLUETOOTH] +[env:ESP32-MKS-DLC32] extends = common_esp32 -board = wemos_d1_uno32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial - -[env:ESP32-MKS-DLC32-WIFI] -extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer - -[env:ESP32-MKS-DLC32-BLUETOOTH] -extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -[env:ESP32-MKS-TINYBEE-WIFI] +[env:ESP32-MKS-TINYBEE] extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer - -[env:ESP32-MKS-TINYBEE-BLUETOOTH] -extends = common_esp32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE ################# # ESPIDF builds # ################# -[env:ESP32IDF-Wemos-D1-R32-WIFI] +[env:ESP32IDF-Wemos-D1-R32] extends = common_esp32 framework = arduino, espidf board = wemos_d1_uno32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer - -[env:ESP32IDF-Wemos-D1-R32-BLUETOOTH] -extends = common_esp32 -framework = arduino, espidf -board = wemos_d1_uno32 -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial - -[env:ESP32IDF-MKS-DLC32-WIFI] -extends = common_esp32 -framework = arduino, espidf -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer - -[env:ESP32IDF-MKS-DLC32-BLUETOOTH] -extends = common_esp32 -framework = arduino, espidf -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 -[env:ESP32IDF-MKS-TINYBEE-WIFI] +[env:ESP32IDF-MKS-DLC32] extends = common_esp32 framework = arduino, espidf -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -DENABLE_WIFI -lib_deps = SPI, Wire, Wifi, WebServer, HTTPUpdatedServer +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 -[env:ESP32IDF-MKS-TINYBEE-BLUETOOTH] +[env:ESP32IDF-MKS-TINYBEE] extends = common_esp32 framework = arduino, espidf -build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE -ENABLE_BLUETOOTH -lib_deps = SPI, Wire, BluetoothSerial +build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE From 584b0164e4c251a879b89bcdb8d33a7bc57ddd9d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sat, 14 Oct 2023 18:51:46 +0100 Subject: [PATCH 153/168] Update platformio.ini --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 36a714bbc..885467301 100644 --- a/platformio.ini +++ b/platformio.ini @@ -11,7 +11,7 @@ [platformio] include_dir=uCNC src_dir=uCNC -default_envs = AVR-UNO, AVR-MEGA2560-RAMPS-V1_4, AVR-RAMBO, SAMD21-Wemos-M0, STM32F1-Bluepill-F103C8, STM32F4-Blackpill-F401CC, ESP8266-Wemos-D1-R2, LPC176X-RE-ARM, ESP32-Wemos-D1-R32-WIFI, RP2040-PICO-W +default_envs = AVR-UNO, AVR-MEGA2560-RAMPS-V1_4, AVR-RAMBO, SAMD21-Wemos-M0, STM32F1-Bluepill-F103C8, STM32F4-Blackpill-F401CC, ESP8266-Wemos-D1-R2, LPC176X-RE-ARM, ESP32-Wemos-D1-R32, RP2040-PICO-W extra_configs = uCNC/src/hal/boards/avr/avr.ini uCNC/src/hal/boards/samd21/samd21.ini From 5495b252251e295b78bbde50c51d416b0b243c6f Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 15 Oct 2023 23:26:45 +0100 Subject: [PATCH 154/168] modified soft reset logic - modified soft reset logic to show startup message after softreset --- uCNC/src/cnc.c | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index cd62ac3f0..94ee1caaa 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -123,12 +123,11 @@ void cnc_run(void) // enters loop reset cnc_reset(); + cnc_state.loop_state = LOOP_RUNNING; + // tries to reset. If fails jumps to error while (cnc_unlock(false) != UNLOCK_ERROR) { - // serial_select(SERIAL_UART); - cnc_state.loop_state = LOOP_RUNNING; - do { } while (cnc_exec_cmd()); @@ -159,11 +158,10 @@ void cnc_run(void) } } cnc_dotasks(); - // a hard/soft reset is pending - if (cnc_state.alarm < 0) + // a soft reset is pending + if (cnc_state.alarm == EXEC_ALARM_SOFTRESET) { - cnc_state.loop_state = LOOP_STARTUP_RESET; - cnc_clear_exec_state(EXEC_KILL); + break; } } while (cnc_state.loop_state == LOOP_REQUIRE_RESET || cnc_get_exec_state(EXEC_KILL)); } @@ -707,6 +705,7 @@ void cnc_exec_rt_commands(void) } cnc_alarm(EXEC_ALARM_SOFTRESET); + cnc_state.loop_state = LOOP_STARTUP_RESET; return; } From fc138f7762e2edf6e8488d90681843235b5573d6 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Sun, 15 Oct 2023 23:28:42 +0100 Subject: [PATCH 155/168] fixed bug on laser pwm --- uCNC/src/hal/tools/tools/laser_pwm.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/uCNC/src/hal/tools/tools/laser_pwm.c b/uCNC/src/hal/tools/tools/laser_pwm.c index 05daa344f..43a11e24e 100644 --- a/uCNC/src/hal/tools/tools/laser_pwm.c +++ b/uCNC/src/hal/tools/tools/laser_pwm.c @@ -57,8 +57,6 @@ static void startup_code(void) #if ASSERT_PIN(LASER_PWM) io_config_pwm(LASER_PWM, LASER_FREQ); io_set_pwm(LASER_PWM, 0); -#else - io_set_pwm(LASER_PWM, 0); #endif previous_mode = g_settings.laser_mode; g_settings.laser_mode = LASER_PWM_MODE; From 712ce5564bb794e24a31016ab186448e7944552a Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 15:48:54 +0100 Subject: [PATCH 156/168] allow startup blocks to run --- uCNC/src/cnc.c | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 94ee1caaa..0cdee3985 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -23,8 +23,9 @@ #include "cnc.h" #define LOOP_STARTUP_RESET 0 -#define LOOP_RUNNING 1 -#define LOOP_FAULT 2 +#define LOOP_UNLOCK 1 +#define LOOP_RUNNING 2 +#define LOOP_FAULT 3 #define LOOP_REQUIRE_RESET 4 #define UNLOCK_OK 0 @@ -123,11 +124,12 @@ void cnc_run(void) // enters loop reset cnc_reset(); - cnc_state.loop_state = LOOP_RUNNING; + cnc_state.loop_state = LOOP_UNLOCK; // tries to reset. If fails jumps to error while (cnc_unlock(false) != UNLOCK_ERROR) { + cnc_state.loop_state = LOOP_RUNNING; do { } while (cnc_exec_cmd()); @@ -481,7 +483,7 @@ uint8_t cnc_unlock(bool force) // hard reset // if homing not enabled run startup blocks - if (cnc_state.loop_state == LOOP_STARTUP_RESET && !g_settings.homing_enabled) + if (cnc_state.loop_state < LOOP_RUNNING && !g_settings.homing_enabled) { cnc_run_startup_blocks(); } From a5add33e82a536d85dae4ee31df305d58e3b7164 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 16:10:36 +0100 Subject: [PATCH 157/168] Update parser.c --- uCNC/src/core/parser.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/core/parser.c b/uCNC/src/core/parser.c index 99508ba67..6a77a856c 100644 --- a/uCNC/src/core/parser.c +++ b/uCNC/src/core/parser.c @@ -584,8 +584,8 @@ static uint8_t parse_grbl_exec_code(uint8_t code) } else { - cnc_alarm(EXEC_ALARM_SOFTRESET); protocol_send_feedback(MSG_FEEDBACK_5); + cnc_alarm(EXEC_ALARM_SOFTRESET); } break; case GRBL_SEND_SETTINGS_RESET: From ad4b674b5a4618a812a3fbdd437f2c0855ad891e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 16:44:02 +0100 Subject: [PATCH 158/168] minor code modifications to allow AVR to fit --- uCNC/src/cnc.c | 68 ++++++++++++++++++++++++----------------- uCNC/src/core/planner.c | 14 ++------- uCNC/src/core/planner.h | 4 +-- 3 files changed, 44 insertions(+), 42 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 0cdee3985..8aa1b33fc 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -722,36 +722,48 @@ void cnc_exec_rt_commands(void) if (command) { cnc_state.feed_ovr_cmd = RT_CMD_CLEAR; // clears command flags - switch (command & RTCMD_NORMAL_MASK) + int8_t ovr = 0; + if (command & RTCMD_NORMAL_MASK) { - case RT_CMD_FEED_100: - planner_feed_ovr_reset(); - break; - case RT_CMD_FEED_INC_COARSE: - planner_feed_ovr_inc(FEED_OVR_COARSE); - break; - case RT_CMD_FEED_DEC_COARSE: - planner_feed_ovr_inc(-FEED_OVR_COARSE); - break; - case RT_CMD_FEED_INC_FINE: - planner_feed_ovr_inc(FEED_OVR_FINE); - break; - case RT_CMD_FEED_DEC_FINE: - planner_feed_ovr_inc(-FEED_OVR_FINE); - break; + switch (command & RTCMD_NORMAL_MASK) + { + case RT_CMD_FEED_100: + planner_feed_ovr_reset(); + break; + case RT_CMD_FEED_INC_COARSE: + ovr = FEED_OVR_COARSE; + break; + case RT_CMD_FEED_DEC_COARSE: + ovr = -FEED_OVR_COARSE; + break; + case RT_CMD_FEED_INC_FINE: + ovr = FEED_OVR_FINE; + break; + case RT_CMD_FEED_DEC_FINE: + ovr = -FEED_OVR_FINE; + break; + } + // if 0 does nothing + planner_feed_ovr_inc(ovr); } - switch (command & RTCMD_RAPID_MASK) + if ((command & RTCMD_RAPID_MASK)) { - case RT_CMD_RAPIDFEED_100: - planner_rapid_feed_ovr_reset(); - break; - case RT_CMD_RAPIDFEED_OVR1: - planner_rapid_feed_ovr(RAPID_FEED_OVR1); - break; - case RT_CMD_RAPIDFEED_OVR2: - planner_rapid_feed_ovr(RAPID_FEED_OVR2); - break; + // reset fast override by default + ovr = 100; + switch (command & RTCMD_RAPID_MASK) + { + // case RT_CMD_RAPIDFEED_100: + // ovr = 100; + // break; + case RT_CMD_RAPIDFEED_OVR1: + ovr = RAPID_FEED_OVR1; + break; + case RT_CMD_RAPIDFEED_OVR2: + ovr = RAPID_FEED_OVR2; + break; + } + planner_rapid_feed_ovr((uint8_t)ovr); } } @@ -1037,14 +1049,14 @@ void cnc_run_startup_blocks(void) serial_stream_eeprom(STARTUP_BLOCK0_ADDRESS_OFFSET); cnc_exec_cmd(); } - + serial_broadcast(true); if (settings_check_startup_gcode(STARTUP_BLOCK1_ADDRESS_OFFSET)) { serial_stream_eeprom(STARTUP_BLOCK1_ADDRESS_OFFSET); cnc_exec_cmd(); } - + // reset streams serial_stream_change(NULL); } diff --git a/uCNC/src/core/planner.c b/uCNC/src/core/planner.c index fd36c298a..59e1c3f32 100644 --- a/uCNC/src/core/planner.c +++ b/uCNC/src/core/planner.c @@ -286,7 +286,7 @@ void planner_init(void) #endif planner_buffer_clear(); planner_feed_ovr_reset(); - planner_rapid_feed_ovr_reset(); + planner_rapid_feed_ovr(100); #if TOOL_COUNT > 0 planner_spindle_ovr_reset(); planner_coolant_ovr_reset(); @@ -515,7 +515,7 @@ void planner_sync_tools(motion_data_t *block_data) } // overrides -void planner_feed_ovr_inc(uint8_t value) +void planner_feed_ovr_inc(int8_t value) { uint8_t ovr_val = g_planner_state.feed_override; ovr_val += value; @@ -550,16 +550,6 @@ void planner_feed_ovr_reset(void) } } -void planner_rapid_feed_ovr_reset(void) -{ - if (g_planner_state.rapid_feed_override != 100) - { - g_planner_state.rapid_feed_override = 100; - g_planner_state.ovr_counter = 0; - itp_update(); - } -} - #if TOOL_COUNT > 0 void planner_spindle_ovr_inc(uint8_t value) { diff --git a/uCNC/src/core/planner.h b/uCNC/src/core/planner.h index 6e99ba5f3..1a09ef8fd 100644 --- a/uCNC/src/core/planner.h +++ b/uCNC/src/core/planner.h @@ -99,9 +99,9 @@ extern "C" // overrides void planner_feed_ovr_reset(void); - void planner_feed_ovr_inc(uint8_t value); + void planner_feed_ovr_inc(int8_t value); - void planner_rapid_feed_ovr_reset(); + // void planner_rapid_feed_ovr_reset(); void planner_rapid_feed_ovr(uint8_t value); #if TOOL_COUNT > 0 void planner_spindle_ovr_reset(void); From b12f7851a9ef471e8f7f146a0020575757d7a748 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 21:45:29 +0100 Subject: [PATCH 159/168] Create new git workflow --- .github/workflows/pio-build.yaml | 41 ++++++++++++++++++++++++++++++++ 1 file changed, 41 insertions(+) create mode 100644 .github/workflows/pio-build.yaml diff --git a/.github/workflows/pio-build.yaml b/.github/workflows/pio-build.yaml new file mode 100644 index 000000000..08b416e54 --- /dev/null +++ b/.github/workflows/pio-build.yaml @@ -0,0 +1,41 @@ +name: PlatformIO CI Builds + +on: [push] + +jobs: + build: + runs-on: ubuntu-latest + strategy: + matrix: + boards: [LPC176X-RE-ARM, ESP32-MKS-DLC32, STM32F4-Blackpill-F411CE, AVR-X-Controller, ESP8266-Wemos-D1-R2, AVR-MKS-DLC, AVR-UNO, ESP32IDF-Wemos-D1-R32, STM32F1-Bluepill-F103C8-CLONE, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, AVR-CNC-Shield-V3, STM32F4-Blackpill-F401CC, ESP32IDF-MKS-DLC32, STM32F4-SKR-Pro-V1_2, RP2040-PICO, ESP32-Wemos-D1-R32, LPC176X-SKR-v1_4-TURBO, STM32F1-MKS-Robin-Nano-V1_2, AVR-MEGA2560-RAMPS-V1_4, LPC176X-MKS-BASE-V1_3, AVR-MKS-GEN-L-V1, SAMD21-Arduino-Zero, ESP32IDF-MKS-TINYBEE] + + steps: + - uses: actions/checkout@v4 + - name: Cache pip + uses: actions/cache@v3 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + - name: Cache PlatformIO + uses: actions/cache@v3 + with: + path: ~/.platformio + key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} + - name: Set up Python + uses: actions/setup-python@v4 + - name: Install PlatformIO + run: | + python -m pip install --upgrade pip + pip install --upgrade platformio + - name: Run PlatformIO + run: pio run -e ${{build.boards}} + - name: Upload binaries + uses: actions/upload-artifact@v3 + with: + name: ${{build.boards}} + path: | + .pio/build/${{build.boards}}/*.bin + .pio/build/${{build.boards}}/*.hex + .pio/build/${{build.boards}}/*.uf2 \ No newline at end of file From 117d9a5af74e87dec0bff69518848b0d39c9f5d2 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 21:52:47 +0100 Subject: [PATCH 160/168] Update pio-build.yaml --- .github/workflows/pio-build.yaml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/pio-build.yaml b/.github/workflows/pio-build.yaml index 08b416e54..66039dec0 100644 --- a/.github/workflows/pio-build.yaml +++ b/.github/workflows/pio-build.yaml @@ -30,12 +30,12 @@ jobs: python -m pip install --upgrade pip pip install --upgrade platformio - name: Run PlatformIO - run: pio run -e ${{build.boards}} + run: pio run -e ${{matrix.boards}} - name: Upload binaries uses: actions/upload-artifact@v3 with: - name: ${{build.boards}} + name: ${{matrix.boards}} path: | - .pio/build/${{build.boards}}/*.bin - .pio/build/${{build.boards}}/*.hex - .pio/build/${{build.boards}}/*.uf2 \ No newline at end of file + .pio/build/${{matrix.boards}}/*.bin + .pio/build/${{matrix.boards}}/*.hex + .pio/build/${{matrix.boards}}/*.uf2 \ No newline at end of file From 3a60a4a162f34d2f2223c74c8af13eb6875a1bd1 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 21:58:28 +0100 Subject: [PATCH 161/168] fix MKS-DLC build error --- uCNC/src/hal/boards/avr/avr.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uCNC/src/hal/boards/avr/avr.ini b/uCNC/src/hal/boards/avr/avr.ini index 38759aae2..fe793d72f 100644 --- a/uCNC/src/hal/boards/avr/avr.ini +++ b/uCNC/src/hal/boards/avr/avr.ini @@ -32,7 +32,7 @@ extends = atmega328p build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_X_CONTROLLER [env:AVR-MKS-DLC] -extends = common_avr +extends = atmega328p board_build.f_cpu = 20000000UL build_flags = ${atmega328p.build_flags} -D BOARD=BOARD_MKS_DLC From 1ea7f852532f0c8b647ce699494f61b2e770566d Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 22:07:51 +0100 Subject: [PATCH 162/168] Update pio-build.yaml --- .github/workflows/pio-build.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/pio-build.yaml b/.github/workflows/pio-build.yaml index 66039dec0..e09bc0b8d 100644 --- a/.github/workflows/pio-build.yaml +++ b/.github/workflows/pio-build.yaml @@ -25,6 +25,8 @@ jobs: key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} - name: Set up Python uses: actions/setup-python@v4 + with: + python-version: '3.10' - name: Install PlatformIO run: | python -m pip install --upgrade pip From 8764ed9f672e54aa09bb201a9b33bd5945e7f771 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Mon, 16 Oct 2023 22:13:10 +0100 Subject: [PATCH 163/168] Update pio-build.yaml --- .github/workflows/pio-build.yaml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.github/workflows/pio-build.yaml b/.github/workflows/pio-build.yaml index e09bc0b8d..09331069e 100644 --- a/.github/workflows/pio-build.yaml +++ b/.github/workflows/pio-build.yaml @@ -6,8 +6,9 @@ jobs: build: runs-on: ubuntu-latest strategy: - matrix: - boards: [LPC176X-RE-ARM, ESP32-MKS-DLC32, STM32F4-Blackpill-F411CE, AVR-X-Controller, ESP8266-Wemos-D1-R2, AVR-MKS-DLC, AVR-UNO, ESP32IDF-Wemos-D1-R32, STM32F1-Bluepill-F103C8-CLONE, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, AVR-CNC-Shield-V3, STM32F4-Blackpill-F401CC, ESP32IDF-MKS-DLC32, STM32F4-SKR-Pro-V1_2, RP2040-PICO, ESP32-Wemos-D1-R32, LPC176X-SKR-v1_4-TURBO, STM32F1-MKS-Robin-Nano-V1_2, AVR-MEGA2560-RAMPS-V1_4, LPC176X-MKS-BASE-V1_3, AVR-MKS-GEN-L-V1, SAMD21-Arduino-Zero, ESP32IDF-MKS-TINYBEE] + fail-fast: false # Allow all machines to finish building + matrix: + boards: [LPC176X-RE-ARM, ESP32-MKS-DLC32, STM32F4-Blackpill-F411CE, AVR-X-Controller, ESP8266-Wemos-D1-R2, AVR-MKS-DLC, AVR-UNO, ESP32IDF-Wemos-D1-R32, STM32F1-Bluepill-F103C8-CLONE, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, AVR-CNC-Shield-V3, STM32F4-Blackpill-F401CC, ESP32IDF-MKS-DLC32, STM32F4-SKR-Pro-V1_2, RP2040-PICO, ESP32-Wemos-D1-R32, LPC176X-SKR-v1_4-TURBO, STM32F1-MKS-Robin-Nano-V1_2, AVR-MEGA2560-RAMPS-V1_4, LPC176X-MKS-BASE-V1_3, AVR-MKS-GEN-L-V1, SAMD21-Arduino-Zero, ESP32IDF-MKS-TINYBEE] steps: - uses: actions/checkout@v4 From 5d00ccf9a6e97c7fd7007ba19d6b5f329c28075c Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 17 Oct 2023 11:31:29 +0100 Subject: [PATCH 164/168] simplified overrides - simplified override functions like implemented on #531 --- uCNC/src/cnc.c | 76 +++++++++++++++------------------- uCNC/src/core/planner.c | 46 ++++++-------------- uCNC/src/core/planner.h | 8 +--- uCNC/src/modules/system_menu.c | 8 ++-- 4 files changed, 52 insertions(+), 86 deletions(-) diff --git a/uCNC/src/cnc.c b/uCNC/src/cnc.c index 8aa1b33fc..de77c7bc3 100644 --- a/uCNC/src/cnc.c +++ b/uCNC/src/cnc.c @@ -722,48 +722,37 @@ void cnc_exec_rt_commands(void) if (command) { cnc_state.feed_ovr_cmd = RT_CMD_CLEAR; // clears command flags - int8_t ovr = 0; - if (command & RTCMD_NORMAL_MASK) + uint8_t ovr = g_planner_state.feed_override; + switch (command & RTCMD_NORMAL_MASK) { - switch (command & RTCMD_NORMAL_MASK) - { - case RT_CMD_FEED_100: - planner_feed_ovr_reset(); - break; - case RT_CMD_FEED_INC_COARSE: - ovr = FEED_OVR_COARSE; - break; - case RT_CMD_FEED_DEC_COARSE: - ovr = -FEED_OVR_COARSE; - break; - case RT_CMD_FEED_INC_FINE: - ovr = FEED_OVR_FINE; - break; - case RT_CMD_FEED_DEC_FINE: - ovr = -FEED_OVR_FINE; - break; - } - // if 0 does nothing - planner_feed_ovr_inc(ovr); + case RT_CMD_FEED_100: + planner_feed_ovr(100); + break; + case RT_CMD_FEED_INC_COARSE: + planner_feed_ovr(ovr + FEED_OVR_COARSE); + break; + case RT_CMD_FEED_DEC_COARSE: + planner_feed_ovr(ovr - FEED_OVR_COARSE); + break; + case RT_CMD_FEED_INC_FINE: + planner_feed_ovr(ovr + FEED_OVR_FINE); + break; + case RT_CMD_FEED_DEC_FINE: + planner_feed_ovr(ovr - FEED_OVR_FINE); + break; } - if ((command & RTCMD_RAPID_MASK)) + switch (command & RTCMD_RAPID_MASK) { - // reset fast override by default - ovr = 100; - switch (command & RTCMD_RAPID_MASK) - { - // case RT_CMD_RAPIDFEED_100: - // ovr = 100; - // break; - case RT_CMD_RAPIDFEED_OVR1: - ovr = RAPID_FEED_OVR1; - break; - case RT_CMD_RAPIDFEED_OVR2: - ovr = RAPID_FEED_OVR2; - break; - } - planner_rapid_feed_ovr((uint8_t)ovr); + case RT_CMD_RAPIDFEED_100: + planner_rapid_feed_ovr(100); + break; + case RT_CMD_RAPIDFEED_OVR1: + planner_rapid_feed_ovr(RAPID_FEED_OVR1); + break; + case RT_CMD_RAPIDFEED_OVR2: + planner_rapid_feed_ovr(RAPID_FEED_OVR2); + break; } } @@ -772,24 +761,25 @@ void cnc_exec_rt_commands(void) if (command) { cnc_state.tool_ovr_cmd = RT_CMD_CLEAR; // clears command flags + uint8_t ovr = g_planner_state.spindle_speed_override; update_tools = true; switch (command & RTCMD_SPINDLE_MASK) { #if TOOL_COUNT > 0 case RT_CMD_SPINDLE_100: - planner_spindle_ovr_reset(); + planner_spindle_ovr(100); break; case RT_CMD_SPINDLE_INC_COARSE: - planner_spindle_ovr_inc(SPINDLE_OVR_COARSE); + planner_spindle_ovr(ovr + SPINDLE_OVR_COARSE); break; case RT_CMD_SPINDLE_DEC_COARSE: - planner_spindle_ovr_inc(-SPINDLE_OVR_COARSE); + planner_spindle_ovr(ovr - SPINDLE_OVR_COARSE); break; case RT_CMD_SPINDLE_INC_FINE: - planner_spindle_ovr_inc(SPINDLE_OVR_FINE); + planner_spindle_ovr(ovr + SPINDLE_OVR_FINE); break; case RT_CMD_SPINDLE_DEC_FINE: - planner_spindle_ovr_inc(-SPINDLE_OVR_FINE); + planner_spindle_ovr(ovr - SPINDLE_OVR_FINE); break; case RT_CMD_SPINDLE_TOGGLE: if (cnc_get_exec_state(EXEC_HOLD | EXEC_DOOR | EXEC_RUN) == EXEC_HOLD) // only available if a TRUE hold is active diff --git a/uCNC/src/core/planner.c b/uCNC/src/core/planner.c index 59e1c3f32..7e8986a45 100644 --- a/uCNC/src/core/planner.c +++ b/uCNC/src/core/planner.c @@ -285,10 +285,10 @@ void planner_init(void) #endif #endif planner_buffer_clear(); - planner_feed_ovr_reset(); + planner_feed_ovr(100); planner_rapid_feed_ovr(100); #if TOOL_COUNT > 0 - planner_spindle_ovr_reset(); + planner_spindle_ovr(100); planner_coolant_ovr_reset(); #endif } @@ -515,16 +515,13 @@ void planner_sync_tools(motion_data_t *block_data) } // overrides -void planner_feed_ovr_inc(int8_t value) +void planner_feed_ovr(uint8_t value) { - uint8_t ovr_val = g_planner_state.feed_override; - ovr_val += value; - ovr_val = MAX(ovr_val, FEED_OVR_MIN); - ovr_val = MIN(ovr_val, FEED_OVR_MAX); - - if (ovr_val != g_planner_state.feed_override) + value = CLAMP(FEED_OVR_MIN, value, FEED_OVR_MAX); + + if (value != g_planner_state.feed_override) { - g_planner_state.feed_override = ovr_val; + g_planner_state.feed_override = value; g_planner_state.ovr_counter = 0; itp_update(); } @@ -532,6 +529,8 @@ void planner_feed_ovr_inc(int8_t value) void planner_rapid_feed_ovr(uint8_t value) { + value = CLAMP(FEED_OVR_MIN, value, FEED_OVR_MAX); + if (g_planner_state.rapid_feed_override != value) { g_planner_state.rapid_feed_override = value; @@ -540,37 +539,18 @@ void planner_rapid_feed_ovr(uint8_t value) } } -void planner_feed_ovr_reset(void) -{ - if (g_planner_state.feed_override != 100) - { - g_planner_state.feed_override = 100; - g_planner_state.ovr_counter = 0; - itp_update(); - } -} - #if TOOL_COUNT > 0 -void planner_spindle_ovr_inc(uint8_t value) +void planner_spindle_ovr(uint8_t value) { - uint8_t ovr_val = g_planner_state.spindle_speed_override; - ovr_val += value; - ovr_val = MAX(ovr_val, SPINDLE_OVR_MIN); - ovr_val = MIN(ovr_val, SPINDLE_OVR_MAX); + value = CLAMP(SPINDLE_OVR_MIN, value, SPINDLE_OVR_MAX); - if (ovr_val != g_planner_state.spindle_speed_override) + if (value != g_planner_state.spindle_speed_override) { - g_planner_state.spindle_speed_override = ovr_val; + g_planner_state.spindle_speed_override = value; g_planner_state.ovr_counter = 0; } } -void planner_spindle_ovr_reset(void) -{ - g_planner_state.spindle_speed_override = 100; - g_planner_state.ovr_counter = 0; -} - static uint8_t coolant_override; uint8_t planner_get_coolant(void) diff --git a/uCNC/src/core/planner.h b/uCNC/src/core/planner.h index 1a09ef8fd..0af35ce42 100644 --- a/uCNC/src/core/planner.h +++ b/uCNC/src/core/planner.h @@ -98,14 +98,10 @@ extern "C" void planner_sync_tools(motion_data_t *block_data); // overrides - void planner_feed_ovr_reset(void); - void planner_feed_ovr_inc(int8_t value); - - // void planner_rapid_feed_ovr_reset(); + void planner_feed_ovr(uint8_t value); void planner_rapid_feed_ovr(uint8_t value); #if TOOL_COUNT > 0 - void planner_spindle_ovr_reset(void); - void planner_spindle_ovr_inc(uint8_t value); + void planner_spindle_ovr(uint8_t value); uint8_t planner_coolant_ovr_toggle(uint8_t value); void planner_coolant_ovr_reset(void); #endif diff --git a/uCNC/src/modules/system_menu.c b/uCNC/src/modules/system_menu.c index 8f2e6cf6c..ba0ed6044 100644 --- a/uCNC/src/modules/system_menu.c +++ b/uCNC/src/modules/system_menu.c @@ -699,10 +699,10 @@ static bool system_menu_action_overrides(uint8_t action, system_menu_item_t *ite switch (override) { case 'f': - planner_feed_ovr_inc(FEED_OVR_FINE); + cnc_call_rt_command(CMD_CODE_FEED_INC_FINE); break; case 's': - planner_spindle_ovr_inc(SPINDLE_OVR_FINE); + cnc_call_rt_command(CMD_CODE_SPINDLE_INC_FINE); break; } break; @@ -710,10 +710,10 @@ static bool system_menu_action_overrides(uint8_t action, system_menu_item_t *ite switch (override) { case 'f': - planner_feed_ovr_inc(-FEED_OVR_FINE); + cnc_call_rt_command(CMD_CODE_FEED_DEC_FINE); break; case 's': - planner_spindle_ovr_inc(-SPINDLE_OVR_FINE); + cnc_call_rt_command(CMD_CODE_SPINDLE_DEC_FINE); break; } break; From aa6f0f4217b4601c0bb6042517dbda366bce4a6b Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 17 Oct 2023 18:43:22 +0100 Subject: [PATCH 165/168] updated workflows --- .github/workflows/arduino-test.yaml | 65 ---------------- .github/workflows/pio-build.yaml | 19 +++-- .github/workflows/pio-release.yaml | 75 +++++++++++++++++++ .../{platformio.yaml => pio-test.yaml} | 18 +++-- 4 files changed, 99 insertions(+), 78 deletions(-) delete mode 100644 .github/workflows/arduino-test.yaml create mode 100644 .github/workflows/pio-release.yaml rename .github/workflows/{platformio.yaml => pio-test.yaml} (55%) diff --git a/.github/workflows/arduino-test.yaml b/.github/workflows/arduino-test.yaml deleted file mode 100644 index 8bc57b846..000000000 --- a/.github/workflows/arduino-test.yaml +++ /dev/null @@ -1,65 +0,0 @@ -# This is the name of the workflow, visible on GitHub UI. -name: Test Arduino - -# Here we tell GitHub to run the workflow when a commit -# is pushed or a Pull Request is opened. -on: [pull_request] - -# This is the list of jobs that will be run concurrently. -# Since we use a build matrix, the actual number of jobs -# started depends on how many configurations the matrix -# will produce. -jobs: - # This is the name of the job - can be whatever. - test-matrix: - - # Here we tell GitHub that the jobs must be determined - # dynamically depending on a matrix configuration. - strategy: - matrix: - # The matrix will produce one job for each configuration - # parameter of type arduino-platform, in this case a - # total of 2. - # buildoptions: ["ENABLE_BACKLASH_COMPENSATION", "ENABLE_DUAL_DRIVE_AXIS"] - # arduino-platform: ["arduino:samd", "arduino:avr"] - arduino-platform: ["arduino:avr"] - # This is usually optional but we need to statically define the - # FQBN of the boards we want to test for each platform. In the - # future the CLI might automatically detect and download the core - # needed to compile against a certain FQBN, at that point the - # following include section will be useless. - include: - # This works like this: when the platform is "arduino:samd", the - # variable fqbn is set to "arduino:samd:nano_33_iot". - # - arduino-platform: "arduino:samd" - # fqbn: "arduino:samd:arduino_zero_native" - - arduino-platform: "arduino:avr" - fqbn: "arduino:avr:uno" - - # This is the platform GitHub will use to run our workflow, we - # pick Windows for no particular reason. - runs-on: windows-latest - - # This is the list of steps this job will run. - steps: - # First of all, we clone the repo using the checkout action. - - name: Checkout - uses: actions/checkout@master - - # We use the arduino/setup-arduino-cli action to install and - # configure the Arduino CLI on the system. - - name: Setup Arduino CLI - uses: arduino/setup-arduino-cli@v1.1.1 - - # We then install the platform, which one will be determined - # dynamically by the build matrix. - - name: Install platform - run: | - arduino-cli core update-index - arduino-cli core install ${{ matrix.arduino-platform }} - - # Finally, we compile the sketch, using the FQBN that was set - # in the build matrix. - - name: Compile Sketch - run: arduino-cli compile --fqbn ${{ matrix.fqbn }} --build-property ./uCNC - #run: arduino-cli compile --fqbn ${{ matrix.fqbn }} --build-property build.extra_flags=-D${{ matrix.buildoptions }} ./uCNC diff --git a/.github/workflows/pio-build.yaml b/.github/workflows/pio-build.yaml index 09331069e..490b6b84f 100644 --- a/.github/workflows/pio-build.yaml +++ b/.github/workflows/pio-build.yaml @@ -1,6 +1,12 @@ name: PlatformIO CI Builds -on: [push] +on: + push: + branches: + - master + pull_request: + branches: + - master jobs: build: @@ -9,7 +15,7 @@ jobs: fail-fast: false # Allow all machines to finish building matrix: boards: [LPC176X-RE-ARM, ESP32-MKS-DLC32, STM32F4-Blackpill-F411CE, AVR-X-Controller, ESP8266-Wemos-D1-R2, AVR-MKS-DLC, AVR-UNO, ESP32IDF-Wemos-D1-R32, STM32F1-Bluepill-F103C8-CLONE, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, AVR-CNC-Shield-V3, STM32F4-Blackpill-F401CC, ESP32IDF-MKS-DLC32, STM32F4-SKR-Pro-V1_2, RP2040-PICO, ESP32-Wemos-D1-R32, LPC176X-SKR-v1_4-TURBO, STM32F1-MKS-Robin-Nano-V1_2, AVR-MEGA2560-RAMPS-V1_4, LPC176X-MKS-BASE-V1_3, AVR-MKS-GEN-L-V1, SAMD21-Arduino-Zero, ESP32IDF-MKS-TINYBEE] - + steps: - uses: actions/checkout@v4 - name: Cache pip @@ -34,11 +40,12 @@ jobs: pip install --upgrade platformio - name: Run PlatformIO run: pio run -e ${{matrix.boards}} + - name: Zip binaries + run: zip ${{matrix.boards}}.zip .pio/build/${{matrix.boards}}/firmware.* - name: Upload binaries uses: actions/upload-artifact@v3 with: name: ${{matrix.boards}} - path: | - .pio/build/${{matrix.boards}}/*.bin - .pio/build/${{matrix.boards}}/*.hex - .pio/build/${{matrix.boards}}/*.uf2 \ No newline at end of file + path: ./${{matrix.boards}}.zip + - name: Display structure of downloaded files + run: ls -R diff --git a/.github/workflows/pio-release.yaml b/.github/workflows/pio-release.yaml new file mode 100644 index 000000000..0bf5c62b7 --- /dev/null +++ b/.github/workflows/pio-release.yaml @@ -0,0 +1,75 @@ +name: PlatformIO CI Release + +on: + push: + tags: + - 'v*' + +jobs: + create_release: + name: Create release + runs-on: ubuntu-latest + outputs: + upload_url: ${{ steps.create_release.outputs.upload_url }} + steps: + - name: Create release + id: create_release + uses: actions/create-release@v1 + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + with: + tag_name: ${{ github.ref }} + release_name: µCNC ${{ github.ref }} + draft: false + prerelease: false + + build_release: + runs-on: ubuntu-latest + needs: create_release + strategy: + fail-fast: false # Allow all machines to finish building + matrix: + boards: [LPC176X-RE-ARM, ESP32-MKS-DLC32, STM32F4-Blackpill-F411CE, AVR-X-Controller, ESP8266-Wemos-D1-R2, AVR-MKS-DLC, AVR-UNO, ESP32IDF-Wemos-D1-R32, STM32F1-Bluepill-F103C8-CLONE, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, AVR-CNC-Shield-V3, STM32F4-Blackpill-F401CC, ESP32IDF-MKS-DLC32, STM32F4-SKR-Pro-V1_2, RP2040-PICO, ESP32-Wemos-D1-R32, LPC176X-SKR-v1_4-TURBO, STM32F1-MKS-Robin-Nano-V1_2, AVR-MEGA2560-RAMPS-V1_4, LPC176X-MKS-BASE-V1_3, AVR-MKS-GEN-L-V1, SAMD21-Arduino-Zero, ESP32IDF-MKS-TINYBEE] + steps: + - uses: actions/checkout@v4 + - name: Cache pip + uses: actions/cache@v3 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + - name: Cache PlatformIO + uses: actions/cache@v3 + with: + path: ~/.platformio + key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} + - name: Set up Python + uses: actions/setup-python@v4 + with: + python-version: '3.10' + - name: Install PlatformIO + run: | + python -m pip install --upgrade pip + pip install --upgrade platformio + - name: Run PlatformIO + run: pio run -e ${{matrix.boards}} + - name: Zip binaries + run: zip ${{matrix.boards}}.zip .pio/build/${{matrix.boards}}/firmware.* + - name: Upload binaries + uses: actions/upload-artifact@v3 + with: + name: ${{matrix.boards}} + path: ./${{matrix.boards}}.zip + - name: Display structure of downloaded files + run: ls -R + - name: Upload Release Asset + id: upload-release-asset + uses: actions/upload-release-asset@v1 + env: + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + with: + upload_url: ${{ needs.create_release.outputs.upload_url }} # This pulls from the CREATE RELEASE step above, referencing it's ID to get its outputs object, which include a `upload_url`. See this blog post for more info: https://jasonet.co/posts/new-features-of-github-actions/#passing-data-to-future-steps + asset_path: ./${{matrix.boards}}.zip + asset_name: ${{matrix.boards}}.zip + asset_content_type: application/zip diff --git a/.github/workflows/platformio.yaml b/.github/workflows/pio-test.yaml similarity index 55% rename from .github/workflows/platformio.yaml rename to .github/workflows/pio-test.yaml index 38e7c497e..7154745e3 100644 --- a/.github/workflows/platformio.yaml +++ b/.github/workflows/pio-test.yaml @@ -1,31 +1,35 @@ -name: PlatformIO CI +name: PlatformIO CI Tests on: [push] jobs: build: - + strategy: + matrix: + boards: [LPC176X-RE-ARM, ESP8266-Wemos-D1-R2, AVR-UNO, ESP32-MKS-TINYBEE, STM32F1-Bluepill-F103C8, AVR-RAMBO, RP2040-PICO-W, SAMD21-Wemos-M0, STM32F4-Blackpill-F401CC, AVR-MEGA2560-RAMPS-V1_4] runs-on: ubuntu-latest steps: - - uses: actions/checkout@v2 + - uses: actions/checkout@v4 - name: Cache pip - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: ~/.cache/pip key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} restore-keys: | ${{ runner.os }}-pip- - name: Cache PlatformIO - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: ~/.platformio key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} - name: Set up Python - uses: actions/setup-python@v2 + uses: actions/setup-python@v4 + with: + python-version: '3.10' - name: Install PlatformIO run: | python -m pip install --upgrade pip pip install --upgrade platformio - name: Run PlatformIO - run: pio run \ No newline at end of file + run: pio run -e ${{matrix.boards}} From 172eb25c09b896857d0ab0aa8367fff6cb7d470e Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Tue, 17 Oct 2023 22:38:17 +0100 Subject: [PATCH 166/168] Update esp32.ini --- uCNC/src/hal/boards/esp32/esp32.ini | 3 +++ 1 file changed, 3 insertions(+) diff --git a/uCNC/src/hal/boards/esp32/esp32.ini b/uCNC/src/hal/boards/esp32/esp32.ini index 0aea2c33e..4faac889e 100644 --- a/uCNC/src/hal/boards/esp32/esp32.ini +++ b/uCNC/src/hal/boards/esp32/esp32.ini @@ -39,15 +39,18 @@ build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE [env:ESP32IDF-Wemos-D1-R32] extends = common_esp32 framework = arduino, espidf +platform_packages = platformio/framework-espidf@3.40405.230623 board = wemos_d1_uno32 build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_WEMOS_D1_R32 [env:ESP32IDF-MKS-DLC32] extends = common_esp32 framework = arduino, espidf +platform_packages = platformio/framework-espidf@3.40405.230623 build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_DLC32 [env:ESP32IDF-MKS-TINYBEE] extends = common_esp32 framework = arduino, espidf +platform_packages = platformio/framework-espidf@3.40405.230623 build_flags = ${common_esp32.build_flags} -DBOARD=BOARD_MKS_TINYBEE From d9259371b3ee3ebc4a37b66c60a91c349aff7dc3 Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 18 Oct 2023 10:52:25 +0100 Subject: [PATCH 167/168] updated readmes --- CHANGELOG.md | 30 ++++++++++++++++++++++++++---- README.md | 17 +++++++++++++---- 2 files changed, 39 insertions(+), 8 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 6594c2e7d..1a9366fd5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,22 +8,43 @@ # Changelog -## [1.8.0] - unreleased +## [1.8.0] - 18-10-2023 ### Added - added status report extender callcack (#454) -- added Plasma THC velocity anty-dive (#456) +- added Plasma THC velocity anti-dive (#456) +- added initial Scara Kinematics (#460) ### Changed -- Unified interpolator run function and new S-Curve acceleration profiles (#458) +- unified interpolator run function and new S-Curve acceleration profiles (#458) - implemented Plasma THC status report callback (#454) -- Plasma THC tool update via PID callback (#453) +- plasma THC tool update via PID callback (#453) +- configurable S curve patterns (#459) +- moved custom MCodes to laser ppi compilation unit (#464) +- added new RT Hooks inside interpolator step ITP, to be used by laser PPI and G33 (#464) +- moved all ESP32 I2S IO update calls to core0 (#485) +- added frequency clamp to step to frequency functions (#485) +- complete redesign of multiaxis system (#477) +- new autolevel with multi axis config (#477) +- fixed ITP for multi step linear actuators (#477) +- modified homing and added support for multi axis homing in parallel (#477) +- integrated backlash filtering in the rt segment flags (#477) +- modified cnc delay to run dotasks instead of only io_dotasks (#513) +- prevent re-entrant code inside dotasks events (#513) +- redesign the main loop tasks to prevent re-entrant code on the event callbacks (#513) +- force interlocking check before getting the alarm to force alarm code refresh if alarm condition is triggered by ISR (#513) +- fixed scara kinematics code to match new multi axis (#513) +- complete redesign of the serial communication to deal with multi-stream/sources and allow future expansions (#529) ### Fixed - step output generation from beta (#457) +- fixed tool helper macros (#468) +- fixed bug in skew compensation (#476) +- fixed 74HC595 concurrency race (#478) +- fixed hold issue on version1.8 that keeps generating steps until the end of the motion (#489) ## [1.7.6] - 17-10-2023 @@ -40,6 +61,7 @@ - fixed RUN state clear after alarm while running (#520) - fixed pin status report function in command $P (#525) - fixed IO input and output macros for RP2040 (#526) +- fixed RP2040 input change ISR macro (#526) ## [1.7.5] - 26-09-2023 diff --git a/README.md b/README.md index f3dd1f922..c4c0a54ae 100644 --- a/README.md +++ b/README.md @@ -13,9 +13,13 @@ Although most of the options are configurable via the web tool, some options mig # VERSION 1.8+ NOTES -Version 1.8 introduced some small but breaking changes to tools functions declarations. This version also introduces a new IO HAL that makes io abstraction easier. Previous version modules should work in this version but future module will begin to use this new IO HALL. Previous modules will be also gradually converted to use this new IO HAL. +Version 1.8 introduced several breaking changes from the previous version. These are: + - Tools functions declarations. This version also introduces a new IO HAL that makes io abstraction easier and more performant. + - New serial/multi-stream interface. All communications ports and extension modules (displays, SD cards, etc..) that communicate to the parser now do it via a custom serial stream implementation. Serial streams are segregated and responses are sent back to the source only instead of all ports. Some types of messages are still broadcast (like status reports, alarms and feedback messages). + - Modules now also defines HOOKs that can be used as hookable points for a single consumer function. + - There are several README documents that contain relevant information about parts of the system/HAL/modules etc. This makes it easier to keep the information up to date with each change. -Version 1.7 introduced some small but breaking changes to modules function declarations. If you are upgrading from a previous version you need to upgrade the modules also. Modules for previous versions are available in the releases section of the [µCNC-modules repository](https://github.com/Paciente8159/uCNC-modules). +With version 1.8 µCNC is becomming too large for Atmega328P (still supports it, but barelly fits). For that reason and to keep giving support for this MCU a branch of version 1.7 will be maintained with all the latest bugfixes and patches. # IMPORTANT NOTE @@ -65,7 +69,10 @@ Version 1.8 added the following new major features. - added realtime modification of step and dir bits to be executed in the fly. - added new tool for plasma THC. - all analog inputs were modified from 8bit resolution to 10bit. -- complete redesign of PID module and modiified tools functions to make use of PID update loop. +- complete redesign of PID module and modified tools functions to make use of PID update loop. +- complete redesign of serial communications to support and deal with multi-stream/origins. +- complete redesign of multi-stepper axis and self-squaring axis. +- initial support for Scara kinematics Version 1.7 added a new major feature. @@ -229,6 +236,7 @@ Currently µCNC supports the following kinematics: - CoreXY - Linear delta robot - Rotary delta robot +- Scara ### µCNC roadmap @@ -241,9 +249,10 @@ These changes are: Future versions are in plan for: -- Add support for graphical LCD +- Add support for Web interface - Add more GCode features and hardware modules - Add additional kinematics +- Add HAL for new MCU ### Building µCNC From 84e64368e0df2175e43b05b988d49e99d59e89cf Mon Sep 17 00:00:00 2001 From: Paciente8159 Date: Wed, 18 Oct 2023 11:48:33 +0100 Subject: [PATCH 168/168] updated ESP32 readmes --- CHANGELOG.md | 1 + uCNC/src/hal/mcus/esp32/README.md | 2 ++ 2 files changed, 3 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 1a9366fd5..09bc4312e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -15,6 +15,7 @@ - added status report extender callcack (#454) - added Plasma THC velocity anti-dive (#456) - added initial Scara Kinematics (#460) +- added ESP32 optional optimized compilation using ESPIDF and Arduino as a component ### Changed diff --git a/uCNC/src/hal/mcus/esp32/README.md b/uCNC/src/hal/mcus/esp32/README.md index c9ef25f0a..74149ea5b 100644 --- a/uCNC/src/hal/mcus/esp32/README.md +++ b/uCNC/src/hal/mcus/esp32/README.md @@ -8,6 +8,8 @@ _µCNC for ESP32 can be built this way_ 4. Edit ```cnc_config.h file``` and ```cnc_hal_config.h file``` to fit your needs and board. 5. If needed edit the platformio.ini file environment for your board. Compile the sketch and upload it to your board. +ESP32 on PlatformIO now prevents 2 flavors of the same souce code. The normal Arduino compilation and a version using ESPIDF and Arduino as a component. This second version adds an optimizations to timer ISR that make step generation smoother in particular using 74HC595 IO extension. It's possible to also make changes to build more performant code if for example you want to compile code with only WiFi or Bluetooth, by tweaking the options on the ```sdkconfig.deafults``` file. + **Note** ESP32 boards build environments are available in two flavors. Regular Arduino and an ESPIDF with Arduino as a component that has some optimized options for low latency timer ISR. ## Method two - Arduino IDE (easiest)