From 83325ebf78d9f0e654cb5bf029126d1bfbea26ad Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 23 Mar 2023 08:44:25 +1100 Subject: [PATCH 001/310] Initial I2C native driver --- I2CManager_STM32.h | 322 ++++++++++++++++++++++++++++++++++----------- 1 file changed, 242 insertions(+), 80 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index a55fd2e..58a623d 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -38,7 +38,10 @@ * bus on the SAMD architecture ***************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) -void I2C1_IRQHandler() { +extern "C" void I2C1_EV_IRQHandler(void) { + I2CManager.handleInterrupt(); +} +extern "C" void I2C1_ER_IRQHandler(void) { I2CManager.handleInterrupt(); } #endif @@ -91,44 +94,60 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Use 10x the rise time spec to enable integer divide of 62.5ns clock period uint16_t t_rise; uint32_t ccr_freq; - if (i2cClockSpeed < 200000L) { - // i2cClockSpeed = 100000L; - t_rise = 0x11; // (1000ns /62.5ns) + 1; - } - else if (i2cClockSpeed < 800000L) + + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Disable the I2C device, as TRISE can only be programmed whilst disabled + s->CR1 &= ~(I2C_CR1_PE); // Disable I2C + // Software reset the I2C peripheral + // s->CR1 |= I2C_CR1_SWRST; // reset the I2C + // delay(1); + // Release reset + // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + + if (i2cClockSpeed > 100000L) { - i2cClockSpeed = 400000L; - t_rise = 0x06; // (300ns / 62.5ns) + 1; - // } else if (i2cClockSpeed < 1200000L) { - // i2cClockSpeed = 1000000L; - // t_rise = 120; + if (i2cClockSpeed > 400000L) + i2cClockSpeed = 400000L; + + t_rise = 0x06; // (300ns /62.5ns) + 1; } else { i2cClockSpeed = 100000L; t_rise = 0x11; // (1000ns /62.5ns) + 1; } + // Configure the rise time register + s->TRISE = t_rise; - // Enable the I2C master mode - s->CR1 &= ~(I2C_CR1_PE); // Enable I2C - // Software reset the I2C peripheral - // s->CR1 |= I2C_CR1_SWRST; // reset the I2C - // Release reset - // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation - - // Calculate baudrate - using a rise time appropriate for the speed + // DIAG(F("Setting I2C clock to: %d"), i2cClockSpeed); + // Calculate baudrate ccr_freq = I2C_BUSFREQ * 1000000 / i2cClockSpeed / 2; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = (uint16_t)ccr_freq; - - // Configure the rise time register - s->TRISE = t_rise; // 1000 ns / 62.5 ns = 16 + 1 + if (i2cClockSpeed > 100000L) + s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set + else + s->CCR = (uint16_t)ccr_freq; // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + digitalWrite(D13, HIGH); + DIAG(F("I2C: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -136,32 +155,46 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { ***************************************************************************/ void I2CManagerClass::I2C_init() { - //Setting up the clocks - RCC->APB1ENR |= (1<<21); // Enable I2C CLOCK - RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9 + // Setting up the clocks + RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK + // Reset the I2C1 peripheral to initial state + RCC->APB1RSTR |= RCC_APB1RSTR_I2C1RST; + RCC->APB1RSTR &= ~RCC_APB1RSTR_I2C1RST; // Standard I2C pins are SCL on PB8 and SDA on PB9 + RCC->AHB1ENR |= (1<<1); // Enable GPIOB CLOCK for PB8/PB9 // Bits (17:16)= 1:0 --> Alternate Function for Pin PB8; // Bits (19:18)= 1:0 --> Alternate Function for Pin PB9 + GPIOB->MODER &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all MODER bits for PB8 and PB9 GPIOB->MODER |= (2<<(8*2)) | (2<<(9*2)); // PB8 and PB9 set to ALT function GPIOB->OTYPER |= (1<<8) | (1<<9); // PB8 and PB9 set to open drain output capability GPIOB->OSPEEDR |= (3<<(8*2)) | (3<<(9*2)); // PB8 and PB9 set to High Speed mode + GPIOB->PUPDR &= ~((3<<(8*2)) | (3<<(9*2))); // Clear all PUPDR bits for PB8 and PB9 GPIOB->PUPDR |= (1<<(8*2)) | (1<<(9*2)); // PB8 and PB9 set to pull-up capability // Alt Function High register routing pins PB8 and PB9 for I2C1: // Bits (3:2:1:0) = 0:1:0:0 --> AF4 for pin PB8 // Bits (7:6:5:4) = 0:1:0:0 --> AF4 for pin PB9 + GPIOB->AFR[1] &= ~((15<<0) | (15<<4)); // Clear all AFR bits for PB8 on low nibble, PB9 on next nibble up GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up - // Software reset the I2C peripheral + // // Software reset the I2C peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C - s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + asm("nop"); // wait a bit... suggestion from online! + s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation + // Clear all bits in I2C CR2 register except reserved bits + s->CR2 &= 0xE000; // Program the peripheral input clock in CR2 Register in order to generate correct timings s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz + // set own address to 00 - not really used in master mode + I2C1->OAR1 |= (1 << 14); // bit 14 should be kept at 1 according to the datasheet + #if defined(I2C_USE_INTERRUPTS) // Setting NVIC - NVIC_SetPriority(I2C_IRQn, 1); // Match default priorities - NVIC_EnableIRQ(I2C_IRQn); + NVIC_SetPriority(I2C1_EV_IRQn, 1); // Match default priorities + NVIC_EnableIRQ(I2C1_EV_IRQn); + NVIC_SetPriority(I2C1_ER_IRQn, 1); // Match default priorities + NVIC_EnableIRQ(I2C1_ER_IRQn); // CR2 Interrupt Settings // Bit 15-13: reserved @@ -172,8 +205,8 @@ void I2CManagerClass::I2C_init() // Bit 8: ITERREN - Error interrupt enable // Bit 7-6: reserved // Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz) - // s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts - s->CR2 |= 0x0300; // Enable Event and Error interrupts + s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts + // s->CR2 |= 0x0300; // Enable Event and Error interrupts #endif // Calculate baudrate and set default rate for now @@ -181,14 +214,26 @@ void I2CManagerClass::I2C_init() // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = 0x0050; + s->CCR = 0x50; // Configure the rise time register - max allowed in 1000ns s->TRISE = 0x0011; // 1000 ns / 62.5 ns = 16 + 1 // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Setting bus idle mode and wait for sync + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + DIAG(F("I2C: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -198,49 +243,56 @@ void I2CManagerClass::I2C_sendStart() { // Set counters here in case this is a retry. rxCount = txCount = 0; - uint8_t temp; - - // On a single-master I2C bus, the start bit won't be sent until the bus - // state goes to IDLE so we can request it without waiting. On a - // multi-master bus, the bus may be BUSY under control of another master, + // On a single-master I2C bus, the start bit won't be sent until the bus + // state goes to IDLE so we can request it without waiting. On a + // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. - // If anything to send, initiate write. Otherwise initiate read. - if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) - { - // Send start for read operation - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 |= I2C_CR1_START; // Generate START - // Send address with read flag (1) or'd in - s->DR = (deviceAddress << 1) | 1; // send the address - while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set - // Special case for 1 byte reads! - if (bytesToReceive == 1) - { - s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit - temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition - s->CR1 |= I2C_CR1_STOP; // Stop I2C + // Send start for read operation + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; } - else - temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit } - else { - // Send start for write operation - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 |= I2C_CR1_START; // Generate START - // Send address with write flag (0) or'd in - s->DR = (deviceAddress << 1) | 0; // send the address - while (!(s->SR1 && I2C_SR1_ADDR)); // wait for ADDR bit to set - temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + if (timeout) { + DIAG(F("I2C_sendStart: SR2->BUSY timeout")); + // delay(1000); } + s->CR1 |= I2C_CR1_ACK; // Enable the ACK + s->CR1 &= ~(I2C_CR1_POS); // Reset the POS bit - only used for 2-byte reception + s->CR1 |= I2C_CR1_START; // Generate START } /*************************************************************************** * Initiate a stop bit for transmission (does not interrupt) ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { - s->CR1 |= I2C_CR1_STOP; // Stop I2C + uint32_t temp; + + s->CR1 |= I2C_CR1_STOP; // Stop I2C + temp = s->SR1 | s->SR2; // Read the status registers to clear them + while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further + // writes to CR1 while STOP is being executed! + // Wait for bus to be clear? + unsigned long startTime = micros(); + bool timeout = false; + while (s->SR2 & I2C_SR2_BUSY) { + if (micros() - startTime >= 500UL) { + timeout = true; + break; + } + } + if (timeout) { + DIAG(F("I2C_sendStop: SR2->BUSY timeout")); + // delay(1000); + } } /*************************************************************************** @@ -252,9 +304,11 @@ void I2CManagerClass::I2C_close() { s->CR1 &= ~I2C_CR1_PE; // Disable I2C peripheral // Should never happen, but wait for up to 500us only. unsigned long startTime = micros(); - while ((s->CR1 && I2C_CR1_PE) != 0) { + while ((s->CR1 & I2C_CR1_PE) != 0) { if (micros() - startTime >= 500UL) break; } + NVIC_DisableIRQ(I2C1_EV_IRQn); + NVIC_DisableIRQ(I2C1_ER_IRQn); } /*************************************************************************** @@ -263,50 +317,158 @@ void I2CManagerClass::I2C_close() { * (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()). ***************************************************************************/ void I2CManagerClass::I2C_handleInterrupt() { + volatile uint16_t temp_sr1, temp_sr2, temp; + static bool led_lit = false; - if (s->SR1 && I2C_SR1_ARLO) { + temp_sr1 = s->SR1; + // if (temp_sr1 & I2C_SR1_ADDR) + // temp_sr2 = s->SR2; + + // Check to see if start bit sent - SB interrupt! + if (temp_sr1 & I2C_SR1_SB) + { + // If anything to send, initiate write. Otherwise initiate read. + if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) + { + // Send address with read flag (1) or'd in + s->DR = (deviceAddress << 1) | 1; // send the address + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // // // Special case for 1 byte reads! + // if (bytesToReceive == 1) + // { + // s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit + // temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition + // s->CR1 |= I2C_CR1_STOP; // Stop I2C + // } + // else + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else + { + // Send address with write flag (0) or'd in + s->DR = (deviceAddress << 1) | 0; // send the address + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set + // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else if (temp_sr1 & I2C_SR1_ADDR) { + // Receive 1 byte (AN2824 figure 2) + if (bytesToReceive == 1) { + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK final byte + // EV6_1 must be atomic operation (AN2824) + // noInterrupts(); + (void)s->SR2; // read SR2 to complete clearing the ADDR bit + I2C_sendStop(); // send stop + // interrupts(); + } + // Receive 2 bytes (AN2824 figure 2) + else if (bytesToReceive == 2) { + s->CR1 |= I2C_CR1_POS; // Set POS flag (NACK position next) + // EV6_1 must be atomic operation (AN2824) + // noInterrupts(); + (void)s->SR2; // read SR2 to complete clearing the ADDR bit + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK byte + // interrupts(); + } + else + temp = temp_sr1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit + } + else if (temp_sr1 & I2C_SR1_AF) + { + s->SR1 &= ~(I2C_SR1_AF); // Clear AF + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + while (s->SR1 & I2C_SR1_AF); // Check AF cleared + I2C_sendStop(); // Clear the bus + completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; + state = I2C_STATE_COMPLETED; + } + else if (temp_sr1 & I2C_SR1_ARLO) + { // Arbitration lost, restart - I2C_sendStart(); // Reinitiate request - } else if (s->SR1 && I2C_SR1_BERR) { + s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + I2C_sendStop(); + I2C_sendStart(); // Reinitiate request + // state = I2C_STATE_COMPLETED; + } + else if (temp_sr1 & I2C_SR1_BERR) + { // Bus error + s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + I2C_sendStop(); // Clear the bus completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; - } else if (s->SR1 && I2C_SR1_TXE) { + } + else if (temp_sr1 & I2C_SR1_TXE) + { + // temp_sr2 = s->SR2; // Master write completed - if (s->SR1 && (1<<10)) { - // Nacked, send stop. + if (temp_sr1 & I2C_SR1_AF) { + // Nacked + s->SR1 &= ~(I2C_SR1_AF); // Clear AF + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + // send stop. I2C_sendStop(); completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; state = I2C_STATE_COMPLETED; } else if (bytesToSend) { // Acked, so send next byte + while ((s->SR1 & I2C_SR1_BTF)); // Check BTF before proceeding s->DR = sendBuffer[txCount++]; bytesToSend--; - } else if (bytesToReceive) { - // Last sent byte acked and no more to send. Send repeated start, address and read bit. + // } else if (bytesToReceive) { + // // Last sent byte acked and no more to send. Send repeated start, address and read bit. + // s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK + // I2C_sendStart(); // s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1; } else { + // No bytes left to send or receive // Check both TxE/BTF == 1 before generating stop - while (!(s->SR1 && I2C_SR1_TXE)); // Check TxE - while (!(s->SR1 && I2C_SR1_BTF)); // Check BTF + // while (!(s->SR1 & I2C_SR1_TXE)); // Check TxE + while ((s->SR1 & I2C_SR1_BTF)); // Check BTF // No more data to send/receive. Initiate a STOP condition and finish + s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK I2C_sendStop(); + // completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } - } else if (s->SR1 && I2C_SR1_RXNE) { + } + else if (temp_sr1 & I2C_SR1_RXNE) + { // Master read completed without errors if (bytesToReceive == 1) { -// s->I2CM.CTRLB.bit.ACKACT = 1; // NAK final byte + s->CR1 &= ~I2C_CR1_ACK; // NAK final byte I2C_sendStop(); // send stop receiveBuffer[rxCount++] = s->DR; // Store received byte bytesToReceive = 0; + // completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; - } else if (bytesToReceive) { -// s->I2CM.CTRLB.bit.ACKACT = 0; // ACK all but final byte + } + else if (bytesToReceive == 2) + { + // Also needs to be atomic! + // noInterrupts(); + I2C_sendStop(); receiveBuffer[rxCount++] = s->DR; // Store received byte + // interrupts(); + } + else if (bytesToReceive) + { + s->CR1 &= ~(I2C_CR1_ACK); // ACK all but final byte + receiveBuffer[rxCount++] = s->DR; // Store received byte bytesToReceive--; } } + else + { + // DIAG(F("Unhandled I2C interrupt!")); + led_lit = ~led_lit; + digitalWrite(D13, led_lit); + // delay(1000); + } } #endif /* I2CMANAGER_STM32_H */ From cc2846d932461ace1c546d956812f943f78adaa0 Mon Sep 17 00:00:00 2001 From: Neil McKechnie Date: Mon, 27 Mar 2023 00:20:59 +0100 Subject: [PATCH 002/310] STM32 Native I2C first working version Working for reads and writes, needs more testing and perhaps a polish. --- I2CManager.h | 3 +- I2CManager_STM32.h | 437 +++++++++++++++++++++------------------------ defines.h | 6 +- 3 files changed, 213 insertions(+), 233 deletions(-) diff --git a/I2CManager.h b/I2CManager.h index b1003e6..ede30cc 100644 --- a/I2CManager.h +++ b/I2CManager.h @@ -539,7 +539,8 @@ private: uint8_t deviceAddress; const uint8_t *sendBuffer; uint8_t *receiveBuffer; - + uint8_t transactionState = 0; + volatile uint32_t pendingClockSpeed = 0; void startTransaction(); diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 58a623d..5132640 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -49,7 +49,11 @@ extern "C" void I2C1_ER_IRQHandler(void) { // Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants I2C_TypeDef *s = I2C1; #define I2C_IRQn I2C1_EV_IRQn -#define I2C_BUSFREQ 16 + +// Peripheral Input Clock speed in MHz. +// For STM32F446RE, the speed is 45MHz. Ideally, this should be determined +// at run-time from the APB1 clock, as it can vary from STM32 family to family. +#define I2C_PERIPH_CLK 45 // I2C SR1 Status Register #1 bit definitions for convenience // #define I2C_SR1_SMBALERT (1<<15) // SMBus alert @@ -83,15 +87,20 @@ I2C_TypeDef *s = I2C1; // #define I2C_CR1_SMBUS (1<<1) // SMBus mode, 1=SMBus, 0=I2C // #define I2C_CR1_PE (1<<0) // I2C Peripheral enable +// States of the STM32 I2C driver state machine +enum {TS_IDLE,TS_START,TS_W_ADDR,TS_W_DATA,TS_W_STOP,TS_R_ADDR,TS_R_DATA,TS_R_STOP}; + + /*************************************************************************** * Set I2C clock speed register. This should only be called outside of * a transmission. The I2CManagerClass::_setClock() function ensures * that it is only called at the beginning of an I2C transaction. ***************************************************************************/ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { + return; // Calculate a rise time appropriate to the requested bus speed - // Use 10x the rise time spec to enable integer divide of 62.5ns clock period + // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; uint32_t ccr_freq; @@ -110,44 +119,31 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { if (i2cClockSpeed > 400000L) i2cClockSpeed = 400000L; - t_rise = 0x06; // (300ns /62.5ns) + 1; + t_rise = 300; // nanoseconds } else { i2cClockSpeed = 100000L; - t_rise = 0x11; // (1000ns /62.5ns) + 1; + t_rise = 1000; // nanoseconds } // Configure the rise time register - s->TRISE = t_rise; - - // DIAG(F("Setting I2C clock to: %d"), i2cClockSpeed); - // Calculate baudrate - ccr_freq = I2C_BUSFREQ * 1000000 / i2cClockSpeed / 2; + s->TRISE = t_rise * I2C_PERIPH_CLK / 1000UL + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode - // Bit 14: Duty, fast mode duty cycle - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - if (i2cClockSpeed > 100000L) + // Bit 14: Duty, fast mode duty cycle (use 2:1) + // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns + if (i2cClockSpeed > 100000L) { + // In fast mode, I2C period is 3 * CCR * TPCLK1. + ccr_freq = I2C_PERIPH_CLK * 1000000 / 3 / i2cClockSpeed; s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set - else + } else { + // In standard mode, I2C period is 2 * CCR * TPCLK1. + ccr_freq = I2C_PERIPH_CLK * 1000000 / 2 / i2cClockSpeed; s->CCR = (uint16_t)ccr_freq; + } // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - digitalWrite(D13, HIGH); - DIAG(F("I2C: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -176,18 +172,19 @@ void I2CManagerClass::I2C_init() GPIOB->AFR[1] &= ~((15<<0) | (15<<4)); // Clear all AFR bits for PB8 on low nibble, PB9 on next nibble up GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up - // // Software reset the I2C peripheral + // Software reset the I2C peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C asm("nop"); // wait a bit... suggestion from online! s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation // Clear all bits in I2C CR2 register except reserved bits s->CR2 &= 0xE000; - // Program the peripheral input clock in CR2 Register in order to generate correct timings - s->CR2 |= I2C_BUSFREQ; // PCLK1 FREQUENCY in MHz - // set own address to 00 - not really used in master mode - I2C1->OAR1 |= (1 << 14); // bit 14 should be kept at 1 according to the datasheet + // Set I2C peripheral clock frequency + s->CR2 |= I2C_PERIPH_CLK; + + // set own address to 00 - not used in master mode + I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet #if defined(I2C_USE_INTERRUPTS) // Setting NVIC @@ -205,35 +202,21 @@ void I2CManagerClass::I2C_init() // Bit 8: ITERREN - Error interrupt enable // Bit 7-6: reserved // Bit 5-0: FREQ - Peripheral clock frequency (max 50MHz) - s->CR2 |= 0x0700; // Enable Buffer, Event and Error interrupts - // s->CR2 |= 0x0300; // Enable Event and Error interrupts + s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts #endif // Calculate baudrate and set default rate for now // Configure the Clock Control Register for 100KHz SCL frequency // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns, so CCR divisor must be 0x50 (80 * 62.5ns = 5000ns) - s->CCR = 0x50; + // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) + s->CCR = I2C_PERIPH_CLK * 5; - // Configure the rise time register - max allowed in 1000ns - s->TRISE = 0x0011; // 1000 ns / 62.5 ns = 16 + 1 + // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. + s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -243,56 +226,27 @@ void I2CManagerClass::I2C_sendStart() { // Set counters here in case this is a retry. rxCount = txCount = 0; + // On a single-master I2C bus, the start bit won't be sent until the bus // state goes to IDLE so we can request it without waiting. On a // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. - // Send start for read operation - while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further - // writes to CR1 while STOP is being executed! - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C_sendStart: SR2->BUSY timeout")); - // delay(1000); - } - s->CR1 |= I2C_CR1_ACK; // Enable the ACK - s->CR1 &= ~(I2C_CR1_POS); // Reset the POS bit - only used for 2-byte reception - s->CR1 |= I2C_CR1_START; // Generate START + // Check there's no STOP still in progress. If we OR the START bit into CR1 + // and the STOP bit is already set, we could output multiple STOP conditions. + while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset + + s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit + s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START + transactionState = TS_START; } /*************************************************************************** * Initiate a stop bit for transmission (does not interrupt) ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { - uint32_t temp; - s->CR1 |= I2C_CR1_STOP; // Stop I2C - temp = s->SR1 | s->SR2; // Read the status registers to clear them - while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further - // writes to CR1 while STOP is being executed! - // Wait for bus to be clear? - unsigned long startTime = micros(); - bool timeout = false; - while (s->SR2 & I2C_SR2_BUSY) { - if (micros() - startTime >= 500UL) { - timeout = true; - break; - } - } - if (timeout) { - DIAG(F("I2C_sendStop: SR2->BUSY timeout")); - // delay(1000); - } } /*************************************************************************** @@ -317,157 +271,182 @@ void I2CManagerClass::I2C_close() { * (and therefore, indirectly, from I2CRB::wait() and I2CRB::isBusy()). ***************************************************************************/ void I2CManagerClass::I2C_handleInterrupt() { - volatile uint16_t temp_sr1, temp_sr2, temp; - static bool led_lit = false; + volatile uint16_t temp_sr1, temp_sr2; temp_sr1 = s->SR1; - // if (temp_sr1 & I2C_SR1_ADDR) - // temp_sr2 = s->SR2; - // Check to see if start bit sent - SB interrupt! - if (temp_sr1 & I2C_SR1_SB) - { - // If anything to send, initiate write. Otherwise initiate read. - if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) + // Check for errors first + if (temp_sr1 & (I2C_SR1_AF | I2C_SR1_ARLO | I2C_SR1_BERR)) { + // Check which error flag is set + if (temp_sr1 & I2C_SR1_AF) { - // Send address with read flag (1) or'd in - s->DR = (deviceAddress << 1) | 1; // send the address - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // // // Special case for 1 byte reads! - // if (bytesToReceive == 1) - // { - // s->CR1 &= ~I2C_CR1_ACK; // clear the ACK bit - // temp = I2C1->SR1 | I2C1->SR2; // read SR1 and SR2 to clear the ADDR bit.... EV6 condition - // s->CR1 |= I2C_CR1_STOP; // Stop I2C - // } - // else - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else - { - // Send address with write flag (0) or'd in - s->DR = (deviceAddress << 1) | 0; // send the address - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - // while (!(s->SR1 & I2C_SR1_ADDR)); // wait for ADDR bit to set - // temp = s->SR1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else if (temp_sr1 & I2C_SR1_ADDR) { - // Receive 1 byte (AN2824 figure 2) - if (bytesToReceive == 1) { - s->CR1 &= ~I2C_CR1_ACK; // Disable ACK final byte - // EV6_1 must be atomic operation (AN2824) - // noInterrupts(); - (void)s->SR2; // read SR2 to complete clearing the ADDR bit - I2C_sendStop(); // send stop - // interrupts(); - } - // Receive 2 bytes (AN2824 figure 2) - else if (bytesToReceive == 2) { - s->CR1 |= I2C_CR1_POS; // Set POS flag (NACK position next) - // EV6_1 must be atomic operation (AN2824) - // noInterrupts(); - (void)s->SR2; // read SR2 to complete clearing the ADDR bit - s->CR1 &= ~I2C_CR1_ACK; // Disable ACK byte - // interrupts(); - } - else - temp = temp_sr1 | s->SR2; // read SR1 and SR2 to clear the ADDR bit - } - else if (temp_sr1 & I2C_SR1_AF) - { - s->SR1 &= ~(I2C_SR1_AF); // Clear AF - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - while (s->SR1 & I2C_SR1_AF); // Check AF cleared - I2C_sendStop(); // Clear the bus - completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; - state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_ARLO) - { - // Arbitration lost, restart - s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); - I2C_sendStart(); // Reinitiate request - // state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_BERR) - { - // Bus error - s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); // Clear the bus - completionStatus = I2C_STATUS_BUS_ERROR; - state = I2C_STATE_COMPLETED; - } - else if (temp_sr1 & I2C_SR1_TXE) - { - // temp_sr2 = s->SR2; - // Master write completed - if (temp_sr1 & I2C_SR1_AF) { - // Nacked s->SR1 &= ~(I2C_SR1_AF); // Clear AF - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - // send stop. - I2C_sendStop(); + I2C_sendStop(); // Clear the bus + transactionState = TS_IDLE; completionStatus = I2C_STATUS_NEGATIVE_ACKNOWLEDGE; state = I2C_STATE_COMPLETED; - } else if (bytesToSend) { - // Acked, so send next byte - while ((s->SR1 & I2C_SR1_BTF)); // Check BTF before proceeding - s->DR = sendBuffer[txCount++]; - bytesToSend--; - // } else if (bytesToReceive) { - // // Last sent byte acked and no more to send. Send repeated start, address and read bit. - // s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - // I2C_sendStart(); - // s->I2CM.ADDR.bit.ADDR = (deviceAddress << 1) | 1; - } else { - // No bytes left to send or receive - // Check both TxE/BTF == 1 before generating stop - // while (!(s->SR1 & I2C_SR1_TXE)); // Check TxE - while ((s->SR1 & I2C_SR1_BTF)); // Check BTF - // No more data to send/receive. Initiate a STOP condition and finish - s->CR1 &= ~(I2C_CR1_ACK); // Clear ACK - I2C_sendStop(); - // completionStatus = I2C_STATUS_OK; + } + else if (temp_sr1 & I2C_SR1_ARLO) + { + // Arbitration lost, restart + s->SR1 &= ~(I2C_SR1_ARLO); // Clear ARLO + I2C_sendStart(); // Reinitiate request + transactionState = TS_START; + } + else if (temp_sr1 & I2C_SR1_BERR) + { + // Bus error + s->SR1 &= ~(I2C_SR1_BERR); // Clear BERR + I2C_sendStop(); // Clear the bus + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; } - } - else if (temp_sr1 & I2C_SR1_RXNE) - { - // Master read completed without errors - if (bytesToReceive == 1) { - s->CR1 &= ~I2C_CR1_ACK; // NAK final byte - I2C_sendStop(); // send stop - receiveBuffer[rxCount++] = s->DR; // Store received byte - bytesToReceive = 0; - // completionStatus = I2C_STATUS_OK; - state = I2C_STATE_COMPLETED; + } else { + // No error flags, so process event according to current state. + switch (transactionState) { + case TS_START: + if (temp_sr1 & I2C_SR1_SB) { + // Event EV5 + // Start bit has been sent successfully and we have the bus. + // If anything to send, initiate write. Otherwise initiate read. + if (operation == OPERATION_READ || ((operation == OPERATION_REQUEST) && !bytesToSend)) { + // Send address with read flag (1) or'd in + s->DR = (deviceAddress << 1) | 1; // send the address + transactionState = TS_R_ADDR; + } else { + // Send address with write flag (0) or'd in + s->DR = (deviceAddress << 1) | 0; // send the address + transactionState = TS_W_ADDR; + } + } + // SB bit is cleared by writing to DR (already done). + break; + + case TS_W_ADDR: + if (temp_sr1 & I2C_SR1_ADDR) { + // Event EV6 + // Address sent successfully, device has ack'd in response. + if (!bytesToSend) { + I2C_sendStop(); + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } else { + transactionState = TS_W_DATA; + } + } + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + break; + + case TS_W_DATA: + if (temp_sr1 & I2C_SR1_TXE) { + // Event EV8_1/EV8/EV8_2 + // Transmitter empty, write a byte to it. + if (bytesToSend) { + s->DR = sendBuffer[txCount++]; + bytesToSend--; + } + // See if we're finished sending + if (!bytesToSend) { + // Wait for last byte to be sent. + transactionState = TS_W_STOP; + } + } + break; + + case TS_W_STOP: + if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { + // Event EV8_2 + // Write finished. + if (bytesToReceive) { + // Start a read operation by sending (re)start + I2C_sendStart(); + } else { + // Done. + I2C_sendStop(); + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } + } + break; + + case TS_R_ADDR: + if (temp_sr1 & I2C_SR1_ADDR) { + // Event EV6 + // Address sent for receive. + // The next bit is different depending on whether there are + // 1 byte, 2 bytes or >2 bytes to be received, in accordance with the + // Programmers Reference RM0390. + if (bytesToReceive == 1) { + // Receive 1 byte + s->CR1 &= ~I2C_CR1_ACK; // Disable ack + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_STOP; + // Next step will occur after a BTF interrupt + } else if (bytesToReceive == 2) { + // Receive 2 bytes + s->CR1 &= ~I2C_CR1_ACK; // Disable ACK for final byte + s->CR1 |= I2C_CR1_POS; // set POS flag to delay effect of ACK flag + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_STOP; + } else { + // >2 bytes, just wait for bytes to come in and ack them for the time being + // (ack flag has already been set). + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + transactionState = TS_R_DATA; + } + } + break; + + case TS_R_DATA: + // Event EV7/EV7_1 + if (temp_sr1 & I2C_SR1_BTF) { + // Byte received in receiver - read next byte + if (bytesToReceive == 3) { + // Getting close to the last byte, so a specific sequence is recommended. + s->CR1 &= ~I2C_CR1_ACK; // Reset ack for next byte received. + transactionState = TS_R_STOP; + } + receiveBuffer[rxCount++] = s->DR; // Store received byte + bytesToReceive--; + } + break; + + case TS_R_STOP: + if (temp_sr1 & I2C_SR1_BTF) { + // Event EV7 (last one) + // When we've got here, the receiver has got the last two bytes + // (or one byte, if only one byte is being received), + // and NAK has already been sent, so we need to read from the receiver. + if (bytesToReceive) { + if (bytesToReceive > 1) + I2C_sendStop(); + while(bytesToReceive) { + receiveBuffer[rxCount++] = s->DR; // Store received byte(s) + bytesToReceive--; + } + // Finish. + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } + } else if (temp_sr1 & I2C_SR1_RXNE) { + if (bytesToReceive == 1) { + // One byte on a single-byte transfer. Ack has already been set. + I2C_sendStop(); + receiveBuffer[rxCount++] = s->DR; // Store received byte + bytesToReceive--; + // Finish. + transactionState = TS_IDLE; + completionStatus = I2C_STATUS_OK; + state = I2C_STATE_COMPLETED; + } else + s->SR1 &= I2C_SR1_RXNE; // Acknowledge interrupt + } + break; } - else if (bytesToReceive == 2) - { - // Also needs to be atomic! - // noInterrupts(); - I2C_sendStop(); - receiveBuffer[rxCount++] = s->DR; // Store received byte - // interrupts(); - } - else if (bytesToReceive) - { - s->CR1 &= ~(I2C_CR1_ACK); // ACK all but final byte - receiveBuffer[rxCount++] = s->DR; // Store received byte - bytesToReceive--; - } - } - else - { - // DIAG(F("Unhandled I2C interrupt!")); - led_lit = ~led_lit; - digitalWrite(D13, led_lit); - // delay(1000); } } diff --git a/defines.h b/defines.h index 5582e8b..ab9cf45 100644 --- a/defines.h +++ b/defines.h @@ -144,9 +144,9 @@ #define DISABLE_EEPROM #endif // STM32 support for native I2C is awaiting development - #ifndef I2C_USE_WIRE - #define I2C_USE_WIRE - #endif + // #ifndef I2C_USE_WIRE + // #define I2C_USE_WIRE + // #endif /* TODO when ready From 4f56837d28198e2cee8af66ad757f3d3c8040bb7 Mon Sep 17 00:00:00 2001 From: Neil McKechnie Date: Tue, 28 Mar 2023 18:07:52 +0100 Subject: [PATCH 003/310] Fixes to timeout handling (due to STM32 micros() difference). --- I2CManager.cpp | 2 +- I2CManager.h | 4 ++-- I2CManager_NonBlocking.h | 13 ++++++---- I2CManager_STM32.h | 52 ++++++++++++++++++++++++++++++++-------- 4 files changed, 54 insertions(+), 17 deletions(-) diff --git a/I2CManager.cpp b/I2CManager.cpp index d0d8550..1d1387e 100644 --- a/I2CManager.cpp +++ b/I2CManager.cpp @@ -92,7 +92,7 @@ void I2CManagerClass::begin(void) { // Probe and list devices. Use standard mode // (clock speed 100kHz) for best device compatibility. _setClock(100000); - unsigned long originalTimeout = _timeout; + uint32_t originalTimeout = _timeout; setTimeout(1000); // use 1ms timeout for probes #if defined(I2C_EXTENDED_ADDRESS) diff --git a/I2CManager.h b/I2CManager.h index ede30cc..08d81d4 100644 --- a/I2CManager.h +++ b/I2CManager.h @@ -485,7 +485,7 @@ private: // When retries are enabled, the timeout applies to each // try, and failure from timeout does not get retried. // A value of 0 means disable timeout monitoring. - unsigned long _timeout = 100000UL; + uint32_t _timeout = 100000UL; // Finish off request block by waiting for completion and posting status. uint8_t finishRB(I2CRB *rb, uint8_t status); @@ -532,7 +532,7 @@ private: uint8_t bytesToSend = 0; uint8_t bytesToReceive = 0; uint8_t operation = 0; - unsigned long startTime = 0; + uint32_t startTime = 0; uint8_t muxPhase = 0; uint8_t muxAddress = 0; uint8_t muxData[1]; diff --git a/I2CManager_NonBlocking.h b/I2CManager_NonBlocking.h index fb5bae5..59bbcaf 100644 --- a/I2CManager_NonBlocking.h +++ b/I2CManager_NonBlocking.h @@ -172,6 +172,10 @@ void I2CManagerClass::startTransaction() { * Function to queue a request block and initiate operations. ***************************************************************************/ void I2CManagerClass::queueRequest(I2CRB *req) { + + if (((req->operation & OPERATION_MASK) == OPERATION_READ) && req->readLen == 0) + return; // Ignore null read + req->status = I2C_STATUS_PENDING; req->nextRequest = NULL; ATOMIC_BLOCK() { @@ -184,6 +188,7 @@ void I2CManagerClass::queueRequest(I2CRB *req) { } + /*************************************************************************** * Initiate a write to an I2C device (non-blocking operation) ***************************************************************************/ @@ -240,8 +245,8 @@ void I2CManagerClass::checkForTimeout() { I2CRB *t = queueHead; if (state==I2C_STATE_ACTIVE && t!=0 && t==currentRequest && _timeout > 0) { // Check for timeout - unsigned long elapsed = micros() - startTime; - if (elapsed > _timeout) { + int32_t elapsed = micros() - startTime; + if (elapsed > (int32_t)_timeout) { #ifdef DIAG_IO //DIAG(F("I2CManager Timeout on %s"), t->i2cAddress.toString()); #endif @@ -300,12 +305,12 @@ void I2CManagerClass::handleInterrupt() { // Check if current request has completed. If there's a current request // and state isn't active then state contains the completion status of the request. - if (state == I2C_STATE_COMPLETED && currentRequest != NULL) { + if (state == I2C_STATE_COMPLETED && currentRequest != NULL && currentRequest == queueHead) { // Operation has completed. if (completionStatus == I2C_STATUS_OK || ++retryCounter > MAX_I2C_RETRIES || currentRequest->operation & OPERATION_NORETRY) { - // Status is OK, or has failed and retry count exceeded, or retries disabled. + // Status is OK, or has failed and retry count exceeded, or failed and retries disabled. #if defined(I2C_EXTENDED_ADDRESS) if (muxPhase == MuxPhase_PROLOG ) { overallStatus = completionStatus; diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 5132640..eac331a 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -232,6 +232,7 @@ void I2CManagerClass::I2C_sendStart() { // multi-master bus, the bus may be BUSY under control of another master, // in which case we can avoid some arbitration failures by waiting until // the bus state is IDLE. We don't do that here. + //while (s->SR2 & I2C_SR2_BUSY) {} // Check there's no STOP still in progress. If we OR the START bit into CR1 // and the STOP bit is already set, we could output multiple STOP conditions. @@ -247,6 +248,7 @@ void I2CManagerClass::I2C_sendStart() { ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { s->CR1 |= I2C_CR1_STOP; // Stop I2C + //while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset } /*************************************************************************** @@ -273,6 +275,9 @@ void I2CManagerClass::I2C_close() { void I2CManagerClass::I2C_handleInterrupt() { volatile uint16_t temp_sr1, temp_sr2; + pinMode(D2, OUTPUT); + digitalWrite(D2, 1); + temp_sr1 = s->SR1; // Check for errors first @@ -302,7 +307,8 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_BUS_ERROR; state = I2C_STATE_COMPLETED; } - } else { + } + else { // No error flags, so process event according to current state. switch (transactionState) { case TS_START: @@ -324,6 +330,7 @@ void I2CManagerClass::I2C_handleInterrupt() { break; case TS_W_ADDR: + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit if (temp_sr1 & I2C_SR1_ADDR) { // Event EV6 // Address sent successfully, device has ack'd in response. @@ -333,10 +340,25 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } else { - transactionState = TS_W_DATA; + if (bytesToSend <= 2) { + // After this interrupt, we will have no more data to send. + // Next event of interest will be the BTF interrupt, so disable TXE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; + transactionState = TS_W_STOP; + } else { + // More data to send, enable TXE interrupt. + s->CR2 |= I2C_CR2_ITBUFEN; + transactionState = TS_W_DATA; + } + // Put one or two bytes into DR to avoid interrupts + s->DR = sendBuffer[txCount++]; + bytesToSend--; + if (bytesToSend) { + s->DR = sendBuffer[txCount++]; + bytesToSend--; + } } } - temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit break; case TS_W_DATA: @@ -344,21 +366,24 @@ void I2CManagerClass::I2C_handleInterrupt() { // Event EV8_1/EV8/EV8_2 // Transmitter empty, write a byte to it. if (bytesToSend) { + if (bytesToSend == 1) { + // We will next need to wait for BTF. + // TXE becomes set one byte before BTF is set, so disable + // TXE interrupt while we're waiting for BTF, to suppress + // repeated interrupts during that period. + s->CR2 &= ~I2C_CR2_ITBUFEN; + transactionState = TS_W_STOP; + } s->DR = sendBuffer[txCount++]; bytesToSend--; } - // See if we're finished sending - if (!bytesToSend) { - // Wait for last byte to be sent. - transactionState = TS_W_STOP; - } } break; case TS_W_STOP: if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { // Event EV8_2 - // Write finished. + // All writes finished. if (bytesToReceive) { // Start a read operation by sending (re)start I2C_sendStart(); @@ -383,17 +408,22 @@ void I2CManagerClass::I2C_handleInterrupt() { // Receive 1 byte s->CR1 &= ~I2C_CR1_ACK; // Disable ack temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit + // Next step will occur after a RXNE interrupt, so enable it + s->CR2 |= I2C_CR2_ITBUFEN; transactionState = TS_R_STOP; - // Next step will occur after a BTF interrupt } else if (bytesToReceive == 2) { // Receive 2 bytes s->CR1 &= ~I2C_CR1_ACK; // Disable ACK for final byte s->CR1 |= I2C_CR1_POS; // set POS flag to delay effect of ACK flag + // Next step will occur after a BTF interrupt, so disable RXNE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit transactionState = TS_R_STOP; } else { // >2 bytes, just wait for bytes to come in and ack them for the time being // (ack flag has already been set). + // Next step will occur after a BTF interrupt, so disable RXNE interrupt + s->CR2 &= ~I2C_CR2_ITBUFEN; temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit transactionState = TS_R_DATA; } @@ -448,6 +478,8 @@ void I2CManagerClass::I2C_handleInterrupt() { break; } } + delayMicroseconds(1); + digitalWrite(D2, 0); } #endif /* I2CMANAGER_STM32_H */ From 4f43a413b5aeeb709fe14e2cb298077ebbe38081 Mon Sep 17 00:00:00 2001 From: Neil McKechnie Date: Thu, 30 Mar 2023 18:30:38 +0100 Subject: [PATCH 004/310] Update I2CManager_STM32.h Remove debug code (writing to pin D2). Update comments. Restructure. --- I2CManager_STM32.h | 73 +++++++++++++++++++++++++--------------------- 1 file changed, 39 insertions(+), 34 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index eac331a..f1d7e08 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -238,6 +238,8 @@ void I2CManagerClass::I2C_sendStart() { // and the STOP bit is already set, we could output multiple STOP conditions. while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset + s->CR2 |= (I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable interrupts + s->CR2 &= ~I2C_CR2_ITBUFEN; // Don't enable buffer interupts yet. s->CR1 &= ~I2C_CR1_POS; // Clear the POS bit s->CR1 |= (I2C_CR1_ACK | I2C_CR1_START); // Enable the ACK and generate START transactionState = TS_START; @@ -248,7 +250,6 @@ void I2CManagerClass::I2C_sendStart() { ***************************************************************************/ void I2CManagerClass::I2C_sendStop() { s->CR1 |= I2C_CR1_STOP; // Stop I2C - //while (s->CR1 & I2C_CR1_STOP) {} // Wait for STOP bit to reset } /*************************************************************************** @@ -261,7 +262,7 @@ void I2CManagerClass::I2C_close() { // Should never happen, but wait for up to 500us only. unsigned long startTime = micros(); while ((s->CR1 & I2C_CR1_PE) != 0) { - if (micros() - startTime >= 500UL) break; + if ((int32_t)(micros() - startTime) >= 500) break; } NVIC_DisableIRQ(I2C1_EV_IRQn); NVIC_DisableIRQ(I2C1_ER_IRQn); @@ -275,9 +276,6 @@ void I2CManagerClass::I2C_close() { void I2CManagerClass::I2C_handleInterrupt() { volatile uint16_t temp_sr1, temp_sr2; - pinMode(D2, OUTPUT); - digitalWrite(D2, 1); - temp_sr1 = s->SR1; // Check for errors first @@ -330,8 +328,8 @@ void I2CManagerClass::I2C_handleInterrupt() { break; case TS_W_ADDR: - temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit if (temp_sr1 & I2C_SR1_ADDR) { + temp_sr2 = s->SR2; // read SR2 to complete clearing the ADDR bit // Event EV6 // Address sent successfully, device has ack'd in response. if (!bytesToSend) { @@ -340,60 +338,65 @@ void I2CManagerClass::I2C_handleInterrupt() { completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } else { - if (bytesToSend <= 2) { - // After this interrupt, we will have no more data to send. - // Next event of interest will be the BTF interrupt, so disable TXE interrupt - s->CR2 &= ~I2C_CR2_ITBUFEN; - transactionState = TS_W_STOP; - } else { - // More data to send, enable TXE interrupt. - s->CR2 |= I2C_CR2_ITBUFEN; - transactionState = TS_W_DATA; - } - // Put one or two bytes into DR to avoid interrupts + // Put one byte into DR to load shift register. s->DR = sendBuffer[txCount++]; bytesToSend--; if (bytesToSend) { + // Put another byte to load DR s->DR = sendBuffer[txCount++]; bytesToSend--; } + if (!bytesToSend) { + // No more bytes to send. + // The TXE interrupt occurs when the DR is empty, and the BTF interrupt + // occurs when the shift register is also empty (one character later). + // To avoid repeated TXE interrupts during this time, we disable TXE interrupt. + s->CR2 &= ~I2C_CR2_ITBUFEN; // Wait for BTF interrupt, disable TXE interrupt + transactionState = TS_W_STOP; + } else { + // More data remaining to send after this interrupt, enable TXE interrupt. + s->CR2 |= I2C_CR2_ITBUFEN; + transactionState = TS_W_DATA; + } } } break; case TS_W_DATA: if (temp_sr1 & I2C_SR1_TXE) { - // Event EV8_1/EV8/EV8_2 + // Event EV8_1/EV8 // Transmitter empty, write a byte to it. if (bytesToSend) { - if (bytesToSend == 1) { - // We will next need to wait for BTF. - // TXE becomes set one byte before BTF is set, so disable - // TXE interrupt while we're waiting for BTF, to suppress - // repeated interrupts during that period. - s->CR2 &= ~I2C_CR2_ITBUFEN; - transactionState = TS_W_STOP; - } s->DR = sendBuffer[txCount++]; bytesToSend--; + if (!bytesToSend) { + s->CR2 &= ~I2C_CR2_ITBUFEN; // Disable TXE interrupt + transactionState = TS_W_STOP; + } } - } + } break; case TS_W_STOP: - if ((temp_sr1 & I2C_SR1_BTF) && (temp_sr1 & I2C_SR1_TXE)) { + if (temp_sr1 & I2C_SR1_BTF) { // Event EV8_2 - // All writes finished. + // Done, last character sent. Anything to receive? if (bytesToReceive) { - // Start a read operation by sending (re)start - I2C_sendStart(); + I2C_sendStart(); + // NOTE: Three redundant BTF interrupts take place between the + // first BTF interrupt and the START interrupt. I've tried all sorts + // of ways to eliminate them, and the only thing that worked for + // me was to loop until the BTF bit becomes reset. Either way, + // it's a waste of processor time. Anyone got a solution? + //while (s->SR1 && I2C_SR1_BTF) {} + transactionState = TS_START; } else { - // Done. I2C_sendStop(); transactionState = TS_IDLE; completionStatus = I2C_STATUS_OK; state = I2C_STATE_COMPLETED; } + s->SR1 &= I2C_SR1_BTF; // Clear BTF interrupt } break; @@ -477,9 +480,11 @@ void I2CManagerClass::I2C_handleInterrupt() { } break; } + // If we've received an interrupt at any other time, we're not interested so clear it + // to prevent it recurring ad infinitum. + s->SR1 = 0; } - delayMicroseconds(1); - digitalWrite(D2, 0); + } #endif /* I2CMANAGER_STM32_H */ From e51f8e9c0a53e4de08699ac255b6f17cb42f18bd Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 11 Apr 2023 15:48:35 +0800 Subject: [PATCH 005/310] STM32 I2C Clock selection for 100/400KHz --- I2CManager_STM32.h | 75 ++++++++++++++++++++++++++-------------------- 1 file changed, 43 insertions(+), 32 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index f1d7e08..cde4f20 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -26,34 +26,42 @@ #include "I2CManager.h" #include "I2CManager_NonBlocking.h" // to satisfy intellisense -//#include -//#include #include +#include "stm32f4xx_hal_rcc.h" -/*************************************************************************** - * Interrupt handler. - * IRQ handler for SERCOM3 which is the default I2C definition for Arduino Zero - * compatible variants such as the Sparkfun SAMD21 Dev Breakout etc. - * Later we may wish to allow use of an alternate I2C bus, or more than one I2C - * bus on the SAMD architecture - ***************************************************************************/ +/***************************************************************************** + * STM32F4xx I2C native driver support + * + * Nucleo-64 and Nucleo-144 boards all use I2C1 as the default I2C peripheral + * Later we may wish to support other STM32 boards, allow use of an alternate + * I2C bus, or more than one I2C bus on the STM32 architecture + *****************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) +#if defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) +// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64 +// and Nucleo-144variants +I2C_TypeDef *s = I2C1; + +// In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz +uint32_t APB1clk1; // Peripheral Input Clock speed in Hz. +uint32_t i2c_MHz; // Peripheral Input Clock speed in MHz. + +// IRQ handler for I2C1, replacing the weak definition in the STM32 HAL extern "C" void I2C1_EV_IRQHandler(void) { I2CManager.handleInterrupt(); } extern "C" void I2C1_ER_IRQHandler(void) { I2CManager.handleInterrupt(); } +#else +#warning STM32 board selected is not yet supported - so I2C1 peripheral is not defined +#endif #endif - -// Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely Nucleo-64 variants -I2C_TypeDef *s = I2C1; -#define I2C_IRQn I2C1_EV_IRQn // Peripheral Input Clock speed in MHz. // For STM32F446RE, the speed is 45MHz. Ideally, this should be determined // at run-time from the APB1 clock, as it can vary from STM32 family to family. -#define I2C_PERIPH_CLK 45 +// #define I2C_PERIPH_CLK 45 // I2C SR1 Status Register #1 bit definitions for convenience // #define I2C_SR1_SMBALERT (1<<15) // SMBus alert @@ -97,8 +105,6 @@ enum {TS_IDLE,TS_START,TS_W_ADDR,TS_W_DATA,TS_W_STOP,TS_R_ADDR,TS_R_DATA,TS_R_ST * that it is only called at the beginning of an I2C transaction. ***************************************************************************/ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { - return; - // Calculate a rise time appropriate to the requested bus speed // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; @@ -106,13 +112,9 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // writes to CR1 while STOP is being executed! + // Disable the I2C device, as TRISE can only be programmed whilst disabled s->CR1 &= ~(I2C_CR1_PE); // Disable I2C - // Software reset the I2C peripheral - // s->CR1 |= I2C_CR1_SWRST; // reset the I2C - // delay(1); - // Release reset - // s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation if (i2cClockSpeed > 100000L) { @@ -127,19 +129,20 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { t_rise = 1000; // nanoseconds } // Configure the rise time register - s->TRISE = t_rise * I2C_PERIPH_CLK / 1000UL + 1; + s->TRISE = (t_rise / (1000 / i2c_MHz)) + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle (use 2:1) - // Bit 11-0: FREQR = 16MHz => TPCLK1 = 62.5ns + // Bit 11-0: FREQR if (i2cClockSpeed > 100000L) { // In fast mode, I2C period is 3 * CCR * TPCLK1. - ccr_freq = I2C_PERIPH_CLK * 1000000 / 3 / i2cClockSpeed; - s->CCR = (uint16_t)ccr_freq | 0x8000; // We need Fast Mode set + //APB1clk1 / 3 / i2cClockSpeed = 38, but that results in 306KHz not 400! + ccr_freq = 30; // So 30 gives 396KHz or so! + s->CCR = (uint16_t)(ccr_freq | 0x8000); // We need Fast Mode set } else { - // In standard mode, I2C period is 2 * CCR * TPCLK1. - ccr_freq = I2C_PERIPH_CLK * 1000000 / 2 / i2cClockSpeed; - s->CCR = (uint16_t)ccr_freq; + // In standard mode, I2C period is 2 * CCR * TPCLK1 + ccr_freq = (APB1clk1 / 2 / i2cClockSpeed); // Should be 225 for 45Mhz APB1 clock + s->CCR |= (uint16_t)ccr_freq; } // Enable the I2C master mode @@ -151,7 +154,10 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { ***************************************************************************/ void I2CManagerClass::I2C_init() { - // Setting up the clocks + // Query the clockspeed from the STM32 HAL layer + APB1clk1 = HAL_RCC_GetPCLK1Freq(); + i2c_MHz = APB1clk1 / 1000000UL; + // Enable clocks RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK // Reset the I2C1 peripheral to initial state RCC->APB1RSTR |= RCC_APB1RSTR_I2C1RST; @@ -181,7 +187,8 @@ void I2CManagerClass::I2C_init() s->CR2 &= 0xE000; // Set I2C peripheral clock frequency - s->CR2 |= I2C_PERIPH_CLK; + // s->CR2 |= I2C_PERIPH_CLK; + s->CR2 |= i2c_MHz; // set own address to 00 - not used in master mode I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet @@ -210,10 +217,14 @@ void I2CManagerClass::I2C_init() // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) - s->CCR = I2C_PERIPH_CLK * 5; + // s->CCR = I2C_PERIPH_CLK * 5; + s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + s->CCR |= (APB1clk1 / 2 / 100000UL); // i2c_MHz * 5; + // s->CCR = i2c_MHz * 5; // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. - s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 + // s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 + s->TRISE = i2c_MHz + 1; // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C From 9f38dae8ba99aea18bb82ecade79dad5c2ffec01 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 11 Aug 2023 00:07:02 +0200 Subject: [PATCH 006/310] Check bad AT firmware version --- GITHUB_SHA.h | 2 +- WifiInterface.cpp | 16 +++++++++++++++- version.h | 4 +++- 3 files changed, 19 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index a889ba7..de4f953 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308041244Z" +#define GITHUB_SHA "devel-202308102205Z" diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 7511af6..ab36957 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -200,7 +200,21 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, // Display the AT version information StringFormatter::send(wifiStream, F("AT+GMR\r\n")); - checkForOK(2000, true, false); // Makes this visible on the console + if (checkForOK(2000, F("AT version:"), true, false)) { + char version[] = "0.0.0.0"; + for (int i=0; i<8;i++) { + while(!wifiStream->available()); + version[i]=wifiStream->read(); + StringFormatter::printEscape(version[i]); + if ((version[0] == '0') || + (version[0] == '2' && version[2] == '0') || + (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) { + SSid = F("DCCEX_SAYS_BROKEN_FIRMWARE"); + forceAP = true; + } + } + } + checkForOK(2000, true, false); #ifdef DONT_TOUCH_WIFI_CONF DIAG(F("DONT_TOUCH_WIFI_CONF was set: Using existing config")); diff --git a/version.h b/version.h index eb2d068..076daef 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "4.2.69" +#define VERSION "5.0.1" +// 5.0.1 - Check bad AT firmware version +// 5.0.0 - Make 4.2.69 the 5.0.0 release // 4.2.69 - Bugfix: Make work in DC mode // 4.2.68 - Rename track mode OFF to NONE // 4.2.67 - AVR: Pin specific timer register seting From e327e0ae8d93248fd933b5affcc67f112c2a6fb8 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Sat, 12 Aug 2023 18:40:48 +0100 Subject: [PATCH 007/310] Added ONOVERLOAD Added code changes to create ONOVERLOAD command in EXRAIL --- EXRAIL2.cpp | 15 ++++++++++++++- EXRAIL2.h | 3 ++- EXRAIL2MacroReset.h | 4 +++- EXRAILMacros.h | 3 ++- MotorDriver.cpp | 5 +++++ 5 files changed, 26 insertions(+), 4 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 0e17ea9..0c60c68 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -2,7 +2,7 @@ * © 2021 Neil McKechnie * © 2021-2023 Harald Barth * © 2020-2023 Chris Harlow - * © 2022 Colin Murdoch + * © 2022-2023 Colin Murdoch * All rights reserved. * * This file is part of CommandStation-EX @@ -94,6 +94,7 @@ LookList * RMFT2::onAmberLookup=NULL; LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onClockLookup=NULL; +LookList * RMFT2::onOverloadLookup=NULL; #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -175,6 +176,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); + onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD); // Second pass startup, define any turnouts or servos, set signals red @@ -986,6 +988,7 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: + case OPCODE_ONOVERLOAD: break; @@ -1140,6 +1143,16 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) { } } +void RMFT2::powerEvent(char track, bool overload) { + // Hunt for an ONOVERLOAD for this item + if (Diag::CMD) + DIAG(F("Looking for Power event on track : %c"), track); + if (overload) { + handleEvent(F("POWER"),onOverloadLookup,track); + } +} + + void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) { int pc= handlers->find(id); if (pc<0) return; diff --git a/EXRAIL2.h b/EXRAIL2.h index 4d106e6..6b3a9dd 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -1,7 +1,7 @@ /* * © 2021 Neil McKechnie * © 2020-2022 Chris Harlow - * © 2022 Colin Murdoch + * © 2022-2023 Colin Murdoch * © 2023 Harald Barth * All rights reserved. * @@ -188,6 +188,7 @@ private: static LookList * onGreenLookup; static LookList * onChangeLookup; static LookList * onClockLookup; + static LookList * onOverloadLookup; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 588a417..5ac3ab7 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -1,6 +1,6 @@ /* * © 2020-2022 Chris Harlow. All rights reserved. - * © 2022 Colin Murdoch + * © 2022-2023 Colin Murdoch * © 2023 Harald Barth * * This file is part of CommandStation-EX @@ -93,6 +93,7 @@ #undef ONTIME #undef ONCLOCKTIME #undef ONCLOCKMINS +#undef ONOVERLOAD #undef ONGREEN #undef ONRED #undef ONTHROW @@ -215,6 +216,7 @@ #define ONTIME(value) #define ONCLOCKTIME(hours,mins) #define ONCLOCKMINS(mins) +#define ONOVERLOAD(track_id) #define ONDEACTIVATE(addr,subaddr) #define ONDEACTIVATEL(linear) #define ONCLOSE(turnout_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 66b0111..69b5995 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -1,7 +1,7 @@ /* * © 2021 Neil McKechnie * © 2020-2022 Chris Harlow - * © 2022 Colin Murdoch + * © 2022-2023 Colin Murdoch * © 2023 Harald Barth * All rights reserved. * @@ -320,6 +320,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONTIME(value) OPCODE_ONTIME,V(value), #define ONCLOCKTIME(hours,mins) OPCODE_ONTIME,V((STRIP_ZERO(hours)*60)+STRIP_ZERO(mins)), #define ONCLOCKMINS(mins) ONCLOCKTIME(25,mins) +#define ONOVERLOAD(track_id) OPCODE_ONOVERLOAD,V(TRACK_NUMBER_##track_id), #define ONDEACTIVATE(addr,subaddr) OPCODE_ONDEACTIVATE,V(addr<<2|subaddr), #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), diff --git a/MotorDriver.cpp b/MotorDriver.cpp index d5dca13..d2b4495 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -4,6 +4,7 @@ * © 2021 Fred Decker * © 2020-2023 Harald Barth * © 2020-2021 Chris Harlow + * © 2023 Colin Murdoch * All rights reserved. * * This file is part of CommandStation-EX @@ -574,6 +575,8 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { DIAG(F("TRACK %c FAULT PIN detected after %4M. Pause %4M)"), trackno + 'A', mslpc, power_sample_overload_wait); throttleInrush(false); setPower(POWERMODE::OVERLOAD); + DIAG(F("Calling EXRAIL")); + RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload break; } if (checkCurrent(useProgLimit)) { @@ -591,6 +594,8 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { trackno + 'A', mA, maxmA, mslpc, power_sample_overload_wait); throttleInrush(false); setPower(POWERMODE::OVERLOAD); + DIAG(F("Calling EXRAIL")); + RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload break; } // all well From 247763ac0005aca3551194587b7e418bd928d8e3 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Sat, 12 Aug 2023 19:10:35 +0100 Subject: [PATCH 008/310] Code Corrections Code corrections --- EXRAIL2.cpp | 2 +- EXRAIL2.h | 2 ++ MotorDriver.cpp | 1 + 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 0c60c68..ac277a5 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1143,7 +1143,7 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) { } } -void RMFT2::powerEvent(char track, bool overload) { +void RMFT2::powerEvent(int16_t track, bool overload) { // Hunt for an ONOVERLOAD for this item if (Diag::CMD) DIAG(F("Looking for Power event on track : %c"), track); diff --git a/EXRAIL2.h b/EXRAIL2.h index 6b3a9dd..700cd6b 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -62,6 +62,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, + OPCODE_ONOVERLOAD, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -130,6 +131,7 @@ class LookList { static void activateEvent(int16_t addr, bool active); static void changeEvent(int16_t id, bool change); static void clockEvent(int16_t clocktime, bool change); + static void powerEvent(int16_t track, bool overload); static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index d2b4495..e3ecd64 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -27,6 +27,7 @@ #include "DCCWaveform.h" #include "DCCTimer.h" #include "DIAG.h" +#include "EXRAIL2.h" unsigned long MotorDriver::globalOverloadStart = 0; From e27cceeb74ad293d36b302d5044793cf43ac7c5b Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Fri, 18 Aug 2023 11:30:37 +0100 Subject: [PATCH 009/310] Update PCA9555.h inconsistencies to IO_MCP23017.h causing IO_PCA9555.h compile error when configure for Mux Updated Class PCA9555 definition reflecting changes in IO_MCP23017.h to support PCA9548 mux. Checked with PCA9555 base board, compiles and run EXRAIL script with output driver --- IO_PCA9555.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index 137e287..e493165 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -30,8 +30,8 @@ class PCA9555 : public GPIOBase { public: - static void create(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1) { - new PCA9555(vpin, min(nPins,16), I2CAddress, interruptPin); + static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) { + if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } // Constructor From 4b2c0702a49f3b11ab0f8af5e9d6eac5e745db6b Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Fri, 18 Aug 2023 11:40:34 +0100 Subject: [PATCH 010/310] Update version.h Update version.h for IO_PCA9555 changes --- version.h | 1 + 1 file changed, 1 insertion(+) diff --git a/version.h b/version.h index 076daef..cf1fd26 100644 --- a/version.h +++ b/version.h @@ -5,6 +5,7 @@ #define VERSION "5.0.1" // 5.0.1 - Check bad AT firmware version +// - Update IO_PCA9555.h reflecting IO_MCP23017.h changes to support PCA9548 mux // 5.0.0 - Make 4.2.69 the 5.0.0 release // 4.2.69 - Bugfix: Make work in DC mode // 4.2.68 - Rename track mode OFF to NONE From 1491da48134852b0f8623b8455eb8c356e566e53 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 20 Aug 2023 19:26:04 +1000 Subject: [PATCH 011/310] Starting, very broken --- CommandDistributor.cpp | 4 + CommandDistributor.h | 1 + DCCEXParser.cpp | 29 +++++++ DCCEXParser.h | 13 +-- IODevice.h | 1 + Turntables.cpp | 176 +++++++++++++++++++++++++++++++++++++++++ Turntables.h | 164 ++++++++++++++++++++++++++++++++++++++ 7 files changed, 382 insertions(+), 6 deletions(-) create mode 100644 Turntables.cpp create mode 100644 Turntables.h diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index ab6b52f..eef84a9 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -161,6 +161,10 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { #endif } +void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position) { + broadcastReply(COMMAND_TYPE, F("\n"), id, position); +} + void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { // The JMRI clock command is of the form : PFT65871<;>4 // The CS broadcast is of the form " + if (parseI(stream, params, p)) + return; + break; + default: //anything else will diagnose and drop out to DIAG(F("Opcode=%c params=%d"), opcode, params); for (int i = 0; i < params; i++) @@ -1013,6 +1019,29 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) return false; } +// ========================== +// Turntable +bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) +{ + switch (params) + { + case 0: // list turntable objects + return Turntable::printAll(stream); + + case 1: // delete turntable + if (!Turntable::remove(p[0])) + return false; + StringFormatter::send(stream, F("\n")); + return true; + + case 2: // - rotate to position for DCC turntables + case 3: // rotate to position for EX-Turntable + { + + } + } +} + // CALLBACKS must be static bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream) { diff --git a/DCCEXParser.h b/DCCEXParser.h index bb05ebf..bf067a7 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -45,13 +45,14 @@ struct DCCEXParser static int16_t splitValues( int16_t result[MAX_COMMAND_PARAMS], const byte * command, bool usehex); static bool parseT(Print * stream, int16_t params, int16_t p[]); - static bool parseZ(Print * stream, int16_t params, int16_t p[]); - static bool parseS(Print * stream, int16_t params, int16_t p[]); - static bool parsef(Print * stream, int16_t params, int16_t p[]); - static bool parseD(Print * stream, int16_t params, int16_t p[]); + static bool parseZ(Print * stream, int16_t params, int16_t p[]); + static bool parseS(Print * stream, int16_t params, int16_t p[]); + static bool parsef(Print * stream, int16_t params, int16_t p[]); + static bool parseD(Print * stream, int16_t params, int16_t p[]); + static bool parseI(Print * stream, int16_t params, int16_t p[]); - static Print * getAsyncReplyStream(); - static void commitAsyncReplyStream(); + static Print * getAsyncReplyStream(); + static void commitAsyncReplyStream(); static bool stashBusy; static byte stashTarget; diff --git a/IODevice.h b/IODevice.h index 769e111..8b8f3fe 100644 --- a/IODevice.h +++ b/IODevice.h @@ -542,6 +542,7 @@ protected: #include "IO_PCF8575.h" #include "IO_duinoNodes.h" #include "IO_EXIOExpander.h" +#include "IO_EXTurntable.h" #endif // iodevice_h diff --git a/Turntables.cpp b/Turntables.cpp new file mode 100644 index 0000000..45a1d05 --- /dev/null +++ b/Turntables.cpp @@ -0,0 +1,176 @@ +/* + * © 2023 Peter Cole + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +#include "defines.h" +#include +#include "Turntables.h" +#include "StringFormatter.h" +#include "CommandDistributor.h" +#include "EXRAIL2.h" +#include "DCC.h" + + +/* + * Protected static data + */ +Turntable *Turntable::_firstTurntable = 0; + + +/* + * Public static data + */ +int Turntable::_turntablelistHash = 0; + + +/* + * Protected static functions + */ +// Add new turntable to end of list +void Turntable::add(Turntable *tto) { + if (!_firstTurntable) { + _firstTurntable = tto; + } else { + Turntable *ptr = _firstTurntable; + for ( ; ptr->_nextTurntable!=0; ptr=ptr->_nextTurntable) {} + ptr->_nextTurntable = tto; + } + turntablelistHash++; +} + +// Find turntable from list +Turntable *Turntable::get(uint16_t id) { + for (Turntable *tto = _firstTurntable; tto != NULL; tto = tto->_nextTurntable) + if (tto->_turntableData.id == id) return tto; + return NULL; +} + +// Remove specified turntable from list and delete it +bool Turntable::remove(uint16_t id) { + Turntable *tto, *pp=NULL; + + for (tto=_firstTurntable; tto!=NULL && tto->_turntableData.id!=id; pp=tto, tto=tto->_nextTurntable) {} + if (tto == NULL) return false; + if (tto == _firstTurntable) { + _firstTurntable = tto->_nextTurntable; + } else { + pp->_nextTurntable = tto->_nextTurntable; + } + + delete (EXTTTurntable *)tto; + + turntablelistHash++; + return true; +} + + +/* + * Public static functions + */ +bool Turntable::isPosition(uint16_t id, uint8_t position) { + Turntable *tto = get(id); + if (!tto) return false; + if (tto) { + if (tto->getPosition() == position) { + return true; + } else { + return false; + } + } +} + +bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { + Turntable *tto = get(id); + if (!tto) return false; + CommandDistributor::broadcastTurntable(id, position); +#if defined(EXRAIL_ACTIVE) + // RMFT2::turntableEvent(id, position); +#endif +} + +bool Turntable::setPosition(uint16_t id, uint8_t position) { +#if defined(DIAG_IO) + DIAG(F("Turntable(%d, %d)"), id, position); +#endif + Turntable *tto = Turntable::get(id); + if (!tto) return false; + bool ok = tto->setPositionInternal(position); + + if (ok) { + tto->setPositionStateOnly(id, position); + } + return ok; +} + +/************************************************************************************* + * EXTTTurntable - EX-Turntable device. + * + *************************************************************************************/ +// Private constructor +EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) : + Turntable(id, TURNTABLE_EXTT) +{ + _exttTurntableData.i2caddress = i2caddress; + _exttTurntableData.vpin = vpin; + _exttTurntableData.positions = **positions; +} + +// Create function +#ifndef IO_NO_HAL + Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) { + Turntable *tto = get(id); + if (tto) { + if (tto->isType(TURNTABLE_EXTT)) { + EXTTTurntable *extt = (EXTTTurntable *)tto; + extt->_exttTurntableData.i2caddress = i2caddress; + extt->_exttTurntableData.vpin = vpin; + extt->_exttTurntableData.positions = positions; + return tto; + } else { + remove(id); + } + } + tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin, **positions); + DIAG(F("Turntable 0x%x"), tto); + return tto; +#else + (void)id; + (void)i2caddress; + (void)vpin; + (void)positions; + return NULL; +#endif + } + + void EXTTTurntable::print(Print *stream) { + StringFormatter::send(stream, F("\n"), _turntableData.id, _exttTurntableData.i2caddress, _exttTurntableData.vpin); + } + + // EX-Turntable specific code for moving to the specified position + bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { +#ifndef IO_NO_HAL + // Get step value from positions + int value = _exttTurntableData.positions[position]; + // Set position via device driver + EXTurntable::_writeAnalogue(vpin, value, activity, 0); +#else + (void)position; +#endif + return true; + } diff --git a/Turntables.h b/Turntables.h new file mode 100644 index 0000000..5a6f346 --- /dev/null +++ b/Turntables.h @@ -0,0 +1,164 @@ +/* + * © 2023 Peter Cole + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +#ifndef TURNTABLES_H +#define TURNTABLES_H + +#include +#include "IODevice.h" +#include "StringFormatter.h" + +// Turntable type definitions +// EXTT = EX-Turntable +// DCC = DCC accessory turntables - to be added later +enum { + TURNTABLE_EXTT = 1, + // TURNTABLE_DCC = 2, +}; + +/************************************************************************************* + * Turntable - Base class for turntables. + * + *************************************************************************************/ + +class Turntable { +protected: + /* + * Object data + */ + + // Data common to all turntable types + struct TurntableData { + union { + struct { + bool hidden : 1; + uint8_t turntableType : 2; + uint8_t position : 5; // Allows up to 38 positions including 0/home + }; + uint8_t flags; + }; + uint16_t id; + } _turntableData; + + // Pointer to next turntable object + Turntable *_nextTurntable = 0; + + /* + * Constructor + */ + Turntable(uint16_t id, uint8_t turntableType) { + _turntableData.id = id; + _turntableData.turntableType = turntableType; + _turntableData.hidden = false; + add(this); + } + + /* + * Static data + */ + static Turntable *_firstTurntable; + static int _turntablelistHash; + + /* + * Virtual functions + */ + virtual bool setPositionInternal(uint8_t position, uint8_t activity) = 0; + + /* + * Static functions + */ + static void add(Turntable *tto); + +public: + static Turntable *get(uint16_t id); + + /* + * Static data + */ + static int turntablelistHash; + + /* + * Public base class functions + */ + inline uint8_t getPosition() { return _turntableData.position; } + inline bool isHidden() { return _turntableData.hidden; } + inline void setHidden(bool h) {_turntableData.hidden=h; } + inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } + inline uint16_t getId() { return _turntableData.id; } + inline Turntable *next() { return _nextTurntable; } + void printState(Print *stream); + + /* + * Virtual functions + */ + virtual void print(Print *stream) { + (void)stream; // suppress compiler warnings + } + virtual ~Turntable() {} // Destructor + + /* + * Public static functions + */ + inline static bool exists(uint16_t id) { return get(id) != 0; } + static bool remove(uint16_t id); + static bool isPosition(uint16_t id, uint8_t position); + static bool setPosition(uint16_t id, uint8_t position); + static bool setPositionStateOnly(uint16_t id, uint8_t position); + inline static Turntable *first() { return _firstTurntable; } + static bool printAll(Print *stream) { + bool gotOne = false; + for (Turntable *tto = _firstTurntable; tto != 0; tto = tto->_nextTurntable) + if (!tto->isHidden()) { + gotOne = true; + StringFormatter::send(stream, F("\n"), tto->getId(), tto->getPosition()); + } + return gotOne; + } + +}; + +/************************************************************************************* + * EXTTTurntable - EX-Turntable device. + * + *************************************************************************************/ +class EXTTTurntable : public Turntable { +private: + // EXTTTurntableData contains device specific data + struct EXTTTurntableData { + uint8_t i2caddress; + VPIN vpin; + long **positions; // Array of longs to store step positions + } _exttTurntableData; + + // Constructor + EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + +public: + // Create function + static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + void print(Print *stream) override; + +protected: + // EX-Turntable specific code for setting position + bool setPositionInternal(uint8_t position, uint8_t activity) override; + +}; + +#endif From 98f8022268ad536cf6e2183e472a56ba7a6bcf04 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Mon, 21 Aug 2023 06:43:06 +1000 Subject: [PATCH 012/310] Fix device driver, disable objects, start parser --- DCCEXParser.cpp | 33 +++++++++++++++++++++----- IODevice.h | 1 - IO_EXTurntable.h => IO_EXTurntable.cpp | 4 ++-- Turntables.cpp => Turntables.cpp.txt | 0 Turntables.h => Turntables.h.txt | 0 5 files changed, 29 insertions(+), 9 deletions(-) rename IO_EXTurntable.h => IO_EXTurntable.cpp (97%) rename Turntables.cpp => Turntables.cpp.txt (100%) rename Turntables.h => Turntables.h.txt (100%) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 4a32902..cfe2563 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -41,7 +41,7 @@ #include "TrackManager.h" #include "DCCTimer.h" #include "EXRAIL2.h" -#include "Turntables.h" +// #include "Turntables.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -96,6 +96,7 @@ const int16_t HASH_KEYWORD_ANOUT = -26399; const int16_t HASH_KEYWORD_WIFI = -5583; const int16_t HASH_KEYWORD_ETHERNET = -30767; const int16_t HASH_KEYWORD_WIT = 31594; +const int16_t HASH_KEYWORD_EXTT = 8573; int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; @@ -1021,25 +1022,45 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable +// - list all +// - delete +// - operate (DCC) +// - operate (EXTT) +// - create EXTT +// - create DCC? - This TBA bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { switch (params) { case 0: // list turntable objects - return Turntable::printAll(stream); + StringFormatter::send(stream, F("\n")); + return true; + // return Turntable::printAll(stream); case 1: // delete turntable - if (!Turntable::remove(p[0])) - return false; - StringFormatter::send(stream, F("\n")); + // if (!Turntable::remove(p[0])) + // return false; + StringFormatter::send(stream, F("\n")); return true; case 2: // - rotate to position for DCC turntables case 3: // rotate to position for EX-Turntable { - + DIAG(F("Got %d parameters (2 or 3)"), params); + return true; } + + default: + { + if (params < 40) { + DIAG(F("Create turntable with %d parameters"), params); + return true; + } + } + break; + } + return false; } // CALLBACKS must be static diff --git a/IODevice.h b/IODevice.h index 8b8f3fe..769e111 100644 --- a/IODevice.h +++ b/IODevice.h @@ -542,7 +542,6 @@ protected: #include "IO_PCF8575.h" #include "IO_duinoNodes.h" #include "IO_EXIOExpander.h" -#include "IO_EXTurntable.h" #endif // iodevice_h diff --git a/IO_EXTurntable.h b/IO_EXTurntable.cpp similarity index 97% rename from IO_EXTurntable.h rename to IO_EXTurntable.cpp index 29ce679..f1a108b 100644 --- a/IO_EXTurntable.h +++ b/IO_EXTurntable.cpp @@ -20,9 +20,9 @@ /* * The IO_EXTurntable device driver is used to control a turntable via an Arduino with a stepper motor over I2C. * -* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/Turntable-EX) and contains the stepper motor logic. +* The EX-Turntable code lives in a separate repo (https://github.com/DCC-EX/EX-Turntable) and contains the stepper motor logic. * -* This device driver sends a step position to Turntable-EX to indicate the step position to move to using either of these commands: +* This device driver sends a step position to EX-Turntable to indicate the step position to move to using either of these commands: * in the serial console * MOVETT(vpin, steps, activity) in EX-RAIL * Refer to the documentation for further information including the valid activities. diff --git a/Turntables.cpp b/Turntables.cpp.txt similarity index 100% rename from Turntables.cpp rename to Turntables.cpp.txt diff --git a/Turntables.h b/Turntables.h.txt similarity index 100% rename from Turntables.h rename to Turntables.h.txt From c4febd1d0f15d2dec5fbba1784c84d9b3f58327c Mon Sep 17 00:00:00 2001 From: peteGSX Date: Mon, 21 Aug 2023 19:33:45 +1000 Subject: [PATCH 013/310] More parser --- DCCEXParser.cpp | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index cfe2563..55a6cf7 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1044,18 +1044,23 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return true; case 2: // - rotate to position for DCC turntables + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + return true; + case 3: // rotate to position for EX-Turntable - { - DIAG(F("Got %d parameters (2 or 3)"), params); - return true; - } + DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); + return true; - default: + default: // If we're here, it must be creating a turntable object { - if (params < 40) { - DIAG(F("Create turntable with %d parameters"), params); + if (params < 41 && p[1] == HASH_KEYWORD_EXTT) { + DIAG(F("Create EXTT turntable %d on vpin %d and address %s with %d positions"), p[0], p[2], p[3], params - 4); + return true; + } else if (params < 39 && p[1] == HASH_KEYWORD_DCC) { + DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); return true; } + } break; From b277d204f00b171b6d32407d3910da422a2334e8 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Tue, 22 Aug 2023 19:30:22 +1000 Subject: [PATCH 014/310] Progress! --- DCCEXParser.cpp | 28 ++++++++++++---------------- Turntables.cpp.txt => Turntables.cpp | 26 +++++++++++++------------- Turntables.h.txt => Turntables.h | 8 +++++--- 3 files changed, 30 insertions(+), 32 deletions(-) rename Turntables.cpp.txt => Turntables.cpp (88%) rename Turntables.h.txt => Turntables.h (96%) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 55a6cf7..4823e8e 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -41,7 +41,7 @@ #include "TrackManager.h" #include "DCCTimer.h" #include "EXRAIL2.h" -// #include "Turntables.h" +#include "Turntables.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -1033,14 +1033,12 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) switch (params) { case 0: // list turntable objects - StringFormatter::send(stream, F("\n")); - return true; - // return Turntable::printAll(stream); + return Turntable::printAll(stream); case 1: // delete turntable - // if (!Turntable::remove(p[0])) - // return false; - StringFormatter::send(stream, F("\n")); + if (!Turntable::remove(p[0])) + return false; + StringFormatter::send(stream, F("\n")); return true; case 2: // - rotate to position for DCC turntables @@ -1053,19 +1051,17 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { - if (params < 41 && p[1] == HASH_KEYWORD_EXTT) { - DIAG(F("Create EXTT turntable %d on vpin %d and address %s with %d positions"), p[0], p[2], p[3], params - 4); - return true; - } else if (params < 39 && p[1] == HASH_KEYWORD_DCC) { + if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { + DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); + if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); - return true; + } else { + return false; } - } - break; - + return true; } - return false; } // CALLBACKS must be static diff --git a/Turntables.cpp.txt b/Turntables.cpp similarity index 88% rename from Turntables.cpp.txt rename to Turntables.cpp index 45a1d05..67dc8c0 100644 --- a/Turntables.cpp.txt +++ b/Turntables.cpp @@ -36,13 +36,14 @@ Turntable *Turntable::_firstTurntable = 0; /* * Public static data */ -int Turntable::_turntablelistHash = 0; +int Turntable::turntablelistHash = 0; /* * Protected static functions */ // Add new turntable to end of list + void Turntable::add(Turntable *tto) { if (!_firstTurntable) { _firstTurntable = tto; @@ -73,25 +74,25 @@ bool Turntable::remove(uint16_t id) { pp->_nextTurntable = tto->_nextTurntable; } - delete (EXTTTurntable *)tto; + // delete (EXTTTurntable *)tto; turntablelistHash++; return true; } - /* * Public static functions */ bool Turntable::isPosition(uint16_t id, uint8_t position) { Turntable *tto = get(id); - if (!tto) return false; if (tto) { if (tto->getPosition() == position) { return true; } else { return false; } + } else { + return false; } } @@ -102,15 +103,16 @@ bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif + return true; } -bool Turntable::setPosition(uint16_t id, uint8_t position) { +bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) DIAG(F("Turntable(%d, %d)"), id, position); #endif Turntable *tto = Turntable::get(id); if (!tto) return false; - bool ok = tto->setPositionInternal(position); + bool ok = tto->setPositionInternal(position, activity); if (ok) { tto->setPositionStateOnly(id, position); @@ -123,30 +125,28 @@ bool Turntable::setPosition(uint16_t id, uint8_t position) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) : +EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : Turntable(id, TURNTABLE_EXTT) { _exttTurntableData.i2caddress = i2caddress; _exttTurntableData.vpin = vpin; - _exttTurntableData.positions = **positions; } // Create function #ifndef IO_NO_HAL - Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions) { + Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; - extt->_exttTurntableData.positions = positions; return tto; } else { remove(id); } } - tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin, **positions); + tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); DIAG(F("Turntable 0x%x"), tto); return tto; #else @@ -166,9 +166,9 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long ** bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL // Get step value from positions - int value = _exttTurntableData.positions[position]; + // int value = _exttTurntableData.positions[position]; // Set position via device driver - EXTurntable::_writeAnalogue(vpin, value, activity, 0); + // EXTurntable::_writeAnalogue(vpin, value, activity, 0); #else (void)position; #endif diff --git a/Turntables.h.txt b/Turntables.h similarity index 96% rename from Turntables.h.txt rename to Turntables.h index 5a6f346..2fa4255 100644 --- a/Turntables.h.txt +++ b/Turntables.h @@ -104,6 +104,7 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); + /* * Virtual functions @@ -112,6 +113,7 @@ public: (void)stream; // suppress compiler warnings } virtual ~Turntable() {} // Destructor + /* * Public static functions @@ -119,7 +121,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool remove(uint16_t id); static bool isPosition(uint16_t id, uint8_t position); - static bool setPosition(uint16_t id, uint8_t position); + static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { @@ -148,11 +150,11 @@ private: } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin); public: // Create function - static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin, long **positions); + static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin); void print(Print *stream) override; protected: From ff9c558b61b9213f54d68e3db2e667cf040e91e4 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Wed, 23 Aug 2023 19:08:04 +1000 Subject: [PATCH 015/310] Not much progress --- DCCEXParser.cpp | 6 +++--- Turntables.cpp | 2 +- Turntables.h | 7 ++++++- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 4823e8e..e6bd814 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,17 +1035,17 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // list turntable objects return Turntable::printAll(stream); - case 1: // delete turntable + case 1: // delete turntable if (!Turntable::remove(p[0])) return false; StringFormatter::send(stream, F("\n")); return true; - case 2: // - rotate to position for DCC turntables + case 2: // - rotate to position for DCC turntables DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); return true; - case 3: // rotate to position for EX-Turntable + case 3: // rotate to position for EX-Turntable DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); return true; diff --git a/Turntables.cpp b/Turntables.cpp index 67dc8c0..5aaf9f0 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -74,7 +74,7 @@ bool Turntable::remove(uint16_t id) { pp->_nextTurntable = tto->_nextTurntable; } - // delete (EXTTTurntable *)tto; + delete (EXTTTurntable *)tto; turntablelistHash++; return true; diff --git a/Turntables.h b/Turntables.h index 2fa4255..c7bb394 100644 --- a/Turntables.h +++ b/Turntables.h @@ -57,6 +57,12 @@ protected: uint16_t id; } _turntableData; + // Linked list to store either positions (EXTT) or DCC addresses (DCC) + struct Position { + int16_t position; + Position *next; + }; + // Pointer to next turntable object Turntable *_nextTurntable = 0; @@ -146,7 +152,6 @@ private: struct EXTTTurntableData { uint8_t i2caddress; VPIN vpin; - long **positions; // Array of longs to store step positions } _exttTurntableData; // Constructor From 57d4655d54be41357d7a87469c45847044b8f51b Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 24 Aug 2023 07:22:37 +1000 Subject: [PATCH 016/310] Fix Uno/Nano build errors --- Turntables.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Turntables.cpp b/Turntables.cpp index 5aaf9f0..2f2a05e 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -133,8 +133,8 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : } // Create function -#ifndef IO_NO_HAL Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { +#ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { @@ -153,7 +153,6 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : (void)id; (void)i2caddress; (void)vpin; - (void)positions; return NULL; #endif } From fa0aa27d466264378b680675b54fd1d86d96f8a5 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Fri, 18 Aug 2023 18:52:34 +1000 Subject: [PATCH 017/310] Add OPCODE list to DCCEXParser.cpp --- DCCEXParser.cpp | 73 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 73 insertions(+) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aaf733c..7610d45 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -25,6 +25,79 @@ * You should have received a copy of the GNU General Public License * along with CommandStation. If not, see . */ + +/* +List of single character OPCODEs in use for reference. + +When determining a new OPCODE for a new feature, refer to this list as the source of truth. + +Once a new OPCODE is decided upon, update this list. + + Character, Usage + /, |EX-R| interactive commands + -, Remove from reminder table + =, |TM| configuration + !, Emergency stop + @, Reserved for future use - LCD messages to JMRI + #, Request number of supported cabs/locos; heartbeat + +, WiFi AT commands + ?, Reserved for future use + 0, Track power off + 1, Track power on + a, DCC accessory control + A, + b, Write CV bit on main + B, Write CV bit + c, Request current command + C, + d, + D, Diagnostic commands + e, Erase EEPROM + E, Store configuration in EEPROM + f, Loco decoder function control (deprecated) + F, Loco decoder function control + g, + G, + h, + H, Turnout state broadcast + i, Reserved for future use - Turntable object broadcast + I, Reserved for future use - Turntable object command and control + j, Throttle responses + J, Throttle queries + k, Reserved for future use - Potentially Railcom + K, Reserved for future use - Potentially Railcom + l, Loco speedbyte/function map broadcast + L, + m, + M, Write DCC packet + n, + N, + o, + O, Output broadcast + p, Broadcast power state + P, Write DCC packet + q, Sensor deactivated + Q, Sensor activated + r, Broadcast address read on programming track + R, Read CVs + s, Display status + S, Sensor configuration + t, Cab/loco update command + T, Turnout configuration/control + u, Reserved for user commands + U, Reserved for user commands + v, + V, Verify CVs + w, Write CV on main + W, Write CV + x, + X, Invalid command + y, + Y, Output broadcast + z, + Z, Output configuration/control +*/ + #include "StringFormatter.h" #include "DCCEXParser.h" #include "DCC.h" From 9842ea8a429ba877579f615a181dfeabacaa7446 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 24 Aug 2023 10:03:29 +0200 Subject: [PATCH 018/310] Bugfix: execute 30ms off time before rejoin --- DCCACK.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCACK.cpp b/DCCACK.cpp index 1b339ee..8a074b4 100644 --- a/DCCACK.cpp +++ b/DCCACK.cpp @@ -351,7 +351,7 @@ void DCCACK::callback(int value) { switch (callbackState) { case AFTER_READ: - if (ackManagerRejoin && autoPowerOff) { + if (ackManagerRejoin && !autoPowerOff) { progDriver->setPower(POWERMODE::OFF); callbackStart=millis(); callbackState=WAITING_30; From 25f8852af6d72fd506c0b7d2f87a43a2ac9cb9fc Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 24 Aug 2023 10:09:38 +0200 Subject: [PATCH 019/310] call devel for 5.1.X version number update --- GITHUB_SHA.h | 2 +- version.h | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index de4f953..9de7154 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308102205Z" +#define GITHUB_SHA "devel-202308240808Z" diff --git a/version.h b/version.h index cf1fd26..bd45999 100644 --- a/version.h +++ b/version.h @@ -3,9 +3,10 @@ #include "StringFormatter.h" -#define VERSION "5.0.1" -// 5.0.1 - Check bad AT firmware version +#define VERSION "5.1.1" +// 5.1.1 - Check bad AT firmware version // - Update IO_PCA9555.h reflecting IO_MCP23017.h changes to support PCA9548 mux +// 5.0.1 - Bugfix: execute 30ms off time before rejoin // 5.0.0 - Make 4.2.69 the 5.0.0 release // 4.2.69 - Bugfix: Make work in DC mode // 4.2.68 - Rename track mode OFF to NONE From 6392c74eadac6b8ed4a26e79a1e59f3d9b53c4b6 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Thu, 24 Aug 2023 14:53:01 +0100 Subject: [PATCH 020/310] Update myHal.cpp_example.txt Added missing ::create to LiquidCrystal --- myHal.cpp_example.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index d93ea5c..5e9fec4 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -51,7 +51,7 @@ void halSetup() { // Create a 20x4 LCD display device as display number 2 // (line 0 is written by EX-RAIL 'SCREEN(2, 0, "text")'). - // HALDisplay(2, 0x27, 20, 4); + // HALDisplay::create(2, 0x27, 20, 4); //======================================================================= From fb226311e5ed62cfae2b1dce42fd1a41293b9004 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Thu, 24 Aug 2023 14:54:33 +0100 Subject: [PATCH 021/310] Update myHal.cpp_example.txt Added missing ::create to LiquidCrystal HAL definition --- myHal.cpp_example.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index d93ea5c..5e9fec4 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -51,7 +51,7 @@ void halSetup() { // Create a 20x4 LCD display device as display number 2 // (line 0 is written by EX-RAIL 'SCREEN(2, 0, "text")'). - // HALDisplay(2, 0x27, 20, 4); + // HALDisplay::create(2, 0x27, 20, 4); //======================================================================= From 3453da067130c9deee9cbbd12a823f157062f796 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 25 Aug 2023 19:07:57 +0200 Subject: [PATCH 022/310] Bugfix: ESP32 30ms off time --- TrackManager.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 0f69235..91c78ea 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -53,7 +53,7 @@ bool TrackManager::progTrackSyncMain=false; bool TrackManager::progTrackBoosted=false; int16_t TrackManager::joinRelay=UNUSED_PIN; #ifdef ARDUINO_ARCH_ESP32 -byte TrackManager::tempProgTrack=MAX_TRACKS+1; +byte TrackManager::tempProgTrack=MAX_TRACKS+1; // MAX_TRACKS+1 is the unused flag #endif #ifdef ANALOG_READ_INTERRUPT @@ -505,7 +505,12 @@ void TrackManager::setJoin(bool joined) { } } else { if (tempProgTrack != MAX_TRACKS+1) { + // as setTrackMode with TRACK_MODE_PROG defaults to + // power off, we will take the current power state + // of our track and then preserve that state. + POWERMODE tPTmode = track[tempProgTrack]->getPower(); //get current power status of this track setTrackMode(tempProgTrack, TRACK_MODE_PROG); + track[tempProgTrack]->setPower(tPTmode); //set track status as it was before tempProgTrack = MAX_TRACKS+1; } } From 25426d076dde591e94e85879e660344f799f4d91 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 25 Aug 2023 19:14:03 +0200 Subject: [PATCH 023/310] version number update --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 9de7154..8ae1d2b 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308240808Z" +#define GITHUB_SHA "devel-202308251713Z" diff --git a/version.h b/version.h index bd45999..4bcf6b5 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.1" +#define VERSION "5.1.2" +// 5.1.2 - Bugfix: ESP32 30ms off time // 5.1.1 - Check bad AT firmware version // - Update IO_PCA9555.h reflecting IO_MCP23017.h changes to support PCA9548 mux // 5.0.1 - Bugfix: execute 30ms off time before rejoin From b823a647ac82a90ad1f95b3797933e92854d0eca Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Sat, 26 Aug 2023 10:26:01 +1000 Subject: [PATCH 024/310] Some progress --- DCCEXParser.cpp | 26 ++++++++++++++++++++------ Turntables.cpp | 29 ++++++++++++++--------------- Turntables.h | 49 +++++++++++++++++++++++++++++++++++++++++-------- 3 files changed, 75 insertions(+), 29 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index e6bd814..835dd32 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,18 +1035,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // list turntable objects return Turntable::printAll(stream); - case 1: // delete turntable - if (!Turntable::remove(p[0])) - return false; - StringFormatter::send(stream, F("\n")); - return true; + case 1: // nothing here for the moment at least + return false; case 2: // - rotate to position for DCC turntables DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); return true; case 3: // rotate to position for EX-Turntable - DIAG(F("Rotate EXTT turntable %d to angle %d with activity %d"), p[0], p[1], p[2]); + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Position %d value is %d"), p[1], value); + } else { + return false; + } + } else { + return false; + } + } return true; default: // If we're here, it must be creating a turntable object @@ -1054,6 +1063,11 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + Turntable *tto = Turntable::get(p[0]); + for ( uint8_t i = 0; i < params - 4; i++) { + tto->addPosition(p[i + 3]); + DIAG(F("Add position %d"), p[i + 3]); + } } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index 2f2a05e..1ab5a70 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -62,22 +62,23 @@ Turntable *Turntable::get(uint16_t id) { return NULL; } -// Remove specified turntable from list and delete it -bool Turntable::remove(uint16_t id) { - Turntable *tto, *pp=NULL; +// Add a position +void Turntable::addPosition(uint16_t value) { + _turntablePositions.insert(value); +} - for (tto=_firstTurntable; tto!=NULL && tto->_turntableData.id!=id; pp=tto, tto=tto->_nextTurntable) {} - if (tto == NULL) return false; - if (tto == _firstTurntable) { - _firstTurntable = tto->_nextTurntable; - } else { - pp->_nextTurntable = tto->_nextTurntable; +// Get value for position +uint16_t Turntable::getPositionValue(size_t position) { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + for (size_t i = 0; i < position && currentPosition; i++) { + currentPosition = currentPosition->next; } - delete (EXTTTurntable *)tto; - - turntablelistHash++; - return true; + if (currentPosition) { + return currentPosition->data; + } else { + return false; + } } /* @@ -142,8 +143,6 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; return tto; - } else { - remove(id); } } tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); diff --git a/Turntables.h b/Turntables.h index c7bb394..3708d2a 100644 --- a/Turntables.h +++ b/Turntables.h @@ -33,6 +33,41 @@ enum { // TURNTABLE_DCC = 2, }; +/************************************************************************************* + * Turntable positions. + * + *************************************************************************************/ +struct TurntablePosition { + uint16_t data; + TurntablePosition* next; + + TurntablePosition(uint16_t value) : data(value), next(nullptr) {} +}; + +class TurntablePositionList { +public: + TurntablePositionList() : head(nullptr) {} + + void insert(uint16_t value) { + TurntablePosition* newPosition = new TurntablePosition(value); + if(!head) { + head = newPosition; + } else { + newPosition->next = head; + head = newPosition; + } + } + + TurntablePosition* getHead() { + return head; + } + +private: + TurntablePosition* head; + +}; + + /************************************************************************************* * Turntable - Base class for turntables. * @@ -57,15 +92,12 @@ protected: uint16_t id; } _turntableData; - // Linked list to store either positions (EXTT) or DCC addresses (DCC) - struct Position { - int16_t position; - Position *next; - }; - // Pointer to next turntable object Turntable *_nextTurntable = 0; + // Linked list for positions + TurntablePositionList _turntablePositions; + /* * Constructor */ @@ -73,6 +105,7 @@ protected: _turntableData.id = id; _turntableData.turntableType = turntableType; _turntableData.hidden = false; + _turntableData.position = 0; add(this); } @@ -110,7 +143,8 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - + void addPosition(uint16_t value); + uint16_t getPositionValue(size_t position); /* * Virtual functions @@ -125,7 +159,6 @@ public: * Public static functions */ inline static bool exists(uint16_t id) { return get(id) != 0; } - static bool remove(uint16_t id); static bool isPosition(uint16_t id, uint8_t position); static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); From 1425da20b500f254f7f16b2a1ba4493f463753ce Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 26 Aug 2023 19:41:17 +1000 Subject: [PATCH 025/310] Correct order --- DCCEXParser.cpp | 5 +++-- IO_EXTurntable.cpp | 1 + Turntables.cpp | 12 ++++++------ Turntables.h | 6 +++--- 4 files changed, 13 insertions(+), 11 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 835dd32..995162b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1060,11 +1060,12 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { + DIAG(F("Params: %d"), params); if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); - if (!EXTTTurntable::create(p[0], (uint8_t)p[1], (VPIN)p[2])) return false; + if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for ( uint8_t i = 0; i < params - 4; i++) { + for ( uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); DIAG(F("Add position %d"), p[i + 3]); } diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index f1a108b..b57fa25 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -100,6 +100,7 @@ int EXTurntable::_read(VPIN vpin) { // Acc_Off = 9 // Turn accessory pin off void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) { if (_deviceState == DEVSTATE_FAILED) return; + if (value < 0) return; uint8_t stepsMSB = value >> 8; uint8_t stepsLSB = value & 0xFF; #ifdef DIAG_IO diff --git a/Turntables.cpp b/Turntables.cpp index 1ab5a70..f75b30d 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -126,26 +126,26 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : +EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : Turntable(id, TURNTABLE_EXTT) { - _exttTurntableData.i2caddress = i2caddress; _exttTurntableData.vpin = vpin; + _exttTurntableData.i2caddress = i2caddress; } // Create function - Turntable *EXTTTurntable::create(uint16_t id, uint8_t i2caddress, VPIN vpin) { + Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin, uint8_t i2caddress) { #ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; - extt->_exttTurntableData.i2caddress = i2caddress; extt->_exttTurntableData.vpin = vpin; + extt->_exttTurntableData.i2caddress = i2caddress; return tto; } } - tto = (Turntable *)new EXTTTurntable(id, i2caddress, vpin); + tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); DIAG(F("Turntable 0x%x"), tto); return tto; #else @@ -157,7 +157,7 @@ EXTTTurntable::EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin) : } void EXTTTurntable::print(Print *stream) { - StringFormatter::send(stream, F("\n"), _turntableData.id, _exttTurntableData.i2caddress, _exttTurntableData.vpin); + StringFormatter::send(stream, F("\n"), _turntableData.id, _exttTurntableData.vpin, _exttTurntableData.i2caddress); } // EX-Turntable specific code for moving to the specified position diff --git a/Turntables.h b/Turntables.h index 3708d2a..303c542 100644 --- a/Turntables.h +++ b/Turntables.h @@ -183,16 +183,16 @@ class EXTTTurntable : public Turntable { private: // EXTTTurntableData contains device specific data struct EXTTTurntableData { - uint8_t i2caddress; VPIN vpin; + uint8_t i2caddress; } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, uint8_t i2caddress, VPIN vpin); + EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress); public: // Create function - static Turntable *create(uint16_t id, uint8_t i2caddress, VPIN vpin); + static Turntable *create(uint16_t id, VPIN vpin, uint8_t i2caddress); void print(Print *stream) override; protected: From 2202cb0c5eddbc4ca3c1a3df1c95604278f64353 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 27 Aug 2023 19:30:56 +1000 Subject: [PATCH 026/310] Minor progress --- DCCEXParser.cpp | 6 +++--- IO_EXTurntable.cpp | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 995162b..48c45fb 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1060,15 +1060,15 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { - DIAG(F("Params: %d"), params); if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); + if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for ( uint8_t i = params - 4; i > 0; i--) { + for (uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); - DIAG(F("Add position %d"), p[i + 3]); } + tto->addPosition(0); // Need to add position 0 as 0 so positions start at 1 } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index b57fa25..8c7057b 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -51,6 +51,7 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { void EXTurntable::_begin() { I2CManager.begin(); if (I2CManager.exists(_I2CAddress)) { + DIAG(F("EX-Turntable device found, I2C:%s"), _I2CAddress.toString()); #ifdef DIAG_IO _display(); #endif From df4a501e8a34fd7748675bf3801be10419334649 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 28 Aug 2023 08:36:09 +1000 Subject: [PATCH 027/310] Writing to driver --- DCCEXParser.cpp | 23 +++++++++++++++-------- Turntables.cpp | 22 ++++++---------------- Turntables.h | 1 - 3 files changed, 21 insertions(+), 25 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 48c45fb..45e8a73 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1039,19 +1039,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return false; case 2: // - rotate to position for DCC turntables - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (tto->getPosition() == p[1]) return true; + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + } else { + return false; + } + } else { + return false; + } + } return true; case 3: // rotate to position for EX-Turntable { Turntable *tto = Turntable::get(p[0]); if (tto) { - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Position %d value is %d"), p[1], value); - } else { - return false; - } + if (!tto->setPosition(p[0], p[1], p[2])) return false; } else { return false; } @@ -1061,7 +1069,6 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) default: // If we're here, it must be creating a turntable object { if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { - DIAG(F("Create EXTT turntable %d on vpin %d and address %d with %d positions"), p[0], p[2], p[3], params - 4); if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); diff --git a/Turntables.cpp b/Turntables.cpp index f75b30d..ec31a00 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -84,19 +84,6 @@ uint16_t Turntable::getPositionValue(size_t position) { /* * Public static functions */ -bool Turntable::isPosition(uint16_t id, uint8_t position) { - Turntable *tto = get(id); - if (tto) { - if (tto->getPosition() == position) { - return true; - } else { - return false; - } - } else { - return false; - } -} - bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { Turntable *tto = get(id); if (!tto) return false; @@ -117,6 +104,7 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { tto->setPositionStateOnly(id, position); + tto->_turntableData.position = position; } return ok; } @@ -163,10 +151,12 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : // EX-Turntable specific code for moving to the specified position bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL - // Get step value from positions - // int value = _exttTurntableData.positions[position]; + DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); + // Get position value from position list + int16_t value = getPositionValue(position); + if (!value) return false; // Return false if it's not a valid position // Set position via device driver - // EXTurntable::_writeAnalogue(vpin, value, activity, 0); + EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else (void)position; #endif diff --git a/Turntables.h b/Turntables.h index 303c542..f3a3321 100644 --- a/Turntables.h +++ b/Turntables.h @@ -159,7 +159,6 @@ public: * Public static functions */ inline static bool exists(uint16_t id) { return get(id) != 0; } - static bool isPosition(uint16_t id, uint8_t position); static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position); inline static Turntable *first() { return _firstTurntable; } From 3bfdd16288af0424c7d162f6f13787a79030dc25 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 28 Aug 2023 13:11:37 +1000 Subject: [PATCH 028/310] Start on JO --- DCCEXParser.cpp | 26 +++++++++++++++++++++++++- Turntables.cpp | 4 ++-- 2 files changed, 27 insertions(+), 3 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 45e8a73..f8dd9d4 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -85,6 +85,7 @@ const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_I='I'; +const int16_t HASH_KEYWORD_O='O'; const int16_t HASH_KEYWORD_R='R'; const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_X='X'; @@ -691,6 +692,29 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; + case HASH_KEYWORD_O: // + for ( Turntable * tto=Turntable::first(); tto; tto=tto->next()) { + if (tto->isHidden()) continue; + StringFormatter::send(stream, F(" %d"),tto->getId()); + } + } else { // + Turntable *tto=Turntable::get(id); + if (!tto || tto->isHidden()) { + StringFormatter::send(stream, F(" %d X"), id); + } else { + uint8_t pos = tto->getPosition(); + const FSH *todesc = NULL; +#ifdef EXRAIL_ACTIVE + // todesc = RMFT2::getTurntableDescription(id); +#endif + if (todesc == NULL) todesc = F(""); + StringFormatter::send(stream, F(" %d %d"), id, pos); + } + } + StringFormatter::send(stream, F(">\n")); + return; default: break; } // switch(p[1]) break; // case J @@ -1075,7 +1099,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) for (uint8_t i = params - 4; i > 0; i--) { tto->addPosition(p[i + 3]); } - tto->addPosition(0); // Need to add position 0 as 0 so positions start at 1 + tto->addPosition(p[3]); // Allow setting a value for the home angle for throttles to draw it } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index ec31a00..5332aa5 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -152,8 +152,8 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); - // Get position value from position list - int16_t value = getPositionValue(position); + if (position == 0) return false; // Position 0 is just so throttles know where home is + int16_t value = getPositionValue(position); // Get position value from position list if (!value) return false; // Return false if it's not a valid position // Set position via device driver EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); From b0d85101275b3184f902547a9b0f6a684571e5e9 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 29 Aug 2023 13:38:52 +1000 Subject: [PATCH 029/310] Working but limited --- DCCEXParser.cpp | 17 +++++++++++------ Turntables.cpp | 32 +++++++++++++++++++++++++------- Turntables.h | 2 ++ 3 files changed, 38 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index f8dd9d4..9047cad 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -695,7 +695,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case HASH_KEYWORD_O: // - for ( Turntable * tto=Turntable::first(); tto; tto=tto->next()) { + for (Turntable * tto=Turntable::first(); tto; tto=tto->next()) { if (tto->isHidden()) continue; StringFormatter::send(stream, F(" %d"),tto->getId()); } @@ -705,12 +705,18 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) StringFormatter::send(stream, F(" %d X"), id); } else { uint8_t pos = tto->getPosition(); + uint8_t type = tto->getType(); + uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE // todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d"), id, pos); + StringFormatter::send(stream, F(" %d %d %d %d"), id, type, pos, posCount); + for (uint8_t p = 0; p < posCount; p++) { + int16_t value = tto->getPositionValue(p); + StringFormatter::send(stream, F(" %d"), value); + } } } StringFormatter::send(stream, F(">\n")); @@ -1047,7 +1053,6 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable // - list all -// - delete // - operate (DCC) // - operate (EXTT) // - create EXTT @@ -1096,10 +1101,10 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for (uint8_t i = params - 4; i > 0; i--) { - tto->addPosition(p[i + 3]); + for (uint8_t i = params - 5; i > 0; i--) { + tto->addPosition(p[i + 4]); } - tto->addPosition(p[3]); // Allow setting a value for the home angle for throttles to draw it + tto->addPosition(p[4]); // Allow setting a value for the home angle for throttles to draw it } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { diff --git a/Turntables.cpp b/Turntables.cpp index 5332aa5..bcc0a94 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -81,6 +81,17 @@ uint16_t Turntable::getPositionValue(size_t position) { } } +// Get the count of positions associated with the turntable +uint8_t Turntable::getPositionCount() { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + uint8_t count = 0; + while (currentPosition) { + count++; + currentPosition = currentPosition->next; + } + return count; +} + /* * Public static functions */ @@ -103,8 +114,11 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { bool ok = tto->setPositionInternal(position, activity); if (ok) { - tto->setPositionStateOnly(id, position); - tto->_turntableData.position = position; + // Broadcast a position change only if non zero has been set, or home/calibration sent + if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { + tto->setPositionStateOnly(id, position); + tto->_turntableData.position = position; + } } return ok; } @@ -134,7 +148,7 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : } } tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); - DIAG(F("Turntable 0x%x"), tto); + DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; #else (void)id; @@ -151,10 +165,14 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : // EX-Turntable specific code for moving to the specified position bool EXTTTurntable::setPositionInternal(uint8_t position, uint8_t activity) { #ifndef IO_NO_HAL - DIAG(F("Set EXTT %d to position %d with activity %d"), _exttTurntableData.vpin, position, activity); - if (position == 0) return false; // Position 0 is just so throttles know where home is - int16_t value = getPositionValue(position); // Get position value from position list - if (!value) return false; // Return false if it's not a valid position + int16_t value; + if (position == 0) { + value = 0; // Position 0 is just to send activities + } else { + if (activity > 1) return false; // If sending a position update, only phase changes valid (0|1) + value = getPositionValue(position); // Get position value from position list + } + if (position > 0 && !value) return false; // Return false if it's not a valid position // Set position via device driver EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else diff --git a/Turntables.h b/Turntables.h index f3a3321..1016140 100644 --- a/Turntables.h +++ b/Turntables.h @@ -140,11 +140,13 @@ public: inline bool isHidden() { return _turntableData.hidden; } inline void setHidden(bool h) {_turntableData.hidden=h; } inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } + inline uint8_t getType() { return _turntableData.turntableType; } inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); void addPosition(uint16_t value); uint16_t getPositionValue(size_t position); + uint8_t getPositionCount(); /* * Virtual functions From 6cad794411f60f2022548cb9fb9c6272a0daafd2 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Tue, 29 Aug 2023 19:04:45 +1000 Subject: [PATCH 030/310] Working with 15 positions --- DCCEXParser.cpp | 10 +++++++++- DCCEXParser.h | 5 ++++- IODevice.h | 6 ------ Turntables.cpp | 4 ++++ Turntables.h | 5 +++++ defines.h | 20 ++++++++++++++++++++ 6 files changed, 42 insertions(+), 8 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9047cad..a37e5d0 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -692,6 +692,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; +// No turntables without HAL support +#ifndef IO_NO_HAL case HASH_KEYWORD_O: // @@ -721,15 +723,19 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } StringFormatter::send(stream, F(">\n")); return; +#endif default: break; } // switch(p[1]) break; // case J } +// No turntables without HAL support +#ifndef IO_NO_HAL case 'I': // TURNTABLE if (parseI(stream, params, p)) return; break; +#endif default: //anything else will diagnose and drop out to DIAG(F("Opcode=%c params=%d"), opcode, params); @@ -1051,12 +1057,13 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) } // ========================== -// Turntable +// Turntable - no support if no HAL // - list all // - operate (DCC) // - operate (EXTT) // - create EXTT // - create DCC? - This TBA +#ifndef IO_NO_HAL bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { switch (params) @@ -1114,6 +1121,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return true; } } +#endif // CALLBACKS must be static bool DCCEXParser::stashCallback(Print *stream, int16_t p[MAX_COMMAND_PARAMS], RingStream * ringStream) diff --git a/DCCEXParser.h b/DCCEXParser.h index bf067a7..a3d5e10 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -24,6 +24,7 @@ #include #include "FSH.h" #include "RingStream.h" +#include "defines.h" typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); typedef void (*AT_COMMAND_CALLBACK)(HardwareSerial * stream,const byte * command); @@ -37,7 +38,7 @@ struct DCCEXParser static void setFilter(FILTER_CALLBACK filter); static void setRMFTFilter(FILTER_CALLBACK filter); static void setAtCommandCallback(AT_COMMAND_CALLBACK filter); - static const int MAX_COMMAND_PARAMS=10; // Must not exceed this + static const int MAX_COMMAND_PARAMS=MAX_PARSER_PARAMS; // Must not exceed this private: @@ -49,7 +50,9 @@ struct DCCEXParser static bool parseS(Print * stream, int16_t params, int16_t p[]); static bool parsef(Print * stream, int16_t params, int16_t p[]); static bool parseD(Print * stream, int16_t params, int16_t p[]); +#ifndef IO_NO_HAL static bool parseI(Print * stream, int16_t params, int16_t p[]); +#endif static Print * getAsyncReplyStream(); static void commitAsyncReplyStream(); diff --git a/IODevice.h b/IODevice.h index 769e111..d2c80a4 100644 --- a/IODevice.h +++ b/IODevice.h @@ -27,12 +27,6 @@ // Define symbol DIAG_LOOPTIMES to enable CS loop execution time to be reported //#define DIAG_LOOPTIMES -// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required -// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. -#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) -#define IO_NO_HAL -#endif - // Define symbol IO_SWITCH_OFF_SERVO to set the PCA9685 output to 0 when an // animation has completed. This switches off the servo motor, preventing // the continuous buzz sometimes found on servos, and reducing the diff --git a/Turntables.cpp b/Turntables.cpp index bcc0a94..6b4260f 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -26,6 +26,8 @@ #include "EXRAIL2.h" #include "DCC.h" +// No turntable support without HAL +#ifndef IO_NO_HAL /* * Protected static data @@ -180,3 +182,5 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : #endif return true; } + +#endif diff --git a/Turntables.h b/Turntables.h index 1016140..67017df 100644 --- a/Turntables.h +++ b/Turntables.h @@ -25,6 +25,9 @@ #include "IODevice.h" #include "StringFormatter.h" +// No turntable support without HAL +#ifndef IO_NO_HAL + // Turntable type definitions // EXTT = EX-Turntable // DCC = DCC accessory turntables - to be added later @@ -203,3 +206,5 @@ protected: }; #endif + +#endif diff --git a/defines.h b/defines.h index f3822ca..342d1b6 100644 --- a/defines.h +++ b/defines.h @@ -213,6 +213,26 @@ // #define WIFI_SERIAL_LINK_SPEED 115200 +//////////////////////////////////////////////////////////////////////////////// +// +// Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required +// The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. +// +#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) +#define IO_NO_HAL +#endif + +//////////////////////////////////////////////////////////////////////////////// +// +// This defines the maximum number of parameters DCCEXParser will accept. +// The increase is required to allow for a sufficient number of turntable positions. +// +#ifdef IO_NO_HAL + #define MAX_PARSER_PARAMS 10 +#else + #define MAX_PARSER_PARAMS 20 +#endif + #if __has_include ( "myAutomation.h") #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #define EXRAIL_ACTIVE From 26ddd27ecf769f1be45e3b7acaf16f5265023783 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 29 Aug 2023 14:27:38 +0200 Subject: [PATCH 031/310] let user disable command in favour for HAL on the Uno platform --- DCCEXParser.cpp | 4 ++-- IODevice.h | 9 +++++++-- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7610d45..49d2d20 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -638,12 +638,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case ' ': // < > StringFormatter::send(stream, F("\n")); return; - +#ifndef DISABLE_DIAG case 'D': // < > if (parseD(stream, params, p)) return; return; - +#endif case '=': // <= Track manager control > if (TrackManager::parseJ(stream, params, p)) return; diff --git a/IODevice.h b/IODevice.h index 769e111..4eb24e5 100644 --- a/IODevice.h +++ b/IODevice.h @@ -29,8 +29,13 @@ // Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required // The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. -#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) -#define IO_NO_HAL +#include "defines.h" +#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) + #if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG) + #warning you have sacrificed DIAG for HAL + #else + #define IO_NO_HAL + #endif #endif // Define symbol IO_SWITCH_OFF_SERVO to set the PCA9685 output to 0 when an From 232ac993ecf58451457d6b959cd0845616ff18b0 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 30 Aug 2023 08:45:11 +1000 Subject: [PATCH 032/310] Separate add from create --- DCCEXParser.cpp | 65 +++++++++++++++++++++++++++++++------------------ Turntables.cpp | 14 +++++------ Turntables.h | 18 ++++++++------ 3 files changed, 57 insertions(+), 40 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a37e5d0..24a7914 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -98,6 +98,7 @@ const int16_t HASH_KEYWORD_WIFI = -5583; const int16_t HASH_KEYWORD_ETHERNET = -30767; const int16_t HASH_KEYWORD_WIT = 31594; const int16_t HASH_KEYWORD_EXTT = 8573; +const int16_t HASH_KEYWORD_ADD = 3201; int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; @@ -714,7 +715,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) // todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d %d"), id, type, pos, posCount); + StringFormatter::send(stream, F(" %d %d %d"), id, type, pos); for (uint8_t p = 0; p < posCount; p++) { int16_t value = tto->getPositionValue(p); StringFormatter::send(stream, F(" %d"), value); @@ -1059,10 +1060,12 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) // ========================== // Turntable - no support if no HAL // - list all +// - broadcast type and current position +// - create DCC - This is TBA // - operate (DCC) // - operate (EXTT) -// - create EXTT -// - create DCC? - This TBA +// - add position +// - create EXTT #ifndef IO_NO_HAL bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) { @@ -1071,47 +1074,58 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 0: // list turntable objects return Turntable::printAll(stream); - case 1: // nothing here for the moment at least + case 1: // broadcast type and current position return false; case 2: // - rotate to position for DCC turntables { - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (tto->getPosition() == p[1]) return true; - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable + DIAG(F("Create DCC turntable %d"), p[0]); + } else { // Otherwise move a DCC turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (tto->getPosition() == p[1]) return true; + uint16_t value = tto->getPositionValue(p[1]); + if (value) { + DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); + } else { + return false; + } } else { return false; } - } else { - return false; } } return true; - case 3: // rotate to position for EX-Turntable + case 3: { - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } else { - return false; + if (p[1] == HASH_KEYWORD_ADD) { // add position value to turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + tto->addPosition(p[2]); + StringFormatter::send(stream, F("\n")); + } else { + return false; + } + } else { // rotate to position for EX-Turntable + Turntable *tto = Turntable::get(p[0]); + if (tto) { + if (!tto->setPosition(p[0], p[1], p[2])) return false; + } else { + return false; + } } } return true; - default: // If we're here, it must be creating a turntable object + case 5: // create an EXTT turntable { - if (params > 5 && params < 41 && p[1] == HASH_KEYWORD_EXTT) { + if (p[1] == HASH_KEYWORD_EXTT) { if (Turntable::get(p[0])) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; Turntable *tto = Turntable::get(p[0]); - for (uint8_t i = params - 5; i > 0; i--) { - tto->addPosition(p[i + 4]); - } - tto->addPosition(p[4]); // Allow setting a value for the home angle for throttles to draw it + tto->addPosition(p[4]); } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); } else { @@ -1119,6 +1133,9 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } } return true; + + default: // Anything else is invalid + return false; } } #endif diff --git a/Turntables.cpp b/Turntables.cpp index 6b4260f..a7d42ab 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -70,17 +70,15 @@ void Turntable::addPosition(uint16_t value) { } // Get value for position -uint16_t Turntable::getPositionValue(size_t position) { +uint16_t Turntable::getPositionValue(uint8_t position) { TurntablePosition* currentPosition = _turntablePositions.getHead(); - for (size_t i = 0; i < position && currentPosition; i++) { + while (currentPosition) { + if (currentPosition->index == position) { + return currentPosition->data; + } currentPosition = currentPosition->next; } - - if (currentPosition) { - return currentPosition->data; - } else { - return false; - } + return false; } // Get the count of positions associated with the turntable diff --git a/Turntables.h b/Turntables.h index 67017df..36f5b90 100644 --- a/Turntables.h +++ b/Turntables.h @@ -32,8 +32,8 @@ // EXTT = EX-Turntable // DCC = DCC accessory turntables - to be added later enum { - TURNTABLE_EXTT = 1, - // TURNTABLE_DCC = 2, + TURNTABLE_EXTT = 0, + TURNTABLE_DCC = 1, }; /************************************************************************************* @@ -41,18 +41,19 @@ enum { * *************************************************************************************/ struct TurntablePosition { + uint8_t index; uint16_t data; TurntablePosition* next; - TurntablePosition(uint16_t value) : data(value), next(nullptr) {} + TurntablePosition(uint8_t idx, uint16_t value) : index(idx), data(value), next(nullptr) {} }; class TurntablePositionList { public: - TurntablePositionList() : head(nullptr) {} + TurntablePositionList() : head(nullptr), currentIndex(0) {} void insert(uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(value); + TurntablePosition* newPosition = new TurntablePosition(currentIndex++, value); if(!head) { head = newPosition; } else { @@ -67,6 +68,7 @@ public: private: TurntablePosition* head; + uint8_t currentIndex; }; @@ -87,8 +89,8 @@ protected: union { struct { bool hidden : 1; - uint8_t turntableType : 2; - uint8_t position : 5; // Allows up to 38 positions including 0/home + bool turntableType : 1; + uint8_t position : 6; // Allows up to 63 positions including 0/home }; uint8_t flags; }; @@ -148,7 +150,7 @@ public: inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); void addPosition(uint16_t value); - uint16_t getPositionValue(size_t position); + uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); /* From dbf053858b61d5315790427adb5ed4da08e7a8ae Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 30 Aug 2023 13:40:09 +1000 Subject: [PATCH 033/310] Undo max params --- DCCEXParser.h | 2 +- defines.h | 11 ----------- 2 files changed, 1 insertion(+), 12 deletions(-) diff --git a/DCCEXParser.h b/DCCEXParser.h index a3d5e10..8a7367a 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -38,7 +38,7 @@ struct DCCEXParser static void setFilter(FILTER_CALLBACK filter); static void setRMFTFilter(FILTER_CALLBACK filter); static void setAtCommandCallback(AT_COMMAND_CALLBACK filter); - static const int MAX_COMMAND_PARAMS=MAX_PARSER_PARAMS; // Must not exceed this + static const int MAX_COMMAND_PARAMS=10; // Must not exceed this private: diff --git a/defines.h b/defines.h index 342d1b6..3286aca 100644 --- a/defines.h +++ b/defines.h @@ -222,17 +222,6 @@ #define IO_NO_HAL #endif -//////////////////////////////////////////////////////////////////////////////// -// -// This defines the maximum number of parameters DCCEXParser will accept. -// The increase is required to allow for a sufficient number of turntable positions. -// -#ifdef IO_NO_HAL - #define MAX_PARSER_PARAMS 10 -#else - #define MAX_PARSER_PARAMS 20 -#endif - #if __has_include ( "myAutomation.h") #if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG) #define EXRAIL_ACTIVE From a0c1ad182cb9f76be7da471a6f18ea7698431cde Mon Sep 17 00:00:00 2001 From: peteGSX Date: Wed, 30 Aug 2023 19:48:30 +1000 Subject: [PATCH 034/310] Start on callback --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- DCCEXParser.cpp | 5 +++++ DCCEXParser.h | 1 + Turntables.cpp | 10 +++++++--- Turntables.h | 5 ++++- 6 files changed, 20 insertions(+), 7 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index eef84a9..ee760b0 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -161,8 +161,8 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { #endif } -void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position) { - broadcastReply(COMMAND_TYPE, F("\n"), id, position); +void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position, bool moving) { + broadcastReply(COMMAND_TYPE, F("\n"), id, position, moving); } void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { diff --git a/CommandDistributor.h b/CommandDistributor.h index b1af10a..a51d58a 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -49,7 +49,7 @@ public : static void broadcastLoco(byte slot); static void broadcastSensor(int16_t id, bool value); static void broadcastTurnout(int16_t id, bool isClosed); - static void broadcastTurntable(int16_t id, uint8_t position); + static void broadcastTurntable(int16_t id, uint8_t position, bool moving); static void broadcastClockTime(int16_t time, int8_t rate); static void setClockTime(int16_t time, int8_t rate, byte opt); static int16_t retClockTime(); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 24a7914..2b0e06f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1226,3 +1226,8 @@ void DCCEXParser::callback_Wloco(int16_t result) StringFormatter::send(getAsyncReplyStream(), F("\n"), result); commitAsyncReplyStream(); } + +void DCCEXParser::callback_Imoving(bool moving) { + if (!moving) StringFormatter::send(getAsyncReplyStream(), F("")); + commitAsyncReplyStream(); +} diff --git a/DCCEXParser.h b/DCCEXParser.h index 8a7367a..7a7ef89 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -72,6 +72,7 @@ struct DCCEXParser static void callback_Wloco(int16_t result); static void callback_Vbit(int16_t result); static void callback_Vbyte(int16_t result); + static void callback_Imoving(bool moving); static FILTER_CALLBACK filterCallback; static FILTER_CALLBACK filterRMFTCallback; static AT_COMMAND_CALLBACK atCommandCallback; diff --git a/Turntables.cpp b/Turntables.cpp index a7d42ab..a0419b1 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -95,10 +95,10 @@ uint8_t Turntable::getPositionCount() { /* * Public static functions */ -bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position) { +bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); if (!tto) return false; - CommandDistributor::broadcastTurntable(id, position); + CommandDistributor::broadcastTurntable(id, position, moving); #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif @@ -116,7 +116,11 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - tto->setPositionStateOnly(id, position); + if (tto->getType() == TURNTABLE_EXTT) { + tto->setPositionStateOnly(id, position, 1); + } else { + tto->setPositionStateOnly(id, position, 0); + } tto->_turntableData.position = position; } } diff --git a/Turntables.h b/Turntables.h index 36f5b90..d59bc80 100644 --- a/Turntables.h +++ b/Turntables.h @@ -36,6 +36,9 @@ enum { TURNTABLE_DCC = 1, }; +// Callback needs to return a bool: 1 = moving, 0 = stopped +typedef void (*EXTT_CALLBACK)(bool moving); + /************************************************************************************* * Turntable positions. * @@ -167,7 +170,7 @@ public: */ inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); - static bool setPositionStateOnly(uint16_t id, uint8_t position); + static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From fb8cca8d3507e5722ae7eed6b84c9a2ac4cfcdb2 Mon Sep 17 00:00:00 2001 From: FranziHH <45534937+FranziHH@users.noreply.github.com> Date: Wed, 30 Aug 2023 21:02:37 +0200 Subject: [PATCH 035/310] FastClock BUG serial is working I2C is wrong First, the initialization was incorrect. The FastClock was initialized before the I2C Manager was initialized Second: FastClock Functions are missing --- I2CManager.cpp | 6 +++++- IODevice.cpp | 12 +++++++++++- IO_EXFastclock.h | 4 ++-- 3 files changed, 18 insertions(+), 4 deletions(-) diff --git a/I2CManager.cpp b/I2CManager.cpp index d0d8550..a68d08d 100644 --- a/I2CManager.cpp +++ b/I2CManager.cpp @@ -48,6 +48,10 @@ static const FSH * guessI2CDeviceType(uint8_t address) { if (address >= 0x20 && address <= 0x26) return F("GPIO Expander"); +#ifdef FAST_CLOCK_I2C + else if (address == FAST_CLOCK_I2C) + return F("Fast Clock"); +#endif else if (address == 0x27) return F("GPIO Expander or LCD Display"); else if (address == 0x29) @@ -363,4 +367,4 @@ void I2CAddress::toHex(const uint8_t value, char *buffer) { /* static */ bool I2CAddress::_addressWarningDone = false; -#endif \ No newline at end of file +#endif diff --git a/IODevice.cpp b/IODevice.cpp index 2ed21b6..1155c85 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -27,6 +27,12 @@ #include "IO_MCP23017.h" #include "DCCTimer.h" +#if !defined(IO_NO_HAL) + #ifdef FAST_CLOCK_I2C + #include "IO_EXFastClock.h" // FastClock driver + #endif +#endif + #if defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_MEGAAVR) #define USE_FAST_IO #endif @@ -75,6 +81,11 @@ void IODevice::begin() { } else { DIAG(F("Default PCA9685 at I2C 0x41 disabled due to configured user device")); } + + #ifdef FAST_CLOCK_I2C + EXFastClock::create(FAST_CLOCK_I2C); + DIAG(F("EXFastClock::create")); + #endif // Predefine two MCP23017 module 0x20/0x21 if no conflicts // Allocates 32 pins 164-195 @@ -582,4 +593,3 @@ bool ArduinoPins::fastReadDigital(uint8_t pin) { #endif return result; } - diff --git a/IO_EXFastclock.h b/IO_EXFastclock.h index 5ed237e..06d546f 100644 --- a/IO_EXFastclock.h +++ b/IO_EXFastclock.h @@ -56,12 +56,12 @@ static void create(I2CAddress i2cAddress) { // XXXX change thistosave2 bytes if (_checkforclock == 0) { FAST_CLOCK_EXISTS = true; - //DIAG(F("I2C Fast Clock found at %s"), i2cAddress.toString()); + DIAG(F("I2C Fast Clock found at %s"), i2cAddress.toString()); new EXFastClock(i2cAddress); } else { FAST_CLOCK_EXISTS = false; - //DIAG(F("No Fast Clock found")); + DIAG(F("No Fast Clock found")); LCD(6,F("CLOCK NOT FOUND")); } From 01919b33df5b7a2854e3cbae8508de8e23ef8ef9 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 30 Aug 2023 23:55:39 +0200 Subject: [PATCH 036/310] Make parser more fool proof --- DCCEXParser.cpp | 28 ++++++++++++++++++---------- 1 file changed, 18 insertions(+), 10 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 49d2d20..53cb5ce 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -451,12 +451,16 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) #ifndef DISABLE_PROG case 'w': // WRITE CV on MAIN - DCC::writeCVByteMain(p[0], p[1], p[2]); - return; + if (params != 3) + break; + DCC::writeCVByteMain(p[0], p[1], p[2]); + return; case 'b': // WRITE CV BIT ON MAIN - DCC::writeCVBitMain(p[0], p[1], p[2], p[3]); - return; + if (params != 4) + break; + DCC::writeCVBitMain(p[0], p[1], p[2], p[3]); + return; #endif case 'M': // WRITE TRANSPARENT DCC PACKET MAIN @@ -479,14 +483,16 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) #ifndef DISABLE_PROG case 'W': // WRITE CV ON PROG - if (!stashCallback(stream, p, ringStream)) - break; + if (!stashCallback(stream, p, ringStream)) + break; if (params == 1) // Write new loco id (clearing consist and managing short/long) DCC::setLocoId(p[0],callback_Wloco); else if (params == 4) // WRITE CV ON PROG DCC::writeCVByte(p[0], p[1], callback_W4); - else // WRITE CV ON PROG + else if (params == 2) // WRITE CV ON PROG DCC::writeCVByte(p[0], p[1], callback_W); + else + break; return; case 'V': // VERIFY CV ON PROG @@ -506,9 +512,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } break; - case 'B': // WRITE CV BIT ON PROG + case 'B': // WRITE CV BIT ON PROG or + if (params != 3 && params != 5) + break; if (!stashCallback(stream, p, ringStream)) - break; + break; DCC::writeCVBit(p[0], p[1], p[2], callback_B); return; @@ -642,7 +650,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case 'D': // < > if (parseD(stream, params, p)) return; - return; + break; #endif case '=': // <= Track manager control > if (TrackManager::parseJ(stream, params, p)) From 44d8154223f9dbc57a3fab24f6fa9309d4c84c9d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 30 Aug 2023 23:57:49 +0200 Subject: [PATCH 037/310] version number update --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 8ae1d2b..98afa03 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308251713Z" +#define GITHUB_SHA "devel-202308302157Z" diff --git a/version.h b/version.h index 4bcf6b5..d03eab8 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.2" +#define VERSION "5.1.3" +// 5.1.3 - Make parser more fool proof // 5.1.2 - Bugfix: ESP32 30ms off time // 5.1.1 - Check bad AT firmware version // - Update IO_PCA9555.h reflecting IO_MCP23017.h changes to support PCA9548 mux From 9fa213e198f66c877a8fdc6db7bb03ee9ea3e1e4 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 31 Aug 2023 13:51:25 +1000 Subject: [PATCH 038/310] Undo callback --- DCCEXParser.cpp | 5 ----- DCCEXParser.h | 1 - 2 files changed, 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2b0e06f..24a7914 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1226,8 +1226,3 @@ void DCCEXParser::callback_Wloco(int16_t result) StringFormatter::send(getAsyncReplyStream(), F("\n"), result); commitAsyncReplyStream(); } - -void DCCEXParser::callback_Imoving(bool moving) { - if (!moving) StringFormatter::send(getAsyncReplyStream(), F("")); - commitAsyncReplyStream(); -} diff --git a/DCCEXParser.h b/DCCEXParser.h index 7a7ef89..8a7367a 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -72,7 +72,6 @@ struct DCCEXParser static void callback_Wloco(int16_t result); static void callback_Vbit(int16_t result); static void callback_Vbyte(int16_t result); - static void callback_Imoving(bool moving); static FILTER_CALLBACK filterCallback; static FILTER_CALLBACK filterRMFTCallback; static AT_COMMAND_CALLBACK atCommandCallback; From b8d1c682ea333a10a58abbcfe51014275f2d4b18 Mon Sep 17 00:00:00 2001 From: FranziHH <45534937+FranziHH@users.noreply.github.com> Date: Thu, 31 Aug 2023 10:08:23 +0200 Subject: [PATCH 039/310] FastClock is working for Me Fast Clock can be easily activated without complicated adjustments in config.h: Serial: simply comment out the required port: e.g. #define SERIAL1_COMMANDS OR for I2C //#define FAST_CLOCK_I2C 0x55 and define the address --- IO_EXFastclock.h | 5 +++-- config.example.h | 11 ++++++++++- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/IO_EXFastclock.h b/IO_EXFastclock.h index 06d546f..54d4cf1 100644 --- a/IO_EXFastclock.h +++ b/IO_EXFastclock.h @@ -95,7 +95,8 @@ void _loop(unsigned long currentMicros) override{ if (FAST_CLOCK_EXISTS==true) { uint8_t readBuffer[3]; byte a,b; - #ifdef EXRAIL_ACTIVE + // I would like to use the FastClock without EXRAIL + // #ifdef EXRAIL_ACTIVE I2CManager.read(_I2CAddress, readBuffer, 3); // XXXX change this to save a few bytes a = readBuffer[0]; @@ -110,7 +111,7 @@ void _loop(unsigned long currentMicros) override{ // Clock interval is 60/ clockspeed i.e 60/b seconds delayUntil(currentMicros + ((60/b) * 1000000)); - #endif + // #endif } } diff --git a/config.example.h b/config.example.h index 0f136f9..505d2b7 100644 --- a/config.example.h +++ b/config.example.h @@ -239,7 +239,10 @@ The configuration file for DCC-EX Command Station // SAMD/SAMC and STM32 have up to 6.) // To monitor a throttle on one or more serial ports, uncomment the defines below. // NOTE: do not define here the WiFi shield serial port or your wifi will not work. -// +// ------------------------------------- +// For Use with FastClock serial: uncomment the needed serial Port and +// FastClock will work, no further actions are needed +// ------------------------------------- //#define SERIAL1_COMMANDS //#define SERIAL2_COMMANDS //#define SERIAL3_COMMANDS @@ -247,6 +250,12 @@ The configuration file for DCC-EX Command Station //#define SERIAL5_COMMANDS //#define SERIAL6_COMMANDS // +// ------------------------------------- +// FastClock with I2C +// uncomment the following Line and Set the used I2C Address +//#define FAST_CLOCK_I2C 0x55 // default is 0x55 +// ------------------------------------- +// // BLUETOOTH SERIAL ON ESP32 // On ESP32 you have the possibility to use the builtin BT serial to connect to // the CS. From f40d57d8bde35ef7b075a602e65ec213a7058b2f Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 08:44:32 +1000 Subject: [PATCH 040/310] Add DCC type, EXTT broadcast from driver --- DCCEXParser.cpp | 55 ++++++++++++++-------------- IODevice.cpp | 7 ++++ IODevice.h | 5 +++ IO_EXTurntable.cpp | 16 +++++++++ Turntables.cpp | 90 +++++++++++++++++++++++++++++++++++++--------- Turntables.h | 29 ++++++++++++--- 6 files changed, 152 insertions(+), 50 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 24a7914..7473c26 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -708,7 +708,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) StringFormatter::send(stream, F(" %d X"), id); } else { uint8_t pos = tto->getPosition(); - uint8_t type = tto->getType(); + uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE @@ -1075,22 +1075,29 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) return Turntable::printAll(stream); case 1: // broadcast type and current position - return false; + { + Turntable *tto = Turntable::get(p[0]); + if (tto) { + bool type = tto->isEXTT(); + uint8_t position = tto->getPosition(); + StringFormatter::send(stream, F("\n"), type, position); + } else { + return false; + } + } + return true; case 2: // - rotate to position for DCC turntables { + Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable - DIAG(F("Create DCC turntable %d"), p[0]); - } else { // Otherwise move a DCC turntable + if (tto) return false; + if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); + tto->addPosition(0); + } else { // Otherwise move a DCC turntable if (tto) { - if (tto->getPosition() == p[1]) return true; - uint16_t value = tto->getPositionValue(p[1]); - if (value) { - DIAG(F("Rotate DCC turntable %d to position %d"), p[0], p[1]); - } else { - return false; - } + if (!tto->setPosition(p[0], p[1])) return false; } else { return false; } @@ -1100,34 +1107,24 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 3: { + Turntable *tto = Turntable::get(p[0]); + if (!tto) return false; if (p[1] == HASH_KEYWORD_ADD) { // add position value to turntable - Turntable *tto = Turntable::get(p[0]); - if (tto) { - tto->addPosition(p[2]); - StringFormatter::send(stream, F("\n")); - } else { - return false; - } + tto->addPosition(p[2]); + StringFormatter::send(stream, F("\n")); } else { // rotate to position for EX-Turntable - Turntable *tto = Turntable::get(p[0]); - if (tto) { - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } else { - return false; - } + if (!tto->setPosition(p[0], p[1], p[2])) return false; } } return true; - case 5: // create an EXTT turntable + case 4: // create an EXTT turntable { if (p[1] == HASH_KEYWORD_EXTT) { if (Turntable::get(p[0])) return false; - if (!EXTTTurntable::create(p[0], (VPIN)p[2], (uint8_t)p[3])) return false; + if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(p[4]); - } else if (params > 3 && params < 39 && p[1] == HASH_KEYWORD_DCC) { - DIAG(F("Create DCC turntable %d at base address %d with %d positions"), p[0], p[2], params - 2); + tto->addPosition(p[3]); } else { return false; } diff --git a/IODevice.cpp b/IODevice.cpp index 2ed21b6..e811fff 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -176,6 +176,13 @@ bool IODevice::exists(VPIN vpin) { return findDevice(vpin) != NULL; } +// Return the status of the device att vpin. +uint8_t IODevice::getStatus(VPIN vpin) { + IODevice *dev = findDevice(vpin); + if (!dev) return false; + return dev->_deviceState; +} + // check whether the pin supports notification. If so, then regular _read calls are not required. bool IODevice::hasCallback(VPIN vpin) { IODevice *dev = findDevice(vpin); diff --git a/IODevice.h b/IODevice.h index d2c80a4..a03a64d 100644 --- a/IODevice.h +++ b/IODevice.h @@ -154,6 +154,9 @@ public: // exists checks whether there is a device owning the specified vpin static bool exists(VPIN vpin); + // getStatus returns the state of the device at the specified vpin + static uint8_t getStatus(VPIN vpin); + // Enable shared interrupt on specified pin for GPIO extender modules. The extender module // should pull down this pin when requesting a scan. The pin may be shared by multiple modules. // Without the shared interrupt, input states are scanned periodically to detect changes on @@ -405,9 +408,11 @@ private: void _begin() override; void _loop(unsigned long currentMicros) override; int _read(VPIN vpin) override; + void _broadcastStatus (VPIN vpin, uint8_t status); void _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override; void _display() override; uint8_t _stepperStatus; + uint8_t _previousStatus; }; ///////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 8c7057b..fc1f9c1 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -34,6 +34,8 @@ #include "IODevice.h" #include "I2CManager.h" #include "DIAG.h" +#include "Turntables.h" +#include "CommandDistributor.h" void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { new EXTurntable(firstVpin, nPins, I2CAddress); @@ -44,6 +46,8 @@ EXTurntable::EXTurntable(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { _firstVpin = firstVpin; _nPins = nPins; _I2CAddress = I2CAddress; + _stepperStatus = 0; + _previousStatus = 0; addDevice(this); } @@ -80,10 +84,22 @@ int EXTurntable::_read(VPIN vpin) { if (_stepperStatus > 1) { return false; } else { + if (_stepperStatus != _previousStatus) { + _broadcastStatus(vpin, _stepperStatus); + _previousStatus = _stepperStatus; + } return _stepperStatus; } } +// If a status change has occurred for a turntable object, broadcast it +void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { + Turntable *tto = Turntable::getByVpin(vpin); + if (tto) { + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + } +} + // writeAnalogue to send the steps and activity to Turntable-EX. // Sends 3 bytes containing the MSB and LSB of the step count, and activity. // value contains the steps, bit shifted to MSB + LSB. diff --git a/Turntables.cpp b/Turntables.cpp index a0419b1..3e33d2b 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -57,13 +57,6 @@ void Turntable::add(Turntable *tto) { turntablelistHash++; } -// Find turntable from list -Turntable *Turntable::get(uint16_t id) { - for (Turntable *tto = _firstTurntable; tto != NULL; tto = tto->_nextTurntable) - if (tto->_turntableData.id == id) return tto; - return NULL; -} - // Add a position void Turntable::addPosition(uint16_t value) { _turntablePositions.insert(value); @@ -95,16 +88,39 @@ uint8_t Turntable::getPositionCount() { /* * Public static functions */ +// Find turntable from list +Turntable *Turntable::get(uint16_t id) { + for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable) + if (tto->_turntableData.id == id) return tto; + return NULL; +} + +// Find turntable via Vpin +Turntable *Turntable::getByVpin(VPIN vpin) { + for (Turntable *tto = _firstTurntable; tto != nullptr; tto = tto->_nextTurntable) { + if (tto->isEXTT()) { + EXTTTurntable *exttTto = static_cast(tto); + if (exttTto->getVpin() == vpin) { + return tto; + } + } + } + return nullptr; +} + +// Broadcast position changes bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); if (!tto) return false; - CommandDistributor::broadcastTurntable(id, position, moving); + // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT + if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } #if defined(EXRAIL_ACTIVE) // RMFT2::turntableEvent(id, position); #endif return true; } +// Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) DIAG(F("Turntable(%d, %d)"), id, position); @@ -116,12 +132,12 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - if (tto->getType() == TURNTABLE_EXTT) { + tto->_turntableData.position = position; + if (tto->isEXTT()) { tto->setPositionStateOnly(id, position, 1); } else { tto->setPositionStateOnly(id, position, 0); } - tto->_turntableData.position = position; } } return ok; @@ -132,38 +148,39 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { * *************************************************************************************/ // Private constructor -EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : +EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin) : Turntable(id, TURNTABLE_EXTT) { _exttTurntableData.vpin = vpin; - _exttTurntableData.i2caddress = i2caddress; } +using DevState = IODevice::DeviceStateEnum; + // Create function - Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin, uint8_t i2caddress) { + Turntable *EXTTTurntable::create(uint16_t id, VPIN vpin) { #ifndef IO_NO_HAL Turntable *tto = get(id); if (tto) { if (tto->isType(TURNTABLE_EXTT)) { EXTTTurntable *extt = (EXTTTurntable *)tto; extt->_exttTurntableData.vpin = vpin; - extt->_exttTurntableData.i2caddress = i2caddress; return tto; } } - tto = (Turntable *)new EXTTTurntable(id, vpin, i2caddress); + if (!IODevice::exists(vpin)) return nullptr; + if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; + tto = (Turntable *)new EXTTTurntable(id, vpin); DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; #else (void)id; - (void)i2caddress; (void)vpin; return NULL; #endif } void EXTTTurntable::print(Print *stream) { - StringFormatter::send(stream, F("\n"), _turntableData.id, _exttTurntableData.vpin, _exttTurntableData.i2caddress); + StringFormatter::send(stream, F("\n"), _turntableData.id, _exttTurntableData.vpin); } // EX-Turntable specific code for moving to the specified position @@ -185,4 +202,43 @@ EXTTTurntable::EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress) : return true; } +/************************************************************************************* + * DCCTurntable - DCC Turntable device. + * + *************************************************************************************/ +// Private constructor +DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} + +// Create function + Turntable *DCCTurntable::create(uint16_t id) { +#ifndef IO_NO_HAL + Turntable *tto = get(id); + if (!tto) { + tto = (Turntable *)new DCCTurntable(id); + DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); + } + return tto; +#else + (void)id; + return NULL; +#endif + } + + void DCCTurntable::print(Print *stream) { + StringFormatter::send(stream, F("\n"), _turntableData.id); + } + + // EX-Turntable specific code for moving to the specified position + bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) { +#ifndef IO_NO_HAL + int16_t value = getPositionValue(position); + if (position == 0 || !value) return false; // Return false if it's not a valid position + // Set position via device driver + // DCC activate function here +#else + (void)position; +#endif + return true; + } + #endif diff --git a/Turntables.h b/Turntables.h index d59bc80..e318724 100644 --- a/Turntables.h +++ b/Turntables.h @@ -135,6 +135,7 @@ protected: public: static Turntable *get(uint16_t id); + static Turntable *getByVpin(VPIN vpin); /* * Static data @@ -148,7 +149,7 @@ public: inline bool isHidden() { return _turntableData.hidden; } inline void setHidden(bool h) {_turntableData.hidden=h; } inline bool isType(uint8_t type) { return _turntableData.turntableType == type; } - inline uint8_t getType() { return _turntableData.turntableType; } + inline bool isEXTT() const { return _turntableData.turntableType == TURNTABLE_EXTT; } inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); @@ -193,16 +194,16 @@ private: // EXTTTurntableData contains device specific data struct EXTTTurntableData { VPIN vpin; - uint8_t i2caddress; } _exttTurntableData; // Constructor - EXTTTurntable(uint16_t id, VPIN vpin, uint8_t i2caddress); + EXTTTurntable(uint16_t id, VPIN vpin); public: // Create function - static Turntable *create(uint16_t id, VPIN vpin, uint8_t i2caddress); + static Turntable *create(uint16_t id, VPIN vpin); void print(Print *stream) override; + VPIN getVpin() const { return _exttTurntableData.vpin; } protected: // EX-Turntable specific code for setting position @@ -210,6 +211,26 @@ protected: }; +/************************************************************************************* + * DCCTurntable - DCC accessory Turntable device. + * + *************************************************************************************/ +class DCCTurntable : public Turntable { +private: + // Constructor + DCCTurntable(uint16_t id); + +public: + // Create function + static Turntable *create(uint16_t id); + void print(Print *stream) override; + +protected: + // DCC specific code for setting position + bool setPositionInternal(uint8_t position, uint8_t activity=0) override; + +}; + #endif #endif From df2f09f4d2efaaf61722d1f98072e1ee13330898 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 09:04:48 +1000 Subject: [PATCH 041/310] Fix build errors --- IODevice.h | 2 ++ IO_EXTurntable.cpp | 3 +-- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/IODevice.h b/IODevice.h index a03a64d..4803f56 100644 --- a/IODevice.h +++ b/IODevice.h @@ -380,6 +380,7 @@ private: uint8_t *_pinInUse; }; +#ifndef IO_NO_HAL ///////////////////////////////////////////////////////////////////////////////////////////////////// /* * IODevice subclass for EX-Turntable. @@ -414,6 +415,7 @@ private: uint8_t _stepperStatus; uint8_t _previousStatus; }; +#endif ///////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index fc1f9c1..8741c0c 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -28,8 +28,7 @@ * Refer to the documentation for further information including the valid activities. */ -#ifndef IO_EXTurntable_h -#define IO_EXTurntable_h +#ifndef IO_NO_HAL #include "IODevice.h" #include "I2CManager.h" From 798241927f1909e0fb30272f1d4170d842d7fb22 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Fri, 1 Sep 2023 13:28:24 +1000 Subject: [PATCH 042/310] Really fix build errors --- IO_EXTurntable.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 8741c0c..bf06e62 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -28,14 +28,14 @@ * Refer to the documentation for further information including the valid activities. */ -#ifndef IO_NO_HAL - #include "IODevice.h" #include "I2CManager.h" #include "DIAG.h" #include "Turntables.h" #include "CommandDistributor.h" +#ifndef IO_NO_HAL + void EXTurntable::create(VPIN firstVpin, int nPins, I2CAddress I2CAddress) { new EXTurntable(firstVpin, nPins, I2CAddress); } From bcb250bacfc8b2e7a60810dd5b20d0f1da737863 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Fri, 1 Sep 2023 18:30:02 +1000 Subject: [PATCH 043/310] Broadcasts working --- IO_EXTurntable.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index bf06e62..59a65d9 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -71,6 +71,12 @@ void EXTurntable::_loop(unsigned long currentMicros) { uint8_t readBuffer[1]; I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; + if (_stepperStatus < 2) { + if (_stepperStatus != _previousStatus) { + _broadcastStatus(_firstVpin, _stepperStatus); + _previousStatus = _stepperStatus; + } + } // DIAG(F("Turntable-EX returned status: %d"), _stepperStatus); delayUntil(currentMicros + 500000); // Wait 500ms before checking again, turntables turn slowly } @@ -83,10 +89,6 @@ int EXTurntable::_read(VPIN vpin) { if (_stepperStatus > 1) { return false; } else { - if (_stepperStatus != _previousStatus) { - _broadcastStatus(vpin, _stepperStatus); - _previousStatus = _stepperStatus; - } return _stepperStatus; } } From 4bdc4b7079dfd69ccec11292b1f15fe6f4d5d713 Mon Sep 17 00:00:00 2001 From: FranziHH <45534937+FranziHH@users.noreply.github.com> Date: Fri, 1 Sep 2023 13:56:02 +0200 Subject: [PATCH 044/310] Update IODevice.cpp Debug Output adjusted --- IODevice.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/IODevice.cpp b/IODevice.cpp index 1155c85..adefbf6 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -83,8 +83,8 @@ void IODevice::begin() { } #ifdef FAST_CLOCK_I2C - EXFastClock::create(FAST_CLOCK_I2C); DIAG(F("EXFastClock::create")); + EXFastClock::create(FAST_CLOCK_I2C); #endif // Predefine two MCP23017 module 0x20/0x21 if no conflicts From e734661d1b83eb0f3d79d5116e5e9404f07e4b36 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 2 Sep 2023 08:29:49 +1000 Subject: [PATCH 045/310] EXRAIL ready for testing --- EXRAIL2.cpp | 53 +++++++++++++++++++++++++++++++++++++++++++++ EXRAIL2.h | 8 +++++++ EXRAIL2MacroReset.h | 28 +++++++++++++++++------- EXRAILMacros.h | 32 ++++++++++++++++++++++++++- Turntables.cpp | 12 +++++++++- Turntables.h | 1 + 6 files changed, 124 insertions(+), 10 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 0e17ea9..c01189c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -52,6 +52,7 @@ #include "Turnouts.h" #include "CommandDistributor.h" #include "TrackManager.h" +#include "Turntables.h" // Command parsing keywords const int16_t HASH_KEYWORD_EXRAIL=15435; @@ -94,6 +95,7 @@ LookList * RMFT2::onAmberLookup=NULL; LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onClockLookup=NULL; +LookList * RMFT2::onRotateLookup=NULL; #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -175,6 +177,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); + onRotateLookup=LookListLoader(OPCODE_ONROTATE); // Second pass startup, define any turnouts or servos, set signals red @@ -238,6 +241,32 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { setTurnoutHiddenState(VpinTurnout::create(id,pin)); break; } + + case OPCODE_DCCTURNTABLE: { + VPIN id=operand; + setTurntableHiddenState(DCCTurntable::create(id)); + Turntable *tto=Turntable::get(id); + tto->addPosition(0); + break; + } + + case OPCODE_EXTTTURNTABLE: { + VPIN id=operand; + VPIN pin=getOperand(progCounter,1); + int home=getOperand(progCounter,2); + setTurntableHiddenState(EXTTTurntable::create(id,pin)); + Turntable *tto=Turntable::get(id); + tto->addPosition(home); + break; + } + + case OPCODE_TTADDPOSITION: { + VPIN id=operand; + int value=getOperand(progCounter,1); + Turntable *tto=Turntable::get(id); + tto->addPosition(value); + break; + } case OPCODE_AUTOSTART: // automatically create a task from here at startup. @@ -263,6 +292,10 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) { t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); } +void RMFT2::setTurntableHiddenState(Turntable * tto) { + tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); +} + char RMFT2::getRouteType(int16_t id) { for (int16_t i=0;;i+=2) { int16_t rid= GETHIGHFLASHW(routeIdList,i); @@ -598,6 +631,13 @@ void RMFT2::loop2() { case OPCODE_CLOSE: Turnout::setClosed(operand, true); break; + + case OPCODE_ROTATE: + uint8_t activity; + activity=getOperand(2); + if (!activity) activity=0; + Turntable::setPosition(operand,getOperand(1),activity); + break; case OPCODE_REV: forward = false; @@ -788,6 +828,10 @@ void RMFT2::loop2() { case OPCODE_IFCLOSED: skipIf=Turnout::isThrown(operand); break; + + case OPCODE_IFTTPOSITION: // do block if turntable at this position + skipIf=Turntable::getPosition(operand)!=(int)getOperand(1); + break; case OPCODE_ENDIF: break; @@ -986,6 +1030,10 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: + case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime + case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime + case OPCODE_TTADDPOSITION: // Turntable position definition ignored at runtime + case OPCODE_ONROTATE: break; @@ -1130,6 +1178,11 @@ void RMFT2::changeEvent(int16_t vpin, bool change) { if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); } +void RMFT2::rotateEvent(int16_t turntableId, bool change) { + // Hunt or an ONROTATE for this turntable + if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId); +} + void RMFT2::clockEvent(int16_t clocktime, bool change) { // Hunt for an ONTIME for this time if (Diag::CMD) diff --git a/EXRAIL2.h b/EXRAIL2.h index 4d106e6..96bc7db 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -25,6 +25,7 @@ #include "FSH.h" #include "IODevice.h" #include "Turnouts.h" +#include "Turntables.h" // The following are the operation codes (or instructions) for a kind of virtual machine. // Each instruction is normally 3 bytes long with an operation code followed by a parameter. @@ -62,6 +63,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, + OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, + OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -130,6 +133,7 @@ class LookList { static void activateEvent(int16_t addr, bool active); static void changeEvent(int16_t id, bool change); static void clockEvent(int16_t clocktime, bool change); + static void rotateEvent(int16_t id, bool change); static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; @@ -144,6 +148,8 @@ class LookList { static const FSH * getTurnoutDescription(int16_t id); static const FSH * getRosterName(int16_t id); static const FSH * getRosterFunctions(int16_t id); + static const FSH * getTurntableDescription(int16_t id); + // static const FSH * getTurntablePositionDescription(int16_t id, uint8_t position); private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); @@ -156,6 +162,7 @@ private: static bool isSignal(int16_t id,char rag); static int16_t getSignalSlot(int16_t id); static void setTurnoutHiddenState(Turnout * t); + static void setTurntableHiddenState(Turntable * tto); static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); @@ -188,6 +195,7 @@ private: static LookList * onGreenLookup; static LookList * onChangeLookup; static LookList * onClockLookup; + static LookList * onRotateLookup; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 588a417..7c690b7 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -40,6 +40,7 @@ #undef CALL #undef CLOSE #undef DCC_SIGNAL +#undef DCC_TURNTABLE #undef DEACTIVATE #undef DEACTIVATEL #undef DELAY @@ -51,8 +52,9 @@ #undef ENDEXRAIL #undef ENDIF #undef ENDTASK -#undef ESTOP -#undef EXRAIL +#undef ESTOP +#undef EXRAIL +#undef EXTT_TURNTABLE #undef FADE #undef FOFF #undef FOLLOW @@ -75,6 +77,7 @@ #undef IFRESERVE #undef IFTHROWN #undef IFTIMEOUT +#undef IFTTPOSITION #undef IFRE #undef INVERT_DIRECTION #undef JOIN @@ -95,6 +98,7 @@ #undef ONCLOCKMINS #undef ONGREEN #undef ONRED +#undef ONROTATE #undef ONTHROW #undef ONCHANGE #undef PARSE @@ -113,7 +117,8 @@ #undef RESUME #undef RETURN #undef REV -#undef ROSTER +#undef ROSTER +#undef ROTATE #undef ROUTE #undef SENDLOCO #undef SEQUENCE @@ -136,7 +141,8 @@ #undef SPEED #undef START #undef STOP -#undef THROW +#undef THROW +#undef TT_ADDPOSITION #undef TURNOUT #undef TURNOUTL #undef UNJOIN @@ -165,6 +171,7 @@ #define CALL(route) #define CLOSE(id) #define DCC_SIGNAL(id,add,subaddr) +#define DCC_TURNTABLE(id,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) #define DELAY(mindelay) @@ -177,7 +184,8 @@ #define ENDIF #define ENDTASK #define ESTOP -#define EXRAIL +#define EXRAIL +#define EXTT_TURNTABLE(id,vpin,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) @@ -200,6 +208,7 @@ #define IFTHROWN(turnout_id) #define IFRESERVE(block) #define IFTIMEOUT +#define IFTTPOSITION(turntable_id,position) #define IFRE(sensor_id,value) #define INVERT_DIRECTION #define JOIN @@ -219,7 +228,8 @@ #define ONDEACTIVATEL(linear) #define ONCLOSE(turnout_id) #define ONGREEN(signal_id) -#define ONRED(signal_id) +#define ONRED(signal_id) +#define ONROTATE(turntable_id) #define ONTHROW(turnout_id) #define ONCHANGE(sensor_id) #define PAUSE @@ -238,8 +248,9 @@ #define RESUME #define RETURN #define REV(speed) -#define ROUTE(id,description) +#define ROTATE(turntable_id,position,activity) #define ROSTER(cab,name,funcmap...) +#define ROUTE(id,description) #define SENDLOCO(cab,route) #define SEQUENCE(id) #define SERIAL(msg) @@ -261,7 +272,8 @@ #define SPEED(speed) #define START(route) #define STOP -#define THROW(id) +#define THROW(id) +#define TT_ADDPOSITION(turntable_id,value,description) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 66b0111..fc8dbca 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -187,6 +187,30 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { return NULL; } +// Pass to get turntable descriptions (optional) +#include "EXRAIL2MacroReset.h" +#undef DCC_TURNTABLE +#define DCC_TURNTABLE(id,description...) O_DESC(id,description) +#undef EXTT_TURNTABLE +#define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) + +const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { + switch (turntableId) { + #include "myAutomation.h" + default:break; + } + return NULL; +} + +// Pass to get turntable position descriptions (optional) +// #include "EXRAIL2MacroReset.h" +// #undef TT_ADDPOSITION +// #define TT_ADDPOSITION(turntable_id,value,description...) 0_DESC(id,description) + +// const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { + +// } + // Pass 6: Roster IDs (count) #include "EXRAIL2MacroReset.h" #undef ROSTER @@ -268,6 +292,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), +#define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), #define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)), @@ -281,7 +306,8 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ENDIF OPCODE_ENDIF,0,0, #define ENDTASK OPCODE_ENDTASK,0,0, #define ESTOP OPCODE_SPEED,V(1), -#define EXRAIL +#define EXRAIL +#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), #define FOLLOW(route) OPCODE_FOLLOW,V(route), @@ -304,6 +330,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define IFRESERVE(block) OPCODE_IFRESERVE,V(block), #define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id), #define IFTIMEOUT OPCODE_IFTIMEOUT,0,0, +#define IFTTPOSITION(id,position) OPCODE_IFTTPOSITION,V(id),OPCODE_PAD,V(position), #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define JOIN OPCODE_JOIN,0,0, @@ -324,6 +351,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONRED(signal_id) OPCODE_ONRED,V(signal_id), +#define ONROTATE(id) OPCODE_ONROTATE,V(id), #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, @@ -343,6 +371,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define RETURN OPCODE_RETURN,0,0, #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) +#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), @@ -366,6 +395,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), +#define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) #define UNJOIN OPCODE_UNJOIN,0,0, diff --git a/Turntables.cpp b/Turntables.cpp index 3e33d2b..dcf50a0 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -108,6 +108,13 @@ Turntable *Turntable::getByVpin(VPIN vpin) { return nullptr; } +// Get the current position for turntable with the specified ID +uint8_t Turntable::getPosition(uint16_t id) { + Turntable *tto = get(id); + if (!tto) return false; + return tto->getPosition(); +} + // Broadcast position changes bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { Turntable *tto = get(id); @@ -234,7 +241,10 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} int16_t value = getPositionValue(position); if (position == 0 || !value) return false; // Return false if it's not a valid position // Set position via device driver - // DCC activate function here + int16_t addr=value>>3; + int16_t subaddr=(value>>1) & 0x03; + bool active=value & 0x01; + DCC::setAccessory(addr, subaddr, active); #else (void)position; #endif diff --git a/Turntables.h b/Turntables.h index e318724..b95c9c0 100644 --- a/Turntables.h +++ b/Turntables.h @@ -172,6 +172,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); + static uint8_t getPosition(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From 004d10ee586a5efb5eb6ae7c2704b75e4fe8b100 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 2 Sep 2023 18:45:59 +1000 Subject: [PATCH 046/310] Fix build errors --- EXRAIL2.cpp | 14 +++++++++++--- EXRAIL2.h | 2 ++ EXRAILMacros.h | 12 ++++++++++++ 3 files changed, 25 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index c01189c..77a9f88 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -242,6 +242,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { break; } +#ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: { VPIN id=operand; setTurntableHiddenState(DCCTurntable::create(id)); @@ -267,7 +268,8 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { tto->addPosition(value); break; } - +#endif + case OPCODE_AUTOSTART: // automatically create a task from here at startup. // Removed if (progCounter>0) check 4.2.31 because @@ -292,9 +294,11 @@ void RMFT2::setTurnoutHiddenState(Turnout * t) { t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); } +#ifndef IO_NO_HAL void RMFT2::setTurntableHiddenState(Turntable * tto) { tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); } +#endif char RMFT2::getRouteType(int16_t id) { for (int16_t i=0;;i+=2) { @@ -631,13 +635,15 @@ void RMFT2::loop2() { case OPCODE_CLOSE: Turnout::setClosed(operand, true); break; - + +#ifndef IO_NO_HAL case OPCODE_ROTATE: uint8_t activity; activity=getOperand(2); if (!activity) activity=0; Turntable::setPosition(operand,getOperand(1),activity); break; +#endif case OPCODE_REV: forward = false; @@ -829,10 +835,12 @@ void RMFT2::loop2() { skipIf=Turnout::isThrown(operand); break; +#ifndef IO_NO_HAL case OPCODE_IFTTPOSITION: // do block if turntable at this position skipIf=Turntable::getPosition(operand)!=(int)getOperand(1); break; - +#endif + case OPCODE_ENDIF: break; diff --git a/EXRAIL2.h b/EXRAIL2.h index 96bc7db..16fff82 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -162,7 +162,9 @@ private: static bool isSignal(int16_t id,char rag); static int16_t getSignalSlot(int16_t id); static void setTurnoutHiddenState(Turnout * t); + #ifndef IO_NO_HAL static void setTurntableHiddenState(Turntable * tto); + #endif static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index fc8dbca..f5d905e 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -292,7 +292,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), +#ifndef IO_NO_HAL #define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), +#endif #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), #define DELAY(ms) ms<30000?OPCODE_DELAYMS:OPCODE_DELAY,V(ms/(ms<30000?1L:100L)), @@ -307,7 +309,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ENDTASK OPCODE_ENDTASK,0,0, #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL +#ifndef IO_NO_HAL #define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), +#endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), #define FOLLOW(route) OPCODE_FOLLOW,V(route), @@ -330,7 +334,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define IFRESERVE(block) OPCODE_IFRESERVE,V(block), #define IFTHROWN(turnout_id) OPCODE_IFTHROWN,V(turnout_id), #define IFTIMEOUT OPCODE_IFTIMEOUT,0,0, +#ifndef IO_NO_HAL #define IFTTPOSITION(id,position) OPCODE_IFTTPOSITION,V(id),OPCODE_PAD,V(position), +#endif #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, #define JOIN OPCODE_JOIN,0,0, @@ -351,7 +357,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONDEACTIVATEL(linear) OPCODE_ONDEACTIVATE,V(linear+3), #define ONGREEN(signal_id) OPCODE_ONGREEN,V(signal_id), #define ONRED(signal_id) OPCODE_ONRED,V(signal_id), +#ifndef IO_NO_HAL #define ONROTATE(id) OPCODE_ONROTATE,V(id), +#endif #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, @@ -371,7 +379,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define RETURN OPCODE_RETURN,0,0, #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) +#ifndef IO_NO_HAL #define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), +#endif #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), @@ -395,7 +405,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), +#ifndef IO_NO_HAL #define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), +#endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) #define UNJOIN OPCODE_UNJOIN,0,0, From 1e48c59cd8d4b0a16370731078e60e8abb949999 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 3 Sep 2023 18:54:56 +1000 Subject: [PATCH 047/310] Capture progress --- IO_EXTurntable.cpp | 12 +++++------- Turntables.cpp | 5 ++++- Turntables.h | 3 +++ 3 files changed, 12 insertions(+), 8 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index 59a65d9..eba8321 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -71,14 +71,11 @@ void EXTurntable::_loop(unsigned long currentMicros) { uint8_t readBuffer[1]; I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; - if (_stepperStatus < 2) { - if (_stepperStatus != _previousStatus) { - _broadcastStatus(_firstVpin, _stepperStatus); - _previousStatus = _stepperStatus; - } + if (_stepperStatus != _previousStatus && _stepperStatus == 0) { // Broadcast when a rotation finishes + _broadcastStatus(_firstVpin, _stepperStatus); + _previousStatus = _stepperStatus; } - // DIAG(F("Turntable-EX returned status: %d"), _stepperStatus); - delayUntil(currentMicros + 500000); // Wait 500ms before checking again, turntables turn slowly + delayUntil(currentMicros + 100000); // Wait 100ms before checking again } // Read returns status as obtained in our loop. @@ -128,6 +125,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } diff --git a/Turntables.cpp b/Turntables.cpp index dcf50a0..f7b2a46 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -122,7 +122,9 @@ bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } #if defined(EXRAIL_ACTIVE) - // RMFT2::turntableEvent(id, position); + bool rotated = false; + if (position != tto->_previousPosition) rotated = true; + if (!tto->isEXTT()) { RMFT2::rotateEvent(id, rotated); } #endif return true; } @@ -138,6 +140,7 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent + tto->_previousPosition = tto->getPosition(); if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { tto->_turntableData.position = position; if (tto->isEXTT()) { diff --git a/Turntables.h b/Turntables.h index b95c9c0..67ab0e3 100644 --- a/Turntables.h +++ b/Turntables.h @@ -105,6 +105,9 @@ protected: // Linked list for positions TurntablePositionList _turntablePositions; + + // Store the previous position to allow checking for changes + uint8_t _previousPosition = 0; /* * Constructor From 7b5e2b41da918e76faeda6a074b37de6b25fde46 Mon Sep 17 00:00:00 2001 From: FranziHH <45534937+FranziHH@users.noreply.github.com> Date: Sun, 3 Sep 2023 16:09:26 +0200 Subject: [PATCH 048/310] new config options For Display Shows IP and Port in same Line: PRINT_IP_PORT_SINGLE_LINE Shows FastClock readable: FASTCLOCK_READABLE --- CommandDistributor.cpp | 15 ++++++++++++++- WifiInterface.cpp | 10 ++++++++-- config.example.h | 8 ++++++++ 3 files changed, 30 insertions(+), 3 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index ab6b52f..52169b5 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -181,7 +181,20 @@ void CommandDistributor::setClockTime(int16_t clocktime, int8_t clockrate, byte case 1: if (clocktime != lastclocktime){ // CAH. DIAG removed because LCD does it anyway. - LCD(6,F("Clk Time:%d Sp %d"), clocktime, clockrate); + + #ifndef FASTCLOCK_READABLE + LCD(6,F("Clk Time: %d Sp %d"), clocktime, clockrate); + #else + // Make Time readable + int hours = clocktime / 60; + int minutes = clocktime - (hours * 60); + int hoursH = hours / 10; + int hoursL = hours - (hoursH * 10); + int minutesH = minutes / 10; + int minutesL = minutes - (minutesH * 10); + LCD(6,F("Clk Time: %d%d:%d%d Sp %d"), hoursH, hoursL, minutesH, minutesL, clockrate); + #endif + // look for an event for this time RMFT2::clockEvent(clocktime,1); // Now tell everyone else what the time is. diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 7511af6..38a65c4 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -347,11 +347,17 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, } ipString[ipLen]=ipChar; } - LCD(4,F("%s"),ipString); // There is not enough room on some LCDs to put a title to this + #ifndef PRINT_IP_PORT_SINGLE_LINE + LCD(4,F("%s"),ipString); // There is not enough room on some LCDs to put a title to this + #else + LCD(4,F("%s:%d"),ipString,port); // *** Single IP:Port + #endif } // suck up anything after the IP. if (!checkForOK(1000, true, false)) return WIFI_DISCONNECTED; - LCD(5,F("PORT=%d"),port); + #ifndef PRINT_IP_PORT_SINGLE_LINE + LCD(5,F("PORT=%d"),port); + #endif return WIFI_CONNECTED; } diff --git a/config.example.h b/config.example.h index 505d2b7..1570139 100644 --- a/config.example.h +++ b/config.example.h @@ -167,6 +167,9 @@ The configuration file for DCC-EX Command Station // * #define SCROLLMODE 2 is by row (move up 1 row at a time). #define SCROLLMODE 1 +// Shows IP and Port on Display in a single line +// #define PRINT_IP_PORT_SINGLE_LINE + ///////////////////////////////////////////////////////////////////////////////////// // DISABLE EEPROM // @@ -256,6 +259,11 @@ The configuration file for DCC-EX Command Station //#define FAST_CLOCK_I2C 0x55 // default is 0x55 // ------------------------------------- // +// ------------------------------------- +// FastClock in HH:MM on Display +//#define FASTCLOCK_READABLE +// ------------------------------------- +// // BLUETOOTH SERIAL ON ESP32 // On ESP32 you have the possibility to use the builtin BT serial to connect to // the CS. From dd890e65bfe2b307ff19c501ac3b87c69f0b8256 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Mon, 4 Sep 2023 07:38:26 +1000 Subject: [PATCH 049/310] Add move check --- IO_EXTurntable.cpp | 1 + Turntables.h | 5 +++++ 2 files changed, 6 insertions(+) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index eba8321..dcbe018 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -95,6 +95,7 @@ void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + tto->setMoving(status); } } diff --git a/Turntables.h b/Turntables.h index 67ab0e3..30cba82 100644 --- a/Turntables.h +++ b/Turntables.h @@ -109,6 +109,9 @@ protected: // Store the previous position to allow checking for changes uint8_t _previousPosition = 0; + // Store the current state of the turntable + bool _isMoving = false; + /* * Constructor */ @@ -159,6 +162,8 @@ public: void addPosition(uint16_t value); uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); + bool isMoving() { return _isMoving; } + void setMoving(bool moving) { _isMoving=moving; } /* * Virtual functions From 86f45675565ab4df0d4beddd0d07e52b06c340b1 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Mon, 4 Sep 2023 18:46:28 +1000 Subject: [PATCH 050/310] Revisiting logic --- DCCEXParser.cpp | 9 +++++---- Turntables.cpp | 3 ++- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 7473c26..2014762 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1087,7 +1087,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 2: // - rotate to position for DCC turntables + case 2: // | - rotate or create DCC turntable { Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable @@ -1096,7 +1096,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) Turntable *tto = Turntable::get(p[0]); tto->addPosition(0); } else { // Otherwise move a DCC turntable - if (tto) { + if (tto && !tto->isEXTT()) { if (!tto->setPosition(p[0], p[1])) return false; } else { return false; @@ -1105,14 +1105,15 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 3: + case 3: // | { Turntable *tto = Turntable::get(p[0]); if (!tto) return false; - if (p[1] == HASH_KEYWORD_ADD) { // add position value to turntable + if (p[1] == HASH_KEYWORD_ADD) { // Add position value to turntable tto->addPosition(p[2]); StringFormatter::send(stream, F("\n")); } else { // rotate to position for EX-Turntable + if (!tto->isEXTT()) return false; if (!tto->setPosition(p[0], p[1], p[2])) return false; } } diff --git a/Turntables.cpp b/Turntables.cpp index f7b2a46..f96a3a8 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -140,8 +140,8 @@ bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { if (ok) { // Broadcast a position change only if non zero has been set, or home/calibration sent - tto->_previousPosition = tto->getPosition(); if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { + tto->_previousPosition = tto->getPosition(); tto->_turntableData.position = position; if (tto->isEXTT()) { tto->setPositionStateOnly(id, position, 1); @@ -179,6 +179,7 @@ using DevState = IODevice::DeviceStateEnum; } if (!IODevice::exists(vpin)) return nullptr; if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; + if (Turntable::getByVpin(vpin)) return nullptr; tto = (Turntable *)new EXTTTurntable(id, vpin); DIAG(F("Turntable 0x%x size %d size %d"), tto, sizeof(Turntable), sizeof(struct TurntableData)); return tto; From 3094c52bf8509d600fa829995d8cf7be263b6365 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 5 Sep 2023 08:38:37 +1000 Subject: [PATCH 051/310] Ready to test --- IO_EXTurntable.cpp | 2 +- Turntables.cpp | 39 +++++++++++++++------------------------ Turntables.h | 1 - 3 files changed, 16 insertions(+), 26 deletions(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index dcbe018..b36237f 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -94,8 +94,8 @@ int EXTurntable::_read(VPIN vpin) { void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { - CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); tto->setMoving(status); + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); } } diff --git a/Turntables.cpp b/Turntables.cpp index f96a3a8..120ac2f 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -115,40 +115,27 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } -// Broadcast position changes -bool Turntable::setPositionStateOnly(uint16_t id, uint8_t position, bool moving) { - Turntable *tto = get(id); - if (!tto) return false; - // Only need to broadcast from here if it's a DCC type, device driver broadcasts EXTT - if (!tto->isEXTT()) { CommandDistributor::broadcastTurntable(id, position, moving); } -#if defined(EXRAIL_ACTIVE) - bool rotated = false; - if (position != tto->_previousPosition) rotated = true; - if (!tto->isEXTT()) { RMFT2::rotateEvent(id, rotated); } -#endif - return true; -} - // Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) - DIAG(F("Turntable(%d, %d)"), id, position); + DIAG(F("Rotate turntable %d to position %d, activity %d)"), id, position, activity); #endif Turntable *tto = Turntable::get(id); if (!tto) return false; + if (tto->isMoving()) return false; bool ok = tto->setPositionInternal(position, activity); if (ok) { - // Broadcast a position change only if non zero has been set, or home/calibration sent - if (position > 0 || (position == 0 && (activity == 2 || activity == 3))) { - tto->_previousPosition = tto->getPosition(); - tto->_turntableData.position = position; - if (tto->isEXTT()) { - tto->setPositionStateOnly(id, position, 1); - } else { - tto->setPositionStateOnly(id, position, 0); - } + // We only deal with broadcasts for DCC turntables here, EXTT in the device driver + if (!tto->isEXTT()) { + CommandDistributor::broadcastTurntable(id, position, false); } + // Trigger EXRAIL rotateEvent for both types here if changed +#if defined(EXRAIL_ACTIVE) + bool rotated = false; + if (position != tto->_previousPosition) rotated = true; + RMFT2::rotateEvent(id, rotated); +#endif } return ok; } @@ -206,6 +193,8 @@ using DevState = IODevice::DeviceStateEnum; } if (position > 0 && !value) return false; // Return false if it's not a valid position // Set position via device driver + _previousPosition = _turntableData.position; + _turntableData.position = position; EXTurntable::writeAnalogue(_exttTurntableData.vpin, value, activity); #else (void)position; @@ -248,6 +237,8 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} int16_t addr=value>>3; int16_t subaddr=(value>>1) & 0x03; bool active=value & 0x01; + _previousPosition = _turntableData.position; + _turntableData.position = position; DCC::setAccessory(addr, subaddr, active); #else (void)position; diff --git a/Turntables.h b/Turntables.h index 30cba82..de0151c 100644 --- a/Turntables.h +++ b/Turntables.h @@ -179,7 +179,6 @@ public: */ inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); - static bool setPositionStateOnly(uint16_t id, uint8_t position, bool moving); static uint8_t getPosition(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { From 152f9850bbd0bd8c1ff7f5cfe4a8c5a8ecad8b90 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Tue, 5 Sep 2023 19:05:18 +1000 Subject: [PATCH 052/310] Working --- IO_EXTurntable.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index b36237f..af220a3 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -82,7 +82,6 @@ void EXTurntable::_loop(unsigned long currentMicros) { // Return false if our status value is invalid. int EXTurntable::_read(VPIN vpin) { if (_deviceState == DEVSTATE_FAILED) return 0; - // DIAG(F("_read status: %d"), _stepperStatus); if (_stepperStatus > 1) { return false; } else { @@ -126,6 +125,7 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + _previousStatus = _stepperStatus; _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } From 2f8e915b1e19c088bc742fdddcd4bbb110ff3e73 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Tue, 5 Sep 2023 12:21:09 +0100 Subject: [PATCH 053/310] Added AFTEROVERLOAD Added the AFTEROVERLOAD option - as yet untested. --- EXRAIL2.cpp | 13 ++++++++++++- EXRAIL2.h | 3 ++- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 1 + TrackManager.cpp | 8 ++++++++ TrackManager.h | 3 +++ 6 files changed, 28 insertions(+), 2 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index ac277a5..f9935d7 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -197,6 +197,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { case OPCODE_AT: case OPCODE_ATTIMEOUT2: case OPCODE_AFTER: + case OPCODE_AFTEROVERLOAD: case OPCODE_IF: case OPCODE_IFNOT: { int16_t pin = (int16_t)operand; @@ -686,7 +687,17 @@ void RMFT2::loop2() { } if (millis()-waitAfter < 500 ) return; break; - + + case OPCODE_AFTEROVERLOAD: // waits for the power to be turned back on - either by power routine or button + if (!TrackManager::isPowerOn(operand)) { + // reset timer to half a second and keep waiting + waitAfter=millis(); + delayMe(50); + return; + } + if (millis()-waitAfter < 500 ) return; + break; + case OPCODE_LATCH: setFlag(operand,LATCH_FLAG); break; diff --git a/EXRAIL2.h b/EXRAIL2.h index 700cd6b..6e00561 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -35,7 +35,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION, OPCODE_RESERVE,OPCODE_FREE, - OPCODE_AT,OPCODE_AFTER,OPCODE_AUTOSTART, + OPCODE_AT,OPCODE_AFTER, + OPCODE_AFTEROVERLOAD,OPCODE_AUTOSTART, OPCODE_ATGTE,OPCODE_ATLT, OPCODE_ATTIMEOUT1,OPCODE_ATTIMEOUT2, OPCODE_LATCH,OPCODE_UNLATCH,OPCODE_SET,OPCODE_RESET, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 5ac3ab7..22cf562 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -27,6 +27,7 @@ #undef ACTIVATE #undef ACTIVATEL #undef AFTER +#undef AFTEROVERLOAD #undef ALIAS #undef AMBER #undef ANOUT @@ -153,6 +154,7 @@ #define ACTIVATE(addr,subaddr) #define ACTIVATEL(addr) #define AFTER(sensor_id) +#define AFTEROVERLOAD(track_id) #define ALIAS(name,value...) #define AMBER(signal_id) #define ANOUT(vpin,value,param1,param2) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 69b5995..d1cad0c 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -256,6 +256,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1 | 1), #define ACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1 | 1), #define AFTER(sensor_id) OPCODE_AT,V(sensor_id),OPCODE_AFTER,V(sensor_id), +#define AFTEROVERLOAD(track_id) OPCODE_AFTEROVERLOAD,V(TRACK_NUMBER_##track_id), #define ALIAS(name,value...) #define AMBER(signal_id) OPCODE_AMBER,V(signal_id), #define ANOUT(vpin,value,param1,param2) OPCODE_SERVO,V(vpin),OPCODE_PAD,V(value),OPCODE_PAD,V(param1),OPCODE_PAD,V(param2), diff --git a/TrackManager.cpp b/TrackManager.cpp index 0f69235..9942563 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -1,6 +1,7 @@ /* * © 2022 Chris Harlow * © 2022 Harald Barth + * © 2023 Colin Murdoch * All rights reserved. * * This file is part of DCC++EX @@ -513,3 +514,10 @@ void TrackManager::setJoin(bool joined) { progTrackSyncMain=joined; if (joinRelay!=UNUSED_PIN) digitalWrite(joinRelay,joined?HIGH:LOW); } + +bool TrackManager::isPowerOn(byte t) { + if (track[t]->getPower()==POWERMODE::ON) + return true; + return false; + } + diff --git a/TrackManager.h b/TrackManager.h index 965cfa3..60d5f24 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -1,6 +1,8 @@ /* * © 2022 Chris Harlow * © 2022 Harald Barth + * © 2023 Colin Murdoch + * * All rights reserved. * * This file is part of CommandStation-EX @@ -77,6 +79,7 @@ class TrackManager { static void reportCurrent(Print* stream); static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); + static bool isPowerOn(byte t); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From 1ac104704e5922860cd1f76178c00fb64e3123f6 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Tue, 5 Sep 2023 20:52:18 +0100 Subject: [PATCH 054/310] Update TrackManager.cpp Reverse logic in TM::IisPowerOn() --- TrackManager.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 9942563..edaac6e 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -516,8 +516,8 @@ void TrackManager::setJoin(bool joined) { } bool TrackManager::isPowerOn(byte t) { - if (track[t]->getPower()==POWERMODE::ON) - return true; - return false; + if (track[t]->getPower()!=POWERMODE::ON) + return false; + return true; } From 6adff43f4b0f5b7231ca61e555318232c1fd98f5 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 6 Sep 2023 07:59:43 +1000 Subject: [PATCH 055/310] Update add position --- DCCEXParser.cpp | 24 ++++++++++++------------ EXRAIL2.cpp | 9 +++++---- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 2 +- Turntables.cpp | 4 ++-- Turntables.h | 9 ++++----- 6 files changed, 25 insertions(+), 25 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2014762..de1618c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1094,7 +1094,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (tto) return false; if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0); + tto->addPosition(0, 0); } else { // Otherwise move a DCC turntable if (tto && !tto->isEXTT()) { if (!tto->setPosition(p[0], p[1])) return false; @@ -1105,27 +1105,27 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 3: // | + case 3: // rotate to position for EX-Turntable { Turntable *tto = Turntable::get(p[0]); if (!tto) return false; - if (p[1] == HASH_KEYWORD_ADD) { // Add position value to turntable - tto->addPosition(p[2]); - StringFormatter::send(stream, F("\n")); - } else { // rotate to position for EX-Turntable - if (!tto->isEXTT()) return false; - if (!tto->setPosition(p[0], p[1], p[2])) return false; - } + if (!tto->isEXTT()) return false; + if (!tto->setPosition(p[0], p[1], p[2])) return false; } return true; - case 4: // create an EXTT turntable + case 4: // | create an EXTT turntable or add position { + Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_EXTT) { - if (Turntable::get(p[0])) return false; + if (tto) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(p[3]); + tto->addPosition(0, p[3]); + } else if (p[1] == HASH_KEYWORD_ADD) { + if (!tto) return false; + tto->addPosition(p[2], p[3]); + StringFormatter::send(stream, F("\n")); } else { return false; } diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 77a9f88..d88a6f4 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -247,7 +247,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { VPIN id=operand; setTurntableHiddenState(DCCTurntable::create(id)); Turntable *tto=Turntable::get(id); - tto->addPosition(0); + tto->addPosition(0,0); break; } @@ -257,15 +257,16 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { int home=getOperand(progCounter,2); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); - tto->addPosition(home); + tto->addPosition(0,home); break; } case OPCODE_TTADDPOSITION: { VPIN id=operand; - int value=getOperand(progCounter,1); + int position=getOperand(progCounter,1); + int value=getOperand(progCounter,2); Turntable *tto=Turntable::get(id); - tto->addPosition(value); + tto->addPosition(position,value); break; } #endif diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 7c690b7..21d4f18 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -273,7 +273,7 @@ #define START(route) #define STOP #define THROW(id) -#define TT_ADDPOSITION(turntable_id,value,description) +#define TT_ADDPOSITION(turntable_id,position,value,description) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index f5d905e..68f3bf0 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -406,7 +406,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL -#define TT_ADDPOSITION(id,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(value), +#define TT_ADDPOSITION(id,position,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value), #endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) diff --git a/Turntables.cpp b/Turntables.cpp index 120ac2f..abbac81 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -58,8 +58,8 @@ void Turntable::add(Turntable *tto) { } // Add a position -void Turntable::addPosition(uint16_t value) { - _turntablePositions.insert(value); +void Turntable::addPosition(uint8_t idx, uint16_t value) { + _turntablePositions.insert(idx, value); } // Get value for position diff --git a/Turntables.h b/Turntables.h index de0151c..15333c9 100644 --- a/Turntables.h +++ b/Turntables.h @@ -53,10 +53,10 @@ struct TurntablePosition { class TurntablePositionList { public: - TurntablePositionList() : head(nullptr), currentIndex(0) {} + TurntablePositionList() : head(nullptr) {} - void insert(uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(currentIndex++, value); + void insert(uint8_t idx, uint16_t value) { + TurntablePosition* newPosition = new TurntablePosition(idx, value); if(!head) { head = newPosition; } else { @@ -71,7 +71,6 @@ public: private: TurntablePosition* head; - uint8_t currentIndex; }; @@ -159,7 +158,7 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - void addPosition(uint16_t value); + void addPosition(uint8_t idx, uint16_t value); uint16_t getPositionValue(uint8_t position); uint8_t getPositionCount(); bool isMoving() { return _isMoving; } From 1f5f7754c1a4b5c928fadf10046715cd4099aea5 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Wed, 6 Sep 2023 15:16:46 +1000 Subject: [PATCH 056/310] Start on position description --- DCCEXParser.cpp | 5 +++-- EXRAIL2.h | 2 +- EXRAILMacros.h | 8 ++++++-- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index de1618c..404685d 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -712,10 +712,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; #ifdef EXRAIL_ACTIVE - // todesc = RMFT2::getTurntableDescription(id); + todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d"), id, type, pos); + StringFormatter::send(stream, F(" %d %d %d"), id, type, pos, todesc); + for (uint8_t p = 0; p < posCount; p++) { int16_t value = tto->getPositionValue(p); StringFormatter::send(stream, F(" %d"), value); diff --git a/EXRAIL2.h b/EXRAIL2.h index 16fff82..f6c4807 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -149,7 +149,7 @@ class LookList { static const FSH * getRosterName(int16_t id); static const FSH * getRosterFunctions(int16_t id); static const FSH * getTurntableDescription(int16_t id); - // static const FSH * getTurntablePositionDescription(int16_t id, uint8_t position); + static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 68f3bf0..c413989 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -205,10 +205,14 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { // Pass to get turntable position descriptions (optional) // #include "EXRAIL2MacroReset.h" // #undef TT_ADDPOSITION -// #define TT_ADDPOSITION(turntable_id,value,description...) 0_DESC(id,description) +// #define TT_ADDPOSITION(turntable_id,value,description...) O_DESC(turntable_id,description) // const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { - +// switch (turntableId) { +// #include "myAutomation.h" +// default:break; +// } +// return NULL; // } // Pass 6: Roster IDs (count) From ab393047c10c4ec041347982d27e24fa0296805b Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Wed, 6 Sep 2023 11:20:23 +0100 Subject: [PATCH 057/310] Update MotorDriver.cpp Replace duplicate call to EXRAIL with single in overload. --- MotorDriver.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index e3ecd64..4644ad5 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -576,8 +576,6 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { DIAG(F("TRACK %c FAULT PIN detected after %4M. Pause %4M)"), trackno + 'A', mslpc, power_sample_overload_wait); throttleInrush(false); setPower(POWERMODE::OVERLOAD); - DIAG(F("Calling EXRAIL")); - RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload break; } if (checkCurrent(useProgLimit)) { @@ -595,8 +593,6 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { trackno + 'A', mA, maxmA, mslpc, power_sample_overload_wait); throttleInrush(false); setPower(POWERMODE::OVERLOAD); - DIAG(F("Calling EXRAIL")); - RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload break; } // all well @@ -619,7 +615,9 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { // adjust next wait time power_sample_overload_wait *= 2; if (power_sample_overload_wait > POWER_SAMPLE_RETRY_MAX) - power_sample_overload_wait = POWER_SAMPLE_RETRY_MAX; + power_sample_overload_wait = POWER_SAMPLE_RETRY_MAX; + DIAG(F("Calling EXRAIL")); + RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload // power on test DIAG(F("TRACK %c POWER RESTORE (after %4M)"), trackno + 'A', mslpc); setPower(POWERMODE::ALERT); From 21ce87eb3e72a7d8925ea5fec407222ffbd2ce6c Mon Sep 17 00:00:00 2001 From: peteGSX Date: Thu, 7 Sep 2023 05:33:26 +1000 Subject: [PATCH 058/310] Descriptions available --- DCCEXParser.cpp | 13 ++++++++++--- EXRAILMacros.h | 19 +++++++++---------- 2 files changed, 19 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 404685d..405512c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -702,6 +702,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (tto->isHidden()) continue; StringFormatter::send(stream, F(" %d"),tto->getId()); } + StringFormatter::send(stream, F(">\n")); } else { // Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { @@ -711,19 +712,25 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; + const FSH *tpdesc = NULL; #ifdef EXRAIL_ACTIVE todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d %d %d"), id, type, pos, todesc); + StringFormatter::send(stream, F(" %d %d %d %d \"%S\">\n"), id, type, pos, posCount, todesc); for (uint8_t p = 0; p < posCount; p++) { + StringFormatter::send(stream, F("jO>")); int16_t value = tto->getPositionValue(p); - StringFormatter::send(stream, F(" %d"), value); +#ifdef EXRAIL_ACTIVE + tpdesc = RMFT2::getTurntablePositionDescription(id, p); +#endif + if (tpdesc == NULL) todesc = F(""); + StringFormatter::send(stream, F(" %d \"%S\""), value, tpdesc); + StringFormatter::send(stream, F(">\n")); } } } - StringFormatter::send(stream, F(">\n")); return; #endif default: break; diff --git a/EXRAILMacros.h b/EXRAILMacros.h index c413989..97604c5 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -54,6 +54,8 @@ // helper macro for turnout descriptions, creates NULL for missing description #define O_DESC(id, desc) case id: return ("" desc)[0]?F("" desc):NULL; +// helper macro for turntable descriptions, creates NULL for missing description +#define T_DESC(tid,pid,desc) if(turntableId==tid && positionId==pid) return ("" desc)[0]?F("" desc):NULL; // helper macro for turnout description as HIDDEN #define HIDDEN "\x01" @@ -203,17 +205,14 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { } // Pass to get turntable position descriptions (optional) -// #include "EXRAIL2MacroReset.h" -// #undef TT_ADDPOSITION -// #define TT_ADDPOSITION(turntable_id,value,description...) O_DESC(turntable_id,description) +#include "EXRAIL2MacroReset.h" +#undef TT_ADDPOSITION +#define TT_ADDPOSITION(turntable_id,position,value,description...) T_DESC(turntable_id,position,description) -// const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { -// switch (turntableId) { -// #include "myAutomation.h" -// default:break; -// } -// return NULL; -// } +const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { + #include "myAutomation.h" + return NULL; +} // Pass 6: Roster IDs (count) #include "EXRAIL2MacroReset.h" From 004d7b66317f34a43006e4319cdbc7bf3a0f066d Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 7 Sep 2023 07:32:54 +1000 Subject: [PATCH 059/310] JO and JP working --- DCCEXParser.cpp | 24 ++++++++++++++++++------ platformio.ini | 2 +- 2 files changed, 19 insertions(+), 7 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 405512c..94b711e 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -86,6 +86,7 @@ const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_I='I'; const int16_t HASH_KEYWORD_O='O'; +const int16_t HASH_KEYWORD_P='P'; const int16_t HASH_KEYWORD_R='R'; const int16_t HASH_KEYWORD_T='T'; const int16_t HASH_KEYWORD_X='X'; @@ -706,30 +707,41 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } else { // Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { - StringFormatter::send(stream, F(" %d X"), id); + StringFormatter::send(stream, F(" %d X>\n"), id); } else { uint8_t pos = tto->getPosition(); uint8_t type = tto->isEXTT(); uint8_t posCount = tto->getPositionCount(); const FSH *todesc = NULL; - const FSH *tpdesc = NULL; #ifdef EXRAIL_ACTIVE todesc = RMFT2::getTurntableDescription(id); #endif if (todesc == NULL) todesc = F(""); StringFormatter::send(stream, F(" %d %d %d %d \"%S\">\n"), id, type, pos, posCount, todesc); - + } + } + return; + case HASH_KEYWORD_P: // returns turntable position list for the turntable id + if (params==2) { // + Turntable *tto=Turntable::get(id); + if (!tto || tto->isHidden()) { + StringFormatter::send(stream, F(" %d X>\n"), id); + } else { + uint8_t posCount = tto->getPositionCount(); + const FSH *tpdesc = NULL; for (uint8_t p = 0; p < posCount; p++) { - StringFormatter::send(stream, F("jO>")); + StringFormatter::send(stream, F("getPositionValue(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif - if (tpdesc == NULL) todesc = F(""); - StringFormatter::send(stream, F(" %d \"%S\""), value, tpdesc); + if (tpdesc == NULL) tpdesc = F(""); + StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, value, tpdesc); StringFormatter::send(stream, F(">\n")); } } + } else { + StringFormatter::send(stream, F("\n")); } return; #endif diff --git a/platformio.ini b/platformio.ini index 1a87770..ac2d598 100644 --- a/platformio.ini +++ b/platformio.ini @@ -30,7 +30,7 @@ include_dir = . [env] build_flags = -Wall -Wextra -monitor_filters = time +; monitor_filters = time ; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0 [env:samd21-dev-usb] From bd02d1c15bf4cc35848d07b15c5630dcc352ebd8 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Thu, 7 Sep 2023 07:58:19 +1000 Subject: [PATCH 060/310] WAITFORTT ready for testing --- EXRAIL2.cpp | 20 ++++++++++++++++++-- EXRAIL2.h | 6 +++++- EXRAIL2MacroReset.h | 6 ++++++ EXRAILMacros.h | 3 +++ Turntables.cpp | 6 ++++++ Turntables.h | 1 + 6 files changed, 39 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index d88a6f4..2d379a7 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -95,7 +95,9 @@ LookList * RMFT2::onAmberLookup=NULL; LookList * RMFT2::onGreenLookup=NULL; LookList * RMFT2::onChangeLookup=NULL; LookList * RMFT2::onClockLookup=NULL; +#ifndef IO_NO_HAL LookList * RMFT2::onRotateLookup=NULL; +#endif #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -177,8 +179,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); +#ifndef IO_NO_HAL onRotateLookup=LookListLoader(OPCODE_ONROTATE); - +#endif // Second pass startup, define any turnouts or servos, set signals red // add sequences onRoutines to the lookups @@ -1014,7 +1017,16 @@ void RMFT2::loop2() { return; } break; - + +#ifndef IO_NO_HAL + case OPCODE_WAITFORTT: // OPCODE_WAITFOR,V(turntable_id) + if (Turntable::ttMoving(operand)) { + delayMe(100); + return; + } + break; +#endif + case OPCODE_PRINT: printMessage(operand); break; @@ -1039,10 +1051,12 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: +#ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime case OPCODE_TTADDPOSITION: // Turntable position definition ignored at runtime case OPCODE_ONROTATE: +#endif break; @@ -1187,10 +1201,12 @@ void RMFT2::changeEvent(int16_t vpin, bool change) { if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); } +#ifndef IO_NO_HAL void RMFT2::rotateEvent(int16_t turntableId, bool change) { // Hunt or an ONROTATE for this turntable if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId); } +#endif void RMFT2::clockEvent(int16_t clocktime, bool change) { // Hunt for an ONTIME for this time diff --git a/EXRAIL2.h b/EXRAIL2.h index f6c4807..5247e3e 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -63,8 +63,10 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, +#ifndef IO_NO_HAL OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, - OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION, + OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION,OPCODE_WAITFORTT, +#endif // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -197,7 +199,9 @@ private: static LookList * onGreenLookup; static LookList * onChangeLookup; static LookList * onClockLookup; +#ifndef IO_NO_HAL static LookList * onRotateLookup; +#endif // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 21d4f18..efe91a5 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -150,6 +150,9 @@ #undef VIRTUAL_SIGNAL #undef VIRTUAL_TURNOUT #undef WAITFOR +#ifndef IO_NO_HAL +#undef WAITFORTT +#endif #undef WITHROTTLE #undef XFOFF #undef XFON @@ -281,6 +284,9 @@ #define VIRTUAL_SIGNAL(id) #define VIRTUAL_TURNOUT(id,description...) #define WAITFOR(pin) +#ifndef IO_NO_HAL +#define WAITFORTT(turntable_id) +#endif #define WITHROTTLE(msg) #define XFOFF(cab,func) #define XFON(cab,func) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 97604c5..e3ce129 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -419,6 +419,9 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define VIRTUAL_TURNOUT(id,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(0), #define WITHROTTLE(msg) PRINT(msg) #define WAITFOR(pin) OPCODE_WAITFOR,V(pin), +#ifndef IO_NO_HAL +#define WAITFORTT(turntable_id) OPCODE_WAITFORTT,V(turntable_id), +#endif #define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func), #define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func), diff --git a/Turntables.cpp b/Turntables.cpp index abbac81..d43a515 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -115,6 +115,12 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } +bool Turntable::ttMoving(uint16_t id) { + Turntable *tto = get(id); + if (!tto) return false; + return tto->isMoving(); +} + // Initiate a turntable move bool Turntable::setPosition(uint16_t id, uint8_t position, uint8_t activity) { #if defined(DIAG_IO) diff --git a/Turntables.h b/Turntables.h index 15333c9..e7b7415 100644 --- a/Turntables.h +++ b/Turntables.h @@ -179,6 +179,7 @@ public: inline static bool exists(uint16_t id) { return get(id) != 0; } static bool setPosition(uint16_t id, uint8_t position, uint8_t activity=0); static uint8_t getPosition(uint16_t id); + static bool ttMoving(uint16_t id); inline static Turntable *first() { return _firstTurntable; } static bool printAll(Print *stream) { bool gotOne = false; From dca023ffd7f78f002a4979700a9896f033256a0b Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Thu, 7 Sep 2023 20:27:25 +0100 Subject: [PATCH 061/310] Update version.h Added ONOVERLOAD and AFTEROVERLOAD as 5.1.4 --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index d03eab8..abcc577 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.3" +#define VERSION "5.1.4" +// 5.1.4 - Added ONOVERLOAD & AFTEROVERLOAD to EXRAIL // 5.1.3 - Make parser more fool proof // 5.1.2 - Bugfix: ESP32 30ms off time // 5.1.1 - Check bad AT firmware version From be10be5a1a9e55ef6bbb35cfac156966f5612a45 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 9 Sep 2023 07:22:10 +1000 Subject: [PATCH 062/310] Added angles --- DCCEXParser.cpp | 57 +++++++++++++++++++++++++++------------------ EXRAIL2.cpp | 9 ++++--- EXRAIL2MacroReset.h | 6 +++-- EXRAILMacros.h | 11 +++++---- Turntables.cpp | 17 ++++++++++++-- Turntables.h | 13 +++++------ 6 files changed, 71 insertions(+), 42 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 94b711e..40ea635 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -732,11 +732,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) for (uint8_t p = 0; p < posCount; p++) { StringFormatter::send(stream, F("getPositionValue(p); + int16_t angle = tto->getPositionAngle(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif if (tpdesc == NULL) tpdesc = F(""); - StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, value, tpdesc); + StringFormatter::send(stream, F(" %d %d %d %d \"%S\""), id, p, value, angle, tpdesc); StringFormatter::send(stream, F(">\n")); } } @@ -1107,44 +1108,54 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) } return true; - case 2: // | - rotate or create DCC turntable + case 2: // - rotate a DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_DCC) { // Create a DCC turntable - if (tto) return false; - if (!DCCTurntable::create(p[0])) return false; - Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0, 0); - } else { // Otherwise move a DCC turntable - if (tto && !tto->isEXTT()) { - if (!tto->setPosition(p[0], p[1])) return false; - } else { - return false; - } + if (tto && !tto->isEXTT()) { + if (!tto->setPosition(p[0], p[1])) return false; + } else { + return false; } } return true; - case 3: // rotate to position for EX-Turntable + case 3: // | - rotate to position for EX-Turntable or create DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (!tto) return false; - if (!tto->isEXTT()) return false; - if (!tto->setPosition(p[0], p[1], p[2])) return false; + if (p[1] == HASH_KEYWORD_DCC) { + if (tto || p[2] < 0 || p[2] > 3600) return false; + if (!DCCTurntable::create(p[0])) return false; + Turntable *tto = Turntable::get(p[0]); + tto->addPosition(0, 0, p[2]); + } else { + if (!tto) return false; + if (!tto->isEXTT()) return false; + if (!tto->setPosition(p[0], p[1], p[2])) return false; + } } return true; - case 4: // | create an EXTT turntable or add position + case 4: // create an EXTT turntable { Turntable *tto = Turntable::get(p[0]); if (p[1] == HASH_KEYWORD_EXTT) { - if (tto) return false; + if (tto || p[3] < 0 || p[3] > 3600) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); - tto->addPosition(0, p[3]); - } else if (p[1] == HASH_KEYWORD_ADD) { - if (!tto) return false; - tto->addPosition(p[2], p[3]); + tto->addPosition(0, 0, p[3]); + } else { + return false; + } + } + return true; + + case 5: // add a position + { + Turntable *tto = Turntable::get(p[0]); + if (p[1] == HASH_KEYWORD_ADD) { + // tto must exist, no more than 48 positions, angle 0 - 3600 + if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; + tto->addPosition(p[2], p[3], p[4]); StringFormatter::send(stream, F("\n")); } else { return false; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 2d379a7..32d2795 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -53,6 +53,7 @@ #include "CommandDistributor.h" #include "TrackManager.h" #include "Turntables.h" +#include "IODevice.h" // Command parsing keywords const int16_t HASH_KEYWORD_EXRAIL=15435; @@ -248,9 +249,10 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { #ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: { VPIN id=operand; + int home=getOperand(progCounter,1); setTurntableHiddenState(DCCTurntable::create(id)); Turntable *tto=Turntable::get(id); - tto->addPosition(0,0); + tto->addPosition(0,0,home); break; } @@ -260,7 +262,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { int home=getOperand(progCounter,2); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); - tto->addPosition(0,home); + tto->addPosition(0,0,home); break; } @@ -268,8 +270,9 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { VPIN id=operand; int position=getOperand(progCounter,1); int value=getOperand(progCounter,2); + int angle=getOperand(progCounter,3); Turntable *tto=Turntable::get(id); - tto->addPosition(position,value); + tto->addPosition(position,value,angle); break; } #endif diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index efe91a5..b54a9d9 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -119,6 +119,7 @@ #undef REV #undef ROSTER #undef ROTATE +#undef ROTATE_DCC #undef ROUTE #undef SENDLOCO #undef SEQUENCE @@ -174,7 +175,7 @@ #define CALL(route) #define CLOSE(id) #define DCC_SIGNAL(id,add,subaddr) -#define DCC_TURNTABLE(id,description) +#define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) #define DELAY(mindelay) @@ -252,6 +253,7 @@ #define RETURN #define REV(speed) #define ROTATE(turntable_id,position,activity) +#define ROTATE_DCC(turntable_id,position) #define ROSTER(cab,name,funcmap...) #define ROUTE(id,description) #define SENDLOCO(cab,route) @@ -276,7 +278,7 @@ #define START(route) #define STOP #define THROW(id) -#define TT_ADDPOSITION(turntable_id,position,value,description) +#define TT_ADDPOSITION(turntable_id,position,value,angle,description...) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) #define UNJOIN diff --git a/EXRAILMacros.h b/EXRAILMacros.h index e3ce129..440a619 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -192,7 +192,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { // Pass to get turntable descriptions (optional) #include "EXRAIL2MacroReset.h" #undef DCC_TURNTABLE -#define DCC_TURNTABLE(id,description...) O_DESC(id,description) +#define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE #define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) @@ -207,7 +207,7 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { // Pass to get turntable position descriptions (optional) #include "EXRAIL2MacroReset.h" #undef TT_ADDPOSITION -#define TT_ADDPOSITION(turntable_id,position,value,description...) T_DESC(turntable_id,position,description) +#define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description) const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { #include "myAutomation.h" @@ -296,7 +296,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define CALL(route) OPCODE_CALL,V(route), #define CLOSE(id) OPCODE_CLOSE,V(id), #ifndef IO_NO_HAL -#define DCC_TURNTABLE(id,description...) OPCODE_DCCTURNTABLE,V(id), +#define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), #endif #define DEACTIVATE(addr,subaddr) OPCODE_DCCACTIVATE,V(addr<<3 | subaddr<<1), #define DEACTIVATEL(addr) OPCODE_DCCACTIVATE,V((addr+3)<<1), @@ -383,7 +383,8 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define REV(speed) OPCODE_REV,V(speed), #define ROSTER(cabid,name,funcmap...) #ifndef IO_NO_HAL -#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(activity), +#define ROTATE(id,position,activity) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(EXTurntable::activity), +#define ROTATE_DCC(id,position) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(0), #endif #define ROUTE(id, description) OPCODE_ROUTE, V(id), #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), @@ -409,7 +410,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL -#define TT_ADDPOSITION(id,position,value,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value), +#define TT_ADDPOSITION(id,position,value,angle,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value),OPCODE_PAD,V(angle), #endif #define TURNOUT(id,addr,subaddr,description...) OPCODE_TURNOUT,V(id),OPCODE_PAD,V(addr),OPCODE_PAD,V(subaddr), #define TURNOUTL(id,addr,description...) TURNOUT(id,(addr-1)/4+1,(addr-1)%4, description) diff --git a/Turntables.cpp b/Turntables.cpp index d43a515..ba143cb 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -58,8 +58,8 @@ void Turntable::add(Turntable *tto) { } // Add a position -void Turntable::addPosition(uint8_t idx, uint16_t value) { - _turntablePositions.insert(idx, value); +void Turntable::addPosition(uint8_t idx, uint16_t value, uint16_t angle) { + _turntablePositions.insert(idx, value, angle); } // Get value for position @@ -74,6 +74,18 @@ uint16_t Turntable::getPositionValue(uint8_t position) { return false; } +// Get value for position +uint16_t Turntable::getPositionAngle(uint8_t position) { + TurntablePosition* currentPosition = _turntablePositions.getHead(); + while (currentPosition) { + if (currentPosition->index == position) { + return currentPosition->angle; + } + currentPosition = currentPosition->next; + } + return false; +} + // Get the count of positions associated with the turntable uint8_t Turntable::getPositionCount() { TurntablePosition* currentPosition = _turntablePositions.getHead(); @@ -115,6 +127,7 @@ uint8_t Turntable::getPosition(uint16_t id) { return tto->getPosition(); } +// Got the moving state of the specified turntable bool Turntable::ttMoving(uint16_t id) { Turntable *tto = get(id); if (!tto) return false; diff --git a/Turntables.h b/Turntables.h index e7b7415..6c15bab 100644 --- a/Turntables.h +++ b/Turntables.h @@ -36,9 +36,6 @@ enum { TURNTABLE_DCC = 1, }; -// Callback needs to return a bool: 1 = moving, 0 = stopped -typedef void (*EXTT_CALLBACK)(bool moving); - /************************************************************************************* * Turntable positions. * @@ -46,17 +43,18 @@ typedef void (*EXTT_CALLBACK)(bool moving); struct TurntablePosition { uint8_t index; uint16_t data; + uint16_t angle; TurntablePosition* next; - TurntablePosition(uint8_t idx, uint16_t value) : index(idx), data(value), next(nullptr) {} + TurntablePosition(uint8_t idx, uint16_t value, uint16_t angle) : index(idx), data(value), angle(angle), next(nullptr) {} }; class TurntablePositionList { public: TurntablePositionList() : head(nullptr) {} - void insert(uint8_t idx, uint16_t value) { - TurntablePosition* newPosition = new TurntablePosition(idx, value); + void insert(uint8_t idx, uint16_t value, uint16_t angle) { + TurntablePosition* newPosition = new TurntablePosition(idx, value, angle); if(!head) { head = newPosition; } else { @@ -158,8 +156,9 @@ public: inline uint16_t getId() { return _turntableData.id; } inline Turntable *next() { return _nextTurntable; } void printState(Print *stream); - void addPosition(uint8_t idx, uint16_t value); + void addPosition(uint8_t idx, uint16_t value, uint16_t angle); uint16_t getPositionValue(uint8_t position); + uint16_t getPositionAngle(uint8_t position); uint8_t getPositionCount(); bool isMoving() { return _isMoving; } void setMoving(bool moving) { _isMoving=moving; } From dba5d35aa231ebbe732a755462f8b95043554c64 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 9 Sep 2023 09:23:10 +1000 Subject: [PATCH 063/310] Add response to create --- DCCEXParser.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 40ea635..05e0eca 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1127,6 +1127,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[2]); + StringFormatter::send(stream, F("\n")); } else { if (!tto) return false; if (!tto->isEXTT()) return false; @@ -1143,6 +1144,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[3]); + StringFormatter::send(stream, F("\n")); } else { return false; } From 7ee2c29a526078d2f5a395adc0cd671f1d1df0a9 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 10 Sep 2023 05:30:48 +1000 Subject: [PATCH 064/310] Include HAL create with EXTT_TURNTABLE --- EXRAIL2.cpp | 2 +- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 9 ++++++--- 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 32d2795..c8ff8f3 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -259,7 +259,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { case OPCODE_EXTTTURNTABLE: { VPIN id=operand; VPIN pin=getOperand(progCounter,1); - int home=getOperand(progCounter,2); + int home=getOperand(progCounter,3); setTurntableHiddenState(EXTTTurntable::create(id,pin)); Turntable *tto=Turntable::get(id); tto->addPosition(0,0,home); diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index b54a9d9..c8ff395 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -189,7 +189,7 @@ #define ENDTASK #define ESTOP #define EXRAIL -#define EXTT_TURNTABLE(id,vpin,home,description) +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 440a619..39e5dda 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -69,10 +69,13 @@ #define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; #include "myAutomation.h" -// Pass 1h Implements HAL macro by creating exrailHalSetup function +// Pass 1h Implements HAL macro by creating exrailHalSetup function +// Also allows creating EXTurntable object #include "EXRAIL2MacroReset.h" #undef HAL #define HAL(haltype,params...) haltype::create(params); +#undef EXTT_TURNTABLE +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) EXTurntable::create(vpin,1,i2c_address); void exrailHalSetup() { #include "myAutomation.h" } @@ -194,7 +197,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { #undef DCC_TURNTABLE #define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE -#define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) O_DESC(id,description) const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { switch (turntableId) { @@ -313,7 +316,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL #ifndef IO_NO_HAL -#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), +#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(i2c_address),OPCODE_PAD,V(home), #endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), From a0562fdf5c0e1af6ffb0a95091535d827d3e0343 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 10 Sep 2023 07:06:27 +1000 Subject: [PATCH 065/310] Update defines to match changes in devel --- defines.h | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/defines.h b/defines.h index 3286aca..49aff71 100644 --- a/defines.h +++ b/defines.h @@ -218,8 +218,12 @@ // Define symbol IO_NO_HAL to reduce FLASH footprint when HAL features not required // The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. // -#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) -#define IO_NO_HAL +#if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) + #if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG) + #warning you have sacrificed DIAG for HAL + #else + #define IO_NO_HAL + #endif #endif #if __has_include ( "myAutomation.h") From 4fcd81a118a1ee8b89410bd5a30f2b0d73b4c61c Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 10 Sep 2023 07:18:54 +1000 Subject: [PATCH 066/310] Update version --- version.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index abcc577..e8ee138 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,10 @@ #include "StringFormatter.h" -#define VERSION "5.1.4" +#define VERSION "5.1.5" +// 5.1.5 - Added turntable object and EXRAIL commands +// - , , - turntable commands +// - DCC_TURNTABLE, EXTT_TURNTABLE, IFTTPOSITION, ONROTATE, ROTATE, ROTATE_DCC, TT_ADDPOSITION, WAITFORTT EXRAIL // 5.1.4 - Added ONOVERLOAD & AFTEROVERLOAD to EXRAIL // 5.1.3 - Make parser more fool proof // 5.1.2 - Bugfix: ESP32 30ms off time From da6a3c442f66d8802112b3b676ec47228f0a94b1 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sun, 10 Sep 2023 18:41:14 +1000 Subject: [PATCH 067/310] Remove redundant line --- EXRAIL2.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index fae6add..d6d2597 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -650,7 +650,6 @@ void RMFT2::loop2() { case OPCODE_ROTATE: uint8_t activity; activity=getOperand(2); - if (!activity) activity=0; Turntable::setPosition(operand,getOperand(1),activity); break; #endif From ebbeea5fbb8198ed7d3e7679b4dea6bd212a002b Mon Sep 17 00:00:00 2001 From: pmantoine Date: Wed, 13 Sep 2023 16:46:36 +0800 Subject: [PATCH 068/310] STM32F4xx native I2C driver merge --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index e8ee138..c8f6a68 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.5" +#define VERSION "5.1.6" +// 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - , , - turntable commands // - DCC_TURNTABLE, EXTT_TURNTABLE, IFTTPOSITION, ONROTATE, ROTATE, ROTATE_DCC, TT_ADDPOSITION, WAITFORTT EXRAIL From 8437b0e7aa994d78153a1cbf367559c830b0a314 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Fri, 15 Sep 2023 06:26:29 +1000 Subject: [PATCH 069/310] Updated broadcasts --- DCCEXParser.cpp | 3 +-- IODevice.h | 3 ++- IO_EXTurntable.cpp | 17 +++++++++++------ version.h | 3 ++- 4 files changed, 16 insertions(+), 10 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 08aae01..29c252d 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -812,13 +812,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) const FSH *tpdesc = NULL; for (uint8_t p = 0; p < posCount; p++) { StringFormatter::send(stream, F("getPositionValue(p); int16_t angle = tto->getPositionAngle(p); #ifdef EXRAIL_ACTIVE tpdesc = RMFT2::getTurntablePositionDescription(id, p); #endif if (tpdesc == NULL) tpdesc = F(""); - StringFormatter::send(stream, F(" %d %d %d %d \"%S\""), id, p, value, angle, tpdesc); + StringFormatter::send(stream, F(" %d %d %d \"%S\""), id, p, angle, tpdesc); StringFormatter::send(stream, F(">\n")); } } diff --git a/IODevice.h b/IODevice.h index 4803f56..74fe49b 100644 --- a/IODevice.h +++ b/IODevice.h @@ -409,11 +409,12 @@ private: void _begin() override; void _loop(unsigned long currentMicros) override; int _read(VPIN vpin) override; - void _broadcastStatus (VPIN vpin, uint8_t status); + void _broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity); void _writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_t duration) override; void _display() override; uint8_t _stepperStatus; uint8_t _previousStatus; + uint8_t _currentActivity; }; #endif diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index af220a3..aeb935b 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -72,7 +72,9 @@ void EXTurntable::_loop(unsigned long currentMicros) { I2CManager.read(_I2CAddress, readBuffer, 1); _stepperStatus = readBuffer[0]; if (_stepperStatus != _previousStatus && _stepperStatus == 0) { // Broadcast when a rotation finishes - _broadcastStatus(_firstVpin, _stepperStatus); + if ( _currentActivity < 4) { + _broadcastStatus(_firstVpin, _stepperStatus, _currentActivity); + } _previousStatus = _stepperStatus; } delayUntil(currentMicros + 100000); // Wait 100ms before checking again @@ -90,11 +92,13 @@ int EXTurntable::_read(VPIN vpin) { } // If a status change has occurred for a turntable object, broadcast it -void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status) { +void EXTurntable::_broadcastStatus (VPIN vpin, uint8_t status, uint8_t activity) { Turntable *tto = Turntable::getByVpin(vpin); if (tto) { - tto->setMoving(status); - CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + if (activity < 4) { + tto->setMoving(status); + CommandDistributor::broadcastTurntable(tto->getId(), tto->getPosition(), status); + } } } @@ -124,9 +128,10 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"), _I2CAddress.toString(), stepsMSB, stepsLSB, activity); #endif - _stepperStatus = 1; // Tell the device driver Turntable-EX is busy + if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy _previousStatus = _stepperStatus; - _broadcastStatus(vpin, _stepperStatus); // Broadcast when the rotation starts + _currentActivity = activity; + _broadcastStatus(vpin, _stepperStatus, activity); // Broadcast when the rotation starts I2CManager.write(_I2CAddress, 3, stepsMSB, stepsLSB, activity); } diff --git a/version.h b/version.h index c8f6a68..35d3f1a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.6" +#define VERSION "5.1.7" +// 5.1.7 - Fix turntable broadcasts for non-movement activities and result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - , , - turntable commands From 550ad58c4d2fec42657c5e17374ebf03d160635a Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 21 Sep 2023 14:39:25 +0800 Subject: [PATCH 070/310] STM32 ADCee extended to support ADC2 and ADC3 --- DCCTimer.h | 5 ++ DCCTimerSTM32.cpp | 181 ++++++++++++++++++++++++++++++++++++---------- 2 files changed, 147 insertions(+), 39 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 7402f16..3b14fd6 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -125,8 +125,13 @@ private: // On platforms that scan, it is called from waveform ISR // only on a regular basis. static void scan(); + #if defined (ARDUINO_ARCH_STM32) + // bit array of used pins (max 32) + static uint32_t usedpins; +#else // bit array of used pins (max 16) static uint16_t usedpins; +#endif static uint8_t highestPin; // cached analog values (malloc:ed to actual number of ADC channels) static int *analogvals; diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index cffae40..f57499a 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -52,7 +52,7 @@ HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE // On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins -#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE)|| defined(ARDUINO_NUCLEO_F412ZG) +#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) // Nucleo-144 boards don't have Serial1 defined by default HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 // Serial3 is defined to use USART3 by default, but is in fact used as the diag console @@ -235,22 +235,19 @@ void DCCTimer::reset() { while(true) {}; } -// TODO: may need to use uint32_t on STMF4xx variants with > 16 analog inputs! -#if defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) -#warning STM32 board selected not fully supported - only use ADC1 inputs 0-15 for current sensing! -#endif -// For now, define the max of 16 ports - some variants have more, but this not **yet** supported -#define NUM_ADC_INPUTS 16 -// #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS +// Now we can handle more ADCs, maybe this works! +#define NUM_ADC_INPUTS NUM_ANALOG_INPUTS -uint16_t ADCee::usedpins = 0; -uint8_t ADCee::highestPin = 0; -int * ADCee::analogvals = NULL; -uint32_t * analogchans = NULL; -bool adc1configured = false; +uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels! +uint8_t ADCee::highestPin = 0; // Highest pin to scan +int * ADCee::analogvals = NULL; // Array of analog values last captured +uint32_t * analogchans = NULL; // Array of channel numbers to be scanned +// bool adc1configured = false; +ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on -int16_t ADCee::ADCmax() { - return 4095; +int16_t ADCee::ADCmax() +{ + return 4095; } int ADCee::init(uint8_t pin) { @@ -261,11 +258,33 @@ int ADCee::init(uint8_t pin) { return -1024; // some silly value as error uint32_t stmgpio = STM_PORT(stmpin); // converts to the GPIO port (16-bits per port group on STM32) - uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC channel (only valid for ADC1!) - GPIO_TypeDef * gpioBase; + uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel + ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc. + int adcnum = 1; + if (adc == ADC1) + DIAG(F("ADCee::init(): found pin %d on ADC1"), pin); +// Checking for ADC2 and ADC3 being defined helps cater for more variants later +#if defined(ADC2) + else if (adc == ADC2) + { + DIAG(F("ADCee::init(): found pin %d on ADC2"), pin); + adcnum = 2; + } +#endif +#if defined(ADC3) + else if (adc == ADC3) + { + DIAG(F("ADCee::init(): found pin %d on ADC3"), pin); + adcnum = 3; + } +#endif + else DIAG(F("ADCee::init(): found pin %d on unknown ADC!"), pin); - // Port config - find which port we're on and power it up - switch(stmgpio) { + // Port config - find which port we're on and power it up + GPIO_TypeDef *gpioBase; + + switch (stmgpio) + { case 0x00: RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; //Power up PORTA gpioBase = GPIOA; @@ -278,6 +297,20 @@ int ADCee::init(uint8_t pin) { RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; //Power up PORTC gpioBase = GPIOC; break; + case 0x03: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; //Power up PORTD + gpioBase = GPIOD; + break; + case 0x04: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOEEN; //Power up PORTE + gpioBase = GPIOE; + break; +#if defined(GPIOF) + case 0x05: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF + gpioBase = GPIOF; + break; +#endif default: return -1023; // some silly value as error } @@ -293,31 +326,33 @@ int ADCee::init(uint8_t pin) { if (adcchan > 18) return -1022; // silly value as error if (adcchan < 10) - ADC1->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles + adc->SMPR2 |= (0b111 << (adcchan * 3)); // Channel sampling rate 480 cycles else - ADC1->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles + adc->SMPR1 |= (0b111 << ((adcchan - 10) * 3)); // Channel sampling rate 480 cycles // Read the inital ADC value for this analog input - ADC1->SQR3 = adcchan; // 1st conversion in regular sequence - ADC1->CR2 |= (1 << 30); // Start 1st conversion SWSTART - while(!(ADC1->SR & (1 << 1))); // Wait until conversion is complete - value = ADC1->DR; // Read value from register + adc->SQR3 = adcchan; // 1st conversion in regular sequence + adc->CR2 |= ADC_CR2_SWSTART; //(1 << 30); // Start 1st conversion SWSTART + while(!(adc->SR & (1 << 1))); // Wait until conversion is complete + value = adc->DR; // Read value from register uint8_t id = pin - PNUM_ANALOG_BASE; - if (id > 15) { // today we have not enough bits in the mask to support more - return -1021; - } + // if (id > 15) { // today we have not enough bits in the mask to support more + // return -1021; + // } - if (analogvals == NULL) { // allocate analogvals and analogchans if this is the first invocation of init. + if (analogvals == NULL) { // allocate analogvals, analogchans and adcchans if this is the first invocation of init analogvals = (int *)calloc(NUM_ADC_INPUTS+1, sizeof(int)); analogchans = (uint32_t *)calloc(NUM_ADC_INPUTS+1, sizeof(uint32_t)); + adcchans = (ADC_TypeDef **)calloc(NUM_ADC_INPUTS+1, sizeof(ADC_TypeDef)); } analogvals[id] = value; // Store sampled value analogchans[id] = adcchan; // Keep track of which ADC channel is used for reading this pin - usedpins |= (1 << id); // This pin is now ready + adcchans[id] = adc; // Keep track of which ADC this channel is on + usedpins |= (1 << id); // This pin is now ready if (id > highestPin) highestPin = id; // Store our highest pin in use - DIAG(F("ADCee::init(): value=%d, channel=%d, id=%d"), value, adcchan, id); + DIAG(F("ADCee::init(): value=%d, ADC%d: channel=%d, id=%d"), value, adcnum, adcchan, id); return value; } @@ -344,13 +379,16 @@ void ADCee::scan() { static uint8_t id = 0; // id and mask are the same thing but it is faster to static uint16_t mask = 1; // increment and shift instead to calculate mask from id static bool waiting = false; + static ADC_TypeDef *adc; - if (waiting) { + adc = adcchans[id]; + if (waiting) + { // look if we have a result - if (!(ADC1->SR & (1 << 1))) + if (!(adc->SR & (1 << 1))) return; // no result, continue to wait // found value - analogvals[id] = ADC1->DR; + analogvals[id] = adc->DR; // advance at least one track #ifdef DEBUG_ADC if (id == 1) TrackManager::track[1]->setBrake(0); @@ -369,9 +407,10 @@ void ADCee::scan() { // look for a valid track to sample or until we are around while (true) { if (mask & usedpins) { - // start new ADC aquire on id - ADC1->SQR3 = analogchans[id]; //1st conversion in regular sequence - ADC1->CR2 |= (1 << 30); //Start 1st conversion SWSTART + // start new ADC aquire on id + adc = adcchans[id]; + adc->SQR3 = analogchans[id]; // 1st conversion in regular sequence + adc->CR2 |= (1 << 30); // Start 1st conversion SWSTART #ifdef DEBUG_ADC if (id == 1) TrackManager::track[1]->setBrake(1); #endif @@ -392,19 +431,83 @@ void ADCee::scan() { void ADCee::begin() { noInterrupts(); //ADC1 config sequence - // TODO: currently defaults to ADC1, may need more to handle other members of STM32F4xx family - RCC->APB2ENR |= (1 << 8); //Enable ADC1 clock (Bit8) + RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; // Enable ADC1 clock // Set ADC prescaler - DIV8 ~ 40ms, DIV6 ~ 30ms, DIV4 ~ 20ms, DIV2 ~ 11ms ADC->CCR = (0 << 16); // Set prescaler 0=DIV2, 1=DIV4, 2=DIV6, 3=DIV8 ADC1->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) ADC1->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) ADC1->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + // Disable the DMA controller for ADC1 + ADC1->CR2 &= ~ADC_CR2_DMA; ADC1->CR2 &= ~(1 << 1); //Single conversion ADC1->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 ADC1->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register ADC1->CR2 |= (1 << 0); // Switch on ADC1 + // Wait for ADC1 to become ready (calibration complete) + while (!(ADC1->CR2 & ADC_CR2_ADON)) { + } +#if defined(ADC2) + // Enable the ADC2 clock + RCC->APB2ENR |= RCC_APB2ENR_ADC2EN; + + // Initialize ADC2 + ADC2->CR1 = 0; // Disable all channels + ADC2->CR2 = 0; // Clear CR2 register + + ADC2->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) + ADC2->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) + ADC2->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + ADC2->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3 + ADC2->CR2 &= ~(1 << 1); //Single conversion + ADC2->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 + ADC2->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC2->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC2->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + + // Enable the ADC + ADC2->CR2 |= ADC_CR2_ADON; + + // Wait for ADC2 to become ready (calibration complete) + while (!(ADC2->CR2 & ADC_CR2_ADON)) { + } + + // Perform ADC3 calibration (optional) + // ADC3->CR2 |= ADC_CR2_CAL; + // while (ADC3->CR2 & ADC_CR2_CAL) { + // } +#endif +#if defined(ADC3) + // Enable the ADC3 clock + RCC->APB2ENR |= RCC_APB2ENR_ADC3EN; + + // Initialize ADC3 + ADC3->CR1 = 0; // Disable all channels + ADC3->CR2 = 0; // Clear CR2 register + + ADC3->CR1 &= ~(1 << 8); //SCAN mode disabled (Bit8) + ADC3->CR1 &= ~(3 << 24); //12bit resolution (Bit24,25 0b00) + ADC3->SQR1 = (1 << 20); //Set number of conversions projected (L[3:0] 0b0001) -> 1 conversion + ADC3->CR2 &= ~ADC_CR2_DMA; // Disable the DMA controller for ADC3 + ADC3->CR2 &= ~(1 << 1); //Single conversion + ADC3->CR2 &= ~(1 << 11); //Right alignment of data bits bit12....bit0 + ADC3->SQR1 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC3->SQR2 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + ADC3->SQR3 &= ~(0x3FFFFFFF); //Clear whole 1st 30bits in register + + // Enable the ADC + ADC3->CR2 |= ADC_CR2_ADON; + + // Wait for ADC3 to become ready (calibration complete) + while (!(ADC3->CR2 & ADC_CR2_ADON)) { + } + + // Perform ADC3 calibration (optional) + // ADC3->CR2 |= ADC_CR2_CAL; + // while (ADC3->CR2 & ADC_CR2_CAL) { + // } +#endif interrupts(); } #endif From 5d810a620b759cc8dfa7fff275b68d78c9767a0a Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 21 Sep 2023 16:05:35 +0800 Subject: [PATCH 071/310] STM32 variant support extension and tidy --- I2CManager_STM32.h | 6 ++-- platformio.ini | 79 +++++++++++++++++++++++++++++++++++++++++----- 2 files changed, 75 insertions(+), 10 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index cde4f20..86b9b74 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -37,9 +37,11 @@ * I2C bus, or more than one I2C bus on the STM32 architecture *****************************************************************************/ #if defined(I2C_USE_INTERRUPTS) && defined(ARDUINO_ARCH_STM32) -#if defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) +#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) || defined(ARDUINO_NUCLEO_F446RE) \ + || defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) \ + || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) // Assume I2C1 for now - default I2C bus on Nucleo-F411RE and likely all Nucleo-64 -// and Nucleo-144variants +// and Nucleo-144 variants I2C_TypeDef *s = I2C1; // In init we will ask the STM32 HAL layer for the configured APB1 clock frequency in Hz diff --git a/platformio.ini b/platformio.ini index ac2d598..8767ef1 100644 --- a/platformio.ini +++ b/platformio.ini @@ -31,7 +31,6 @@ include_dir = . [env] build_flags = -Wall -Wextra ; monitor_filters = time -; lib_deps = adafruit/Adafruit ST7735 and ST7789 Library @ ^1.10.0 [env:samd21-dev-usb] platform = atmelsam @@ -60,7 +59,7 @@ framework = arduino lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes -build_flags = -std=c++17 ; -DI2C_USE_WIRE -DDIAG_LOOPTIMES -DDIAG_IO +build_flags = -std=c++17 [env:mega2560-debug] platform = atmelavr @@ -72,7 +71,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES +build_flags = -DDIAG_IO=2 -DDIAG_LOOPTIMES [env:mega2560-no-HAL] platform = atmelavr @@ -84,7 +83,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = -DIO_NO_HAL +build_flags = -DIO_NO_HAL [env:mega2560-I2C-wire] platform = atmelavr @@ -108,7 +107,7 @@ lib_deps = SPI monitor_speed = 115200 monitor_echo = yes -build_flags = ; -DDIAG_LOOPTIMES +build_flags = [env:mega328] platform = atmelavr @@ -190,10 +189,75 @@ platform = ststm32 board = nucleo_f446re framework = arduino lib_deps = ${env.lib_deps} -build_flags = -std=c++17 -Os -g2 -Wunused-variable ; -DDIAG_LOOPTIMES ; -DDIAG_IO +build_flags = -std=c++17 -Os -g2 -Wunused-variable monitor_speed = 115200 monitor_echo = yes +; Experimental - no reason this should not work, but not +; tested as yet +; +[env:Nucleo-F401RE] +platform = ststm32 +board = nucleo_f401re +framework = arduino +lib_deps = ${env.lib_deps} +build_flags = -std=c++17 -Os -g2 -Wunused-variable +monitor_speed = 115200 +monitor_echo = yes + +; Commented out by default as the F13ZH has variant files +; but NOT the nucleo_f413zh.json file which needs to be +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F413ZH] +; platform = ststm32 +; board = nucleo_f413zh +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes + +; Commented out by default as the F446ZE needs variant files +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F446ZE] +; platform = ststm32 +; board = nucleo_f446ze +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes + +; Commented out by default as the F412ZG needs variant files +; installed before you can let PlatformIO see this +; +; [env:Nucleo-F412ZG] +; platform = ststm32 +; board = blah_f412zg +; framework = arduino +; lib_deps = ${env.lib_deps} +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes +; upload_protocol = stlink + +; Experimental - Ethernet work still in progress +; +; [env:Nucleo-F429ZI] +; platform = ststm32 +; board = nucleo_f429zi +; framework = arduino +; lib_deps = ${env.lib_deps} +; arduino-libraries/Ethernet @ ^2.0.1 +; stm32duino/STM32Ethernet @ ^1.3.0 +; stm32duino/STM32duino LwIP @ ^2.1.2 +; build_flags = -std=c++17 -Os -g2 -Wunused-variable +; monitor_speed = 115200 +; monitor_echo = yes +; upload_protocol = stlink + [env:Teensy3_2] platform = teensy board = teensy31 @@ -232,5 +296,4 @@ board = teensy41 framework = arduino build_flags = -std=c++17 -Os -g2 lib_deps = ${env.lib_deps} -lib_ignore = - +lib_ignore = From dfe3e9d42c590c6a821406f049df34f3094d51a1 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 21 Sep 2023 16:09:04 +0800 Subject: [PATCH 072/310] STM32 ADCee extensions --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 35d3f1a..f10ceee 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.7" +#define VERSION "5.1.8" +// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands From 8052090e0f1c47d7c87220cf1b925354539d1125 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Fri, 22 Sep 2023 17:03:40 +0100 Subject: [PATCH 073/310] Added Single Track Power On/Off Added power On/Off <> commands --- CommandDistributor.cpp | 4 +- CommandDistributor.h | 2 +- DCCEXParser.cpp | 51 ++++++++++++++++--- TrackManager.cpp | 111 +++++++++++++++++++++++++---------------- TrackManager.h | 9 ++-- 5 files changed, 121 insertions(+), 56 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index ee760b0..32f9874 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,6 +269,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter,dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format,trackLetter,pmode, dcAddr); } diff --git a/CommandDistributor.h b/CommandDistributor.h index a51d58a..99b9f1e 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter,int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 29c252d..150070c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -555,6 +555,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool main=false; bool prog=false; bool join=false; + bool singletrack=false; if (params > 1) break; if (params==0) { // All main=true; @@ -574,12 +575,28 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + uint8_t t = (p[0] - 'A'); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); + if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); + } else break; // will reply } TrackManager::setJoin(join); - if (main) TrackManager::setMainPower(POWERMODE::ON); - if (prog) TrackManager::setProgPower(POWERMODE::ON); - + if (!singletrack) { + if (main) TrackManager::setMainPower(POWERMODE::ON); + if (prog) TrackManager::setProgPower(POWERMODE::ON); + } CommandDistributor::broadcastPower(); return; } @@ -588,6 +605,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) { bool main=false; bool prog=false; + bool singletrack=false; if (params > 1) break; if (params==0) { // All main=true; @@ -601,17 +619,34 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> prog=true; } -#endif +#endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + uint8_t t = (p[0] - 'A'); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::SetMainTrackPower(POWERMODE::OFF, t); + if (prog) TrackManager::SetProgTrackPower(POWERMODE::OFF, t); + } + else break; // will reply } TrackManager::setJoin(false); + if (!singletrack) { if (main) TrackManager::setMainPower(POWERMODE::OFF); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setProgPower(POWERMODE::OFF); + if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setProgPower(POWERMODE::OFF); + } } - CommandDistributor::broadcastPower(); return; } diff --git a/TrackManager.cpp b/TrackManager.cpp index bd7c623..413fd95 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -353,32 +353,48 @@ void TrackManager::streamTrackState(Print* stream, byte t) { // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; auto format=F(""); + bool pstate = TrackManager::isPowerOn(t); + //char PMODE[] = "OFF"; + //if (pstate) PMODE="ON "; + //if (TrackManager::isPowerOn(t)) {char PMODE[] = "ON";} + // else {char PMODE[] = "OFF";} + switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - format=F("<= %c MAIN>\n"); + format=F("<= %c MAIN %c>\n"); break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: - format=F("<= %c PROG>\n"); + format=F("<= %c PROG %c>\n"); break; #endif case TRACK_MODE_NONE: - format=F("<= %c NONE>\n"); + format=F("<= %c NONE %c>\n"); break; case TRACK_MODE_EXT: - format=F("<= %c EXT>\n"); + format=F("<= %c EXT %c>\n"); break; case TRACK_MODE_DC: - format=F("<= %c DC %d>\n"); + format=F("<= %c DC %c %d>\n"); break; case TRACK_MODE_DCX: - format=F("<= %c DCX %d>\n"); + format=F("<= %c DCX %c %d>\n"); break; default: break; // unknown, dont care } - if (stream) StringFormatter::send(stream,format,'A'+t,trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,trackDCAddr[t]); + switch (pstate) { + case true: + if (stream) StringFormatter::send(stream,format,'A'+t,"ON", trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t,"ON", trackDCAddr[t]); + break; + case false: + if (stream) StringFormatter::send(stream,format,'A'+t,"OFF", trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t,"OFF", trackDCAddr[t]); + break; + } + //if (stream) StringFormatter::send(stream,format,'A'+t,PMODE, trackDCAddr[t]); + //else CommandDistributor::broadcastTrackState(format,'A'+t,PMODE, trackDCAddr[t]); } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -412,45 +428,51 @@ std::vectorTrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode) { +void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t thistrack) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - MotorDriver * driver=track[t]; - if (!driver) continue; - switch (track[t]->getMode()) { - case TRACK_MODE_MAIN: - if (setProg) break; - // toggle brake before turning power on - resets overcurrent error - // on the Pololu board if brake is wired to ^D2. - // XXX see if we can make this conditional - driver->setBrake(true); - driver->setBrake(false); // DCC runs with brake off - driver->setPower(mode); - break; - case TRACK_MODE_DC: - case TRACK_MODE_DCX: - if (setProg) break; - driver->setBrake(true); // DC starts with brake on - applyDCSpeed(t); // speed match DCC throttles - driver->setPower(mode); - break; - case TRACK_MODE_PROG: - if (!setProg) break; - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); - break; - case TRACK_MODE_EXT: - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); - break; - case TRACK_MODE_NONE: - break; + if (doall==false && thistrack != t) break; + MotorDriver * driver=track[t]; + if (!driver) continue; + switch (track[t]->getMode()) { + case TRACK_MODE_MAIN: + if (setProg) break; + // toggle brake before turning power on - resets overcurrent error + // on the Pololu board if brake is wired to ^D2. + // XXX see if we can make this conditional + driver->setBrake(true); + driver->setBrake(false); // DCC runs with brake off + driver->setPower(mode); + break; + case TRACK_MODE_DC: + case TRACK_MODE_DCX: + if (setProg) break; + driver->setBrake(true); // DC starts with brake on + applyDCSpeed(t); // speed match DCC throttles + driver->setPower(mode); + break; + case TRACK_MODE_PROG: + if (!setProg) break; + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); + break; + case TRACK_MODE_EXT: + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); + break; + case TRACK_MODE_NONE: + break; } + } } - + +// void TrackManager::setTrackPower(bool progTrack,POWERMODE mode, uint8_t track) { +// // write the code for this. +// } + POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) if (track[t]->getMode()==TRACK_MODE_PROG) @@ -526,3 +548,8 @@ bool TrackManager::isPowerOn(byte t) { return true; } +bool TrackManager::isProg(byte t) { + if (track[t]->getMode()==TRACK_MODE_PROG) + return true; + return false; +} \ No newline at end of file diff --git a/TrackManager.h b/TrackManager.h index 60d5f24..3f9c73f 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -60,10 +60,12 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vectorgetMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode); + static void setPower2(bool progTrack,POWERMODE mode, bool doall, uint8_t thistrack); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode);} + static void setMainPower(POWERMODE mode) {setPower2(false,mode,true,0);} + static void setProgPower(POWERMODE mode) {setPower2(true,mode,true,0);} + static void SetMainTrackPower(POWERMODE mode, uint8_t track) {setPower2(false,mode,false,track);} + static void SetProgTrackPower(POWERMODE mode, uint8_t track) {setPower2(true,mode,false,track);} static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); @@ -80,6 +82,7 @@ class TrackManager { static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); + static bool isProg(byte t); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From c9d4f5e94dc31fcdc0e55d53eeae3a89008ec783 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 15:56:09 +0100 Subject: [PATCH 074/310] Update IO_PCA9555.h --- IO_PCA9555.h | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index e493165..75f2c38 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -33,17 +33,16 @@ public: static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) { if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } - + +private: // Constructor - PCA9555(VPIN vpin, int nPins, uint8_t I2CAddress, int interruptPin=-1) + PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) : GPIOBase((FSH *)F("PCA9555"), vpin, nPins, I2CAddress, interruptPin) { requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer), outputBuffer, sizeof(outputBuffer)); outputBuffer[0] = REG_INPUT_P0; } - -private: void _writeGpioPort() override { I2CManager.write(_I2CAddress, 3, REG_OUTPUT_P0, _portOutputState, _portOutputState>>8); } From 6ad5326f1d1e44b8d17ffb5b3a7bd2312d9f7ae8 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 16:06:14 +0100 Subject: [PATCH 075/310] PCA9555 compiles and tested on PCA9548 mux IO_PCA9555.h added changes that had been applied to IO_MCP23017 for support on PCA9548 Mux. Constructor now also private and type casting of variables made the same for IO_PCA9555. Tested with MCP23017 and PCA9555 simultaneous on the same Mux Subbus --- IO_PCA9555.h | 1 + 1 file changed, 1 insertion(+) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index 75f2c38..607e1a8 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -34,6 +34,7 @@ public: if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } + private: // Constructor PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) From dab02ec65960764b750a0cd7bb2250f6b7315b97 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 16:10:16 +0100 Subject: [PATCH 076/310] Update IO_PCA9555.h Now compiles and works on PCA9548 Mux. Tested with MCP23017 and PCA9555 on the same Subbus --- IO_PCA9555.h | 1 - 1 file changed, 1 deletion(-) diff --git a/IO_PCA9555.h b/IO_PCA9555.h index 607e1a8..75f2c38 100644 --- a/IO_PCA9555.h +++ b/IO_PCA9555.h @@ -34,7 +34,6 @@ public: if (checkNoOverlap(vpin, nPins, i2cAddress)) new PCA9555(vpin,nPins, i2cAddress, interruptPin); } - private: // Constructor PCA9555(VPIN vpin, uint8_t nPins, I2CAddress I2CAddress, int interruptPin=-1) From d57b5ba537c86bd9c6d6963b196d0a7febe25424 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:09:01 +0100 Subject: [PATCH 077/310] Update version.h to 5.1.7 --- version.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/version.h b/version.h index f10ceee..9b7c8ef 100644 --- a/version.h +++ b/version.h @@ -3,9 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.8" -// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 -// 5.1.7 - Fix turntable broadcasts for non-movement activities and result +#define VERSION "5.1.7" +// 5.1.7 - IO_PCA9555.h fixed to work on PCA9548 Subbus, tested // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - , , - turntable commands From d07718be8cc34ffc852c771ba6cf4754eb7aebe8 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:18:59 +0100 Subject: [PATCH 078/310] Revert "Update version.h to 5.1.7" This reverts commit d57b5ba537c86bd9c6d6963b196d0a7febe25424. --- version.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/version.h b/version.h index 9b7c8ef..f10ceee 100644 --- a/version.h +++ b/version.h @@ -3,8 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.1.7" -// 5.1.7 - IO_PCA9555.h fixed to work on PCA9548 Subbus, tested +#define VERSION "5.1.8" +// 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 +// 5.1.7 - Fix turntable broadcasts for non-movement activities and result // 5.1.6 - STM32F4xx native I2C driver added // 5.1.5 - Added turntable object and EXRAIL commands // - , , - turntable commands From 11b9fd4ef56d417d3e73a81ea0c390cad7b02233 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 23 Sep 2023 20:25:10 +0100 Subject: [PATCH 079/310] Fixed IO_PCA9555.h to work with PCA9548 mux --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index f10ceee..b7c157b 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.8" +#define VERSION "5.1.9" +// 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK // 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and result // 5.1.6 - STM32F4xx native I2C driver added From aacb980dc873cc52742d5840aebb215ef0b573ce Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Sun, 24 Sep 2023 15:40:42 +0100 Subject: [PATCH 080/310] Power control plus EXRAIL Power Control <0 A> etc plus EXRAIL SET_POWER Not yet fully tested. --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- DCCEXParser.cpp | 18 ++++++++++------- EXRAIL2.cpp | 14 +++++++++++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 8 +++++++- TrackManager.cpp | 46 +++++++++++++++++------------------------- TrackManager.h | 15 +++++++++----- 9 files changed, 66 insertions(+), 45 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 32f9874..a521b52 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,6 +269,6 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter,pmode, dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); } diff --git a/CommandDistributor.h b/CommandDistributor.h index 99b9f1e..d54ef31 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter,char pmode, int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 150070c..9c94f82 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -576,7 +576,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - uint8_t t = (p[0] - 'A'); + byte t = (p[0] - 'A'); + DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -587,8 +588,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); - if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); + DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::ON, false, t); + if (main) TrackManager::setTrackPower(POWERMODE::ON, t); + //if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); + //if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); } else break; // will reply } @@ -621,8 +624,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - uint8_t t = (p[0] - 'A'); - if (TrackManager::isProg(t)) { + byte t = (p[0] - 'A'); + DIAG(F("Processing track - %d "), t); + if (TrackManager::isProg(t)) { main = false; prog = true; } @@ -632,8 +636,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::SetMainTrackPower(POWERMODE::OFF, t); - if (prog) TrackManager::SetProgTrackPower(POWERMODE::OFF, t); + DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::OFF, false, t); + if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); } else break; // will reply diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index d6d2597..07f4768 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -780,6 +780,20 @@ void RMFT2::loop2() { TrackManager::setJoin(false); CommandDistributor::broadcastPower(); break; + + case OPCODE_SET_POWER: + // operand is TRACK_POWER , trackid + + switch (operand) { + case TRACK_POWER_0: + TrackManager::setTrackPower(POWERMODE::OFF, getOperand(1)); + break; + case TRACK_POWER_1: + TrackManager::setTrackPower(POWERMODE::ON, getOperand(1)); + break; + } + + break; case OPCODE_SET_TRACK: // operand is trackmode<<8 | track id diff --git a/EXRAIL2.h b/EXRAIL2.h index 8af36d2..ad399ec 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -59,7 +59,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ROSTER,OPCODE_KILLALL, OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE, OPCODE_ENDTASK,OPCODE_ENDEXRAIL, - OPCODE_SET_TRACK, + OPCODE_SET_TRACK,OPCODE_SET_POWER, OPCODE_ONRED,OPCODE_ONAMBER,OPCODE_ONGREEN, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 11c598b..03e310e 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -138,6 +138,7 @@ #undef SERVO_SIGNAL #undef SET #undef SET_TRACK +#undef SET_POWER #undef SETLOCO #undef SIGNAL #undef SIGNALH @@ -275,6 +276,7 @@ #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) #define SET(pin) #define SET_TRACK(track,mode) +#define SET_POWER(track,onoff) #define SETLOCO(loco) #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 0784242..62b852a 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -63,6 +63,11 @@ // (10#mins)%100) #define STRIP_ZERO(value) 10##value%100 +// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF). +//const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0; +//const byte TRACK_POWER_1=1, TRACK_POWER_ON=1; + + // Pass 1 Implements aliases #include "EXRAIL2MacroReset.h" #undef ALIAS @@ -407,11 +412,12 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile), #define SET(pin) OPCODE_SET,V(pin), #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), +#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff, TRACK_NUMBER_##track), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco), #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) OPCODE_SPEED,V(speed), -#define START(route) OPCODE_START,V(route), +#define START(route) OPCODE_START,V(route), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL diff --git a/TrackManager.cpp b/TrackManager.cpp index 413fd95..ad7ef6a 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -354,47 +354,32 @@ void TrackManager::streamTrackState(Print* stream, byte t) { if (track[t]==NULL) return; auto format=F(""); bool pstate = TrackManager::isPowerOn(t); - //char PMODE[] = "OFF"; - //if (pstate) PMODE="ON "; - //if (TrackManager::isPowerOn(t)) {char PMODE[] = "ON";} - // else {char PMODE[] = "OFF";} - switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - format=F("<= %c MAIN %c>\n"); + if (pstate) {format=F("<= %c MAIN ON \n");} else {format = F("<= %c MAIN OFF \n");} break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: - format=F("<= %c PROG %c>\n"); + if (pstate) {format=F("<= %c PROG ON>\n");} else {format=F("<= %c PROG OFF>\n");} break; #endif case TRACK_MODE_NONE: - format=F("<= %c NONE %c>\n"); + if (pstate) {format=F("<= %c NONE %ON>\n");} else {format=F("<= %c NONE %OFF>\n");} break; case TRACK_MODE_EXT: - format=F("<= %c EXT %c>\n"); + if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} break; case TRACK_MODE_DC: - format=F("<= %c DC %c %d>\n"); + if (pstate) {format=F("<= %c DC ON %d>\n");} else {format=F("<= %c DC OFF %d>\n");} break; case TRACK_MODE_DCX: - format=F("<= %c DCX %c %d>\n"); + if (pstate) {format=F("<= %c DCX ON %d>\n");} else {format=F("<= %c DCX OFF %d>\n");} break; default: break; // unknown, dont care } - switch (pstate) { - case true: - if (stream) StringFormatter::send(stream,format,'A'+t,"ON", trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,"ON", trackDCAddr[t]); - break; - case false: - if (stream) StringFormatter::send(stream,format,'A'+t,"OFF", trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t,"OFF", trackDCAddr[t]); - break; - } - //if (stream) StringFormatter::send(stream,format,'A'+t,PMODE, trackDCAddr[t]); - //else CommandDistributor::broadcastTrackState(format,'A'+t,PMODE, trackDCAddr[t]); + if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -428,10 +413,9 @@ std::vectorTrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t thistrack) { +void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - if (doall==false && thistrack != t) break; MotorDriver * driver=track[t]; if (!driver) continue; switch (track[t]->getMode()) { @@ -469,9 +453,15 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode, bool doall, uint8_t th } } -// void TrackManager::setTrackPower(bool progTrack,POWERMODE mode, uint8_t track) { -// // write the code for this. -// } +void TrackManager::setTrackPower(POWERMODE mode, byte thistrack) { + + DIAG(F("SetPower Processing Track %d"), thistrack); + MotorDriver * driver=track[thistrack]; + if (!driver) return; + + driver->setPower(mode); + + } POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) diff --git a/TrackManager.h b/TrackManager.h index 3f9c73f..c6eea5c 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -39,6 +39,10 @@ const byte TRACK_NUMBER_5=5, TRACK_NUMBER_F=5; const byte TRACK_NUMBER_6=6, TRACK_NUMBER_G=6; const byte TRACK_NUMBER_7=7, TRACK_NUMBER_H=7; +// These constants help EXRAIL macros convert Track Power e.g. SET_POWER(A ON|OFF). +const byte TRACK_POWER_0=0, TRACK_POWER_OFF=0; +const byte TRACK_POWER_1=1, TRACK_POWER_ON=1; + class TrackManager { public: static void Setup(const FSH * shieldName, @@ -60,12 +64,13 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vectorgetMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode, bool doall, uint8_t thistrack); + static void setTrackPower(POWERMODE mode, byte thistrack); + static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode,true,0);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode,true,0);} - static void SetMainTrackPower(POWERMODE mode, uint8_t track) {setPower2(false,mode,false,track);} - static void SetProgTrackPower(POWERMODE mode, uint8_t track) {setPower2(true,mode,false,track);} + static void setMainPower(POWERMODE mode) {setPower2(false,mode);} + static void setProgPower(POWERMODE mode) {setPower2(true,mode);} + + static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); From 5a7f278b1e94251a971eb65bd49da48cc722c29d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 24 Sep 2023 20:54:17 +0200 Subject: [PATCH 081/310] correct return when requesting D RAM --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 29c252d..c9f31f0 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1057,7 +1057,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) case HASH_KEYWORD_RAM: // StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); - break; + return true; #ifndef DISABLE_PROG case HASH_KEYWORD_ACK: // From 624656ebc97a60df1c8085fda0fd9e8cb4d33b99 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 24 Sep 2023 20:56:27 +0200 Subject: [PATCH 082/310] date tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 98afa03..d46ef22 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202308302157Z" +#define GITHUB_SHA "devel-202309241855Z" From 9e3ae21bb8fc26e25b5e448498217cea53159207 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Mon, 25 Sep 2023 09:59:17 +0100 Subject: [PATCH 083/310] Change to EXRAIL Set_Power Change to EXRAIL SET_Power --- DCCEXParser.cpp | 6 +----- EXRAILMacros.h | 2 +- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9c94f82..a8c257b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -588,10 +588,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::ON, false, t); if (main) TrackManager::setTrackPower(POWERMODE::ON, t); - //if (main) TrackManager::SetMainTrackPower(POWERMODE::ON, t); - //if (prog) TrackManager::SetProgTrackPower(POWERMODE::ON, t); } else break; // will reply } @@ -622,7 +619,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> prog=true; } -#endif +#endif <= else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> byte t = (p[0] - 'A'); DIAG(F("Processing track - %d "), t); @@ -636,7 +633,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - DIAG(F("Calling SetPower %d - %d - %d"), POWERMODE::OFF, false, t); if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); } diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 62b852a..b85b68a 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -412,7 +412,7 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define SERVO_TURNOUT(id,pin,activeAngle,inactiveAngle,profile,description...) OPCODE_SERVOTURNOUT,V(id),OPCODE_PAD,V(pin),OPCODE_PAD,V(activeAngle),OPCODE_PAD,V(inactiveAngle),OPCODE_PAD,V(PCA9685::ProfileType::profile), #define SET(pin) OPCODE_SET,V(pin), #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), -#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff, TRACK_NUMBER_##track), +#define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco), #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) From 17c004aecf558baa980bf9bb620cd7e456cf7969 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Mon, 25 Sep 2023 14:32:54 +0100 Subject: [PATCH 084/310] Code corrections code corrections --- DCCEXParser.cpp | 37 ++++++++++++++++--------- EXRAIL2.cpp | 6 ++--- TrackManager.cpp | 70 +++++++++++++++++++++++++++++++++++------------- TrackManager.h | 2 +- 4 files changed, 81 insertions(+), 34 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a8c257b..a68b398 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -556,6 +556,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool prog=false; bool join=false; bool singletrack=false; + byte t=0; if (params > 1) break; if (params==0) { // All main=true; @@ -576,8 +577,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - byte t = (p[0] - 'A'); - DIAG(F("Processing track - %d "), t); + t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -588,7 +589,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::setTrackPower(POWERMODE::ON, t); + } else break; // will reply } @@ -597,6 +598,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (main) TrackManager::setMainPower(POWERMODE::ON); if (prog) TrackManager::setProgPower(POWERMODE::ON); } + else { + if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); + if (prog) { + TrackManager::setTrackPower(true, POWERMODE::ON, t); + } + } CommandDistributor::broadcastPower(); return; } @@ -606,6 +613,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) bool main=false; bool prog=false; bool singletrack=false; + byte t=0; if (params > 1) break; if (params==0) { // All main=true; @@ -621,8 +629,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } #endif <= else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - byte t = (p[0] - 'A'); - DIAG(F("Processing track - %d "), t); + t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; prog = true; @@ -632,24 +640,29 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) main=true; prog=false; } - singletrack=true; - if (main) TrackManager::setTrackPower(POWERMODE::OFF, t); - } - + singletrack=true; + } else break; // will reply } TrackManager::setJoin(false); if (!singletrack) { - if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setProgPower(POWERMODE::OFF); + } + } + else { + if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setProgPower(POWERMODE::OFF); + TrackManager::setTrackPower(true, POWERMODE::OFF, t); } } CommandDistributor::broadcastPower(); return; - } + } case '!': // ESTOP ALL DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 07f4768..8fd9532 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -783,13 +783,13 @@ void RMFT2::loop2() { case OPCODE_SET_POWER: // operand is TRACK_POWER , trackid - + //byte thistrack=getOperand(1); switch (operand) { case TRACK_POWER_0: - TrackManager::setTrackPower(POWERMODE::OFF, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::OFF, getOperand(1)); break; case TRACK_POWER_1: - TrackManager::setTrackPower(POWERMODE::ON, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::ON, getOperand(1)); break; } diff --git a/TrackManager.cpp b/TrackManager.cpp index ad7ef6a..d653645 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -364,16 +364,16 @@ void TrackManager::streamTrackState(Print* stream, byte t) { break; #endif case TRACK_MODE_NONE: - if (pstate) {format=F("<= %c NONE %ON>\n");} else {format=F("<= %c NONE %OFF>\n");} + if (pstate) {format=F("<= %c NONE ON>\n");} else {format=F("<= %c NONE OFF>\n");} break; case TRACK_MODE_EXT: if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} break; case TRACK_MODE_DC: - if (pstate) {format=F("<= %c DC ON %d>\n");} else {format=F("<= %c DC OFF %d>\n");} + if (pstate) {format=F("<= %c DC %d ON>\n");} else {format=F("<= %c DC %d OFF>\n");} break; case TRACK_MODE_DCX: - if (pstate) {format=F("<= %c DCX ON %d>\n");} else {format=F("<= %c DCX OFF %d>\n");} + if (pstate) {format=F("<= %c DCX %d ON>\n");} else {format=F("<= %c DCX %d OFF>\n");} break; default: break; // unknown, dont care @@ -416,9 +416,51 @@ std::vectorTrackManager::getMainDrivers() { void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - MotorDriver * driver=track[t]; - if (!driver) continue; - switch (track[t]->getMode()) { + TrackManager::setTrackPower(setProg, mode, t); + // MotorDriver * driver=track[t]; + // if (!driver) continue; + // switch (track[t]->getMode()) { + // case TRACK_MODE_MAIN: + // if (setProg) break; + // // toggle brake before turning power on - resets overcurrent error + // // on the Pololu board if brake is wired to ^D2. + // // XXX see if we can make this conditional + // driver->setBrake(true); + // driver->setBrake(false); // DCC runs with brake off + // driver->setPower(mode); + // break; + // case TRACK_MODE_DC: + // case TRACK_MODE_DCX: + // if (setProg) break; + // driver->setBrake(true); // DC starts with brake on + // applyDCSpeed(t); // speed match DCC throttles + // driver->setPower(mode); + // break; + // case TRACK_MODE_PROG: + // if (!setProg) break; + // driver->setBrake(true); + // driver->setBrake(false); + // driver->setPower(mode); + // break; + // case TRACK_MODE_EXT: + // driver->setBrake(true); + // driver->setBrake(false); + // driver->setPower(mode); + // break; + // case TRACK_MODE_NONE: + // break; + // } + + } +} + +void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { + + DIAG(F("SetTrackPower Processing Track %d"), thistrack); + MotorDriver * driver=track[thistrack]; + if (!driver) return; + + switch (track[thistrack]->getMode()) { case TRACK_MODE_MAIN: if (setProg) break; // toggle brake before turning power on - resets overcurrent error @@ -432,7 +474,7 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) { case TRACK_MODE_DCX: if (setProg) break; driver->setBrake(true); // DC starts with brake on - applyDCSpeed(t); // speed match DCC throttles + applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); break; case TRACK_MODE_PROG: @@ -449,17 +491,9 @@ void TrackManager::setPower2(bool setProg,POWERMODE mode) { case TRACK_MODE_NONE: break; } - - } -} - -void TrackManager::setTrackPower(POWERMODE mode, byte thistrack) { - - DIAG(F("SetPower Processing Track %d"), thistrack); - MotorDriver * driver=track[thistrack]; - if (!driver) return; - - driver->setPower(mode); + if (mode == POWERMODE::ON) {DIAG(F("Power Track %d ON"), thistrack);} + else {DIAG(F("Power Track %d OFF"), thistrack);} + //driver->setPower(mode); } diff --git a/TrackManager.h b/TrackManager.h index c6eea5c..39f708a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -64,7 +64,7 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vectorgetMainDrivers(); #endif - static void setTrackPower(POWERMODE mode, byte thistrack); + static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} static void setMainPower(POWERMODE mode) {setPower2(false,mode);} From 2a46b960838e3d96e4577001afb24bd3ae7f8016 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Tue, 26 Sep 2023 18:02:39 +0100 Subject: [PATCH 085/310] Updates to power Updates to powere routines and EXRAIL --- DCCEXParser.cpp | 175 +++++++++++++++++++++++++---------------------- TrackManager.cpp | 59 +++++----------- TrackManager.h | 5 +- 3 files changed, 114 insertions(+), 125 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a68b398..aee7e05 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -552,84 +552,88 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case '1': // POWERON <1 [MAIN|PROG|JOIN]> { - bool main=false; - bool prog=false; - bool join=false; - bool singletrack=false; - byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> - main=true; - } + bool main=false; + bool prog=false; + bool join=false; + bool singletrack=false; + //byte t=0; + if (params > 1) break; + if (params==0) { // All + main=true; + prog=true; + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> + main=true; + } #ifndef DISABLE_PROG - else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> - main=true; - prog=true; - join=true; - } - else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> - prog=true; - } + else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> + main=true; + prog=true; + join=true; + } + else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> + prog=true; + } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - t = (p[0] - 'A'); - //DIAG(F("Processing track - %d "), t); - if (TrackManager::isProg(t)) { - main = false; - prog = true; - } - else - { - main=true; - prog=false; - } - singletrack=true; + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + byte t = (p[0] - 'A'); + //DIAG(F("Processing track - %d "), t); + if (TrackManager::isProg(t)) { + main = false; + prog = true; + } + else + { + main=true; + prog=false; + } + singletrack=true; + if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); + if (prog) TrackManager::setTrackPower(true, POWERMODE::ON, t); + //CommandDistributor::broadcastPower(); + //TrackManager::streamTrackState(stream, t); + TrackManager::streamTrackState(NULL,t); + StringFormatter::send(stream, F("Track %d ON\n"), t); + return; + } + + else break; // will reply + } - } - else break; // will reply - } - TrackManager::setJoin(join); if (!singletrack) { + TrackManager::setJoin(join); if (main) TrackManager::setMainPower(POWERMODE::ON); if (prog) TrackManager::setProgPower(POWERMODE::ON); - } - else { - if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); - if (prog) { - TrackManager::setTrackPower(true, POWERMODE::ON, t); + CommandDistributor::broadcastPower(); + + return; } - } - CommandDistributor::broadcastPower(); - return; + } case '0': // POWEROFF <0 [MAIN | PROG] > { - bool main=false; - bool prog=false; - bool singletrack=false; - byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> - main=true; - } + bool main=false; + bool prog=false; + bool singletrack=false; + //byte t=0; + if (params > 1) break; + if (params==0) { // All + main=true; + prog=true; + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> + main=true; + } #ifndef DISABLE_PROG - else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> - prog=true; - } -#endif <= - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - t = (p[0] - 'A'); + else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> + prog=true; + } +#endif + else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { main = false; @@ -640,28 +644,33 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) main=true; prog=false; } - singletrack=true; - } - else break; // will reply - } - - TrackManager::setJoin(false); - if (!singletrack) { - if (main) TrackManager::setMainPower(POWERMODE::OFF); + singletrack=true; + TrackManager::setJoin(false); + if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); if (prog) { + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setTrackPower(true, POWERMODE::OFF, t); + CommandDistributor::broadcastPower(); + } + StringFormatter::send(stream, F("Track %d OFF\n"), t); + TrackManager::streamTrackState(NULL, t); + return; + } + + else break; // will reply + } + + if (!singletrack) { + TrackManager::setJoin(false); + + if (main) TrackManager::setMainPower(POWERMODE::OFF); + if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off TrackManager::setProgPower(POWERMODE::OFF); } - } - else { - if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, POWERMODE::OFF, t); - } + CommandDistributor::broadcastPower(); + return; } - CommandDistributor::broadcastPower(); - return; } case '!': // ESTOP ALL diff --git a/TrackManager.cpp b/TrackManager.cpp index d653645..f66fb4d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -26,7 +26,8 @@ #include "MotorDriver.h" #include "DCCTimer.h" #include "DIAG.h" -#include"CommandDistributor.h" +#include "CommandDistributor.h" +#include "DCCEXParser.h" // Virtualised Motor shield multi-track hardware Interface #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) @@ -319,6 +320,7 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) FOR_EACH_TRACK(t) streamTrackState(stream,t); return true; + } p[0]-=HASH_KEYWORD_A; // convert A... to 0.... @@ -378,8 +380,10 @@ void TrackManager::streamTrackState(Print* stream, byte t) { default: break; // unknown, dont care } - if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + + if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + } byte TrackManager::nextCycleTrack=MAX_TRACKS; @@ -416,47 +420,16 @@ std::vectorTrackManager::getMainDrivers() { void TrackManager::setPower2(bool setProg,POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { + TrackManager::setTrackPower(setProg, mode, t); - // MotorDriver * driver=track[t]; - // if (!driver) continue; - // switch (track[t]->getMode()) { - // case TRACK_MODE_MAIN: - // if (setProg) break; - // // toggle brake before turning power on - resets overcurrent error - // // on the Pololu board if brake is wired to ^D2. - // // XXX see if we can make this conditional - // driver->setBrake(true); - // driver->setBrake(false); // DCC runs with brake off - // driver->setPower(mode); - // break; - // case TRACK_MODE_DC: - // case TRACK_MODE_DCX: - // if (setProg) break; - // driver->setBrake(true); // DC starts with brake on - // applyDCSpeed(t); // speed match DCC throttles - // driver->setPower(mode); - // break; - // case TRACK_MODE_PROG: - // if (!setProg) break; - // driver->setBrake(true); - // driver->setBrake(false); - // driver->setPower(mode); - // break; - // case TRACK_MODE_EXT: - // driver->setBrake(true); - // driver->setBrake(false); - // driver->setPower(mode); - // break; - // case TRACK_MODE_NONE: - // break; - // } } + return; } void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { - DIAG(F("SetTrackPower Processing Track %d"), thistrack); + //DIAG(F("SetTrackPower Processing Track %d"), thistrack); MotorDriver * driver=track[thistrack]; if (!driver) return; @@ -491,16 +464,22 @@ void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { case TRACK_MODE_NONE: break; } - if (mode == POWERMODE::ON) {DIAG(F("Power Track %d ON"), thistrack);} - else {DIAG(F("Power Track %d OFF"), thistrack);} - //driver->setPower(mode); } + void TrackManager::reportPowerChange(Print* stream, byte thistrack) { + // This function is for backward JMRI compatibility only + // It reports the first track only, as main, regardless of track settings. + // + int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); + StringFormatter::send(stream, F("\n"), + track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); +} + POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) if (track[t]->getMode()==TRACK_MODE_PROG) - return track[t]->getPower(); + return track[t]->getPower(); return POWERMODE::OFF; } diff --git a/TrackManager.h b/TrackManager.h index 39f708a..cf2d54b 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -64,12 +64,12 @@ class TrackManager { #ifdef ARDUINO_ARCH_ESP32 static std::vectorgetMainDrivers(); #endif - static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); + static void setPower2(bool progTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} static void setMainPower(POWERMODE mode) {setPower2(false,mode);} static void setProgPower(POWERMODE mode) {setPower2(true,mode);} - + static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); static const int16_t MAX_TRACKS=8; @@ -84,6 +84,7 @@ class TrackManager { static void sampleCurrent(); static void reportGauges(Print* stream); static void reportCurrent(Print* stream); + static void reportPowerChange(Print* stream, byte thistrack); static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); From 25bbfa4c6805bf03cdb188d6d7d3457eec9b642b Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Wed, 27 Sep 2023 14:46:48 +0100 Subject: [PATCH 086/310] Fix <1 JOIN> Fixed <1 JOIN> issue in TrackManager --- DCCEXParser.cpp | 15 +++++++++------ EXRAIL2.cpp | 4 ++-- TrackManager.cpp | 18 ++++++++++-------- TrackManager.h | 9 +++++---- 4 files changed, 26 insertions(+), 20 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aee7e05..c82175b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -589,8 +589,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=false; } singletrack=true; - if (main) TrackManager::setTrackPower(false, POWERMODE::ON, t); - if (prog) TrackManager::setTrackPower(true, POWERMODE::ON, t); + if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t); + if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t); //CommandDistributor::broadcastPower(); //TrackManager::streamTrackState(stream, t); TrackManager::streamTrackState(NULL,t); @@ -603,8 +603,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (!singletrack) { TrackManager::setJoin(join); - if (main) TrackManager::setMainPower(POWERMODE::ON); - if (prog) TrackManager::setProgPower(POWERMODE::ON); + if (join) TrackManager::setJoinPower(POWERMODE::ON); + else { + if (main) TrackManager::setMainPower(POWERMODE::ON); + if (prog) TrackManager::setProgPower(POWERMODE::ON); + } CommandDistributor::broadcastPower(); return; @@ -646,10 +649,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } singletrack=true; TrackManager::setJoin(false); - if (main) TrackManager::setTrackPower(false, POWERMODE::OFF, t); + if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, POWERMODE::OFF, t); + TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); CommandDistributor::broadcastPower(); } StringFormatter::send(stream, F("Track %d OFF\n"), t); diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 8fd9532..321872d 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -786,10 +786,10 @@ void RMFT2::loop2() { //byte thistrack=getOperand(1); switch (operand) { case TRACK_POWER_0: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::OFF, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::OFF, getOperand(1)); break; case TRACK_POWER_1: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), POWERMODE::ON, getOperand(1)); + TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::ON, getOperand(1)); break; } diff --git a/TrackManager.cpp b/TrackManager.cpp index f66fb4d..dd27d85 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -417,17 +417,17 @@ std::vectorTrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,POWERMODE mode) { +void TrackManager::setPower2(bool setProg,bool setJoin, POWERMODE mode) { if (!setProg) mainPowerGuess=mode; FOR_EACH_TRACK(t) { - TrackManager::setTrackPower(setProg, mode, t); + TrackManager::setTrackPower(setProg, setJoin, mode, t); } return; } -void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { +void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack) { //DIAG(F("SetTrackPower Processing Track %d"), thistrack); MotorDriver * driver=track[thistrack]; @@ -445,21 +445,23 @@ void TrackManager::setTrackPower(bool setProg, POWERMODE mode, byte thistrack) { break; case TRACK_MODE_DC: case TRACK_MODE_DCX: - if (setProg) break; + DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); + if (setProg || setJoin) {DIAG(F("Nowt to do")); break;} driver->setBrake(true); // DC starts with brake on applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); + DIAG(F("Doing it anyway")); break; case TRACK_MODE_PROG: - if (!setProg) break; + if (!setProg && !setJoin) break; driver->setBrake(true); driver->setBrake(false); driver->setPower(mode); break; case TRACK_MODE_EXT: - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); + driver->setBrake(true); + driver->setBrake(false); + driver->setPower(mode); break; case TRACK_MODE_NONE: break; diff --git a/TrackManager.h b/TrackManager.h index cf2d54b..21b8d59 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -65,11 +65,12 @@ class TrackManager { static std::vectorgetMainDrivers(); #endif - static void setPower2(bool progTrack,POWERMODE mode); + static void setPower2(bool progTrack,bool joinTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,mode);} - static void setProgPower(POWERMODE mode) {setPower2(true,mode);} - static void setTrackPower(bool setProg, POWERMODE mode, byte thistrack); + static void setMainPower(POWERMODE mode) {setPower2(false,false,mode);} + static void setProgPower(POWERMODE mode) {setPower2(true,false,mode);} + static void setJoinPower(POWERMODE mode) {setPower2(false,true,mode);} + static void setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack); static const int16_t MAX_TRACKS=8; From ed0cfee0910fd37a78f0996ccfb2d0c2d2c88236 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 28 Sep 2023 17:43:22 +0800 Subject: [PATCH 087/310] STM32 DCCEXanalogWrite for TrackManager PWM --- DCCTimerSTM32.cpp | 117 ++++++++++++++++++++++++++++++++++++++++------ MotorDriver.cpp | 66 ++++++++++++++++++++++++-- MotorDriver.h | 38 +++++++++++---- TrackManager.cpp | 12 +++++ version.h | 7 ++- 5 files changed, 214 insertions(+), 26 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f57499a..0f9c432 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -1,6 +1,6 @@ /* * © 2023 Neil McKechnie - * © 2022-23 Paul M. Antoine + * © 2022-2023 Paul M. Antoine * © 2021 Mike S * © 2021, 2023 Harald Barth * © 2021 Fred Decker @@ -154,13 +154,28 @@ HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 /////////////////////////////////////////////////////////////////////////////////////////////// INTERRUPT_CALLBACK interruptHandler=0; -// Let's use STM32's timer #11 until disabused of this notion -// Timer #11 is used for "servo" library, but as DCC-EX is not using -// this libary, we should be free and clear. -HardwareTimer timer(TIM11); + +// On STM32F4xx models that have them, Timers 6 and 7 have no PWM output capability, +// so are good choices for general timer duties - they are used for tone and servo +// in stm32duino so we shall usurp those as DCC-EX doesn't use tone or servo libs. +// NB: the F401, F410 and F411 do **not** have Timer 6 or 7, so we use Timer 11 +#ifndef DCC_EX_TIMER +#if defined(TIM6) +#define DCC_EX_TIMER TIM6 +#elif defined(TIM7) +#define DCC_EX_TIMER TIM7 +#elif defined(TIM11) +#define DCC_EX_TIMER TIM11 +#else +#warning This STM32F4XX variant does not have Timers 6,7 or 11!! +#endif +#endif // ifndef DCC_EX_TIMER + +HardwareTimer dcctimer(DCC_EX_TIMER); +void DCCTimer_Handler() __attribute__((interrupt)); // Timer IRQ handler -void Timer11_Handler() { +void DCCTimer_Handler() { interruptHandler(); } @@ -168,22 +183,24 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interruptHandler=callback; noInterrupts(); - // adc_set_sample_rate(ADC_SAMPLETIME_480CYCLES); - timer.pause(); - timer.setPrescaleFactor(1); + dcctimer.pause(); + dcctimer.setPrescaleFactor(1); // timer.setOverflow(CLOCK_CYCLES * 2); - timer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); - timer.attachInterrupt(Timer11_Handler); - timer.refresh(); - timer.resume(); + dcctimer.setOverflow(DCC_SIGNAL_TIME, MICROSEC_FORMAT); + // dcctimer.attachInterrupt(Timer11_Handler); + dcctimer.attachInterrupt(DCCTimer_Handler); + dcctimer.setInterruptPriority(0, 0); // Set highest preemptive priority! + dcctimer.refresh(); + dcctimer.resume(); interrupts(); } bool DCCTimer::isPWMPin(byte pin) { - //TODO: SAMD whilst this call to digitalPinHasPWM will reveal which pins can do PWM, + //TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, // there's no support yet for High Accuracy, so for now return false // return digitalPinHasPWM(pin); + (void) pin; return false; } @@ -235,6 +252,78 @@ void DCCTimer::reset() { while(true) {}; } +// TODO: rationalise the size of these... could really use sparse arrays etc. +static HardwareTimer * pin_timer[100] = {0}; +static uint32_t channel_frequency[100] = {0}; +static uint32_t pin_channel[100] = {0}; + +// Using the HardwareTimer library API included in stm32duino core to handle PWM duties +// TODO: in order to use the HA code above which Neil kindly wrote, we may have to do something more +// sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones +// currently used for HA so they don't interfere with one another. For now we'll just make PWM +// work well... then work backwards to integrate with HA mode if we can. +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) +{ + if (pin_timer[pin] == NULL) { + // Automatically retrieve TIM instance and channel associated to pin + // This is used to be compatible with all STM32 series automatically. + TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM); + if (Instance == NULL) { + // We shouldn't get here (famous last words) as it ought to have been caught by brakeCanPWM()! + DIAG(F("DCCEXanalogWriteFrequency::Pin %d has no PWM function!"), pin); + return; + } + pin_channel[pin] = STM_PIN_CHANNEL(pinmap_function(digitalPinToPinName(pin), PinMap_PWM)); + + // Instantiate HardwareTimer object. Thanks to 'new' instantiation, + // HardwareTimer is not destructed when setup function is finished. + pin_timer[pin] = new HardwareTimer(Instance); + // Configure and start PWM + // MyTim->setPWM(channel, pin, 5, 10, NULL, NULL); // No callback required, we can simplify the function call + if (pin_timer[pin] != NULL) + { + pin_timer[pin]->setPWM(pin_channel[pin], pin, frequency, 0); // set frequency in Hertz, 0% dutycycle + DIAG(F("DCCEXanalogWriteFrequency::Pin %d on Timer %d, frequency %d"), pin, pin_channel[pin], frequency); + } + else + DIAG(F("DCCEXanalogWriteFrequency::failed to allocate HardwareTimer instance!")); + } + else + { + // Frequency change request + if (frequency != channel_frequency[pin]) + { + pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! + pin_timer[pin]->setOverflow(frequency, HERTZ_FORMAT); // Just change the frequency if it's already running! + DIAG(F("DCCEXanalogWriteFrequency::setting frequency to %d"), frequency); + } + } + channel_frequency[pin] = frequency; + return; +} + +void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { + // Calculate percentage duty cycle from value given + uint32_t duty_cycle = (value * 100 / 256) + 1; + if (pin_timer[pin] != NULL) { + if (duty_cycle == 100) + { + pin_timer[pin]->pauseChannel(pin_channel[pin]); + DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); + } + else + { + pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! + pin_timer[pin]->resumeChannel(pin_channel[pin]); + pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle + DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle); + } + } + else + DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin); +} + + // Now we can handle more ADCs, maybe this works! #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 4644ad5..61e229f 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -34,6 +34,11 @@ unsigned long MotorDriver::globalOverloadStart = 0; volatile portreg_t shadowPORTA; volatile portreg_t shadowPORTB; volatile portreg_t shadowPORTC; +#if defined(ARDUINO_ARCH_STM32) +volatile portreg_t shadowPORTD; +volatile portreg_t shadowPORTE; +volatile portreg_t shadowPORTF; +#endif MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin, byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) { @@ -68,6 +73,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin.shadowinout = fastSignalPin.inout; fastSignalPin.inout = &shadowPORTC; } + if (HAVE_PORTD(fastSignalPin.inout == &PORTD)) { + DIAG(F("Found PORTD pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTD; + } + if (HAVE_PORTE(fastSignalPin.inout == &PORTE)) { + DIAG(F("Found PORTE pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTE; + } + if (HAVE_PORTF(fastSignalPin.inout == &PORTF)) { + DIAG(F("Found PORTF pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTF; + } signalPin2=signal_pin2; if (signalPin2!=UNUSED_PIN) { @@ -91,6 +111,21 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin2.shadowinout = fastSignalPin2.inout; fastSignalPin2.inout = &shadowPORTC; } + if (HAVE_PORTD(fastSignalPin2.inout == &PORTD)) { + DIAG(F("Found PORTD pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTD; + } + if (HAVE_PORTE(fastSignalPin2.inout == &PORTE)) { + DIAG(F("Found PORTE pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTE; + } + if (HAVE_PORTF(fastSignalPin2.inout == &PORTF)) { + DIAG(F("Found PORTF pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTF; + } } else dualSignal=false; @@ -279,7 +314,7 @@ void MotorDriver::startCurrentFromHW() { #pragma GCC pop_options #endif //ANALOG_READ_INTERRUPT -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) #ifdef VARIABLE_TONES uint16_t taurustones[28] = { 165, 175, 196, 220, 247, 262, 294, 330, @@ -330,7 +365,7 @@ void MotorDriver::setDCSignal(byte speedcode) { byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127 byte tDir=speedcode & 0x80; byte brake; -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) { int f = 131; #ifdef VARIABLE_TONES @@ -348,7 +383,7 @@ void MotorDriver::setDCSignal(byte speedcode) { else brake = 2 * (128-tSpeed); if (invertBrake) brake=255-brake; -#if defined(ARDUINO_ARCH_ESP32) +#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) DCCTimer::DCCEXanalogWrite(brakePin,brake); #else analogWrite(brakePin,brake); @@ -372,6 +407,24 @@ void MotorDriver::setDCSignal(byte speedcode) { setSignal(tDir); HAVE_PORTC(PORTC=shadowPORTC); interrupts(); + } else if (HAVE_PORTD(fastSignalPin.shadowinout == &PORTD)) { + noInterrupts(); + HAVE_PORTD(shadowPORTD=PORTD); + setSignal(tDir); + HAVE_PORTD(PORTD=shadowPORTD); + interrupts(); + } else if (HAVE_PORTE(fastSignalPin.shadowinout == &PORTE)) { + noInterrupts(); + HAVE_PORTE(shadowPORTE=PORTE); + setSignal(tDir); + HAVE_PORTE(PORTE=shadowPORTE); + interrupts(); + } else if (HAVE_PORTF(fastSignalPin.shadowinout == &PORTF)) { + noInterrupts(); + HAVE_PORTF(shadowPORTF=PORTF); + setSignal(tDir); + HAVE_PORTF(PORTF=shadowPORTF); + interrupts(); } else { noInterrupts(); setSignal(tDir); @@ -393,6 +446,13 @@ void MotorDriver::throttleInrush(bool on) { } else { ledcDetachPin(brakePin); } +#elif defined(ARDUINO_ARCH_STM32) + if(on) { + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500); + DCCTimer::DCCEXanalogWrite(brakePin,duty); + } else { + pinMode(brakePin, OUTPUT); + } #else if(on){ switch(brakePin) { diff --git a/MotorDriver.h b/MotorDriver.h index 21bceb6..20a91d3 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -1,5 +1,5 @@ /* - * © 2022 Paul M Antoine + * © 2022-2023 Paul M. Antoine * © 2021 Mike S * © 2021 Fred Decker * © 2020 Chris Harlow @@ -60,6 +60,16 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #define HAVE_PORTB(X) X #define PORTC GPIOC->ODR #define HAVE_PORTC(X) X +#define PORTD GPIOD->ODR +#define HAVE_PORTD(X) X +#if defined(GPIOE) +#define PORTE GPIOE->ODR +#define HAVE_PORTE(X) X +#endif +#if defined(GPIOF) +#define PORTF GPIOF->ODR +#define HAVE_PORTF(X) X +#endif #endif // if macros not defined as pass-through we define @@ -74,6 +84,15 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #ifndef HAVE_PORTC #define HAVE_PORTC(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 #endif +#ifndef HAVE_PORTD +#define HAVE_PORTD(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif +#ifndef HAVE_PORTE +#define HAVE_PORTE(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif +#ifndef HAVE_PORTF +#define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif // Virtualised Motor shield 1-track hardware Interface @@ -110,6 +129,9 @@ struct FASTPIN { extern volatile portreg_t shadowPORTA; extern volatile portreg_t shadowPORTB; extern volatile portreg_t shadowPORTC; +extern volatile portreg_t shadowPORTD; +extern volatile portreg_t shadowPORTE; +extern volatile portreg_t shadowPORTF; enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT }; @@ -163,16 +185,16 @@ class MotorDriver { unsigned int raw2mA( int raw); unsigned int mA2raw( unsigned int mA); inline bool brakeCanPWM() { -#if defined(ARDUINO_ARCH_ESP32) || defined(__arm__) - // TODO: on ARM we can use digitalPinHasPWM, and may wish/need to - return true; -#else -#ifdef digitalPinToTimer +#if defined(ARDUINO_ARCH_ESP32) + return (brakePin != UNUSED_PIN); // This was just (true) but we probably do need to check for UNUSED_PIN! +#elif defined(__arm__) + // On ARM we can use digitalPinHasPWM + return ((brakePin!=UNUSED_PIN) && (digitalPinHasPWM(brakePin))); +#elif defined(digitalPinToTimer) return ((brakePin!=UNUSED_PIN) && (digitalPinToTimer(brakePin))); #else return (brakePin<14 && brakePin >1); -#endif //digitalPinToTimer -#endif //ESP32/ARM +#endif } inline int getRawCurrentTripValue() { return rawCurrentTripValue; diff --git a/TrackManager.cpp b/TrackManager.cpp index bd7c623..687eb8b 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -154,10 +154,16 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTC(shadowPORTC=PORTC); + HAVE_PORTD(shadowPORTD=PORTD); + HAVE_PORTE(shadowPORTE=PORTE); + HAVE_PORTF(shadowPORTF=PORTF); APPLY_BY_MODE(TRACK_MODE_MAIN,setSignal(on)); HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTC(PORTC=shadowPORTC); + HAVE_PORTD(PORTD=shadowPORTD); + HAVE_PORTE(PORTE=shadowPORTE); + HAVE_PORTF(PORTF=shadowPORTF); } void TrackManager::setCutout( bool on) { @@ -172,10 +178,16 @@ void TrackManager::setPROGSignal( bool on) { HAVE_PORTA(shadowPORTA=PORTA); HAVE_PORTB(shadowPORTB=PORTB); HAVE_PORTC(shadowPORTC=PORTC); + HAVE_PORTD(shadowPORTD=PORTD); + HAVE_PORTE(shadowPORTE=PORTE); + HAVE_PORTF(shadowPORTF=PORTF); APPLY_BY_MODE(TRACK_MODE_PROG,setSignal(on)); HAVE_PORTA(PORTA=shadowPORTA); HAVE_PORTB(PORTB=shadowPORTB); HAVE_PORTC(PORTC=shadowPORTC); + HAVE_PORTD(PORTD=shadowPORTD); + HAVE_PORTE(PORTE=shadowPORTE); + HAVE_PORTF(PORTF=shadowPORTF); } // setDCSignal(), called from normal context diff --git a/version.h b/version.h index b7c157b..95d7461 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,12 @@ #include "StringFormatter.h" -#define VERSION "5.1.9" +#define VERSION "5.1.10" +// 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX +// - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible +// - ESP32 brakeCanPWM check now detects UNUSED_PIN +// - ARM architecture brakeCanPWM now uses digitalPinHasPWM() +// - STM32F4xx shadowpin extensions to handle pins on ports D, E and F // 5.1.9 - Fixed IO_PCA9555'h to work with PCA9548 mux, tested OK // 5.1.8 - STM32Fxx ADCee extension to support ADCs #2 and #3 // 5.1.7 - Fix turntable broadcasts for non-movement activities and result From 52cfc187543a487cde464a40fd7c7904284dca98 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Thu, 28 Sep 2023 15:02:30 +0100 Subject: [PATCH 088/310] Remove Diags not needed Tidy up Diags and responses - use HASH_KEYWORD in place of 'A' --- DCCEXParser.cpp | 21 ++++++++++++--------- TrackManager.cpp | 7 +++---- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index c82175b..a561561 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -157,6 +157,7 @@ const int16_t HASH_KEYWORD_VPIN=-415; const int16_t HASH_KEYWORD_A='A'; const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; +const int16_t HASH_KEYWORD_H='H'; const int16_t HASH_KEYWORD_I='I'; const int16_t HASH_KEYWORD_O='O'; const int16_t HASH_KEYWORD_P='P'; @@ -576,7 +577,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { @@ -591,10 +593,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) singletrack=true; if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t); if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t); + + StringFormatter::send(stream, F("<1 %c>\n"), t+'A'); //CommandDistributor::broadcastPower(); - //TrackManager::streamTrackState(stream, t); - TrackManager::streamTrackState(NULL,t); - StringFormatter::send(stream, F("Track %d ON\n"), t); + //TrackManager::streamTrackState(NULL,t); return; } @@ -635,7 +637,8 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) prog=true; } #endif - else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> + else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> byte t = (p[0] - 'A'); //DIAG(F("Processing track - %d "), t); if (TrackManager::isProg(t)) { @@ -652,11 +655,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t); if (prog) { TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); - CommandDistributor::broadcastPower(); + TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); } - StringFormatter::send(stream, F("Track %d OFF\n"), t); - TrackManager::streamTrackState(NULL, t); + StringFormatter::send(stream, F("<0 %c>\n"), t+'A'); + //CommandDistributor::broadcastPower(); + //TrackManager::streamTrackState(NULL, t); return; } diff --git a/TrackManager.cpp b/TrackManager.cpp index dd27d85..bab202d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -358,7 +358,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) { bool pstate = TrackManager::isPowerOn(t); switch(track[t]->getMode()) { case TRACK_MODE_MAIN: - if (pstate) {format=F("<= %c MAIN ON \n");} else {format = F("<= %c MAIN OFF \n");} + if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} break; #ifndef DISABLE_PROG case TRACK_MODE_PROG: @@ -445,12 +445,11 @@ void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byt break; case TRACK_MODE_DC: case TRACK_MODE_DCX: - DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); - if (setProg || setJoin) {DIAG(F("Nowt to do")); break;} + //DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); + if (setProg || setJoin) break; driver->setBrake(true); // DC starts with brake on applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); - DIAG(F("Doing it anyway")); break; case TRACK_MODE_PROG: if (!setProg && !setJoin) break; From 7afd4443d616d95526cef697e7bc7c68fd728b61 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Mon, 2 Oct 2023 12:04:47 +0800 Subject: [PATCH 089/310] STM32 revised I2C clock setup --- I2CManager_STM32.h | 57 ++++++++++++++++++++++++++++++---------------- version.h | 3 ++- 2 files changed, 39 insertions(+), 21 deletions(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 86b9b74..7e0f547 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -117,35 +117,46 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Disable the I2C device, as TRISE can only be programmed whilst disabled s->CR1 &= ~(I2C_CR1_PE); // Disable I2C + s->CR1 |= I2C_CR1_SWRST; // reset the I2C + asm("nop"); // wait a bit... suggestion from online! + s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation - if (i2cClockSpeed > 100000L) + if (i2cClockSpeed > 100000UL) { - if (i2cClockSpeed > 400000L) - i2cClockSpeed = 400000L; + // if (i2cClockSpeed > 400000L) + // i2cClockSpeed = 400000L; t_rise = 300; // nanoseconds } else { - i2cClockSpeed = 100000L; + // i2cClockSpeed = 100000L; t_rise = 1000; // nanoseconds } - // Configure the rise time register - s->TRISE = (t_rise / (1000 / i2c_MHz)) + 1; + // Configure the rise time register - max allowed tRISE is 1000ns, + // so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. + s->TRISE = (t_rise * i2c_MHz / 1000) + 1; // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode // Bit 14: Duty, fast mode duty cycle (use 2:1) // Bit 11-0: FREQR - if (i2cClockSpeed > 100000L) { - // In fast mode, I2C period is 3 * CCR * TPCLK1. - //APB1clk1 / 3 / i2cClockSpeed = 38, but that results in 306KHz not 400! - ccr_freq = 30; // So 30 gives 396KHz or so! - s->CCR = (uint16_t)(ccr_freq | 0x8000); // We need Fast Mode set - } else { - // In standard mode, I2C period is 2 * CCR * TPCLK1 - ccr_freq = (APB1clk1 / 2 / i2cClockSpeed); // Should be 225 for 45Mhz APB1 clock - s->CCR |= (uint16_t)ccr_freq; - } + // if (i2cClockSpeed > 400000UL) { + // // In fast mode plus, I2C period is 3 * CCR * TPCLK1. + // // s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + // s->CCR = APB1clk1 / 3 / i2cClockSpeed; // Set I2C clockspeed to start! + // s->CCR |= 0xC000; // We need Fast Mode AND DUTY bits set + // } else { + // In standard and fast mode, I2C period is 2 * CCR * TPCLK1 + s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value + s->CCR |= (APB1clk1 / 2 / i2cClockSpeed); // Set I2C clockspeed to start! + // s->CCR |= (i2c_MHz * 500 / (i2cClockSpeed / 1000)); // Set I2C clockspeed to start! + // if (i2cClockSpeed > 100000UL) + // s->CCR |= 0xC000; // We need Fast Mode bits set as well + // } + + // DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2); + // DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR); + // DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE); // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C @@ -159,6 +170,7 @@ void I2CManagerClass::I2C_init() // Query the clockspeed from the STM32 HAL layer APB1clk1 = HAL_RCC_GetPCLK1Freq(); i2c_MHz = APB1clk1 / 1000000UL; + // DIAG(F("I2C_init() peripheral clock speed is: %d"), i2c_MHz); // Enable clocks RCC->APB1ENR |= RCC_APB1ENR_I2C1EN;//(1 << 21); // Enable I2C CLOCK // Reset the I2C1 peripheral to initial state @@ -181,6 +193,7 @@ void I2CManagerClass::I2C_init() GPIOB->AFR[1] |= (4<<0) | (4<<4); // PB8 on low nibble, PB9 on next nibble up // Software reset the I2C peripheral + I2C1->CR1 &= ~I2C_CR1_PE; // Disable I2C1 peripheral s->CR1 |= I2C_CR1_SWRST; // reset the I2C asm("nop"); // wait a bit... suggestion from online! s->CR1 &= ~(I2C_CR1_SWRST); // Normal operation @@ -191,6 +204,7 @@ void I2CManagerClass::I2C_init() // Set I2C peripheral clock frequency // s->CR2 |= I2C_PERIPH_CLK; s->CR2 |= i2c_MHz; + // DIAG(F("I2C_init() peripheral clock is now: %d"), s->CR2); // set own address to 00 - not used in master mode I2C1->OAR1 = (1 << 14); // bit 14 should be kept at 1 according to the datasheet @@ -214,6 +228,7 @@ void I2CManagerClass::I2C_init() s->CR2 |= (I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Enable Buffer, Event and Error interrupts #endif + // DIAG(F("I2C_init() setting initial I2C clock to 100KHz")); // Calculate baudrate and set default rate for now // Configure the Clock Control Register for 100KHz SCL frequency // Bit 15: I2C Master mode, 0=standard, 1=Fast Mode @@ -221,12 +236,14 @@ void I2CManagerClass::I2C_init() // Bit 11-0: so CCR divisor would be clk / 2 / 100000 (where clk is in Hz) // s->CCR = I2C_PERIPH_CLK * 5; s->CCR &= ~(0x3000); // Clear all bits except 12 and 13 which must remain per reset value - s->CCR |= (APB1clk1 / 2 / 100000UL); // i2c_MHz * 5; - // s->CCR = i2c_MHz * 5; + s->CCR |= (APB1clk1 / 2 / 100000UL); // Set a default of 100KHz I2C clockspeed to start! // Configure the rise time register - max allowed is 1000ns, so value = 1000ns * I2C_PERIPH_CLK MHz / 1000 + 1. - // s->TRISE = I2C_PERIPH_CLK + 1; // 1000 ns / 50 ns = 20 + 1 = 21 - s->TRISE = i2c_MHz + 1; + s->TRISE = (1000 * i2c_MHz / 1000) + 1; + + // DIAG(F("I2C_init() peripheral clock is now: %d, full reg is %x"), (s->CR2 & 0xFF), s->CR2); + // DIAG(F("I2C_init() peripheral CCR is now: %d"), s->CCR); + // DIAG(F("I2C_init() peripheral TRISE is now: %d"), s->TRISE); // Enable the I2C master mode s->CR1 |= I2C_CR1_PE; // Enable I2C diff --git a/version.h b/version.h index 95d7461..21dde65 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.10" +#define VERSION "5.1.11" +// 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection // 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX // - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible // - ESP32 brakeCanPWM check now detects UNUSED_PIN From 2ff1619ad15ed43bb87eaac23b3c402d5df10923 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Wed, 4 Oct 2023 14:54:06 +0800 Subject: [PATCH 090/310] STM32 reinstate 100% duty cycle PWM --- DCCTimerSTM32.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index 0f9c432..f2d51ff 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -306,18 +306,18 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { // Calculate percentage duty cycle from value given uint32_t duty_cycle = (value * 100 / 256) + 1; if (pin_timer[pin] != NULL) { - if (duty_cycle == 100) - { - pin_timer[pin]->pauseChannel(pin_channel[pin]); - DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); - } - else - { + // if (duty_cycle == 100) + // { + // pin_timer[pin]->pauseChannel(pin_channel[pin]); + // DIAG(F("DCCEXanalogWrite::Pausing timer channel on pin %d"), pin); + // } + // else + // { pinmap_pinout(digitalPinToPinName(pin), PinMap_TIM); // ensure the pin has been configured! - pin_timer[pin]->resumeChannel(pin_channel[pin]); + // pin_timer[pin]->resumeChannel(pin_channel[pin]); pin_timer[pin]->setCaptureCompare(pin_channel[pin], duty_cycle, PERCENT_COMPARE_FORMAT); // DCC_EX_PWM_FREQ Hertz, duty_cycle% dutycycle DIAG(F("DCCEXanalogWrite::Pin %d, value %d, duty cycle %d"), pin, value, duty_cycle); - } + // } } else DIAG(F("DCCEXanalogWrite::Pin %d is not configured for PWM!"), pin); From fe618d0b854a200dec5ce670e24dc92587735464 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Fri, 6 Oct 2023 19:11:11 +0100 Subject: [PATCH 091/310] Add getModeName() Add facility to get the name of the track mode --- .gitignore | 1 + TrackManager.cpp | 22 +++++++++++++++++++++- TrackManager.h | 2 ++ 3 files changed, 24 insertions(+), 1 deletion(-) diff --git a/.gitignore b/.gitignore index 6237359..482da70 100644 --- a/.gitignore +++ b/.gitignore @@ -13,3 +13,4 @@ myFilter.cpp my*.h !my*.example.h compile_commands.json +newcode.txt.old diff --git a/TrackManager.cpp b/TrackManager.cpp index bab202d..3ea9877 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -556,4 +556,24 @@ bool TrackManager::isProg(byte t) { if (track[t]->getMode()==TRACK_MODE_PROG) return true; return false; -} \ No newline at end of file +} + +byte TrackManager::returnMode(byte t) { + return (track[t]->getMode()); +} + +static const char* TrackManager::getModeName(byte Mode) { + + //DIAG(F("PowerMode %d"), Mode); + +switch (Mode) + { + case 1: return "NONE"; + case 2: return "MAIN"; + case 4: return "PROG"; + case 8: return "DC"; + case 16: return "DCX"; + case 32: return "EXT"; + default: return "----"; + } +} diff --git a/TrackManager.h b/TrackManager.h index 21b8d59..486057a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -90,6 +90,8 @@ class TrackManager { static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); static bool isProg(byte t); + static byte returnMode(byte t); + static const char* getModeName(byte Mode); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From 68fd56e7fccc74be4c06a11eae04c8bec846538e Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Tue, 10 Oct 2023 11:52:46 +0100 Subject: [PATCH 092/310] Added returnDCAddr Added function to return DC address --- TrackManager.cpp | 7 ++++++- TrackManager.h | 1 + 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 3ea9877..7d86de0 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -356,6 +356,7 @@ void TrackManager::streamTrackState(Print* stream, byte t) { if (track[t]==NULL) return; auto format=F(""); bool pstate = TrackManager::isPowerOn(t); + switch(track[t]->getMode()) { case TRACK_MODE_MAIN: if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} @@ -562,7 +563,11 @@ byte TrackManager::returnMode(byte t) { return (track[t]->getMode()); } -static const char* TrackManager::getModeName(byte Mode) { +int16_t TrackManager::returnDCAddr(byte t) { + return (trackDCAddr[t]); +} + +const char* TrackManager::getModeName(byte Mode) { //DIAG(F("PowerMode %d"), Mode); diff --git a/TrackManager.h b/TrackManager.h index 486057a..d197751 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -91,6 +91,7 @@ class TrackManager { static bool isPowerOn(byte t); static bool isProg(byte t); static byte returnMode(byte t); + static int16_t returnDCAddr(byte t); static const char* getModeName(byte Mode); static int16_t joinRelay; From a092e06a6fec69159de22e14127524d53e65a20c Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Tue, 10 Oct 2023 12:11:49 +0100 Subject: [PATCH 093/310] Update .gitignore added UserAddin.txt to gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 482da70..759b739 100644 --- a/.gitignore +++ b/.gitignore @@ -14,3 +14,4 @@ my*.h !my*.example.h compile_commands.json newcode.txt.old +UserAddin.txt From ea4f90d5fcd76b59f2a3a4fb0daa5a6f7ceeb815 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Wed, 11 Oct 2023 17:06:56 +0100 Subject: [PATCH 094/310] Merged in Power changes Merge in power changes and EXRAIL command & update to version.h --- version.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 21dde65..e9e1e79 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,12 @@ #include "StringFormatter.h" -#define VERSION "5.1.11" +#define VERSION "5.1.12" +// 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> +// Added EXRAIL SET_POWER(track, ON/OFF) +// Fixed a problem whereby <1 MAIN> also powered on PROG track +// Added functions to TrackManager.cpp to allow UserAddin code for power display on OLED/LCD +// Added - returnMode(byte t), returnDCAddr(byte t) & getModeName(byte Mode) // 5.1.11 - STM32F4xx revised I2C clock setup, no correctly sets clock and has fully variable frequency selection // 5.1.10 - STM32F4xx DCCEXanalogWrite to handle PWM generation for TrackManager DC/DCX // - STM32F4xx DCC 58uS timer now using non-PWM output timers where possible From d5978b1578ef461fdd23317ebc4f92ca47f8b00d Mon Sep 17 00:00:00 2001 From: peteGSX Date: Thu, 12 Oct 2023 13:28:39 +1000 Subject: [PATCH 095/310] Change broadcast --- CommandDistributor.cpp | 2 +- DCCEXParser.cpp | 12 ++++++------ version.h | 3 ++- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index a521b52..1651771 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -162,7 +162,7 @@ void CommandDistributor::broadcastTurnout(int16_t id, bool isClosed ) { } void CommandDistributor::broadcastTurntable(int16_t id, uint8_t position, bool moving) { - broadcastReply(COMMAND_TYPE, F("\n"), id, position, moving); + broadcastReply(COMMAND_TYPE, F("\n"), id, position, moving); } void CommandDistributor::broadcastClockTime(int16_t time, int8_t rate) { diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 9cff75a..e53b882 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -60,8 +60,8 @@ Once a new OPCODE is decided upon, update this list. G, h, H, Turnout state broadcast - i, Reserved for future use - Turntable object broadcast - I, Reserved for future use - Turntable object command and control + i, Server details string + I, Turntable object command, control, and broadcast j, Throttle responses J, Throttle queries k, Reserved for future use - Potentially Railcom @@ -1244,7 +1244,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (tto) { bool type = tto->isEXTT(); uint8_t position = tto->getPosition(); - StringFormatter::send(stream, F("\n"), type, position); + StringFormatter::send(stream, F("\n"), type, position); } else { return false; } @@ -1270,7 +1270,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[2]); - StringFormatter::send(stream, F("\n")); + StringFormatter::send(stream, F("\n")); } else { if (!tto) return false; if (!tto->isEXTT()) return false; @@ -1287,7 +1287,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); tto->addPosition(0, 0, p[3]); - StringFormatter::send(stream, F("\n")); + StringFormatter::send(stream, F("\n")); } else { return false; } @@ -1301,7 +1301,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) // tto must exist, no more than 48 positions, angle 0 - 3600 if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; tto->addPosition(p[2], p[3], p[4]); - StringFormatter::send(stream, F("\n")); + StringFormatter::send(stream, F("\n")); } else { return false; } diff --git a/version.h b/version.h index e9e1e79..ee65765 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.12" +#define VERSION "5.1.13" +// 5.1.13 - Changed turntable broadcast from i to I due to server string conflict // 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> // Added EXRAIL SET_POWER(track, ON/OFF) // Fixed a problem whereby <1 MAIN> also powered on PROG track From ce84974967cd9771479116a7cde2dfd2d1b627e9 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Thu, 12 Oct 2023 13:42:14 +1000 Subject: [PATCH 096/310] Missed one i --- Turntables.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Turntables.h b/Turntables.h index 6c15bab..aa089ef 100644 --- a/Turntables.h +++ b/Turntables.h @@ -185,7 +185,7 @@ public: for (Turntable *tto = _firstTurntable; tto != 0; tto = tto->_nextTurntable) if (!tto->isHidden()) { gotOne = true; - StringFormatter::send(stream, F("\n"), tto->getId(), tto->getPosition()); + StringFormatter::send(stream, F("\n"), tto->getId(), tto->getPosition()); } return gotOne; } From 0214a55b23599cddc66b4fd24397fddfdcb60527 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Fri, 13 Oct 2023 04:37:38 +1000 Subject: [PATCH 097/310] Fixed --- EXRAIL2.h | 7 +++---- version.h | 3 ++- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/EXRAIL2.h b/EXRAIL2.h index ad399ec..7b0a9af 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -64,10 +64,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONCHANGE, OPCODE_ONCLOCKTIME, OPCODE_ONTIME, -#ifndef IO_NO_HAL OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, - OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_IFTTPOSITION,OPCODE_WAITFORTT, -#endif + OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT, OPCODE_ONOVERLOAD, // OPcodes below this point are skip-nesting IF operations @@ -81,7 +79,8 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_IFRANDOM,OPCODE_IFRESERVE, OPCODE_IFCLOSED,OPCODE_IFTHROWN, OPCODE_IFRE, - OPCODE_IFLOCO + OPCODE_IFLOCO, + OPCODE_IFTTPOSITION }; // Ensure thrunge_lcd is put last as there may be more than one display, diff --git a/version.h b/version.h index ee65765..468971e 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.13" +#define VERSION "5.1.14" +// 5.1.14 - Fixed IFTTPOSITION // 5.1.13 - Changed turntable broadcast from i to I due to server string conflict // 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> // Added EXRAIL SET_POWER(track, ON/OFF) From 6eb7051fd63f3abe1042507070842f98bb65fde1 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 13 Oct 2023 13:59:06 +0100 Subject: [PATCH 098/310] LCC and signal compile-out LCC commands in EXRAIL for OpenMRN Adapter FIrst use of compile-out of unused features. --- DCCEXParser.cpp | 5 +- EXRAIL2.cpp | 116 ++++++++++++++++++++++++++++++++++++-------- EXRAIL2.h | 13 ++++- EXRAIL2MacroReset.h | 8 ++- EXRAILMacros.h | 43 ++++++++++++++++ StringFormatter.cpp | 14 +++++- StringFormatter.h | 1 + version.h | 3 +- 8 files changed, 178 insertions(+), 25 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2bd79e9..dab213b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -67,7 +67,7 @@ Once a new OPCODE is decided upon, update this list. k, Reserved for future use - Potentially Railcom K, Reserved for future use - Potentially Railcom l, Loco speedbyte/function map broadcast - L, + L, Reserved for LCC interface (implemented in EXRAIL) m, M, Write DCC packet n, @@ -906,6 +906,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) break; #endif + case 'L': // LCC interface implemented in EXRAIL parser + break; // Will if not intercepted by EXRAIL + default: //anything else will diagnose and drop out to DIAG(F("Opcode=%c params=%d"), opcode, params); for (int i = 0; i < params; i++) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 321872d..c902708 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -85,7 +85,7 @@ RMFT2 * RMFT2::pausingTask=NULL; // Task causing a PAUSE. // when pausingTask is set, that is the ONLY task that gets any service, // and all others will have their locos stopped, then resumed after the pausing task resumes. byte RMFT2::flags[MAX_FLAGS]; - +Print * RMFT2::LCCSerial=0; LookList * RMFT2::sequenceLookup=NULL; LookList * RMFT2::onThrowLookup=NULL; LookList * RMFT2::onCloseLookup=NULL; @@ -176,23 +176,26 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { onCloseLookup=LookListLoader(OPCODE_ONCLOSE); onActivateLookup=LookListLoader(OPCODE_ONACTIVATE); onDeactivateLookup=LookListLoader(OPCODE_ONDEACTIVATE); - onRedLookup=LookListLoader(OPCODE_ONRED); - onAmberLookup=LookListLoader(OPCODE_ONAMBER); - onGreenLookup=LookListLoader(OPCODE_ONGREEN); onChangeLookup=LookListLoader(OPCODE_ONCHANGE); onClockLookup=LookListLoader(OPCODE_ONTIME); #ifndef IO_NO_HAL onRotateLookup=LookListLoader(OPCODE_ONROTATE); #endif onOverloadLookup=LookListLoader(OPCODE_ONOVERLOAD); + // onLCCLookup is not the same so not loaded here. // Second pass startup, define any turnouts or servos, set signals red // add sequences onRoutines to the lookups +if (compileFeatures & FEATURE_SIGNAL) { + onRedLookup=LookListLoader(OPCODE_ONRED); + onAmberLookup=LookListLoader(OPCODE_ONAMBER); + onGreenLookup=LookListLoader(OPCODE_ONGREEN); for (int sigslot=0;;sigslot++) { VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); if (sigid==0) break; // end of signal list doSignal(sigid & SIGNAL_ID_MASK, SIGNAL_RED); } + } int progCounter; for (progCounter=0;; SKIPOP){ @@ -343,13 +346,65 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 reject=!parseSlash(stream,paramCount,p); opcode=0; break; - + case 'L': + if (compileFeatures & FEATURE_LCC) { + // This entire code block is compiled out if LLC macros not used + if (paramCount==0) { // LCC adapter introducing self + LCCSerial=stream; // now we know where to send events we raise + + // loop through all possible sent events + for (int progCounter=0;; SKIPOP) { + byte opcode=GET_OPCODE; + if (opcode==OPCODE_ENDEXRAIL) break; + if (opcode==OPCODE_LCC) StringFormatter::send(stream,F("\n"),getOperand(progCounter,0)); + if (opcode==OPCODE_LCCX) { // long form LCC + StringFormatter::send(stream,F("\n"), + getOperand(progCounter,1), + getOperand(progCounter,2), + getOperand(progCounter,3), + getOperand(progCounter,0) + ); + }} + + // we stream the hex events we wish to listen to + // and at the same time build the event index looku. + + + int eventIndex=0; + for (int progCounter=0;; SKIPOP) { + byte opcode=GET_OPCODE; + if (opcode==OPCODE_ENDEXRAIL) break; + if (opcode==OPCODE_ONLCC) { + onLCCLookup[eventIndex]=progCounter; // TODO skip... + StringFormatter::send(stream,F("\n"), + eventIndex, + getOperand(progCounter,1), + getOperand(progCounter,2), + getOperand(progCounter,3), + getOperand(progCounter,0) + ); + eventIndex++; + } + } + StringFormatter::send(stream,F("\n")); // Ready to rumble + opcode=0; + break; + } + if (paramCount==1) { // LCC event arrived from adapter + int16_t eventid=p[0]; + reject=eventid<0 || eventid>=countLCCLookup; + if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]); + opcode=0; + } + } + break; + default: // other commands pass through break; } if (reject) { opcode=0; - StringFormatter::send(stream,F("")); + StringFormatter::send(stream,F("\n")); } } @@ -377,17 +432,19 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { if (flag & LATCH_FLAG) StringFormatter::send(stream,F(" LATCHED")); } } - // do the signals - // flags[n] represents the state of the nth signal in the table - for (int sigslot=0;;sigslot++) { - VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); - if (sigid==0) break; // end of signal list - byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id - StringFormatter::send(stream,F("\n%S[%d]"), - (flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"), - sigid & SIGNAL_ID_MASK); - } - + + if (compileFeatures & FEATURE_SIGNAL) { + // do the signals + // flags[n] represents the state of the nth signal in the table + for (int sigslot=0;;sigslot++) { + VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); + if (sigid==0) break; // end of signal list + byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id + StringFormatter::send(stream,F("\n%S[%d]"), + (flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"), + sigid & SIGNAL_ID_MASK); + } + } StringFormatter::send(stream,F(" *>\n")); return true; } @@ -1034,7 +1091,21 @@ void RMFT2::loop2() { invert=false; } break; - + + case OPCODE_LCC: // short form LCC + if ((compileFeatures & FEATURE_LCC) && LCCSerial) + StringFormatter::send(LCCSerial,F(""),(uint16_t)operand); + break; + + case OPCODE_LCCX: // long form LCC + if ((compileFeatures & FEATURE_LCC) && LCCSerial) + StringFormatter::send(LCCSerial,F("\n"), + getOperand(progCounter,1), + getOperand(progCounter,2), + getOperand(progCounter,3), + getOperand(progCounter,0) + ); + break; case OPCODE_SERVO: // OPCODE_SERVO,V(vpin),OPCODE_PAD,V(position),OPCODE_PAD,V(profile),OPCODE_PAD,V(duration) IODevice::writeAnalogue(operand,getOperand(1),getOperand(2),getOperand(3)); @@ -1072,6 +1143,7 @@ void RMFT2::loop2() { case OPCODE_SERVOTURNOUT: // Turnout definition ignored at runtime case OPCODE_PINTURNOUT: // Turnout definition ignored at runtime case OPCODE_ONCLOSE: // Turnout event catchers ignored here + case OPCODE_ONLCC: // LCC event catchers ignored here case OPCODE_ONTHROW: case OPCODE_ONACTIVATE: // Activate event catchers ignored here case OPCODE_ONDEACTIVATE: @@ -1141,6 +1213,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { } /* static */ void RMFT2::doSignal(int16_t id,char rag) { + if (!(compileFeatures & FEATURE_SIGNAL)) return; // dont compile code below if (diag) DIAG(F(" doSignal %d %x"),id,rag); // Schedule any event handler for this signal change. @@ -1208,6 +1281,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { } /* static */ bool RMFT2::isSignal(int16_t id,char rag) { + if (!(compileFeatures & FEATURE_SIGNAL)) return false; int16_t sigslot=getSignalSlot(id); if (sigslot<0) return false; return (flags[sigslot] & SIGNAL_MASK) == rag; @@ -1260,8 +1334,10 @@ void RMFT2::powerEvent(int16_t track, bool overload) { void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) { int pc= handlers->find(id); - if (pc<0) return; - + if (pc>=0) startNonRecursiveTask(reason,id,pc); +} + +void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) { // Check we dont already have a task running this handler RMFT2 * task=loopTask; while(task) { diff --git a/EXRAIL2.h b/EXRAIL2.h index 7b0a9af..de14f11 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -66,6 +66,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONTIME, OPCODE_TTADDPOSITION,OPCODE_DCCTURNTABLE,OPCODE_EXTTTURNTABLE, OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT, + OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC, OPCODE_ONOVERLOAD, // OPcodes below this point are skip-nesting IF operations @@ -94,7 +95,11 @@ enum thrunger: byte { thrunge_lcd, // Must be last!! }; - + // Flag bits for compile time features. + static const byte FEATURE_SIGNAL= 0x80; + static const byte FEATURE_LCC = 0x40; + static const byte FEATURE_ROSTER= 0x20; + // Flag bits for status of hardware and TPL static const byte SECTION_FLAG = 0x80; @@ -173,6 +178,7 @@ private: OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); static uint16_t getOperand(int progCounter,byte n); + static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); static RMFT2 * loopTask; static RMFT2 * pausingTask; void delayMe(long millisecs); @@ -191,6 +197,7 @@ private: static const HIGHFLASH byte RouteCode[]; static const HIGHFLASH int16_t SignalDefinitions[]; static byte flags[MAX_FLAGS]; + static Print * LCCSerial; static LookList * sequenceLookup; static LookList * onThrowLookup; static LookList * onCloseLookup; @@ -205,6 +212,10 @@ private: static LookList * onRotateLookup; #endif static LookList * onOverloadLookup; + + static const int countLCCLookup; + static int onLCCLookup[]; + static const byte compileFeatures; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 03e310e..bdb6420 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -86,6 +86,8 @@ #undef LATCH #undef LCD #undef SCREEN +#undef LCC +#undef LCCX #undef LCN #undef MOVETT #undef ONACTIVATE @@ -94,6 +96,7 @@ #undef ONDEACTIVATE #undef ONDEACTIVATEL #undef ONCLOSE +#undef ONLCC #undef ONTIME #undef ONCLOCKTIME #undef ONCLOCKMINS @@ -221,7 +224,9 @@ #define INVERT_DIRECTION #define JOIN #define KILLALL -#define LATCH(sensor_id) +#define LATCH(sensor_id) +#define LCC(eventid) +#define LCCX(senderid,eventid) #define LCD(row,msg) #define SCREEN(display,row,msg) #define LCN(msg) @@ -236,6 +241,7 @@ #define ONDEACTIVATE(addr,subaddr) #define ONDEACTIVATEL(linear) #define ONCLOSE(turnout_id) +#define ONLCC(sender,event) #define ONGREEN(signal_id) #define ONRED(signal_id) #define ONROTATE(turntable_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index b85b68a..3322180 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -85,6 +85,30 @@ void exrailHalSetup() { #include "myAutomation.h" } +// Pass 1c detect compile time featurtes +#include "EXRAIL2MacroReset.h" +#undef SIGNAL +#define SIGNAL(redpin,amberpin,greenpin) | FEATURE_SIGNAL +#undef SIGNALH +#define SIGNALH(redpin,amberpin,greenpin) | FEATURE_SIGNAL +#undef SERVO_SIGNAL +#define SERVO_SIGNAL(vpin,redval,amberval,greenval) | FEATURE_SIGNAL +#undef DCC_SIGNAL +#define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL +#undef VIRTUAL_SIGNAL +#define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL + +#undef LCC +#define LCC(eventid) | FEATURE_LCC +#undef LCCX +#define LCCX(senderid,eventid) | FEATURE_LCC +#undef ONLCC +#define ONLCC(senderid,eventid) | FEATURE_LCC + +const byte RMFT2::compileFeatures = 0 + #include "myAutomation.h" +; + // Pass 2 create throttle route list #include "EXRAIL2MacroReset.h" #undef ROUTE @@ -278,6 +302,16 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #include "myAutomation.h" 0,0,0,0 }; +// Pass 9 ONLCC counter and lookup array +#include "EXRAIL2MacroReset.h" +#undef ONLCC +#define ONLCC(sender,event) +1 + +const int RMFT2::countLCCLookup=0 +#include "myAutomation.h" +; +int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; + // Last Pass : create main routes table // Only undef the macros, not dummy them. #define RMFT2_UNDEF_ONLY @@ -354,6 +388,11 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define JOIN OPCODE_JOIN,0,0, #define KILLALL OPCODE_KILLALL,0,0, #define LATCH(sensor_id) OPCODE_LATCH,V(sensor_id), +#define LCC(eventid) OPCODE_LCC,V(eventid), +#define LCCX(sender,event) OPCODE_LCCX,V(event),\ + OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\ + OPCODE_PAD,V((((uint64_t)sender)>>16)&0xFFFF),\ + OPCODE_PAD,V((((uint64_t)sender)>>0)&0xFFFF), #define LCD(id,msg) PRINT(msg) #define SCREEN(display,id,msg) PRINT(msg) #define LCN(msg) PRINT(msg) @@ -362,6 +401,10 @@ const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3), #define ONAMBER(signal_id) OPCODE_ONAMBER,V(signal_id), #define ONCLOSE(turnout_id) OPCODE_ONCLOSE,V(turnout_id), +#define ONLCC(sender,event) OPCODE_ONLCC,V(event),\ + OPCODE_PAD,V((((uint64_t)sender)>>32)&0xFFFF),\ + OPCODE_PAD,V((((uint64_t)sender)>>16)&0xFFFF),\ + OPCODE_PAD,V((((uint64_t)sender)>>0)&0xFFFF), #define ONTIME(value) OPCODE_ONTIME,V(value), #define ONCLOCKTIME(hours,mins) OPCODE_ONTIME,V((STRIP_ZERO(hours)*60)+STRIP_ZERO(mins)), #define ONCLOCKMINS(mins) ONCLOCKTIME(25,mins) diff --git a/StringFormatter.cpp b/StringFormatter.cpp index c475ef0..b40de1c 100644 --- a/StringFormatter.cpp +++ b/StringFormatter.cpp @@ -117,6 +117,7 @@ void StringFormatter::send2(Print * stream,const FSH* format, va_list args) { case 'o': stream->print(va_arg(args, int), OCT); break; case 'x': stream->print((unsigned int)va_arg(args, unsigned int), HEX); break; case 'X': stream->print((unsigned long)va_arg(args, unsigned long), HEX); break; + case 'h': printHex(stream,(unsigned int)va_arg(args, unsigned int)); break; case 'M': { // this prints a unsigned long microseconds time in readable format unsigned long time = va_arg(args, long); @@ -218,4 +219,15 @@ void StringFormatter::printPadded(Print* stream, long value, byte width, bool fo if (!formatLeft) stream->print(value, DEC); } - +// printHex prints the full 2 byte hex with leading zeros, unlike print(value,HEX) +const char FLASH hexchars[]="0123456789ABCDEF"; +void StringFormatter::printHex(Print * stream,uint16_t value) { + char result[5]; + for (int i=3;i>=0;i--) { + result[i]=GETFLASH(hexchars+(value & 0x0F)); + value>>=4; + } + result[4]='\0'; + stream->print(result); +} + \ No newline at end of file diff --git a/StringFormatter.h b/StringFormatter.h index 6923c10..1231d54 100644 --- a/StringFormatter.h +++ b/StringFormatter.h @@ -49,6 +49,7 @@ class StringFormatter static void lcd2(uint8_t display, byte row, const FSH* input...); static void printEscapes(char * input); static void printEscape( char c); + static void printHex(Print * stream,uint16_t value); private: static void send2(Print * serial, const FSH* input,va_list args); diff --git a/version.h b/version.h index 468971e..c2fd520 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.14" +#define VERSION "5.1.15" +// 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. // 5.1.14 - Fixed IFTTPOSITION // 5.1.13 - Changed turntable broadcast from i to I due to server string conflict // 5.1.12 - Added Power commands <0 A> & <1 A> etc. and update to <=> From 0978bb0c11a387174b10ef0d72842816e22d1c36 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Mon, 16 Oct 2023 08:12:11 +1000 Subject: [PATCH 099/310] Changes made, but non-functional --- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 6 ++---- Turntables.cpp | 2 +- version.h | 3 ++- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index bdb6420..5ca2e91 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -196,7 +196,7 @@ #define ENDTASK #define ESTOP #define EXRAIL -#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description) +#define EXTT_TURNTABLE(id,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 3322180..31bf0db 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -79,8 +79,6 @@ #include "EXRAIL2MacroReset.h" #undef HAL #define HAL(haltype,params...) haltype::create(params); -#undef EXTT_TURNTABLE -#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) EXTurntable::create(vpin,1,i2c_address); void exrailHalSetup() { #include "myAutomation.h" } @@ -226,7 +224,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { #undef DCC_TURNTABLE #define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE -#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) O_DESC(id,description) +#define EXTT_TURNTABLE(id,home,description...) O_DESC(id,description) const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { switch (turntableId) { @@ -356,7 +354,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL #ifndef IO_NO_HAL -#define EXTT_TURNTABLE(id,vpin,i2c_address,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(i2c_address),OPCODE_PAD,V(home), +#define EXTT_TURNTABLE(id,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(home), #endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), diff --git a/Turntables.cpp b/Turntables.cpp index ba143cb..daa71fa 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -183,7 +183,7 @@ using DevState = IODevice::DeviceStateEnum; return tto; } } - if (!IODevice::exists(vpin)) return nullptr; + // if (!IODevice::exists(vpin)) return nullptr; if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; if (Turntable::getByVpin(vpin)) return nullptr; tto = (Turntable *)new EXTTTurntable(id, vpin); diff --git a/version.h b/version.h index c2fd520..ec00f0c 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.15" +#define VERSION "5.1.16" +// 5.1.16 - Change EXTT_TURNTABLE to use HAL and remove vpin/i2c_address // 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. // 5.1.14 - Fixed IFTTPOSITION // 5.1.13 - Changed turntable broadcast from i to I due to server string conflict From 650e411a4f70c779cbbcaf463a5a9447a8ea00df Mon Sep 17 00:00:00 2001 From: peteGSX Date: Tue, 17 Oct 2023 05:06:35 +1000 Subject: [PATCH 100/310] Add vpin parameter --- EXRAIL2MacroReset.h | 2 +- EXRAILMacros.h | 4 ++-- Turntables.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 5ca2e91..d44b244 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -196,7 +196,7 @@ #define ENDTASK #define ESTOP #define EXRAIL -#define EXTT_TURNTABLE(id,home,description) +#define EXTT_TURNTABLE(id,vpin,home,description) #define FADE(pin,value,ms) #define FOFF(func) #define FOLLOW(route) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 31bf0db..8e7fbb9 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -224,7 +224,7 @@ const FSH * RMFT2::getTurnoutDescription(int16_t turnoutid) { #undef DCC_TURNTABLE #define DCC_TURNTABLE(id,home,description...) O_DESC(id,description) #undef EXTT_TURNTABLE -#define EXTT_TURNTABLE(id,home,description...) O_DESC(id,description) +#define EXTT_TURNTABLE(id,vpin,home,description...) O_DESC(id,description) const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { switch (turntableId) { @@ -354,7 +354,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ESTOP OPCODE_SPEED,V(1), #define EXRAIL #ifndef IO_NO_HAL -#define EXTT_TURNTABLE(id,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(home), +#define EXTT_TURNTABLE(id,vpin,home,description...) OPCODE_EXTTTURNTABLE,V(id),OPCODE_PAD,V(vpin),OPCODE_PAD,V(home), #endif #define FADE(pin,value,ms) OPCODE_SERVO,V(pin),OPCODE_PAD,V(value),OPCODE_PAD,V(PCA9685::ProfileType::UseDuration|PCA9685::NoPowerOff),OPCODE_PAD,V(ms/100L), #define FOFF(func) OPCODE_FOFF,V(func), diff --git a/Turntables.cpp b/Turntables.cpp index daa71fa..ba143cb 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -183,7 +183,7 @@ using DevState = IODevice::DeviceStateEnum; return tto; } } - // if (!IODevice::exists(vpin)) return nullptr; + if (!IODevice::exists(vpin)) return nullptr; if (IODevice::getStatus(vpin) == DevState::DEVSTATE_FAILED) return nullptr; if (Turntable::getByVpin(vpin)) return nullptr; tto = (Turntable *)new EXTTTurntable(id, vpin); From 754bd993810b75243c72299dcdadcc4abee0d2f7 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Tue, 17 Oct 2023 05:08:04 +1000 Subject: [PATCH 101/310] Update version --- version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/version.h b/version.h index ec00f0c..00fdc37 100644 --- a/version.h +++ b/version.h @@ -4,7 +4,7 @@ #include "StringFormatter.h" #define VERSION "5.1.16" -// 5.1.16 - Change EXTT_TURNTABLE to use HAL and remove vpin/i2c_address +// 5.1.16 - Remove I2C address from EXTT_TURNTABLE macro to work with MUX, requires separate HAL macro to create // 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. // 5.1.14 - Fixed IFTTPOSITION // 5.1.13 - Changed turntable broadcast from i to I due to server string conflict From 7b3b16b21190c5dfdb9fd7d09dcac09a2ed1aea7 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 23 Oct 2023 11:45:52 +0200 Subject: [PATCH 102/310] Divide out C for config and D for diag commands --- DCCEXParser.cpp | 80 +++++++++++++++++++++++++++++-------------------- DCCEXParser.h | 1 + GITHUB_SHA.h | 2 +- version.h | 3 +- 4 files changed, 51 insertions(+), 35 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index dab213b..d79136f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -49,7 +49,7 @@ Once a new OPCODE is decided upon, update this list. b, Write CV bit on main B, Write CV bit c, Request current command - C, + C, configure the CS d, D, Diagnostic commands e, Erase EEPROM @@ -693,7 +693,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) Sensor::printAll(stream); return; - case 's': // + case 's': // STATUS StringFormatter::send(stream, F("\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); CommandDistributor::broadcastPower(); // is the only "get power status" command we have Turnout::printAll(stream); //send all Turnout states @@ -714,13 +714,17 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case ' ': // < > StringFormatter::send(stream, F("\n")); return; + case 'C': // CONFIG + if (parseC(stream, params, p)) + return; + break; #ifndef DISABLE_DIAG - case 'D': // < > + case 'D': // DIAG if (parseD(stream, params, p)) return; break; #endif - case '=': // <= Track manager control > + case '=': // TACK MANAGER CONTROL <= [params]> if (TrackManager::parseJ(stream, params, p)) return; break; @@ -1114,19 +1118,28 @@ bool DCCEXParser::parseS(Print *stream, int16_t params, int16_t p[]) return false; } -bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) -{ +bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { if (params == 0) return false; bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off switch (p[0]) { - case HASH_KEYWORD_CABS: // - DCC::displayCabList(stream); +#ifndef DISABLE_PROG + case HASH_KEYWORD_PROGBOOST: + TrackManager::progTrackBoosted=true; + return true; +#endif + case HASH_KEYWORD_RESET: + DCCTimer::reset(); + break; // and if we didnt restart + case HASH_KEYWORD_SPEED28: + DCC::setGlobalSpeedsteps(28); + DIAG(F("28 Speedsteps")); return true; - case HASH_KEYWORD_RAM: // - StringFormatter::send(stream, F("Free memory=%d\n"), DCCTimer::getMinimumFreeMemory()); + case HASH_KEYWORD_SPEED128: + DCC::setGlobalSpeedsteps(128); + DIAG(F("128 Speedsteps")); return true; #ifndef DISABLE_PROG @@ -1146,12 +1159,33 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // } } else { - StringFormatter::send(stream, F("Ack diag %S\n"), onOff ? F("on") : F("off")); + DIAG(F("Ack diag %S"), onOff ? F("on") : F("off")); Diag::ACK = onOff; } return true; #endif +default: // invalid/unknown + break; + } + return false; +} + +bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) +{ + if (params == 0) + return false; + bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + switch (p[0]) + { + case HASH_KEYWORD_CABS: // + DCC::displayCabList(stream); + return true; + + case HASH_KEYWORD_RAM: // + DIAG(F("Free memory=%d"), DCCTimer::getMinimumFreeMemory()); + return true; + case HASH_KEYWORD_CMD: // Diag::CMD = onOff; return true; @@ -1173,34 +1207,14 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) Diag::LCN = onOff; return true; #endif -#ifndef DISABLE_PROG - case HASH_KEYWORD_PROGBOOST: - TrackManager::progTrackBoosted=true; - return true; -#endif - case HASH_KEYWORD_RESET: - DCCTimer::reset(); - break; // and if we didnt restart - - #ifndef DISABLE_EEPROM case HASH_KEYWORD_EEPROM: // if (params >= 2) EEStore::dump(p[1]); return true; #endif - - case HASH_KEYWORD_SPEED28: - DCC::setGlobalSpeedsteps(28); - StringFormatter::send(stream, F("28 Speedsteps")); - return true; - - case HASH_KEYWORD_SPEED128: - DCC::setGlobalSpeedsteps(128); - StringFormatter::send(stream, F("128 Speedsteps")); - return true; - case HASH_KEYWORD_SERVO: // + case HASH_KEYWORD_ANOUT: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); break; @@ -1223,7 +1237,7 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) break; default: // invalid/unknown - break; + return parseC(stream, params, p); } return false; } diff --git a/DCCEXParser.h b/DCCEXParser.h index 8a7367a..3c3382c 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -49,6 +49,7 @@ struct DCCEXParser static bool parseZ(Print * stream, int16_t params, int16_t p[]); static bool parseS(Print * stream, int16_t params, int16_t p[]); static bool parsef(Print * stream, int16_t params, int16_t p[]); + static bool parseC(Print * stream, int16_t params, int16_t p[]); static bool parseD(Print * stream, int16_t params, int16_t p[]); #ifndef IO_NO_HAL static bool parseI(Print * stream, int16_t params, int16_t p[]); diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index d46ef22..d2a7fd1 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202309241855Z" +#define GITHUB_SHA "devel-202310230944Z" diff --git a/version.h b/version.h index 00fdc37..4daafba 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.16" +#define VERSION "5.1.17" +// 5.1.17 - Divide out C for config and D for diag commands // 5.1.16 - Remove I2C address from EXTT_TURNTABLE macro to work with MUX, requires separate HAL macro to create // 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. // 5.1.14 - Fixed IFTTPOSITION From 3da4cb0961270b76df4fed37423118fdac309336 Mon Sep 17 00:00:00 2001 From: FranziHH <45534937+FranziHH@users.noreply.github.com> Date: Mon, 23 Oct 2023 19:21:03 +0200 Subject: [PATCH 103/310] update read.me --- README.md | 4 ++++ images/IMG_5870_1.jpg | Bin 0 -> 758356 bytes 2 files changed, 4 insertions(+) create mode 100644 images/IMG_5870_1.jpg diff --git a/README.md b/README.md index f820075..a84c7f4 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,7 @@ +# My (FranziHH) DCC++ Ex Hardware + + + # What is DCC++ EX? DCC++ EX is the organization maintaining several codebases that together represent a fully open source DCC system. Currently, this includes the following: diff --git a/images/IMG_5870_1.jpg b/images/IMG_5870_1.jpg new file mode 100644 index 0000000000000000000000000000000000000000..5f3469c8323cb65178d6480a2a714b8bad76c052 GIT binary patch literal 758356 zcmeFa2UJtf_b)n0C?d@YN{xVGql8|Bh;$K9dKDpr5JM6mp$J0ksHj*$r75UL7Z5@b zqN1Q8y@QB|(u*a429n&BfaP26{r&&?tD%d2a(uXc3<~4`0QL|7urWMb`{57(HlAMOU3dWq;00hA_n)yhfk;^V zg`3*i!*x_mz>$UJV1*+1c{TDS`k>)^{fT5E$)6YqH@4SQM!=o11Ycqp38<;6sp}zB z_0-hi2wgpdnw~lWm<4+iBCsT!H{97ffQ%0QhXC&G$5m1G_s08#1YBxaf$Z@0H`kUoOY`%wT~kQ7x@7XCtpon6?SnkW@F|o+CB>d0D5`RhszxOCHYMl0K7}`G#CJUOMDg#0RGF1zH$0fV2NJ= z09d}HQwRg#)Mb8dzm~%QxOf@L)m7C2;L>mW<==R4Ysr6vsw(8xueL*PE%qTC1_10g zo_C4Y;RQe>ZPEXyJOGF;@vnFQSdsQ?j6m)z@*ILL@toMgev|Y4#;e|09BVB+03hx_ zfiM7IkOu&@JG|UDf8qf^;|>%^aK# ziTGC;;9BQ+#+g-|>*BBYN&rS+02l(m?QgZ8xqpa5N6x#08{7eD0PLXPAJY$LsH&@~ zX{f5I>S}0m);Vr$U;Gxu#aJ)OP0f_-5jsk0s;YQA+)qVaSyM?02L%uS<@T7Jt`2~LUt@T&S2#8y+ER#iVL9)w_3$b0U)Mtj zba4*6;spS@#DCbdXw72D;~!Uc7kd&2an~;|V`~6mPXQ5b3iux3sIq&(2_Up=*)oA; zLIMIpD+QMeu3RfBBqX|a-RjkASFc{TQiw}SmwzXSu%Mu@i0}##kriu1L`2qbeni$R z7FqdUF~EKdRxSg#z%3X=4nS8zU@IZ)KEMN(v!6kb06=&lTv}`*fN>(g%g4V=V7VaV z@0kz)h5g7}0U$gO7?cOf%g?ur7bc_*0nn8&o(-!Iyhi)HSIY$*RpVQ8>2|>`d4;uh zPkhuhf{!&D^KZOt|7qYeilix)R(O1q$rT4*)2HcVE%6q|_vkN0C#qXR2EUpqUcGbj z;k9RNALw_BpSORUaqk~g8uO`=p z4Tx1dM*F;jl9lf-M1r3^m;#!HDJP4&x>FOI(>+&T>D1Axih;(e%Ox-#*IB{5R z-51}LQU(@Ete92=Bi{)fwQH#Ptdz%)?k6du-dQ&(*XFzHsu)rI|31uNSnvobM019#bgQET6(v>h-+pt&FuF zquCWjmOIWyq&=`vib>AZ54inxs^58vQbRdTZ*GjoC<>k2DYMR*GR_8v;-nv6fNzbo zpfq0=&12fV)_;J@c6PQ2CB?AT))cfgvQBi{QD^vh4lwtQUW14f=DQ9*>#|Oyz25F2 z`mK3PCcndJ5K)6DIElWMdKX`jQVXF|9r}mfR>*!vp}c0$&Gf`;BoFO9Mug^3MjRb! zUPL!MCC*wq$CxXAFq5fpc{zpML{}I+7I@4dd9$s+7R!ydhRZ|G_nWL9gxc8+=-3ui zU)=dk5wdZ!qQI_jOREJ(oAirYZa1XxWQ$jzP3x{O2HHiCdn)SI%tY^67>U!eZaL?@#?qW=y+$Lr)b_D=afR${t1Lye8&N&-*=!i0`*yP)ErOoQpl-&(C`@YJP1qbyiq~CEg5}F;QFD26EBDEH^wh^*Rx>Wj_S?n_^IM9>ugz)1 z*-iA|{F6i9Q)Ob2^;NyA)jym&ad&kXJThdE4Q|$N5%qW8#s4ioC5li-z;q;yU&ztT z%cya6FUdDzgS9uP&?gJyWQ8*CkhUECg!~IKD4pJ zx2(ZnCah(DB5Uh`5U-qDL1Tlpak|(+KTPu~ONGm9z;33??c_<}%T~W1<@5B(p}XlF zWwbp6Arx|OJJQr`tW5dYsP6akt0p{fdH#l)1s&R~E6$fw?vG3E-f{NkjgM;$Vo%3*WABW^c=WD)wBdRz=!;Sb(UquM`hwo^!~yK)*`=Se$Ju18F1>KM;GrvaG8< zdizbO-kw_3E3}YMEvdeI(zOaktXj1x(`s$6C7HG{kCYU3ueP#3^&#HwsjH8&*`bZ| z_YmhOL+P^BpU<@`2d}E0UvT-x@_NJiqLNwmJ)Gha^rdKfWmj9_ur9URuO(EsxHgNK zm^2(cM$f7$_TJ&Njh=!Br($o)D1Nm@S5(@5P|>|lpL2Oaw0nj|SGSRfIi*?@%h8y5 z1MAfKX{HSQU;!~(xm-=I;tqd&iU9wJuDbG`561+aiQdan>zu0$@=LAOJ#?@Nm2fcC;LO3?V4OCm3c1iY$YvQr+VMNhGhi>^2@AXdRFRV>XFFTZHpG>qHTl+wpFg~l9#=}4F_M8Ojb!zNh z9(L;#GH2E)Z$T%oMwmaD$(aP_2Kft)~G!*Tjw;ViPOaXN_Qr@fpoz= zY1}}&>;2ZtjN5I!)Yjgr-18naiXCsZM<71ih`CSJ-piWodi74XxH#3igBm)S*jp@< zpL_jMS+YLju~zhXV;fuTjn$WD6MCpIN|P$ZeGRW(KB=ZDKT6$4Cx)yQQhfqE{A>YP0J2P*Op{ODY z_!GJvZ*biW9fey9>!d6D%O3`wznwE<71yGC-tx$BWGGXG(5|KP0*a0{y}9nCOm@G| z_f9)TWk;~yw`gVI4#!Xa-*LE`0^bqjs(0gY|U6e#W1zy-dA;2J+>&WDn3Wb zz@l6idL?D84u;4`&~nvIU);*dEis7KCJ9{-JuP2gQ#$r$-mp02;Qj$LdBAzJ6BUaS zp`?A8VqLpHVuR$a@|;Z*&+e9wG#S*`&L)3z+BD#?B9+yKI5K3L3 z&%AG=Eo54->?wTtSjI~>IFnbv1}D@gUt2rRG$HHOuz?4q?LJAAq2~J-c{i91Cgs_{ zMsP+TeDt00Gqt&c2e4Nn-wa=8=sUXVKXcya?Hyk9Rf{REKN5{Q)t{C#RGF5eRn}{I z)mJ;{ow(Pf63WADwHm~+n+_8X!(5?zjbQS3g1$+uRv4a*ut8kY|-bD z7w(=bG*m4clQNq({}THO1k4S{&Z+3m=ym018uYsLZhxNj1Z9=oHLs=L(L0@+`e}l7 zu-|Gy{C;VCe01-_3d@<~soC=%Dqo9PzJ#&zo!itW@*(kj zLp_~hP60hl9Wi_ft3nYKDK$!SXtfH`!ALLD>*->>*@t2ZN^|Mu=Ob^<8+5yewd0(S z?OTgVL>?cZeHD*`h?w&USkY;14R6bpRHGj|Dcy&&{?8I#eDVZq|S-m zp0~PT^t||?LB5vD{=R1|9klk`+!)=wg13p(NsrG|NKWMkw~iu3v9x#18$K5I8uwIV zruEmyBgjg%RXsudjtw;$UA+M$p0d~Qj-CnTkbYEjUSkU-oeeCGC3XdjU$RO~bsvw) zLDSOC#8-5jpJW3;%=fc%?u|90xmoj>cS>45jZcT?=5DxCocN}bSTaqgj2PgMj~QC6 z)gzU=E4G9r+ssSa-wZ(AGbOs3^*E+un}EEZlHKI(rv`ey<+QN-^;L5d%uS6$o$jaPS6xyU z@=v||eoPqYZdh1Y&wuxvLIo>8NcX{Izmyz-wZ_29Kh@lx(k#_H$Zm_++ieekB#*qtWIMC&fG~NSC%V z%7+jQxKD4~It_BfdOU_6>dw0=5i4+OPor*}uTh9oeSSrQ=f$PAu>nSW^ym3k6uX9o zu(yu!u{KYfd>+uI(y8qbGk3Ol11e=_2RVK<3^5n5Z?4zhIdm@C1q9T6X$MA zUIGN?*Ma6|-AqCbI?N?X2)-8AzLL>$kWNUW)F~r+iiQ_j53|8^_Ic{qzvF%q%Lb@A?*tr*oU5rzWs=b%CEkJ`5LH1{MrbrN{HQ54D&u6`6ME?5m(SK zCi$T*2Py4YTOytwWv0c4iHMv_{CwQhmw#-qw4-)jrK`T7FcJAUg31QER^m4XDTWO_ zY>?l=1~jDwSva|jc+tQ~%+phU8^8KpbW}o?TaAOIMpsRYR!-#Bc>~Hp(sok+Si~WG z{)js|o{{yr2<~+)6s_eOG2eTQ3YmN>Wf&5a%^ zDZ?2ieCep{Vw!dx(pSe}(M}fglI!+pzAKK8m8O^I_j@&YRGImi$$u(DspI8Hdo&luSfg|wDkeRuf4@JFZDLuZ*= z1(SkK7LDmmUU8q8jUePPXBqt|4-kybj@={M)8?5%PN#G@g zrI#}E{FzKq$8=Sa$3$YXdv0c9<|hRruD28~)8FV>>x`;(o>{gbA1yM?Pv2EljTzD( z%}Sy_`v{Y4VqK#3Pd^(utSD7bedAnd!24@~M`c@|&leo8IAz|QWPUg)J!7UT_F~h7 z;2DHabaKOmoz=)&f$xKZqXR$1#&^mjL_TiLJVO}p*$HOEMs>S>l1d8xOmeS{6{h2O>p z-A4w#d``07>y=(Pzl~DT-z*vB#0JM}XTDI9(~5`Jk!H^h-e{e2?=m#{FdEzs{}Nj6 zwY#dJpjB!#r$0)Cs8=xU*DDc4v&`%N9@~}4NVeIC9^4LbktbzCa&v@fH2RHsHh8fg zcY@b}zEC2ORUz|A(90WISySR}n?EW$)OX2iRJ&r*YcwH<(izJ*iS(7$%xDjN%J|}b z05u*-NyVhQ&l>hsXi;>%7@CLxJ*NKHkbwjKXR`NU4j#IrZ!|vzkUVo?4VQKi;qxk6%jh@H`&1`UtK4IimzRs3W za0NATzkS@L*KJ@5S7%IfpQ~U=60@h+z?=1=3}&Ns>I+Ndw~{V~B~08~vuacQx;rHXn+P*V{nlRkEaf;0 zA5vO76G6)o-*Ead8|2BlL3XsqQC-xw-C@N!v98P^2gKdaP$#ZVGW2;4uaYb<&TnV8 zkN>u!Fk)2Jb#;cAX+Cw^50O4Cp@Lz&QXFe^meFx$gSNH9x>0h}&csVL9laM?qo&u%34KUJN$L!Rdd%M2pec(>!c1ncx8NA!1Xk9!)nQcttXHA$>^(OC48`Jw0>HB zfd9>0j9QH|No$^Uq3s6IMyq)Cy(U%j!S<4-`Uf73n33*^x$cRsVpcABb#n7aLs?!` zt$U=WVfN9r{CXw$8qu)I2|61LAaAC(y`X2i8yJs;S-mJMIVbTLR~L55bK|{NSjilc zRA=;s+OGbV2;>0mHlthMsjkQu*nCOfOT#@!f~u9?wqD)(h)LW)*l0I!x+iGtVf4*( z6%nk;3Pj>^(!8poCqy5iC(iIK_0AzoiyQ&QN#^w~ro|D?Q^5;i#dap86*3XJ&7)N*q_gbKdVbPzs^;Km@%Gm-&Zil@el=B8 zqU3R-CKhp6+4y#dO-9ovvrV?Ut0pLRwIyRW-98QD@x|`;H)jccjs5QOa0L6I<@i_cO$)3&^{+U$x#mVjL~}Tw#6d3R1wczx_>5dDQx~ z9}?`*oh^*hT~Rs6d&>B#T54CI&Q;am8L>o~$ zxAXK7Bau^*=XNG!*yLR+Q#tUwc1`7k(!Gk~$&k1^>dgmyg4|U8YD`JWdrldsa|(M+T?R9*;QXA3{x*%v9Yej>#r}IQ#DOVRDKa% ze=UNNmM=l2v4KI_U@5A!aBS?NM%wF$w}M_{4#UnkDq&%$+p3=pgz2M9o?ELkoa}Yl zkKfA}K~_AQP_1H}T?iDMexRdOxYMw+a}-kcn$89${W!50n+o;2^d09)e7dh(aZD*v z?V?!BCewABU5elKJGU3HVDwnIq`aG9#g&pWLuGfw94%FPSJStO>rYIO4A`Kaa(s?4 z>lsyq{>J~kF?+-0#ylm0I_n%2p8TMPbv)U2A#4g2@zBLa7iMC|x7YM6(z)c>SisBC zhuvuH!M><~0=fpVFo7UK&q=PDoSdCE@Uo((B;)wUG1kDhg>Ib83;U|0ETmvs-1-s*xYt7rJCHRe)Wr~LJ;*WJDS zsNvNSdQWuX9CNwn!t__Gf@jDq`9ccNO&IqedW8f7EgDi#c+g|6-$H-n&vwOPwsiS zap1gM-?K}5kuBS3VPDf4(;B@-B2ovUkj2qC1<^Tez0vpfoyRM^O#6IQDRZW(<6>tw z8sBS9`##pq1_Epl#0ECy$YQjlTm5mA^eC0?6ea51+*g6QH{GP&Hsi@q`NRfI6EjXH zqW67}y!ajUL5f+-O!e!qy-W4S?_geUF7mI(Mc<%@GAfXd8E<1Ul5&dMndy`g1JB;d zq^Mhcw6GpFAkq8lDNiG08xGhRB_@s%HHt#(n@7Cpm7990#M@((9mAbP#B3Hn10B}t z8r@FGe9*eTZywW96z52vN;Pg}Vb2wfGQ3j9qAtHaoOsr44>nX6<*vM@rU{~lDojml zNS|keG*;v&D{fMDmL?}{C5!7Oo6RdLJYj5{&!)6ibTNCor{>t;c)BdZ08>&OX<${5 zt=LppSf5awhcDiTFQyR`v*|Q*Rsu_O(#ya0nHVa%@o3!1b5Hhbn!S1+{oZ(UAl`8P z_;wbxHJ`b*q`h#sa~L<(O{5M!A7z82=dYcMw@uD_>=D0Mw@g9SsrB|(CzXQ!BDJH6 zZ#us+P3;9oT#y6XTZhi0bJppuExX$o>G|+@`cB-@W}oGQ%35j$Pi)6y$r8wD=#+PY~%*B@qPlTQ+Ekj`?1ZpmOb6$e|Kd(;VDGbPnzWWIj%$mwB=^ z%Cm3QW3u9j%ALq%%+a}yX@ap98ysbWe9BRedoHrXLLY71o1lgJ?%!;Vzih8wcX2x` z{dP>Md!OS>M~|0LLXml}HlnTDzet`~gt<3NYh?p|;wa55V8=x4!T#-#R5L8P}g`WL+%~Ha;FTL1jjnu;k}!C*9;FHG?Z<;nVck zLL`Cd9i<$D6r<`kPadfuV8dFnDk&*!z*F&N%e>f*8-|I#3kgYdcdH1RM`%Ugxte+M z$71S;es6RqrH3-~1)0dgMr?v8@~=yY+Qc$l@h0anS;m&#ImRl`Gt8Z_XM>P{g#*f{ z4F%_~zYCqtoFadlz(r-}HasU#Y+pSll?au4*|0&MN&tclx}w`(?z`H%HFVQny85_( z{x+$Rp|0kl&MZoDO~q)zxc++tGCSGB$5#AQTg$KyVfCnF2^+NMSm7C&$7))~=7XQ% zb9*Xh)rsSV{Vh?lbjqB3S4mZE5Up)qSH8W!0__no+fO4;GgR>Xqm`_Ddj3PFGLML$ zg7NSW!-r3r8v;mlm--iB@2QIDu8EL6+mH0yJ<*$fi^0rjWz?qDzy;o5y%=i)^WyZ+ zp`;%}IgiN^M_cphFvAy=n?3HM_N-%PwajxQS)why6_}AqB{sn1ON=+pTAl1=HB1j{ z+h%w%0%EDQJ;(t`Ofwq@jxnNh%hq)zVV@M1h*xyZj)nGmBR+IYkuI%2enmJE|EORv zFg900#_-ZXuTddNd2~}g?P>lAHcH!DW0^wbb*hM51o@e{Hk z`fN_pm;DCXtz*z9H29MhHuF5jVSN?Rll`{+tg~?=GheT!7VTraco9U%d*DUnkMn=? zF|gB`f9NDTkar<$m{+oZl-Qd4;%RONb^X)27azY&cC_0vth5M` z&9V1iK90JckIQ<6s+2qtUw10qHYya+-w+*!)`MtM{ZHPxB#$n=)pCl@ z{T+suujlOz)#$c=)ADrITJF^i`VG_#Ivb3q&SVanjA7$tPN$ULfDAXk#@8ofKAi16 z3|T-{deBxkSQNQ|Iev#xcE-;SQu3fy^ZT)jb#7L%Osy_SS6sC#)sGEYBCavcR>|(J zdx5P@yEQMdQ$I;kKdv^kmZDW|n9!nv>W{iM?C!WH_gkyG$Nr8>w)ej7ADb(lV9KVC zMIWQh2fP3p32WmD&K^?mIjFFL%-TkFmw21r(TA!J&XcYc{8k>0yJ% zY@kyq&%?SK#|CTqUpyL=srVF;urIP8H{?*jyn)s}YQO`{_^O`if~g`&+tz{#rjv@v zqWN zG(}mb2Pdj?B+FuD^O+m(Nu}(a9hfheUprYnXWlieJvJmCeLg;JSxMu<C*mq|izf2O$Wt* zbzXCwi)JirROM~Ytp3CazOqw<(E6&`H;tGKHc07=n%znxZ(*KF?K7jrpP8-wl5xUM z+mhJwJmiS0H|v5CJ!#p!D-1qXd}_w*y$LojA8|RhAd}>d)nVPeaQ9qhKUzuXAw~aE zadGseI5yZhy&w=F-h~CpnWvV{#teAFC9*w?inD-!MZf`k9+)D?=)-xt)sJHtS{kHH@O`b*tQo z-t(p@^t?Umb^hEgsSPr3C>LYvD>CUx=hC*_dDu%b*mP5Ng%7oLp%Z1U}hI@6=_MS!E6)oKr2eZAbb4w7t=EaYhHBOh*&~UIP=yam& zMGCu{J*f(QVRO}$Re{bfOKTnu{1pI<6vPd{BsZE%K>>gs08-GsV8!3jxl&MVu#5xA zM5wB%OF?%4L4=NmjwWIo2i_+IC4&urFY!00aYru>`Vh2sto>yoB)t#sR_hXhH~{qt4+uS3C1v#+<7S9u9Xf zb#VXyC;(&N4G4e;2mlT&!EOKt#()R{01*TOIM@q<0TvJd8K8friNFtFK>$DlI8Xzs zKow|mtO8(3AftcO$>BLN#sdFoTI)AOa38WYzI2n#v6}b z@=yFP{$ashpuJQl9FVv^VF4PD030|2P8+!~(&tnHDf~-}R{a(u+dwjwNFXgj(*ZCJ zBoltP0E`2Cf`2CLFeK}r3FBab@vj7d{424?CxG-b#|A?V{h2Vu2bla!SQ5y;Oz%SB zFt$DiQ9nEJNAGYUop!!(xGyopXD9I;r!8DE4<`IWwkzPDdb@&s9UKW{GkLoJ&S>~a zy8?XS|0cI11(3P&z2N~n?S85+4@INM#9$L|vNxv%T-fAZ%wE!u4(9M2<-M4_+(ESm z?YC&=Z`C>w1OK&JdsM)pd~Yynr|V+1oZf>?a`_cY;8W<2E4ODC@u{5c084~Cvef4s zDD@)DIh?Dx{%2Z-YxOHPEx`Td#+)Nn2GrdMMnH^n=`-yhy=_JJDh>|dwLg{h+j-| zTmiriUv(1kQCWZw5MZ`x8#$vF9 zrCB0mYR|E5%as8DguO$^L~}F&9qdg;bHUyYhXQ}BnadZIITDVamUs-u-~Zd~hlKs(+OV`4GuuBK{w8!C)-L|L^MD*|(WH zFoih78TpCJFUmO^kd`)PaP>GEK#}vqiSez)Kgc@(*$x2M^Z~2`kUu#5KREn9IQ&02 z{69GSKREn9IQ&02{69GSKREn9IQ&02{69GSKREn9IQ&02{69GSKREn9IQ&02{69GS zKREn9IQ&02{69GSKREn9IQ&02{69GSKREn9IQ&02{69GSKREn9IQ&02{69GSKREpV zx8m@*Shx*bY#av_4B>#`M1c|T1w`P(#hmX2{(uO`fCxxjE|7B?_0%_Kx4E&)*>PpZ69IdfQrDObbaNJhVUKXdg1s$ zJeuqc561@(NP6K0a$Mtj1d<*{tRe^Js*rI8a*Jn#yIAjq8xw=ka7|@ZC6uZb0Dif>E!7q5>t`Uh)Tpqq zFy%0HWnwT!1)-~}tD>r=qNb)4?CYmQIz%9Qhbs|C@;@w?ph>7;EEgva=UDXiA%>6* zVS@{!=^f$2sc%Ugl>ux8M(V!tsID*8g7MM=#^?Keb6@(@^sNTARdyn5x*JNyLy~ z6xuWtO(4s2Dht%J^Cn{n7y~)g#iTXS7wdP(#G8yZkmKwTQ9`IHsi`~sIO=_ys+yka zlB#hq+MA62r|QxP-^!{wOD54|Z(nb+_dhk4&X50xQDU$Ikr?n}l>OT6@|Tn7<>0<3 zJwIYF-kWS7hsAqi&?*N5(HJ?ncSyLNJvtcc9bglJ_dy36$o+o&^zNQyA)Fb-37V;~ znu)5ax{0=isg|0Vjt)ZGL|02w)y!B!-B?RaUF}C1OTuC}IAy}|fy!8{ubz&kj;5A| znuf8qHp0{tf!L*MW@M_XsiSRbqNb*%tM#MoBBI?p;J;O`A$*4~N)N>u-o)UgrOF;1 zw8RBq4gVhF9V(o)Cje^*U*r~*RsLec7p2FAUXzy07zL1j8sw~2dI8>?X&A1wgeI5! zM=k%@h4uGp7fo`i{aF)tA5r*$V(r_eGOX06ZAQ&u=^# z9nL*bz?c|#i2Ec2-;CME~7~46(Q6a&hiyGV$V0giDAPUxi^*{#5gUvt*r~z%D4|W1mup8I{2jB|! z0~GKFcn}Q2z+rF{oC2}nBDe-_f>dw^WP&_U2&mu@cmirb9cTjWpclLYAHg{I1ZKfJ z1OnlQ2t!sw)0wj3Btr+8(>N>9hfo97Ul-?g9XE)VP|3Suryd6tQ=MgYlXdo zO~AhM@bRqXf%7Qw=<`_cIP#!)f_S2N&hgyjxzAI=^NgpJXMpDu4~tirSBiHVuO6=@ zuM01RH;nfbZ#?fk-eTV8yzRUnd1v|f_{8`W`Ly{g_+0r8@8U;QI%r9TLTyeRwHj-k)`qW5TwA&Jofu4P zlbEGgfLNSZp;(6)LtI+iNE|JGMm$fvMSO0ZNjk`b%70RjRj^h#tdOnHvr%B9&PM-@2^(uS&TUfM02{7GmKfb*(Y;N^GNf@7Q7Z#7MCnKEu}3{mYJ5H zc5CmB+WpK*$jaX8rq%mBTlWO-DYu4N@3y{T{l;da4Z((L3v4ZIuh{nORool2w_+dP zzP<-)2+OM|vvd^-gb=c()=g{l8*)hcNsgtOahf}80oU@7ZW#@M;DlSnj zb*>VwSl3cFem5t#du}uCrta6=KYD0-obu@KRP+q@e7Rp@f584qFHtXVuc8CI2b>RN z9a!+T^-lAi@v-zt^7(`^MkS!eeRuj^^&LeUpf96`{S5pr`;A}>Fjp|6{z(6L{|T%y z_9pi8L5qW_2j_6MxC|USz&RivzYKo>Uq)C(z!9DiWr*R#=D=-%rvl#v=>=U2`V?#x ze2)Ynd6G)WYsi7**CCrjPKFGG8ipo@ehYI7D+*s3P6&T}XzQUfhlV4}BJM`=M4}>} z9^P>H=;47Vqo~`_kZ7Oirxbb03ChPK=11-yU49gIwEmdtvCGHk$DNOtpO8LrWtBkNj=ST8hg6ojQW`yXIN)_&%TOPjg608IEOm->OA87_4Diteis_z zwBk}O@?9ic?6`!ybpP_o%Mq6cuUKCxxeC8}_A33F*R_}N8u6(K%M(Hp-d*2wz4V5{ zjf*!HZu;MBPu!K5pCpxZCTT9&H@PKcXG&hGbZTrW;}-T-*KPCLC25<|;?w!kL(_-u zINhnet8+K=p2WS_d&~?%#=HA=_n&2IXJ%$eWyNJfvqQ2+b3AgIa!qne^OW*#=ZodX zJ^&9w9*h+nDCj7(Dtua`Q>&wr=&u5!R+ z;Prd^_q~It!SN5I4+|ep3<(d#56cc`j;M`18Z{ej8gn1}I374YKXGbulG*D{ZOeg;Y792^9N{dT9rzl@KUM*y}Q3IT!;0Qfld|GWd@Is@*E;t3a+-+)$<$2S9JSfe$yuWCY0LXBzQ@T|PN36^s#^!Q==gmN*{Z8& zVY%DI)eYm1Js27mekkJPshHDe&R)G1pK$%g%{zDRW!%rqdRSaSEiEg5_PnO{#miT1 z?H!$6-8~;Z4h@ftj?rgk=e~VstmL@N`8+Bw4-XF?A1@vPg{|b-u!5!uXqoydE+-woVn*ip z>xd3<(mrvL>+sht5?Aj$HPd!>#t9>TDbU!pT2&-^hMXmH(g6t z?4dI^GRt0ekAB~(x7+Pt#Mzr!<*$0i7=QhuYVWL7VaYXd*=t%nSw~(OCT)@FhMr1Q zj{h*m2F@bojvtMj&}gPJBUUgjcY;#gUugKY(&&3D(+gv__K3s{^NfYQwxD|*rAR9l zMQhF@NklPUghvE9G@iJ@*C%JSl7`#MY@NA0Usd33eJwRmr`!Fc57+jlALtmqv7 znmd$irib3EBRC0*t#LkrZVM15(&_fJ!$7;b*9|s6dTjc9ptw8OOJwsOwL z>eJuhaK)I*bCooi32U=JWL-OHw~RDtZY$PEf#>pSXZ-W>$|C|x zDBVfRE`4l!bk5TcS6H8?ql)=Yk4Kzl15wY>=6gc}HyHt9Z>}(+?+DK4+3Xy5C1{Q# zW8^|Vyip%cvr71)y5u*u;GEsz-M-lH=6!Aen%DR+2ke}a4 zg@2~Y+D6~qId0Nv7=<~1T(iyf$bol>YnMkUz*sUfotd_VWutbd-W?-6OPx4QM=>FW zvufea*$$%yX)y-DJ4Ssh96h(Ec67X>9HkDvr9Ej^ugz<7`w+|5>MI7>^`LBcbQ&e4 z*S96burkb{DjH^>Lu(X4&DA^GU3p${)y?>B$mpSrXq+~~CXDNngvF%Rm+iK_8U9oSN z1WE?YCpr9($lcVIov^*`SpL0!?}U-frqk2=qj2!yIL{FU_&Ygir?L$@OSM=TpQmeX zWbDtgO|@GQ8xf@~lYhUxQH*u`?P$$$X`IZp@rDi@uq??20>!zbieq)tZ=-Pe@_;ac zrwcyW@%CA8^zrfO>eo%J`5~A4cL}(!vUnh-(DT0L17x~QHevtRZfp^#dA6So;^8al zNTb@ynW;i}v+SkwM~2?dLCm-Fx1D4Ik*N9Hp_rzbr(2x-pEaw!T=VE@XVv|en}*on zm=X0ubkuyV#HTSAWNCEL*38NYo#OM4#o0hMx^}p;s5a-`D-EXP?#r(_OKF?f;3REc zHhTOp!shlJO0eG{Bg9MiS+x_}9{HPHbUh?~)oa0=7VR0{+9|C&!n?;%eQdI5x127;k$y=6Cmj%ai364{%Vo zS=>d#dv6yY3K26^Wp9q&mt5s)Q9Pp}McHq;FhAFr@AF7+NC}R#{vRBg_dnH-De7-aSVP@=tl92(FpulkcjWfReBF6g(Xr8a^(Dso@~J<9I}| z(;w&lpr6C#&6o8wn;r&59L?{|4_Y|oPE3Rbz5B=&g4FFOZIYd!&}8G7Iwuj;l+z;#G{L7pzvE0#NFWT} z(+r81`q?r(=ns*+g|YqPRLgF z?UeF*>)Xw4K=NPFM6gSf<=ukQfYoHIgXMoZQ8I4mb|Ka}b_36!zl>!ZvP`T8FsT>( zq2_&l0>?%c*q4_~tTzQC#X{GV*t%_|umXSLVn_S0N^ZEe zXrmj8IL5~M2^KlMb7Uurwkz6M9BA{=Cnu^e*d(~Zr!KY&W%02frk?z@%kLO(VqOLRelhKBw{ipYtKe9U38 z$QVEM3Q76lYv`}zG8Yyhzd&fd@TBRs^-Q=u4gJ7hFt^t5%%1PRE{7$VRGAE;tY3E9 z8Vi9P9)XjV=?Z68&X9>aGoL_%hI2E7$0 z1Siq!vsG-n#g%^EMYqZ>{#g1E9Njac2tCmq>&se;G|oObM4j>~?u}O|xCzPs_AM9p8`C=j&Psd!p}#9Q+*JB&%f{Z@CCfhLUqzhr25k2*$+44_ zZ6Q2RAL+_*25_nR@YOASl){T=vrlxQ)xm|K5nrMeA1(~4gDyHph88)zKXaD{cD+0< z=nB{5@j@qbU2%x>LQWqFa`Sr`JEjPf5%3Y3m>}l2+ob4;`Bjr!OAIX^Mzf!VLH*jr<<@UQcu%sAgEJ1LZtc9n3V{hIS z+0lh)11zt#nA@->L5;HLtVcPDW`eLk3UsWCFI*nEoS%2h08Cz=MDBS6wSj-S9mPcz zwUDS^M5>OlgwwpV^_ri5A0%zu-iFTmwJyD84s6SKyZEQ!L0f&O_q0c7&O6!S+(V^8 z*Dmfic?QQp<#&%Q7UDF-i_CkSsz)DW95R5+g@22wFQ?`k_hq9~djG3qa+OS&jGg-$ z@(hP`n19`?*mC}3-&CGhUQqBbfkdX9CTgb}g5KbBYZ!plx(l1en~^j2_R_rt#Z?+B z_@g*xBmwUR!crU9X90!jP%Z8j(7WBVi3qlUa2yN|o@9Iuzx(&eiTH;H=96#pxh^M~pIyb(tGmyXJv=_l4!;9}ofi~) zPp(D%*cu8zJn?)^e6W4Z=%xVQoix$ncEFM5D2l*R=!DIt*8J;N*q&N!NJOi*|7>=? z)iZo-4r>0j{ZREgZya0^W@5`HXkkY6*^FL%l}QmjoxC>EFnM}ID=lf%_QmtZh`zJk zO=omBzYLI`JUjn)>I`;LhLzg>;pACTMeBsZwK zO#18eD|GnJ*38(rXjzoyyM>hK-lSi_uV3I-%4(|Xa-{^-Pb~sluR1vyly^vlZ=Tva zUK3nYGQMCP_pJKqp8+N{HOn49H8sJn^Z3>J=JS1|tm?kdEh&EXoA>{4+LAj}saG`p zY+tNKF#vT2u=1pX$KEh#b(^pb>->e+&cRu24&2D4RdhC`Y7ePp+t_%9pI$wa@5I-C zr!KtzZELbifKXG!{p_Kul}vYHOT#Pl0QSg74Qx!7Z1P4fouL}LA(Yp~{Y*8oxIebp zCQ{PxKNQ+&M@=F4XjJEw2kXg0521JLL0Qm zLz}YCnc71yL&T=@b0uTWGJwFXTHoqOcuwuoh2m@NpOgez+9vhJe&Dd{G>*mDjOABMTBSIz$9VM=DXvnP(qa)*Vbx~M}!l(t)f6bua-WzM4ksX+d!0mfp zt@|Wb1^1>;*R7rY)Ml2NXtoQh1Vwn$duP_OGEiyceq&HQzR4XdmKBDH$DU#_Q5Ohx z>)6IH(b|lQu{|A@&J4iDKO5XTlQf8oB7Z+hBR=e4GY&}-Xad){i_osM=wg+8k2uw%~(!N58s$R88LIDcRbJ@>k7UuTOQe0WKBflcuFR5w! zo)BuZt8pmPbu+m_{f%p?G(8F|cw5hQq?MQ}`-cKa*UKmeu8G`^o608QmAs+O3}6$z ztp-S-^laOF>A~hL?c4;?zX9;6qMyc9+C5nc_^krp!Aat zfT#?MQK1)6dBT_R3C1;AEY)P-j+yJDo6_#kg1WxSU-i22-*0gcb&HPNnLmJb{6tO| zKvKvkNH^CaCEX%OOyo+>4TSAOEA*TVhqPbolr;45x0g{_~ zr(>ae#HrhF4vWN%TbQ|=8GsdxXZTO(!*Kc(bhi@pcSPX(x6X?mA43KZ_c1%NsY7P} zfO1N3=Ewm3D9^)jaDVn7Yc_YeM#G9NV5IMDWsq%SYP4-k&;AJz7QsP{K1H4rsB)`S z_ALhlCiQ6dBx^dfbKp?H1uX_p+%U&3P(x+_ny#^^dgimB;DfQy0Xk-Wd-`d}RrI5b zjf-qjnJf}!`Ps1Utk7X}2x$zvObDdJXew3qz-^$!j)lb;%0ERT-hFE4YM3?xUh%$9 zlE}0~H_@er>HbDrv)99`Awx!N7E&=i66)6}T(B}MhSwZDS;v7wo>Mtc^3p|tFd};B zWNP@f9tGl|OqL-Fh6UW;A9`mS8cxT-k(lTrwBthjFwJ9$l*1}-@WayJYr8J8G?>VX z&JI0KCiQj>nBGWA*3gu zr%~(HJ*dM*V_9bg;9;rRG-82qIE0kkkiUtyGy!7$Gn9G${fkpM(e{`{xKwLLgH|PR z{N3eO@t9@fHUv9%7U3@aA%dKz$yM>X8I)}5z7!q70Qli}i320&3YR2n;Y{UvUP&we zsbZuy?-2$@vMW6yzg0>084Wi5Pj-iCrI%*M03?o_VbOlwwxsm8q_Ch~_Y8o^VhP^H z0GgMeN5c)sJ{{2NMOi6_b7q3ac-M5c8#1KGtB8Td6j#;1DcQ(Mf+sK7qe@bL zdpfG9@Nv3;lXnnX3L8ykO^tU~a+7x2fVfYVp0F%<^YAMjWkXy_Er1e=UG{V|vkeRe zcU2~qLY#E-snf`xM-hHkrpnvUDaSFTMAjM(=FnZ-V& zm($K-&=4YFQ2dcOZ}!w>oLP@-Z29hS^Wtphtb2%g3x_a^We_Afl3v0>-`yU^x-TL? zkSskWV__jqy!2}E7*=X_<`ap4(QT=$uxoF}IoN&M5jm1dEs6l3<5hfgBsrAicuU;W z!sK#B>>%$@yNnfuh0ZdYRE)F(KXFw?((dMZrP;bAOA*6(HhR}|DCpq&EG@{Lfl_j| z{@k>_}oR^?HvD67stClI7cmD{ZPcRVn@e3*stb=g1jn)9@#9 zcTIJ=?Xg%;ZT`sS(i6VxOirol@mwrb>+ok`OsRH3{YaMiT=X>*|J`+E(JBN~A!Wj_Hg2)~2L(jL6((`}|kKY7sl z-@vIN5u0Ddt78g3Nk6bSg}>`Qy|4_5s4{N$Q;+iber>epmce#xpN?mZ#+( zx{t0!cg!9=P9<+QuCP$78dIN@Qp>@LWL9Veg#2=Qu*;ii&UsSCZ_zNb^%u;8+xzgD z1ynP{AdT)`Sob9?(l-&l@?`(Yze#&;pWDi|9qw(%>3C6OTbL6Cd(W{>!MDr*lkd8% z;j{AH!n*|)cEcS6Z=9xWM~yxTG{d4De2F_qgP>Bu@gLF`EH@_{ z-y0~1g|vsAKM$am>m6hIcBO_6zO~Ymb%xgU@AKO9j+XgyzexCQICgf_<0?$*<&R6j z`uBH{F6<28sz;1nG_7k_^4HBJLw?1g_DQG5`3n}#E7eq7bZl3M&3mia@d?g1r=W)T z7RAME@d_@PN>g>NrTWWduzdy}h0PH(>q z%QR=3Jj!a^yV)$86BfN_U>EWqJE$;OeQR;#;iC}gDH}-2d~UJrgsxBW|9X0$ky+Qz1} zinIjI&W|Qrrnsxr?#h!0c#$rf|8v|q*?HBQgoVE}efOM*Tk-k0CG<=va}eMq+X z!InTTB2~w5Jv7-nfwY7#>l4&tTPev`&MJ|Y*l5zT^V@xmwF;GB)nTM%h+LB0&^{be zDH%LwIMTvmrmzS1xqrFUJL~in4Lk-lP_ny|LbLB# z{A|-YWvbdF_G9Mnh;G$YV{$YW|2g{Y>bJul9AS+PV4!S{UAvX0R>61XzouG4VUH@_ zZV=UqcYST6d0R-!yIY5oUb+gVv{<1S`h&qkx|?znNM*ZGfK%C7Cv1aFcckD1W`bN<>eSV>>5O3a&ws z>8lh=3i&{W0lfNo;3|HJnopN!x!2l3U)D*Qy(GS8FU~lIvC4 zt>wJyLCQLHQ)aq}{~ng1?n`>`e}Z{TtV^^ajq7tXZ>%6MGk~=P-AX4g-+ z6l07njbwAejOl-q@%6fCYo*%!OP-v0OEVJqCOkZhe=tx<8 za*+dWl>B0CrB`#o6W7{M(9iv^qyW3VD5WIOy02mcl)lIs^0CsR4NU4=gSO`Nu{eFe0$6fPRm0)bvc`;LCP zD>vL&Y}lGjDYlDuOlO^HmU70+>~Htk3?n)JAg;CNX2>E;c|;;Rmh$8*Sa!Di(HqQt zOxQYPpF!v$yteQW=ft~b*U&0PH_`u;alt9>tOv+7BM z*A|BH#kC+L>dI5*PxchpNmUflfAs&Y@7@Rs8kEFz{>BJSfwM$Ktvs$pUg&x{cxA~P zpqH(0&$xy~eX>ryk7EGf!>EFY4ckPv9;*<2mObTLLXyQW)_AMkb6?nA?wf!4&6BKY zE-;4BA1; zj(ojE5JAa12DH=Bh9Z!K`=^WPt$7|_g_QN@??!W=Gt^18{VzK=3yf7|K1z+aeMmTC z8`f9EBtz9Zs(l1mFauZ`CvlNdHJ9I0r(8yi#7fy$ceiJ+eKwcZve_rSm$yA5V=LTQ z4RGaDw>9*DJ;=1<(ZL4W#nHj~1iM04mttdSs;FZd;*TiwXc%ezMGGF^_%@HtWb|=U zSRh1ht=w^Ha%P=SXQ6CEGitoY03MyYX21X@BIe-c@G4AnJknc@0XR_5pyl!@_}50| z-~ksdE|1u4Hz;D9V3bI&Ra>Vg?Vm6J$wQf$AH%~)>#76}*WCL=ZnJ{*;A)-&$x*uc zHWuN08ns2Lu}f%e!u1qnXxWg#yTV6}pJ8rcyrRZ`Z#unKm6366%)1iN)Xa(?eLW(Q z{VwR80}rkeu26Ek%jsGR-+N{eCKA+}_}7)8MW5uypgVw6mOnoSH2~fa3?T(HZX`d%NsHAEXunZkHEoGhXzz^v(LbE;z?{sz~PXn`xz;PUh4^U3W zw8+RCQ7c&_9#2Suhs7T$Z~^TWOEHWAa5&d+AgnLgr%U(uFo1{t^hS6I6?&8<{&b{G z4D?f-%}ZYcRY$@epm4=7LBSy-clDCrpiRf?Z3rn>cw7-%cWMs<@c!S|RUdP{PhL^d zx*(gUyYo#rR?=g*3-&VV&=>yS6Ef2O1WRw7H$jc0bvdZdtzE`}#tAOfC67gI*8k#NU1MrrSfGX(OA==52%VYd zS+#{Y)?A4i^jA}oNKEADaKos$kKUB1Yp$gpy(}ABjB}u2Fp$nja=t-&{~IMCdy6vl zEdh9pE*ZZDTD+Mp5FcjzMADRZz%yc%su;z8>5v^dDMM%&ZpiOy^)aQEKx-#L}ua`G(k2Muu#G- z&UWiTFgAE=Q|GDld%PQQY=oQ>2H-M_K;}D>sw=y0)P62K)%(wqCkB*R116AY(f@Yl zGtl_ZYL!CsvfvVGsv|J#@;^`9t0uXr+2bPWODHkASzczb9WuMn{cSzS!&vv2-@St( zFCll?833g1Z}R7?&~WH@(lOL8IH_tLAS6UpgEMbeRIj(N&ly&vD)>h^Ha&Ntz-4H` zzND0cWsc{KZ8Im33Db;tsgGrb&9*DUp5hTw{03hoUEm&7sLV`=AF<`HxkVOOmF!UK z_OGk9F6{XX_^L^k)PRioR$uQ5POn*rldZoyX?*5ig;Tlr)JyC=;gQyitl0O2(Igiy zs@2b4UAZ$dh0dVlHR^*U87Fj`JcR)?Y#jv%X=cu`fd?E;4roo+D1bnqfng z?7^J&brY8g*-#$iWG)f?*}AT2*W2t3T;#dcQT% zIRXFB-OCYMDQz?fuaaHDD{h`MK4!9qfA0e3pGO2D%sMju-3|y!#|oro*Oxkl?u>y> zE?4l$O`2V+z&*;<3w%Od#ldujgr4tg;(u@(*x6iz!Cq=pULm(0PhacXXCArEWJ{5d zTwMo`&^(GyR3_C(b}kY!feRz9zZZt>XOCgO$8Gt~-V{wNA7GQJzs@Tt@?fW5#|A5E zoZ>VlKDJ?x9|?9y?pGALNSc-@PGGxfe_UXE#gd;%in*KXQjibg@uy5##I$k}XR_{9 z**P}$l(RrHa|e;oE%_4sk?z9)u1J$y1tpC9UveF{J}qcNsmskQ)}c049xwoCEb*nv zGp0x8KQ~9CK764+yviFCNrY6`nMuCo`~6{on%Zm{uAC~TwI#{SDVQ94_lh~IWeTgn zm6>?+T-kHCTyj6I4E;XC)`k7~`7V#O_8n0bD?`F%MA zLw4VISS`)z-D~Av-z(l`o5;PECDiBNbIjIS(95cgDb-`r>j5|c4o(1A_u&EMRM@uE zv7ysrf~(e7D42iH;KfVqRaLN2_cu7L{yRKv*X@PfBf&9d$Y7ZEnS-i5(nL+llL|rY z%gjWVT$wTdtP{W^&H#Nf;dx@c?~@uL}Yb(RR%?9hgOY~$kOKA4w) z%o9|lbDPCPVroyYUpT+4WO@IH` z7X|y>c0W{WpQJXQH9>EP>1yw$NM;e;lAVj}qci$|lIfn7zu zigBD#idCTY>sjWTH84!M^C1K9828V9dtx0w zTw+L88tw|*O%!3dPKyaSN%?R>DD!3joE5VpMre5Mi|-T-1q&m)3C!gqHtFWSvRRK0 zi~dc9n*tK;AHN5tea@40a_gBZeuym#%D%)KVBad~pC`93AwoHjHdF8{x#k|g09q}z z;6vZw3!Mbvh1O4V-5hW&WY))y>XvtfNxQR)hRj+-ZvK_>6TaDmp2gEoFL0ojjiOOfBrljs}>LgU_tr& zJOZ3eh@l&M7Y1+hN6Jl1|0xU7oVmm%WN25ZX8^K(v&RWYULG<1&!FC;uSY`ni5&Rm z-&gagb*`lv!W1R`J6ZmKEexzX*qST-F4&4nu_G9WyA(?Qj9_0h@mC>GElx$D(}r2) z44^s^vSA7N6F$`VGJTK<($3y*M2UeTJF^l_!DA=nZSzl{+FERRo=>wP3y(%e;N7*^ zZTq9rJmfHv7bPBIbWh?o*YWSfhdv%wa=T#@a0#kk_=<(QOpK0~jEAgStTGC0hvC+v zKzFecC=2(_gZ$6$qV-sr3~)?~vRvjpkjQc}ME`V zXuybNsM5d^Mzx#J%bKIKOT&cSZQH#nd)9MOmb;|7D9BBDsg{_&3qJluM$4}mfXB?2PW;Db zoN17(fT4pxk&A5T23n;}_@FDiSz^P8bCl+>O6udi1}4(o!qVg35^^e6sOu}ssx-AJ zdNgU2(9i^kh%ta1!anJJwh^bv)ul{ZM-*ZIfB^(=--~)F*T5Z9en^gS%hMk&)7L-t z!JQd}dKBqwWS)^}Xl7AcbY%efn?y??Syw-ZNcz@Y{*%QnhmsKf$zy1 zsYpPq&lLp+S)3BkH?5h;}SFSW8)~?{qk2Aq#0!8XXJH2M$Xd{-;lRn4v!xHFq(O z;!Lp>>{#8yc=SjdggiBpKrP2k?voTkdk)4`!>X(nW<5^05K$yM`jacwsO{#0lWqm!%iZ}&JI?4 z;-ON0R{b3y7z#6n_(Ovg(e_Cm!BtLi71KyhJxcg-lN7vGZniEhgoryfi0V`S5A~-Y zGmwn>!vGS{6tutE2_GT3!yRtQ2E+vg{-77zY)@%-;?1Le8kJ{9_(vN_#SaAU9JSnd z8r38g4O(KZk=wB*!U^+vSPET-R9hslNBXFY9qD1VjnkK<1=DwKQBRLtDwPOILae*~ zvDm|S-ZeOwFmp`qv}MT5@!c3(8x7S{#OX9Y98l$jawSY59mDN~9bP-@B?;AEnq3>M=(oS`c9kvAekNG<)C zJCwwNY@=FgD0yy@w2c#s8jA+~6f_ZGP3~ z41i1WkWO>2TfOgH!`IO2+uVVn5HQ*_J>7$s6mlru=dnt|B<^D$Z-07sJPF=_K9v(B zeSa(A_E;oBno_W1RL-m?b-|ycOG|@z>_C1o579WTE)|G|4p8{$64Z-%rE{QNtZSe1 zBNcM{DD2KG(TETiJy96dUIF?Qx8xYdv`7s;mZkAxUQ#;=tGEP3PCAEdoK^=$lV!H^ z@TOH!mpepIHy3PefFO5J3S4G8k5&otoAeDp^!n=h4-QM|86$EFhZlRyGnccS8sCCT_!i z!dSAd;6Je`2Jl*Pbf$B5oDiBfQp-VlqKS);$`+bUb=lv3Mteh=1wpPVb>}^1HVEtS z$g~hf0rHZYv^B4y!l#RkL5{-LSa_rqv?Z+;*GydawtFrdlDF?ea-+Fl$@^pbv8*&$ z*{L@454oD;I8V5pdj%K5TMfI|)PY)}MQ^Ww@L=68+fEd~9O$Lm8-5_^aZJF7;dV%~ z`EH+!?P3Boj5NqRdXD>8j#-2|={+-_LHddJz(E#WhWbC^^o;;%`cax7uC_!1;>Z*N zt6bcRK1D(@J_hq=^Ugc|sj-$2Jbt9~X{@4n6R zDn*q1Yi^PwD`1XKAK6B}fEQQA;BWSwYqLK|`gcog%en<2E;|OQ%yse(yAu;2JQB$O zpt@rQqBj+*8^E|IeTa&BOs^Gol>rF<4O|mD7oQE(7ILiAsTpZUkegrJ-S++boiMm`?ErVI()NBxYS~)z`+_1#{I%u?cNQ~P;!uiG z>EfNETwT2VKmeXpCK$|=-opUy8ipS#<}rY)ppP9#Mb@yg;lSxHiCxd1=WX>Z&Q)D7 z7IIv#sQrbv#Sb)f#7iO^vOhMKwA9uaAE&A8**)D6u-l?-q{NSeF)bKhZ7uYv0P6!nv+~ zW%`Jv+jS5ki`n}4*A8f45fIPH&O$?1~dJxV#9=eEg>yvG6!LP;{z!^}n`X~9@!Km;88=A)RychrB+@Nje z>;?E1G!vf}T>>YNkxqZ?)AGC^CgSfeu|BML+q-e4JKX$h^SC=Se#j-cb=j=_hD*{& z!rMY=y^9EZApAw3qsG?tkoJ!E%D{e zplZ$M$40x0he zahVs)zCF*LYEv96y+0t77sr<p{N|XmHhZi8tV}8>Dj~RB=zV*+#`60Mh~A_)iv5gVPzvD|L7{1$Z1d=5;&% z24$>XIcoTVIGRcWOKH)K#F=MzD$f0`o@M~Q@4g6ZYs~for+M&n9{DZ${vGT`3@k^T z%KVGu6RA-Wyhn~MPc)@D8PMXTc4pl6EW`HJ8sVHDNB2O9po_-$v7WE2?g&*;9(z-J z+*2gK(VP2&C6{R<(-4~s!Asz`;NJ{j0dsHIGTXH3G#&NXOnO9uD!lA?PN(xOC>6zm;%PERX&YbVj#*67v z%sTKV_?Z&q%uSO4%vsuQInG|qS7CFumRm?0LmfAh>EkpaTfAJ*5()qiNyiw|c=59T05TSUI&EKxwhtiY0k z5{{Lu+THd-2Ni||s)$9IfFe2*goN8p=zqahG@XrNCEWafzahzFvK_eo_`#By*Dkhu zEJ=bMiEz%HL%EB?8KYAw?0L3c>@mE$Iq)j*V)-n>_XqY|Udo@*VR4_Qf1DZxQstF~ zt7xW(QXF^^y2}7~-ADQoDlI6OeAi2NJ4;NZ-1G{;E;EZ1$7l=k(Y7L?VJx=dC1pkJ z=@ZYM)HVdSaeMRCxm5UP493ndUDChOXc{KBaosgu*Md$a_I zz4KCOh&}QF;HYsM`U z8uEp>sT=)*G?Lb7;-9TsW;Spo@Bq`L0;pd_`@hy{*NJ>BtjyMWesIvw%SbHs{Qp!m z%14mrvA0OGot0OFJg;38C9-6576~ItC1`yg$a4_{njPu;*C4P}+sR6AHuH}CED3rT zYOO%8C(jw4)s6Ns5NR!9LXF1txVr9-ei=ZH$o| zT_48N$?Itl=MSq0R~O=WdH?gg2QHF0ixK=$uz5qe%q67j7qewTeepO=(xXg>odFPb z;MGTsZ7JT3Pfe7<08SH`7K)~Y>9@H?^5npD0J*arsS0XrbMN9>Vuo+|JyMa63G1$wCj?;dS^ep!1Hm)ild z7`14eI-%I1nDlYKTmi&@Kp~e-Wcy-!h$d$GxXL6&>s?L$Ap#T zTS8mCaxi_wVILkfk3~kl>>Nl2K1IWYBtAw`XJ$&GPg!45c4WX$oa!Nfi+wI@@yCXQ z?Q+EK(PGZn)0gc<9iA3~k6w~RZ}BW zwSa2%o{lze|E4#+`KbGg7I}K}<0jE1mZn>5uA4O5`M2R|)GB`hlU+dEp^M`z5k8r- zJq=yP>s2o3u{HR^pJto&aHL9-wx^->Q%=cqh+Sc6ywrsg$!%R4p>yTcwZ!HFE0@wS8;vB_5TEIbD?t&$p_x+!PR26Dr0tnPmtW-gOujE8QgOXufCqjDBFQnrX!m|i@;t!MiL3Bi{%EVlh{i5*HmreuB3 z@~8i=#$6&|hY5|==GFPumtxvt+Uj|b2W`V>+epY9Pn7wXeO;Z>b#4LCDPFtdc62>l zk_08QMNJzqVM~rwogS(e27Ta~CBmIB$9!0HNDb-90C%zOYgEJveOB1H$TOfZT904P zl+yhnrypJZCa#xI5gPk3B^=*6s|6KrcC7D9v`@RZWcl|$S{1JEKQF?vKK=9IKiPJ` zQ{wZ%9~0@KqC#t7*NyS6;G1qac~`3wo_x4ke#7sop)w%MEdWR0PIVH+h1M@GSm+bp z>fo{%05gHQT2|IXVJ_ftIl9qnWME=uam5D$vBlvWsSq|X6$hux0m7KJ?Hhq-&;GW4 z8dNH`GE8_IbN1+NxOi*W(CviR`ZZbrFBt}NyH$RZE$xNm_+Rgt*O`;rD4Qc;vv z`{n!7S9clX=r*l@2#W1ZsBkJO`=&~jaXW`diA}YBA9c6$r&Lo{BEQId)|>Yyf|q|% zvRoyl^(yt(t{&Hoy7Ydk)d(7jV=?GJQ8{jTXc#)u2R$K>2j`dAO%+(fzRTCPXx*b< z$uZ3T^~SI$^W%d(g~5h*mRPXb)=vgtB66s5uF88SVQgh3qzKe|_%$vwslv{KIbbY1*K^<#uP6 zO~~=&Ch^HH`vC*l_tIkzyzSB*J5Mi^zxZ>R@;>9?lsSq;dg45D0?W>tGbg{Psk6{% z=G4b;9?V)@9WR0mfsw?8=d#(@U0bT$&UdAlY1K{yTkJ7rlmV;{hS*r+4(-?O{|Yt@ z{E}v7V`ISm_lJac>;5zTZ`LJ-d&j#e!!NQ8LejF8urBR+3-^{&6)PuscyKWz-Ch8> zT4neCQ()ezyk_hRQY6E(W8|nM&&AkS){i;S(3OXi_ld|{to4}-ATUz%@o@j+F1hf) zTJ&_$jITxJlna9QO<&N<#EJe#+K@%2{GL$qoPWb(W+W$%aJ zqui4AI4ABA&V+0!`Yq3MnRTLy&4GrkBQHQUsJ-dXceha$w>d%~ur-s98K1kJELHTS zB&EG$2R{oWzFq2nEDbGu)}d&k&yh<#?TgTKf3XCen}m@2>uc`{Tx~X~Ean#}i%-eQ z`Bqj^IgZ)Szv9sqD10QO>HIZfo$^4RgDjP)X5nm^cgOIl{;&gK_r(b^klJRh`Q&9| zzt?l~JC()?@=%no)sRpRGPf^elmWn>j|{pvG}qRyc(~uss_IS5xBYRKKkq1WDs?+! zv|FcpbjY{>wsByk;v0BVjIECU&us~=%L+?ZaCgYru36jo(XJoCZTruxHcxYM4GK+! zvabU#^1bjI*x!av{lahXU#LTuL^;2A_M3v3sRZ4=Y+{;;U3yyku)cJ_oA}ZBJ?N*% z&*#}iEqRq3PBK{+%j%eU5FP7n*LVy-1M2EEt{GL81=$-t{1)0S6nH{1*y8I^Bhynw z3x`V$5s<8fyI!gdPVhc=0@ncs{ZeXGJSYZtLLRsL*d zbc>X8KQQdRrW5tIDnDP}2j-T3Mc?<#PI+x4{Vxx+Ml6<2-ux6}Q3#s&(V7rPOVMk}+zif@$?_a7! z#1(sa?+>q@f)E2L7-vhW#^zxLk$3Xc08}}=dh^Tjbn$PNlZvfNiZ5rMbfb*i^_)%L zR86#ZcmF#-+E*Xs9akJA0EhxQaRF!iH6iMRFzn&aRq8Z%HR! zX;IeYY@Zjl?7RIzFQCGlu+ry~<=#toNLjvVzSsOe;4D4Iw9~*Zey0g*T4lamH&X-4 z+#jVLQ__C+n8`4kEeC;nI?zeD(33;w*@4xn{%6%Eko0$u^REEi^kBR6E|-9>*K%tzDY3UUa+`^?x7Al{xJITULSZWmdm+$ z@bFmWSYqR@2umNiTL$6ACgy8>wpo_Od(1}*(pfvtW09Zl(z8d(#MvAE!6eQVo96`Y zb})dH)7?ry$Nx_xdDR*o@?Z0n2H1JNZ_SeNbZl`HN5jrn9j_6`o3Wmq`t2OqXE|aI zbZLZUXUJl?kI{pSGi3-8H+)2t2;B`?l=>P33*lV1P9+^t9o(3b$lyKWY>_ zAl-S>_<=%!g(f-V$h+R(X)02|e0#PT1`MzWWW>EO7lH zECP+5C}BPIi~7eZZnrlS9hJl7^y+2P8Dk;o{*zI<6d(EMqmn&~Ao0!j5(6WNj?AE< z0_Tl6K7X1r?^3o7{!8d8y%tg%r#9O8C2ByA+s%F=2Bm>c7{35R&nn?9?vx zFaTB8#-Q4dcwzrkq9%rek`2cneWFsx=KiaM2TaYkz@>m`fQ1O_rkOYF+JAtLWpuLM*kR8XiABjq>&vCGKu>3j?IiSe{s+t< z+%oRhP7?J=4o_SqPvR`NHjdD zf#pL{hbpC)sGB&YS{)5*z+xbu?%Q{e-YG6M&AIy8gs!1qgDo7;s|{kdk>u%^hd$l8 zqvbS}1DwTb@u4nl*&Nm5FhKsLx&}7W)L2;JinjOzB{)~{xr>J=3tTHEsz9@#Qz7tb z3iQZ*fMW%;)1C99i(ROFPI4VyB6~V30x7exc>u|>E#7VM1(Og+Nq0DMb*6LXX*B3p z6|vrUF~&%kc`!71mjV1ANB7}R_4mgC{9~mEm6dsAWLL`0tYjr4d+%^_bt9YWlDH(<_sW*-X5Z^_x!3Q}?~gd=@i_0->-{`Vdy@!joFMR4PBgk4v$3yB zPkx8wE@-L2Wb)hTKAnn;(C?Mo*&@Nv<8x<3o0}?ON1|gBXPiKaE_RU0P+gNi=^|sg zA_9e(EC4V4g$rOZg=J}B(J&G;f`GoO)2-Zc&;ga90ZX1OB%!ot~#KzAC0)>1kE*c84s{5qit?uP&_ zfX*`_!z84xA%*A6T*v}XlOKYjULay&*;bSMYNfe}6lrJ`2kD>u5cY=+N3TzPbNcR5 z+O|wuicR_ZIe&H_T{A>RMubdG z+~f<8n3=NJoUz87lQmmN7r+kr3}NzN`%$v+{uR!qco2>;LWj6w4QYP?vkJv;cUWm% z02QR(C|?$2=p+OsMM%*)XDRxkp$QE5jSx6M6AL}$ybx?{pq7Vgpy7@r>j_m_WVJe# z;l|OP8P2qaefy5mCofA8&zsqgmSG}D>!|Ypzwl)}Lbb(TKIM3f{GUVWxM*6kCWkQK z+q+O>U#n)PlgyRdui@&f#2b0Hhn_@%BL3Z29tCP`f{AjiF1I+$zkFF@9pMmKKuTg! zJs2%~WUt0B1eNIV=+Q7+V{4iE%)1 zSr=7)d}$H$J%t4sjcFewvX{jiHp8!4J#pP85~!-)L(b zLtwlq%nH*N-AbEYgFb#oAa-4P2QSFM#ksy!l?NVDch{3(11Lhv*+}~*ECOKC<-09$ z2QS$@S5oK(R$2EJAN0cg(X8V% z3Lmr{;{?7i`E6f5FMxNGV3F_#YnW~oEwFt&=U~LoM#Xlt!+8BY&gDu@sO zLlBgVj+eCD;@W$27SwrkXJY8=VNUb(2FU2Cz4;51OweY)3yHRLr|)rklND%k*}GY# z#;n#-$k;p!uaZAEotw)8=ofK ze^H*UaUoiGe2{>AO<9?XHTZUgZV{7FDP5)Vt8}*d%G^(FpJrWWcJH`C4=N@FjWrCY zXpHL$n|#;VOE@N?r}};8;Pl^N$r)3-QXdXp69;M;_VNc1VKE<>+c(<>-7|c4jCCgW zCyjUO{#0iS$%19Gij&3d#a4BGH_+KLCjau>Fta!P&0ARrTH%~8N@()T)wTlXbI9)6L&n^qhTc8za~Z($V-7{m!9O3?KATPM$#_-+z9)JAlBkJ6Sh!qP zW%G?laT*$~(3g2iXrHbHC8%eRH?;2$zi>dqcTT};KjTu;*&6uAzl*`e+ydVlH+p4| zMIgHyGfGtA2UEK~h_n(z)w;upb^g4n#G?pZxeEZjC{7&lYMXEywQ&vL_7CaPpczXq zj9mO$85F*%<~nVu-+G8YUc0P3bK9sqidvY)z_VBX)nLvvUjXW*?T(0<8UM1304!){ zuCr08A!df78RGTHyE^$6%Y5&H_->;gYSDKWczc=)7<5Xwg^U+!wUuVs18x?HHVmWFLYV{^A-Va>O;L=&<9hA6+!TEYi!FJ==DgwJca z6Eviy%igS1yvq6$^M#=iY~I3t=}K_Y3{M9*_|jCj9~_q7@0(Z9A(QHUyt~{xd8Pih zt(!?K+y2)m$4sVi4_C8KS29b|%qF9A(sX$bdR17ZvVIkfO~pz|0zZCqr~de%X;NB6 zdre0UCkwx`gV^!elfHAq#?wey`Pz@o?)we*svEut)KF_)Dk;0=tYoBJOMPutmnH*R z1)R++O|HHwFVVpveH^`&XnBtOl{i2~H_r|#vY9)tR0%V;Db>@FHM>~3b)s+t=}Ye zqzlEA{mQy!NejMaNQF2(o-9ut(B|fEY{HbRtM_7mE}qT=>-+9~3_tu}NR&NuGr03# znjMFRd)^=OOZ{5roUJI8aF=ZDliCcBye#PMU4rRGMO&7Zethxx^A95%l#*PbutVYcryovRN2VQMFCS!XTX3_xcQAKM zvsksnc7x1_g2Go(V@bYURszONFQC)?B00ybA zl3AX)=5c4) zt9lHe)6x)%?^hcs7&*eZ7OaBLNzfdN;k)Z}U(_DFfzL;1b+n@zf>ADIS36v)J%Z)e z`*-10U+?FRu&6S>xSqYwt?M*9(I@*rQzk&V$4-G59&VQD`&j1ShG4fNGsXyvN>+&}{KMN5y{j1yJy@%b^8k(^ILX+}I+#u*%xgeor94i2y3_sMes-L0AwDN9;ae z16fLMXs%fTe%}_;RW}R%J8z#4u|UY3xZqvNOv50a>&Nv906F61s(DvL_^-SmcQbOM zbfMgj3&7_+M+d*J7HT?tbfmzVOKAnecInY}VxTWYlB8pDmn`kCI+LVwCTM z)or=}5c0yzkHfKfVf(lNAv+5Z%fqNDfr9D+IBNFauGPzlI=U;jnr<*=rS3D;F%6O~ zx$K_P8J4S09pWNQ`CRD@e)Aqxo{Z2jHI{IIV$_<6hC}dBLezY%Vsrff{s7!M9$8=* zu7>oh%j+9S0!rzO)Ga_&@hb2Ul$aq{OI%JdrkEk^+01y#@ z+w-z853x8`wJvndp*hX(1nyrFcq=fkRz2*i^JQ6wQcw^ndy`kWu#DxkRa(I_51m_3 z6U189DxK4y>3QravDO0qDWAXfjKwxYg4A8b zpYn1j3{gcd$Y$8hh%+`WoIOhI>r-hLJRRWZbNWTVf!uB+;~W|d zjXcDmc@<-^iakxUF*oN}@tm#l=hNXt{?2>Mf%LXKm?6gyx)YFwuQU{QO5D4n8p8UB zPI*U{TZh;GZhx`50_8I~V)vbDNCH0>XoQ^7*^|}HxKBT^Z8b=1vrUh*7(%!R5V9_S zECmk2^={7f?#Re4y!H-my3pE@fP?pJq`4Un!}0X{)(b>K`_9YVw_``@=ifW$NscmKk9dc2_u3SU+ow)W=3GI3cYtDHbIT3s_zcL{13 z{zsAU*Z=6>i#_Xa;Wg^{cogq7jim^se~w<*3br#PY?E@iUcDNPL(^%rwh1k^V^6|1 z95MAvmxK;=g(iYdiF^Bmul2d-3Ub=B!c7S$1mL9K2M2mHglYXM))w75MIlo<^?CW*iaMzMs{5i< zf+*#S6APUq753CkBUWswM(He-F_9(POgkehX5PDrs zM|#2Uuqj8ik|Sv3S=js=vRi{Pcu=m)$1o>+Nk*S6g zFQ9RVy(#<=E>yLomeh2^%I9Sgvm)(*Kg+}-($EwqpGwu%mCps02S7!n#f7a@N$gjw z$f#vnpe#@9fXX)gISa}KW{ywlr6<{vg`dpo#UA=1^UYd`j@!hwwhg(i{{?Mg+1yT38%) z*n$T4NvNv(S)Zx@Y45YUm5@~!W!dT7?BdKArXx&#Nz-CDFepPa6H$hn%7??h4 z(#|1xbI-5^)=KJk>IENAD}GHk|DNI4JvZ~+(=S}H!bY^Vf5%@hF_ncNvC1UukT?t5 z+FSU*2OcHdTCv=91&b?NykL@y_l(Qu2p>@nz6jbZr(P|A*n_eEU*pzt$8 zYuu+x4a`i@(vdfB_%e{Sa>D0>qMsw}ORsTp|6rldb%?4c*dl;nkt)hWV|%kWp`~>8 z%bY7Xryw*yQR@spPHlZ3Hd(NM>}_A zPp84_(|it^$%Z06=4W*}2W`W>TGXJ0Z1C7>2A@W^+UF^+`RB3TsmCo#KdeItHZ=Ew;8mv`z;Hz5|Ak_lmG{7rDRHLKGJ$vUtOYGt}I^w zbjj`{36I<%#cgbjB;I7`+Ssd&lYLvl*ZJ^1zHxDW&NUWom;sY(J($e7`bI}6?cgRx zc>6=f=y1cYNUOD3#U(RexB1)G9^?M#P^Ie;jh*xcO{_Gptc^cBU0%<3Z4IxG913@J zx6-{i#wBts#sn_JC*oPlk(!VaeP`#d&&Xly>ZQmI5d-6oRk^Q?HzYj;^UG^?71SPS z8q_NjnHY600Elj*%=+c;j;;6OjiUnl;xO_Y`-4tjt-sinc$?jq=}upd`#3#HEksuq zWc!d#Fo8vLw&s-UZp&6CDs)#Xi@nEVhjOh+c(iqb`>NxEDrMNyz14CvcOw_hV!w^}cNo2epw_~Ix07SB^L7pQ{C&tp*xbjA&G!^5rw2wEykskXtb(_5iIPE~ z=W7P$kGjebB3eGr8u+aj_A>%do%2M43CLXCGc55z$JYYobT;7L^=lFmNdUc-g^Qa{ zi_bAnM3Oz<=j#%JBnH!r?VsPjg5*VuB6(#h%is6}K6ZF)ghIj)2@<3$8C#wn+v6U> zChByC{G&C>W@7{DQm@*TT+J?9*K7u&a^&cb_&8F2o#-AcMxxE^Qf3MBhMlFCEMFU% zk8lY7H~IC3`%mvSvtx{@n5fCO4}o$Qz%QD=a$SKi=^(b}x#eT54;Z+vU0x&96^ea_ z8rT$q?wxrK@(!^T@4d9KX|6heSFuhWxa-|4y#Ty3kKjR5uYyreUi+adC4y{XvN9T# z8w#dGUH<;CuE=K8U$uMSmt4LWlsPNWrDa~#IZb~0E&O1QPibWO4B0H1+?(xA%9YWU z89j*?1JABgRRm&xrWRV%dT-oyIgQQc*a(^x)!)hUfb`djq*N@Y^RFAxNeX7e{sZ?VI@zuQLkiKi^)koW8`bQDN{X%Ex8k9E5I_PRg44I`_vt{xr1W=bO&0 zZUW1D4MEKQjm#6&jdOJ6X(+)NL_=}MoSQ5#Howj@GjQnNIm+tVD>TbTkZ<_fCTmXp zo(=rSsO&TIsS33?taSq{W8KdFphrqB<8EXAAN|1=j?Su|3i)@%?9@-1dc3WE?ATp3 z?Ddi4ZWWg9{BJ0J##!V707ndDq}~;pZi`t$iP|Df^rn1V)7~FY9mYIWU%6uaWMkXH z@C2RM=)>nG_saBWbZWv?Y}>O6TqU_#kx>1%{cXF*r$$C?UA8s8P>q|3tL zKj}@9etb(}x{OzKFTUsYsFYpk6mqXsqPyi*s`!S*swcoK6@mG1v^{mHE6+*j@mwM` z%P3h>ML{JCb>$^GJA+6vEk2xQP{OlB!Hs;9=o3ZKc%VZRHa3^vM`S{M3&BeLouk^-?)s?GNaC_Vj z!OC_cw3>;Ya)V#q3RR0eu3rLZqWR8sU=CK;l|Rd zCV1G(B_!AHOCIx*kvH=OXO&V2--G*u5#CN=?DwVwB+@!M?!VAUxgEIH@hw)*Em~cTJLs4YtR@*;o=SxV$sC75 zT2Y5glt(-^)d5fj^-uQ8r@CD&zW4<@?Us%a-&YGW(>Dz&>YERVhGv*Pe$3oMn5b2& zg4*`OAQq&((sq%ptC^WUE}2#t!ovlZKjFURIud!j#Krx5RM;%gT#k*eJa2a$IbYFu zi&6D^W+=N8vq$0UYs?a8Oy)P3UcP96N5r$?VRR+Gv>Q2CdTZt2Z}NLpbP08U9-)81 z{i@u5B1tZWm^n~coi@rSZV)|->4Gd{?_ZUAU;Dr+UNp63EiLN2;8+c>F|2;Kz@7`P zyr;udrd1+ceGfhP2xcTOom)_W@}ia2W=1;Lt3?FR817y#LWY^y=+E)QESj*vM$T9w ztIAXTJ+ZC(xD3nRpB`yauO>@fLAI$hh=U9xB_6YvgRyZT(a%d1Xj#k?V=lK|0G0>^ zvcnFNR6#QWUwXmkE|Qsm?B<{)TSBYB8Sc{Pb^>A_GGs73oqQF-BwW9ee&swj1&ZF< z3#k}Egu2wVx~$6AlXb(dvDxh!#EqPdpcq^syB%*0?cYw|8Ll+U9x9RiRZmhnwTp1E z-=CM8)XLF0s|sv$Acqm)0J7?Cr!uj^vh@+7n7ABGvJ4m@pilsl*Ce0cxhnJmGbb8# zvkE-zb-O!8QGxOqiVQdW{^AEx8efRE!lzc7EmP zDg~B8SL&p$T)lCgnt*A=ANm@Krcu6!6Q}^lAFK183KI=lx)z*B9HQzKvm$64e$s-R z;Pa{Et`2_(YC(uOlU}g{)K`|Mz@En7MdN>E!Np~q_1jOByXr@Tfn;-DD|KDaQ%4=4 zd?w^y_t+ssfD|xdrLLp050Gx$WQ2ZEMhsp6EMd1RswZPu{@{>$OvAI$eua}z^f^G> z?bKWnHzYt~>%KLA!Qttn@prenqUcA1C@AFmhr{jfqrA-R>*(lh4uHp&YCsU3v1bR4 z)B79>*_Z?b(rcNK&Q}kjk&MB&UKakcRuFB}8v{9=HCExz;a2P_H=J>A;>9Ej_7~*qGk&V+s zl*-6!eBYYvi+A`&jyOr;M_O~IVZtrR2DQZ(z;--m3usS`_#BzCrt+qJHPld7AOoCe z1KT!S3LnMez6YE_2E>~vQPLN{*GMSnkKxK3hXegouBPi%Q zM8M!Or5f`6&;SwOXH1%7OogIJi~q{N3CRu)BTNKN(DT61; zZ4HMeV zd~OuFpa`W#I6B-$E#n09t@~FmiOj~)F?C;>+mA#QM6$0uBdp}B>NuAs3zDLxeXno; ztYp*hdYq}y4sL+WPL8TpZm*|a9(6K%u8N(sfD>|P0-P$DB*}&+fc9j-Aknw!l<mb(a!BC*ta(un`mlrJij&vt7C+To3xgTcz%><%ipw z_d>eUrKFWsF@kw4Z6kHa=9DgS?+|?S)75|rz+w&in$xdho3YY%TfV7>QW~(gkmp<8 zT4ACpyd}ZqJ!6@Ho`?p|{1bc65RQaFJbbV@&EKzkDX3c=hTF5x^F?ZD-8OanYs{0U z0^R3OWcJOLq7U(Gl zB_IFbIr5nBp{`N+Tb6{X`TC<09G-+gj!sVc<7^cn{COh#l{Josp~CgB11{m>bj5bW zaMctptmdSRS z?qh?KO5v>A=eAUMwQb1^%n3s%o@?!}aQhC1A%q&k=-A9(lY6$$?G;8G8Y(PM%1u!h zKk6#1HTaP%w4VgMv%|Eu7mQ+rzkp_@`Yr$jQeLJP z&d_Wl3(D5$dJPFF^cN*0J0(PECfTx6qN&a!A~vZ~lvEYaL)C4k@7lKmLlQn~(V408 zX0j2eZ9iN9`<&OG#rGq`O`4tYuZ&oQ7&)A&qafiT^LM4?XTx*P&S18p5$n2ejuL+gaD3XkO) z@83*A9SU@=M&%X{C1OQ_m*!_gPk-?aLw8>*SHJW4Yi}U=T>OUXCsxfeO-Ds9C6V8G?<-u^ zYr=4FYqM&~t#RF)%L*~ zl1v%kl&qdC;hqWJ>!YRz*Y=bo|LU&nQzvZAI%TnI6^)B$r*Ywb1BbLO-K7-&+1(I zzI?)hXF@HNY!WYkgAOc{9miJASiCb0-PPyS*H&-wO>HWkXkt%(mH+NoS*4s->1A%U zE0)ie>$v9ZIi%T4z4U%1BVXxKV^I9FjUoNY!HXu@Y>s8~4c6J6+1C;?d9TkBTVS`< z>t9rFyTp=fSh;UpDr7j|Qvj=Q^2F`Q=zI#EM*?qUHbi@UxMRAHqv26?=~`M$VGJ@8 zYY*u|mlU3^*Hr%4wL6=iy@P}1S zQPQOxFQjzOC3&A|f>d6aBczB~{y+KPx^v#PY_ zFiRA*VGvLHPb=XiY`j!_!i^HMaJuMuE8He{Dm{uaX8-lMzltYt=tpp=^h?kSX=2g0 z^t=@rC5N(DPMMrHrW4FZdg3$%DL*&nII-nh$OX zT7JIA{Po2!kCvS5fucvXctzZAVQo4-%b3f=!dI_j=cmSX1sxA$SPs>*kCu-iHhgCX zVOQUTK3_W-elPoxH*j+8p=6PaOk2^=O4Zo*{f^$s`gn%1)hcHux!{GQ%OdZsHmUEi z4c`cd?Zj0)uo-Fld%UdBNS9Cv=%dZ(>7Xi3BdIPml@I0?J)}-!B=gQb?3mwiG#U|U z0EAjqtO}{4ZR1p~y!2;-IE5tEs>Y_6hFF4;?(Icfz9GugbmE;kOgOe1+vRSA&3U#V)09vH^o>v$N3Ih`=L&8V{7w^LS9Smljd$$Jq! z^$O*yTQl%Ag992mhlb|2?iDU>!qa3`dC%hh&m!_iGn0^$A8!`cf9_7Z<$toxlXEl8 ztg!x3Ys%PY@`aPLigNc)%iEi8frN7a^MO8|I+mS{rb2on{%a4_o*6rXn7C$^Kxo>! zfx+`I`mmC_UykcGzK;E*w$DLc$GNMcVm71m@|8JBZlMWXDt{Hj_A@xmYjQ5kM^;0x9Ssj*U|`Co(|4`%9IQBTint z=L=_ti-m3UionZOz}xoP!k%W7&ldm;8BhkDx&YX*4J-qM_|IV;K|qf{<{0pyOS-YH=(+bWai9Y;gl)&3y@Xfy(7;l~}~rpo9GEPZ=^n?A4} zx1Xcq#R<=QvtSp{_P0N<;d1Pr|D_j}{y>TGi)5Q6*c3zp>6|0*6~qO0PO<9xrbKM| z53SzZf+CuNaRU_pv{OcYHqhG%BJg+U(86 z54{Z)fC&0=3jP7Cz~1ja7xqJ(n7reo7=}xn0(4Vk#V-lqmzDD0QI_^0V@m#a7MR3m_)L-w@MHg(r5#TwcM%3+yZ6lH>k1 zuXUlc1S|tiQAlnK(&r83R|A!Ray&IUMwc?MT6xa8x8QK6^PxxBdXc`TaxKdr>>9-W z0!W1-P>~THEVC1GvZ0o^HC8Z2#7O@<_OQeLV*7=y;P3+D z+J&en9}e{EX(G#`unX-(UdU2mimC$P`bj;q?*gb&JAWQ9mBU@|1*+CTZ_T(*cL5Ym z_Tp2NmY~S+c~5)fBQ1?(?6qcvHfMVJO~COAaku7KWJIvmB$ND-J?5+BzLHA7o_(Ho z#v@7WeP61kcvR(qqxx60%Go}`{&tfn%$B{0S{GGG=L-P)I-G3^#CmMiBh3Mvz@+6| zAl0hv{$*O0eSvVS{pm{8J@~hJPLWu^;DmPGP(5wWp}>Yu=c!6vOoW^1JqjwrWq|gK zXnwSd%K_%ZTUGcTVK`MloBGgtV(lp};cuEIR~dd=|g@(_lgui2eZ^5F%F| z?LqyRn<)GpX3Fsj@~gHi6TTWC&26=Fam;=QK}`Je=Pmnxi^$1!YVXJ!3nZ*<7D@j) zw60v`x^DHqzB z$7d6#{FmCNrl6W9kcD?<(dLZEjNHP?8F6Eb`-_3EUQ3=UXF{ZKtUXAr;Tm_Bi z83cKe+DO!>!xmX}a{>HX(BB_RV07ay%d%9{cV+T+3Q(?-^Q)K=VlBz zs@3}KEyTi8RFs*HB)%HiBx1W5QK}HF>^OWT9gb)Zi(Cy((_-abAwb00R=sy&flQ z2m5HTyKa*RyDX4+)~_C^)Ocm$16-KS<%)El${bOPOR!Z-O(==)StcLSrC@Dt83(6E1*I?C9ES<{q4-1lP;*3n1y;`F(2HJEBZh z7A*m%Zwi@Z$Mv()iy3tOzL|I|nN}`&_C7SMFZh?k+-bh4;O=hoK9=qAyf{C^ON>5_ z3OL}?Q2FYZt1a#OW=Of9vMtDyKF`15xy5Moa?EtaHzo*k6?OyRkADBd{Q%D{B7V#v zdRDK|czA!9d_4b39gwo$wiT~Fa8?&nJ3rn1%4l%1BIK_-)*Alp4Q~CbRGow$Y zW7?tCuc>t<_4vHLeOCU2girsp3HLSm9$CE8pB|tyITo~5)mwi7=v9<(p0{^BbQ1Wr z^G5BwEIrp9?~DEU=D*X+n?j$5Tg7jc4^26}{0}qMC*^5jkT9E&rk5-tElgr=(A|7H z$b^*)3~f!3Av>WUZ@KdyJolV=bwfo~I9X4_)x?A4nIEgxaOdwO4!>>k2k*msOZAT! zy;LU!pDuqYxSpL%uaO;c9Bi{{F$kafFg!6pP@LJ@!}unon^hL|?;$rNldBrHFrj>( zn3|fLH5qYtx>6Wr{G1bc6jP4ehH^t$TK;BjRSlf%mYZk_NXrRZmsJY%@96>BPhKpv z@93##LzP$3=x}hym|tUHQ(o=(pbw*iU3E>muS>`WwW@+P-*f!QSaPOWuF#=qNqP}}cA#m#tg+-(@c836tiO~VS*@#o zcAPOH12XQP#TuomuGI&fLKmit2@a$FE_cK(eh)ax^iY4fh8?pA_EB7$YujMpkpJnL za}QN2=h|oL53$Yn+xyIsw%OS7`1{k6V=9c_z+;`i+N=(E|@Mt*)!C zS)(fyJE*o;RHs}-6Td0;>+j5@?t<)%_-?;(tv0eS907%NJF1MB2_%qS*(v1TDNgpf z`F*q7Hnk$r_8=Tk=OCSpO7wXtR~~MbuXj*?b=tM&ZIpXq5(2*ER+;jG@x_n2tAVAT z@87@2p^jZl!^@b2-0)KV9hf(u6OgLSjg8+df0I6)qt>_(0!xeVdu;d^!&g>N(HC4d zQ55%7!R0vRrRl-$XIG8?if8T0WO9%abg`hE!eQQ3XRqE_yovn$Hx6qO556~#4XlNl@3Ye^I48W3Up_z){~ohG`5 z3HxeoxYu_fxZZBoFJoK4MCU-T$O@j5kjMITn8%2%#aL#}J z{7#XhQyo*gBGzjfNR`2(d`f6RKRsTcL6H&>XE5;F3bfznt4dd7V7IIGKhAi%_4_6_ znSZ}sjYPGIReP+;GmKmjin&|R;l9-Cx;Lc?YFNqm)L@iZdwee3FnHN#?lYC)KE8a^Jmd&R zVQw-zoth1BY)@?Rda}$XU%rwgF|2BT zY|8YlheV^v3uBmZ>NFinJug9v%gjJqQ8YQ^<<6FM!YD^E7RJqDpQN@ITPFWuTx*P{ zD?_~v9NZrc-knLh1QqS5Z}@v)rD>6xuSePz{zfi)_UhHJN@KhE15UMK?dHs%rIH#? zOz8#Rb~$|6-|E%*ouI18##N_6Y9Coe9U7jVxKvZ_KsftUEW-WnuB|n6 zGmMaF6&2j}xRg#F40XNX7eKfGK#+3D=SVDw%LhOF@YtmD!e8Q-&CjAg1VkCx{a__L|c9% znI?K&jVvhtwrof`CL+{Yuot6q=345twpHUd@2%cH1UAwleO2rACd#_umkiHn&XEB& z)kjdw+G8H3XWCU7>pie`>@h@-#^HH~M5vi#`O_CJgMNfCpYADez}`#V`^xiI6mQ~$ z^2*j@!$@8Y73HxWY*6sE4{m?%Pgx(Q^0Q_m8`Y+XeyFfa7Qdc%@2Fb^f)93;)JEi0kjtR?V<(^ncu{7@xAXO_FJxW%mja1!( z7u*Yg{oXiJ#*JIGja$aiq)J^DrWp{;k05ouM4059J8V~2%~8^ezh45N_NwNB7l1MT zJe+8K)l(D8A+g<}Sy|;AmHO>_1QY{u!0mNYYg^wu zXK}d?g=s;(AsrA-2@9!oa6A(B=NnOdCH!nLo4-?$zfDvipMEt^N_(qbWnrUWpIC>~ z1HiGEM{KkTpr@!M4#yDnf=JLRZcg!(znuY)x})L978E=#rAx_bK|#J;VK1t%ZyLO% zC;?Sp2^NMLQ~rII;gwm%{}>_GZtH&&VB6OK=|_WY7E!&JR+ri;XLjAyv|#l~o*>Hj z0$I=ev+{xm)e#O$+ETF7QdR#=y>tP@!BCKr?dM_pCYmeOmTR zd0hic_69)4eRb;7ut*$w2W{tIkV7f))gVjy7lQVQyG_qkgCuM{Ihu=yd!&9y|C8NN z3jb2_m1DyA^j51K-Qwn*J6CSKTRPaA_l=2FiwJbqpws0PQ6xWF4Ky5GTx?xI7`gnV zM7T%mkuERIF&0>e5&{UkXG9xYZitNjC9v(i+dnl(sd6`q>uZ~U$gWiDe^O|cF1qRW`HsG4-S#^OX zCgkL+!+2!jG&Ej-`7Sh4?vO9+Bd%%6uj=cARJFn*-_TZ2LD(sz_GO)MUChe9F9cM9 zLB~Q1)pm}Vn>{oL+j^0?(>#{Z1da>fn&D{pq8aW!>>E>EF_(;_vA%X$I0ML(+#*DR^IY@WxGy_MFnGz&Et(og0r#~PB3@CDH6xfB4! z?ahU?*dtFH=169yJTpY0a~+in0KOLyUL`cO$zNQp1rx+{T=zqqoQ-y?hHqeG{a#RC z0X>-@q2wtsSoLKz3S^Hg7^;ody~DAz#fT>O>Yyg?@sro|To9(tNOuS0DMxDS3m}8Q zUjpq`BVdw&vImq}$dFz(7OpF$YaDLp{c0{T*`EA=;p+z*%Pp0!)n8WU>U~2m04h8` zc`aYnG-Iu|&aI7_NMJwrXIYvph^*7L$E6vgD;!gIj&&g)Gc5&vrFRpZ&$*70%gd z=c2)U_UF3B(UcKu_Lb*}`TKMH(yoVQ^8+Mt6UC-l(*oRSOXIdd$Y=o}@>lIo8p(_o zV?Mup9pv1mrt~uUPW_eYIadpOsUA_Ot9=xv(om-AcpMf1=SdUbOwNNuNQ3W_;(oz= zzLZQRLDfD#HeQErHFx5iH*!+t)f|*$d7qL_o%spM!G_GUx#PQ9`Q!S z-d=+S{`3fGgqxK7tu#BO;|og6QQ(`%KmD=&KaS4B9}340<7bCZWMrL;WT&izBbg<8 zWJi)cPeyl#l9e45>ur6=_|{RZ3^CX*B9xZW_Au8+!OxCc*oW8lq5euUori8~#*?QfOsLHy z-5aXGii`sK-|*h)$GYe~JLbyC-CDF8hs>R$I(GY^gK~O*9 z{VLIjY|*}9@5lXbxL=s}{W&>TA4(q>TRr?@z#o~BP(752Hjm>^92xnS=Rq5><=6bS zknSUYs9vbrXbG;$&hT1v9hZPapS45 z_^4{5@OI=(t33Rs#+9)y7q@req=Y_8g1F1jT1CmgC|KzyXMpz~PH#B_V=+a+?K#hh zLus?8nabi9N`y3Jtcf1dmk&8v(=&+iF?l^eFsmsU(^dWII(Dt%gSEHdULkWtMDb*m zx6EthF6RzYvS_nzp6K=IYViQ7j?bb@G$R%iD~B-Fy&W|+myj!|uFHH4t7unj)6JTa zV)XJB_Tk5Zbjf^a3H_V$!#ez*laJ~XBeYu#Ak9bopZ`rPwCLVbd~!>fdq0M^qPys^ zvsuiuRC?9>b22;oVHmWBAq(6)PWPdw+Cv?&!I+zJw=2Gdafztk6fB>8AiF#SQ(!s# zs^__jB{gWg+8bk^R+md!5MayxkSbpOT>j)nJa=tuTS=dP#^0N|sV1ptHLfpPI1%BakWMr*}8D+YOGdnRCsnwwfjIJjj^xKAaDI27QK6LHe)B`({lGac@L zvXP&feoyxf#@aVZ?s_J2ZkUs-LWu7C(d4kxa?v#>4O^LcxfWU4%i|(its-`3d_`Bl zIeEW+?r0B(+EHe981%_3GEY9U7}Yjh61WBw8B&7T&fvlXwf z@;R+?x)*J%Hs^ewoR+r1r!-*))?Xgz>XGk!bF{naBJuaO>C?yzk029I0!wbq0S-X# zJW90{ux)9=GKx+zgdy+*^`?8e+*RrJE?+nK&#BVwjZOAFH<0DE6DfJK>4VpWmki;2 zpv7zY#0a_BFEaTJ}JG!!Zkj2Pk zVGx!YG{DDMM}j~mCW@}>>M~OsEJd>&A8kGOq}$Nm>~Zd%vV*gFeP>22BR|jDX6BaD z6HT#~VOAX0<^rIvg&!F*U5-2@yGp2g;O>R-qAMv{zt2AF^VWlYP?$~%=lGBZJnefZ zbiCBT2&Tfw`jbUzWn~R|ND}FZ=6iOiEfv78Gn9OnYMnBT#q&P9?qxy`>sfzGR7jw@ z-ZMTnM0Rvg!~6CW>|8BTX3U!947Cq2yIoY_)53bML1~%(zIm~thHZTY(A;!Gl1YF2 zijrL|pf&i8VlhLt2dQCWZETVKQA$Jp;M64MAW2++H2r``0}+S1G%&_iSy@?z=W&~Lt8Y%aN3GjyQKuM4bM4CFm*bySov)|v{`@#( zGNmXDSo+2ZTH+5UJ~LF~RMpARVlcPeQP^g}5aGD9QwL3|^WaU@NQD*5ZJ8=h0OD$A zq)*vFGm#30Xg?1avbzK@IHq=_{tCD7a8OIt61~F@b2=o{{jx@Y)4AW=Vk@`FBt;k5 z5F;077UGHnu*vr^Pd+hGnZXR3_L}L@&*@3PQ`(4O&VF3C6*72G?B6HWCjq4=b)ZTE zB_&|W*8T$Av8>c4XY~0KiD43ISZs$AJQHa^*z1%Sch{XL7I@T3mlVe>p6pAX$aYF0 zY#2XlF~on7i2o@W$?xUD^(*I^!6g8AhCn%|sN#40aX)zfpijidkI&mS$U!HBec1=N zi50BgxW()wb0q{od!PU>y#PiOOR5nG4t3T~u9blSf6rf#_30_NTmi3|R=IAX6gyTe z5-@g7yFhN~c=buc!H*OD-mH zlUk9@4bPYAQ#LzeK%@%!&ll7^7Nc4tc_)a%+Gh8==Q&nNF%>upSUZV?(fqe@eW5y% z-={)>!5w*hfu@pA*coUAH36)O>g2O?*5>Y106%D%xbY+HIr|^)f@Q1;&3&2VObwEk z<4v5G<`uv9_}^mWF&|M0p#Uhqy(fzQ`u>8u;}POJY!W9~UMuOVopT8=+lUd#^`>hj z?3{zmCTRw1M*P4q%nqRC_DT)}`u@KrwLa!$iq>D>&5ZXFForv85kDS6;+Jem#NFr*Y-Q|u9wNj^GN{K`ko-*Jdw5X{PO{?N zwh}T9CB(-LXxT=gz)QGn@UGT5x1|hzHCJyK)=b#z)Z4}NB0*1R%4mMn0=3a1))!NR z?J)$aparhZM*=MqLDAX$8_RIKKNp(%Iv78ARCXf=BCEGLyH!g}!;>xu-@ULYK*#z! zT=W|sMET~Yed&I*))HZeee@u%kPI98 zPh4eFhQk2fo0c(0MWj4eYk~M(bBfs}#gs0>8YWgyz{u6*FU)YZ=@KAB32hmMgE_Y+aoLf85jRjG zMA2q04pnrFr{t2ck^E}Jow-j_ZStwU8l{#9H1#}LD;bG-T`KSpmX z#Fs1J9v`Tvy9-J3F;8~~k)?U4y2VKlVywpZ*Dp6}zV=B9qDgvyg=iJhB_I|VuzZKX z5nsyM7K?0RtEmPV7gzb6)A!8dy77pHs*$Kl+=-dDPv0egkIe`<8Ab%}72T3-pXyg_ zd{4cQECVYi?6<@^-arV}DGY2pef`pj|L|NG)%!GhLF^3tjJS5>o=rR)^&xG zE#uoUcOzp`w#^)MZWC^kA`Uo4{rjeSyBzj64rCf=I7L8Mn_=n#TxF$G40vq#WU(4o2EKuw3 zzrb3mNntGF89=7xiO4=Y7qX4y3EENLM_AXqq-$$^;gv%ZP(;c1E2DG~(CS`g$3VeS zCi)_fqltPANKH;~8~O)aH|+kcil*;5@~M5$&wOsv7nBn8oXxvw*6_(o0Gp=L;Q&wG zw-00n13ZMA6nyA!EV%i%n`YvxVdb@maEXVcVjSu6n*Q3}=i0(QpHk|E`@ z(Z|!V+n+WI*WVN*Y*jy~Pr+QFlEDiW`fAmoh%3`&TZT-dNXu^KG{=NXKxhd2*vP-# zyCRxgSA9!<|6vmfz>^{jMA)v!yd|2nTit`c1r1IF3yj@9fr}(1xPLxNc8tBQSVL73 zc?sYgth{%$lo!oo!}hBg=@mhEu_cPSb3fIzV;xRr2cg>d3o?d&;|Ku{&at# zJxpnN;DN&Ie67~EGv{r;zA=Myj$xnU{WmX_Vt@CCkNJ)#7)>0BgLnOs&$RiO&DCsJ zR$mRA=IZh~VO$C(L(9uvWkg*YsQy=C;ym=K`68^XG+;gAq&jQJL#&5sn9EXw7cRS! zMivurh1Yky_4@M=t33akcgU?SYvuO4-{6-q5b*0m2MI$pXHvY!c~Zu2y!da2Sj;Cz zPFlYD4(5*)#gS(imZZ8(4)w1mj?3Q$Q_!R8y^Z6Xqzj%1iDr~aL`6sSk{lf(F>ozL zFK*`%&FOaPyCVVVQw+xEILD8WShuVYzFNMr{O1=n+n_moaID}R2^p>}GnZ5Oa`#*~ z<7~g*_fLv^MtMnTx+m#X_ssE{Q2rRZ*QZ_&8;>9WSD5rtqpk~%;+jE4ulutWzQR8*Z+1d9q-Bp83%5GS_kN$YSr?f(HjS%Q`c!Z9em5geyziCJ40=gA-)bL@}W&1v@tt~STT0+Z- zIhl42dZVuUbu8+6U~{t;#@q6pW#E>rS0jIPrV-UsY+&u3_{OPJd4h!(0eXr2`UzGQ!g z=GVVTu@9HC1Kte?{Z}_9`CGm@Lc6Tx$+KeGgfB81&BuO{EvK9!g=;C?BnYH0;%DgL z+zf{kJLBimN-DT*ZXxnJCHE5Gll|2$F7AT4O#Fy8x2qI?kXK!HOOYX%#fv#i#99W= zjgMGwx(6M@fSHDQ!Hi|^_*m6x0RTK-U_NTWX`vP0Zk}Qy>A%?zrq%!JGOb1R{0ZCP z1p4GZh-BHr*zuji-)864Ps#dKM^{EIM7M{Gz*qd;vMw>l)6Dwq>g;r){*g+h2NVpzLG{Mvabjy?c{~cee@s%J z-MLcDNUyf))fVQI8|Jd?VdDi`F%2XstSUGF9~H zw>x5M>6d3O{u---zY85`6c&JwfuP%<6@t5J7hG_rQduzbo`k8}r|$u&MQM~4je$2G zE&&|2Oevh89IBDz$w#vf<-3zmKd}FdHmw9%F5(BUrI^keTe_F;454vds9*{g7Pbv`1IrQ z8m9p_G2&jz(hUU%(7<;Nt4aYKgBQj}tT}J^RiO-rVwI zSG?Vr*C*UWi&arU6JxCx8JNItF9ChW=e=(k&tx!P9AnS94+`bGF3bws-e_zBWt144 z!1Tm9j#0m>HMeEzEL)!)_V0Fe=cl|hsVfRW8(G{cDt<0h`X=4ji)%aN!|#9pbl(H4 z4BISaN82Ve**IU?CktneJ^MloWgb+R3L^6!0O(dslm#)LC3;M5^-yy$!@#QxLlg%I=t^X*gRy? zn`CKH5@)ABfDy7qflE^$56teVEIVq`=77N^7;85403e&wMXH6pxZ^ z%X6l#1Pol+*rWnJ(uv~II57~-KqJ7HqqCZ`(+;G zUIHp+F9F*7+Sm%Hh!)mO0T;S=<6a$rQdjbO7OoG(&i}|$6bLo9WaEYYYYUXULE~Rz z0kfN|PY+chv4xA3pSvPnZV9>%R-v|;Xv*!q>e@y_?G|ukW8}fogmIdBfSXuy&U+u0Z@i$X#CS)i1N6>Mw9H}D!&ryCe(XAdtW{vKGKiK2c0lN~YQ#C_DXH#%V01Q$q&@C7e?g`aU+A*L_4EPH zYC5PF5z5G%s1spaKsT2Ld2J#``q4QY4}(`Fbfs;J7&cc1%AN5~CZ-@z{E+V^5M;nr zy2yyTKjKpz z9vuW{;KkG7W=zurLRZt4?O2URDF#p{s@PAQ+Ypd(M^58A3&DdM{7XB zTbHn66aI?!In3{V(6Y+~oU{`5Z(-Zl`<~F<^X!BbIWF3Kf1E1|%_2n*)-ZjF#hxBm z0LL)1@(FhvGa7Ihv9M5wiR#Non+rRLW^E*UGp;5c53RzQ3FfO*+p`AhPfrGt^8qK< zs8+AP@Ym>!Rw3+v4RdwEA1>=58OR7k}drnJgs}@yC zgcDHVIBk&o^FkVZN4lz0hIc(f2b+jU|So>SeDGW%kbq+y3}% zWRU5PQPM2Co-#GT?+l9ypiz&gBD$uFe|WL>!I?I}mqv~rebNemY46R$WRV%>jvY*C z-Gf(5>h79+i)0w43Mxy4IYIHIf=F!e=^cTyKpzP%H*6qFA4-VI4~m;dKH-Hp<q`<%3#T@dV!1R>$83q+hUHZV+7p5Nc_5>QKM2k$>?fZT{qUeSDZMMsCm z#24BOis~oizcaayMcz?8>IjW=V9?Jn9ag!@(s)EA8bPo= z@gltMN^Sbj#Xy)St0Hqcqv*^+Wwv0`2F5>9Znzz8`GsgP6U{K5aiX!qc#}chOHn;U zCo`5=f~#$nv##|LaLsSuX$c1rzXyI=m%4M~y`-jSnVFxjw>NBFeImvJkJ40SAg}~U z>d!{Ix(;zOkl4nl&ItwGRQ7Dg;9ALN0VDPcVJp-I<>S#Y1}H9ny)DYzC4hT1;zg2y zc=a`-U=j`4ax?MNYTMQ`Y~YVJ^FkW_$4|Qa`RQ!vQ^gk-e}VPWMIlV|U;00_vRu6A zBSAod!(Hyu*Vu!x(!8UwrdJpN;pBdya`F$=m`l)xI`JFLVZ2|10t%TY~ z1Cv$BXamJ5k3nd^uksGjPq_o1B(Hn7+w=U`!6g!AJeDBE8;GrIFm!v_wa`MNr3vcY z9f~!?Dum9GGr~E{u9GGS)w=F2W7Vgm?V*O|4g~lH? z?)UD1CL?m8xNjZOYSmpq%=vanKaYEo;+E5(silLxvf+FY_glzhycxq&xpTIP(kC@_t4sTQTzCBzy90MzxEw@Khy&W?!PA~qq591mxLCoCGzmCp9 zzmT7}di2m~cY7TmAISFP)$}5HZh*hyg)nnYkq5xEsK>KQM2hC@$!nE=dG}Pc{91=D z(Ai;mT{($%Ay=m3G-P^i6cE#_%2Y;;uSrZ?^GiVNxBRj9k@~GG=hn~4cay!j*wzS@ zm?JbASu;>#kF?8?ATduaOe&*4LkRwR?9FA1nG@!4Xq33l~wZEhX? zfC?BjeXO_r%K3pPn;T^x`S)`(|IC|LaD->pF*Z3fVVg#ZG|;_*B zWx4uWMry2jb*H?!A+LDL@%Xm-D0ng zuwa3=I)C&sB?4daV{W9+UVfzYv{~v-I<9uy#u5UJT~H!C3G!<9wW>bseVBg<@cae- z#+6b1x4NlYku_oB67W>YX=6CryF&W;uIrhQ@>bKQg_NO20m*8>kmJd{<_>yQh^9@! zZ2E&%WuVgmVZWi;tkd|j$@Zp8*~jRLm;8zBx+$X|kO^#_e37iyJ|S<4F4&*yP*UA- z3%>Ul7XE;zITdrYhEZ2^YZbzVow+BbcQxt~z=|YH zL)NC`tA;k}rk~M@66chZ1{OLZJoNRf;VPTv1$@1oAe|}v(e+g~^ z8Hdmc6pxV|ru4Vu7v{iC%IcaQqstvW{TP{e>G5en-_!6kjqSoLZ68GUOF2yo=BYP2 z`#3}InIM0e=ts)yZc-~h{#%Fair`_RPehgURcoumfh)yV(l~no-Dj;~!H;2I1lMD4 z9_F-cf24@LW3<8HsI5l_3=3MW61Yeax8{e=zLyCGi3{?3oxcnqBN;<}Jl_MYXFvzs z&%wt5=ZYxv`|-1N@eXDlZjTN0-8%+@`j(nsx?8*igsy4K zSC09vyrI8`Vr$R1k><)?@cfQcgRgw+x2WsJ#;@12Z6se6rJIeM=UvT@YH%?6Y{BVl z!!Xtzzgh09oSD?|iB^Q~Yc1{BC&__Ph(*rGYDBdRjFv{xL=U?Z_uIJeQzbe1Mzs1UEjejZhi+cizn$iKy-hl_E|@7=vc0pyBP|X76*q1hsS9;l-|nM8 zla9OO`Ku_u|0c}ugpakq5&ShB8Xq*HO=tS0$B#dRE1HSlZvEwS1d5~Ojr8Q}?bT%Q3PbIy zfqi9v1R@nXT-7ILH>*tgezzOZ86()_H%|R=0f?9zp3glr@9LdVm65tPNxCeA~G|u^ejRTHZ{F=o+!XMETKc^NSEamjN4y?SB@OnHx)1xY;0Vq!Z^!x`9g-OB8*tG2Z+K zAy2ZK23xs-u^jWiEzLRc_0eIO;Ej~-7Swe#zY2ck2zT@St=3y#B)ro6w@%sj_~e%~%8Jcw-5BIX0`i`P93G3haq@FyK~= zCnmx@kl}V_Y(q7&VlG{(F^SPTyg;e;KDI5fahYnUmf)${58T8LlL*zcYpFMM@7Py{ ze+694*Y>Ifm0bclBSwz#IJB<8vg*d_=pXAO-p}TNVV3~QfPV!rVANiZ`s=bW6EFB0 zmM$&vy^iV?2L@wRjgMKEfOkO@!4t2vv-XA84;oDSjSXB~+W02?x0 z6fpwNa=)h{UB8$ZK5Z0KY$M^*AK$NPbv5wgn1MV!sGVh{2$f=m1Tl?KbIdG ziLV0B^=UQ>qhnBb?vh@I)XKU+PFY#=smSgSWj(X*~dU8@SYFqW=4sJi_tn^#kp=+LpTor8_4R zF9C>s^cpr6{#->Wf_#IWv1Lmfj)R5cTmj$0!BbaR^YIbKu72BGv$NOtVY0|)t(kO@ zN)B@UC_q{Syk9g~ee>WL=e%O1dNBS#X{j3efD5_X-zGj!L_DwIi51LnJ?~1Tt9ISD zRMhxxo0kH2fLPeD8pZKDuKF9VQ^-9#I6azjO}MEr@rHv@lzb$^%Ju@57%?n@L2YdR z;y1Yj^nyig1VY3&=W`!j0;(ys8hG3(cuxhFE|#gyR*eU4g)F8VwxHPW==0z#j%va; zT=D+i#os(==kzI^@Y0oq&O>b1zxt>xE{07&og}Qhj$66q0*x~N_uUg2^4EJB4*$9CQQS9eYDps`|YDctfj;avVvpT5dr?HooR2?iU~>po*F=Dn#o1ib|XK zLZlFQuimV_FHyJ>u#~bFoeU5KbSFK+5F?t{*ffx)$J;tzC}`UI0)|$ZQ=mtR zxVb>ft^$2a(F|YN;DzzRbT&Nc;$SHkNntG<8Lhr=sh@to+9F;#sdZGp&XWJR0d>!z z9~3u!y!8WCIy{9qt0i57O~|c~VNl#$z{gb9f>1o263K=OMMF{Ehkm+=>nR6hih_hU za6{t(e(2$g3Dvo0UKj=5;VtQ_Ssjqzn#xT61EV&=UZVsi_+*+=vg%Q*1bT7_=p*BX zsyBvGo?qjuKSq}${$2v;yX_WQbDJfp1YUi#q4Bya`d#;wCXEc5{I8<6jD|p9kZmOpg=4eeR8^Dk?%(lcTzuO?+o~e5-UAi5bwMJkmVDo*>>TwP3nd1k#;GCu{Hg>~ z_fNX%0*|&_WI-mx=?(ZF(z}y-+$-t#z#Ui&xk-dt*$AY@X_G)*_*0QwJI&t9u$74UULa$dJiwHC+o{*J;yZHen`6nj0(wK0zffF zs*MdYopPcvj|0ks905YoUPl11pMzeD{8^{!m}}#hOXk+Wmw1Tni=V^A8VuJZUhy{S z#1|(0J?FpJh*k8(K3qRezpBBp&QQ5_Bi8j*wiA4E?XF_mVP4j^;;b~mWNRu{)#G>adgqDa>@x0G;5 zt2fJ5j;+oo8pUxrSlDcj*xYe9kHXj9rAy$?&Jub}!FNwAJv znz+96R>t_^?$ozp4>^T8x5_N5d)Ji@)za7$%)bl|#PQ@WD%WyLPFL|``Dz7kwFE*u z|1ctEzLCzrBFA*2$);bVLMnAp`@-)89rY?v=Lrpql!v4TzXzX=o0yWqV*R_bzb3uB zC=Jq6e0lV)Lf@-G%v3z7+eSpmOlw)EE?tEH4ezj`OJ1VY{RVi<1i;@c4sGFhRygx1 zsO3l?pH{co95qv2VZ8388A@aP>=T?L5Y&Bf30SOIN$zyX27W;a94Jni3hPdGLU(qJ z@*D4E%8%EvuwMe`XERm%)x`GE4bOs;Hr6!2P0@5&R#UzwBK{!tLf#f^#=pNdH16>Eh`B)D!l2< zhhBY;r>_qO#f$_wgJm+kVJ5^2oq>y#eL?TM`MUng3NU759 z$n)bAMW5QI)zm`|B^FsrFxNE^hr>*x?^2vJjn_;ko75{w%@lUu>EHLQwGS@=?mOO9 zEti1LXiIH5o3(UpVs1eCbYQGsxtr(_WC`ASD&o7*<=M>8vOTYLYWUXFIFsLe4Pz4M zw!Ft*Svx1SU0qM@@idRgQ!UA21zSm{)7CT&EMLcX9hP9YLE1alk2j5f<$e8^81(acu+G>jJqgA zuQZXWHxa5n(Zzwo#(u?VIh~nPMxJu}l7a@#8a2$>P##~u23MZB|Fn>|qW+^>3!wC! z^4Qkk!)`7*YhUoB9AOLQoq>DpKRSQ?qYE|H_gnRv;3Lu1WV5B3xmxMon9^vUGaJ|Q z=Q0Se{31DE?E(?`HC+WOZ`qi%o}+yZL9TOxD++&J0(^K7B=Wf2o|>1qsNaWziZa;U zZs0Vl>MS39{O28w*xx0YmjDANu9s6&^w*3k3_O+otqLny2ij`iX5z#Y>9Q%&%qt=D zTNmWK(`ZSgk;< zq941TBlf{FmjKR(tyS9t@|i5fUp|PreZ2CwcY?+qzRl3^ckbPf=4w`WnbU!?xl!Ec zMH=bRT-|BfIjrLQ+wq4F!=HREuPS{0r1I&m&_p-4(n=y3Hp%8LX_K9NV^cu1iYL;O zRdv5f!09zO#Ge^$bhMFDE>k$m8A@YZPfG^Pn}wJ$0evog zQhnv6gIAx-qZ)=mhN?0XX zuTuLwKRx?%&4J1}fz|WAHvgA_PKc$dbkHj9r86Qa3v`sAh`euLx#3ox9XcEs2}t66 zlFre=uVVcNe#FWj4rz+3f89hzfd>2Vh-Tc?jERaWe~G__iR|oEHI17!e|9~t-Yc6Z zJXqhDeh*}<2^tfrZi6k|<_legy6t^j9{au9M0ps(sadJ8Y~cD%rd^3k-lL#Qy5!pv zd2F|G9oH({>qT$Px(@Z1Vc^$8DvE{r-QVet8q4G^?!x>^ogN7rFjW~wf9PheKkgU0 z1iYRhr_>j4Td4$BM*hI1QN`ogN20Og-u*9}8J4Q?g4?ed^U#hb>OoJ~r{kEYQ>jD} zXCq+~_9;;M_t((~$oF6|TJ>tzioafIE(ZJnh6@-Jq@f;>#O82UqTn%}ez=>}+gpq4 z5@5OCGn|V&Qg?kROT}PTCzA4mKe`8Z{-1hs8>G>aqM;s;{lo9 zPfdptvcmhGMB16iS|lkcjq0r&F+)@cd-NaWH?Uog!GemfSCTST?RLN~YRnxy$ zF9BZ07enJPyNd~En80g`>o}|^fW19Vxd}CKSB>iuK(mjIb>tMOsp*w-4$g25at1>* za!DY#ohV5|yDAS#)ykj9Die`I_VzmwJcU9$JE4#uz&0Q%A_ta&&7nxE<(>xWQ$-KGkDj3y6sVFF;=l@p3&M3QmU{D-*g z+HopmQc@e;qZGnBSj0JguT_1o*XM+bYQh5b_F9A^*0 zocd{VfKW7R)5mnxRpu$90SeMnCZuH?jsUQMMQ)tq5rgH_{YBKUzlQ;3bto)}r7L&0 z2LXfE=tt5c+d7zM63Kd_Si+uSKH3&xUnr)LrQAm8wA%(vUL2JA=!O&Qr^W$c&9$<0 zyOlUf3+n12Kbs>?StF5RlURQH=R#Em8CKd64z8&W|C*ex&n-;KfvAWiI+0^huy@t? zG%dSIX4!%VYUQAmEf>%{`D~aeS0I9<{vxJ0>~`|wLus=+Q3#l*n-&APxXJN9qa^|? zZt{wY1YxN%8d8ltA;A#)<3~rhU!-!3No1{~md~TpMYc^J{OwBs9EuQZIma&~@!YWk zFj{iABKM3}9si5Xh{({5-EG77OaNX3x=d6#Kf5&{HPqZ;I$#5uEjWm#q46sV z@p8H&=%A5D3Otp);!k+9PLbl0%hs(zO|vL0r2 zYh%mHE*At!ffjp8O?Yi!Z;NIz9Qs@Z&CGAWOOa!z;Jr@wq(?b$6JLE`5v$$>5Q=at zb>p062B`UlcL&M z?br~=?9n`M6VuH^L6!4MKn2o*yKnxNf@r%2)m1k`v(9&i$B{1cRdG7~R zC$Q{X#oYIcguhRo$XF_&f4M0${dE~J->5ge1cWqq^cjA7liVRE_Sl)?(GM(Hen=1p zKa{)eN01*ZS-0fc^wNHA429R1@(L(;re|BE2-aY`~RO3=z6EU4{8>87~Cdxu6 zknoPwC z(=?+amm=POi+7UzrNrOsS?$oYPX_Vt-Ww^~zg!)!W$AuRT>`XQ$ZyWw_3epcLj_~a zuTjH#Ke|T$xQ<>0L;1?7u`3 zH_BEE*7fL{ze}>FKK@og9ClZo_n7lwegBQGoO@a>!|c~Y4)X$b!=|_0Ha|+jOOnkz_vhcd4^2*NcX^u@dGgk}` zg-Ywx*?-$~dhZYVt-CKF{_op<1<;WA?)G%E<L*{JRb~4 zntcrZoZ9R3qj^PW1==8fKl?$6gGAc&gs^I`G4JEyHQQIwS1tih>(WS0)w+9|k`+hqo+g2(zIQ1V#?gbs?uW z3z9v#C`aI$g`tgQEmN~GJvHzHew7dUeGc*usNw>OpKXNXSR&e5ya$YmC%)~ceag}w zUl~Z4g+AXBoOmI-1=-E4FnoJ+u_Mm9e4-?PDCN7?I z-1I0k=C7HE=y-$GtOD>ZgGMRK#@>FizUtMrc4bU^R`-TDA}wMLeBnJpAE_4AUZzN6 z%k^gOcsmmq=O;6pI-+lSdV=rk6gQHxA1fd@%-2ODlKnM54_K~e~4Q} z1n%%oQ;&)n-M$~PcIV>FjnS&eYgKcx3U@S3Y`?d15w1jRxCm{iv|K4)a(vz+1}myu z0~qJY{Vi&67udu-h3+zqG(EV@++HaUjX@FhK-3O1Q824wzaeCzb7NGHvhX zw$WckK?i?JZlzb&6TPkNGg;iLd=yYAGFRX=>mr+A+kLKE`m#mTrzeNxLZ}?s8$$dZ z7Ox->n05DYU9_N*9gUYwrbcdeV&E^?Pd;lq<0wZITWkd7J{w$1tdD53^xl1ljA07BTuwGE|NRLz#? zu+GD6^g28=HdRa7_7M28K&-n>06CS`u`lU_p3u6>?r81SsB&D;JCg&jfri@(-cQx< z+!KHAQ4AO3{lu!5b26#Ysy4H=JMjX~p0Zi2@mHh}f{cngoG>T#Zx)2E9XIBw#M)Lq zGwqbLPp{Z_q4H6tbp7EN=z_?Rh-z^53vCbZ`awcrm@i`Q_w8o=y0EEAq3Z19QsCYA zzv}kE!C?@L`-E@PL4M3T|b5wZipy3!F6tf z<%<7*E1{U~jC6PtsQ?2X)%F?I`g4I2u=$&nw5+GMh#?^uVXklM8--ni4lRwvVhNB| z31927CxJJ|$8@Wcgp1cgG&pY*;N;gtI5b4JwDXp2IYPVe+b?JSdwrWGC5G-;5Mugu zHGCCQ{%FqoNkagiYg$c*Nwul@*TQH;XIA0SFIoy@k<=Rw^+!)&08Z>}BO-v(3U(THGu1oT)wbcK8y)owv-xPm}Y3 z-0C_x=0Y&AU$CD?;6KD6`!NBv3c-iN!5}lrf8sP%`ydO#sm+cSxni_DIHzrLxsZE= zhC4m3zP2IlBKcOzB@hA4l^wQUal?wJmG&g+C~16NKWh=EB!Xr`Mwa2KD2H^*2`jKP znS%>I73IOT8ZUVB;2qrlq{ONq!T5BY-?REbMtz&4tjGwC=3-cRw)Jk z7?2lVy#(y4n_@4aiwjek)-bfE8>|*g6_#~OvP@NA_zW`X3GiTt^h#r@$b@e?CDzF$PH&Bdwv+-(%^ZrF@An?O7lbttYi)UB3H6HBU z_hYW0Q)9zm@*`N)8Hx%}rC>k*uCkl==Y2J4DgLl7oaVyTmI`Qa*v79ebb=6OeS#(* zt6z+8+9uBki3MFdU4w4{HvT{2uD)DFN>3!JK=vQbJKu$$*AbVJndIrVw`-{YhsCnr z?Mn0RuHx3Pa+Hg3GIq2uqWB^V_TVBc?7R;Jys?Ha>7sUnsSY@Y;yTivS|l(y(fqsR^>wW?XDpEFdz z|9ifKU->B4qa8JRy-wa15wd(7Fqc~ibs*Pw4jRUOE*Y+#@FWAg{sXZ7P1NJQ4=osj z!UQNdb!;tWxcVhPYlWPUs3U?$oTVHrra?~G+4zHdf2KJ46)#yY>Iq1BdL2wJY1tPk zCba7?Gm)pNzKBp9FI5TQ>?H{MvSs^L`e=oQL9Ui1TJ<$J&IfwsCsF`~GpOe@@+7wW zbM&C|=8PaP!lA3Nuu|}fs4m}itav?_N$?AgS&BBf;d3*w{)M5zPjzD&V!sK~?BB7D#vlWyw|xAjs4E(-5o2bO{}d)h^zxAY-A(Mx_S! zA}XNH=Riv}80TCjvpIG*FJMK?ytN(d6z+kg;x^f&}-vUI1o^qK@h)Sd2J1#@Tvc1wr)WgWj{1HA~>O4@Bg%YIYDzwFN^-8#V9w z2)&Bt3)4ZP#@|)YbeHMgHuLeR-~x>$`4CX!iQ)$B`ih4*A>WItPG%5*7G~5;1(=4N zg^~}K9aQV)!B+&EXy@R=BWz)3&OgDq?hh5geG9t|x+#tXh2~oFV)hI8sQ_h5=~U@& zcviRbv#e*9Nhsg?!$Gw8uRtYOSf^_9LOk zPCRBVcQiC1i?;s~0a7Yjx>^2AK*XT{kp!;ot{hMUOkJTbW6TL|Krc`Ms(9!ecozar z6Z|95Wq>%U6}(O$+jlQ~;jHqT#O;KVH?Rypset$fHZ@>ku;4i%2#iM9S{NI7YG947 zOnTVF9eWL9$szOVOOO#cI)0rmpLJ-Aw~ZPb`WeF+TJBvEx~n+E7?d_@!^?TdEss2= z4rL>?M&i!@;lQg{Vb*Q>R6EZ?1_g#@Zjl|vbB~ZkYvJIdombag7(6>^0)7{+PyvTd zl4ryks1?pm!Muey+pvb!ghlp zggq@;+{3bjUVCz6R#M;Vr&s>ZIzyvhAx#6*hRmnUiDq8vhD)@P(5FqU(mZ$T4cgfS zB5WsL{x|B8$iV(qsy8roJ)B#?k znRF^u9_&sc&`?&I4w(6~((}?~WpoS?-4(}1-Fqs`4$=xVm3;)bi80r^x!XD)(!7P7 zuXpa<;%r{a(7GyC-(XUgGAO6O=P>P4n#gA0NCkv08ROXlYuVM$Cgey&ccH{3~o3g7)sUww7@4KK@*y8kn@b_DrSo60i`ltira%R-`JvmUo+_> z(ay8)yWWpZB|{7lo{P^VKV;Vr-iKQ843jJVRnI@O-JSjEIaLG`gtSoLE&jLJ;AgjO zSb2wyn^d*lDrKf=x(SHoO_OFMc#6y82^!Zw4A-&Jv$Ay|%RABE8*w@t#CtQrqFlp| zZchcni@!_(9XiENXn!b~)!5Ee+D1s+wdh);hfJN8_bojo4YEm0 z^$8Ft>pw!-ax1z|k$cY*%-Z;n7mG2frV1%~P#e zyU^AIZN{v$y77eZccMW@%|PfmK%{~qx>s8;dsFZYt4tsb)s)6K1BzC20KEujcMhsIHrMk-)` z@xh?nHJb`U-s`&ehrck5N}B-rWXi)DUSCNu})-b_a|Zaf~;Xw+W#?jD|U!|x<1 zw3$_CMa2erEVau6!EOxyaY%U8%PIiuP^xzf&7Pul+ej+MHJW)odl!U~sDD-!I&Ev= zv;wsI^YuGco;hYpe8GmhW8K?&0nD8<5G*O&xrg*O{~@}JVr1J_VWQNvlI?J?StcLm zpp}-mglu8sQXLVAPLiVzUA%nZ*f!8)SHi0zf|3uQm=ohWU{b~1Nr*TkeH)j;M1fg6 z0oD~n1=x_!7n4*xxbl`KOIT<8jdc+rE$M zWx5y7er;IbF8qvUm*s$S7}yl@Rb3}juax%k`KwExMwBxZ(AuQWcz<73@tv70o(2va zyx{keY!%@dPU2^YOS3SW`8j{czcC~;ph`))t;;8MYWuFgQ455*; zh{lW)5+Nz4J9BUDz^9bUzy+0eJRBJmh90bX4MV_OIj7oY-89U5%ujiWgGSuMxnzf* z{rt2*{_3dB7jmZ}XmmF=gQb!R_zmkiB@tBjy&p{fdsJ^ki!h? z85E0@TOU_3A=%)!dUzKG@^)<{4Q=;^+H&S(zon)cy;?s`auR=d6i5hkYLe8lb=xTy z6?5CU|LNDiUfH5K&C(fsIuGkLJABm@x9+h$q`46xzet~bw;0ld{yrOrR=8!j3{Vf`-?d!K4`13aQec4h8x0l#41A7C!rW*s{Bzq~ zky+qM!?2g(hTmuglk4ZhUg>Oyn$Th3Al#Izb?lzsmsb`H*Ej~-Wu(&!fAkx^slWEr&iKc>5{me5RKQi+I*yK%iWH}ymijPt z;=yyJX%%o0Tdq$z(aRy+BAzkQ^8B=b1l}Q}T`v-5DV(Nza(zeKTbprbfSqv>K3pXr zj-`zsY>g1{!?#-My^LgS@2=72yU2Gm9 zfh&C(Rh;QLgaq>A!pv*%aVOsF=ToW_Yy_XG-Txh}rd)uBBI+TQ4_kz7^wDDMV>3QY zMKLS1Ex;Y5Z9&3vxVK5C+mrU$p)ythb}Z10Q*$zzgG>ML_s;=u|wa&An)1u;c{RC@O&QB;Y`A?&pPF5Mcs-#=*Mh zGpb$NgeR`hAlaH;T2xa3z~UYT=gS7tCNAWT-$77`k3Aox-(z~_;&H>!F3nQdQ)1ql zDB=)YT?b&O>VvWleJ0#s9K-ot&MtnrO(215v5^!9v!Q(zc?A=18s(6wlPWRD5h+w9 z_?3=56EiCbG()jQ_rOr+N1)*L3HVU(c0NjfFx~sna$ONxETBV~H6gTmOYgApHBSMhY$GJF^AZ;{uDWad?t3``J zl%P#APH;U-Y<1tym^|DG*UuOk)x_4ZiJDgc`2}q@+w@`c^Aj)q-Y?>)AU|L&NtrIvp0eN;`4CKgwaO z0?CqisG%?$V2uj+yg6^^t%I>SSK5wC5Hi7)rnC6>RZ3{Ty7b5Ffan&>eigo=IMi49 z9%D?n9u+1=S$tXHygI9ft8mQNyuO&$3ep~# zZl!DAGi7U~k6axEH4v8m|MqvN_KEc!`-GPJ>NcV(gd1ARFP4j|l6PFu|Owd>pK(t?+A5S@OKx|Hu z`&zvUww5F4BfJ$sIqc^cw9#f&>VEc=b~&I_kN(OO|&06>5>9<|@1h_SEo7<-`e zi-o0ZV}NPtach$TH_0 zdoxL{K7K4Y)D0ZP#6NPxG-AiscnKCl%t|8J)7cy&!@0>EH<$!D{@jj?^z?3pO`X5Q z=)66qMJZ=C>h+vi~ z`!lfC{+Dj~Okr{H*DL{nU{hGtaDAK{JAEfgD6b3;Fh%syLfHPiu-D3Djzy$rT*L@8 zhMW=WUU_-B(i_KqFBNt3wOr-pH~YxP`t0SWskX^AYqyy7iyYGOzQ|*?Hyfw}e{)q9 z-T$1Lul_WnTQ8&|5h8PT0@w*3vzjVa#v3P%Rdv5p0Su}$V7ow@zpDGBg1O)yfkS3Z z@7XkC%4+K2_qt_6w-s5rHx8u363rt2O*H6dR+3C>xJOpv19iIJFG5B=23c6o1BTfa#2y34% z_Ey!hpg(!r5wlBqz3HbYsBlcT>#lN&W`-3gcVqQrcXglNhab~+G4|me`whvAhp>&p zVQYv$*QI@)l$KcHiFl;DQw00>;wGP2Bc*#(fW-TC&4tpl?s%->((vwe)ZOAjNbxoC z;vA5aCgl54LVh)Eleu>1m;0kp*olMErjz@Bw}k^$g)P*@zeX4U%)_B$JtG83YYqIl zsR1WD_oA7YPQP54pm_r(Jw0)2@BO@TGkXM#BVXg_)mx&7uXpU$l*EzYLz&iYM7UZD}d}*7wT_v$`!3gHykE-FL2oHyY84 zaZ;F0+rV03|8BIlKTA^YrZ@j~QgRf0(KMzK}O4Aw_}r?OFZ|J6}1(4KTakUK)L%o3SGrn$(8=^4e$C&Qr&I2N2vAoa{rq zL;kt*D@T7NO>S9V^0}z>QR(*k;fKn|pED(=F|bFM>9uOe4B;v_YooE-+aVV9Hl9>~ z3~=N2=;3qGyTe56pzV7Z4kW*da$we`|N1j$pBHW`t_ul#4^}n5+RJ^>_6oK7I9C)} z7Xli%6A#nvcU05YVR3sl!>%+=PuqelhA3@hJ^M*i`0lkP25qo9OIVc^7ZeGvu6q8R z79sVuxUb;-^w__ut z^NP%bH1PT8Uh};6m=oI^k!BDWB%GteW3@lh%koNxt0ngCO@3231*4vZE9JtW*GJmi zW(}o7JU&(D3we5X9{)h<%wWMqEs9YX>rX+65==z!ffZT>`R{V3A4&slHY$#V{t@CdlrDb->)s@A$%Kd zHFgUT631f?dvfopex2Z~Qom?xYg`C^_5FIf2CA#BSwuFzkJdT*~$ z_7ZGYU=tmCn|3R?JUZrSYKi5_Qc`h#3yt&d3aAQ3^;Fu!-eB4|CO#nex;Um`Kq}0a z3P^?g9uE30U^e5q8n9w-Uk7n7pvO$qXqx8F2xoX6F4;udKqQ-Q@R*A1=dJC}mM*8&)R84jf@9973T zw$0>XehFUJ)KLEQO=uj^RMB*4ej}nu)w#2AB>UX>p3Zxl!gKR@)9+aqqnATeKp6@? zdUh#>uN7{i>g5L`;6iakfZtbH2Udx{GUFN3T-gp)bbQV^%cX*d>{S5Z( z@AT6J%Hp{|PKm8$HYqJQAM1711O&{Vd@$q`M7Hmqq5|IC3z8>AhcFRN@-BvGhS^HI zU9vRxcGbdXI!V6B<5CLB$Tn#wASBUK>mHU0@bto*!<@n_F#?gX0k1~BbbKwSY$XmF zbLtB$eABMgD%f|+dh{*SSH|?_;PempI!Fd?v9U1bnL8Mg3)i zdFq3dcEoI>XfVUK=9C|scbR0Q>*@$6D+%VBY3HcuUdnR=uc~tA*)v8Q)2-Xn=KvLzPibl;tv4^UT?_(VKa<&iU*jD$Iswm-wk*&$PsU`W{EAnBSoX;|o z1ix%X=eORxeoLyG)eRL! z-lLr&nWJAnfzIm5r339Y!;(s)!<+6Ic|0@f0_N_|!}BLFu7sVABGHm~`}u1+31u3i zu;8>?9T|gL-AVIj-??j%b0@C4;0#Xzl@V7Ss#QTw-MXs%g>RcCwi-W!wu;AN88&uq07nZc2LdBOZ-i=vQgL?@VCqw1LJG zTY?;(-CGRE;c*1+z#VFa3n~$)DHVj6Ci?_<*uu;=v*2YH=kx009whL-fE7+Kk*lF2 zT^U%xZa7Y%;U-oZK?ut^?GgXE>}tu=?Vxe~LCStU5ILkhW0cbG=QZO?ex1xxZ=A`7 z_!>T72u@2`%htJ`#-;Wa6~NJ+6yoPwLOwsD=OZk6oF<^D*g4(Di%lMj#$Nw%NNJ5? zPWC{2flX~O?5B{wJlEfIzro)uwBPGrJ-Iv!neLUz1nU}Ms~MgqS&T^fYT@Z^7kX~` zlo9hVDpr=&9y$CjqXQUiMhm$11UVtaiE)I*esy8nULe~%d;}|0{dPgxn~S%HWy)Wt z0e$Ntq)f3&5!@P^f_<=t^VZB_#{kWkeJ*Dyn+q5|GI;kZ(4ZyWK8ajyIo%Px3GW;$ zo(ow-THo$fI#d>wzbL&xRCTk#7J*<9#k1B)KkWUns*I?pL4~n2P%^tR@Kk_s#OhGL zzK;DuSe;b6ZCfMu!uKhfyIGmSu6pr;*%ucUtePhNR>4R$Cx6kQcb^gMr>qDAA?$mV z);%B^-yGuXCvP3og&>gUFsPg?zsKKfm(dxYpZA#6ujAdSoW zr2t2$&i!f$KofScc{HZ!0u{2pj^$uyhPKZTo0OCAYv-O$ahvw-kU#qS5)uUj=+!2L zi^ciB?v_+QDR`GK&{-0j5>&sFLgygfcFj z6I@LbnvPZ8C`W>RUKN?>;^wpUmppKP7=XD@aUH96+T8XzMdaQBsb31)ER-u=ONL;1 zSNQ{*fY@l^EXyf2^-Ht^^gs<%Y2DnVV>ZEt5$s#fBi75!9; zFmUuL-(&R14a~xhoAn##a#Ern7SL*wCQv+11sI30=c4f8k_YdWc`)`%L4-7{kxpx^ zpn(3+P%jnGP1#(iD2^;ffCwr!ktVuzQORkfmlt9Jtre$`m47YFwBEH3aRTMw0bC z90kIdux~t2@NrtS&Eeumm>Lz}v){b;%Ag^obG34S zz3`*Ip_rk(Py~f>j1sUvUSfmK8@5gLo(pGW4Y?zR&=CV+sQ||VsDmm>P4#cHCQBQ@ z;>#O*Ddupmcj!&>`C;cWHvF&BkdtgfLYf3Ce0=VDNEpp!2SKe{S!t22Ub9QWE{Lpv z2OK}8JyqRN&mF@y`<;;o;szN2w}jagg%dgLFOpTJengxS+Sz9(U3YVB1+0hsoR|-T zlsUpC;#u8Dmv-(y^aHSuv~SqXEp#9>Jhh0R|QJg?53WuOF4NI*b5uK1fx( zZX(SIZXrm;x0!r>`-%PHj((+L!?X?+;2E~xVILOqc@=wQeDdoKz}-2QT~8(eb|?sI z4>^?MTJgXpJWm9~xux|3XH)@Fhaq6%WEGp+6$~x)huwFe^ zqXKHtP3o&=`S^L5RI{FuidO&(^I$Q{*5NQ%;G*Z@(|%lMF#gv5k2bMdrH|nYi9TRJ z5FFwxw8#5k{ zPDSh0wRiz)7=oL&9lf=F)=3*znxK_ei}VU(gQ>ksQ~A4{Y5TA(+QIS?>~R_FB{)Zg!~^L(9x}%j}<(k zpl%M`eb6oj5$K@ZohBl@hs@|z-Bq&n1ibzGt3fLh1okhp#;LW}pp^BpTC(I_)nCxn z6Tx+u&xfprbdB|Ca!{%3{7PNj#i%l@iC=SJ*{6T7y|#7Hy>P!+mBNo7rM$0S-z@NUt_cO_SsBun6B2WFcxiYDJ?w| zq`0YbEejgoBD--0kCjJUS}5uc4A^#Pw&oYywKHou@_ln0zzzAD@LWu3_pfGavH7jc z>bCpIZtG4ukM4@#4umfc&(l8+^3^vLak*p$(~S`%08iSmjrOK-fSEw<-dRZ($DRg>l%K7qc7?$ zxA>gxrT=;0O5dB8TKp*qg{JH@Q6GQp>?}pME}WVKXKCCa2x+Z|PRX7kIRY|| zx-eO%Vr4ZtVhzt_G^G0FxE5G?LfW2KPWF>|S+ORK`?~#FCB?xza9(9F?VE>Ph7c>_OK#GT{zG*dHv_J} z5c!$PLT-UMA#L^v?`phA_~cE2APH0V)l)wiDnP`K=fdZN3Lt?#|I@8qZ$db%mzQyi z?g$OA4jw&1@)lnyfmM?asHm!MVmuW9-Z8YRg%WOU3Uwg+@9WIBXF)3BE zw*W|H;3Fc32zh6BzcBv&`8hA&FsyzeSLT>h7J)17$hc%S4qI!grzWO#j? zLOg^%Cm0-b7shg6CCDV2)?l!0E^9CErg^-Kc2W7ldTWI-dTZLY{>6# zlDaPH+ur9F2(|j*QR$PifK^v_k0vcQyu5!Egy^fm|C&WBb~ih-?7J%ciRqZxulAyd zjP=Fe+k<>b`x@m8$qSYC%_D-=y{bbHMEU#Dx-v#b$)9*hiCpcMQX*e|ZdrX7o7pX%-to}<&t>2Ac!y(0i?_wz6AX)Kz5LryAxM)@6Uj7EXp?c3cIEQf zH~TQg1TBKVY0wP_fdN9=h5d?aa`!&i5K1dacqL(@SNh)mu5pWNj$=}J%IK}J%5X0N zXpH>PE2D7kLs_(42{R-4KbA|RL0oWZ=QC4Sq@pDyGt0PS28Pf?}8an4e%zG^exJeI2LEPDc8rw-MiCp`s6UHey`wB)kW5n0W&PCnz^+ZWty$K>6RRLpG7Ib?fOb z?IO@0dc8OujU-qbKNNH8QUP}c1FsUE_Kw=#$YjLMU2pW-cI?lYJ$VR1w(s8>8ykXV z?%f+NA^ShOehOx{)g1K;7Zdyic4)kMOnASPa zNlm>EzolB)y;q_qc{#r70;VXN4hz?MnfY1VOX25BS@V}MFHDvDPxj#$huL*&X_$Ib z1Bcm0(wDtaMBR6cR-3E9jbwKnDnN9rdi$QARB7@152~C=?SlmdNe@S_JEv^5r@*#% z|7mmLw*~<_A_efHQkRvvsbFc!E6QO)PDhrIO+rx$M~3K1-nU86*Y&&Q*5kzCa(eymMt~D-%`Q87xj`{fmwE<0mw=>{&VxfC7VKVx#wD5+2Sc{1gA2LMvgbaF^&B=fdn z2?_EVrUY(JzYu;~@a(}3Nkrdj8n#gRA3vz(_G#g4mRxda&*X4>fTVg-%*`D5zT0v_ z(%V?AB1c1(C*rh!8|y!Dr;PF{e9p+F`#5e2wN!=)je&h`NT0dFq~E+vS(JB_}?vV(fHd)AT8DgzX#p8?EMxW>9=3dSgJ?#rnzcYAwrt^G`U2 zJ4Om*cy+R;elr!oo=fbw5{|8Sn~UZ5y}@q*Rth}n8*fkKvkf!EZ!Sb>_YFag_(ZW< z_^bOcOQl(Yf9J8!jzbAL7>j%r57~+WJvW_hcu0AGi5DR&oDZWmk#7jw*VCl$);f98 zfWpxxAo}xpwFf_x<~7|g)ig8xcOtwE6-1Ky=xKIrjwoU0SBhJ3_F+y=_S|+*Sv#@f zHPx(a7wud09|^?PMDS z0UKYT(O9Xlx2rnBS;y>SM|&zk_?owoC4W&a^gF2%O^uDsN}q)xUzF(_FENW>?x8&T zc%284qHVVBw~TTloB(UdPk}j#MD)wes>lJi&F)HciO#j#`uosNbJN;r;RpgTZ!+FG zRVBcv+=pN;zp)y{J>f${hls??PF8gDfyN=HNiM7|3_Jn;jT>_mb)f~6hSHJTux)g) zS?%h!PbVPEk_s?TIah&vGD@1o%83{HdjlLWz?~|L$o7Gj{#6x^c%?OyT^0_-|0gmx zL3=8|xP;P#=4AsOIjFWjc4xQ!mHW_Q!e0A6#ePOwT?fmgHAH9{ zLv<8tP`#C)lD5de*c=oND_Ag5S=+)5dd|HWK@tWM;YgG;fVN%Bz9{GjCl1uJO!O*( zmGaRI6I6HfA&Z-n3cTK0ERKFYV=j0qpikc?gcj99K!Vck0Acrc^*#<&YDD!$kZob8 zkkT?vr2Pp_kk4OT`A!&EKp#C7v45d?O9)Aqf_0^>s}2_z4O$W}%xoHle8pTg|KWPrapu@sgFIwYd->M^JHnHCXL5$;Z(M zfa>FqgUEN-PgN<_N6XmSo_9Dnc@9_hGt5t242HBGDn-qPK z_}vKrC^S$3v{XRS0Y<=?VsGb}C}T_b>$*E2>8t+e>~1(d9F#{sA937}={_bAmVSRU z+PPE4%h1J5W*-k~X(p!xTrSQ>RO{>^cS(d*^*MIiaCx&D!BnL$HMBj6Fa`AaFq#|i zPQ~MRkN@pIunX;P+|Gkeq-p_FzXO3guhJaQk@mjh^_|a#TQ3NBbQcIJ8PbMG6qNm2}@z5|7?Q4C7Vt&;^vq zmCSMQx8rbI?rZ9d;h+T)-2x?Ga$vGhpgw;}8a;9cvC|pn3r!>XP6@3WPEX=Cu_{-d zRBBzDi<=_HY#y7Tu+iGX){K;#mez*=DBTUFCOVumfgIAD3kZH!l>i7POuy)pZ@#qz zWf!CZ;$u+bzFZ~N=UP_RB`b_3%G9|*V{z=IwZt0#pM;AOYy|yes*3Z7X;DN|DS%-Z zi_d}?65(KaT2?X0(Q?Z8C@0H&m@Yek`&P5awjTwCng1;tky9D)Vgs_&%cPdhZ7N|n z`uoCmN+4|aHE%d*82g1b+n)*dR&efQ74^}sc?k-{9rPS>4I{1PWM%j9xa?i-?yPLR z%i^_NFW5b%C8ehFaqza!fk(MMHVGgq`*p)Kl&UImjdfwZ|CABkkcc6t>v=M z#FI614U&TZmM3SMvtXm?WrH7bV+r*5TY8D>#@g4)@GW%ugEv4*5oCvj-@IP~&LJfX zBtm3pToB5{HZd?tUa9ixgT?2J=j!r%@`djgT zY*?em$H~usA&+iX_A@=zr0-*^h(q2|V8l6kun(gq%NhK}%*NH}V$3p*vw|fBR4bLs znKeY;j+@2S2;X3&F9YJvA7wN==E5LItu`}4f_$$oR6I0}Wx&_=y^FYCtmu5^c2d8% z%u%!Xzw7S9CzI!xez$*iJ>N`q59M|odJfhXQP2-7=L(`t&qCbse}UC9SplA^HbI_t z{q3$q%@4j#6(=Unwf=j%)zW_TUKe2!GG>{P1161vITdin1ka7{B!87E*aymgO!@RuKBy~%G5&XzFo%2RybUz_L2B1teCX&G2G?GI)(Cz$F&`?kiu%b5Ns7{wzd#voVb1io>_?d6ixJbFN;u_;Zw{Go@cJ$|{DaAkJx+}YXD zwe=BH-9cZyo%nd(CZWlHV>V<+%0ZB@6`6STu4TUZb$XykdxQh(?H(HeB>m`~wQ`Es zl{nm-+x2jc6#OC&Lxrv=W0VGj!(K=BqUq01;>BG z2OXtNjd#hz2e8({Ed1fQADve4y}kh-D`j~jwb5T!CPmfsn3Kgf)e?x_aR0d1u~!SC zZLVJP)N5nBroKnRmcvyYG=k*^JVmY@P1~ffH`cWHd_TVzM_2cRl->2U*GW}rKc+NY z^hdAJs@Uw^tcqQpa-kv)<15iQiaigH+Zu~s(>_%_Z6h9-F2vlO{i%0bBOVEq6HKc$%lofYgxF5>dpo25|5Anyb1B3 z`&N8*yW?=Syh9N}l#cz__VDq1*2i6U-K#>@wf4LS_d6XDgZJx zu;J~IPVvc0kX)dT)wS1tDN)<5u`bU}pL1kqy0`6>J?H)O`EAKWseeN9x%e9~ zskZO89+c+BCO`WwKpW*Zx5$5zop;ekM4w#4yf+x14XT>A`{|y)&EHi+6mVR%s~EG) z$t#U+gBoo}`;F_Ty|n79=uP-K#>m0y657#EdUxU&-0RYmq&xRDh&@ zZ_1^;iuw%7E)4-(beqb?wLB|QkP^$1o~-pMn#(eLyEi%G?^xkROnH+a*O>WN+`L#u zY&_L9{dwApzn~zGeZRKaIqw#whr&$}ua%@SCQ^0oMwhBHzRFBs25>o>Z*6{SNt3du zo0EJ~cVuqUFH+vGrmU9A-@j(TS*`fvP2PuFzsna^E}cUPNRgiVW3wnP%4#2B;hp5D zB(^2K_r90+Aa2gbc2nG61+J6W^$%sf-|KW&Y%tc%Ei$}!%KbE85Ez`*;jr$7{YC|p z$rHIv2E`deS~z>^w%W zC4f2Ln{3r9{f8DJG9*9e4?f2SQ}f#&liuxD-O06jGg!zK$TL%zADP#~(BpGGdDY0ru<7Zm42ulU z{kK6TcS;LKo!LuMM+48Qdu#79j-}RfD+xwRj*OS=S)R+she_z-&o);nB)e zfT35LnF6nW9(XZQh_vjhS{q+ zB%(zW_Qe=t7{|k06s){5>_;^W(|+w$8vMd^u^{&f>(qp{t?j;0FfE87iPmdwZ){>{GObM82csyj`f;mPeljk8*` zYBl(><3B%DW)+{>$0JV|zy%ejjd#}`V(s+npVwL#zlFcleL+JBgNJ>+AIy@q z?hQge`o7UFS*0UKIyzU%P~AuGD=5Z(fL_RvQaA;m*`do+z<2TfWKz*_WTEKjJgUvC z$Rh~f`-<;wb&$eUNs{WCfaUI#ylo0u5OLa*2?I@!4-Nep`g6X45bZ;ro2{N~B`b@u z7q36R%$I6qPSreHMQW$z}h!h=EoXegoPrg+7 zUec{Q^6_8z*&S7smBX)C+jwqV@7q!_lPH8#{_BP(>#>(QczR2 zGNK%Ov_51*k;Kr~yH877OpgOd(aOstF#@sLSv31bq&;i!9zQ=%_`a39DFD*6Tn|rE z{#qZOR3EsYs2J$k#J(C#^=%|%wyiZ%QY4b2l|%)_I2RxSZVC3M1OiCN{{S!eE7ET^ z{JPyw{t^U={hRWRP6Ph{p&gG3Yfxq}ru@p5c!+IA7bFJbmQn5Zuh85NBP?Y8$v@fr zx@6PFi1~ou^XFUFF&0K$2uctV=TiWA)PENr>`3-m>(lf;ygK7=DNC|xa1}vb4x4he z<#{&u?!8(APcFE!q(CZ?Jw!7ONBk6D)SzGbd-hLTsq-ChXH-^8@T4ymt2J;uPX^PDXA>~8pR=zx3i?0;>2q>Of9OZz-;wn9uD6r}-DTw8$}t1Z;nu@1pffG_rAB*M==C{ zsBp-Oq+M(WsGconKKwWV)qN|&{Jlq63QM5#`+Cb0Z6%vcw2w(7azDf0xYw=MH0%G- z+*0a=m-T*@S0~gBt@IzM!T!HbX^#?dUY2PjR=De*t5Y(NNz$)>t*`n=_2>PEy^>8n z%5~%9w8yVmij;dP7f^&kMC{VYK~_2q%ry3PRvUzV_A$JBlZAMalE zT#miN9dh{{V0A#E&jLXzHa$mtIu5YXaPGPa?wnmHP94daX~-uU8lc)2#kGn~MTK z76#;-0c-vU9`#-Dn;;;&^qHfQcBExKIEeO+fHSA3#^~J=hx6hZ^-@*rhX0qDNd+-qrvn zi+`%Qxi&oWZ}q+Fjt+XI3WHuJtg_c@7k}z4V`0Fs{GV079`*rRkb1Cs4^z}1y|=2% z>0-)37bKtc?QeS3KmjJ5c%MHmvi;?cr%1hrsEhJ%^tr#+-l{WG*0t82L#}4IJc8%w z3aBRheJ%ADx4(J;*Q>yeq%C?gsy3Uhf$I&%eFAQmFmx7Or?$+z}Y`>)H>uLEB}jk;>3TCP^jv`U`$N?2%AH_jT%lL*>_k z*pXvmIA5S!etG=+)k&$Z9=r`RTArk+B?~ty0niB-)%{8if7tubV_b3S^%bQ%KtG>c zh_}>}U_O^%03S{d9{p2KKDID0)u;NuZ&=hZVn_Pm-oP%K^Zq1{cJs;4UJO93FitQ*t{lIuPI~acIqG65H&RsG^1teU7X%-m zHvD_`v!sE;{a@khMSq`xWT7fkxKf%v!sv7 zBob}_KTSj4fnq=h{M~A~KAn0+vX4n+Qcj!LfO!7^WA4G&DelF8)%kVrndllNwoQlRt))nsEyT(bgoau)YIoi-Od6Z!tW^-^klx@S;c zJvCM35JGe@jM#<;n;u97haX?9zaI2)lhu^aocUmMUw6(~RV8b!*6au&fecNqf7j>y z2fY)Db>rtwi(Y#?V2Yrt-oTqHa5WE8UB99K0AcTAfUixc1d8En$NgW=s(JaTy-hwk zx;2;|DoCopuD(yy8{g~fowYoypwg$MGgKm1fZ^2vb{$vT&sRG!a?-OFwbhME=iK9bJd=8O>Ex_0P*Ja#k?KN7=g`d1%+@D_d(AW~$Iz zNs@SDjxfrgksg*L00d3$p#s;JXVgmuxJvr1V_?7UM4$3?5qprlgBrC)XvZ}2pB$f3(u*z&t(B{p326qFTvZrgih@BNVENal?k1K!F|^vN1ZA|I+xfW5iKyxo~*ArV~3RCp(s`uV<33mpet0S_zg4IcO>=(ZL)^4C=&# zaqTpa+$3mYqZSpQ01YPe5K>7`d?j=(d9 z-BQoSnW;FCt0oCtYDzFBp_eAS4l~u?Y%sxNESCpdvB<TWs<5n?v-C~j+zWsaK7E{4ZX*UCWnrN zMi?@h0CfX~s5DA&8mr_CVQH|Oc2wyjRkd}Tfw zZK;=+D@nX^lVfsuOx_M<$GvXft;FJJD`{Y=$5+ zT3qfLpL4;uV#!z3rq`~idMdn@+QwsQ=_JTzv2{~LD?;z1?L>@6q-Knwi z`AxI9;>sLk*p`cH?tPWGlL1o}PdALj<_t9S8FrqJF*Ox*o+C~qSD6q>u7KI=TdT>g z?P8usj@8Q>65O)Ep_+^+ior=F)Q}4iq>(~+c@C{( z;k9GU+&kte5)%eLubK!ZF-7-CvTmv{$kj13E5T5(s|8;`WWV(HDSJzCCC&c;GRZQH zOB4WlioB$Q=b8$7Q2O;K`(Zbax$c#VPMdY(#8spi91Ygga+oWoo6USbTI9Q$GDsL{p+^;1ycWLiT$6#(L<}svo7#)zA9odr&q^`L? zy!kdzw$X4up!b2BlHBfGzq9R63ysHp-5N%tRCYdrjwY897YBe9rVm(6G`E}mj^HT& z0A0+x;w3#|hE|cN!#KE<0;3caJO@GdM@KxL5kHi@T~j={jnjeokJy>H9yvq+Z_kz~ zk;P6c9yO+@kL;i#=vz*Zte}y3``bF>nPg$%Wj; zrr%iR7XG&Wp3MD>sP^BSCu||!_Xb*e3tL)a<-(qTbT#|8lO?}3IKrLys6S*-3jYAB zJ$&81Zcipd<$uVEqchDM-MPHXLENy7Bg)MhC;-_)D*XrP`g@UieTwW`I<^mhzqX&x z?dn?Q=dUtv)LIjG`1HX40E_6O$q4luU4k(BeLu&Kt^J+`Cltp-!coAVKk#(x+7)V; z{AC+R#su1!YItDtGsO(cMFWzNgQhl-t_uNco_(C#ae5Cvg?o0B6o2Ul_&O{xC^aN_ z&m!c0l0K!0Z=qg!{-fENnvDANU?>FvJbJPZh%rM`UqA%EW=(AW0K_!bO;1r#j-#YX zx?@34_SHsE9wQT~p-}QGNx;9qNTiyBRtsEu*N6E}$YZZZO=XG4`8|5E50o%u@!fq# zN13RohYrzXGJAb#B9UlC7ECNzKn;GitAqH2MtD|BeaIS>xLc*7G>1LZr};Qhb6&9OC-(qdLdA}+p&T(EpL?f~>csxf^<%E2^_!F) zwF}4tSyi|!E#FJJQMF^P}046xUX4tfpC2!5^fY($RVtGHa9-? zPfopo#~nwS+_>PeA(xvo19FYB)RXktw?LPs>rK%aKE1t7cupy7;0_2+mr2+bvb7gJ?g|Ef^>l}W6>K$m;Sw4Mr6I>ZrfUILH za7=^qbAB8B_PokBwPJ}Uw){o&~>WQ%ZFVsTemj-Xv7Oz!s6Wh zPrnnAN0(l%4m!?tX&{EM7bKDO0DU>J9_d_lzq77)01`hba&Pn?UyFgjKK6L=r&__q zddYk8Sn3L(TwDQbk`MK{`hGpvtyJcu{{XSqFrc;V^*)vQ0&D{kZ)+dv?^UNBweXSl z^^`82EG|XcfCF2B={DpK&%M-~*RAjvr?329Tmd7CAE+U(`u_kIAM1P3J!-h}>%~C^ z_bx06{?3ujf`6*_y7j8@KD}}PwUiQpj|crt>}_waKc9ZF{Q9q*Pp48eev%1RDy^t+7t~24{sp-A zs*kjFu}U7YDg-~I7ZICS3msRuAM1;KefqvbhhD8%bps>}bkZ^B_Q2E+9C9qb*5B>@ z_z_OFq>>k)?Q;N1NhAbvqw9S<6}TUt>+e+n6RWLMFZuqS_E`pc)p)U9vYepQY(><1bvNK?AMNfwpX2Y<6(iHH6H!`< z^(f{23JC(&ZU@l)ZUFjRaqmTi4NqRiJ$jQCQA$S4$^-MJ_jRzh{G0VZ)84@+;o;SK zRM2FDc*$~a!BNVa{+nCrbI-eA{{W`z-b8tHtBQE)5e?JmFX{r{Tl4w1y4Tl-Tk;j_ zFb7e;q!OfY^#hA9`u_d=y7$O%>yg!cBz;(tPtXBkKiH3cJUZ2QpFXk%ZA1=5$@+bN zHva%_J?mC+)~ipmtcXipw6E29907A-$L7}h`?8w-y>7mJOiQz*JZQNkNaulZZ|Fzo z-s&h%mtOShPk=tJ8yx^xxd1WKYmh#M*Y{A~U3)a4^6N6v0zj}fA77yW3kw1M+}q!^ z9vyqjt_B4c{VKsqqi`%#-%%WYt$%yf*Sf@!w1Js`2E=I~dWrmVabs)$0FS#CAa$yW zp1BlY+HM#Ctja~r?_x*fX#?MZrh3@>1v>4~LkTWjB>XAjKG;K^XGu z$OVfsf-h^HE|=i2KT@OLwP&wZfY5R4Fo_FEVWmxg9C7*dpRI`ZwQ3F(>)No1}k@>yP9{fo>Mo(I2r1B;Pc15f`2ZxT-UCG7B;=K5JA7!{fG4T>gNZobFq?^Wa1 zy1_UM5s6`9Pt<{L=*#`De&N>ee7XX=5}}}qL-kN~1^&=a>OVI(_MS%~T|U3+sp&x! zi%{dyX{gFtSykBCulh$SN&Pqasj>e6ZSLxPhYpdK3{7iZlleTc6w)}5>5Wazzo;vy zT-~qzJ?xgFd7O1+sj2f6&qb$xX9^<$A<*D~sDRfhLATKT1;9M>?tz0=qlZp0s3N%N zvF;tf5{{^u1=U{H1X(O@L2gg@k9v{H#>dQg^-*3OQD4ms+V!~~ut_bZN4N|$IWBB% zaBX4q`V;J?GEAV?C5Pqyu03k%QQ)v1oIZ5wrMoV$QDdj5W1!vsoLK1M=ks!Z)*j!u zka(;I8dLN0=%pAG0l0egc3<$GEK$z&XUc57GRs+CRonYx2M#VKXO^kP)}^batB#f} zQdA!-;uJOqU!-2=++psBCc~8@2sDE7Y*j+y9f&+-pubpG?9*x5?F4Q>--Quc;!pC?U;>^#>=?(N@6E)TMH zA5hm+nq9%T<1t{~zK0=8K~-A#%HskJyV|~Bz1m>hE(A7`&K07HRV^b#Lb6Ke2=LZm z!J-bq%2C}>S!$NU+ik-3(B4S!M>$POq!wmj_#5F0-bSrJXbA^UT%BdyTNkzIdpmD! z%pP~IyGx?Cl?PwDpL!sD*O-dj>Kx?crAk@kwc2nj~|S{k7(9 zaN6SD?e1-Cb_o_k9M=Vl+!)xW=v$!H(3V*j>ROR%h13#CYI|zrJ?nR|v%iz{AebqS zT9VBh79Jr`Muap4HIUA%uBu~T=5qm2OOM?=e+qc;&m!U6DoVEgTSzqY@OQLwSO=rjkhGrI-Un zRF(U?IlVUj09y6$T-Ej;VeXtJ@XBo(Y}R)P)*W@YD|Ra3>h~XCWBYS;P~|Z-J*F|a z`g;0pzeA76RJJuLYbp&jEiCgQ?o#&mcjlH!ezF@Ksnv?yN|H&a#z1clDEpmibeAlP ztT0`AA4>jM^(A5t1WC(kLsZQ#w$Zs<;e7XKwZ;PEO6re0lCZ zp5Ffe7(PtncC}w%({)#1)$L8&h3sy*qLK=1j{WHl;@GuSTN}2q+jLaIxy*bcADzN^ z3sg|}Af9-h=Ket4IZ0Y}zJl*;z!woKpd_6jJW_Wdu91du+_frML2sBjHv5;-+DRvk z)t4@yg1y89U~Ak!sM5>`%|WOO*{e5>Pd7Ho>JF*go%h-l8*UxfnAux*Ikq-l-q~AH zvmn^qR%f((TYSq7%wR>gpW`Jw6al(#Iwyi=F=JSZvA# zjj1Cag$Wo0V3J1=I07q5iiJtt9gWtTr>d}jE`BI>C&fHZeb?Z2{{TvMynTb$9p}

*U4MbvI=0ii&|ti;E|Yn-P_(ibSW#6pTp2J^R{y*I~4maJ1fS zcSzw{y2TW*$|$VTG-&2P@x}&QT00D^WK;u<(~&m~stND(_|}%`t+XlBt3$2n-Bmy; z^dPE`Xhx!=#zt!D31PzGHa_s|o$HEqdQ%L+M6?M z;c9DX##eD?EAiNjN=%J3-bo>fPzJ%WU-KRGdp6G;b6>PiF)rF7iWu_KO(h${O+{mj zg=Us#ju@4sa5^H{wt4s4xom9J8b*zz^-zi{Qg{tVN+Bcy?5n6&pbFmIzu%n$4Mz0& zm+*Id{9ougT=olYSA2}b_oqvIf!LjUlHC~w!C)%8lMC0U4ZV8%YS(7wf|h*z6j@AO zGD^5bW5lyY?JDmc%kH)jA=){T&v%r?tHMYow_?>mV~@lyt?0#pe+@`dx`WY3s()`c zj|TQ@NW|?B)!`^6StwOX!mF#qe3uE1)NJa~8q9tqQq*9(L$T7fIM#I7v@ofssETN# zQMqAfF-sFk4OBG>P{$%MLZa$OVeG5gBxStj!rV+&{6z>V^HoS9pyX739W)}RrT*5& zM&rFc3N^YFAmWAcKbZR|^XUBz#F{|4;1afR!CQhz{{Rv7{{RnjZoOPzx98N$P;u2~ z{{S-X>!;XVAH6aUTC~Ycwz90Q(xQfTpqe#Rztx%Bivn->KEr&$I;EtlSn4B9er!Oe z+DA%akz=DV0YE0CfCW72Xb0`^erwif~c`}>w|El~RihOHRrLP=5G9sNv?|7ihOKV- zK0uIq*dzH=BzbR)zalry14PvOtGTzirk*+Bk~gNnY>l%?BP_a&(kjVjP+0O7{{T)( z&u3z5Ph}*&o)(5%xwi|F9|Q{hI_eEVEA-{4b3#1&mVWLwfwoz%Bc`kE@<}K&O86;H z_oX6-IQu&J$$YEY#<#fpQ*=UOmXkf$`_i(KXk-#aJYU`%gnmSs3#7v7^#t-Q`1Ui| zfRAe1BO`^hW{2j0^gQM=A9~&HmDQE*WFUi3YQ$iS9QpK5DzWbukmxoVzo5OZWBwq1 zeVeN)lBK_A&!Qzb(nps`F4veGgG9EpG#I$G8-hrnr_>7A2*CUS$FU`)Xh=LxIvUsl zVvkpnj)1x)*HLzi%WJqmNV^YBi>bei5-u(N9?TY;dR{4>tb5`V@Y81LB&_q&QbDd< zgU1~`V=~K2I@7~PMIlOxnwe%q9x8V7C}xt(5TUWHJ4bi;dh+~2rk;QCUcYBn3G$LD zG2MP>KJKC%}8Z^J{w{a-$)zjLz+-xydSh~;W&>Cp+1p;+RL8_4Z_QG@DH^lpE{ z+vbX*go))~rtkj%ksEqhVuq_J@z#c;8yvF%_h%8<*pIweVAKQn zS1ybIvxN*uAY3@#?j_2v5a>_HcZ&Yp51-r9M1bfA3ZL?SnEqXFn*q?Fb+9FZ5_l?q z4PZsAIQCu*bLG{}M_HKaE>^^9QNaYU7xj~V4?j=Oy;p~?TMa-DpHbOD4I;!LZzaXZ zBZ5tZ?AP~hBE482I`!J9ETX{1fNB>yfMIiE#me#Z_pTMrdew3B>j^*zwTN=Su)WIP zhbQWnKJ8p&b#I@qTtRLT*MV{whN7U}z^MNKRsDVY?CW_I6zig?WmePxYXw%h;^mL{ zbNM{}42pHtxK+Q8No$ftiyLr%puYtEJ^RUawEUs`qACzLBQEG>%n(`f4}-0ABw5LBJe3_fkY*1M_mA3xZ0H z2?f8_A76F{fUbD;ud}SG0+Fj#v|QfDk^MiY)yKB#0qrFD)2;Q=ry5k2cC(Z97XX3} z`p5n2-B^NKj}EJX4GwzCWt1|LVptvkKT8Xrq2%0qs6KsawZQ8uC7)NQt*`w`h87n5 zbN=z~+3KX6isrp#jRW#mNL3297e1TudvkmH)~{Z*>-O~^DGCOk=%<28-2FbB+ucd7 zYu5EsIH~GOM65_tZ6N@#KU2$C+Qa>Sdan?Asq^&frHNQ+A+CV2Cy+j%DgM_NGwcdcv<^!;D&UiDGe zn1M`Vt|B5G*YyNdvvXp?#M}Hy{Cl>nb>e6bb$XT|7EVBGmL}FeU2H$V5P#Ml+b!0! zz?@UAW-{NXfD2q&$5M-f^!nf5t3Xf7uWO+h&-$^~CQB<5#lTQcHWvW5(3Zcy1H-MB zKAwGKShy+&)Dg;?lVU;U=GXjt)q2%_cfv#2|akN z$s>!{^U1e11MoTby4R0hA86sz9^!U~6;k8sfsO6JvYUNue?IFYew$|)>g&h-S?IMK z+X-b0AoRPf^@h{^9ln-7mLy{zh3g4A4={xToJ448AWfRVMC|PrNWx#;HbM#F|hl1(tR)O>UF5+knKJ zDqvTKa+5#@8r0PEvPOa@@Wcv8P)Q}SNCy;PDV$@Xn7{C)ujb5@{!y0rjZr)zl+6Uc z7x6GFRAgjmscBZBw|z8oLUdot9jsXD;9M#F+eIwbkE9+tV$aXu>8}|GAL6mp`Bm^g z-uQa-ro;aL!k0gql}#mFnJSNmc>1`p_485Ef3l&F$t`ACXQxbFAWe(xEmY9t=?z4m zbkX?WXjL2^AZ2Ul3Xs3NWhK9(4hOIHV}=Dk%f`XbkM|Zjjz1sl`27C>mr`Z_0EIe# zHM}vRiz!X;uO0W8x-8WzbxI)@D;E>WVA>ckFC#@_8lJA|VZJ+R`R^KZ}oE3XMsn6-?7^MAMa`dQU~ z!lS>NZ4G*3;o1KH05c_Np1EtOdONj-F1H-+7K0&=u72&KO8RQ>N~1)e2~m@q1~e8X zL=t^;pjMPC6>I26hmYIV{8ZElwTut7>HOQP9R60H&xiS&{O9>Ey86GedW+#rA6xY= z$DYyoG1*b<{hQkRBY5r|lh&CXrGu;6yAN~Mb~gUQL%XsWJ?l^Q$y1Ls-{i8Hq*Mi2 z4fImk!q4^O+)%P3B2oM?sgk2fT}x4}r%9pGcpWtGod_*JC5WoCR|6O|1lE|vMR;|% zTnz&+lDy04@s8V>Noe`x(sEH)d;aPxSKqubTM0H7HKc>nUdeDlG z&WAlFS0pL*r}OGUqXrAdBwpNJKyJW~!BBnJAD()#Cm^3boFj>sQvt{-Mff-5YEpku z=b!8DrGfi8@nPI4k<;{4LPE?DkEIy}tSzM6+x=5}_ge>nJxu#O7LebCumb-8PA*UN zvG=-u+I4T3>5`&0Mi)*CHOS?G{{R8~tB-mI=hZ7(3iXANZf|wCy8i$|Y;H%?f<4-_ zuiMwPdHJ5Y(ZO~s6sCZ{i?#S9{WP9=_uzPSut7EQ>x#mCAL>@)O^%~rMaSbwCjS77 zd$4RCtxWO9T$MtX)HPWB2lZeEr5{hIg>x{sy8CJbnlG{{TyWUw*I8uTN zZ_2X+Z}9&Bdb#(i;>a}`|v(PhguEC)2zNb3ornSUdK`7@&W$<5BINr%`4Y|JUa6!YxBU=Y&ZY` zZa=B_v*+bc^7ZXiB-f~w0pp2$afw)ysFD;$0JvlI)VCjwdH3pqwCjFH73j8h)j*CJ zxzt)h2?SZLrH3C|fyIZ{*=(*%?5cQ2jNu|DlLa#Tl{=e4W?;hR{ zfIP=YOB&;(wqGs&O(Qc45W`Nd>vj!pZf*YC-r7u5R-Ifitq%^0A7kzxOw45}6q91W zg(T@F*ZSOlupa0bS4j2$04Gi>aj594?!C&ZjH*6T{+Tak~?vJBGL7ug!Wr zsUuM4Yxl6lQB_fypv=#n$n~8>c$sK2Q52endOkN)t`B&`Cuks%kg4~oFpB-J? zo9n#sor%)hVyh*Cj-zkqvpXxU@wt4aGPPu=INU~2XyKYzU)2oz!7kfzvPZScNp}Zm zq@WaKUk$~=gF~f`u^4VO(!f!HAP;oStL-~>-1fnDQ#7s*5%l3&BDEZRNi?t(s`zcf zwKg5`!{cUSV0G~C$xbXcU+EjaHPNeFc??JMAzi;)n(971(k=@TvxFyBlHzwKa zY=&PukbJ=q|_FnMz8W7B;sv*gJn6zHk%L<*KP_ zB&V*QA4N{7k*cTxdz-mHHXFNpsuz?+rZNRgqEgK3k=YUgY6VDrIH(;0{mY)()0gaQ zw5h$G?OHW0RuM$4;z{A0=<^D)+Zu_C*Hr&hH8h$+L1esgpgi_l74QoutX_`7s8bs-Bjn7pB$ayoY|?&u4wf ze6t?g9b<+8367x1vm+lBUpj*s3pf%G#wU%3=`?jefZpe}@Jtpe32Kg$GMtA7;pxO=CL7-L#digQ6cDFak}+p=$J*JHWmdrMuCB#QRlLbpoZBFJwVBza~bjS5H}kjR~ks8jn$ zqyY~iOSePIal>NLi4noMT-7CDHCI>RaG-*ntOZHdAE3Ya%XQZ9@BaXY-8(l()Z?+6 z%WVA5_-)ynZxx-%P~qj>lzSVvahVL3HxUXgMLEmut+^EYf_TKVQ&VDb6%NxP#PG-< z=9{RtyE{quJGG7xEQ_J4-YIw{9vvzMemsV#jerE?AM+;TYh%jX%P~&rtR#sB2B(w+ zR0?wCfg?)gRF^bWBpBa@G3?q7$oV6hrNk)g45a%!KG5KDFe@AQ3)U)W^Ph0THUsJ91YcX4;F6HrQ&EJOILQF51_5gYCDW) z#K;n4FYU8iF4=!>=)b(ua#_L<%?m1+!E&Qr98FH*R1gg+Dp5QJkPqAEAW$3liCgv9(mi*MjJe(K#j%D-*XZ(Oz;t~$RHpUh-wrp#tC zwN;s1w&&a1Ulk!-j!F&Llcf9Vnuw$#R-{IBbfb4j)7rVMRP#`Uf;GkJGA08U)n;@G zzY?rS?eL8!^$Dkih{xK<#8w-eOu8m58PG_m0UXc|Ah{I;hcyG?=z94POR#3>f0A1( zN#<0yL8?c32+%TUol9TjTG1j$uQ#!IY0nb%y@`tn`-F?@%HWp%=0WRFYY#q0`V9Dia=(03XW^$Q4 zg)>p*@wr`i$>4vprxfHUWqAoVI!Ck!#jbB$Cq1`MQ^y;-t9MW zt6H05Aq)Wpfh1}Nw2FaB*ERWcTXWStN3;eqJ^8Wr-B0(sb49bT5o0z@Joze}%UwlR zlcL2^RpBv_Ee!b@EOh=il2{{e0Selz3aGA3QWbd#T_&XDXui!0ACGo&01-o0d;UB5st9cZ@-Kb+3mZvr`S~Zo%_9Ns_?ruqdT#usiV(iF}U-Q zte~#SRM2NAX1jUU(?Uw}6+?4&vX_S1WM-o^5`zkA#LxqPYfR##a6LNl z>>(w%pJ9u~1yD0a8mz}edh4#L2qRNdCY7P-O+We(+L&*??0vgbwH14Z8Gzd~+e5D9 z+;Qac8Jg*0hZQ|u-o%Q%oRst`%TF|qPeV~W;x8gpv`Z~5=8XuBe&Bf2ijk9E>>2^4 zm8f1AuS@Lhw(GlV#=D9&mH-()PN}4@O(BBTAc2JqRSv9>)YRu!xV}H*vVI(H+3c>p z%x|6RfZ6>Qg{au|P;ENS!OKaK$<4F(42*Jknrau?m@2s_r^!hKl@$<#dF7Y(q_MfT zxgjD8E#6v#Ngf*JMHMUh0M}zOhZSvaOz`L zig~E1>4i-|GD@v8$s>@<*?#bNg{v8JT;#uzIpA=-0O5hq%a`Q8p3d?c{t&V(YO1P{ z#t_v}R{#<<9wf0QwLNR6na31)L0bkSa0kL7I@z!I@Y*3pyP0LP_8N9`FM zE?ON_;A%f-9;{>H9C;YGMlP!jPd!`4t63j{D9h75GPP4x#WhkkB_^;igsTQQVs}8w ztWUeC3>jEs{f-#&HS*7=TaPpc{a&Z?=y;D|<){O*CY2_2W*J8inK7bLxJ7v(u_U-4qkake*m6 z%LAK|nL;Fj1x_;q?}#(h-+MUxyI0tFXVxwx^lO4(fYifT$9_p|>1K8};P{YZ^} zi2VNm2>$>n>wQxKwUjmOq`O#$I&2R-kWIao7oeyZqczKd~@gh$ZGh!jhZ0x=_>pf?~B_yGR^PkQ-zb?gCJ=dRF? zNMHa)47#`>x%G}k#s2`?d#Tk*k^ZkPylGyu@~a@aolGx#AN9cgtIxk22KD~{KlwV> zT)@--HaA{vegc7S>B#p&K>>V+UdJA@q7Xxo{gOC8MkdDKTl3Gl=Dd2T<4-QRq-9FB zfn@~=K9bhCAM8Qr-D+q$rvpN9)?lMSVt-PC56}iY055N$`unM2gI*nbJbK6{i2^B+ zREWVgHsF6}{B?V&Wd|%esWhoQN?M9lae0+kBAp?wH6Bfy`VY^x*~W98sjDQ@ALQ#l z+|mNX%$L*@XdvnhW2gOq_fW^rtyi>1N=unB(0=CY{0M}8=JEmal!iY$K&6N0%_K>#~pZ8(tx1Kmm=eztI@nd1k6 z$>3bt{QXb#_qy@VS_Gao>!zxtAcdJYKTykiT$`WxpMDKedi7{}NAIfGVB59MCqhIr zF|!Rr(s)tF_I&_iyZp|zJ6#jgAK&>@9 z0@$s>@zLX^Um8NySbCg=9Zg7{s=ic$CTUb8OQ{-0(V-Lr$oJ<~1G+xrk6$jg^B%vq zrtQayr>L*W7Nu(zB_kBkQ6o*sDzjeNgvR5YV!?D_R3Tx8pKCrgIhIJ%rxTE7`jP%tyW zAexONjyb3e)q|Rbq<<f{ zD7RfVQG9>uuZ@(QN&J+4Uu~`9OR#a3Ki+=h-pjnY7af@Fz4^IJ)W5~5bAn2G%4Dg7 z?kFewn9TE}(U?QKs!bJ^<0ak1lgT37A0Uyhf@lV6wWSV{0ieJ+I=pyR3si#FOQy2S zTBVy!IM7i=1p%v6u_THG-m4Q7Fi^!DaxRDn@c;yBiWLCSAN#E@{hk25z0%#n!3bJ> z3s16xr0HJ@JYz`z00$19EgH(g;N0prKT^W?1Lwh$xT-E9%k! zy~z4~dEve25vM0TZnPx&{{WYv29A+DFtGzxkV66qH|L%{w)ee7ssZ!r%TRqsQs<_L zm-N^Ge^1ud`VZ(Y?`6C*TH~v+BRqOV&lm18xAp)UK;^$*Q2zjF;QejMBk}KKlGI=I zf3eejL3qHh=aZ)2n*pnfbM^lKWAA!}39nu}Db^Q>bc7^}aIJ4pHzw!ta6j04-AS%7 z*Mk7KIURCT)4?qN07JkRV|!Tt0D-r^R-&VaR;@E$yV5l&wS#?0w-!7Leowy>#MiG> zW6*WU5HpZT)AS$K_r3oB*Y~|%yn4M!sq*VGM|NNV(zgJca-*A%@CWnn)%4@lK?LXG z>!1l{PzbfT{1f>90AcUlSb7oGRY71sD9Ww=rsQ06{y*)%9`#!1s#n()>zPRlBS&xA zb}p;{)Th!kgKkH^Wc)pNwn6Gburf-)JZcpzyxfopy8dntx`+6hnEwDTRp1A&SxN#m zH#$gQe+T_h`h8EkD*`on)2mk>KCzVy9H?Pqa6Y_`q5hzA@4(a&dev#b^@>FS8MNsk zwfen3*|oXiGn0_Db^q0F1cu{{SaW z%<3UgigZVEIWlLEqZS^k>T7UCm;g8i{@+=tq@EoY_@JF25PCvx46qcAM1i<1!64m1 z8c#O3C*6#KnZ;}SI@E8ZfLPP#{;%258||IQkhH)^H4xhQ1x>!31HlLD{@>asoR_Am zdG%+M5JHpl`#L9kpLIJ>)T+LuWMz<@M)w||rsm&Icamz1;M4hZnPnBppySm`_iag& zGd#@15i<}Nk?0O|n~&{V>+KXyR$!`YpY>Cu_is^8Fe&?bt8Vhk8r+zKJ=I=Qer?AG zi`(5JZ}E$VIHmymdM&(^tP!Yh%dLlh;X2ujRx_ghWiD58?d%Xj*4v@aXK@%= za#F#utD=-+A<5R!&6WF%%2HFy9Wa(*A$ioZr~J z@zR+rzU8OINt@jC+b?`efv4Kp`l)c#q}R<$JzE-JDosKY83t_J#kg|BS9bdcFdyB_ z8ANj_P>jsX?;Hoki66u!K2b^A;www}O{EwZ$P9~CX4J8k(z0r8 zLqVf(HB+Rvb|xR>R%@Xn*!>G83*p8q9k~YX#znAcalMz?84BntYpbTl?k&^1sOH+( z&4-q#sS;0v#n7E`pS3knQlxN#m)>QOtcJ+KX&K~|+5BccT1YApa#)}QQ~^p0Z;$+m^)uwy@m?(^QQO8ptYW)dAF~Ak?;v z3hqlfvsAOMVq`u{cMi+n?Xzp^zBOid)l+7(J%vx2#`b4@ZVa?Bq*(l~@yxy~?H#*B zl+5r&5Hu7S{7gP zJnlCp402x{^-r)al;2c zcYJ={({)yVuwlnNOgJff1FNQrZL62uX+cpXswt&PSSnswV1^GM)N!}(2WFB@%a^xV zttWbifr~mHE+e({f_yU~7mN}Wg-GdM)6Fw%dhV=mrH#!&iHi|l16B&jKu?F_DPdAI z_Yu&>Q@eNGGkfH=p4F@9y~(`s=?38Kz1g^FdpG0;=a!oqG5Cu2tCpGY7~I}El=zmX zBGuK9XpN8;1-+MUclSG`)86j0wAW5RZ3K$xr4gmW1t0)KVQMP6sZdhi@AsRn^Ilv> zB(jY?(lb=5gV+W%=9p1UIMvWE*L}nDKc?cR*&VgFvmN(Mg>SOKcduG@J#R+*fm}pV zQq|DWZ@0tK)9vl;C-G`?G^Q`NN!cQ5gpySbt0CSJ)@ZNxoyOwE_z+oRX+&&lbtP4` z_&f=YU1$#u6%JYRB$g61meX=*(gFXLfc^-DPpx zV?D4p7{bqiqV2Be?0Syu?0OtsL~=BE-J7>-(YBt~SSEE0Wi1?v%w1*DfLnLocP;Kf z`d3emyODiBWd0d@3>8L8uDi+Y4 zz%d!fG(8sWq1hidemv!0ZErE0`AM^>>+5Q^zWSSf)^#7rEs-8w>c5K8QTArop@xTY z;$wrw95Kxt6?#J#swixxDRywa_Xkw5$>s0|T1*XkjVw*!`1t`BrLUpcds>dNeczJAR@J3NIYgnTMTCfIX^GSfZntgYdb!)} zH%?*y02g*hL($z;rEsDAB4doY<4mqeTIn@bAf7KYNzBt)Z9A6dFtV4jN}5D+7#B(` zZb1VwD<3#+%T_`+=*<~J|>*4%rphKnn>FCwv!#WrKzNXmm(6cOaw>^s~=wIf9;=?R69R#{e<}xMt>_6G5|{n8FW~% zv9~|t?0fa-Bxr>-06(A4*X7iib9#`PG3>2A%zvt#SN`bl%0129BXG%EO+GfODX?&p zB$8727x-pbDk>}L4O{q{N(d|6f=YY{KyokdRx>o0Gih$wCtTM6Dul23y!s^FZp4Ri z(rUj%R1OvGV?ub=r1W|_E3I(-m4csV<)x~d6;qj_%gDG?(^E8<*Ol?XN~@ZBn4R^* zEF=|HDoH}Xm^wyGQcT1c$!y?cY0uySlK{fvXFGulPO)aJ6g0VLD2=O{;uDITX*900=0vKgT6zCq?pBFmsZte^g z=)rE?`IcRix@fmNIJtB5mAGf!G_)ByJbA9AhKYxUN-Tt)XoRs#Qu;x07O0xh%N%UY z9Bbm0bsn^FMx{KxJb})7NpH*WZIc&>$Q0>f4mA~G$@1e$(QDP~K~LIi z>C}tLx_@=w$j(RVt_PM5KQBK~_I0f$;Gj`a{gqPXSlLts)ob(V1Ov(XduLdw=*gc> zq<Nl`M@5s6dO7!5XC@&m8YfVc!$dmCCB+FKv!kM(_>NmhcE zwuYbROa2a%xQcXowgNDwW(?vm$kQ}xstHldjb#82uk`k{LCHK#I#s|{y;*m}_~(x? zj+TZMGr>stMS*4!H3ZnHqKxJ%X(d@Gswo7{v9PUE68V7&?WB9TAS)X1AM8?}WqP{z zIiSb*Iyc`U^OP^OVW*(WWHW19iKVX2WD(Z2A<0$L)C{g43y^6@TpSRZca>HODI};_ zBk>plvm{gTR~|#kqtyOd#xJf5J+#6geM|Um=W;W&Z$< zMe*YsB~?_-NZ3}StnE4$Riji$@(EKkwEEo7tz3rjl>viaMQyG~!c_s|UK0LXI!?`3 zh!Ol}_LS>-{XdWOjsBj>ijns9>QfzJ(m=A?>KWOE%Ub^c(0xa}0%=D0f6LZ^pdj_x zj5WrqavX3yB!6rCPx}7u9O@Nrt`A&fjU+yzKtKT_f)}ej-X1|sj#(;zQ12~RuoZDUaY2{Z(Tl-3fXl618ZJ1l5C*f{{Uaj{o6G8 z^<}QCo}!a<1w!1mh9Q9}2P7@e_*(w}PJQpry;$e2AU>c|NMfX3+?D#Z!M)i30EfS0 z^6S*|^XmgO+k^cDtaS!IPxc1h_60iKeE$H|{{R)&c3;v#Z_})XDn*UT+*?h@zj<}) zc~?DiKe>G&v=HFfg$c;#@#_G7e!l(I_|rXNlmLjsP5!OP1oCVO{Y8iP`|#_{UnAH5 z)!b`Rc$5>$Fn82%>jc>G$XkE6_Mgk=(yWvA^~FH-qmD^s)AjV9Q2zj1pL!VUXUo^D zi_aH6G%s%ip<73*9*I?l=J2Ed?V0k_~NH~zX?^KX7}=jqmmpID5@ ztf*9n^yoGhB%5FQ5IwVA6v6A+;zwE5LCwYVgM0q~YTR-8x%aArmg_|E&U(sfP%q&E zfL)r_RveyB_GAW-zG_TFC+_oAae!EwTwEv2BDX$SOmTm;`;GbE-A+mN^*`iQ zza(3M6EM+$eBB8=h6(X5mfEu<<2kH;JV&*Ts-s0}? za-Sr{3?;E8^sMsf99zP-Iz@P>G8608J8$25Myrld= z4?wMd^9t{ppH(JP0fb3Rarmir{u-gF3A;%kmZ)T>l|WlAqhrZF;|t%skG&Vuvs>>r zu*5YGv020c{sF38ZB_LAM<=MV_wP6EoS_yC(`&Ov91_kq&_+vYkjTtGgfXYDO=EfDY4hjgi%!u+yKrJwlSrqZ zZD7MZOahxoaVP|%`y$so`?P;}KYVDKd7)1ctLbffiQzyK@c#fmFmcwK?;-CAk;Ht{ zU_Ak_w!j!GQyA_%YJV<uZLd;hs%SkA&!rq6DSPkBRTWQXY9F0aBe-m z{{VU4e&g{%Z&s583VSyAjRs2`cNz{f;5cWaM)$wnLeQV%t6LfXN-{kd!R zpZCUiWsq|Q-Q!Sct%P9-HKlV}Qyf9BA3ln=f4m2~+a2f9U2fYnv#C1cj=>I!55W&Dehn7v2$8cM{LII5$g!ciJ#k(q->O!DOX!%my2d+8S* z*UR^~_qr*HtlM#1um;95K&}C!8jp=hod7sr{5f~qdoH*4G!J_@bHg{Q7Oa^4{jf8lT*I5s&~#@a_f)`CJ`D{y4 z)@<#m9W_jnLltUca?pkg2zR82NtkHls*d`ku_YApzWop17u?JL0IPyKU76;9jbUw^ zlsno=CT|DE{>R>?M4A9iByCrBBnkkQ$T> zJX%yA+radrZujrpy~-CURBEx96*Z#RFn1kdo#29&HKGI8}}yEV=PDZ5_x$FOg`H5 zdtvW?JG5^1+iuGon4r;dLJ6%w`i>OEFl(CmbQ$h1<`ued>*Sja*HcHVEK<|e=H`fi zFEoNx%NUBrNC1QC`rFy%r`|i=Yp|pGy|kn0&0?Cl;g1{koOF99ynNBGL_2=W=}-%( zxGFw)pMc@eYcKOs%Hvv8%5A>9#ZL|9ihP}J;-<$;5=%R!aLahK#EKcq6#zAb?d;rp z`R>!hBU$p^({kdXixtMPj8z2VQLS(Y^64=5x0}qrLcG7T$#PVX-{WC%!lT9~BhdYn z>sn8i*&5Ep`CIbWuqf9Z4nukTp6or(g{Fo|ddyxruO&7=DVqCvs%14l!-~)QQlmVT z3{zJ=^OuwN33nb>{Hiy=I<^q8DhKB8obY3ivG zI@u(L7Lzqh!kRNIv7tqc+y!IVUW)QWp{a@vB>7XzJTs55bg@8U75j2BP6w&Skm70k zI>jvx69ty4t*orb=c=D0CL)nIobI0r>hufNT-5qw?f|+o2*qRE=oVjsZ zn4D2Ti>Rl;y-YvEC^6=kNgg*RGz?SjWJyp;b?9Ss_SDNN1=6Gi$I8A(t?E~+5yYJQ zy2Xv9t;}w^eY>);^^aYi+*J5&p|j{|zl-M1Q*h-5D*?5!D~^gfjPByg$yrT7PZ~uO zwYeFAjxf?BVVPY*n~R5_RVA333IS42kOG9CKss?nO2--!4-Z=K1Ll0G({^8OWGS+h zzjV1wHcAStggHtr(MeZDp2TJFv&lh`#AYa^jk0*`<{Gj$h2W@I>R^% z7?9YgBOrs2LEu5+2*;S~-gHqy4GnnX1b*JH$Nm%BMM;SHXY*#d3T%taf0O6S%B6g~ zO-j>vXJt$_>{YMO7_FUNC?yV8hieUZ|Y)bW_I} zprzMK;k-s$)Jz?cB?O*9_s*NYzb`OtVblF-?B$LIDR~ISh=`vPIHeIaMgUP-w3?Uz4Mj&zN%DJtBgmC~RT9A$KkfaiPrpv-Bf}GWR}6AV8px{m6NW0>D!v_8hXX=5 zQoR%0d-uLuRy&Vw0i9%_5nhQxlfZ^ZNOfVIN_4N8Jv`KWtH{wv7CoOGY_ZbCQcVtW zqOLJ1yVTN37Zj3HR8yzbU-QSaYoESvG1Rg{bXt9d0w_oLIo+B7$r_Qt}>gcYr0X81$BWBXT z@)#e*kGiMdcIh-5uV^P#^DB2>uz=BUIM1#+(|zc+!~{1WUAxqLH&KB@=iL@5z>iUk zb<}^%ZyHbJBEd7R9;8i zYnlTN03N2e>Zk8bvFKJji?|m*hw33T#|o7Kr}ljMRqel?U0a@eW%kbbz@dy8Dx;yI z&QryxgJ}~TQnlO@$yiwb0Ee-L(f82y;_cOUzE|FMwUlbLXK3S|H6C^FWN9cqQJ=G;HMKh%U~ig_wA!1m6Pd{@KXE=HIog*q zPZ$B4&55l_e2O}$yAK%va!rrCg5>`IbG^Iw0Qh{H&GvVCeR}4*|xOAK-8F z9>-;wNen1@5tbVCo*!qQT?mK@6x)m6{z2!1`M13WBOYB^ppj4Yf2+%`^exnocsi6H zrT+j*^YyIciMl26;#3YwaFNW_xLpxo+FYuoT_KO}#=d+~8aqi3&Yq+UyXVyFm1ENT`{ z-I3UMp;i4)AsmHK$v@NDSGq(bROpSy@dCTZ?hc z1FS9m-NHQ7k+4^m-^8*N80uX>jRM84-%E~t!+Y=FE7?7s?n_O+`u_lUkqracz~}#dVZ|!S)qn;Oy(**xa_q7v&;{z&#sXZO|i^Ki72aI)mh?pqa; z!!D0(X&|U7S6FT%BmxJS2cj7L_}d+2EA8JilAK3@X{x`&PpkNt{4}k8U2uPwSh-@U zXu9vSWR{4|G8DA*8+uC2bX4J5X>u`t9#KtBgY>y1H_&tMcE5d}ZSJop+o0s#`L1F@ z?0?0ys*f^!T43YtB9-ai_4(NTmP>)ioX%MohmCEmnppIWM99BZG%Ye7q&LcC}OEgnGEnPapxMrQBs(4utmEpK+doWMFN4K+C9mYOU z-%XHmj6khTc~6pm1Wa-%)zvfJ3$8o z4uD?K?@0F?wG@=SciFEkG)8=yt_vF=!$|O~ziE+T{D!@Cotw8fEKKE_DI>G+8yw$725B}oYiXkLa*617nO#mdQBvyx@ z6EpJLt|}xL*s*)yRn^BN@I-L<-`%59!K+X%WuNUMDoZ`A06xs5`_A&1wR^M5+qky_ z<3CSD`4QsQx#889-+oqE5+>!n`^9zv2h+jdUorkO@cjN0BXxPdW=fY5YSuq(m&QzNLAW1JVk{P{zE?=DYq9-cSmLJt+Cg;&Gx^2ZTdZm*{M>tw`^wd z+Zz{|t;z~|ykzvTMNri=&rVUS;1A+3Xr_7pk z7v_6~-;IZX9Fd{|-Q=hyq-8-hPzRnWe%`hgn-jSdy>sC(9!HeD{{V@TBQYlKvkDz7 z%x*|L+x&gTzqw^Jf2dGA#SL@(yt)TVw#cjEYerM)^5dWL^~Gh}O*h&-1|C@&84QuZ zmY4`)Kpd0gq*Y)(hTQ)Eu=laFF)yO&bSTYh{;#*B#y`|(Rg{pXq#w?|!4>}iFP}^%uhL@>IX|9!{?46Z$!3;7jgH4R zh^dkl$jI>MMj-h|+lIIF01iFcD^N=kz@nV`f3kXcKeX_vPzb24NBX|bmNa`eFSsOW zDTdE8pfe$sQ^WRja+_b&%Idcf78(9S z96v1eIzu9j28QkxU{meyl#6`>fkUej$Y~Nt2Ba z9vn}hrw*+q*(?%xCh{`m)dfjBGf_&4f5mi?6nSj6PO}>vTW)NH5*x(w)e%xsFFc71 ztxh${pmL;K5$zN^Y3j64Xp-lt!KvHbx${`UUsqvW;0{7hTl@O*oQi`v;#@HHtQ089+4c z&Z0@6p#K05OZMx{!(I$WA++R~BaEub*%=GXAU9NDO{joJ)NnnSw=YD-LG^&WMGY(d zq0!3hj=+;}rS$q9K7OC2!jjEN zSyECNQ_G~t68<>{IzhGV`S#t$+ZT@+X^0^JrkdiP;q&RIj3Gpk)}<+tTvPpyq-1)N zH@r5^LkW?o*{Olc(P^n#ifpvB^;E&5m134Orz;^PLt4ZF2el8&@JgV)*)ftBc8t=5 z6Q3iTbf({IYlxf)6;aoXIMavw9(^$F-kIC~03J40>BDut$l8gR?Habr=bNs!+>!1L z!I0WGEQUfUa%oRMxjfu-SjnnnjTg%Cvq)7g#FhKEKJxznwY<4;f6W_=sk6yH#uTte z2~AElcE+f^@_Z;V)Leo804na*e6eSJ9m?F!ZX`lHG<%6zqm9W_jB1g9MP|~1f|aMH zuD>~Hen!^z>(@R!?R;^?P|JpbvvOl0smM@ei`CL*e%U2|4K-X+C_=|t=^=nO0IENA z`DO3!p_1z1ZcqxZgh*0UH8lf5Xnk@&XF)CZ-HnE8t9I46Tf)$!sIpqk8IdIcmOu#Z z1xPA?z-l@VemdayrbBjZ-n8EJFw^f1{{X)6csyIy*Flh`5$;*&vCw2HW=0U2N^K71 z0~Tv(0Fno}H1`t;7-&1Ckz-`=~+3xnF* zyCc0jFEh5E8@%@g1u@Cd)8a62*U;gNYgYLhe2A*2T1j_oR1(R$NocJvh~5EkSx^qv zkSRVJ$j4F*XyP^QKqNYpRqe*X1iNHAmE4-AN<;#l(oq*v6HP#t;Gl{DR@JBkFCWY| z;kQEkXzE_k`Tqd$hiGB?JF&ho<*6zAGp9Q8zI5vElsgA+z!RpL%tYwaD+ zio#~+%VM`KI+_f|K4^_bN!AsPdKd1l46$0Iw#G<-(HwCiBQJ|0pEaiR2Kx1r}DCuJ2@>LnJbI zN<6io1=@#+s|`E~(43M8AmqKS%I|Kq++>I|EkFcRYGAHO`!xjs;1EqKLKFW0%=hA@ zVCh}a@<-x^z}r|4m0dkYhuyf^>RRZwj?LfwU$is0t;5>=d)inUBp8kBOP=doRz{x& z&q^|sS!_)I>6psyM=`}5ix<)d)hoUkB1K|!Fjjq8qNytw)Xc`BgkiaC);q1G z#k}xVQl~*tMiNqp)dYMb)KY_y;5%u>nZSEwnv6W3x;YJ@}P)G7TPdjsoY%FC)syqlr zKM7DqK4Y%%kVvyfDhF9sNOZhpD?-}C#zT|)PUUV7;DPOOx6c**zb=;y&;fzffpi68 z(p0px@W%C$$OBQ;JdSHj(Md68$deqA%l8)u!a&UAf~+hLn<9W>pRn}mRX7^-YrBUX z44rvKVEz=!dtEiEoW8q-v1o{2E{m1&-yqYDJ4NXcP&Y9TU{7$Hk!nvi&d`+j{o zR;n{VPgQM}+w)I6H8Rn<(WX+Ol90&1w?0B~6p+O#M8Zhwye+Ttq%DWj-?de!PC&2o zYBDGCwi(QhU~~1rk=YWBned%&U0#@ zBD1?hMw4KDmTz13*~_~|>$`5V820#lGVBz!2YAA*S;^IfMP@a?=(}>ew%cvfalL;I z(Go(<#43#hnhcsy3MghIfC0~2y}`NgH6|5Il{z&=1r}BxF)(Y! zl0vg3O*KUS00e@x>}~-1&>9m?p8-h~T^U(Oy1KAsVg3YM5PhGiNn=SOWoU@Q15iiW zIx`wv22u$5b>J*-{`mXQ#Z7bm9=A-_u8NC;Zb`lG`TT#cZ+qZz$Jed;bsk8cK~w;} z?yAf{H({$${EK}BxcB5Vby5dj2Ou7?JYh>Y;ES&$_}$0=zMI?vKiBr4X%s+l)q&tV zx{D$Rfd)I4JTKJK%9hQ^dz2b?%q`EbvUP& zUAaK5`&M8-1f4Fe!vpngUyJ+I59QT{S0k?lW@Bd5Ol8`{ToN^0n+x&v_v`_I*MZ?) z9dLC~sbeM0k=*GkVt%QpTI7Gc``GK=v>EHSVJE17NGqg)Wo|4(4hQ>hdh32z;n)Ax z+*p-$AP-fLT#gl3+=Kq!!~A`v836RIqsUNol}hsLKA->zCc}^ouVG=yx4n!E@#|E< z$5{|CRVKvodtdNKAC5)2{CjV>93Id;I@imrypn>&MY#l<5PqDVY;E=Twg7@b$6g0L zB(k|EsjEC_z_-#yB-oF~`$!;haqTf;q~p)6u{6NPP4H%%HjR1}mi9LvLCuZ+zwdtP zUyVjOXqwPh%b-)TyP}V6K~qk(F^4NQsRW9*A#}0v~$G3L#d-_@$E86PfZOhg3ntr zxGXfm8@H%ohq|A5ox)kJ`ET0`j}A0uNw-P|W^M*M1Yt^y*5TBT_t+m7SiSB?zYlEp zdl$FTsklN`UBar!w5VZd2r5dDLAa0=ul6X$jtHG*;LdJJ$tyB7jgX|T4^ffIWh9=v z9Zyoy6%|@uNvmh8k%3i`q{zbDARK$dhcP6#cNf!1CgCfROEGDsG^sMm#IrH;&mTUq z4(jUad9QA!xqFG`t330wO6?*1WU(yFPXgrA$N`R(RG189ZYH8yto0RLb}Wbf8CP1A zvu3F393>St3Z4XJYL6Lbc^F2KCp?>g8JBpzhE+DUMJ=RPq=9i6QBqi*B$_A!r&k(u zO50Oh+qLz@*aRs6IiZx-2@nE>hZfd_sOAe%~SfPLjQbxy`E`5=1IP94vIy zBB9R{P}QIq^Br-Z$nD)ZIMY2nZ8m;rvP!EQ_V2Xe! z2{}BnyMqfyjL6Z+j>ZhGH6WETa?9hAD!60&Xy{Eno#$DM{&v&;b=N?$i~Cb#F530C z6RcYpSP1Le>#Pd=Knf2)ah|m$#k3Yu+uT7Hj0lv-O*?>~KqyHJ4!m(9oHNn5*!!a? zwzhs_aY=%u%q2D!Nb^lz@qMO08<$1ENmo#iR3e&jRaG717PB&zwFPghJzeV0qRKE<-FRgZ}+d=QO_FNmYhpXD;%_e+33QlS5QF6 ztxYm|DmD9mab+T@&*LekfbBd~$++?~ryD#uyyX(g^_iHcE98(`6}`yTp@yG6G$ECWepkT8}& z4!2;$kOFBGK%%QsYEMOCujGvt97h`r`_0hIA{EuRt*It5CX!G16zK!B?MpHAx-j8S z79-kwenZ@0b2NLL0zD+@UlUeEDN-r?^U<~ED)Mx;Ur%jgawc93?4@|r)m6Osbbr1z z)~@cwzhmSDGznjWrJHWiW8LYgDW{I7F@~*3DJrL_c&IbeVno6@3$zsq84ic!5xm7N z#@lAkWiv}WhI1nvjR{5?nx7h$BZfzoItWF|_Au^Sz4OjQG5AK^0}V<_xMZLtXnG3Q zxg9|is}7sD+NK+E7*cqsn^gr(bq+ofW6L#tG&QqHSq)5YXj*!gS5R(bO+cu%!`8P~ zwpaHFIM*y%NMn#gF0CLQ28a3e8g5pQ?YGwnt3sI-h*8@0P{&X;^I{LoSElxx7Yq{1 zO-(~2n6nw3B$LTbqNSQj8S7_^A&k|*s_LPv2l}9W(JrS(RaazoEGtTuudkPH0D46s zSU`$6qiqYVg=(Wws%ktzVO$R^aq0g6AR3eVvn06bVoldkk~n&*3VH(^$&L}nkXj)# zG;z~VPRS&OLb3?iNETu4_FJXgk>0@^;hNa0l0{8fb!n*?BxE1k(cH0JLvONOOK8!J zz{((HRipSMEV@D95sH(ljirMCLFa#ijMd=&%^^#1_FsPTSck~$iCC|;E5 zhD!5T$>h|_8Y`Vd01vefx$Y+3Vl?SPn9T;N{wmWf25H3k4wCKH5leNZ^Kcf{5iu_6 zl{Lzug}`UlRInr{Qb{0Zu7+E5wQ^%At7=lFqMou^-7Q4b60916tu)F+FvSFsI|b#~ zHJ9oyLAu>EK^9hIjEYbU6P%7TKj#OfM&o;Tw1VE^x07nr29VD{aGpYxBxa|}%Di*i z{{XQ!ej{y-^}Oo$b{2semv1Dp;vkO$LqR1jjAazmRJ6G!VH9Wqk)&dXP@8}~oNN*; z&Hcn{0D=s(y`fdG%+0EUQPfE%Cnmiv+;=`{-t2aN>n8g);bM`Pp)S$thBVVi)s~_%U9Nkp8I*qBA+P!hQx77|-YP!=uVCPy&xOUzOIH~D$<6w4@ zI7G8(f~FXxyo+r{Lgl@%?<-@q--Lqr+nboDWo=WT4$wpwf$=}kqytMVe06+7+bC`2 z*exuel-gf?EY}_(EvoE?e-02RG%;F789lG0)Q&w+UT?eh4o0@CC%X5io_f|Y*2hD( zGjA+Ym$b0Yz z!H9HSNEFsOflv)-#C(U@o`LPry?S>$kE{M2yX#iG$1tOX@EMwR^P7k&R#_Oq5EkWF z`#sxvKb)*)iLXVuw-hH#fSP%&DO2)28$T!5#aoL#(1ua)GLQ{^d^mCApH7MnZ*og5 zB(xPOwMfY;N+e~|QcItr5=>#)K_K!-{{SCyHMZRtX1I*$C(q1u85V=Sb$~+>&>-O(dIIJi@pbvnw_hmf`*lF&{Ee`!sV%Aq@G3;?BF3%E`FMZYx3Ka zEl0||MUky0$ z=Oz$KS2@X2NU}jh97c^SEKDlO`dY*jYi5yq>)V?BogGT5NKwP=^CP5X6x&N{BCUNa z+n*zgs4X@!qa{;ZGWEEIj%YENyoE5Qj(x0jvdtABNoN47y}|bSTue1-RSLp@(v+{C z+xFCTLlU($RDr~KAD7s8W29d0-H+ILTFuC4Fu2;u0>s!YvxKR`?aW*>#iXX7#!x*? zMMBfj`A3pBc}XNPuow5`5*%wJ*NHq&pH^Zuvv_K?JOH2{A;+c>i7{oUs$j^}Qp;0L zW~Hx6si`ulUqJCSDne)^hJ0;ct^uj4U6x2ntCqTh@53m{%TZj8BAh=zpH(1Iy$DrP zH9m5qC7aGv*4EUS;;($8H0x87uBI|p*4EV4ndhslGL~tlZEZ0w_ttfL*@e6_qzZh! z1}Xl>Ue~FPqf&hQ{@|3Z`b1MszclBznE^k8S8l6OGRtF5rsaRHlJH3wn#uZymW=n)=f`HYi*Ze94MsN-^;x&wgeM_xn1&s{|pabL$K~vOyb@k~6xo1U`$U+|F z697PFP(@aXL$yE@Y!i-<($ZHNmkm)>MGK_O1Ir^arjou9D2|-yj&6N?pg;({{i3?v zuWfE6Tbqf(%!I~~u+}L+1u2|o?BIGKEx5F-d}AH82?T;@M*wlby>cl+E7FdK8Q8S( zx?nODG$MkUN}bVM*(xeZOm!fO&ePS&DPiHHgrTZ|W1ZkZYp41da039xA!lWO;XU?JsV%v^|MP|5TDn_xT3l?T_0THblR8Zw= zDz!aH#&<6I+gQv(ZVGtir*y7dep(ECm@UHb(99#Jr#ZQrDlC>hlC{FBMwGQlC)Q^A z68*x%caHmP-=Mv^vfZ9A(Kzj@A)_>UG`w$6qr_IJ6riE0*4fWH_SLm**882hh&)L= zDOMwIa#k}%Rk$Q1u*WCDijm5%Qf6!pjkc|mPaM^hwAL?G6=cma$LptQ0+cyf?4RDFcjXTgYxi?=yT9d$7zpl;tC{TwYOlh+ zB(Rnw${n6W6fxmhPD=Y%?`WQ7*!iD#o@<#T3adRD;aPzv!*HO=iUz4xXYmwOp=kgp zY&Q#&#BLmIHfI5ppv_|HgEb~Y9a5Dv)9C;*2SezRAMGOm>Ubjl`Zcs~dq(}XS?_xm zRbj!EfMqx!b(A(+m5$|UZ@6u@kz8%^tx`zXGBEpB(BO_B;DCB@ z@SOmtA#e2}_ckYuTwDR{#L15?mI(r%O!eG=Knu2&R#lL<*5HrL&*R;-ttw7Bw~9!w z1746B-R+OXKaHe}ex+#{tOIff)B65BrJC|M#!vbB(VPkoK8r^F?%ZxM(;ov?WwN!w zmWL09fY)Vbu_Mj)>gXY+47M^z$fuCHh_|?R-A{cv3)(wdX6C)Y+jO~F!)I=yOPLn5 z*1(Xk$66?oMo>u_Lv#`5K6cqTU2WsNl4-Xo{{XVKfjnE825RCUMwrD2GC5T=A$2gP zMI&@~7G`XAZv!?evX60AJ!EM&-F^ATLroh?JP%Ly@#E&2s5X+ON0K52m1~jj3VHYM zLCk#LVSlx3TW!UKq>?C+V3>=61`mZKp+F*P>6K!mARVr2);jZdy*s?kbGF-U@>xt> zm%~{WN!=4J8G;0lP{jilPb!`Xy^oOJ8LWOQ6OY^21k6u7RP?g6lTuHTO>s??&19mg zm8#Wo(6DLzOrkSlv5%*?OJ?P3{$sjCihFBeHPMbh%m75~{Yf3_#dWwsYRt{$#Pt=~ zZ(PT`exBR1Tcq`z3iKYD^=0eN>@Rfr`3V_;_;+-3Q^xrIR@3wu;2re$HVx+-Khw*@_!jFUqnTWG1Nvs?i z9-(cV&QU4g&C4bpmb)=S6&)5TYP_^YrgUcUwhKvOGZ4hSA>}0{O>6@YJ(t;XR2HV* z*2i>bxw?49sPzLGH7vA0gHIDm(Q(szM)9}^hUId$V&-VXaicWANWj&69O8ARfEbiz zF2EB)FjVL24L0j)ZK00cRbOL01ay>HtmZZv`q{#LjeQD0w31Dc#0dP7tc=jkh|1^~ zk76y8lr~#Sj$+&vL%75HzE~oK^`e;=3f(J4%1n@HEQ;jCQ{1j;LqojWT`uJm8ypu` z1qy(&Oq$r!NnJWgc!(_3I$czu0G^Q;+ERM|0CVph=eU+C3`_ZPyN-s5sw*ZiGz*TP zpq@!Q^mTPrvL!pm94{G!G=zcAv;C89vtD23h_@Nc8%3N7+LS4f&KX2eDKtN;BdC>t zJ-WIjvx;f9P4j);w?f-}yNz?kz2pr#LY^xtIat+IN|ic^0;Cg7!}C9TZMrEb>hsx3 zTy_$wykRo5DTu8Z6lmHqt5G_|S6M+{3xXb{H2n>QxQZm%Ba&N%Zd{PhDwv(pNkYg2 zRIpJ^D_Rgm56Zac^Ox^E%KBSR8+?M_Y>AAJyJ?Y_Fs71p7I4Egahe0=)pvI{&8_X& zISf5sYjN&r{{XvKl-u+Z)MNIFR>6d&mZDmEDUK9F7F5D(CJ8l4$txEjq$B7%<<42R z+tyJo!mAw49zdo*9mrKIH5vxetARjhDme9h^LOW6*Y|9jhW=+3aR{R!V^>JQX46ze z@hDlSUZ#viXir4%Exsu7l{qYqQ#X-(6b6dAl3YxY{{R|HG|%RZqNeh~l(mvmhK_0% zmNLGwF3w|h&58#p*~#$q*FcYam{wd4PmN2AhpIn17L!q z;XE(-cBTw&AxT-gKF#t}xGGACWT*b{*X`_glPQ*`#6c)}l%-iK z9w6Q&c{HmHEV*ZFm4KaN5lLFnH5K#&g+*zMbTiuHj9lA6JjOWMPz;0?@YI?IV7qKL_G1<3XB!Aik!#gLdzQ3dJjG~#ZRnbXaW&i>}{l8h7WT-7Q)$b%%X8pPJ{)vUIMa_plpJUq#W=Om+pi})v z^5|HSf!m6IgRQgw0O2~`N}q?HBjiaIPqg_=^oXbTWI<8W8xp1=tc_5{(maF%btDoj zb$h=3ANZcg3Xps`!Ka_gH!v1QLI8ZY*M~%FXz)jPt?}tJH2Ht3y(Tuo%aPF= zlCiW+9knoIV)jyWkkS!r{{XM;4%&?*pgQ)Hr$shD;{^ps!LQ1Oohk8HspiSmQ_1C7 zk_l=WKcSGu>@ER9%Ar(R{{Vx}wYIkJuHkf%#M9T#zvTIJX=MXF?U>Dy&&sk5an4MLi=?wXQBX_pO>I`k4#V01xds{QSDM*pvSDc2dCV zHT?eo$cJYQD~^d1aqh@vO5-QX?FZFlmSZpt>U} z*aElY*n1?~V=uVRBkI;!$@1b(G3DjaExb}m%+oVAMA9F#kET63Rb;k@lYL?-aZb$=K}@)upC-CDuvd>CIN8VRiB} zKoEKUp3fqIio~jEMI-i5^eNk6WrE&6MW%jv{imR7<_E}KxA9-Ew!dL+s{FPqACTQJ z?C3LidMWENF=ZvhSLK34)X|!ZXqqY(A8>$uG?S#CaaX;CmzVi!B(S)hr`%a-3qr0H zAT0H1*;EGwM`6}!Pls1m->;?F_Q>yT(3zu_H3S+kCs719;UJD9Ij35Be8KrKPu|_l zmft&Cx~ivcs-*@Jg0eS{D@{Nj*HxB|7}l5f>swvpW9j6bMEi^RN0lx1*ssgjO8~i- z#H5ZSVrkl?hAI?O7zc+@cQJ2UruBL*Hw|LlQC1~wB!R?=t_Wr<)j7^jK(|z6YVw~W zx^ov$X39k;XmxB<*r=tbt4L|;H*O-XY<@f|nyHdWRz{8xe2(p;a!0(D_J-Y1*sO7P z8{C`*YG$P3q$sD%3UqnONX@ohGpW+<)dSCles~n8n8zNs8~E$|!uG#c@4ff&p0jY_ zH})rKQB~)+hept4Dt4cG^~BrH?e|U-D}nwsUxK9F8y9ucWL|o@N@tm=8oW>Uu`Q^o zC);hoqJ~0IUez3^VS}!Kp*x8+sqS8p%wx$D9 zD0D1IU`S*vXj~OVYxzm?#}V0kcB`g3*Q{zfbEvoOKOKVYO1Wui>wDw1cJAM-k2>9L zvo^n3RAv(yxAzt{f})pl*VM_F$>cWuT=el$(#XQHH8bunc(H1Xsz%-*Kxj)P7sW90Zy_4LyOe@gIjFu`5p}g@p42JZhifTdj zYSPlhiJR`Dl2#QEh!HKt&7wpeBDU=@X&#!6lDH#DIV34AYx;ExrGTcnb8@)l){?^K zYpsm3k{ud_7%GCgXx<i0%Lvo#e7L6MQDO2vI(L8!T@%^s%yn0Z^*SL$Ig}SSdPw5TxtWbm(e1 z`MXWjJ*V;Ji!<3BiQG6Hy_f84CVv@%*%TOv@Vo9BJ-=N#zB3WL@KYo9xKw9kK3KcaubN*d$o}lNje|H66j*uQdK%bY78AJprZk*5Z))S zmta}$_gl!Uq`QuZ7*hFLnV!cCZ3c_D#PR|vbY+Ic{Sp_5S4pnau)HLPmP44dc;N&$;sXN=@;O#?j|8 z**v6lxeQd}>}0H~mZExiCWfwaQAbTtDUK-|D>5%PAd`?A7r2*^ZFW|3Y)vGvK#8ej z9l=y6VhZ7y3Xll^`VOb!HKsa4N!Gbq z4B^I7ZZxfSN_SfNI)4N;u~lh8@TEXj@Q+f0ex-Qh+=;Vq$93D%{jCf{vjT*IRF6_T z_;B^=PS|(xy>0Mci#CT@VWEgDq#gu{1C0Eu)%gDaDR1RZoB5aC+aqJ=K1Ofti?9Pe z;NM5D_MR?X>q)n zZYK$u+jtHC06x~AvbF%o(wcl-Cil*5+zuBLousRJT9tya=;*8KBS`$hN3_yWFJYGV zaI=mAj{}b2YNt{w>7g|YHSo?TYvt0}V4W>3E?!E-AUa2$7^x@aRsR4cdUO6?-^f;@ z=J#03+?&JYE?c3g&tflMZOm?0t|iXo_onWBw~gHtwcC1Hy~&5Br`xQRjZQ0!bEv7N zlm%dfdkJ%2H{SBx)^XcMV*dbD6D%TWnH{cbOlVaR&wx=~q>z;%jB2{I60zqtb3OMj z-`d(j_DYk)s*iBax~^nt1W>3!+@wZKuc=CFT`IsiO}l@V@A9JCUjTRB_}y}M_ig-* z>?-ZIh^Lyjcj2}VT+mT%{BA{SnXtP{AB{Nymd$44WT~vG%RN8v>S!W`QQk==32yIm z&3nu?TZMwA+pu3nyT{?mZKsk*;&|d$5^WL7~6yA*P)g7b0RcdgS5@weclVD8 zlNqXs{^uQ04mwo-dNF6Ee>LkzHQ@ew~jl6=0=XzR(YMSVDY1*r1+NM zp=g#Mt?|YU6oqkyteEO+x6asHO?3rK87wtE9tgJv=f%{=nK?|dK_XJrR$-@VXQG?K z8ns=c38qvrl`6;+?$Z0q?X(+4@38JMZXBy=vRg-YeGI=@F5$YOcymoXiBvG_QQ}-I zMv>}Y2gB0H6UlqOZELm79KuT#i~M5hCRvru4}=V4sYg&0%1Q-gbtu7uCrb^J+<462 z+feR5vc=?QA~-U1a~U?)Mppr$h6>4Do`SYTC-x>JY8ph0=RlSHxckL&-!=&V_h#VVp?;|B(y{47wK*yh0nd4J(K>7}ThUUWO{C%@k)q!7^TB?J` zJz|i>iTRaLUZ2E}$7fKUF_b$o~La z-II!zIU}p7`DBi|5xGP+RU=c8Vp!OnB$0c72m60_#ZEfiMNT@8HGsaM&#zdx)yD;t z@(&+Rdmm;xzmXn&W92Pk0g+e-L3OzUn|&+^=idHaU3#EWop_HKCrLNbtU>1FeNDcH z{p;Si^>3N$6o02fdX3u0=mo59Pt)t~XYK3R6t7?Z*W6(N(EkA9STH}?b>~PUgMX;w z^T)K+9%mgYJbKA{#2Ks@s8Rl;J6I@D{?rHK-mBe@O!ec?6&u6pJV8l>XKLLF8YJSbnF^?y%v)J${N}JGTmSnV2ZgRAt*ABQhO>Q(09_S1em+?`6l(&*YIQ^Entxim9370mj~< zDBgJiw63NwZ>StE_xs%ItGB%N@0YHKhM(@i(Wt~4QppdiV9Y@{IyhIXVfU}xNtDgW z8!gv_89&EmQfd{2MYv(`hf*41IH3qI#-))r4EaimlUWpX82w?YD`J=I>oXNj%MxW? zSiz1uT6mjEARZv2#(*2QyjzhH(IQKB{{S3NXfQ-d6#kNr@SZiv>l7{~hER~A1%k8y zV7meFu^+Gw0AOaPp#q;FPl&|tt5IiR?W2uW6`ZdEhlTs4wdus38!O9%JCg4&X&vJ$xO5IfrHe;6!FvT%1VzU6xB@tDJVdHa42F&xuWyhUPD{C z?PtB-zMd)EP)PtLhLi-W1*uxpDJOv^k6reE?jYIkpxbXPzVz3z!Zb*Tc4&wQd#Q_{ zHI-lsfl7~rj-dYlvulwut4Y^N!A$YKj>VpqU$vRmMWpkcpIJN8s3lv;sJhz4Y(X|& zLgZvD(53pRDo`H0|F zuIVPSzye?aRFXgx$tnmHu4%)iOZ~xIw(~5n_oTgOR+>QB;|)+LsIj;?uXO+b91L`; zuKD-8D|VfB(5LFXw~fZ+Dk!QdCy#vRD=TW=iR6-KD^hF}5KkUl$OTvFU)o6`RB(OT z+uPr5Eh3#wmhk3h1;552P)g9I7AkNy!A)xFaY83?ZldJE{ePWe8VUMPgNoq`n9o(|gv@SexMkt?Y zs1iUuOhlG2c`S9s`e{p5J@uExjvAC?E5tA$7DgaZs(nszN_1Ii{lPrDZFwd1 zUwUoDS&3~wx}#;*Kn&pc>UA|JNv%K_2R%;CeCFP{%K35->|7=uqFPmvY2Xe?(|pz5bYg}mHXZ}*@y$~#5mxS+>W@7{ z)eBH2uPL`sRYw~plNEp}ZWte`lkNWiw+!;M+ji(vPiXO=8as5*b{#HLw{lT2BUeejV^?Qli?UbZyc1v?bU`sTE>Hv4CIRF~amhGXLj`_#g zIGQT#c0XoqWR9vjlPyhVTE4oy%|TH5=6pzj~d-NgyDzY_Pe~*rK1QT?a@DsAL?Dlv`uu zu1kCNcEqFJ8*gcK#^0~Y<0IT#(j2x+D^0XE%`77+m)&_P2gM?8DhwqCI%=tClkMh} zOOGLS0G;ypx1QSG?-snjb+ztoZF?_b98P*Jzajqsn`Z3a6uk+Qqv_qD zRkS;I05Dquil1=rY&PbbZ|3q<*s7d9>B7_|R~eeb<|wjs(LFRU!B0~SOi{p%F0$DR zVfS3*%R4QG+J0i*9jq;5iX?Lb_)(*4jTO~YhK!S;!6j;GN&q?i%>Mv)ZcDzuhTcDL zH+%aVCNV*Bu)}NPrl3sb5~ZRg>!oW&Ra2xMiMCe@K4Udj*}k@uZOc_9L~`LN`y!H+ z_WfKFBz17oV&vI1HIl`Oie+Y^oWoG8L`3Tc+=XfE_b=NdX5RAo*lhQAv9%$QOWFm00#TwiRhe}!h@reT0f-=)7Jb9<;(}N*7+QVNlg3xkZ@$l- zOzNmP3bUHdP|)Qt^)&F(#SLB~8!pw3S|l=&58O-`KA?Ta(R=VVgd0p;q#Z3sf;C)Z zh>IX&+3_&=zF+~uy>?G*{^~ch**0+A`@hlsECnC;RZf{8je@x|gw&POjFVE;zyZ~N z#5`tJx+;o}%G{8oG(r#{B-hks6#^zwrnYJ~r!d_VnpLJjrsK##1U#R3tCWp@I9z(@N-QQ$G@_X zFr8$U0givMn6yh2i%CYB4IJ}Xm`)^T*5!iU-t_+fc!{4>XOj^B015hoU$pjd`BSYg z_g7l2UB2*hSBd`sbty^!Faf!!`%4}?I^{+1w*^5~(^2*o=UPWvjTp+A-I@xjs9u%j z{v{m@brX`Me{JIz38b}+{n38$mwlk}R9M0P02p9R4h~oL^!NOluWve>{owAhcz)`O z0QuL)%{?eS-kveP4YqYHK$g3580Qv=Nl10u?@2X;0* zTH9Z|P1=@0$+1*1{{V>%Pha5vbn55(t2T-P-*_9{29zUeg>gz8c<1fo$I6{xhv9C| zk0(!(pLyroEv-Ee?@Wcbzj&=1a?9_7)dSdJQsy5e1ql51WbRlJE+&0x45gVyiXo}n| zBp50jG+b(j9S&Q&d6 z%}`b(5F}|Dg&#sp9e4d(ytc8ky4&|BwY5fAl-(dz)g#@xwT+SSbK4bc%pFlhr>Wv%N9ADYx#=>Q1=H?+k2p zOM=VpZQZ_V7jKH{Noeb3#?nwhLr&FIbTd2+GwPBQcJYu&xjg$9CQ0Cby1m3SatB&n zttvl>S|$VvnpZ!a2o6vE#y;NMwX>hSXER0NIBKTTVoR_%s4|T@1#}QiOA=P0NIRI{ z=O6Na9YsAObkE1?*(!4oWbzeN`R>iCrL9VOIOt%;CMs#ArJ^MvR+g$Zk)>$HsJ}kd zL$~r&J9F)8%Qp{dZdPyAxDHDwz^8_(pfC;>Kx&E?Do7{RzucMa{iu>N_n6;iS9OxI zZ8pu7T{>Als76tig^GlcmA|%x10Q!E|_$+EmlugGEn#!`4t*Tqtq?J{Tpv?{kc?F4%4|b2vntRqSqS^C1f`G zwEqA^&|^O(XZwZyq?AgxA9@~Vc(nGf?yDuxz+mbZ1d&|O04u-&j;xogyB{&Q@jIO6 zvUuZ{+a0OCwgyt06(wCx5~=nrWE3ozDJDtYrJ|nUo<&t}asL3h zyq&acoZ$Skw%$*1WoBcQMZt}yYN1M#8mQAyKp|=7S5ZB1L+>T+UB9q??Qfpha_=?n z8?M(4rH#Th@(o_PZua>8R>J`09G zv9)nt?R8Z#e;PZ-aO`TzxD20tLnBaAxs$P0dDo9S4*;c$kGODsY8CANs&9$Gv?+i^odv4c#{wAVH;PUB`H-@f; zW`eSkc%)Tm=cS!Wx7A&Z@{7 z{OJU!^eZ2z7WQpJaBvbl=ssPOYgtzZ12wsHj)CI@d9 z-d3NY#H@V_^>^cee|X>TZ@yb+wYw;2Zc^HeEOCc4NsT($Ih>O9>I zLsDciG(LFfXUJu$6u;Wh&ly#}_=G@F2p|gfs0aY-A8%#6i^jgQyPj@jxFTDNwltDvB~X$^B8V=PjwPU=3mD_m zJ||@3+c{a5&t)m7=&{*MlI80wQ}`x2q8k4IEmA{+(_Bggg)@7Ni63)i76bw8RV?n4IsW__;I*% zAud)UT0=^O)Xa3(Q)+4{4>wNt!{J3G4gd;D8eEP@zCZ4A4%>emV_i9~BuO;+dZ|SA zSQ15PNNFZ2$3acG?mJ|cMt!;{#k7o2$DyeLsTvrZiHWHzpr3}WLmG5JyYJSPi4DHT z8l||BLKL%sZyi6kV?tzesOeC^u?+GMdt0n_KX>J7AjHG9av4p!8jB}US|F#Tsrx3U zSt%;_HCxCj@C`X)@qNaLCLW(tbL}hdmNxOd)I`uZ=9RV7SkATH%a_-U zqlYO$mZZl=h=(r~U)szns%A)V(@G)L6taY3qh6&JEPHo#4UNU~?wdW;mgs*;A2G5i zkGWcvD!~Y&08W!oRN&U))0i4b#@)+Tt$d9dqsHqWh9%ah#h8H+dIA}=&<$j$p)C)Y z?0hylz8VM5P|;UyjGo%acoPLv9$qQocykyzH%3<-Qw|R$kOk6Osy2po*Q`jF2ik3~ zm^Tf!+WT(XZfCXIZ%|vdq>Y5o5IjUyWF;|*#8t`@Q&Ku#5_4A9w_iaO^~JTk_L5u9 z%CSh!tfgjzPa;2r?g}2H&Sk?y6B}ZV+ssih1 zbSQ{cy`YcENh^*Z3S__gXlpN_33@S^?Bk2dmt-ALs}Al)%J82RPUUAD{m1b^b}PU zCWZ=VE2@jNR8Z5(9-^iQoH9hxkQiB7NSo4br`W#NWVe=GMk!3l%xV;_i7Ri1?ySOah%Oyaf*o9wXDDo4@-LY_(ois)nJMRkQ-Co(ookwg7NaJtI_WZht)c9a`+uM-%I*YEuLG{Q4C`w#*`tnx)4KW2K!W z)Vb_#K`1f_6VPMj%U9J_cwwTU#nVO-qDGB8wY3!{sK$|qQT1!N09=KeS1;Y)U#+w% zD^ZhxE9d^N@MoiqhnMd+d(Wh^jCg=+ZA1V7AQsL^)Ib0aI+_4TCVPvyDCjcv)FTmF zQfVi6g-X`a#}vg#4JxOGLKXi20_WVD4Dlk zI@|016N}r>r^8>84@-fZy=ThmSDs3TuAV61lc%<|E;<#OgB$k#X$1uA;JIJ`HVQ#8 z_qZjwe&=Ab1!NBd$5F*dbg0vlqyjTho}<2ZSov>rvD?{}SsKhTliR{at_G|E!iOAb zO7(r1?&EPyEj32or>99Bi%7|seOhE@K}R$c;kAodzZN&YxZQW>3*pHOdaJ-zpCR@S zKVE>4^9*sMkh~~?t5a6|sX_UEb?d{mY0f^h%YveqS3@;BiEA=XH3=xeoYKt+o@+Z? z6|$50_T-zp{WS44tYusgf@(29Xnx<%s*U0?6s&C(qjf9soK$3yN}rbu^vSii(8pAU zgBMR<0FF64#)l-5c@?ypUkkt;9>-P9)UQ6-vA=tA!$2qo51;!Uy(8PM($SsS5s(V^ zR2q&0?dU~^vgW61xmRyM&n+v&@;yF9Ol18PTg0ZyexQD<@$AhvmQNH27fzZECkLZ= z_jrV|OZ3P|8Og>mnsBd|pG;Ve(0oNyRTAT<3lmf3ideELt0l=rc@;@vAa6likL4b&?oWffe8@^Ze=O(vlwZ2PFnf?VK%LL{vhI zQO`C)oo0?*NVAPB!KH*h=?p*EdwF@1O0yUuGHIm=KbaKs^&LO`X@}}oLuV7Zf;5L9 zpF>(69-Mw-q;?~+>G7M6vnK{A1anl?$h3x&Ce-S(kd}FsgoZV4SMzbtv{pN+LvUnd zP{z2)6g&s7&Yc!RyjsDyNpukxQUHoq)@C6k^=9?#(3k(Jw0SAYduxSUf58hF&>faphW%og)KL5v+W z?$$vy;536mMnO2~u6_5Dk2;yPz~bPkCMrdwiY$dnOHW9$OtaB1+(9{#Y2Qf&LDR_s z-q~B}qmWF?3YIjcYT8B!6~H9szFkt{EffdcO7+IB};AO zE03y;)KTH9DwcVR2^uLLqaou6rEKKzgdcYsyu=497*#YB2Pe;oJ+=J$b+;&z2J zA+Km-oOYU@FFupIhjnf(#guHdMkrHM{j$XjNr{xTqmYotU3iHmmi8J*T|e#prjlu7 zkjpD7nhqasIG;{ECB3+7$2Z+7x2a%*94SgyB`s9n za`f>u9w4J27>Pq0mHLouZS8Arw=uj$V~j)qp~)x8l&_z!?CEOmw@PDC1ZxU`+({sx zA;%w;Pp3pX`I@IoYpTii|4Y1;Q4#Vsr>#P=>lW!;>rM3JRhg9Vtepa2kSs-Rc2 z?Gtm#&$GSEcCnyYi|J-Pt^fd6KM^`jD?wIXJyM=O`D$dUvJ%%naaYm(;#E)zPxLvR znM6x9q^pjiEzY6J)J7AO5r9d#BE)t*n%GUc!g+%8wSxxm;@~(67UNGk{#_j1`yjVS zBOKF5RtCRKQ}$EF$J<_)8w2@hOM&d&sk?HW^}80E8I{FmGFY9F)_J{~z2v9H$n7LM zJFtJe8K&8Ll_Er%mn?CWjYm=gM+*=f3i)r5c1~Q16o+uSoTR2ou#ExK4FRQ2k>^8J z&kFQ!vU^J&&j_}DVKa9V+YXEa!!kWF=j3t*IyqgT@NcKSLD6iCZuQ$a&Bu`I{BMqj zfA3H4R^#n@xBJswK67&R3O+wIpU&iREM=;xX^d~El#Vq}fL}yc5~vY?01F)vF~9}L z0;aqxUp|C#avOvR4*4o3qDf^A!~;`P+6m!YW`KcFlb!JwuA=ydkjdpb^BG9FiLsMn z8$XfTTc0VoDJUyUQPlqc2+rne@>xuG+%2P#qMjo%BI>$}dt!LvxPn+4T9-5=6$Fnu z&8`&TY2U}|Amk;-jp zGTWZMSk)@LshY)%Rdy;Wy0fMq++fk77E=0&Pj3u%r&MhqUo}<$5HXw|D%4Yf{Q7Ec zONM4wUDjy9BU#d{3F2rDkhS?&7|#;QgIm^?#+o$NMGdR32YT~5Y`>M8mxsuCn z3T$MuQPuddIZBD<%2Cr#JtSqKj-@WjH4+qB^9ZCdq_MGy7&QX{S}mUjz_w6w z(i%#5Y{dW_Bx`?@^xd_Et;=@L$oieJzBlemHJsi1ldHZyWGe}%s)(fqBA%Z$yYP55 z+c^0NsxFwiD#w|bMWWD(PyV$$s_{fGcRj-5`^RbLp0Om8%OM4|Ege!dAm~J(1u6f1^%DdBanpduq4ntU zA8IVEqcGd=5)w%{KnSQ61IUlJIqAZ0_)2$BXY0Jt{{S(5;-HR?2aCq(qxiSA>D_A~ zshYF+m!7Y7R)3IBO5!n0WAjHUmNOM$7!d8Y8!q2&V1gT$O=YUmEpz3B94U|Iob)K# zIauu0(b~s$WQ-PW?^ezz1pptnjZao#@C*4Y;(iMJf!UqYjrpP6ov}rv1X&RHC?-ZMFM ziD%YWFi@jNP&gh6JBcQw;CTn;Te;%5h&uQ&rjRR>n%B~#nhbCPzNW~2C4Vmcr|{RQ zFg;gEzH@!W_SD$8YImOW+t_*vJneK+J#3qnvjdK*sH9AgiL|72vs2OyS6B;N`wH_v zBW&EoxPI`P#*RgVMIKewGz76KtfI0KO&O19@~;3VFmgWI%~#OwJB`URC8&eKD6bI$ zQy_OjDr5wZJA&yZpqzt)M}@~^^0mElCU&ko-A>j1Eu4}(c1t0+>UQ>8vRq{yZcjg2 z(+qV6LQG7wuu??8&rbs`l#CKekGIx0mKU33yN%a@JRS|pjV5W;inr@b+L?>0DzXYA zMglVEqLlYMg%8oqX#2~NJZ_RmMycgipewD(DH^B|m0Bw&ZVgXQQEZw6liR~5yAwB= zhK92Vv_@wGQB5^86qM4nSatKI9!nt|Ff8j*fo1Wp7LQN1U)vp~=JRXZXWj0k-0ba^ z3ubW}cyS^~iZp2nBQJ`?ob;S&J<7xk~qnXUHT@hA3g8r+CcbdTXrTa`PmToobPU zMD~wn_KM4wB(S{N`JZ)N!r3(VvNTdN)}ZSJ0=+>cyiqM&_?Td{L$v#M`<-o8&ztVr zPfNFQ^4IEWsYGTf$rzT6T1{sbz3uiU&9_~~^I+VqtarQFqqtjjPY%ND zI~TuB*q?mo+3q&3Lg&5GM%yGrj^1mdN$h6_!}?3P9Frxxnj33|H99*c>mjgJ7P^ zFb)e8zt+W<>VL!^ZLz5p703F&XI?x-2V9*O#!^5S4lZ~k{&b)0u=idbbn8a69=#Lp z)6FF=>zQPeL~4PU5>=N)(3|~vA7AVB_FB%s%4_HQPgR`eAzYQ~ThHb-^3y53J3nmv zZ0l^)l-rAXmI9H*=($4UP15 z`{$i5rjC8aDOPLc)mLy&iFYX`NzQ6Qu_s740)URNQcoN?JJgRQ)ysJIFIqFJ9ZaK$ zQzLNV1wf?*I$OoMAlvmKwj2&4D~8r0r`wsxnxUy_Y|ldlbu~1QwN4_MM?)YIDRqlV zvX(3Ymm6W+f5oJ_xQ6HonPWOx%|^Ns4H;Iz zUfoWu({t22zNSO@>ui2pI{VPs%Sp6t5&>YXe{`4X^KO4%L(6cT@fO!~QYT z4Z3ryFj2IcRPeTM@R`4Fmsy`FyvUCD_Y&RJ$M+{Fnw04=$OCQ;0s3D50N3A|4X3oc zgNGj!d4IJ1on3b>bkycOxX}9BHYvnY#^YWi_I1+a_p96r0&QYX_b)BLC+l&zY&~3l zFMoPleVpoV8#Vs`et*!Nc<$WpluzBlr12K5{{UP60K?Wq%Wqqdag1yY$=P{Q3k%qt zJA@v8*Zh0e)9s?atOY$~AM^*8mrnlm=K{IfnTZ48wQ6z6{@aP_(7qpZUrqMc$G!2r zyIZEa%XRi{2QA%S!#AGB>>ah$omsT88#AluHy+7@d~EIGz47~_ur~%rcT|+6#_c$2 z>+7l5`P2yXNiXtODso2e%NG}0jg%8ztd|Mm8_^t*>4-EZ!YqZ!dWx#iMoz6KtTgw} z-yeRtBi+rPm3douipyfUw%VC(A7PU6TZt|&q>Am5=~h&>K>~`KiBty^K$^pKOxZEM zGm-8(S{nVkklnLA8|2;b*!`nJLAE!3(XNMiQ54c_yNCQ6j2c znp@;8r)igyd1mI~!rxGVnmK!2%A|y&c&e&RXf+xDeLT-RKJ)zf&f9O^8{PezXXmZi zY#VV{=d@!jtVuN1@r#HJlS=4{9hp&7w~7Y+JDOylCdc;RMh>2*ZJ;< ztlXI_b~2j2EzjRLxG1u+)mF=oj)!m2b`32pP_N0oEizG`xQ0fEG4~?fuY|qgh1E+M z;3-}w@~>E{ZmU~@;4(%eprvb|j3^Z(;(&j#*63f$$L1f$KCAd^@&5p;yX&^GJ5%IV z$HjIA-S0iM*gJ1=p2x-ZO+Rw>HC|>t&s$5ivWvR%Ql(rBmGsq>$x{;{Sy&DMyNYfL zb17SC*=lH2bu9oIKq_bko&)mf>sTYYhsT)0bul$&P)$!79F8DTl%S}`N8@FDn)t!r z+vlqG7fbJrm)U)ziupD1$8^w9VRjzjrp|5LRtJ95WcRjm9l@R1SXeNU#n;P{j;24q zf~KO1X%I&`Geq>;v0^h#p0t@K}9q;0g0u52msWv6bGknqqc$x;i?1^KX=BgP;)NX!J@>UmBL>7`>oN6g@l6zRsfFCP((MoXj@I6LvmT(5&_qXz zQtVi*3imQ*y0`*q(2mv!cHV5fL%Ppr5=|obw(G8B@dB%?Y6AxnRL3HbO(cv4JsHoL z-x&TO^+&&qu6>T+c$LqXDYwxV3ChOUB z8}D^xB8PF~F*w+gO1k|rnwn1qT7$jUx3)gnZ!c-JZObyW4=Y>87yy|R8I{6D#En`5 z5E+ra9_Afohulw_`JZw7*YdT7{m%Q{%ui*xMwa(CHxC;tTFWSoOK%cLqaUR6uAot6 zimNGQh#Fdw$U!a13eE{DcGYE!+T@deulW1JkO??7$NXPi<_3qjVzeD*fyir+q#-3y z&b56&{{Ud0qMxVqVedfFnd@>cp{LYS(v!_K8noKR@Ks3r_R}wY#SjS+<7y91E-;Dqt#n-6PH3_CM^T$$x z@><@jgTtOb*9PBDdh@O{_2Wq5GFe2-Gl z#sq@O%OJSa!-odssXV5yt^T(j_AycA*NT$EzXFH$j=EEzhENLMi@5zv3kxYc=_Bjz zoOAe1KjQkc3W`^|tcpgENR7*qqVHlk9B_Cb{{XFjexPa$73*XIKrBZJ{JM~gbl7R& z{{U&efY|Z*Yah?H!R?}sAIs%~A7HS06Rzilz#mqt2ul1+~#h#>QB0JXifaJ7x< zzlVqVxb?eoQh0R}K)_e45U1~bv5M_Z@9L^;$CkwJd@ptOF8!V(h^UhV2G^|3VX#zr zI-HDgEfkp-tcB7_T|QQ)(8qwpn)~zZKQP&C_uqJiy0Vv(?zdRBXzledyca19lQe_? z7r`S6LDj2>rh530{__4$++Xh@yz?!t;*k&B`%(o2>k?_YI_W}%KqLTLQK6{G>cKkm zxFOsS)L<&9adlYiU1#%q=;=V_bsD)Th3d( zk^tyJP6oG&O$3Km6>92TOQFg)hgCh@K32Xyn>&Qd?W}9;{jZrcm3v6Mng9SE ztaG6|Yaf8Z@9FGEG${k(DKbEcDTj8V@BsR-+}vgHBF; z+r7vfuYb9FYrb8m+HS6lwj}969J6XABQ@`i<$}=%baNd<(nCzE_Jf+Dwin#Ldv>2s zJc4U*dq`$e;(SJhWYDEmKxp4yy7+*Cz4A-COnC;yP*pVb`6{TWXkbS!YAR}`SSi!f zbL)~p>bC>lKy$}C+49!geY)N_@S#R>zHLv!2hWF67dG=g# z%lVT*(ko_diEtH@jmJkGN{C`$&sNme&h(VIY@K|sLx{xF>k>;0Pg5HgX;;ROMI#%P zU0kc1eBHgu=5BE3K5vAbiZlUd5@smma~w$$4Mjs~Wh8(WC6U3asW{k|d#Y~|a~Aic z-QU`osN|xgI?7wxt8qX@OPT>t>}o>Q(vkPQN8WA?)4M+V6E1dqggN>ohLatbuc?7C z?^PBhFH$iWnphT=l*&9<_(FwKQqnOS?RIxty~O;{x!*fGPvFCH=mfK>C~BDgB!G$q zuA0$Sg_8i7Zuzp}Dem{Z{7tnr<4h!tRyd@UfQwqhwP6e>qA2y%U|MJfca@74=-l$| z&%E2)T4^@6!@=nOIhC#y^|aY)dRo+(0RKM#z$)@0WM!wrK0zas6HM-vD=M{2=<@`M zC-=?icWD0raP3yQc6gpWXh_i`2@4ZDC_SXnqlgevo+IXg6Yg85@8!DMwn-YxmMyb1 zga#9ZkPz+|5Re%Hn@E_6bptfY(uIm3{{VMy9=+>HWZU_fF?gDmnztb~PjGCF!yR<> z89ElMpEZD`H1g%^C8F`i6(iI}Qds2jr8z>x2IFzc^Y8NQ`wUlH#}um@MJd!R;wQu_ z6EiGPI*lx>#;mP?_32gX>|D7Z*>@2PQn7hirL&oQLo`I0qXkTiVgMv2K}QE#MW;~& z$A9;?bjOL#;#+Cw^7#5^$8N2=hRxTx)VDdygIV zvawGLQWZ$dM7zfF+ry=9B#g5zsaUcM5R||rpX~ntk^Paq@K`OexA3^l!<*i?93iU2 z?@aS;tiJ5rH1w0>GTFS2O~oxW4K*Ao6qPdW0BH1E@lbg$s@?xLInXD zMyOB@X~aF;Um!cC9DZ{bo5toa*te#xHFVQ%EQ}aP>9F;+>0h3uMGHxk$JfbAFiPk( zMO6?}snjVAY#gfls@Mqc1h%Zf(;uY4fe9kkxNpGJ&NxzmbbDs~xIX8$+}uu!RzjuO zV(oVh%bhNc%EQH8*#HMo0CX^XK<)?mA-c0$FL_G4yJu`%CMP$$u$jEB;2U#%Vd-k8 zrQ5g)yly7H7%Q_ocP)@P3Jk4(-AzX%I${b<&PjVm?Izi4zV2I=>vGpyY;cB`Y>`V? z+{qw#l52$473H_o&j(>ubEs#4zm#@3Z#Na&`JU`2(i!wLpkKRv+83JlJH5-6FD`91m5_EpXpI~!>`6}%?ju%E z4HShX7Kta55d?nEZ1?-RZd-CgX|_0YNc=e-K<6}RJZeZ2Qj~cNWT#=&S6@IMP=76+ zoB83f>3esk{%dT#<=1ujle4OKmcZ-Gwrer9w>1(`)lIdxF45iFqiycJos(QuXqW7= z^i;AuC0+p}cW@)vy_B=qMYMOE#dR{XQJ2C-rqYR?^wCBjzB~IAgB7MJ} zsKCJOf|u{;GDf-J)f>^)IZ=DYpaNfqm+mcB$F;ffEziQVqYmOIM+4x{hbW#?Iw@8*S4SF=s2yVXr?EbG!A@eDIANCSPLIw3wE93QqVH=d2Oyl_zIKj z=s5H_^<*{k^+(An=;X%ZXzOwrauP7GCW zm5y?$r27@}?XyQ9nWXnxcF9;7KS-)~!v{{X^ir!`*- zeo*49;6d_#Ygfl+uwzrze{C{=2r9r+A-VdC{{T;LC%lN#?tHowRnpqv{k3>O{gmq( z{p8a8(X~WDukPj`{j(qQe?GPmp`e9b#Y{$_N2U~6bc>!?NK|@P`VX(?+(&N=aiX0h zxIeO-KHj2uU_>FMU1V_SLH2BE>L=F}X21^`Xj_178=F}yNBYE$eXMJ8QJY!S>NtO^ z)1^W-HDSd1f0xs&IEXAA&KV11Nis5XhMOg;Qr338iHzn)lQZ&M-+4w zgrQ=1?G!Qapf9*m^cA8rsZNc+tPv`#-_ZF$50NJd8Y_ zy3Xnw{L>qibhix|`kp<9QYI`Iii7-*`ML$k9cGqOmaR=Zhx)VAyfivw@@PjTyv!9y zxg7q}5oMHtaz8%SM{H2*97RtLKl6^AOLJP0#ESm_vGb?x>jZR7Q&91b98P3+d1jGf zjUpbVeMg;0N9h9PzZdqx!>&yOwAQ4a81o)=>8}LJ%rFRUB+yfjACU6sMA~%BX{Jdc zE#iouBHg4=WL+Sy>Ihg|AI1Hh*~G#b0bT;Q<6eaOEINrs{sL>~$Av$^(xR$@yC+H@ zi6B{Jnih(zJvu!*Q@Tjbt2i}syr{OdJ(wTVbl=~e-dW-b915_h;AlSFl6YK%~WS{&A%OGERgP9J7ts;;V)sWGwC_~MF{C#QCK>DNrPGZ&r}Y&T4?v_%yX?=S?^#fZ<$@icHv_^e89oeVq>YUyJ8(OSZdntM^SUZd0=U26onB zV=aEy-f)4D$?gt=+{NOb7m%byqo@0?;xum2$yrR({{Z&EV<9|kHBvAnQNp#RnFecK zG$8pNrlg zcH0>O>E=`e^XUW3Lm9EOA~RZ$q9Q4X=dT`^&LAA9_*j zez5DkyN29-hr6cTjz6hdEMKK+cQl(J8GwRiaKxi?rzNe1uR(_oJ`LpZYipM+Muklx{bZR zg7QMnl1!f%Q-y9iDrsFK1%Ls#fkW2Aqbj^*ghfLF!kU4`s%He&oh-36StO{YN_x2} zzuc>T5HZv%Ev1Fb^%2f#V=Wy!ulc)@NA&kc0-ezg2A}Hx054VtOLj|2@&5p0?df%h zTBoMR$R(^*dTRM*SaK1@no*}{{77lFD;-*#YC4J2#{=7Jq||tRU(csinwor2YJD+J zU$(sncvvQtAc>%>iZsS4r;Rc+!l+dzB~j9tnrcRbx2DYHnB4sby%Y>dC@KC=pRdcS zE3nZ*PEVJgl|RGM!jdeF8$y&+jI=eh(Ek9F)7R;EB@=p>Le!-ip**S|O@e`O%W<}h zhYCk;AND%(x}8j0fb{d|LZ**5N#q#pZADD4AQG&*h7mJ<=jw%wcBdt;C$8YI8gIwH z6$(W#zJH%qGz(rV2cGI>$YFKjljm?yfqph+Pm@@lzlACqSzc8~>XX)C5BAJsW5heTT zQMYGxrIT6*tut$k=~8{W8fyWXHK9B!#0pc74C0ycJvA$cg2pE`3z4INt|)7eMr%P% z6!Yo^AA0pZ+RjU~_cm`9cTQdRM`BY+o5xnb*&0~4rcZ9okHE{2N`%T)>{Cxmj-DD; zFAYE2<*sQ|(Qx%N?>7k!nRr0+lSp@X0jbPH{?_P<2a)ZW&T^C&Sbu03HM)kzN36 zsbTZgUL8p4=yO$Ft=?H2?E}CmvfF0`fv9S)yrr9OP}61WDE|P5F}Z>@mmvOlMUon$ zB9BmibwpO0<(8E)g5Q!TA8F~UnE^{xN`+YcDN<-#K6&7MDbR)4m|x>taiJNxHv2_a z3x5)hlB&1I6+?ZMQW&VEr>aJ%q^go2=^_;p8=G8v^~`$oY9t!d6*weR;+~ZI3F?-N zL$FxGdC-tJXV0MbE86{glA_;xM{G+qUgX>O{p*jb#nNrf#Y0Jrso4~8%aew)HrUF1 zH8eEy)>5o*9Yv&Sh{RgSHdW%QQ%I>595I7Ki*lq%l)M7xG`fb`QqgtG0U&e`Zp@c2?rf-lyvdS!Bo6_731Q zwOP8{B4_eZRAFf%z~kOID(q)!NF`W`%^^i>W9Ls{_x<;N*<_n-mJ=avjp-mP-lqBn670tCioxbk%f;#|{L!Z=H2|58FrBOTBaRBKhyK7Ec-}%*i z#-|01spQNOvX6pr^8cJAhAbQ zP~P)5V~23ttag2a_tnM4wYZ8AD}-5{6_hTg8k(VKxMD~h#MJaX9NE2CY!7L-yhv@J zkR!5}dMdYuzo^WoLeW%}CV*-r=dFRaRbR<0zJC|iogcjOTf?(!Fi~gfC*9lUCAM}~ zU2SbGkEGq5hnc3p$^2xr=NTg$81<<}%EN|%XAW+|YWs8#({(iv8= zAz&Lx-Ou%k)Fjt4>xm72NsUPU2M(u?0U-6GD4-;4+CMD&?t{3x*FB%yczx-x`|o<= zcJ3puY4EuG7ToLIqo3Rqm@T;2UBg6b^O-%tK~rDlsmWw6nU?axl$40H-)>Q`-)=XX zfQIUD{wf1N0;&R8mqL%|;;cz*5_k@hZQRj+dArFYMuNgcL|BxApqJCH#HOZm!RtuL z2SjnyQsJsoTL8?es^tZWTheS)f_)^Y{{Ug^SCCIq5b`6_sPdp!Pa6Qfi@neLV{j~O z`TBeHe2-i7J!EuOM!8=kWlJ00=t1<}{-!)0J^RzGgWZlDMAQgWa5ZZz3kx=r#r1s% ztQe9n^dx={*2Ht|ut}?bs=a9Xb?JcL0$jHvhwv|++Dx$fwJo1%QQ}r$EH-B^> zhVE@Y3wr#i_I&!K<17j$kkJx7NAj zN_jVpckyhE9UF%6z?55e5e!~}G>J+4pLlccuHie|>>Dg>L3t&;kc^7N3^4=hd`Vr0 z&3eS|csC}#x!5*hU4-`yb0YaNL=17MJU|U2k@H&lbZ_9^6j>UHB&fzml#4C6Bc;Mp zeZ@>wG_)A#{1mknH4qQDtH)B#=GsA0W8`svc=vO(&1(cJ^(_yBZB{t%W;JCMz%7dT ziuDLy__tEYA}A{Ik^!wW4%AwKQ>1zM(zNT0`D}(n&|@g8QhHc&RrMA5ifBtz(_`Y6 zBusu+C>}uZPdW(UVxda8RU{v3ZLK4XXS<%<{Y$EQ6broJdj+Tij{MC55s48jNu*Nbo zK}`&-7g03s%y=aM5R}7f0kWB$J0f3;zPeVRVvR3B) zNCrXx-z*-qs03a>LHYfa&qecW-FC*;0z+imm}QROks_@O8c6<@AA|VzB;4wEEy|#3 z7cy7v@f)wYosfUJJ&uF7=%A4!eab}nAhYCO(c&z zz%xOOp@eIl*6+%q^1y|g2FW(_dhvL^9l8xtJu9VaKoohq950Z`I27n7?nk&5zTEQi z?y}l_R_#2V6|KIl0!b;Uo<{(ch86FWfvu{joz4gaj{5l!n_%`*Y`XK;QJCeIKK*%6 z+ddjOYLbyApEnF*rjr#tQ>+PHBj*pX+B3r zpDwV-ee8LRb1~(=>+ZmLlUMtIVt`hi#vnC`yg-~(OlAVEM;?bwg}pJG{{V0Q034)M z#8%T(41RA9H2zn{)SM;?aGFY=|JdB z4Mu3naKf~%MhNRQ{k!)EZTAb8qTcMS8s7Rj3|Cg=wfGY%hN8U}#EMlSNL;9D5{?6- zbi2@~3ZoLlGP~*0vM4`PTPwU~-0HYL(~o5D+N+?{15$lQ+3EgXhl#32F4$TMFPJ0G zq~?1%xOn8JrTlu?Fys=C=oS_%ccwUUv*kCt0wVlGNf z;Qc9|vC=^LF-3qQpy?Nj1jNnZBI zfPR{H0##-Ju+za*21BdVUi`l&^trbJTE}CjNCm*wiT!Ajiss_0n zD%@L{4XkWA9P{r&gHslu&)ZM+d3AJ%k`YB%;C;SS=o_Q?1J{+E%Tv)NY|J~(2dkii zAw2`O7QZu&fvPI7kVpucIiij>(;)^T!9mlgdy#ifY`KqWPard_O*nOFIAL}w)Piqy^M!!dMdu*)J+Mxu@jG{RL zO6Vhz(@j*eo`(b!<|c0}t5T&^A`u-DsRXo-D>AB;HU>Q;u;%03c~PbEbsyPIvUrKS zNc%yGnW@cv0Q0XJ`E|xED2r=dWEPB}Wn>p^VeeoIai-S;^X|X`jeUE*dxTWmSZj^wyzhNjL9QG42vObyWM%8W!mHxyWZ<OAxv0R#ppBDL79$1qOuA@sl7F8{ychEM zn;2HQulc0>VA>V#lob?1X8e-u&A*e5N?NL1ogUz$+&BtKS)izbYE+hq%riYTL`f++ zlSjQz&b*AO1iS64iqL>Wf`)_w7^tbPY6u@Q(n$XAKX{9Ulv(>b%-$cs&Nhz;mBFKY z4(z3VOdhl~7(H0$OZCT8<-3pKe)aF)nSaZ_a`h*}>K>r$O{LX1Z0$xfsA;-;V#B*7 zuBwNw_cq(yX`1hx#^TIWZY-{TvT2idS4rS_@!kqzsqeY(l&>Fbj^CRghDExDLdON7 zh_f_jOJEv>QA6Zd`SfqfUw40e`9}W$emjrd{{WgVXWTX&#@5^|j;2e?m5m~}EZ`W# zY-;i;)f$~htjxt~ii>USY&LIpWVXKFz-`pe?kxR9Ywi3^J`HpDsW(PbE4Ss%&|_ny zrpu;2DukAaD$+wl&HFwx$Gkw@H#^JAo7iRDE+yNH?ok>?Xu@i$XhtPfaHIeS1w26O zz58D&^0v_?-?>+{0;Y70bDXF*?1>Q7p1*kTG)3!O0|&7}d)`bk-UI zn!@Q}c~!YL(0xH{yq};x%4h(ts-Hjb{?3GoK|ccqBEKwum*v)Fu(?o!o=H+JZE#J# zm%Z=#_T6YmeDvWI%}qYv<$IU$GwUM(#OxLRhe7>OLdV| zm^IcrEwquVRqje&`~@R{@7W+{JU=d+TvYzg^?kibjc!p(Mx>upvXZK7exk*jo;~Rp z0@)a^RbUGCsV20i`oC{k38aReuClhKmWG2JOFe#0zNNf0nEDz>%=LA3QvU$D;DRN& z`u+d}kUhI^1lLnV1-wl2yHQkeB$@&Kt{o@7y0Y4=ZucF^@;hz5);5w^WNIXFsH;04 zKs<&?zyy#wEZLuxn@1m!`#fIQs>o1@KW4u~dBICIr z@TDpCNZP-NRO6x3WADwe*m$XO+j;6K<)M};e9j9c91&(PRTHB$KXi~uEESX$YK`{w zP_c?)tiG34MG5ZvMdr^J0-GM8tDP?%xjp59Mq?%cKU0D@reLx!mK^llfwwqagr%)XIeU$1^ue-SX zyuZ)T(Uz@1IFIMnWFUY?j5eU7&~;w+w05=EpL^1@95@>P0F(B0?%EP-r>vD8Ri&%b zpaByri!l6pu0X%1@<-F!JB&pkXUdP+{-M*>fE$}tAk?rtdNlh#6G6HE0GdC`JVdbw zZ?$^|BS4nC%LzaG1Ve%`%ued$YZ%GjfyEFQO~DFUmHH=`1!l& zj(;7OpJU`}qlz$L_SpU5#-RSNa2Sw>^B9mzBg;Bo+r^f zLG&5nBo>cQu9|^Vat@aYXjf9VI5gdDS1=9I+G7%*)KOGoq<1R42v#E^mGUB;Tvtxw z>FO4PWzpv1s@j{^Z_T{69_mD-$FAkV?rdN29j{g^CX%UXTXU{0=%s?LNS++MFodGX zAXc0&Icf=>4ZKc}^48;Q^Vpuz;`pe}h4hwKCT|InM3t)z)GZc*(k`h>mo})Qbmf@u z6}D^JcDc2fXipVqi&S0ax;$?S!D!_wMal%yuHjB5%wcIG-Fq)^$Bf%JdNYtruJGKH zG_z$k{Z8GFk8Ed33K+B8mz8ijF*tby*-?zpj@vg2B9&2Bwks4U- zMNyth##rH&CE|=uolB?+U29n$Mt0lzXlW@v;+}dcX=#H?MzUn;VuGPQ(a+q}RZ?YS zfr5gs8nynS=E?iPEw<6BD6gz8LTU!3V=`3KP&T-U$siR9F;URVk~be3=ETh!!*dyL z45%elnSjz$;${*uRd7Hg@fjisyEA!CAxg)8jr0D4DFzA9gs;R2`2D2wN5}KMi zxRDgC9CUNHDt&I8U!P)6b3Mr1IhNMeE0!xM1!M=jYew*iz@-?~*Z8P#YhIl9C!43- zcRM>9jY$+tWN<3MOe~Z}BZj9sfjoRNrAeO?VW{&{y&h4pFftD7V^@|43#y~ z=5qL-x~-(EtH~l%!AG`nwDD3r8U%FpGd!9LvVw`WM&&+IvfAXkU#Obr#&`@OIUKwy zC01t|irT8j0fZ2#BfPpp$ZF>>E!DQm3vQPoZ!V>XX`>g`@s`ka_aeZEs>wjBBN7yn zDu;U9mf((0u#fF6}V|>p{tuE8)G`JW>(KtFy48%YpP_Qu=DUph@%m=vS6+{I*m&uTC|br zP=uXXTmIs;wQZ8r&%bUlJ3_KIWKlWNHx@?iX$uC9#b%;N->4E)R%8_Iv!>0oT5c;q z@^;u;lE>=g5;nWJK?6)y^5PX@OG~Mc#ym2>#Xc8!M7ysopUvd=4u5wx0Oyvvx~f*K zuESQPZZi@w^$S$h)Hr&%k)eh+f;dW#)O`Rix^n|;D}BnlE%UzTbv?Ssti|5qSj##I z*FHN$UPeYIvCa)aUbkpB`)IeBt}iB<_V`>5FqxYAtY#7_d^RSp8zoItG?Gv}<{4yUhHTN4L6L#1D(17Qq4tMp-*-#x z&ep&|1+~n^I2c5XtkWX+2%&3LGbKD_J*CBHxg8eD_ZQPeZ30DYxyaE&`bg2SWKx=l zCW`JzNmm{tcK{DT{{U3b;r8cXVJr6zPJCuFU~fEGt)kA%)rm_@LH9Iy3QBr`9D-bK z60Qb|?Wz^#jwjH(A@?ux-r;L+yzTq0<#=JU+po$#h z{9i-4+KbD8rpo>g5IL@q8<8r5L)#NCayCFEMggIA{%2VHR!ibPT4pxcqM^;n@~fbB z4J~w4AHX3SW=t<=?h3pXM>FS*sc{*YXc69$Mrf)kVu~=1?uuovyF7939^GAEnZw<| zW-Z)>s9y%zh(2U90uG!~mB6hhY2itEQ+&DG^hYu$f(n2DiS@RU$11H}8~`Nepm+I5 z)<}21dru6L29IFjW`stFv$HOJ&xsU!PHrE`*DCyKJf(5_nLL)k@N!=9S_*PJH^@6RkQ^AJd&bvbNt!R$w+Z7Fyb# z%7>;m=VImeUfz>0y)v=yJ|Y4^e~MB%h(w;(VQNf)%P!;nuPvHqU!EWoa%6zRdTFjiS(;=um^#dL1IIPPt&lIpLN*nQ7c zTRw7pCsXG(hB}iUM>S=0;d2|-pD< zD8fQNEd+4$`+T|-a@-KX9mrLqwm4@>X(PLc$u$+B{JO8s!qPXMZ$wE>tkjMnjhW+& z$w^MkBQ9CA7A1hWus+O`P!V1P{{V-fG?b{P3J>sgxaa&PHlHIW#9x;3%i?S_ek0d~sxG;HMyK|351+*qf1N*J_3Ive-HTTL z0JpIsg2(g3r-#V-`cQSTWO4Xh_?eo@LXfNh=k(s*qMz2^k8tG(B&ewM;4A6WMNZ-r z5vdljDLapn|o5Otr3bvp&zoor>D@yk+PcWradZsPs^rE zF?6bDLF5R`0Z9~~ZB~$24KA(#{M+m8t9GLm2Nj?^NBX{fBaKXQ8W4NGpP2hPT^&=> zOr)*kiO>l}#~0EGUTnXMem$BEZEot%+*J8=cCT0_4x)sA#eQ7|RM0)dWp&-;H&zL6 zSEX5nn@9?52eNq8cF+sdfGE#&8&T#DOjVEJVt19 zUp|D^2$sWEoS!g#I&h+BDh!fJsEH&kOqDWDuo^2cpUX)DMs-Z2A5yx1jn~^y5hQHP zFhwiC(~l1-bZ6o$pvYE>LIEb4Pa1*h51-}Ky1H)$H^z`sY7vM_!BbAq$SI=n$x^b* z1FP!P8bG#nCdI!#?J%M)2MqaOV!!9=l0~A~*Gkt&6{zwVZXdRvpHMN8qt6n;h-ZSj zDz=&Cj78yz%&QY1Rc4b}Vp*<8{{R7hb%En%LcbC@srB<8v(MM6+N#kJ4P*=rYl;lh z{I&DxXBIk1nyQu%kiA54)kI4)=|+*X(nA1YW=dMX+6h0Y39z-juRsbqf#`ofA@(0J z(XzuM8A3fA(x1`vr^xyIk3`SEvXsMkY)z*&S7=aWcXC$Y@tZ$()6yo)N;koW;A!*2-m$$v|v}21#i}BZ#7&(~N`1ps!_a{Fd9Tq1`)6G4_;{ReOV= zv6=4Ri@`P=xIvNrUVlEZ^=&3_3{?e4k7DnfmEn%2u9>1|hEe967sfhIwy)A3Z( z#6gf4el_!<$5X1XHLXjQtwl0NnEn?WY3JrTL1VWz*z5ks>b|4u&im?rjeTL-)qf?c zD=_`=l2&gog*(5i4#-?T$Nu2OZ;bvsV{GdF>Fh1jT?WR7FD(`qCxw9JFsCc`RMAvc zMuDR*#E`BBrGdt+~=&Gkm+>T1je3u1N_(CiE@UWYG+-)ofIo2rt0_7k+A6&qTE z85TB@o{K3_MLj#$%4Vd6HM_$s!ZMPA=vhIhV2p(!xY3_hp;KB$)bkY>N&t&6fL@wmjF zAkrFoOhk3lgh)h4#zsEBNd=Z{4WLg;iRx%7e^bnlih}~Rpa69B(=yJg7_x|BAXfsb znhzoBI9KP;(V4{N{{VvRs5U-33nhHJ$s)?sWGE>FX^9RRva3XN_o-hC2+WOk)-P>0 z_UbCTpmw5DC*(iRnsrj`qEVo0^80E2qtNw}pxLzBwq)8E$|{@;(NrxB8Kj0uVDZu+ zteeL?A{uyFv7APQLN5h=mK3gJrFywiiy5Gy89zU>kEcpn98@UL(?^b?iZh6sC9Zl( zHDa-yax+GeYC{|9RTsVP*SEiXC*@D_`hS07Ub{=`7!*fKT=JusGL`S4JI+{6Dwz_36(aMU9SwH&I20izncgj+$9z zF;KlyO)!i@NidE_k}79rO>riaU_!Q%54|6Ts(%-s_=dQg5u zbymO0yX8M&Embh^4%3{uN199mC}V)RgXz#0LEoyBxx+63xYsB zYj@EV+_tb2;KbTIh-OaD5D*3&C~6XPl4x^IuDv3PGVL5u#?lhbQ58$EW^!Dp1&McK z&*YQ&_Hof&N#c6uKwv`v!2Ll0gZ{WYd-o0AqzNNS#;BoK9zFc~;HkMZOJy&GOx_4($bv;EkTXI)Rkm+5CPrEa5?rg8| zyq;?jNEUpCXDb;@u0tW2pB%zz<&#{JPwOlho7;C!YioORZ!Bj?WqJyM{6#?@DtU_a z9&^I|T()tg@ri^|lAy4vD{8NA9IFaezFxg+GyLgyW=?;YeK*yKJ!EwIf8y@>-dG$K zUTG>*4MW%+#Y+a@%hJ@;$x=l5%$CrFH5Yocj+94ri9-7Y-b$OE>$%_CmRlHB7*rYp zq^rpNqkw9L)x_WvigXgVv^V=FFK=)V+gn3>2xs_&#(13ey<8B04MT|S;nhX`(HpC3 zQVlO0+m~&`!$tMSE@p}*2#gBr^%KwdA9S*aNp)^lAFm(n)Vb&_xhp2kx)S7-x0gRH z2P4zducf}t$WqV=Fm)9aK3DNg1yobSWUHt&kS$CVVG&SPQ^tv;>SHWcBlMqV`#scT z-CDMlm`v;k@djc~+Cj(JN?>(7Y%<1{cJ`&0SVW+fk)JB`O@Eq{d-HRA z8SieF>I@q0-skxjw4~@hwA#0(SFEhn zvF1?gH-s^?(|BzXEaEqI0=1m8N!3Cys8k2D1=I?GU6Y1HZ%5=hcZnmtM8LfSo`n=KlbTk)(d3bM^WUdh+Vosrx$P zsZN#zuu#KEAKE+-$l%}J>BrZt4_&V2JsVpP<4HqPk1&a}TAFum=ZRDt-;r^=iqd;9U_Y+UJwZjOijJd?4nLM*$%Xr-p2 zf|{m@=;K@;~|uKuXAr<1lr7y0AF|^h7^5x^J$kU88313NwnxQ1fWLqX; z$79+hmNa>4W^lR)NkW@#z+1E}mE@CzNanQrJlSbLv`gN6Ey@?O> z46pWa{@0+Np!)v+U$3yH;z#dI#4xGx0r^iwj?s$7CcxKghql2}$;KQ|Td^2dJYk>Nn8rt8uJ*7;+`lVq5zXX)~(2 ze@G!ZhvW!qd4PR7$IraJ&ve!trOgo`ZMxEThJ4~bAHy)YAHwY!jJE*o7$>}Rb@~JO zo9zyq-#cS|Z@!y7i?=o}TGVZMI(nlegMF{sHQ7$F&+HjCUi*_Lipt?;>pYcaVmYg0 zdK!lq%5zSz8m5j|@@2WxZfg{HqH}-YgfW`v14vh^4l$Lj7L_&9a4XjvB>TDZY@F96 zZ>`gpe|a^~zgMKeexvFEShFJCgW64WYOI0jfKmP`Y<%4o%*j{I`1*=myqMUiX&)g^ zHBR7z5e-c}PEwMJM`|EAFj}CMYO$qy9(O%t z*oq~Z2yyh4DdDDa-l#B$@e>wjDU0&US5;eH#3d~{s{Q>}r$|*`K`~fdPO)9yK*?-- zLeQy_oN{og24s-%r2y1H842bU&_>wsyWVKlhBdA*VlDWmTum@Q> z*!W{hvu*vmH7ZAw$t^&td8MnP$JVf(vX-iA8Fv=onNNixY6>8PmDwi@a(IZbbr~9Fq&Zqsk;c1JK`T{Jhg4Zi zaLFW;(h^04nhPlmIOp1_ZJq^%re4_>Qsf%1<-q*CIzeH&TJBQcCf_-CwwJ?`w62)| ztpOlv1JqWAqohar9P3Pe@Tu(@99ANuvvLyE(`75EzlzQFu+L2mvzXcHr+f^xd3f34 zoYO}QOb(1(5hAfYz2=T$yx1){a_g98muHEwZa@?Zlm{~87&=20U-fJ15wi>1pLf#K z)2AeV#dOlhLV)zGXlec*pH8*ZboBaV$In||N#mq1QuxUzOjQ#mvrbk?XGPNBqPLtK^;_EAvvj=L zHw$gkZM~A$aD>)3N>mz9f(=!bfujZlFf=2gE_CHhlb-oz`;)n|mF)L^Tih4Jy0)Fl zppW8N5s--%RCQK~;&gOy95?{h2G!X+XRokS+f!!YBEsO}sG77>$K;+`spmSU$yZm^ z87nL5C(;8M9h$>W7&ujIsQZdAG84RHaDxeFsAk;zxlkD^4c_@XyYkeR2X>2$n@>NJMBXr$PcqRg4fy zmMVDq4t>~~sA4-n>tcyiNhr)o{QXa_m)q7jgH%sZ0#Maj6-kz-?bOq>Z>%&cIBzRS z5L>>L3KrUry_6mrl>o7>JiziN{2eDVJTuZ~DuG9NG*ZVJMtI{j^%UxKXjNd8N|G7G zjDtjSgh0&~?pTtN2L{MR?dtk_@j|*a8aeXx`+v>V(4^}tAgoG2uMJ1#>OD{8)=vVq zvZc8mnC+>+2FJ+uQD*0!Z|#OQGpY1+XmrXQfTC=hL&X!G@4`$8U>YD3xElF zb_m*DWpo@EaHr-0#|(~>SeLni8I7El@-QW$lA6@ijOi>hO+tj=js~Nw@lg3>NTQQd zG>;QVsAP^OKne29fulfg!9SmBpxZC*);|IwQM0Iu0rIK;09T(#Z@2xIYH8m7^-@Ua zGz_^X(MCxePs+U|dtV8c%yjPm0K(w0bI-VP)9kgOfJqe*mkW&D6uCXto@u5^Nfx6U zNQA7d`;(e8H`!qy5!LK{n*5NW`bBv(I|P#3;?^gPMQM`-1{#*mBE zd!!(zi*AEhrEtJX5rP_5P60IP_J5P^3*aPw1Tix2z2or5Xz!e6e>}f2Fh4G%>BzS> zYFT%!T2$mSF?NkMLR#*YuIlONV8P2tRZEJikk&*R3h3%e+N6Q57AW9YRHDLRU?ZA2 zd`6y>m&B_*Q$g!o+*s;H`IquWUyLHWd}Nb+_QQ1ib-%_z{{TbpzGiN&@JG2)JTB>hsVeI}N$d(8w;eIg ze;@gyw&?0%q))oYQrG-~>gvhjsx-8}d630B1w;hOVRFF&o;}Wgc`J9l_5t?hiJsm0 z;>{ya8jMY)%G4nEo}#*d28543zB+#UHva%y?ndbi$gES`1}Mg~kSYWxi6u1GzgKC&68$G3nK;e!0_%hqxv_xnZMhii&7 z3jx<8aH?rjCy3b|Be4OTmSRE*^_Sq6U~Wyv@y~p0ii&JrYZuVH!-vUva#bkTC)c&)q{yCjmRsUd}2JYdF4cuHMK zBd0m&TW$RBvv2mckwmw)?JbbFK{PNO9hV3jOj5c$pvNNz2+_wRps+?MJ(*REP2eZS z=IZxdImlE&Rl1~8iT?EG<%rbon)(>37$fSw>bABs^B*xL!MMqN zZ9229+^8XIxn)rI6PVbO7?N`-T|_ZKQ%cjI&nQo~$-KyIH(7TC7cR10AJbc_q7T){ z7OD`U;7F*(fQ9X-p(!1swf1aXjk+=!m&iUFdG`VBTIS19)yDgdf{Ey8=x|bF{PG_* zKDTbg&uW8nCt00l3g~}Ph+2&dYe2?FT~(+65l)PD$o7l=aKFB~ zS>C}VH!LO$4a70H0xczva=Wue5sNyx)7dU*1`nG0WoF=PfMCv5_?H9(OosnPXU#Yb;3zK?vud zhK9as*%KkRrA#h1rg~JwQB)#O)XytdCNh!g>0~cWM@5i%8dSaEOKLaz`)g-0?6#Y9 zJ6w$(+LCyQ;(%r)djrTbO+!(}F{pVSg8NLuX~pi@NG)1bF$Pf^5*$XQmn#}b#I}1^ ziS_DLZrsZ5&cVoG(VnXu+?Sa+ch%BBGzZ2uc=v9o+pk; zsnSmvEJ!81sxG;gf98R0zgowAX|_u-x0+2YacONJ5ka?>!%G`Cj+W{}$P0+UEl!6& zy6?9g>-T&&QGF)cYVio4vs`f&%jAMVnR;BDkv29lR`9({^%OJenvN|?8q`Roy>~v(`EE^@e&;Sx_R?r# zwA?RRcb4K(Be|5f_HnC~*7C+Rct{;%20%#hD#m8nY)!`5wCym13th~r(l#W~DH;Z& zRwOlACBPCets6a7XJFNB{-f_6)52$RJKk}$a2wI~p6{i4e8yfq&5n+hCr$B=tdH$- z`(JZX)>Ki}$~09{R7o7L9coAoS?wDaCiDLQygakLJ^Z&DOj8Rh$k_O>T_YnW)uyEr zMRXk7+*B8gIcUgwH$_{gD(rlp&3Dtmb$$$1cMOv>o;1d93%TwCttEzF(nl*0tgPzj zLoIr(Zr$(5+jLfB;-SUjXl0U;vGAoDS|+8$(TZ9rWO%}w(=|Poc901rlaek;_HOsL z+|MlcH`bBGYjlZN;_X6JJR~6T)u0Nw%bxbh>Kfd4pC0n+;?@}A1TKie>K&b{UK;yA z)lpV8Jp#Whdm%HQ8oJvdl-=13rY@i6&rj2hig2599k*94S6FuBGu)2(J<#ip-dW+Vh+0@T;3<7K&* z`oFxr-sI-l83RNkj6~$csFpO=8At&|bcH7erEl_vr%Yz|?Rl$RkNfhml+!AyVoK*A z^#(WchO>UV6Zq!-@*CTkRjxUN3X}Bk543Az{vLrl5-M*~nF%CXe}&S&;PdqL>gW4c z9+wEHOm+qw&OEHHUXsi=iT~0VCWzqpUbuN_xw48Zl^F+2k zNw?m`Cf^a#Ba|eC4HdMlRI(seQlPj1X+#O% z;5x{@M~ObQ;Kcc`CZ~z7NiMB#Al;d_KNd^k=pIQJvoKGAL1JkV)Pz)|VyskZW+zB5 z=J8UGwYvfr2mQ%+=VDIk1L<@d^DR71rLMxn-oyqYpX=!9lKEeqRinr3JQZ)p zJYMzPEkQ|Hm%?Oo+rN8BwP-OKrHdvLaK0+CDwyDJ6p=;@z=T2XMQJsW0<2~r3evx( z_5FYo`E+Gr1I8r4(MC1%;(!m&&*ff;XK+z2Ke9JPEOjx~!39MWP*z2xB}5||NMdpj zvLw0)4uG8w3f$Y;gdnM}ss8{EMlt{h1BE)=d;Sv+uHOrOT4{PHo#Ryn)JCl$a!CMKpL+V+7g8Sn zF8a{wUNkfZIL}o{E!?WfaI|WUAcAR%XV0t{d}S>rK55%0kB(YOopls)*Fh6~w4x*T zbg{`OdGyO5SrjQKJy*BCLwB~Vv0=Jf>js2tP)G!PBDHUwH~~|RuWb#nwedydLO{l; zsY6p4QCgE;APjNoN|VtvM){0XW5&in*(yCYck#z|GV$vmarFH0?N9G5x5FUrw&8Ts zGAI>1Jp8}G(#YhuFuKWm3b_K6bslu59yRGPB-mcH!uxJPsrLvxJs=O%S`q$!s<#&7Q+-T&Ks7ql04qxIryO;c zAD6^Y&hpe|@NvZyfcYCKM|DemSTvvlKeci=_T(Fu+L8+HQE|Z5Dr@EkrF}ZQ7Z$O~ z7~MoE<*jOdU{^HrJt^Ycn{eDV;@k1lO&PO)7@*SaCENh*Hw2DH;E!v@>$T{0JDex| zxF6~@=;{mmEo2+Gl?nbe`$^;Jp0d+!-L+2zZ98r(A}r#2ALDRDq1qRSGl70gL&H)Ibv(*fi1^Z3XeXX8?M60MdE?0X@g85FQy+J28t6cWbM5md z*;Jy_u120ZLlCBhIco%xND^t~5qgwzc+v^>`)^xBh4pR`D+O*O3<`OlGwHWMOwAE{nqsgB92KyMG~takgUJABYQ`G9NW(@jk0u;U93ghHI9;2G!({{A&Cqt z#Et-UB>PKtmpktC_IEJNZ6%-&-Q5`y0;Cl=SD^$Ptw~aF0Z?oX%Wiv<=Hu^tRG(d)$4jOQ64wo{{YP@#-nUb$oVg`DWnV6+xlN6Mq0KidJ4x% zq#t)Xs9B?vK_P*wpcz&_=*V$Z;2M;t9vKtYbJP!rFu=fS3Rbkk45ME zmaC-6cDb<#74`0GpdDWz%E# zB|byCJ3D;sne(tx^&|^Q>9Y3ZxXc`faY<=1u_RMPN>?2I6q2Y6g(H-o2nI;SR)$tT z=#PbuxB{k1htt}vm0AgzVuD1IO&s<#fl0(GrnF!5SEFD9+o%^Vn=vZ#Ujui2EmCZ} zYvg;swamPlGiKZ(gzVyuLPdvOt6a^*=N z$`>^pZR7%&1X8uB9DKUf;V1XYGU+BW`FF1qo;(NiNa0?MH(r{9+dn3nN$BI2FP2-y zCyIrcsMGCsPhL>8=4pX(Sv;{fn0+olL!^5_ZlNu-@ukhj+J95i{Z-@Bmp%6}lmu4V z8vURVkCEui;%XsWj2QYFi6E{O74j@(d8DI-*I8o=zKIe^^)OrNZf#&a+=~2$pWD?% zagsr91MJOw`c>m-BoQT7mbPi$N}8H^r6`^g81b5Tqgw}wlUr$#3Dno(!`(m%J64#l z+tZ2zaWw-2{akt!D0NJbPHD)QF?8|GNKri25|?SAoy$ceOZ~Cw{Mg%%ZXEC!JyJTT zAZcEQ>rrYK>Jz%v4n6b*w_tNC!9ids75qyj?_!ihkPtx$@~G z=dnno2|wT%{{TN#H~frtMki!+C&?^kGMq%1-~8NB`H@I(s%#NMgpG6aqUVpLdVhETT_FS=NC_a;q?RPt z0Qz846zax1&$lw0OEW{WuoB6Rs5^3}cJ3V9a79y7Ns2X+;&AxPTr$NxLaQ&4r>HYj zI0l*ue?TuNcu9G;c)zkX_M3d-CS@+~Kw6ceq6P&RBn6glOZc zoV`T`LzAVonAz+~GV$y)w{M%poUu&z@=tAo=_MMY&r1=hSPYEmC*lW)k@ucQ<-4e6 zgXl%P`VNT@P^)=rQAKt21Zt&dz~`g&j;^Q5W9V{Jh0QKPlA5-h$fX>?RSHiQv^=Be zadG%Q<#=UFh+>{ISe*k8EHJ3S$ieF!E^Xwrxwy5Oo-9tv)X1um4G);8=!fon7HUdu zme{Ow(_koi`brt8sOf5|=qWN4*^JZ_G(+vG5UUC&c7#8snO9I33Ic;4iF-VfxbTLK zBvzz%e;_p;fV|c9B3-?$tiyn^g4%Tfs)0d2KH>)sC#_SzoJ^aVpXOIsS4p*MsH*b+ z02woM`+o~rK~mD=wrv-2XDK4j(o@eZMO`izG}J9s2x$oQnMk|bgDzm0Z(G!l7)azu zO#vALT7p90U=038xDW%ooRmMDPvIVC86h`t!r%tv~>N+Lg_Q~L8+^%cjqPb!VNu_b8PNE9wt5k4rBU4U} z?)Ur3uaMmnNl36(Egn-~%K-B$MARv}a#g=|6;vwmNgvt7(;;0-;Xnj}J(O%p!*iOo zuL>SN*|lmuU*YQ9y(7Gld9Ued2lz|YwH~8AS){JSuzgO-SSizD6`0yhMDhjr{{RnS zUtdn7+ztahVHa=OV7L7s*aF;rT!Jn?Bm8~uhI;oJgV%A`4J^l1l-zPt@IYj`k#2qa zjXKyB2Q}+6Bq(&qSO7gXQ+ALr(s&-NOa8<9`_QjmB$19CfB)0mSO-J^K9X1+B|@(Y zb|i2tNA>oQk_pF4F`l_8EXi_Ixn;W>evl58KaefK_p?fZM+)^{%c&tp8V&S=jAWQd=oJg zwEbt;d4Cc!v};jUyfGBO^XW2(AhrJh0DZ*DlIGFyKr!7#a5Z-&;!pRw!YHTeAmvsYCON(*HKTmkM?nRG}&GIgax6@gIYfNi= z4zX*S?GjFPpSGv>d>=2zEIUcP zexCH3WOA#*v8jn1)DJR!f6LHrOB88t0>BQOAJ3*(yCdxAahecC z0Du@VSJhy*)VH`c_GmUIntNbsA__*4=Tazt$zQFC>wp*KEaW-NsKw3C~7aUuUujlLT6Ti;mx_0O4Bp>m!*V(Tv zs}5S_rYAqUt+D?AHdFi^0{;LZdn$*nFt|DE{@tm!0%qu^rl^cPHDoYFP35MjhEVX& z3oPS;2_KGm_ATU%hF$LF=`A&Quo&8-1!_$QBY`yP9QX6weY4wbi*BEMF`c_`6UCvx zbdgaIy1F(9?-dj^9Sz?Xdc&wYZ>F}U=$~j}<)_Hi?iIdgB+nKI6}I&wH)s zCg0rJa`UVv2!xHII>R4{r3ounlT(7)ii1H;9UJ;yk;PI&kE6s@OGS;tB}(A&se!^( zoGmqYM4lMx<)>QNpxaSvAQd(&$ms*y)2Uk+3`ui^aqH@tP7uv0e zVVXxzodpOV%k$`4{{RMWz6c>->vix6Ql!kRbMr9jC*;JBmrN1##@CuzCs=6Vh>0VD zmJCQ(pnxMPub23ax!xosd0x-`qDu?=YyEGzZOaq4KnVVZboy4g`%Zc^U%vOe@j@XR z#mI4;LUESkS{O(G@zOhgEOmu?A8EYo?NvCX@kEPH_OVH(Z6o)isWodVYHnCQwZG5- z?xWkTRj7a6krU)Qs42toRQj6W@Zr+c`}F(RBPw^Pwd$^|QC5UxW)2>NWN{rjCq?Yp zC4p!DBTxs9%Ob2lw+Sj?jbNQw1c3UAk@Vw(?_cYC%Rn7lbVWvVomoDkySMBZG|x%D z;N|zWF*Cuu$c*(B1}$H=z{&I{BQ)!TpB{FFQ$hCC`D$2Vk;Pia923Pk*K~xm^A@KH zfUVZ#@qT&tNj5r0VLrNqe{)-u(Ndp4{?`hNo--Pm{<8&jG2^ z*8c#1FMVym5pNOretMy|VtlAr#jEBhdTyuqw}OTvJ(~zOw1VDiwp62J-g*)*8c#zSGjTn$T8(k<4o~BeI`GC&wQGS`>M6Fl2uGL#D_c? zm_iwV92A;YHR@y^7BKQF(+<<@T536D^G^&I9gHKMR448H=(zs?wlh$xI>i1m)@J;h z`(S%*%5n)KO}Umfp&(5yDm?N}`n@_chwuCEn$Hcz%+?nZM!G?3OJyM&1Okx)0iZ3K zlA@=l>K}<)Dr}7eZ`ys4fu)isrJEqw9f_HzXL$#LwziUNMLWY!Px@pq$hTip0zvlM z`)|r7BI~phPxy4The|%vYU-xUqrlC!o3*}6e0Jo8+4P1RX#=jEwtg_82_J?Q) zrQs=t-s`nA;bTbEA(gT1E5sxQPu$h2`wEMzFTh-g<}t8m|GGA25287sP#}UZzLv{?S1&VH!b!>$Q%Fln)GsIdOA+ z&{J|l+V{2n(S5As>XkcmwKXP}65#p@)}Jr%(;YfLyhq=F$VcvWDgY(6_zguf!Ip)+ ze7coQ@b_yv#PvP1+4W#KGse4XuV`MX7XY<9KWjoHr;bKGrc%X_74-dm-Mz8p9b!SY zN~WGy5+Ab!d1v!ICSUIf_uZ|`8n%iWWY|JT0MrsoWS$3wID=l4^xqJ=<_IHz?!MTm zF^EFctwzbC6QXlEJQ3h(BY|4hj@Hr-H}=bWUCI)srm>sF{{Wirg}?yfgx87bQ-64m zzA9ZHgJwwSK&HuCN%ddVA87>8`BSOu@ei$hT2AckK`X{jlkc{GjJ~Ujq3$&fg)MY7U*7)SG;&iSRO6+6nDqG? zcjBs=dEvuHSxXgFh0GF1GUn&U$CA|I}D9UGQH>jvke6vCiq4VmKe|V3+ z6Tvh;yS6oylcB|<>W#k)iVWo#rbQiDTD{6?*9pEI>=-Ghd~WmKISCowT3lXrFsqD~ zR+yE7zNZmSOObjQAvzHvky*-yk(Ui@-Bm^UJAN593GD)|Q-IA^ov<xd+2>8d()z}JOxn$~@RV{4$og0n zY88^I+3jFzryzq$4}FEz9eLb%lOF2$+wj7lchh3##?$Yvt?3=X@$Y!$ggREUQo)qKDFPq?H2#n4nSWI>xI%a5qi5 z<>auw+##}e)L{CixQTE@5pF}ZPZGvL+-SgbN~!(~ZEmKk+E7(wC}Z0lrP(+=tGO!n zl)q=#*zAVslAj-p%I$b_#%-&)zkT;^82!arj{Xl-p2cna-F`C{oUOva zSCU*Mep-%_IVvcUqNQl(cZf?MO=lUm&AjY;?&-2TrPAKv);TFp79f94Ok=%iT{sO< z<=1ODE19F`UP};mk%dN@{68=7b%JoqO;mL1A{S*1C)Ysq>K7W7 zzrg!$by`Tr^Xc1i8sgZ4KpYMnEB?<{Y1i8Jcgjwa-5AQMig|I{SNWMfCcdt5C3SUG zKgu4Qqn-ty9~_TMSh(DT#Jr0TFfEk&`JTS@vt8N!+V*+2)Ms?(YbMl;L0HD$bfws> z39AsTN}S|VhsKxRn)>cOf86&=c~%|L9p#--11N9NRFEqQm0d4fk}^k?0Gsk(e75%6 zIqIFIySBY1A2mr!4mvsbg2wu{e#{OcfK}Rn(*(eCdYe zc6d(6{xth5xSzrHQzE4 z7}-f@4NxbFBxSe-3&%oOB}wzA6$Po)u>6tB(9c)blsOtnPJWvONsrG^(^t@D;L77E zup3})Xu8WkhIj?dS$}w?sE$!olt~iD0Je{Anj)mev6g$F zP%6B!Xm@Q)Lj2a?$~H*W?s{4_qN~Q^@zT)Zd^oBMEj1)kMT@{k1sykqCdW}JT8h+J z160UKc|QRYb#wd1JImu2)U+v9QmGm;s8xwV0J6{;mfHls?>nl!JAIM-Pm_b>n~eV38R?;PIE%WrIjCQ~Q3v5&LyhZB!# zPZk3m9I|4n^PU;%DTYwRGd)d07ZozGlTaf_G{2NzeID_+T*D>oFeEWO03tZG6^tkV zF*=y*AiGr5lhI!-ZrjHDd$jHx%ezN4#1WfFglZG~UMjq1O(c&KxtdlQyhb{UaRFmp z6d5V$=`&fJeln7VpyXhr()EEMKA??$5IC*BsY_7^2_18QeRu4Vp${7?#&od1284i zv{NJi!~#e`Rc6~Cx?ZxXI*~07=E&wEs*z%eMnVj%=k8;w{m7~3jzBajl9w7mwU4;l zm#?GS`NrFHnnh6?tf!F@ac_GXsVg-B3;u|$mee?wI0~Yl zEc8o0N$#ky+b4NuWWfIb63b^~nQ}Q?vgB!NF!_u`A_0qfx_il0LTVGoEgeneD|RZ) zWS5=m-$W*tQmX@%}2tgEp-dCD6H$vBM zN{`0_+=pYgqep2JQJp2!DD(p#v()t)+epId)SO7n7NBuIKSBNui&t@XEkdx-(G^S^QNcIH-(}v+=syUVv^B+r# zD=qoBAJdcWS@zU`Ig7(Ja|9p|cy~Yfzs=Hpj!iq%sJuRq*ZuA?EAk)V>vxWm+S?~- zbl$_+TMKD68*Mhg$L1*Td5Tu2N{KfeAjxGvy_Ey_psL(Cyq-#GjI5HHxo4@GSzO4> zOJ!BE#+J6JZUDAaP=nEFQTd)E)Rtmcl1V2t_Umg)ZMx3Z&Mh{AA*D@EX&;E1l1*yF zl30>SB-gD~z8ZBmaP?38C>QywVx{c8t=Jo9a&_-ec8`A4Y|WFK>wS&0yMwfMF4f(= z1=a^|=4$g8{Py$P9XnfBS1xvfrdP?*R@Btgl&osXc*DD-A_(Mv7_*DLQR@L)yccjO zTBv3sx#6EKqwaEvquq8mmPnpf@gy|T8YmQ^DmDRNXJusKbeAImfYqP*zGS8QeDxUx zT3+VthtwRfX}`W1N1O=&0#=E^8o#x0M;^i)qLrS|gHkP5Byp$&^bq#xOYVF5(??lm z^yA{aYwMqt4^#&%)0PJ3@Koxz1bs*PRmfY<8L7(2?Fxhvv}ku zi}7*q)S*9TPAah^aL-3);w=W+Zie}To6LWD*ENi)`1Ot3uZ5$6eZ361jPGI3S3c;e zsgTD^%PuaRX+p%(IyCH$8z9wc{E(?_Gye zo6qKISO7d!PSfeUYJ!5CM#?WLYqy^ATQ1E4vL{AiR zyky&_FYUX$ab90pK{1L!81WD|0zkx?k&MSoaWowVw_ab`H=DR6+_v~9kz#E+;|^2? z2BN$;)cRASEAh|f=T%bTr^bA{>YtN)mp!s}CuHTZRXs8CdwF2;za@JYBb3AAy34M2 z9d=@^u%93Cn@*c8U6ROdd|ftTO3Exebg|;5sg(W6c;xO`TF5zm$)1Z((gPu@uA;e6 zJ^-|HK_M$q(^mYI$;q!*FIy{-Qp*ya2C4*jQB#LCp;BtBa7esABmP5Us?3|ux%;XN zOc;uJD*RiYGZMB!DtT)1G}ReAeny6cr=*Ag?nE%$J0hqcd(!fkE-idLlFwagPlB1R z6G9jOPnJzFQ`2LUxnumAj+`)6qH$aC8t zZPjd3l+WdHSjvs}L4wF_Jj!kl;{Ft-$>O&KHC*cQr7V>5nHAYy-qxon>|$XM*lj+b zIbB95z*YxI1ZkiP=4pY_h2ZPs6r7(f& zt0#&lVDi4h6n6~<(`1Siv11&62q1A~$zzIAtVmjQvC5pftlk#EXdJTfg&T(fLI?m? zkEcxCN!ec^_h)Wwy_s9teVMhWcm6`77qzkz{{R-=)cCyhMi!>41O4g5<8t(QIPq-g zBCUADvr)vxp`e%{Qt0JxWN=@__pUP&h~1SNR<5USZw!S!b~htQxTM<@Svu9pR@2E_j>~7_ z^6HKyMWuMd0NRwh4#T#$gj&uAkdOgrl9eZb0ew94UaU3^jyLgJXSHc5$H9-w&*A*K z68=SXpMLb#!f7)-quo1`wy>G3{Qb2-o~Mgp?7T07DTT%Dp1$eOGnHGXc2&Zx&p~hoRf}*l-F2l5jMuTg%&l~6xZ38GI4N)d?LB^a4kJ(Sjc?xgchj215d#$*SAh9+`<>|?-mj?JTLTr_o&Ny2JNI%>?JeEAvNgMXwx>;OF0S4* z8CiBtA7ag)&(FSlpSU-akyFh1m4gqqHuVfuH03f?kM}f+7hu`U$!xYT>k@>K%xUow zno%jJ>B|`%=x~8h)b&T$wsr)aveYxEpb(&@PNL^XI66YA@yTKU0PL62pAK;U01Y?K zcx+6D>~6u|i`n&fOvd*VN^*RZy7LuBxpfQ{$zG zn@1J3x=NOjs-sB6ohqe>B~)Mor9i+wWSS0^?OSXXnyzEEg>IxpQc*(DC<#v50t@Gd z5Gjt0e$}hnJHKmXdY8C%?%v=1U)VcpvlG91{{Sf`+$@wb%c7TeZTk446?omvwq<0R znzQNhpbcR^2%tHo^h>>YV9#rDA^!a{%wK7!gjAvG?AN7BS%gFSW#L@Rg$LtQF zuIsn!ZTCmkn;X0OTeADxw>F|~e(d>C(mk%bBOkPPFK*Cb>2S0=+q-&S1F_|bf}?U} zD{$H9^0Td6baK4aF68ow?IyNDATmXu=}`JfWhK*58d`vW2`U+j5Xu4_4IV2Oi^Od~ zfT>k1D~7>3Nv1%qC@Wb>>!V9VY1R4#Vut z+|)R1YW9ZT-Geu`Htyr;TB_Wx=fvf9X{=DmAZ!dP|-y3#~o-j zNWrzp)dj?8f+bJ^tFse82TnAFk z`?F{5&4XP>@<-#%WYQg zoPDFGrw!s-hBY5e2mEx?{a&@{`?x!IFVy{~&|7nF;Oe)=bG$d!;OY;Log;*#qNd%Q z^SbdJdyeeB+wAK8#NBi4{kPM7XYu<1kI7TiR8E_Ur#)J)9CWa-r}BAJJ>9%W&-%$G zk)%;pA{nJ-)xe6P$4z9ixEdBhzS5%3dzmExB6KEzmel2yBMLH0Q^aQ_V~rMt%eo^h z;Orjce*UMx<@Qd(>Tiq59>&;sp84%<^m3cuu{+PU^3h=S2Ef>TFSGFROSZ8!o0_3; z{{Y0dCT5y>Yho=81h7<6v!L5|8x6^q!MjygeF&sBw>lbJa0B#_-kG3AsRsdV=HGj1 z8lzh?OsLX53h6~s6w#|!9mq+bp*lb`B#C_u*_och$aiDpD!iEOkKG&VtoHOXt|#uX zn9Y?JpH+^64+h@rOoL9WX-cbpUzZ+$ zt>LtOVb=ES*}kXjzN*A!{;qJ`-thH)dd%Nj9~;%X+cN`NXtG3U>;BJ4E>Bl?sA$(wt3tTfV7V z#6nbsj1J#~P@FHwe}=tSPigg1Z)(a6_B_D3iad1qYPc#Sc%sQ-WuNZgi_EJ2Dx7s; zcZ%R7i!_MjU0HX&Y-zhJQX_@BkA-Wcf%0l(5yeQZY6#6#>y-Ji`G3Z?nG0FFhZLnz z=|VvB3@8|J8bMst5MyinXP%oaES0miI~z31RWm?fX^SiBSm{zZ3e&&(o)|~B=Rfm-B>5!UDKRj<+?rC%26lu$zeK5bqj)Nwp9#2m;V zikb*%pg|lo@kb0OFJy`&2^x#@WmN;*gov@CMvFvH03Lu~4xvdTd1QHHYP%9i^(54u ziOy#mj?Lk4G;~s|l=%&(Lrn%jq^YKYm{;a9jTTZ`gCj(+P`05cA)cQ}1RLoKONiyV zQy+0HM zN>c!d)YnhDu+YU7L~cD)((AJb?Anjl-E0T=&9yQ_s&m4C)v!KY0e51nu9{s#-s-#*)RlE_kKJ2mcww<~w=eE=F}9u|Or8)KFj_;wmaN4w~P$7`E-Q<(l26o>ei&3j9*DVxPjOfSDwA zAyPDBmeQ=nQHESc$X=Jjtz_9cOcpDx@RT`8qcruIDr`b$Xkf@xLl%@-D$Opr0{Q?X zem#dax<2cDFl;=I!x^JSSbvA-PJ1(L}08^y>Kd-&@@7a#I z6J&cR1&!`3ZS~X%1l#(5kG*}pZ_gZh@sXK_>eI+wLibT&Z}mI@?$iRf&s!PC4!{4@ z+-pEXBePr;2+GIOq#HH9p_;^4`%h1nI#x%|9b&923_+GQn7~qUp!$`6!sJ|woMhS@(`^eb^{0JL_#}wO`ww6X zp6kurqTouRzc8E!?WyRaoU8umvMKb;DnHYXKewu@>ZG&ZK5pfi$xFYtAZ{KT#Obe#aJwVXKr0BtAv zIs|h$y1C8?qEO@@tTie;=P>D=R2avMffmB>B{zKg)+jg<=yp zi4KxYes$x}WtYyoNl;QnXZ3~gGYGZmw2dFvPz!!<&#^6~lCOdoV->HKanOfsfJUk) zGzwO{c;lpV38%g_Li3lP>=UrU>dFa&Xb zc-3~Xjmva-l(Kz9pbFDE&QIC=`uhI>*`D>ePn3m>h?4&AwJgjF4J#C3fCJ5k1Len} z3H-ugTG|epriP#yqO0Fo3d%zZKxwFQIaA&QdE~NU+(hf7-KYK7G}uda`fj??I2D_`B1& z3R+(j`HEfHUzeIjlfzwE7ie!xZ9M86XiYR&_~0O23q}2IJYn@WxjVOL_h)J2u$|f57)o4sXK$CsW2rZ;a*iB4RT-?3 zB@Gh6T9GC;o`#@D1R+FmMWiZ=1MEp@XKO9I1+3830X?IQDu2#?eFkoB?uEqP<1I~R zfi(QR1u@V@K1_UzrdZOSf z%cSP!ZY?{0-aR{G{$PBu#MBqYe3R}vR#$q3DZFxS0V+XqvdZdxJX+Sby0wj?&^5A9 z{D=Cu^|O0+MGWjkeDn5k>Dq6bzb@pEG+!jUZY3)b5gp3%0pTIlSN7FRX*e#bMU{yl zT#{;b+X8cI9)3goom}oWzIRVrdDHygv(vACv#;{~w{C{*5v696F)gFK7qUxAOl0HF|je z0B6VMBgkr7L4S_9#rI!Q)kSeF*@NQ%)ZGFfGNey@5PX5HKVDwy@_e_wdR zHwK?#{{Wk(3NN4k05gZ*M?cCA!Hs93mOmuayMD1As+-k8Pa@5Ond63{#a>m=e-23F z--gw<8dB9kgw?LpGs{GTf{`88NxcM3v?^>#v3bb=3YhvsQ z*`U&+$1G-DvmDV&<6uJ{)GU2pUwRu3*h3L+KnA}Pe}s~MF1&Xewi-->KhXgH04}EF zf0}2{AuT%7e21$@X(JB{}(rtOp65xAH>z+ z_Vu&5UDW=dtv`f$eZS=6)a-ZjV)^GrkVbo_7hGY1ye*XLot<4g=2q14)X2CPUTwO%2WMS>E18r7xVgvz{}Zt7Ec6{ zl#+g@*^;z`+x`SY{4hl}pQ@HpNA>sN%k~6m5fC_hNBvpqpS*5>buv^FQ;+5Le1}RJ z59ba1!gCe$v=qIO*78+W&cYa`>Rp*f5s{%|rK&!{HCWUOuBHkY4|RTD+o??q26z+p z{{X6=;Oggex-6}!Yw{TVmHz+_T%rDQ{{TM{N^uup^^?RUDf|6Zwr81M0<6nYKHi== z6_8rsC?KDq=ii4fZDG7ciH@EXC++;`eQS($Z{ByBN*@lj??STY-p;PMKe12K4`MTHd zE0I7nX$G{X6Z6jxmkylhKb?2;16#~DM@5&3LL_yaM~itRCMg$EQ>{TyPOG$r)*yZb zz0~r~+)l65)$(sn82A}0**cWT4UE$x5F+CWQT;<>*ngIr{CdQ0|iM&>yhR9e%^<(Ny`5vqcwU zZ=B39ieCott*e*Ff)$b-$0b9$#{U5B@g8ae$R_?qH@)wTeEqfwHtRjr7xmzoqGRS` za&(IM>2Z(r$FHFuyZ1ALrb7$r#u{ZuE{rn;#Q*;T%noX1ZgQzoyfDJXd4 zfPdb-wQxwcmP5pY{JQnB53II8O$&}4TYpZk_mk#^A7e#PQwrjC$ItYlNh+sGnzXC$ zE|<*7MfU`wI{5zk?`;t7eEGe=-`Y0i5g-}{GQn{n2~1Dk=odEr42sANWL`JxlgiM;$g^?M7&^;5|vFmsauG zSSYHooiRQ)KeTam_1J3qO}$^Yar!on$iu-)ftzq;Q9O)7-ykU~XNHEKgR$gc|d zaq2GKoi1ST@9zp(gW;@_03?-8YEcCcvsH@#p;X~iP<4Z9VFVk$15f-~O}&oWaOTZc zMm2d800lt$zZ$jFl1U|PEj%GAYay#i0;iQ_F4G4Ir`a{e^>Hw@OOEIPQ5)a2`ivfIVM2bDPErb#|HFs z(pRlcGC0w6(N#m_tEZ@$)=F%9*KpA#Ohe4^#L+X{hAP2FwOd?f^L+zxmXWlG3pGFp zGIj8-DP9Epx)MiiwzLfe*lTqI`!*G5*pO8j{Hi;dS4k%XgHDy3LZ)Ymiis$j4M&#j zZKGHG4vH#B+YtsSvMwpGk67|fv@(g^?#lBj+yy^hV(av|lWo3@#kxT}g6s&?0s3hy zYvCyPQ%jH#W`?H&p^qtDNFcXQ2*YV}yV@~|Fn~s}yoQh#B!z00H3h{ODD&w*D$~`& zUlY@cwQQ|@J2S$?qpgCrdp15Rhe=~%L6Sl0MzI#;LHx^nu}g6baVkz?L}V-6Ayvbn z941rRvW(nVL?DR1L(t#`iDeM<`QP>I^S_+=7M_Y@NbM)dRaW5ZH`G_9GOa$^CZ($OC5F6 zYe;2?u~H_FOG>s--jUH+U6iH7UGc#2rptS0$x@!~aBxx4PNVhjO_bzOT zs@5{gUl5Qf=zS0PdInl}OM7VS=7r9hjBx0rW*w?`S58FHLm>YEN%(1mQ`DMuV^2MM zfU~Md%Q|VgEv+Mfgn)1FAh|VCoY=0!58ZPL(zL1r`w5`=aq3{$QC{DBN|F98At(K% ze_=nft%5(4V?=k~b<0tCBO5aWs3Y{4OJ{8yq;YGTsP$_4`yTsX0{;M5ijRsYKjY0_ zmh4(TeciDH*1!yT9}zNox|}b`?Zxr)5!)0UUnhF*njMWU-OqMj$>^Sf-d`lLyC$=I zQ}}UNX!h>j+WUf^0aqp}g|c;+=xU*KrHt0gM*dRrO#35mZ*O+nFlj7emrIRN=?+zO zEJjuUvMENAIJIaj8IUubQ*S6YHCe#$?SYMpcPw%SWd-N~kBN<1nt-at#52;Y>_qQ{ z-Kp`<Ocb@R>IWaqOi!C2-;c{5ryPw%x>jAW> zF*G#TI_eB;7_3AT(a}@KOQ5%|QgxeCp;Cp753AIcsHkmhD^N(q1puJjk?yIz#QU?! zKIN(*ERUyDfdE+k5U8l2QZ$WLCGOCpQxo&<{%;j8_cZa{yqON-?aGr7zM#W&*GL7J zY9cW$zpozCa&m(*X&sAc86RP$51*Ii(r;~8o1SEtu6%btk(K`d;)hgUGRVBVPstkZ ztOl?E52vU7hv(de3B@{<1e%33ob}2X9fXY6Te=0*4+^O#0FWD6qSsgI1G+*`XKcC)gLBW9T22GRv+76}DtJ#~P5t3lIEL~`#SScGITBmrGX=6=ue z`Cx@E)r>KcN(|&uMO0FC{_W+!h_f&6h5Hs{ry9g-`SLe51P^WtYof{$&Qnl$BYxf< zXB~USwi@em7%RrEqMp8fSn73Fz>6b^tcp#)Ta`?n-QCD4E4H?7SmE(wswA$bS$~Dp z>YklIG8K)b0lhqX(6GE>Q7q-vq@RJS#Bmhh4<4-?u(<(ei08@I{QVzJ(Zp3}f0=&t z%xAxiWGaUG_$>&NaBZCC6_N~JP4o^M7m3NZqRCOghF^9HR8Ce+SLLm|fPe$B{DQ4LLQIpBElurYXE<~d|USYOtj(Y1~D&`ly)O{BuK zVuqC0AD#tR917;RtvXX1MAssLGlVOdnsfJu!4<%EaV8aQsHX!H>$-#hC2) z>m~5wW~ZXaV)6S6GhVbaxTGcvWAmwzbOu@8I=q#sFYw77|jVJU=#amPOmYJu11#^)asxsH_-b@Z)kkzC?-s4C-G#~m=viVgXPwppa6q1@Tkc9 zXli|H`#Ko^0GhVh+W!E>zD89w9$?U)v7?aUXex5^Jn&cTS_n;YM@Xp!W=Z^Fe-bQy zX(W*@0{f+!&d(gC+^I7H1q}c)eVO_Baq7-sQlX|*I&)Ghfn18>zC+fZXG%}z$+9-o zTTA2|(9&cfl7^nDo{o7R%c&`XZQ zMu5y1W#zKVn?DoVzI#c7fc z#q&N?>uV%W1)%X)P>F%asP1A99u)IGmsWrBI89sff4pBER}>J%+B=GpTG-%>WGS){ z;_x)h4nG|vJ}Q`~q-IH{m^J1M5FIAPOOVwV4C0=&b|30JUL|81Pzn`Le$GF)he+MD z!kbHd#7mH@plIZ;couUtWe_UTPW0+tN#ueiKR}2@{o4ajRie_gAK=edH0@GOplSZk z+4AXsL}~Q@01)xhnNtfCMsm?!p<|KV>6%ERAV`Yj#9xDce!km!fXB$5tSUS3m9X^?0iLJuDFa8y?W^`+2AP%}b* z)%NuH*fdqty-k;{r>j~im*j86Z51`1IWh7GyCNy(GowaYM3+=eG-YMepfquSOA0F1 zZK8nF>w(7_gnACPKeF5iAMqKh{`5HXqU#ouA=zIj<$+P6kLD+FQPr1#(nD8YK|!(7 zrVL<5XJ|a^TlX$moE{VcXcdHR38?ys{@VDg4S#3t>HCKz?aKT{(hpt~-`+iGRhroJ zRXEMVMI}yFlD%uHWQrJMshQ27l*1vIf>lA%yhf&Kv0_bhk@yBHpCCG6)!au0vx)%5 zhJb1`(m_*}_?Q|F+Gnmbe;GDD6XhSqE%k%Sb`EA|>+R29kJ%lE+TEMlokO)dXRkBx z?QOU63ZJYuChANs;_mpd9gAN<7UszP{Y5%Q1Jl#e$qAX<+vS4TUO{1J6~F1mz{Z*n z>Ufbdf-6PP7!mk`5Y<`$?d`?vi3q&hCz%5}(bzTsS2~yg#;g{iw5S9M=b@Y9cGkw> zaUGes@YJ!=;P>Bec1G^O;$>+h%TVK_&c(ENh!xdYgQ;Z zjmb!pc#zw=v1KX<`707tc$(=1RjZRc}#d5lAQ^O@3V_6_szHNhFj9(#GP}_hF=C=jGLP7BvF^bg>cCx0Rs~R4ZgL(8Q9- z6iXk7i`1$Z+8HILL952$e2vDT_4izgVx4G!0TijHL8oJUjpJ3|~yRUu}KNWrItUur|Ts)Amg zg!y@pCR95as>kFST8d|ZD^_Y{ zs70nv9E}`?pf0s$jpHd`!9WN4dv+NXHVn=JQzY;h_44TysLZSs5(NPH*QzT1LVJp$ zi)DPg>h0Yc;5!Fve4gIirSmzpA`jdTxpqoPzy$(L@ZU% zphwH`w06_$BuLJTRPkL<$He)PLC>f@oh{$0_tQwHR6ZkxUSheC9R1pU2e!zf*5CJF09PutcUzWUkN941$CWw$OOj|YRSsK;e; zMzSes=<;;43Td$~_U2c7zupl}w1^s_N|snv46G2>#*4!;i2;mPBRK|y3RII&Mv4wbElC=?$EAo(DVzL9YsDhebmhh}_jXQ)EqBjm%>nezC+;WHz*v=7TRmoy*bX z>M5~R^vn``J$q2|Fm)5dDSNDP-`bK=SGbZQYT6pDg1Az^gZw-(kC`0=xrRIc0Ijp| z0~>W&R*9#%iD0xoM2v% zMycFuTQQP+#FY6ssxh)xPJFtkL?GyjKVci#-8YTh#K*vI2rWqMq+*~CAXpY2x#7SC zce!^UHc4Iu@kNV*SGh`=>J3RGogN;l@Ft^;O?mY0JW28=q$#PZG(rBEI?^YRQDT-# zciuRd+@_(XH+<4(wPel2rI$Egj#&CFxZ~1vNP>r>Tz9Zc@!GOmz+wC23mchOB|d z`So5q^W;By{BrHBnUDFG)f)qEY(Cq{&~^6G`5V%^uXOHhk&fK;CbF*wvilPszG*3U zZrn<*wUVV7Q|yBoB!Q|-H3B8~do9|;*HPX0@{)B>FnudRszGMrbyG=X9lDtr)p{x4 z_UWK4x*rkaRnq3A^hPsQuW&%cnW!|1mf}M6HsyZyv*eFj(X4(N%xzZ2S<-j0dTKhI z#Zy-CG8q9+9-xPTBY#W#PqK>N+!d%zM~@NuTso$}%<^dqLK->|z>3t+`Qy*bbzx@f zJfWY`EC36@)YmLeh}7H-Lg!m?$hrRjZSUSy>tLQ8 za8+QE3xmNd39+~!23uHLpY{Fkt^6eV^~w+eC~^>7>HHQP>f-+ZQh%qvAD31Y6~=o1 z)!b==vIBEwX0YI@0ec_tKjMF{wArpP(#inT$6WvkE2jSdP~pE(1BD!LR^Ly4#!sJG zp#rCmUBwB6$>RS2G}mR)PN3%6%a%T}ew=%4fhM(}r}#S2HRH#rU;+SE3VxS2(%ky2 zKc)V+_f{Dd#}2CB4+{13>Hh$QGFM;cPhKXgi28#h6dUl*y2yS>unfo#{1(U9D@#dx zybUK83s0S675@My^XRvnR~r(j&(ghrHy_}q`TDA!uCGJ!>Y|!vkV8J{+*NbLG^$oK zDM=huGE7yP1Zj~SwEb0i_W|>?C;f1tk}x%WEGb_#9mKF6w5T6%Smn%?i*wDFQUX?V zwtxZ-Y2Ha6Jdx3S-BmePh}E=Zp>iOnmcUa<;TmKx7PHA3o(=f+EZUaPIJZ;YqquP* zyaDN}7;T`KK;ysSKDqw@FG2l9T!NNMxO$BNV`WehF{p`All@p6f(?lFc?<|{A}oYQ zQ&HRd5C zMxWv6MX-wR7J4w^?izW}_^VIZj;OuzB-*Vrd25_wOQ+PrqVQ~v-|6QTwD!K*3KUY?^BP&P_9cfD+siovRB=%-!3 z6cSFUe-NvZ7SOL|aD;)RU)<^JL{kIJGnmM?Cfz|i3l9{KJ!lB27zERgTxI~N>>V=@9nl}{_;sXH+#zS6qN}FKafR2vRT7KtE2jQZaBBGMUX3P1w|V|kK{Tb zx<9WvkAqq0zpzmtvFGZ4H@LA=dyn@20N2@|ML~n-{;%_Nil+nR(8bpsRfgXiYkY4l z%h{V}t9Hi3$!%OcZcjae-Fud7hC_KKZLyJ1P;Dvm#Lk#=Zr-p=msZUl`yA20)_T#U@#R)%kyti{Sy5Tm zKy>Iu=OQxD(?tY}T4?41Cfjo~ zJ9^%KSvKix3^u<|T>hj5H6&#gWExECBdT~Nj^%-bNVOuzc=~fU?>jjy(I7IH_@dIf zHLkEfv{K+`BCp0hV!d^_`qK~m3pqZ??e4wor|YUZYK_|#GK)2|CyNzVQIDXPA+xHt zRW>*MB4BYj{DV?WEj)2ngQjSpmYP8-DzM(K=a$M1+m~)EzM!y(mRUe6t-{aY>JYO= zp~XujNk(;b(plEfw%(@PxxJ_2X!6@89JI2}g2V1YWpsl*lfn2hFGyB8iWn+mj&xZ` zRXW-?I5(BLxU)iR7G{nqe+=OO4W7VP(zmOd|nGVi^s3tv*58?t8q`a_Vr$7c7bW;pD48L zTCvkKzB*E&$ac~ik9f6~4gTRGV{Ny|ENp7OsL;k9P?^9|d^)u%!MulFj`k^@^dcP= z?ogajm?&lopTbU)T6Y8G#7W=%71cWyqkds!`Bktt2Kv}_StaJRnjB)#_rL=MIvii z8YP#+JXWd~P_9M|3M_Yx%J|v3Y%(pR+DUUPR8(P5+CyqMr)U+=$n}pq@#`hG>bC}V zt9)&|pHyNt7C(G#?%&2zKN;_#Au19#)gFEAx#e8zGCT2>2|8B~hzk z1R_Uz&zj=DdkZDnE)#!}Ix6Onc9Xq7}1{ zZU$nF5g;-u$)%m+7U$^?#Yg2BV#^&6( zeaW7Vt_;5C!)<(i7MhD`P}k)rtCK02jH`IGENcAy0Wszs-t%UcX0_WkNiXkjXL!{X zNa6}3iRNh?@cj<-k6eBw*N-?B6l%5W~(%0!F zX>=kNM=nh%r$IF&*SC%d;hwSJx=Xq9`=fDe>^D|!+@|Z=bwZPH;7kXf*ZEGPp5E5U~7fL9ApJF3{5C-c#f4+{{S324yzB<-r2TdQv5ch2AI+Wo;k-`yKqD~8K%>b$%=XK+cgb86X~ z-qXxOi+7H$jl7iHty~o324^mJ`}-S9xpz)mnk%^NUT~=_QlkjMc#-(aMM+e>D8owu zRA%dPZgayFuW`4!vcU3+GP0cttjJhUD-Bc??P?km&|x=U@7XrKOM64J@^kF$Hcugo zs@)XPAfuh}l`Th-$WqctGG%JYm3A3aVi|=91Q2>sZ>__mZ732pkwfHLDy(=0K0uncm1;Uw?9Pqf+qSE&ps2#u z?TxG18{2AZ+8yzbq!pN~U-!c|NrlH}^0Cxcp|wbNsvuCkYs zBns?fyGa~@Ol)s$FU+yR^tp{9X%q2B;-<7#rZs8K3C3^;=}oodS0H$JkRmfF;=08^ zZ=cJLttvWCNMSM-jV&9?3y8z&3+dG1OKH{|sr*~$J+D~6rFj1UtNfiTsKM%N6yQ}X zl*Q!|NYSh@1`^8zsx=}gB(iHZupdr6&?zgy#X(M!%PeE=Wr2L;MC9PO;GA}MKTyjBn@}^TwHsIZPbq(vg%ZZMkCgW za4Y6duTl=p8%ewDF{=e;y|!HNt4x3#dU406K}XM=mLnm8rNfEluH2h$hjB-qbf!p( z)K&Ja4p$4M^aEKHE)t>jFcyVelgU2eE_$9Bc^kouAF7Js1E03zP$SHM4G*FDb=!Zt zcHezx?v1_lpeEIOWX1tfejUF{k3}WaV!hNIQ~gK^P00w_ip%vBKP|KZ)5#E z!Ic25T8MGhcrmGJFL0$mKhLI`<{xENY^!R zsYqlbFN>iVsAB8!UFQ`=a|qu~-y;LW825(I2TN|wPjQ&wf@;rx}Q zsNPsCV>8v`%=HgT1~;&=a7O3BFN^P?ge|<*jJFd0`JcK%_g!z8CKWh-oQ0ohB{D-A0pD9y%tHH4oG0XEQ@K?#XF%qCNf_X zX}p3uu<}M{H3C?ar;_#e9$S^>9jAC(Q8n$%uJEL)(XI2x1QF`Ei3ky`qbkus8p9IB zqp2od;K^nak#DZ-OG$VUmPQgrmn#ZHvPL6JMwYsVib)0hP|+rk^-ty{YPoBtk2W)6 zOq!-&D@-5<7Vji2O-D>+ik_ZPP}Jdz(8Kve*A1>NqVxqInj-3`z)X_dGLg;z=`G!0!K>yIQY9-eSbNBf?` zRbsNQ9Yr-P^D{jerJ9Pk7rV>mT8d>!Vv%MKd0D_WR33oF*W$wRm$yGr^$69x+b^yr-R+v)lvY}RXmOgeYR013 z3&YIjoft6iks_6(n9C{CBLH=>kkye%B#N+N&p_-cQ__>Fak)&EDb;4zZVo|79%QpPl_q{mAns{q$9SlGsl$~}r~c4_&8TpLz{HKmo++oaBk zNG*VQjC!cDNf zrW#2=Tn>}!)wFq9s)mcmYHG5TH3-s6P|(pmZA(W}IV@aM%&X~QZt5?}lkO$vqAjk& z?+`E2%Nnw}gW^QeS4fa?qv5?NLMz-l5+I)1?WIN4t5Xn3YDQSm*q$tWj}kM}R&~eQ zy>dmYQxhB)X_wrv!ZFbq?WHg(~-o4yj`=kDhjO45sbx_mZ6E2 z85>W94*=c1pOfz(c|k-m^K&u7ZF2x=>lhq5nKmQgT5r^P2eOq$D^O4hQ`a=={{a60 zl;&OQcMr&UXewQ5qS?4WkwGjl&m*QzxvAo&nn^RSC@{mx6ZyM1Zo zl2H^taW>{EdVJk{VBzZOO(h0NY6DW_CP^wFl+YK^EkrO+NhEJ5Pa3-EzOFrwiWSgL z1H=9+kNNtOB57H5AA}lL*UKMgNEnsGWJubSxUko*$HwON{9liI9~L;!^tLc{psyZ| zU&U2N=--s_OIeYnhJD5H&YnoAXzOZdr;)OKn=L7>lrrI z{^jl9WQTwHw$(nrv*Zs)7WL9W_-UU`Do67b{JJ;$Dj706ay))oSsJdh0x^qM0j44r zs-ZNGsA_u0RI4r=t1ee^X|TjHT%os z?`!s_PgL%FMk8zQJl{}mYMd)(Hm=ibj8tj6DKYn5!M7-?C!VG_-U*EpO!6R59gg0T zCW%Mso+754F;VOOezprKR$qvHoPR!zmMiC1&)9`IgXZVSn)KBnEWL|P%1p|?ZuF{{ zh)qOtz~HDZMZj*>|jd8!YHe_;OrH&TzzKb|$XoV_6Vt@38B zx?FZ%XlAS5Fyr!g%9<((q+EoPO@WG;LdvL7NRvY#by3aj9i6)2VNlfaC;4a3t(SH^ z#;sgneTNjGuMQt)M;mhd$N6cG{$e}ZX~**GNFZ*Px?m`olTzpyJtD;tj7dl#y6 z8~pzOcb1Bo>*;cNtnF<@N<|<_^p-@7r=Qb!Vu9tlCM*kv092X)O$W;q`v)IBy(fvK z7K#Ck8c}IdK125W`oW0#mGbW$^DlZ;r^_#qQf!!NK5xlehs*XipKlya%fauT?xRuT z=Z+d(y1P!V9YtA)^0cwg{k$t8Na)PT&ANRPI8&%YUx=C#$y3Iap(3=;mrnR=^(wVp zHKzfJ1NMD~$n<4Dm!HWV=95pJTw6Koa`rz8uXyYLWtrd%+&^G`ujMAvz-IS; zFL`FM+X1)c`+nRQ++Ip*ZI!sQ8)pHQUa`Psa>kjmxlFYn!&JhO(6iG`RFk6XJ9td8 zwDHKz95NaM+pEKBGm_v1Q$iMuU8sR`P|d(9pv0gPAmijKntIf5uSxHae<;32ZSL0D zxy_aG*W@neS}zbGN!9W##Hm^`=04YRiQBKeNFcFy?QyK6Zn z3j@5c50%G57EP)sXM@8rM-Fv`AcWSjvl|t;LJK-I7!@U5sw$x2e8y>tW{0OvkXWD} z4oIN_g0-&$>t9}kubLks`#T%jo7=Bo`BCy$V`8iKWnK$Allc9JJ&WE{c=|bTtGH(C zPOyarS0zVFiGp)kQ5=y|Vc{~*X=)5K^KQ*-=f8n2VKQ5Za-fx}_=R%djVtA^$PNSo z4I~qY2Y}JXF+oOf3W66^4h=~aI%!gUIDvEJr)u}lR{YKEifn&ye4wT2UE`M7yQ1>`&DeMixm8$cGkF?0aG8ocsoYX|cWtvH( zWm=Kgv>l?osv8UH2CCGMHxP_P5|E~mElmY#Nv5n0>I#rCnow{FT3nS~d8WzMWpY_u zzD~C#SD4CXGBp`omR}=S%~6rbW;2zKEpAIGkf_xoRLt)z@@g*3#Gihk2P^)s^=GHS zAV|l6p!|mq_^&RMdwR1XWTnwfA&dB3ZB|8Tr>AF@m7yYxM7}tYmQq6~TS^7hkJNji zs;LLl{JncsRS7hy{$9W2=uV)T3FxOV$btsN(=AmviNT?nTU4;Qb%}ibZ&NA)pkBtq z-&bh3g8ucxX108r^?*wITz)Ra>Ae6UaQ)8ZyR45c)&EqyGK_B|T?lvJ}B z9r6*+GQBK?JaRFTHed&~%YTe)xudq>7^m7C16~-$P`dr##pWo2YDiN0m`bwA$t=b7oMsc3de9Axn%Cf~x$f(=NeZE#tv7|~b+nHIXd zdC$n!XBhi`$74MuLMn;_L{iq zQyLbi1XK2P-eY0x-QQDy%xe&C zhp$VxlGwQ8#>GhBQ&dt!vvUcwp=4uETe{~*DYjlF({r6 zX_f7j?hD4mu|EipDm0Pt5(zc@3I#J%g%8DzliGC+EuWES>(5x)dr{_ENBi@nxeE7 zs1()4l*TF5<(Q-|I=i%MJA|$%UNQq_v^fn-`HwTx9v9(baN|$ei1p7xM{fLo-+OCq z(`2?z_RH06{jc9UOSCb4Lq(0*dwZ^S_RLPg!sRy%SX$XI$-JQ4n2d8*WT?`gH3c)| z=VXSED-i>p&$YmuWmrz_RYAauXK-56&QpEg3_MC@ex>;7@7~%om+$bO&Z0ag? zF(+?7ijw-;p0>DbNR+tQzu56c+(vFcDL$4qB=3gM!4@jXGrv7Q2 zmqCij(8K&E_{huhg@t;JPAk@6Z!xy3wnF;YRMk!dE1Ko#A`uy>m0u#hjz;_W6cOPCLRPdz-K&|!*m?hdQ*5PzVwyPDZVED2J05y2f5Cs&Bp4R_Lj{`-CBTYMmhfgYJbDf zUv**on*D)-%Cgv_dRwt)%`t*cKH+OQWTgm zQJm*BAdquY$0I#Y@Uk>(;l8Eg`+W1C+tq3R05QzB?PXdJ>-) zlF`9YEe0EJ_eRIu+plm-k&?EWU8{$|ZOlDPwb?|9rIwprBFE&bNfG((Ab=>IZ3TfU zDm#h|R3e0tP&iPADr!8-Ifm(M_6_D=1W6-XvLX{g?09v8{e}~AFPF1&tNtVksZHt~V=0G@xt-@iQd1Eb*i<8CqKGRgt z(w!`*%?A(4fc$6<5l~5&Y?^y*SRFQ3J=g8KEFjj zpMEMhfGgEFW3J7V^J0y6we?sazaVlhKim6hs7^Tb?jx_Bzx*kfh56an#@bAsKUm}+ z?f(G3ra%~ecox6>N3e2G-tWL13x&w_F@k?*53{5^;Gm6)yal6Y?UVhCbyeM4Sk+%1lEdr3fe?i3lnY!B#)>bkO}05x7XO4Lp8w^?a%BTA0@2D za6;viI^~5CF&t-n|*D6ud^Mh0HIIgW+(h3qg{^J!MNEI z{i9w)e$Uiit|Ef2Y<9%QS3+VHben4qDOz}h@cqR90BK0F$r_NZwBmmzlf#wLe!lTy zTXeYJZ(x?b8M>CBVxdbh74oeqUn=9Tt_vN;>uUDfVBBn#8u2!pJtc)zT1euIIb4R& zTUL{UriTReTpv7zOcdQok!q)s3XGRwQ^ijrMD=xY;_7geHQCJWKq}2&m&-~$2)baS zrbLYaV&u=>&B(8D%~t*uB#t{nUmzW1WQ`PIV~l^cW+bt|>zMxle~2zD_K#(Emc1_> z#s2g>I#rpXYe?m}xRJZ%o^!woMGR`Hi>ci8b)OPwG1MOo{t>kd(@9sE>K*Nw$;B)Z ztW=Z9@>97eDN+fUBU-N|B`_yJJ~QdR9_2gcaeHu}6Q@WuIQSIf(~qAXJ#$t!LRw^{ z9D)bSO7Z!FkMMP_H^@q+o4h-2V9dtFXC z+dqMSz&~e1H)s4}Y8-1M{(OJc<4|9;Xicm%iK4h-E&&?8gb%N^=9C0hzhTEo zIP_%tdnMF0y=mN?ci4TqP1f~0&ok9I{lA@)XKuagj;N1mzUiAakCz#?AeOF=BLulh zby;RB42iEvKTr(jNcZUX&R^ZOJ&|vg-V3CWJXC?zr7&q=WWy~H!vT=mPufYlMSb;~ zMfIJsOt1-qDPWCR1Yu}MAgvXuDh+8)gnUPMbxzU8;<_rAb5w3lwM~cG{cV}<`W?TL z##PhQcNTL6oSSuF`r9W{4sR#6c5K)PA)211N^FgMGt|ivM)A|e#FKKq^M5ql-1eb2 z!+C3TmSw{y_@pvKA!*f0hmcCgQtFKvP!h^q^jiBY*H<&{^8TIk$!`7@uvC3NiA5|I zi};OF1qBz48&WG~b{9+Z9^lwJmu+NUxjO>`zp`1J&hy2?xb}Y5!*#mjGh1SpYwe6S z=z|rK&u)#$23PpKRZVp*ELhj4r=y9d5>(2o_bsECxxUMFwcP;Q_GxWnNZ{<2X1EeZ zGfynB>y08pg5EgeW@!USE0m;aRoq(N?@-=BdIhzVkQ4|Cw1wJ)yD+MRN@+z6SJdqK zdk087zAxkc%-h?lJZ}1zx%U=V`?*cm6JzkZn_%NMjVe{)b9=)%z2MG6O;J<0B&1rL z1r-ew*HE7%^~P{gl~~>jj%nQQw)t*sQ*PVh@r}xsN#1uNNa09IR7VmLw-P&rc3_Z& z3S}W|5^l52X41rvK^s4c30E@EG9W?;(uSf|BnQHv8FCCyQunu5Vj=C**IkoU@SV3l z;_B><*TrI}x4(A8*qyhx_hvVD(7xxIj(pv-Ic%jZXO5^UN8>R@SqZQ|dgaaLXXUTn zJ6v4JExo@xmJIMk z;gr(%n&elI;t2J+)n_>sb>VfkM}jCvMKTVib_p`yk2TZGyAU@ldF!ZlQFk9-DA||p~ukF zPc|i{dMzr62=*t~VBEHQS@xT_noDas3rR^z&ku2mHdUsEfN6lp;e1d8l_as~$7#2? z+u?n>PU}c0A#4I;&X~vtj6#X5)5H{FHEQZ6e|qfN&gr1snArk#{s(sKsys9@NncS= zc23Bb3yY?YSKTPu1+t*q~pmd@KWnzwl^<TjR5o3mx- zGwGe%T_Kw3&ds9R)foC++ZI!7?TW3#E+R8SO|&Sc@+{smWLi?Ftnw*}jJewK;qw|?f&?0igh zJBE{L_p!!NVX0}RlCiekEj1NPurn<}prQ@4nylrw=2W#4Zr3xf)!K*Bg4vppMI6mY z+3XSCT}r5KS*B3*Wjz>+eaRXv*TPoZS-^OMfT9**NVOVovjjemiyS??s&j#65(5$Etb;;nUXxotw|4I2%5U7KWasvt-m2XDdt~Ej z_Wc$Ib8UW_+;DA8)rrg1P3A{u9nW5{&?Qv>ml!?EDC!TO?wFM<$G>KwTMXjVU2T zPjwA+;e5d{@_c~lEca{f%=J%Y?A&i&_Dk`>@TH$tnYjbstcEioo zb`MMT7R8$oXfTpTQzTPk{@LcOndssS34T`QD=u8xEN%9=A9hi89(eAd@fXFrl66`9 zc*HkwPvUEwGSoSdQYGYk#Wder+$l*H4)8dA+H&p)+$m8Ujy z2HCo#n{wOP$+r~xPZ1sDx|73`#CexeEKq4=h-!?=%+DYS6Qz^>^uB`Y#(`pm?A?4V zO3d>(1xayG7CIFaDp;{CK&w>DTidGSquYDsyAv%%xprq)?!K>=tfIhVswLc&QseWu zUAtF>+~~CXVwdzhFxwwp5uYoMdCcQ(pg-fX%b)zTgm8zPlB}$Rf z-(mJ&Na4F9Yj)OKvp0GEF&_X3K=;2-;x`7urKHW`tG3MhXDPMmH+@F<%23hdFx%s+ zHnulst#%h1iGSjmIcg}xkx@%UAds^E0Bq)4-KP7O;@Pd3Dqd-rkp3#V%3u*8B1k88 znv=@l!x&i#nLJTM(!;qurNxo8h^1$vk{eKUkVX^}RFL?ZS;*3$Hj>(?6CWb`FKKq> zXC2vtb4J_S$tKFr?Pj5>qr)Aex1Mp=8`oyQk6DJpVe(sQNa^x;vph9Pmq}{c7By1H zL_D>z?mGl?ZC^nr?!bvGZ<&KSs6vGPt0IHoo(Ng{1J{h2@pqio^)x#YPWHVM6P)$=bZ%qps zDdeMu2_$qYbd7ah-1}@pE9+4Nhsemf z&UYVP!B*7JH1wZsKIg|#RDHyVGzjK~VrM~f;<^*+1Q%VFSSHp8Ax&y1aq>NH13!fI z^cL(q1wLc2Iwx<}Eo3J-@^7g&$V^P|!;weKZ_G9!t1(YBb5ob0q^Nn*$c&n!P(c?4 zEZSp9ZX$+7ta1%4Q;IPFf_UT-E9G2gp~O>7X&}3SwA|XC85@XKgc%Wt^8wXK2Z+JP zM6C))D};BDI&6sDv~+b-!?>cWifne_z*EpLq+QQXFp{=y<40KxLXRs>Pnw(ds*%bgj&u8a zy+OR%qHk97%gu33{^$6GjnoD`DIM%>U3U+d zyd#4gfP);cY5xF;K$7h`uwM#vrDLpehAM;?@8zvhtC{baA|__3gR4AsRSUNITF7I#85AePpA8kJrR*c=h$rJL}I5%Sr1 zH!Ii*g2ouA)F(bEz+c5)A0eKuU$$q3cJEW2$&k)HO%}?>E>9Pff3?f)>MER80-$5* zs|y;Ht=ujO$f}20(j$^A0S|k>X}d$a?C{BTa3@m9a3x^!K&>1GF$+}CO{vR#RS1QM z^Iz_4@qHg8e)YS#H?i&LOcGH|yk#LSHGD!_f;16Iuz^^RK&W?7G^Q1yqk@`_o|?FQ zwmy1vg;Z3S>LaX{840M1B+*7Ds%LvQ)yk5i+#`Jo#kc`9g{KSJi%lql02bg_)OzP9 zfan8xb1Acu#@gCAtx{7(WD083U`m{cG>uX*G(U*cj+D`3@m0IZk}9Y&Scxg8E&=Ppew&`Qxutu^Ul2Y(U@pD+Vbri9QI zIU}W4R$FZR%ePzH+Rp}?VyvB|SeU~Arht~3Ot4T`D+MO1Pf_wTZ%rJSxalTe<1bND zBo8Gy%VU!o>!O;5kjjRZodj$zDSB%&Se9=|k1Z@F^`(+VkVN`PP@$OA)sP<{kO{3R z=1*6-ww)GR7_BHSOBPaB#DqjfBLslB7}QE+(L80fP>9i`GaE5-Op9PWjxQ~e?oFCq&PWW6;^{I}hICeV(KIQf z&Y-G{0M#Xj0(;3(?iaVbmvbfDD3R{*zP2E(P&*>7lx11knpFtWbrM)`>xE8go#`@l zwQ*A6v2tbeFN+>ll;z=}%2Xvz-%Qhbn9bO~~t{CeLr_f=ZZkG1pr;aJsXSiTj z;$!sRhS{^)(2^MgQ$5Idj)zlS!eE-};UTxOXKUhS>JUJk=aa0hrs3%Z9T?MH0%bfIP^-?WoN>{{TL#f8_4q{{Vg_=21DCD*BknW#y1hB@e0!E~Wq#zYllEmmBjDY00bX&%iKd2*OzCxJo@(et{^7S1BAl-Z^E<;=g zc`6E$2^2UZ$w@}&nJKbJ@LH@0`X%>MvPj1epjPAgfH0C69mA18W-WHnOsByExj~*sAK8q^hE% zksfxEOxR)OriN76EE?j?T8B^?VWf0u9hs?yEU-Jt#5QdO=h z0{;LILK$d)nw?b@!jVQD3tt?&H)VX4!AJ6YpgYfEcRnMycQrfa`$r89S#uS8qij(_ z7C*1|rrFA4F&nR7f|^#LgAq7SJO@#(n)9u)FnVI-XY=XqNFpt_e0bcmn}x2BL8xb_r=@E{>D5g4Mq_hkaM*U;J6}0Zl*S`ssrO!C zcQkc1*kfB?k)**(7E&m&2A+nmBQ&ZYjy5wp$VR7Yj>%^5^$Ji^g$_M`!O-Ty=4n=v zD;!{&`kM4wBQ16Xbozj~xE`3_`u=V0#ThT;Iy{J}D%9=-e$J0a!paHd>o1hqh-o9Q zrNYs5gqeCqsT27Bf%D#V(b$=kYk7w=9zSvX)6N$+t_oscCNl#arp{kz^ zONs0pwn`1Vxpxjj9~hd05r&T;mhh~PRTVl$!`i8(x3&6srzgdf_K(EW;zEkG2b&NS zP>R$Zmqi4V2a!LsPl)gXG!-}*@)fBhW1^{u?U**EQz4DSZXJ)>c)ALTCzf5UJ;|V@ zMUGsOMHADlDjSuRS|b}CQNpnY+WSWlpFiX}X>-J9<x zaFzL5nRjJ$O+&dQtEs8VrF0NumlGsZl(eEhF~{y`klalv3nH-$4Xhi|;m(o@u;J)y zlV45(omn-P3?CS$%jeOg-uX!pMUtwTIlO3Dkb82}H;pKZ4sP5r94oBqH2I3qdG&c%u#B7o5`aEh zcz?6=sXaPFl&&8zduj#R8_)q@;Q@6?N zZ^(SE!udP%yW<9TpngR4e(r-~?Cj@XY%PPFhp;-2X&Rc&)9AhNvil=#?+w$rcAngy z13cM7kf5iggCA2vOHWxywQ?$SL?TCqtRy3iMgTM!psuPG!&3l&O;gIvLXo)ASB*UV zGAlrHK|oG;fkM6VzqRDwU(U}L4PG{euW-TgYbCbw5#j4$$<}{)FdrAYDvpzG?`%A9 zQsFl41(P)x_<67nVv@WUAAj=ib()hWtrJ~yBMQt?x3!phkzQYc$##k z;KYon5vtLDkrXt^qf=cDMQMOK82(7JR>uPRp zuKxf!0N@Q>)PY~R!>cJGDET_mdd#g}LG(YKSj919X{&aoEE`R6l1FySd z5m}4QZC%~*&c9&fc7EHb$yMx*w8{LV!0dgkxH|$2HbXaG9_-zjTpn*Tj(@g6UxZp{ z;-^;d`BLrXSuUDMBO1lRYXA_crJuu&tVl26gl3}=R;b4ZW)UQDn2+iBM+Azq0o=e~ zgw%A3f$))1K|Ke5%kQt-=TGw%`L)oI{Dbe0kCSZ*Zt~wdSA2X}?7WX%ZhUs&=wFo) z>~6c>LQL`Zbq_CXzf)J{+j?sr3_1zVznBy z>G^r-DriRTKS`6qb5JyrDcw~7fOvpL2+liBDhR3k@;7exZrk6TIlQ}zGud=~Z}H=) z@z>l~Ev1Lw`(}FF<{ud*`P?yVUAKVSa%a1jap3Zqu=w13RPRp@+fvcdq!B`{S*f0R zX3b7`DgRQW=!0F;Eq&%^y zw~dsF>KgowOAR0l@Cr#drl2TkUV_cPEH#UVEgfA$crsK|L=hermL(=RG(r*~7-6AU z`qf43P44kD)WaYSoLmq%Eq_1t9)vxpvn@1rRT0}ESBjLx$np3Q7&?fmN`_b@)CcYb z(!i2!@616~r3nL;r)>L=^d37bhERwz^)XiE8<@4e~v7yER^FOmaJ8l5|<=a}>NnbxfUzIri&Z$e} z@6X)#$B*X|xxNwScO4$j=zNcJ_9x1Y^z3X~)#Eo_;HK^FmBenYtLn*f)K4B~Z|okw z-BFyjLJV6ZyNXAKDczt`6TP|QAc_USB+{f{)X;V4$oh>RT1;bEV}%{6O##%}wQvTCO>jB|aG%aEq`G%)Y+>HJ z%d~z*{KU)mUv72o$ffB$nP0N#rrP-J-HfNg=P+9n50t6H^*+%`7~#m~@wD+)SN+`^ zS45RhDYKIyj%cH@+x2UPq_F_hJDM}l)GbL+7K>6bk{FIXaTmJ35i04TC@gAF15N( zcP{Shd`CcSZPdGCw|gHqzi|~E*}XB#no0?JM-R6%(C$pV9>}bsqNvDD?}7i{te0f}lL020+^2T{TJ zMNKC3cDGqT!Jeb6;Z43hM=Ge#It87 zreXlGadcse!$JarOBN*HQmsK=<~RTf3=Xb;Y4op&81TN8EpzJj&?kuh09JZvg2X96K_lco!}f9i z00&a>lr$K4Vx+}HXkjfgMUJJ0rYv-IRW%aiD`bu>LYhChsHu`hHv!#<`tj{TNK{b( z0+;|`be=`=7?~KKRwkyD$IsAwhf(pnX9Y){%P#ROn zW2re^vyaTk?_H0_*2yIuK0aCNA*qr{D4?&0Cmbr#)W%Rnk*1DiT7F`KNk-(`m2NfcR_KbfnlX<)*E{hYN{`lvo&SG-e2FlBh+)9-gj9fHz z>z1RVq@kgTmZp4d6-_c0Nu-y`iV=xZq_rgP1ZGEW;0fVcQm25){(J{lh-;VhL0Sq_ z8XSrmw*XB~3UTPUWjBUvaOC#hPjBP@0NjS>>gaMpyHebqjTYBmu33Oo&rq)KD z>Q@Q~6$9+6S4a=$wT|A^pUrQ+B$ESLWE~svqbFNb^V3eB+}V1k5s8CwH0@bY=B1Y_ zMLafJO|BNaYwS039Eo+kGL_Ty2hOww6HnQSW73C#=n=ZxUoF<#bvzBNw%F@aQ>Vm} zTXEnC0-Q$*bQyd^+Eq2*D}Fj-hI1(%Kz8QMmYRG;O+E&$8o092RM1IBlXR#!`QWOF z876X4CIQ@N3<*NW$slDtz#bG7qLOLz^#1@qM7zVRTWJu)p^T9)cM2I3*8qIa4n1!f zLyYZu3d(r8&nepdwY>7tW2@?G_g7~_w)*p6(PXIVV`;a>YAk+IEY@z4t}w$7g~wF0 z!y?QgrHrGpdm9Vesid21n5@f&o!RsP$XG^6)YC93y3{KyULrd%Z79-S*1L_;o7TCN z-NKLq1zM0n55-ACOaMk|0Ihl}ee1pcLG-Td+f-ff)EG&-3bPrsdgHrjca2u+>PWX# zvOYp>gSj!a+k0&896m=gilLdIg`lTQiz_uelD$1cM6&Z?+$~~l)ZYtijiDX8Dox=yAyNo+=t8lr$}d| znuB%J=&8bGB&e%QE(31uJ(5CB0uzT|eIa`^z0{V~DNWg|kTAd_Q% z@eDq`_4Dg=83)U+D;*?&NGu6&^(;BJBEy02-hFPo2cHhV|JU4B6;bv@{SUegRRo;V{w#H_7$dHXzBfqTIRJBGAX~ztMx%H7Y8J8o z02A(&6Nh+UT?J-`jPqm zn590?=6XlX^i^4o zRYQOgF-4%Isi2g4G$3lxRKlM{oV>R;)p7klKE@oXRw*|S!mQ35errySHc3F1RghGQ zk@=2-TDb^|LlbL8+Ce0n0&masztDRV#x*cFu6jO%{;Jd0s1ZqQ<{*YTCauQmG94jX z&j>o0`aoNKexA&16=_B^DosD1OLo@=^39r^mofg&5l>e`9)|1c5J<7x_yAqQ1W)q3 zZ?5*$>9;1t`^4oR@*}*|f8s>^e#g&WSW`2fYIcVMCv4mJeYV|KFVA!S;d)(lD=^FU z{ltHvNAdhVlB9rJUp)JreV8@eIntjFiyD8*W@Pc?pVJA>u$*6 zNb>%IkMeQrnU)5Y_W1JqYg3AUgROYG>SS)>?52%GD<@@ds-N3tC1q{fl#o7$F3`>& znIpRdaba<9V*61@Eo(|>U-;|0C%hg|Pi5u{fQhZKn_^RF(4=DD zz(vM`VmZ0w-1|KJ>$^E^TeZn%^^uK#Y5xFMpG5;}+t8+)RT^tgL0&ld^@>lC-P$2A zj>gMrB!>-(+Qo|i2BmYi#E1o~2ChHY`|#a2agW~DAPVG4-{G&B&)c3oIs3NAFe2G% z0rm6a=lr_mAIQ$_h$}B+<<)e9C9ykHx|@(J&A0x(?st9IkxlaIpn^YH#(r7rU%RY_ zXn}M7ugmi4IQa|S0fQ%Ei+;oZ9+T|q>3M~@$0|#Vtc`(W^T#KuxU`Te-GOrmQYH#Q-LE$`dog0AD?wQ-uOjM z`*?Fq%IEwi)2fZW$Od1hT_jV7%zv15mM@WA)?FH2$O?514l_*i=jUt-oL2DamZ#%x1 z3BFv`f}l#=6xDqEjz`Zud-o>PXx~8}8rGhDL;nC~FTIIartEy^F40fpG#g$fbRkN- zZT;Um8RJ_ki`w5qYkSb$w{fTq;^-P@^eE$H|!>DiaAHIBv2<+VBk1{+AXm;8LC6`0$Y#;*dYu}IS^!IbS@2+(={d!yH zG@oWWyv91H+w6k|7Ryn?A8+~3?dn{=A-+IT%`{aVo1TJJkjW@Y9k9w;TdO)eI7W@4 zZ^nb7{{T;IuIsxhxBI)gr8D}kN`7a`gY2hNeX_yy7qg6&;eqAn{LlPfSmXH>-qCAy z?H$4jmn`W^x3sdzG`X?D0CfXndy5i1)Az3BAPC#V!*Mk62{rRPbMq&!F3q+pFJEUrgv$JRQjLwSE$tAA^WzWq=vV%w=A(bFw+e_++8y# zsu^511&onHBHXC;5%l-AzucOk_e+yfapFJu{{YzP%eC#{wJoA*{{T?`00&%~Y2Cv9{Q& zD+^VslTWv&d~bjED^pJ!_V(hUXsW$ zmC<46;=O<4-6(Co&A{<3kgb27dV80*d$;&xHML!*pDmD{zN(dIUjrjy{{V-&MOz-= zqJ6gzq&aFjm6INkO5$klNKgRxzpdO0H~X=csMlDD2Nq<4wBIrjn>O+p(-w{Z|2-LA_D&Nx-n6+9(!q{Ql)uMuFvXEL z*rKPWrq+WBG@cZPpq<#5=|%Z=|JnU56v zhaNI`noKQCXJ^g2UXGS1zT%5?K}C;Aan)#4Q)D28{{Ton@nl@eJ} zr+?`@vVa>DA(TxX_c4DpcQl}rC5V& z{Xf>{+cWn^Af*Wy`+T}`*ss;u)SV(h<(h+Dj=xOgsWJZm&CBJMW_haRo{wmD(@@vZ z)YH*CxlixL&WuI&83$ULs%fBCiQs^mfWN(@!m@kFAH8qV&G$F3ORp3{ea422gSl8* zT$E#9g$cuvp5Q)Rd}e+7H!FRg-A&HsaU^LD-?x;~%d5mOOQk=iq*YiaaT%diZjGmV z*JHPi8z&4=PmlYEDr1sbWrk;_@Y8+8RB~es!KtVKjkK_0iuWUf$1{09XiF`^XSEe9 zH7AhtEBkZu95L54ckXoCuH4HFyR5Z1s)7QpwyIXE9vix(15z+>g8o+WR##)bMC5BJ zDDmrwUZ}+7hB(PvM~$kj%kNjktQpA?307+8sHQI7Ak_;SB7g<`&YNb-INy%x14wpz zTX#p0fFHz|u7%@NuZHY2*R@Ld)CsvxNafr&tDAOa+gjS#mtjU-az2kf!qi}CT7gRA ztDWx{GFc?)z1arMr^D24&Ak}LWMj>Z$3}x2g4yur;@uflo>^v(5RFcl*;+Uz9(h%@ z$hP)D?`71 zUPX65$0(CPBw@fE<~nd;g2z3knIzM!9Jv+U6k6g;s$uD7mm1T{{6qLW)ToAf$P`9p ztr+T1UImW&Wgr$ZCB2BYNZ>NGs-_sFa#_}(m8W$=?z)4~mYI}0p^o@}N@SlLJ1 zWad^#gC8B#U3e|*)0Fo6Ew^&Hmd#7f7y?|64j@>O8rKGD5yHB45lYvg2K9e;d$idj z_(gRYpbWk7#Cslj$fZn-2uk1u7&IrP$41xTBCf$QOH;S#G7#>JPBNn@3fH8&qPGhy zbX1iTEUO(oc0w}ANmCq={j|YIb`C+AIX`lW%HMxTzN^5*LdO7R(k%Oa+ga0oC^ zhG95mG3WxNBw$Bg(p~M4$+EnT)|SQRj20U8Tr^G*DNfdu60x`{5z3uZC!ixc)_Huc zS36l#E8>L>W<{}88H#H8u_lcxXP&NHeo*l8o_7ktCHMJYua7V8w9~Bb2E4|#_!-fq248o$X$v!8Wuvm z%>{KRAew<*f{gE6ZUi_v22UA2Gk83-n`15fN}5Vswo-wij;9?=>jaf>*3!*e6nZ9& z5u|kr%sKX&K33l1u;rWEi%9FbJ1wG#P`k1fRz?^p@hvrg7%(8v^b@({?eQksW^2ff z-F{4PPR~@9c=YOxaAa3QA}t*Pv#?cW;tBr%$o{V0w7Ua;=F&ZM+h+?@yMd;9d49-D zB!JLlV-&$;6*Iucka^<+?U7GphQ(y6j17UOEO30 zP!>oT*pSxbU)=e#Z7AX)9F?!nfb*xVJgd}!x7ZoXAtf4XQC}g%k@k5Gi`@-vRcB&# z(^FyTXVtu@i!)OrG;zHaMW>v|8W(@EK+`K;>Ei~**7q;$(Zz3LzY#gqwi0>&0HqZC z_q`0hXQLijlqUVWnH14>;NKxhmo1TxUp^Tf zZ7tb-W%0+Nu~b{jYiz6sVRx3>!s90C4UxQ#D=C@So2hB=^{{X3=GVy8$43tSpvl*q zzDsoEkY#CUWBYn3kvvqh<*l@r-$xe9w8kKWAP)2-EOa0Sb5laPf~K$4k(s5`DpxZi z+iZ6K00renbWoxw&J92v#2<be;= zCiLHXx}J}4QSA-I@*}YK)eiij+!%ajLT%^VD4nw zqT8(Hv5m_Zq$?G0LIh!?s5}%35mUe#*PtIYN(S|@7nmKwNaUJLH0+6#dtqj@&5oY3Qfnkd#|jpyF(_}yzKj^*N~O zv^&og*?4WeM4Qif<#Uuj##}<;gD#Y_rZya%K1HZPP^vdoptD|Wu=**V% z$r}}QHx7h@a7gxL&1uN;1TDO{B&(!Cq%dTN|*&zdY{Wpd4r*;$hG;4E`b zkr=5$)k!3?O&OhLb_(w7vJeXpIri$VmQc-#jQp$SetlgFb^t{WN2;h}v7gPexK@WV zM)(Rpk^cY=ad0&jGE8kfa-EOS-@`I#f-%(1OItkNSkjQ{R+>h-X#st;YQ|5i!3<`b z9%7Ev75gz>w){b-Z-&1rf}_{hfE*7@J&i>#SA2-x``a~u%5CI z3Ug0V1$_AV^y5ebq4T6398N_k<-_Gl)2)Gj;XZKpmd)#Lklm&6{{Uy;eo7~3e4gqq zudGZY|z8&!CG{{Yy#@1uX1-gCR-#NxN_W_9OqVt3zcQ_%naouz6tr~JR9km(P?;a^;|?TAVi&*>YAjd8T|@v_wM2|)0I7Xk z02mYkoh^bHV~W&Ww~2BUOO+Zc<{4J3R8ogdqvkal^kaXKq&?x*UDxvyv%VO09S_J{ zPiEBoUD*5At9v`KHupjAKBMb>o3}evI*+rv6SV8L=V8UzwfXtKjp8>QHrm4)hO5Oz zQjp6W;VD;I!m};RcUM9Z(gqAQ7{OGb8WkCip-m#GpNYWL(RSf)xIW{zUE1zSn><2M zJU$PJJnX?l9vqD@DQRnW4(sX(^EG(McO6s^rctStd@wRe9A)+_@kb;wJ2Z(d zqQ}jfAc0D0RVt&0!hX`e6p%$8xdTc|cLk<35)_J_$LsO6_D?kMl4NawJwI-}pStaPUFMA?1`reF*pad@78d9dFIP{~*gDZm} z3Qm8!S>E5nVm6)C?59h}T3{iLb2YLC@hzhgItb*MgkdEt1VdW!aOiRW z0GRzxWABJ9duzU=8XKU+_p*tt!` zRgK6+Sy76jsjXG}p9F0LP{xHIOFho>Rq2?@h4ZK?FNYdwP(}feGX>yD)N)TstXBE0 z?xee7v9z)HXi*WNS^!bm8HB9QszD`cs=_haqM?@Bq^QSGVrkP<6tPoeq^7ExNv%|3 zCNz`o5E)))Ezgxko7jDQy+t8FJ=Edp>(a`$wm6~1e1>`zakSIYLksw&WEg^zNukiq zIgvF7F%`4k@BZj7%4;BU&@r}e?dnaRQVd1DIuga6!^nX-XW@L zjVfjPhEp5OA`1bii+@vKJ^83K{lB-ZDF=xP2^omb~vGe(tEU+E6qLA09Ck|nMFQ8 zQl!(+XQcP?wAVJ))5d%hwYL}*I$0`BKhtXcx%KMQcC>R+b?U?!G}tU>^&ZL8M5|n-J##OY(`3DjAJ22nzk9LB5h40yE`w6(f8fP zB0>n&;t{H%rj)H%y>J4SAh-P>1n|?|3qL(brQPe8}0dzpx zsi*+eCb$D`)Qh$jWMEVhfqMy3TDpx35CsU;$K}zs=}xk)+}$hK9hK7G0WsZAjowsy zuV`j>pI+~Oj+;+D4$n&3XUo=O_Fe}Rdp4hL=jmjnA9Rq_RaVC7G;JQKeYJHnl#WR+ z)uLt87?vwh@Qpl1bNn=^Bv+>)w@9W~#Bbv(098}hC-He#6cw)u^i)|4WAfj-HJbRt=OG)g^o!YEW~xv zO*GR+P-NuMpT}uulHJxA!XT=OPz@?* z7@C@K<6absGe7+@=KxwU}tXQR4_}e^-nR4iK#kti9F3R;gpa7r2wr( z1Hv?pX>FobXwpVvS#%P`Rah0z0w_r*RVq73Jz8XTf|ev$3n-?U9U6Aj^Gxnkt0ty% zIlaDw-=Ae*`BTfKB(XJOa(`ePf7t2vIM#JgL5YM)(9G`9%n)g2PXIa?Eyyl!YyB_o z;14fP^<$*$N}XJOUSGHTohCP4=%v}XdGfWg`M&nL3LHfu)zahIyC+m+c&OyaR!Wq# zG_XNWElpiR9W?ZC%QFL~PraZO)W;MgpCAA%OCAcU0VR(P97r8mwEikpN1x7sPusc)2!K=5+KJTh~bXc~u8jO!p?zIXEKnl}SFd)ey zkdfz|Hdx7(Q`nc1&PP{y>RV@|BfMH#q)sD*1z@x!4~Ka~BchWUxN{wa4}+uWZX zJDYp$y4}Oo+dX$S1Hb+|{Fdu&p<67Qr#sOb`*h*%G8MAOVtFG6!PQRTmCiD>)JPRI z!1Ori=}oY5hYLe3ZAA{*&rR1YvohE@pob{9irPsPAfFi2vr?E$jau@Sjz)F0iRap= zZr0r-ibO68DXl=Q6b2ct29xqUdX4$cJ7l?r`fG+k^phw7HPk6-Dm#>h?mP{6aO+2J z=6~0Y&zgBOq6-DmN?eBr9<#a&G{_S+SGS%AjVX7TbYG;K<`Os+b%Iir(M zq@EdK5>2Pb;pu?ay55v3&2+<05(^@ctJAkh;aU+;4QLqNcGXz0K&5w-~A8!)NQ{4M4^i_ESO0rjjPY#y4ye{BqAZl>d z^(nWqyJaRwkK?I4JoJ;p{GA1Ny1v?|K`PS1PnJAb$R2ebM;RS`7j}guEhZKLPfr~z z)lAjd2vPw`e)^~bGqo@a;M5caTMH-y+5X9(ZMM;?66!mv$5A?)`I?WFI-d6ZA55B2 zRrs(1lw-!D%D+CU5Bbn_KJ)KwgYieGwg!41?@r+PVX*fN7R!eVPgk4DP;ESJX0vhc z%6-dIm864bV7kL?R@K#3)Jsn_JxtYXT!6Hr4I~{v(*sZ- z>Y!pO7}AB@(RM9)e|L*eGu=h>@W)EDlgpGGXs7}+NbCY4Db&?vRu{I85{6Hf{aWxf zMD+V#6sQfo_mT-fpn2LAwyH{;lpd3tptA3m`X z!JFz-C{WfPfG$TrKnK4L9eYu&eqD1i1h@bPupoiK)%CF!<$dmz$Cq9w&(EyLgm~7$ zN9uEbs6U&1FVDK4GuG?FA8%j((A-iT1xVHUQr|(yJQfDv-rmz=B=o4)u2I;?SP}~< z^#gF)4X>n|YSCbS*7xtXhg;w?*ON#VyJ{Sh$WTjh^)?{?08e#1Lj3yI&&#I^SqLKP zRl)p*cIL!$^!$6T3KPJb^;2HHdjA0Mrud5d>+4n^shg$inSno)-SZ(NUf`R12E&Wp z`n*NT{{Yps{!~BV=`S_{V%QCPjidhn)zjzx9;#EWEgwW-np$?Am~IX6SyB<&9dOZT zmaZdGyu!kfbtmMJ?h)q-zdYO`JtZ+(sPp)N3TgJ#bpY=mKQ~_}TFLaV0p-LW@S5lH z=&){?;hGAm<*u}|O(CSEu`*7Pu>IK;KW!Ds{eMDlZ)2^dITCe^ARkT?20t=54?c~o z?dC~i(tyT3Ecw&R)}02Gm95|mzy{z4KSCDch2&rQ{{XG*M+LZdAaE7ON4D^4ml;kZ zeZ4h7Q{>9x6uyvas21P}2db(bbQ|hF;C-0d#igrHGHKC`tUz4E6wvsne$L_l02kHX z#3Ma_KqZhujkosrnsEuJ5Gqw;n7YE2c>{4^K9~Oh4|t2(+{Joxr|KvF0H6N=)Oz~2 zW|#eGc2-o>{{Xu7@&#$ApQbb?farP7b*||#{l!s zx!c)#eP=k*wD9bI>fD`kXZyjtPwL08Mnl?e`G$kj^{nbYpY5+#1@LNhqxjSDrlZFN zdZ%7%YB?zlJR(Ky4#p-bi4*s0gP{%Pxe8B=TTQ*nyPl`KyIhVR@x|ft`F?(Vb3VXU z+AmM%UbWiqt0!~zrke$qvNycwr34~1soc3KmJu435v*G50VL@H{QDR{L4q0@jSKr| zIwYE&EV@Moqy8R)81C9sE4xU_i5eqF^1HZ>B#9T)?<9->1Cmd(D508WjtC=pE+lnD zMHOadG(}K2voQbx#=R%=7&-jw{?A7fX8dWx&`~B&vT_YoSRng~j3pg%<1qMe2#}^* zGp!}4mIMG#W`+pZmDKhP@1Q(|_gv)uU)tAl_c6`>`jL2(KxX=T3mqn`C6!%FCtmNYpK)W7l z{ETl5Fk?3@T{U-=ShFrZX)*#etvWQu7gIg#s@ERHFk5}p`I2+6*;;a(n}yY5SmW1j z%t4@7t~Ere>~SB5F1bkpJ!FcQrr*dn?zYy+Yvaf$G|WR2TK3h?b}%Sw=xfk1+x-nT z#-y#?8*a8tp3|eAkunrn83*yLzxS@NLm`n;CCXzy^oYEHR%kB1P(j!33-`zF}rvCuY+ukCvsN?qi zy#i^&9V|A6!Q5NhBaX#kAdHIhG?Qd182yGWijmbS>++8fccqC7S}<2s?m|Wj8+(vF zxc1|J_cxg!<<4IUhz7fxnJeI0L+32C$tU58A>TBVMDrlaXxeXgyV&e)6S(D^*Fq@b z?m#pHfE-zfRRoX;!Hc50Yhq()@_W-E{7Ge+SbvFbJjd{ST=Gc1BMm+dlAuUhnTU~B z%RGo1Q#P9coi?7!dkgJ`+iAOVT0wCd$jC1DdAnw28c2@K7(~G;4wQ~(h@DLIq3TXv zQ{_#L+Bx@`{9;KOkH$G9&V zn5n@305?J7HvL(nTLD0p$Y8AKvfF{H8Irp(bMsPpP*6Z4RI>qDBpsQ*H zMf97rWHq$Pgd3mrKU#R~a#UmyocJXY7;JC2wp6L01-ba7?yxG`NvMKj`Y`K`+} zL^xbVS1wdzu@#xwsU`b#sF6J07b|@YV?C2)-8qYR+4c>N%+I`E-A8W(V1ce_J{7AF z0)PuU6QvPZn1ByX!vxne!)t98yNM)JMW`B`jTLHW1y7kE4ksNP9k21%VQne~%XS_{ zpEo59JQZ09av3Ju`!gKYEhP#v%LMr~c`pjJM3J=a7eq?LU!Z)i_jLBJkT#*e^USbr zx7Mn!b3N>y4%-Wg>R6#I8p|0cN*k7UnuA0r#3+`mxhG`Wty=4TxmleQ7A)QrDe9|` z&zuG&OX7&6(7w?1{{Y6#9G{^3W-}foPv%R$x z(h2r&WwU+Qx&G_=ud(gCuXlZMrK5_~O`X$~$Ph}R35({YD9bY_I-_MBJqFvzyR?$o z*rY~XI);fHJq9~u} z^cj&7ie_o4$L-W6nC4|Gp;%kqFni_f9G=*~oYl*FjJLdzJ=cU*MXk+*k5dv(>NHCW z(4==dVkO3hj58@7$kePnvQDw;27d`(pl@@}-QSS*4t?is(%+i)nJ+nd$83^jj5LwPZX}T* zw-U<}D<~SIl@KuT3`8E#dKL19(PzExcMVNym)+|@*y%4xw1js5Rha6ry5B7asL1t%jfnB*?l@kBwH(m#;dEKYCO$u0r`_o zht0`cv^DCskO7bFSbvwP$ivhX zwuU1qwPq@qxEqJd-v^^w>+Wk z{igNGn-mtiyKb<>tuADgv@%CIb=eSbEPVm}IdH_F{7T%8^AIkT7*&v4%p6a+h&W&0Le06!Q#iU|s zsf*Ce)GtRHC{pMW{x{HWWG%W_F1IDzrIKJ)H9;6823a*RcNNP;q);~k#Cq3!k#2(L zo1M#{w}#aSUM!~KbOdSbqB7J|6s-=N^=#dvSA(I#^xiU?D^X8fRko=qw=UeJrLyLz zp}^q(0J)Lk8j>YSY?6~(CPAW;{F&MvV(g9VH}55{EI01SA&x`3MAD16z+jT77XJW5 zun+)eRWl2nKLIg;Qp!M&+&MPbV&o{S?_D=GvsIoTy^jEbF=`{A3bK>qJlYzu_G=x= zN^YQJqM^pnRkT>t$i*CcW|9LE!;CkOEj+alGRE0yY8Z*vUEz(`Gc(BLU=73xw|OU- zQ|e(*B+v#3UdYr86-A&>@6l6)v~0qEXD$Rh@m0$g&|I&167*1PzS}1q;80@uvKFq z%ga$YSzwl7PmpCw&%bxIEo8AEcyaC&c_gv1^s1_hl{*x%Uv74C-`lyeN%bUPpVT!q zV&aD_nvUvriVXB;yDg+sS;2cdGXe~OBqPLEIgF4hs(%pzqksTVkt3*T@)*q48kg># zTG`igHC;UmK_)LD6qq)pii&SQm9cdUv8%K|O27*NW^Z#Y#VgxvoWUGYNhaei%eW!X zXeUPz1&#dtHe$NM_s~=WOvoP9&pn;i%?dd!uHl$|22TOkOV_(W?FOC1P*4iDSh1a( zgxdRhvjLlc2^2*ry42jWCK^?0K zJn0l*=W6$Fl(|O3YUQ2RX`6PE3ppJLjUsp@c;tz!re?sF>6D?7TCiK9PRS&Ws)BnC zYTI^wu5G_?S+^*bN#-%f5RO}E%Df8%>nobP`ivI$28#$L;Hh*)Ag<%xI6Q@R>)jR9 z)LVCScGWdgZp@Y|X31NK>v|QJ7?e9}r*`PdFPCv-qoE6s+)wt>V}f27q`jy>Id z$J@7Ste|+o)xY!Bl2lESj|T9$jUhUP_WGiE8R3p00SQ#7jSp zNgf4)CAW=%a!D7tu(>1L?aTJ(!(jx4XrL%2x@$_4>(#c4W|60s8FDdCPhZIY04{-C z1#CGE$?Li^9Mi!^x=l<}YW_Ekqr+t8N!mpkrH+zB4(fPh1aWijR@!YIEwh-MkPFyI zE5@d)kCk`> zC zQ3$EA&{tGc(_?h2(Ri9W&N~L{%$A5@+04etn2dx7UlkFwnpwycQX?e+qOlC139pwf z`K~Ae?blJIt7)s;A{vySjaErTND2rEs+wvjMLIvf1?xU9ZXTuDd+Xu`^4tBB)IFcO z^SjqS+msuRCAxRdXLh|pK>MR}cYb?t(opY{+w}DBO%+`xc9Mp_9ZIl69V8UuBqcYW zQ0+I=mj}ahM)-wP@ijFjgEck5;ZCb07sGV=t=i^UH#tmxB$BqNA4NiH;1v`SQ5982 zqQF(zn?YZj^;w9!pQ@|2?iB7^ukkMJs%%SPrrdDXQr1<+OJ36AAdXq&NNHs=Ea7!Q zGNj5wAU@V|O3GrAMHM2-+*8V>SaAID)%heU>|6a~SqIgvRE5|eCd+$@xoTMO%*@711dUl059#SNUxbrER;CF#B7pE66FPTxMp+P{ z4Ztc^_g5$D_2>P!x7cu|7dZKJau6$2V1J*ZvGGEtn-$bQBCBMQo~EZMm+IVIE*f{N znQG}Maea+lnXWk1kulO#QA1M-(^SZFx_H{?tNZvXXqo6=*BRB=8(S z&zDPJ74sMzE9!XuRO-jRSoJQ!`OVRtG4eA9+xX47@^cN>8)L6~qaV5Oxy%+9d~SW8 zjge`Sf8kc6bMF1M+1MSfDRG$n;XzN3*<14qMMWb20C#I>>uBVBpj)YDP&CQ|G4s`h zsPzV!6{tDQN$GcnrB*}$On9GAFe~N{%hMvgRFwxnRqX8UIxYE?+xyOrDv!FX*xLs? zk;vwAQ^4=`_$u6`HX&0JO20yAcZ({9@=d*X-%>Dx z=e|*QcYSYc%HaE7e`Dy?cI7T7ulB?l%w{&HA&lybh6Z}9O2-pYK@LiNH8Lb}vu7JB zUR_+>gn{L62}0HK2|2}nDw0U1DO!>#b1s&*iU^tJWC6`+6sV1pSm>`;ZkVyL~ICQnE?o10~FcfmjK1C>K z=AaN{psUf3rl6ood}cD9s60 z%5I^ht-wi?tsPsrvYRtvRqh?1wD-kvk{m>sa49OX6V4;3imtMqrb7((LO1%0WHnM% zRJ-XRe8Q>|Kr31hM;i3wNes=RJBgY@mNF<%z@Lc;a%u$!c^bG50CiYhla2WAk?tHB z??^Y^C*!6ourga`ch&V4(8g~*>!WCKJGUjX_Rm#qP5%J3HytMD-1$x8gvZd!1$H)S z*s)7nSK~6kwozGD4;AfRS#&W7nnRKnqfVk0p!Z~eMk*^_yfD&79LkYYRgFr8s06l} znr9#aYvt9A?7q49-?R4~7YExJkLLZ+T_28St*YD`uXB75-n$d41$A6C7~Jk`^`_h1 z`@W-O?z%Uniz7pU!DJ<%%1f?N@cAm?FSNRmWdi;F};W-K0n%!rD>9A{hTQZfvMLW+iEAXF9kQ~rpz1l8FsuZ-HcjfIBX^;`F1 zZk+ZiF++sev=UESN!;yUyr?LvcAg50U?iD}yp4Ke{?{Mm^SVZ^0gN6m=`F=kjRS+k zRD!^dRj&$h0~P9w79*(*8Cc{T*DHnwna=}4K3y6te^dVeEFHC14j*7t{{S^!!s~s% zxbu1KpV<2g6Y;-q_2p*i%T>jW+?)GkZK}Pk*8Pc9HhPMV>76@eX!i~#Sf`+#x|OJ; z46L(wg|2ql<70pyPOS$aimR4D%R{1FGOcMOXyAcqA=1kndxS0m=RtNrYeKq$lx9;^ ztYwoOta$Xa`wo-p-<$N3?2XmEJ1gRjE1)*s*NVQjqjYY4)4n&z$nPEDU!C4NYPyGS zjg_HS20L z{W?!2BB?Av1Z0ClO45omOy-1CbQ$an_eEy*4$8<@b_er?`2pJat*5oIUG2QS8+=vj zEU!v+#{8|@l$*aHv8gay$F4VhS*F{xQg~`>G1*}6IZO?6a(p(r$*f~4KlsZ{#Qbu}QV5_VLAHJvmS1RCl!6&N6>7CRSn^wV}n z!rig)-?KY&cE`L^~68e;Wln79apnwrkc4bDX~9n zYNT3$T~H>YR(c?l$#6n2jwDl72D;g^-9S5N6w@8l1dvFrBt$IEtX-+w!k=dmT9ZO5 zDN+EZM`H~Tl(H;uQ9PB@lS&nqJBC(B;fhWIx@fa2*-D;1p4h2kz*GGFY=DiEQU?z@ zbm6~brl;6_T{S!t5g*V00EPypDUzY6v9xrZhgm&UOvsTlK|2jmi6IinE12}gRZZ^! zB2B+Zq57Iv?TN<^GHXhF>U{dLtbgOg{{YG(pI=YeUIhAjbqA*K&`sDsC>FM>Ba^~S z^S9-0U_+BKQ&YBLOr`@BUzwp;WoW5sWr~4mL5YU3Nq-tW?#;a39j(8GCumtHeDgfD z#XQYh>@@4wF^O&ndQ?Xq0V1EKv=!rlKu`1NTHV?Hz1W$pGvhR9Hsu~?_-zyfWL}bKBaQ7P)T*_4m17JP z8mZLe(?C&Hzyz@%Du8N5I`Ua8ikcPtZ91t&07sGHmoz}Sz(B0Qn6l{v9-TVpxjs5} zCt>csf$1&#vHPR7I`e7JZteTGdYf_A?|0hUQok*Y#YeawJq|H;o^6IozMhtdj^Ie+K*34UaA+EY z^kM!!?){nCJKI0FcCIMnW9#1M$aO%<&6tZfi`+FkLZ1ySW^-xR(p6ScR_zVLN1lpI zY|@3PE*V%x!<}2nJ2Y=M!1}3CoN7=_Kp>JU_7T?ZBDaZMV^Uv2lUm@g27px5jtAxs zLpMO;XmURlarEg(@Wq?RZ;5N;r`169EhhWV)5z1rkkX20YHD%sn81;*@v|-Pdv9V#?q34DG36Zp-nZV zFf;z4(^A_)kX=Y38i$4!q?%NnUVe1*^XSd|R}_?;C9rCRH9a%ECgrNgQ&C1Fk5g|g z%^G;=p|nxFaRm&B0V(PHU)?5^&K%V zj&+nt5vEeVZtbp`t_OG>n()zD85&wQWjd9Zg5OJD+ceUklhs*;XtkjA{{Ux?<2dr9HL?5XOYf1K8L zv~hn6yL%zik>qOkG#yLZMuvwSB~~vZH;WO5gL6tO&SI zaSL2p-9!arDuIABB@C!!QRmzM1n{A!0(wytfhUW^c2}v$0Fc@oBdtLNk=m*#YCx}5 zzwwLtfByg}Z<5~-J}-RD{#i3qd?@)5u*S}QulYH#q{!Cx*G+cjTP;nnw|`&!k?UIR z-kVRiqRj3J+MThu@Oil=qp#cfN!u4zF*R{XQY75B6n)_y#7E#uDk{bmR6J8^DGd~N zP1{4HnIn+{v27Y&I;j(#KFokPiz zW8AyjGxKBPp1}DH+uH|YbwBe8=r5Q*9R4iq{e!amFZjiGReX@@{{Wget*_mihpYD% z9=3yXR_tEw>ne)*&KD_7S0dsu@UVJ;66D=9FJzb7bI2Ai%io115cJ}NaAtO6P%*l zn{wFUvWX>)t>pz-QHG~tq>V&zKolIPqYpFIke|%g8QJ)+=GXFirH*E>ZjQ6~<(E`>b?MJY7K0cM58X~#-=XEH`t z;xhXG0K(e6Si82SAfSG z`TmFBy7ye}g@{%3f(DzLwXRDpu0c1wzMlP_HR{+RfOVCa0Gb$*eOhh7PpJg{Y&rL@ zx2@OHum929Oe(9gTFf-R0f#HejNDsQxgOI}ygFDiDo!icg17*X1)Wc%3yytP2lM_P zpL+GrTH{=2tnH>pU=5LjYCH=!1O?*61MkG~0OWP70ba63+KT8TmH-Qe1fB-Faq76Y z*WGGCCbd#}(+XgYzI`9?rxkDZdV0jS>OC)$1d+~_-g1N=>PWHUo8I^K43GWJ-$)cw zaJ2sboI`Q}@}OnprG{{VaI>arbDdrPn|6mQ)d zc7H2!ar4c3t}mYQ>Y?eltZtbe-C|AoCvf4cKDM&h{{Tb%ea~LYgY_KXPw-g}`ll~k z(f;tKrpN3gBjFc3!hh<$m-{_jPr^#UKgMs4bn(IBY+qeLP9zm8JvB^~J%_&Xeppab z!6h7v_j)EqGXCP0Rw}>=PjVmQcVCzMb$aHVnEwD4w;B#cIC}p8m(#6uyRZ}6U69fc zMBDdxNa}*isrMd6P!L+{%YUprj9_2Vx2dmc{{Y8FL~>?Fp|5fO01r!_joV&4*86PD zRXCo5Y2#+dCzdue>zJ!1mlYXqVrk$8N`+Tar^Rt*1Kw19)VX3E-`pGCXS%l!Z?Rf< zsa%h$xMK_r$Ks8ASyrKiW6che(9e)|<-Fcr@>B*ZRMacO#ABsCRbJ;G>1)Iem0u=z zt#p|h9=xS`icD=bK9e_}@yY4UR@J$eA4yQEbs8!NV-gt20M7cEPJ|$B_p;}m#w-1! z+eV0B_TjZ$wT01_xZPP#59p-KN9wVF&u=R>rZJ>uLe9mSapfJu z_x8qM+)0)|S_x~$NZD{$oE9odlf;$O#IYx$0l4t8ZLP()HtWi>e*(*7ah_FXktK$X zca8~!u8@*ioGCA)3*3QkeDmk-Sv-}`Jlo1es|MeHG)QVqVhmaqsQ{2-C~Hjd1cC{L z?yZfT)#a15S{Yp{>!FCR0qMqrqtDTJJYLD_x7`^ZG&ASv>UU0lS@hA#9xD?aV&bTW z+<5fDlxXtA>~zTWH(m($(677aFKrx$?B%C0?w_G9;|!af^pa5+K?syUfVLG@-As`d zGM1XiCTF;4?MSbyA$u9{Qm&YyWhE7$#u;8?vyP-4Z0KH z+QJknMG~a9xG;4|O_syfQe@~VU~;IF)5<1VdV%R#pq)XESez7eVhA9S>@~FR+n+A(+gC8` zlbAQlDbi?U7%J%6mb9f+sYX(CvXZTWM@eliCb7J?y|y&CiGwNoJdenVh8}82I6WKQ z*Y19@-u-=-#8Opcr_E)*h1cV0&JuKw8JMH0hNh|h;#pxxV5W@EOeC>qj!T3pNEyHG zuigjRUUc@uo4H?ZlX89QaE95Uhv^DM1=2|z+KjSGr$h`Sk6MP2qjFVh#d?x?pPBX@ z*JZh}w=x@o(X@3#+R8yDq>sW~Dl&C&rD#wfmK83Q0i}p)Xv#@r1H+_^p+Y5oPN^XRg@V@Iy{y(qMr|4k*3K*S{y|+HAMt7QkdRI zodt+xunYqqW9_fnZ*;fYExU5rJ-XfQ_Upt~f>^EDl2u|=Ol&?dSQW>ZBachdY29X6 zq=##{c-=u#vAYJXX{4wi@bWz*XQ%M!k>rd&mS|+8Q~py&QA;R_Nb6v9UkPJ>AJ+O! z>_@Of_Ve1@T-x12(cMKOB#6R{j)bct1CYwVs}CYNKvs>B{=w+ld|AX-iFa1wnrYt_ zk4K21#~O--$5mw>GgnnzQAD!+jYV|@4~`^xBWWW0i^js|-erBy`Bn$J=Pz(BAy%5* zS8cU41gp%eHPfN42#7@)?Z}r6f()7M#@8H=xo)zpbW$km{6uPUK457d?Ycw!l-^bQ zmwC^%8cAW>+d1RMr3$_2av9?nn6{L_79(CO%+&5`#RF$!`Z3?x+Nl(<2 zjuojWzKFFHEY$)kDzY+F47jPPT!l2$vZZ`7{hfSMQz|VDVogosk}9fW0)=%qxEDV0 znm1^shI@IMJGkTz9EeK1aw!E}91vC1fXcvv2&m{JjL2hn+^nj=f+`A;kid!%LEuLN z)rak>h`W!d;fFNwRL{9^)p%UpP>rc!P0@)V>GC|p(WKGV#Z6TtkuQiy&Zqzyef3}4 zP31l9_IA;Es0pq&Yg>)B{zm}=-9$nQoB%ZkHrHj)0pkYKq^SaOuyy9HQ)sSf;>`(0 zYH0#!&L4;S@GG4oPD+7HbzH9-#&k|EBvMNR;1Vr74r7-{V6UXIn`!|608kIUSX|lM z?YEb^Rpmam)_Eb4mH6Ryjrf3mB{Zso>H)`4Sg8XU{{SyXSK`((Ik4N)H8WPm^>x@R zH7cwuly$IUDJv=@XcZ9>qPm7^z_J}g+0+{nNzMgQ0{-#C->uHym_6h70`@Z#+eLJ? zi1D)&b+m~sgOgfnZw%`Lv_7CKl0Y28aF@IO@o=b=Y1u&rposev{{XfNQ{_{PbcRWs zKDgee$R4CSq|=sllmgoS0C9^olml<5{{Rv0AU4oAU{D=ga%gMooc?_kPXT;jmFUntz5R`PL zkG=Zc&_on99X(d)$3a&pa~l$n>oVDcfJY1MCgF=)g4q2tU)i7K)3sqj4{#&)*Y?7q~+xr9a_qTyUrSUsbL03nBa~T1a3L%HP)z_i1B;oc-UG#QDLz`1wJXMl zucQ7#wtL@WKIYb|5=fDbQn_Ml+O~T{lNknbRf6%a8j|Qk)PN{ zm&>n=fA0z{aqbrO43!4gY}E810j6Sdz!Ac^6{p+L$;jm?YA~OCG5J{aaK!WM!`)S4g!610eRRM3o?Qk^*e052RowRK-8X(=I+48=BgrrR3w zEYrspHnT0*50RyvqazlXCda}=OH!X$*v3#R4`ZE$E;k9?Edn5yKrG8w4h))AN$mmi zs-V|O@bedPWxUs`%*ke&Z-h1?CZ$zXr!6 zR71C?gJn*EW=sw`n+LSx+|N+d5K~Uo`Kcp=!BbXT&b0FieIQ6mKYh~n$8_a|n&umg zt%cI62k)?LHoh|z3L8z!Y4Dn2#F&^y6bI;I?){C#_S}0hOKESgfh2HnTP`8LbR!yG3|pHLp>OqRhl>; zjy6h-Hs#NRKUPI@5oVtX_A75iiO$6{^@S{l`++tuc}D&*OnXNFkm+OAr9 zm|%*dB<0wLCL`%Fsf?Q+E?G6FFYKc3N$1)lmvy|75C_%x+Ww1ggaAA`=#EL8mUS;i zDgtyImg{Sp%GT0-(qVgXXX0K;i25yik^YjxGOAio%Bb_PY7?mqYKT-j@}nykL+(o4 zo+2#8enzJ!ho{?7!%+=ZD*+WXWllqM?wMtdS{b(mT|g1irDQ|NO0L&H-j{i6maKNT zrQEJ|ryR?5BA_f8W3-ANhfNq#Sy-B*DWZiShhjQv3+a<%f$lBUr<&=bjulo76icn1 zd#5}nFGYo2YROjwR*S3d`=DldUI}TkbW={rODq*a7-F18)3Q@6q=6rX>QJ9eg4~-E zkeeionj?`}B~{KVUo4UPdS`67@La7*wJJy)MQQtML(m1cV3v!sHW{HrYUwvj>*J~- zK@K)-9%3w!xVbVtBeOV1iQ zxqVig$0{ojWQ0@arcM>be%_3^T8Dbw-O{COLviBXGKzXqp17?#+3V%+L}Gid;cn=| zbq>Mn&E>v&V`pqG;`p7N>^SQ&)ca>Si^So#i*N0@yteHnMt^H>{D<&7qSNOo(xO;0 z^P@_V#?wUkN|HlwX%yCU7NKYe0f9x*zz#L4fl>`yjce9rh%9d6w~s=!Fr;!q-e43W zIaK6S0!p?=o@>^;Kgq`j9@+kFU(R1^bS7(YPw=*va%Yg)X$H$7>P=G24pLw5a^S zT;V01$1!sKt+mRVxnOBz0F7Q7G=33aYRZO2lfyU%Oo3_@fYuY{>t^4!x=S5_sH|PV zxN=+TY++6=vRr+Aeot{`@z~scGM=&-sfx>xtf^ST7e)QTT&moF=Or$*k~oP0t*xo~ zhM@j_eFS+6#Ft^;{+^}H*!X<@Ed9Ug`E)>g_XXH^TvNfl@;ib#@Y~OEYrioUN#-6;c_JQn1IN zT~+Lo;1Av#Th!`NH3yNZryp8VA3i-Sw;q3oAK^djQ_G>FZchd`WKmApdTJ^K%XlbhC0u!OhXh3qt_V&JkiY}u~RL4rdEX0A_2m2ihILZ@2 zP(OxLQB$>o#|1_>Q^_jRC^YjNi#t`cva>Qr8xyJ8!2La_9i-^t{tlZp{vST2b}nl- zvwGVx*co~{ijAv}iSU)Vj8-+{#A5dz>Br^H*~RB_^vx`k*(~iwDyTsWfIgZ@2_Ubw zCMBaFn(8EZWYVO5%%7J}CZU})12y}7PtVJuLyh?hz4G50I=ABnJ3Can0|B|W4)m+S z(#=Os)Oo$zQuLdZqRU52xs;~dxVlgZ;kTz=Lr?&)ZxHMrW%!LqvZH(Yc1s%Z30k;mg_f|faIB#JWa_?hhEjw0YR z?4{RF>3*74Ko}6rt6vQYwztxaL@dkea{|mIxE+H!Xh?Hj)T)qGSkqh76irMuFba06 z_>sPTKz6rid{pdQw|(~{`xkut2HTyN-M=1tAELUuuCSE-uefB`I9;*XR5f_+zsGi- z!`&ORFG0I1tG3-{db<*15y?jsF~y~}){$G@ZXqIN;v!fi*g6%Bxe6!n7o-{{WiL!(123AB&sTyA_HH-Mu}xv)zZ& z`T7Vgm#xWQC?w2fdfu{VV>LMqvDmbj;YTeSF@-WBinK4Djur_nSVbFL(=meI?M7IA zv<9C#c~_?36`D1rYH9m%)`dBK$HP)rV(2L%qRCXnQR0TD3At&rRWFmv!4+06h|<&2 z%FmSXOn^rsDQ-oyf_E-)+2mU*6{?X3=05+|k z*O^TA?Z9BMy+_zNjj^#Z*;@MjwY0PQi{rA#xp$@)ZcSHDiO1(RhTEoUO1kLcTA65y z)5_9862=s5(TAIHVERgfJlLq@ z+?90oLc0>*-Ux9t)DzGNvM^G|l8y-L%h07H-@1VuMP(&g_qEzF-`>q2Q&YmV2A`i* z1&9TON2edieV$!axAQ#TyOTTo^R})gJn@$Q3kC9{X^c$BhyGBjdi}=#`nD@pm zm%~SouglU@JdjJ0(NQmwN|@58NpK6T7gg5iTTs<3v>>LMBK4f+d^XZ@E>GBhHbvEzZLwMtQj{}+8{fmUkWHEc^ zV~O|v-ocI6h1@Yj($WlFHDr|3bJEn()zC{+Wu++St?eD^=}Se_P&~>$WH1Jm^3(-B z&Yp|8r;|#T2{1` z%}Wh!7J8bNnmXC*sw!$&q9nDIQyDa|ZAJX_+VNvC8zwBJEgV=R+}Ub6iE7y^ z@|gOkjZ{)oRv?~AXDrdDytGhhZyOgpH8Xf_0{xsxBB$&fY|0^q_Jnwi3no03s4Md| z#tj#aN$6tfd1RM=e5QHW{na1MZWnEu`gjXvqb(^FNnMNKt3)x{FL^%1X+$XSP} zo7zZwt*zX(N%08u6`Dikjx{*x+kg!5R=Pw{0sfc6QU|SgDGOby}nueS?vvt zx+u2(?f7fBen9v4NoThv%*<|oj@^s0yXUO1Js;S8E#FuzvAOX5kB<2{fyn2wd99PY zvC-7x;oG#;6!nyq5?06}QxAdSrO6}eBaPtZh%(+w`@#Rj2;|EqdB? zTW-xAgsLLkWszWZl8qja<>8XqRhe9>g&O4wwPPZu`WleSCEiT7^Et3pl6d?bULb8N zs7zcSiA%W&r&BOcSg`J;22X|fN%pQ!wD9=}Yb3@~e5UN2h97WAj9g6)=fzUC*u)*f zjHpFuYq1r3ixXV{oph~I(}@>{E$w_HNVbFz(pZQYsUQ{#$IrM>)6k9`Bf5Gt;)7cS z2jpA0jMKOR19}>P!=qc!lzEI#MB(=C;G~9&bEa=|E_5Wae+|dgRc?HxWK&dCLF5Y) z(ai`%U1sG}-zSR4TAg1PiwA8G5;-Ni29b$1PXBF2KB%7^*%Rq`=b{{XXb z@TIBheDp29zD-Y%j8sP*M3r>?B5A3lRKJ|k#SL7KEM$Zv#sDN+->iZ9g{cBR0qI^f z)gK?r0=~8K>h~puq{GizR~$!uKW87y=h2S%ngpE%)uKIcMA)6nQ&J>Gl2=(bmgi?i zWiG|k5*t%%uoqBn1!{C#YRT{-srmS8#+^HLQ+Ih#1t)Rx!KFW!MrIm1NSUkSf(Rw9 zfugIZ2Sm)2>#CTJR5LDscu-FU24WHa* zg>d+4oK+4`RaezxHw;ixWp>t22(^^eu~dN#T?~^bDs;GP-NR(srIA!=I;v@d@o>mm zdX6+SG#xCC(tD$#D9f=SR-Sw)DsfO~al_OCPg*@=znj0p{{V%(?efVtNuqw+u2_&F<&-!w(0Cn-0Ggf-ko33 z`?I6A*K+p`7K0DiJJO@A>vx3N9iFd_rEEn$R~VJ~S+Iz-h1M66%@c40g3TlGbuw$$ z+!dG?HK7X3Fw3Wf1_f$pvDpWSq?En56)07*)L^4hkzFmPH2`LnAa%S(*;|O7!fCQwzd5%lC(BJiM;%2S7AtQ_l&PqmNMdqqLdFl^{uOH} zH)zo{EO!J9`YP1cnc+c>CcH7!Wz9Bl-|t&WPjX__U`7V2j~YrS1b_ugF(l*)44RD} zf0#ZEDu0{*0L#G&(oqeqPty@sQ`0Nxt$2DrVp7b}x`@@JXD;1&1G&y|oo%Sqf@ zTB0D~=4k~q(n{b)H8V1-e^GJ|BiUR9Qb>y$0aAWKhQF|9pziEH#Nv8tKT!Y_%}A98 z4?21E^d{=>?&Q0Evmv)U+A{gvrc)^OGfyQ=Mp9>v2CAAVrI9Iq=7yFAREQ)+EZ|+3 zliiEKJ7fkB0o2-up0dQ9Uo%kDK15R#>U`Q|x0=Q|Etr_h7@F+0XCCY*y}=2^&*sZOOL<79waW zG((umXQ)vbrKU*PMcviBG9t@43mDeQ3gjB9gIt2=QpPGZQSfw{7jv`6Z^_%Cmfd8U z>DCAouvTeKOCTg_SQLktsAC$k7SgX$Yw;P{EQimHjZKc9Ak?*6FC(}jO5}+uUXopj zxT#m}BBuWUCs9=x=acmO--PGiy>r*Nd3kl0U!bm#TT-u==yZRy z3k@ZK=iaHtoooYI_5ae`N+QMGpHUVCzpAJlt&bNs7WSXdhf3-P3fHb?=mh`*K>fe? z^03t4+}%ai`mReKdf-hu&YrSg!ArzgI4)v^@n{{X9Ce>zvDIj9pCE~z*+vQy>yrl<4&04G%mv-JM}veOeZ zs-Wk48GJ_Ivx*q>M_??)o9IdZ01t4VGKT*ET%rQ!!m|8@TD?HKjX$q9K>R)hxBUIl zL(CM8HzBMws}^t6t>Xhg{P@5hU+R6x)_R*tkz7!I-al_bsD`NudFkjl%(-v^*n<23 zIpkd4_P_Xh650T&wLAw$Hmj$@JOv2-oifmXxtvC|5-;&wb<+AT{#OYjRlyp*m%kp& z;Hxn7>3zLSv6@tg7ydjy$;YeKP=C?g8$P9f?)DTF)Ctros6bXCz?<8VYx~1jt8*>( znp5g${{Wx*`lEuW?FPWEM{dox=Z-+P>b5?5lc%UvzQ1+bPDSs_Zag?AjyWstd-hyu zes0Zw+%NjKFI>j{@HsW@{==a775RjL>06sFu4mz7VLmhbe3krchpi|Fjb}2tvTmK$ z`pj3n4C^TL8wR$a!S^WcC;V>YgF+Ad`nmb_&O0Ivy|V+}qsxa91%E7_wbk!?{{W@F z!34ytyTfp?5V3d|zE-KVqq{K|2lNtjo-S?dVQ>A6K7j!Ha6iN4(F~xhvMJ&jzruPR zzAap1yipEqmRgERlyr6AtAY=_b^F6hYjN*aJ-xiD@vN4}#Z5qx zD@Y@iK1~~|BM&B0Is)@li2TXDGB7LS(;P6M5&02A^8|DlYH+1ZwJ;%+{VXg2Hx{|~ z4C~0#z?$?Q6sfQLS4R8dy?#cjZT|p6QInc#Xz4c9Qd8B`Je0y%WXRH_$Ym_+Bvi^H zKnMXWK7f18AGyrZt=GA>+T7cC7B8lxr-&YP)>gFDrmL!zp`pMOls&bP{{Y?OLCJ|k zL=P&T60Pzy1E9C$Of`6(*Uwh@VQ0zW@Oc3x@npgW*Ccup>2sif` z{p>87+uhyP=*}50cAFVil?4L9^yN>ftR;aTg@EEZ3v;|L4>9giGXiBu+*8OH)o6Zw zzFiwW%EwnyboF)vY*Nni)L=HI+Q#FlB9kRmH4Su_nmH&V6PX`LrX@?WYK;Lm7WbRp ztc`ekhE*4nlFN1Q<5|wXQ-!AZ!$qT^1RktS~rNv z3@D&#B`S(kR;S?{1z4tGf9(}{=G|3zn5!&tGQMAA=q){yLI03aGhJ{MT zBwq3!u=eg4;fihU_=z>pq-1FvXuct?rZlf=kSIVc$E6lu<1WI=)0(_4;M|lI21(Yc zxhnB{hJ~vpMS6d_g(0O{VvTla<8)_Mu+l7jim!g`9?I|5!MT2G`&gl3vQKAy9qQ|4 zsw|5jkt(z88zA{$^insL$j|le zc;NH!#O*S@RwpM-f8qJ;Ty+vtN0OovX_Zh(84VPHWr_Gc|U47TarDz*f+^H zgxq$!D59K4YO)}7m6?ogCtYi#f~J7^Q_rb;W#?UoZrgU7OM^d+3`ng+s00ktyFbgK zXK#pgEddi7o5`xT;jS>fI+=k-hd%?bAzqj4Fmzj5qO=i;X zak-v7SZxzd@+P5EM$*EfriP=-sGdWvX`lGrkL_ZAz@J% z=BVYF+88;3f*~ZT>b19L3Jw=rP_-~fsTJyB_V!0REy@=qQth;ZzygSI_L}~E6mHMP zON{KT{{Tlku}sUl^A(FEA(k^9MxnA%1LReGaY0z2?giKze_wc$?`4bae(`&mZ7kwO zeb!0!07foVZdFJ>i55_eEnO{q+n+a2fuzV(RXlYw)KcIv^Tkm{Y2JNNmzdnib8%n;a(h|# zedI~R{^9PHSA5NNEb>b(>2_l?Nh1j)V`T)2kkGhvC3CL2m=FOt<*riN3JvRUS#L;U z!bt>5#L$*l(1u+#sH?Zd_EAbYbE3C8QRKGbJw84+sY$A~UgMIhQl#;$uJGh0$&V~H zF~(#Fw{OoL%@f)myXUx8A6d(rF5M-XEQ%%CuB3^OlB2|Q*5I^kK#b23k2+|;^q_LD zDQ?lnHro0lp&Fr-zH7vZ44D)o%lsV{E%VoT{=dp&sIu}?hDDxb7)#{MMwn7w8cXZ53g0{T4b5Pmr;;dGMNEk;`D?j{+$3= z0019PV0IdcRC)3L09OyQsoFg#2#%UR&!6Y#(?wV* zD-4=&K*#0Nw%_h$sU&LgS0A5N0gK1fWd31N;o>slUbk@k*Tzp>G?g`vgvHhGo}I7A zNt1+Atj3&AN~pdyxu~5UKotudg!lF_6fm{I1pbCmHsRKP4P3yIH9^b=HQCp7BQc*oE zGVQ$P7Zn~tlCN&mQAuA%RW?uVprp>%RMS3|l0O@HlH$qr=Uuhl&v|gtHOOnVnvE4n zL_9Fx5fwT?r9A7z4rT7!PUW|&3#(ZY*@Qv~QFSDi@+P?0%Uv?FA)^sS)U_SCDR1T3 zlH2)gZ+fjP*_sW}_qd4FXzHGZyEQ>m7FJ!qNx0ysm8h16hORt|ed0>8Qnb2XTDbN< z+ctPNEz0`NOZj8FHicmb`Xgpy!S#w@DuG!8DUP7lgpQVS#k8|u?odHH$1l;*JSV2M zC4wZN&;(PdjDUj~BA|ndf%y?zOFnn2F&mo&oSS(~wZ73QmW435-NI=w8(iaPJXF;c z6sb|PamrUATMMi+NmFD*j2$-j-p_V!ZP@I$1b5%#fX6F3#}s!=iwdTVEXd1g8Z1)C z2=Sf%6)H&;`?VxzaO8Up=V_Gl8rTTKs+gglL>B%OR1Cvivg$W8DG1Fd3acM#2NZ^; zmaipMLwtrZ2q@91>5`6`hK@Y7IiOWlkUNM(msn)E5+V|+5HlQPxJ|m^*0WqXZXPH) zh86pXU_MDe0j&z~_2>r>ze~%>w)nhjG(-|Ag;h@!cz$`)TIit2QfZ}F^zXClv9uZO z#|>U8uO*hL!$~D24&tk<#AET*k*Y&WyK1DMfA=XvgOPuDR;oiH$boEyPq7y%-B{b) zT+4TB1lL9hk|uX_irv{eFBw#UF@W$%KTPYX%8s?N&1Gl3?l4cZH22b5pA9Y@;z-<4 zR`HrMSBl(@^_T^HN)~{F(>L)rMP)1GXtG%-vNW{`l2D?Rt0JkGr6qnd#)~Fal9l5k zrCp+zS^^1GRQA@#2GM(YW8x&!T&u8{EekW{gpu&5H3fr}JV+FvHHPLSxwSWTbIlyc z{v}4A8A}lxLrNI}Fd{%ont?+=7p3Q1PhI`}$H9-x(NeBIXyvQ^;;~{^&P7jEje@rX zm2)X-SFVn+CykhS58ASl3j!uCS+ugg+&4t}@27$-qIZzK8eo#!280%-inAoO;@%dT z8sK^D=hltN#w$C;jKgO%fUq6lGONH@s#jQW%6N|qtwn3mK<`ZRV0%w{Qq4&%MSX5x z?s7Rva#dj~-g@m!<+3nlb=VuZrm1GYjjU%09l~^&& zDp07X@~4+k=eX0|S@W*=Ew<;DdF4iVi?|P}Gz95h)d4_JN>mOUdIoa+hVxd_(==;I z_SnkSKWUw;pG(B8B|R+D$cY^s63mO_lhvo{E^Iye({$O|Mw(@)bs~!+8o8wjslWz= z(}x_IbYC6s)ZE7n)DlFo+sJ7gjK^56g)B#EGXNd4P9mm*qIdFRwd?2Wto|^VUU{O$3+=nyYDGSgt5NF8KjM#(>P^^;PZi{0hHcuv%a7UC%l`n$ zl*GrsCajiKN5|}yDoEEQNuMWc1-Uw5wxRk*`u@aT-vt(%@liz*#0UG!f1C5`+_f7G z_j(d7Q|VHkl<^II(dWa{t2f=h%p0YCGjA>V)ph>>B|9!Gi({iZO6DbM|SRQjkY!p_m`#UHiiQx`+{jrbq+eRj%KZ{#aBejBT8E=o7=;e zrtRGc4)xCVy$(AcM@wBEYARaHeKat^9W^~Lg*~&mPjhwkQr;_zfg98jLMWVc@TtKk zIepW2bo@IUASv#IgWRZWUDN3@Ke)2svQ1EHa>y zq*toz`ArVu%HXkkyCFeG1vOUZ%F5q=Ls5y{bQN2*rp(k~XsK%DS?hK_GNz5iEFL>y zo=*sEGp)t~R`C`oR+8yrC@?@GwIhK9;CYJrbs+4Q7x&QJ8|zaY!by@;s5+~F50E1j zsm~rg5;}6_qX@}YE&*RS}AHLr`zyi&Px}OrAg>2vsp}PRZUbC8dz$gq`!$0Mv1Jn=8r6r9hPoG1EE*cqPrRpUA0nePetYoPK0dPgn zw*yqDrw*%5+Skvde{1&!H>x(?(VruUn>~Q3?VY{Yc|3kjmmQa*lX~^`&FpA49@)t4 zjN}t-y}{QxoQCm{v!bU?Mh_B8P2_MF+Ie0;6%Zz>ITaNZU=*K`RjoeLUY*jUHl}R{ zO+cn;QU}ab3g`CqRh>=zJ}k{LWG8|MnWtFhlt{?6%i=VJf+;K-PoOpoE)Bh?N?;Mk zri$Z9>v*5|Pqk)JAB^A4R}qV!zVf+E$(r~zwQy4WW8Kv|53{mz?rqcB7?~i(cFhhS zFP`e{n@HIQgLv+2O*7^8?$?sGs||d_bb<9EEXih*BmFyGQHUf3P!XA!213dJ)KD-o z>F|hUVy9zJGU<>j_%Fp(jY<(k46HSt2uPwa3|VyQTe9n@{{WaK%Ys&fDJ|FW0j6cEQ^6b~j%3ju$^$pRdGrbzgt>9VSPtGkb4);Nk2DlMr)H zG_;1Ic{EH5`_-Wu%yJ_D&NV)jj0nVN=fe{XQnr#+YowBB3+p1f*$KQgQ>Yy(J9U=T zR?rI+T_qTrRQ9SG^>-U%cy3Hb#ahnQ?Ys_W1G%fZt8{k;{MdP{%|Oa*N%Pn&rv1tF zbh)@1nc;4{q^)P+m&VUk|<>*sqxS=8Vc7*$WTpm(0O&} zX>)&Uk*Gk@B90i~pqv3yO0n}KlU}tR{$&*#2YGxr{$05qq{D0)&bHqjt8z=op{o|Zm>&C*oX;HqjVVX4b)n)wx_qpL8(EbxNj-q&r6OuLha*efA4 zB8HTUi2Fy|(-(Lap@P>){kq?e&&&QRtI*4By7()x(^9+@6%gmK@?s;3rh=_95GF>N zeQ!-c6)ec^!%CybW6@z{a!DS7ZBqeti#l4VeyGH6CKNfoWx@sHLlsD3c!r9er&# zi6IcsmTC2(*(8$cShuKN-qfOqq*f;_`vLjYyOzmhgyxiFtrC(pFDs_$3&m`gwSMm z&+?w`O4`_Hv}r+6rqyLA)L@5jPFsJ(phszmxO(J@`t&vYH`_U!f53lxZp}9hAZ2ieoa^ zIcutOPMH*z9Gl1)T0sgcw2i5OAhBI=36@3IS`{C$SNuMIY3Yc*6({`tSO;9>7yTAC za|H|4W2W6(TW-j+M-YLdlB%MjI{F$$DJ?cZ>an&WF`%y?@$Qo;*WP|E1JjKF{{Ro! z)seqYEk*%9;OTX_zCY})<;-oI?%>I9Ode-wcOOdkH1F4&lx?cr>zL?_j&C>A+ZTT1 z>Ty{tonKdDHx6#1y1NsKmlri{P)B;Tc;aM8tdY%cD@2ZBa_Sfgc$!LTYEZtFCWyqP za#Yi$1(|yTkc@>-s8T^Xb3j;uQ$k1-;7v!a%*Z`{#_9T~4I9l@{LB6q#Vid2#|}D4 zI~uxKa?jERR>=PVnlgWf_GdKfVX80HhCYq) z`KbO_Cl&nqFW4`XT`|+$-`ag&zV~ikr?fkV`GS1F+1)qR*d)j1cfRq=U~{;Q!JMgh zWvHU0!EEeZ4P;d2zbR21Re3svp`%Ia11h1lidVF zxA0L>l*>?RDnL@8DwE_vEL%=6GH5!5)t^2-H2iwQ^#@pYcHzw8dy{+aS(9P)l3;50 zp6KkVEdKf2*(me7VokDZaK~$5X)47nMRs1YhA4A1jYz(EUI8+DRF*HLgb?njL#O&N z_Yp79?pj zf^~uzBy!TKEnKqcCX_WKspDMIo_{WxlfiqLB!mTlo3&^`0G}bA6sAp2Kp$Lutm&@! z?!KJu9*)e`_P<g#Jh7UG;+YqJXR5sMMxAaRVRR9 ziqlu89*@UHcQ;w?cx$!~RqSo`v!mE}*|M^1?bBOFiI#1>x$~KcBHVjjS8-<(J%c&u zr-pqqtI$m(QArwkA_ay=pmjl@1ztE59lywa-!sRmtE)Sym6(<%R-B(QO?>O>YfRvD zWkzCppqlU*#}QFPK$kTfQq1hZwNszD)~XwV%oMVb#l7pYrm>Aal{v>%RWx9-kZW4$ z82r5PpDK0fcP>f_O2(ULWfqiTsp?~qbM*16PSc3mnxb}{C80DrfSJ@tbsZ`jpKivg z&7qV4ae`<*e`oo6)6ovJn3hs_sIL!B6+C@DeQG=Z01BP$sy(mPJ8NiHZ(o)jb(N{; z&DB+h#q|E->&d!%e#@WU7)(7SAA96;b#iZb@TpY<$w3tmr8yLNk!DF_NM%U&kj-~1 z%Mvt-uz-wk6g-DnQO8zkTF|GSXlE7O#9L5`CeaJeAu?$0bK#&d2H-S`7Nsk$oG5zI zGvZH5cE@~dZ;*QnqB`4gc9&tc%-H$qHrCOOmZL3%+M9QJK~QW?eg_YZ$JF?@ZfgO$5|3}}%mAs#(N|a0XXC1&+b}^-HB7WA0a`S9VO?bpw05yu zTQe1!4JJbD29c<-1iMnYiKR7UwFjS1NYco$>W%b;025kMh^28uTKatY`fgydn}sO4 zOEtFQps%HWjr~tSjgpc)MP)R?vt(m3l$Ci38tBxll(Vp&lp+wZ0B#kTJ)WqIuD6Sijk%&t!X3|Mmemla(iJrb)h0(YWo*z8thC@k^&sgX^YVwX@xRTZ z=ZwP%AbF`ei*Rl_yp>KCrl0${oawH;t;A=VraXkT5>##q$%N2~ZB=AQ##qzT03P8Z zNq6v!JU^_EVE!OY1wCo`aH-+YXL5r6JF6*f2BtQ#v($o0u&Huu#<<3QRIf`PDfYSz)EEuXi`zNF zki8Ue(o<4b$5!GGxD$KU=gZs1+FtVNK|BuOq;ad%suQRV!@&yS0|lbg^oN>0y)NwM z+-gIO0h=WOH4zOUDl_~;NYKoCyUtH1$0|M1P4kPbS8~TC1#sEhhba~&NuHqNcJ+41 z+^a)C)rAsSmXu76QPRd|H?aVP9I%X+n}C0eD*`<~vmkyzkMQy6>y(`u>L}JGSi`YR zMu;#{xRK-zpbN-%8kjt~uua0AH{B4`TXIlk3!*_Kveg%9kaW^Qe`v7C)-Q z+;MU5WOZTZ)>$OG+US>33a!Q0>bDoMxcrZP>eQjZ#d?k!T#?VY@cMIP@`I_!idA3JWa*iU6h*- zaIZ2c9^|z_!dV~Ahy7IZ>Id9`JnMKE(L`3%{{VSC6TG&jE)VV{iS;iL=vB3evE-hA z2i%or7s7~)HV4~U@#t9wm2pfSALr;k%mx8Z=TQ26K({|$e?HIc4M{#!=-SlPlpOTS zM&dli9!&w&GPve3x6y*tL+LjMf<2mBint$dMplF@@%e!&)P0OG`Sp5nxPG^#3P1yG z;M(HkAM%`c>T+*k{@(uZ+4PQOzFPkP#Hs%PZ+~A?_Vpgna`6VF?E81wL-hXu?sXzb<{hmdS9<9rbxF73V>+XH_Zj|PuOxDl&Lj7|80Pp?%m$FOvNAKhNZtXg` z?}U*E{x)uIu>-NexXKQ?h{xi+;zMeX(Xiyr#f&u8y1 zxp7>mSs!+iVVc%C!p$3hwvE)&h$e?4sNa8$;NSP8ktrwD%4zauEDk}ngsbn8O%1BaBk$!!|^u-h&C!&geeH$N&BK6&X#Gordw&MVisfXj=L#{8ZwvCcK-*uZt*JZV&^P1E2;k8#`s)PdJbb>(vm{%Q4_csyRSWkC2 z{Rm^!as@)K0DgQv(mJfY@4j~rVdUE>xN4+$VtJPlh*$prAi`tindXX$mKeloBg7uh zJ1LezF3f%MSKJ?P`IFr3>Rs!Yu2|ZJf2Fk4Og50a7Fc3Z0Kh%+71twoF{$ewcWv79 zd%0_^!a`1TC*X}qu9X-V;8=}KOq144kG*ppeUpnZwd9%d9&H&sM8aut8-oza4A|_2 zEK;Ciu7%cB3oJ&=jtcup$h`B+KHG2bb1x~*BD;-gBu!HV%r)8H4RHs9|50J9sMTVw`UuC}G!tN>BsM{^Ci zxJ5%C1xuik)?b9WF(g%1lLs?e+i$$G_Yk3GNJYd%DJ(l`M*!4hsAb_$tU=NTRni3T z6j_If{87w=Si8qii8N%gwWI|Y5Ptyszrb;;cwS%igUT@0vW zVzU+}$PA0=jG*LS^?g0;ny!Jyzu@a$mE+XJma-aI!PJpzrfC%TfMz7UJen988-^qi z#g9CDvYP3r^Zx(`SIGSOv5$>a6;kyc1te?JzJGMQak7&LsFt{fmKcy)8Rb<9zzZ+} z{`!IUP*_viE>x03MLV_WK4OC5c>IUUsmGB&QyNA_haf9R{Ki>~OfXXk%_QBxLFX z>2vR(Uvvcn+wO62gp-sf7`-N&3XJESlRyon{j`u^F0?X?SdoQJNQ%9 z!B!tGOEf1*hEqdF9MqDzyi!!tNTnT-nF$;ps2I2Rgpn>i?)N05id0_4gsB7uOK1^* zBNbKzA22~2M^Wc8n)43#k(-7X;3-e$I2w6__H?DgceiBWHiXy=bw1gpq{iduu^6nR zIR5~*%I(Tw3sb`Q*wVM{>nf&YW;4$e?2<8WPo~FvC*Dil9$w|EZdBUl+ZN8&)orb2 z`dv3Rk*blZ7e`p$T$U2g9IUV2xupzX=Pl~rZ~fZ`f)pa6K8ieQ1t^)*Up-8$)g*&Z zC*7pY7%{|@3_t&>F z++NB{Ni43?OCugFB#ukFA2P(Af-GI-cXux%8j?*(Cy6X-N%bU?)9%jQnaz*6DR*Yv zl@hlcujZqvXKZd~8tOjt3z&u(VUnjGSgB&6gChlGWn~NwIbWK&gONA8UTozZ!L4_= z0iyv_l@IoiPaXu&Oru1Rw-G|6SStnFZsT>eUM2mZq^W`pbh_517y=1XPf$Stl!gF{ z72lLNefQP%weiJAOBH_7k8|RusFc*4B~($|T2P0T&uo$1ZYcV%B%j*P?9xD9v#E>k~-g$B~tk>k)IN1=+P^rtNA;yr!-MEBS`CHhK7}!kpF9r{`y9%~SjZdy6iE1W|T^NaZ1xWz=#2#^Y zlbZd-QuKLum!SD1vNs+CRE%RE%jr|uxMjNbpYGK#hOk?56@ynAYc|mfz%${c>5p+3TDNGhcEgVeB9iTiwpb6kGvhsR=;+ex!D#+esHq_ zpycSEhsb$X$k)rSjBoE7vpa_|?luuKEPgGu2^4iIi9mGluj8S{o;0mj+mCZ^PQAfb z(^KK&sFH!ItKBOywbj@PtbJ7^6!mKr0hLmodFMnDPfk#ffgJeCx4Z_jOB>6yg6hyQ z!xF3&)rSBWR_u5j|+-?Z!!TwS!ma3FxeA?;GqY8BI`2ee40Y( zA+NkuvJ2h0uCF8df2+K#5!AhyA4~v^%XoTkja(wsfe_b94MHz z$BDEFfR9dw$L-E94(=%?NZJ_H5mSzpBlv;KellnQVNpfFjh^}KdmtJi6kyGrRZ=Rz zekT~G15HFNC{%kIpKxR<_tiEoT0=<&0VT^OQfhcBr-nvKlC)7*%seu!Lw(1Z^0P*s zVxlro33+#Jy4)81cH4BCIBn&UM%5acCX4l7d04&GKoI3RL1GijIboRHUc#)k8&8qaiI}nx>uz8kM}B zGF}-+O%VTw1)My zLnI_9QW0BNsS-0(s2XZYhHYAEG}QDHBaMdIbt=y{J6AzoKE;p+3xE~b^bk*5?jn#y_t$4x+ER8;fIlNU+Dk|s|iZ%|X0BRXlDj0=o)SBhzwT|M%vI{2x zl~fFO3dockB+?X;bg){0t`A!F?}~|`o?2>%nrR>`wWPF)Dj!Ml)X=!Gks=Rp!r+c= zVnE0piZpatBfw$X@*a)$^#0!hxe^jSUZ7(Kpbj^yrQe$i?P^sKcWomzL}jle0*18J z#W*(7d)L}+?Xzz{+)$9vOpC3c=fUm z@^Gm8-L3MbryVQ_RRspkhKjY+AGWCR=jud&OtM5}hGj<~l%pWAxVZK)`VO|l_Qvx02iUuhElCbTcyFE1ckI}Dx~j^`nkp=I9vTW$ z4Ll;2pC#s*BHJykbVioYs{|Mdt3bMFF+)nRHFjc45_skPt)0D`hv_SzB7^G0W~Gf- zl?O`aO0UA8U}{nPg6G{^bLS89dfFI0u}8DMI_=EP-^fMRdqRZZ_BPJ#+)OF6U zX%8{&Hqiz8^J^rM3ipUh#A7;h+u}5<2tR~K5YRB|Uk~OPNeo?y)0DN_hCQm2;Cl*K zvhJBl5kBs}6oNe%Xk^Lwr!RNXqzKiGjjimvl4IBPh+cqOTLbgM`Fy%2_VzX#7V$t9 zmrI)e07TRBryhvc$Q^^0#B{F0-Y{OPV>V>S3{59vB6IAX=vc7%STk`jr#m?IbWe6G?X_M4UIrc z@+P4_kf-y{N-fWD0-jm?&qo7c(nX5f6qFFh98jEvJdNeM$dcAm09VMY%(F)t0LoA4 zTa)a;4H6=}X~X&SsFPDs(7S_VhN=lAj(JsTC7r3@2`nob>p@N!*{RHz1zZ!su|DnT ziVySu0Gq9f{{XAy&;|0h4UpVjaf+ZxOthGcm2Tjvfg4pfo}PlDmWAP+m(48n)b%q& zKt47P&ngeJ?7yfO@d`)nrhk`L-~iRc*Zkk%>bq$+uHwM${08t8mGSM}!z6f!swd6Fg!-Ph@@S|(9*^(;Yez^thpjlll^p|jGU)u=jAY|f7{P{ut3 zFk1HmLKM?9ECp%h{P$k?z3^kNx>vq-uX@k7@jLsoai0|Noq4^!SX5TwA9D96WNtn4 zKH=>h$Gjn&^#;i3G zNg9}FX-#Ov1{fG+{As*D6+g!wMkFfGRkYA30Ajj=jy}02wD0`#KbqFq?5?}sUjV)q z?_cl6=if2Ii1{#@y^|wO;qZ;V{*?3TzEh z;a4xWww`WC!_v~{YN?~B$W1|2R|5UIWM^2FQcE%EV(jed7DL@YCGfeLdbif7RbBH2qd?}lTxyOAXkNYREZ=4&Fy zrAauVt!t*WJV2l=_)^a%n4&VW&}bQ`A=%Tpae$XC}_q za_&yi-@68uEM`)J8AVTm%;a7s#b#|CG>Vbqjl5Xxg}JyA&OjuH)U0YDTH=*X8&(M>TU#PKAE0YWHbCCOvj55hPF!QyGAy+e)6N5xX}I_^4SaaE)C}Pl=?Owi&9O5)TZFcy6b~ zn{`O-GDuK$9YBOo&p-%bqg_q`qOl-#O=4O@9h0@z6ma|_CrHn!#ziwso{A61Zj;y_ zKDI9U>TU1W{oA&4KM!`@A4qjZFLZWp-Jh^~W4L}lXSVM~Y|iiRj>6p=V;_ZDe#6A} zduH=k7^24gv~h)6*b)_I-LZF$4Zy`1xtqdNT9CH>AxOx;)a3#feN`mYOYs47@+9q^$){;=JT|$82mnG>SSG z{#jj@+&zcBHa_9lE8TsI^4|}e+i#cMcrE>u!uBo~ZS^-?Q0@ASqt#mP-%aCDwy zWZ-kVD`xI-*tslD^M2OA&5@RmIaN555bUvvI_j!e%~PwHuHJSjG8w@EyoLbMI8Xp7 zlbTTE8uW~mfto2{WuagI6{rkGs)J7MG#<3*_G9p$A$k?I4^n)Vk7!qKuJgw2?!m@w zJ+3xpBLnfazhq%Ij^N$BVZHZ$&ZeuN?(XWy&zPixGnB?lNwx6uQ$U#5-6#9H%M#8= zGV7fvS+h)lz7%Ug+N@dpN24%cx)zvuBLyOIniSVf4NDS58R|})VO4R&>TW$7jkcya z6{-xPTDsVnRYX}Kg^PK_NFxf(BTAl@Bi5t*eWo=aDj=X0JzG&wz?}IH^7N+c>WoY6 z9)P8fBG6aYe=)y^@ljJz&JADjdG`k6qoK-HLh5FLF?A0VrldsC2^Ax7bcRja1LN4~ zBm!gx_cuxOH&+J3O$px_ZAwDC!cwx`?{LUog_5rQ7oXN zTTG5N>B(}kn~Q;~h*T0zq*A85Pz3<$CcQg!s~qtwsA^l=_VCtBQInsTB$7@zb!s01 zN6r`c2l9hseA(MQdD$C}erNY~{Oezmm~H<67Vzy|*-5c+b@1*?CO>ISwsyTAU+gWN zkHFNX2kvWeEB0ADkB=KPRT51m?x2d++9J0UAf%05MCm6w%U}b*jL}cRtwYrzmP?C< z0^jwIU;{`+)lDEM1l4^(H8iVWhOd2zjs9fao4qM_m-76`Y~IA^jm`4Qb$3Qn6Or8U z^!DfZXVsETuw+4>-nodVw*_yS_nh3_@6`ES zskgS~$nH+fUye2XQ_#4qPT{NDd-3`wvv-E%?A_V9^Hf_~Y}973-C;wxDVr-jRVFf| zVR-i4aU%^^4R2M32H{S0J4CajB`)LahdT83mwW6#}a+ej>!FAxId& zz!d<3OH|XRFXhXD{$h}IKh9l?^Q*18!@DZ`KMB35`bXq9_pXm|RaH%0wK7=BZI9F2 z8ixdw8*i+(MJI~BnQG*~Wmhp%G!o5M;D}OENF%kjS$?DpsVvnj6cAcM#)`NGiWG{P zl_IKimn$X3UdV?HfVx5o@LeLTMxqNfOA&%~9blO64gUcA#e4g^M(h4sn3@le{{Rm+ zkI25F#&3$8Hcu7P`G1wT?y%|pvf7==u<$*Lyz!Ww*RVc3Vl%scA-1zmi-HWy5xYJ; zt0GJLaw|ohV-Isne-h!smSL${V#_SJt7{8b!Kf)ps5~5=U!`(96lsw^sRUr{?R}_5=~)|0JjMn z2L-FE3~HcKl_G#(P@lwW+!an;47raLBg;`WDwx2US9dD1NJ9+@vAHo2-Zm_BeJ!N> zE2nYu=}w|>MhX3$KTb0#G}1>|B#@;&GR00OjpK=AZA<1^Rdu$zn8H|J>-~NBiqvH1 zuU49i0gva_f&T#Tvngti$-jb-Rhdaoj=hOl6ctGy+*40CVZjwd!If5EwMiOq+LUSZ z+n;GR_}w?n;h9YhwXg*6BC~M$0#6*)zP&BFbv(Vbig$f=*Yb+kAI#KNm>>@^on!tk z_Lp+?4gd&1_rKZs2fVspvpXBAbD!NlyuxMoCtK&Mw)Rq|9becK^|ZLmjeQFF4melh z)_nnk86gB;PXZYgUJVj(*0}W`H~0l<>Cqf=NgT@XwImAJ#}Ci;etiiUADBNg>+)Gm zqmcP^@@6V6{HulDM=RLdjv8IZNxhZ`^3dezqN{hQ$7G?Xyp8E;A|#btk?keDtTHc# z*2))E0Lc^$ivIwVbgoO=zyTL*NgjY?;~4VtKeMl?t^;aCS4q*>S?iLTrnBQ`P*UY( zro~NFJau%N9}|zNnmQ`F>Sdy#f{A0EX(XH&;YM9eAs)mL%uM^SR3Gk3e5p_laD4D6 zJjYQ-G}y;=yzKGGF-3biVKucxt})!BNCvFLiUl;OBdrdYF>r6*Hv2zb4XEjl_g4D011T@~4>N z!=RSu0Ta;tnNv;BEsB=He(sut>Q*LBp7P( z?q*;>;iT03>P>o`ws~TEYDGX5jsT@9YER~Bde_tWqdv>|XY()lXMBF?I_;^G`E%2M zH*=lSyPFG*mZNy|FU20a>&)KS`9YuUx>|Y8OJQwJ>EE+$3Vp3nm7=7JcdaZn6cbca zsCF{Bl^YW4WQyI(>L9AdO89A}weHkUZ93ET%e>%bR=$G_Z%Hp zu>1r$d@qZAARWwFwfj(h%nE+qlx+qX_jxW7Jt}5>BZUWse20-4AD31LET9pkff|S4 z^U1Zx_DB2Qu`X&oIvL~+J!M8~=~Ws}EPkM0@Gs4e``^DGQ`Lv1I?1XgAlUwvR$GwZ z4sH(u*Z%-`_pJ5o9vyRd)l{)$)^5R7jg@VC@;<-e{eAczw?m%4|J2+`l&TE^Fyd_uf`$@6tUb`|OLL7ithAak^)Jpv?{vO+4LCMcr#%enG^Zx+C znO;}<)7FAoc`2Ly3fCPCq~6=kpkC-%NdN}_09cFj>>C=NtluaoexY&y05;eBKjG<) zY6HUM?AJ}J{{T5jr`i6mE~-yx0>2yREgY`W*Y< zC0Qw0_=2RI`g(LKh*XMGp!+d>L=UKI{Wv1r5%jkn#1?c^034Cg#h9T*JP%BiKpfr~ zSh9na#s+0wY@w@Q)XJjztfZTMeVSVltQuqfFQZFd>CjX0uiNnsuT=m&bxM)Gxc>mV z*j0`~x&uZk=mN1HRTkuf$oGbayP2;Pj2oHj{{S27>TV(z+6|1Hh1xdk`p{c{s-Krt zsq@OiA=Qy1JI1NmMOlCcQ*L@ad=5Ax>+~Yt=kI346Pg;i)oK3#R$H!M{r>soQTx-bIz(I$E6M5}6SNqE(&-3M@{L3tan> zcLF}H?PZ^~H2fhqSEK~bhvS0m2MO@U?P zz4)-_=stjD0i;n-)KGu1(FCED}LPxyb;`E)S+Q^|=Z-#8bpk=WB=^R#%jT`()f zG??s#ddLCMAzF%f*={bNAIH4m`<`zkPwo#bJ>v~f+g?QpBSA5{Tg@Q;m=eMW^IZNM zNnYGs{{YEe(7r%P6@4jHb_dp_0UlzWody2@AhD9;dt-6R(yWP_rp4x|ipL~gD5s!` zm8pq)q|Hw~6RSEBgz>=y2-ojNvA)&r{^x$vnIPS4Z7z`LC>KmZ+2aJ^^gIj;4^RlG zJqCHw2Dj#2z`jhH9DR(Sesmy;j8q;5paZCYn9G((!z#%y*GO^3rMNn{{{VRRk7opF zH9Z9>gG15f_?7oK&8OJ2$3;aXd$%*UF&}$hhsRdcKsKw?Wn!q?S$BlyFqMLklDi>vq%WXdqz&2 zmH19U=mX5trRM#;%@Y2fj8tZ|@W76sj8U}eA0wRfeX_9EZ;qd>j~yK!-tLaLq?(qV zDx|8U`_qYrq|--OptHZ0mEi;R`G$fn2=~!@q`3DV*~t@ZXnwPNtIMH-(5LELCZeOa{bQr1h(SGlojVzL*gQ?-ptiXY78sFl@-YAAYgNA$ylUxP&!!J!~Is9DFva)a3Zzy`+Bu}>5j9gx-u<^ zBq$AbDx_J+2h(Bx@$W&8!lxDC=hnQ%dOu$kvT{$ca@eWs+Of9Q=~?2Uk}U@vN1C9D zsyL#41xypyQcmq+bhBTJ^U(hQx%Tibc>|iZR=a1o+c%LS#>WW_+$zAvD}`xbn79<9 z5Pu$Kk8UnJO_t{0#w=jCG#|o_0{{=5SULF``sAZ;>~=#3*n8_1mGYVB_YP`fJsfqE zFE%$S&yXZWSWIYUrL9$UV$sTm{Hgbe9{FdDcllH?)DCk(7!m3+2^r}VOzxlsP8vX}6-C1p3OP3# ze;``K`-+Hc@Wy}D^XR2=0H!*zpN#ksiR$IZO-nr)&gXLbf}(1=h*klQ$M~_3)TO(dj}0MfKdk3mEv*XDRrq8GVxFlF~ndcKdwDYH9|E0U)IK=H(x zT$Izstval6%N#;st%8Ll5;*tH?seYn`G=i3&zSAu5n5kv*Ha?u462gcIaV$O2q1^l zF+)+*F+9TR@_U6{B59q#OtK{Kilh$o)U?#J@Id}nVkM49mA-?Yc^k~1bp7|0xm%n0lKY;lZs*%}^K}ds zcJsf~l+x0xNiK~Fu@;eJMUXH;NDD$mcl?jK?VEn#xLw`ARs{?eGViPwqZ*Y^p#jxg zf&t;tdUq=~-9@4oX`RtwCK8&Qm1tE?sG$LhfDZ$Yr@T^D4vNDdj)8=gKM2XM`#pPH zF-q>p!VsrgsT%aC)WH}j8qfAm;QOS{;X@>ZR46C*b*CjmRA2&s)$7%zVQFI79Wz5s zSk&HZH(yH}uP#1CfKNU?TFCzM9aypvR%&b30YK9}YcM;U)V{NCDO0%tD+r>*MrlOPpqj{EKv|&wL zMLGz+4YJgHvG~DDQ!9xNYi(*j9C7&MsiTg)Y8IBdXoEFfBj_n4T2!=PsC#kmk#eiY zw8*j#)E52JrVTSdJc05b;OY*G1~7gQzo`B z8~U*XarO2bc38Wa>E&PezNDyQp5zs`fU^NyR}1Sw{{R)!W?S|sYsxb`iA6CAw9O>2 z&QP#V16WG-{C<)?p6Ng8MJI;iK|}U+>v-jc`rRjltBF7=O$h-0(fRdZxEzI4e>35Z zmm08B(PzGF(_<%En5y8WX!E^FDk7z;cY4_xC_(Z~E6V=>xB^^jUvpR9Lg}LWtX$l} z0!jUHu~ii$s0nZee`v47GgD5!IsX3ug`wx|&T{pf-P^ck0S#FfTTlU@*Wv&GD?llZ zg|6qJYHgXA#xm-SsHS=vY;iSB6+|@h&lL^n{Ru|UI|4y5sAjk^k{1B^N_Cca<5X`5 zRe?0Yrd0jBeMb@3Id>!~*7l@;8HSLV2t`Q9#VKAMXN5Y${Ix|LJ|Dfsc1EI#nx{3^ zl@#>UU%!y3t)ZjdhDb5A&g%tRQl!Y!t69V>G?%@-%UdagZWG=3{vFg-@fA=%Rf9<& zV-PrZj)AnCka5KHua{+q>bE%Vq-24T76EDEF;1nXO3%@i~?W0mxufBmTZ#R z*-zDOE#t!#B5|tFp7#FGMN#3SQK8gTtF1sZ_ku+6y}Odi${k`WlnnrNNrMX_s2#{z zA_E_V;nr3{b*%zf>FBFr271ShagNi;B@iENh^RFKO)!#DW}H?|r5{*mY28uh(!mk2 zib=y?RyfH(;Eh!ABvZzwgf5;Uym+4>)NyfQ*H+EqP7+9)P*feUvYrFX>oo?oR5UM; z0db?LNXGifTT2>AJdZTGq)=NxJBAx;N8D20 zR#}C#f;Q8Lk;;c7@d+HVqOy=`Pp+P+1Fqn8?p3}@xY>$iM48a zveeV2EW|YQX-u`n43bi_QAbZSEE+QET3Xs<61_a}yqeVyqaaz%) zyJkl0%Ajr`utuOLNb&@Xw@Gdm3uA6)U~VKrV^kpO0RI4@sIHn5S|2dPJt$TPa{5ZiQhN<%DGURpw$+&BCK0UEDIg3R$=$d(1x+|zw2UVf*T2jz3 zr3|f6C3SY;SgSDU<2O}4V*|G-^ioyi_LjrMY>ZRWQqf`Q>h|Ul4K6Pok%Jl`r^<|W zAr^+7u2|NxNFk0omtv_Y2VQUcr#s1Eb<8&+>vXf*AhM0hs>)!s)F5dJ)5mmIF?jL@ zoskhIchZt{WYf0cW45ZI%Xw+HtP0c#t}w=nEe#(^ewdJ`k-#1^GaY?Yf6jPc{TlR*GIg8HDDIGD(0dTN8J z>==M}y_=EFq3SK8NV^&%J;)#s z(NO%dG5*I}7k?r7W^6ynR!Jq2DEAj%#Za|6gi;sBW?Za5h6Pbr1|O>C{DbUyv8sqK ziYTdg{{Z8xD0(_b(Kor8FYP{sGfZjmn~3wF9D1{_n19SS;~v%OZo>FO@<+V)wqs*K zkJ=fo(%YRuusb`m_kTp}Y<}RO&f&J-XKx<0+L`J-kFxhHxMa2`H7vP=$1a#sIwJxB zw#h#-%?b^++DnbP2>=omO$t|1_+g!p$`OI6Q74A#s$FOhOPdAvIzzR6ExW{RnHRy5 zP`Z&r14U+F9y$#xtyrLKA&MB4M<0fGFOC~S<4()Ud=CEMWPUtuQM_$HyK{yOVUKbGAKnT z0`LPoMr)FBno@x&W8H1{OPTLpXWe9&nO;{V-G-vNiNYuiSdkTDRcfM*M4c(WnPAD| zdqd-(+Pi-nx+|BjH>F)BGPfW6N)?KmH;JmJ$cjkkrK+XKV=5_8%z{yC={l8&_HoI2 z#G8`9xEA)=^r4oS;lunL2>rSq4=?VT2B`j_2&gruhro}Yr>|9&-}}3L=KAAcHddV>x8@;oVO^d0= z21b?^Pqtdz98}UW%FeGGvqhvZE$uA-0NUAh)R8V}!wLQx{&eZeJKrQV$#Buzy_ssZsS!J(xAgg(xt6etkWB zO6i}GUAfuxTSMc=#eK=#9hHWb42jruc%zrk?7TKcp%Hg_X7O2#zmV9txn*!8tCpxh zYAvEUY**is8D|fojH~ef(jSo(ZOTCFj;J<|tQ#&-M<%-8+jdx-pbJ3Eh2nw=)yq zB$pp2YxOT|X1B&K?l#Q^9kX_sDS0EE30TL z>FO#!V;6`tPe#f$NR;rREy(11SVo;p8-lMK0fAFf{u=e@$SMnrRM+z-)7RzE^w~RJ zUz}YwI$z=6Oh3w+?)2F|GIk!$8J)$~dvk95baUDZ^zCImE_bvxp4HtOI)ilK>SASzJicoVwOLh4xM{I8GQ0++p)?m;ZOzPSV z0FXURy*BQ`_=`7iRqh{}o!RgoHSuzyyJyF>wkK~-@kh8jLm~1jWcF`lmQ+4#BEyJL9n?~vQF59QagI|ppN zM&munu_>|rHP<`!Xm(Bu1-0`1ag?fh>I|;lf}*Nn6(q6Drh4-^c#_Ck+-={yAd_`5 zx~T<6d2lsQlI1{JXet0LrvY zcz!JHn!SOszCvvdfyQnP{{Y)GejVRG$33fAvAf56V0L95$)L$$@cZW^xsAC+xAyXF z=;^Sq45ZHD8n{&v`^i{Z-mzkBmZhsg^0LOKN(02X!xrF*#AFVfjnYYyMv8>DZE6t# zVMcN|Ee&W7a}mcNioX&60GA)g%Fmqr5B$Y8jdxXlEFX!PexK-F&$fOcb)RYDvAe^0 zZT|r7huv;HmA^W(Ike&GiMCf}RqsriWuGZCZagF8l6qL9%+ZNib9fM3%J)}j_fH`q z4;5V@Ryi1ou&R@)Jdy}fss~I1c3_4ZXr=l=P~1o_sJSD{;VVHRyN{#3 zWou1-&wC1hr?b$=}R)ShQr3Gy? zRJlZ~rKmZ8lXziPAcw+%lt=`MnE;be($NqStA(w29vphSvn-CCr^6t3dX-ud!`8I` zR~}qCICvQqBmyrv*IDC-%?e71`z*4vN300K7rOldw?9MehwT6!2EXe3`fQRYv;>1w z_IV%k_0NA};HlXk8Ng}C}a-|Zf1F6 zUq}qMdf7?2vtxx;a!5XrIr$IU=R?B1dB^DADW;PNr`labYx1r|ICM%fzssNFmj3|k z{{WG_!`z)2mCg3%U*n&*?Tox>MP4A= zRk>JbA*iUsxrILN66%j3AeSIJJe6iyk`o|c2r-f=P)g+RsL1o_sNPt=vw0GNf`km7 zHK*+!hd!M*b>H&C_*>M}QDgd}VRi>sMG8@e!tCDn-_+RbNUC+Il0~39j=GkHT+Grm zlDtvGt{a660S-O$$j+z0(AXowpd*b3$R8@2blhmr#;B4_RmdfQKWQXZr-9E5bTZce z04uM9yZgAde_`*AmCWw_!?UKM$Kdyd=k5N)%2ZQhWE0Q0sH!q_d!h}|Us;fgAj*{~ zAZl8Z6siGJcH_A4%!?R`j3{)*LDB^Vf6r6Kho@ax{4H%EWUVU0O4R0n0mgt(W98DU ze=R+yvi5HI>MXZT?>^t5lAAq->dgGVBs)V9OINe=a@XQ$@tdE=yK%VuR&JAMWK1~- zQi?brtXXBJc~+xTY|A=KRom&c;4o;5Ed?vvQaq{%H5Jobb+i($qM~x-u_QW!Q%X>g zfWCOCAXC?%^W)d@oWyh$EfrTx{CUiEO(hO3=%u6BA1V8529hE}Q%?nL3eCP+mZvNt zc_T?46dEO9%2c2VXSx!ST3d2Yq$CO+IQ-~qQ|af@c%q&KSmToAGsnaP*eHn*?7V& zW-Imz=g`y8bmp`*IRLU&?P|Pvs-b#X*u`B1WRd>kOA47%L@y+B5KAj*&~1J_sEfu; zL`UadBaixzOvv%FiqBK_9v|xR>*u@w01H9I)lz(@_(7PKf$6BLzC3m&9-Zf!kk2({ z7k^{st0JDBS>}QW;K@SD(zmR+00OP;6{N%W-t8Get>D1{5YteB8<=Ja{T>s=*CKEI68+WYwZMs-tLQsu9}7y`8&K+Ez&Q%C5RaXfhjCe5xov zZ$!$W0Hkq+9TU%*RoKZhErPcJNa9vvwb_T_^% z>Y*wzrRoKI&WcnF(}&NmpoSH@C+&J>nwol8}Eu0W!U=>vKXfy6+;#x`d4$MV((02+7V}Qq}+tg{y&ANW}+Z$}R zM~+Kinp?s;hluT<>ng=fH5%fe(Bgwe59SrOI|CK`-~M{7MKe`3M4J5JeOy?4cG}8C*23q|BDc zuPa24DOFt>=14%d)gr9ED-BAi@sLS6obXgMpd?V5a1QP*q*i?JkGt$)eAnDO|q{+{<=F1_>e z>!^!f%tI}RLe>`l000TQFuxx4*MU3_4!{4^+)G*oR#F+6*s%lv9fiL~)CTGwhsb2VN#r## z01x>6Y6@w$)W6t-WU>I$G zPDJ6opV-yM4WDfWzO=UEPxT(FE9YB(xn8mSX{YRKa(<1v zY3=^s-1+R_q+HMQdtdspdgdSB<*9M(+LM)wdj9~l%YLr!;tZkwJM?PO%PX2rq1h36 zTgqA~CC66POC3L+IG6}(CV$cyNj{RxVq~q*Ai22GyiHHq0RI42&#rdZk>J7|YP1#m zKF+nd?y8Yh*&D*ENQ~6xDrGRNMLcZeGwBSfNoh$e!~*2%JfCA2mrOBdH0V7cI+~d^ zKjAs~^vBj)&Zn<8t|N3u=XyvQS{&sqE}t!C2PB_um4Y31Lpnml`;&dG z=gEDx=beL_#1c(q1cp19kbv`AN~SsET|_Rjj9NWJ4-r(72S%F)>-(2?w7+C60-8t# zDp9c1ubB9U41g*JN0+g>=L6i^R}+@N<|%&a8fUB7yODg2im#)okqu5GFBEaTToK76 ze1gAmMN*_Pb0VIRdx!1cC;Rotdo}LWzbirCHq*Jrg`+~{R^s03DtL;mqfGD}Gum7r zaI6H8%`b1;1-CWr*7vqoC@#Vi1hqOHNvT;dSPxF!QN2M>O8{G8_`TWBJ{Z?j?M!_Z zPM%7Ns`zv8Wu?L_H8WGa9dxZ#Lgv>1!-51If4-g*skSNl~}YS;69>D zAtcZ+Y@o)fmH2{&=h?p*@>Th2+~-|XQAW86!!2Ib%FOuVM_o`%wUT18vnSa}MDjV8 z?d9>bDoUYc(x6Z7@7-N_pMBkVr;v9`eZP0Rm&CZ+?t`QTS2db@Y1A==WNOIP@}`Am zZwgHXVn+AxZ>}EVOTCDui5jK`Aqtbk#>R`LxzfdSj45uLI`iWmdQ8N1U5)%M95z0o zC0rISAekDx^ua`tLoH=0ntCi!%WpU=W|K~ZRaWu>FKvG5S37q57US-H^_||`Zo#6l zvuBlVWTjW?B`AR)My9xw86_h~D1^UF>^|OJeQL?f3mCLRUkMyLNNG?BTB^rdYR

1}ZNrqQhF$2ia%hJUgs1V(NrZV}bP;6oRSKq}p4Wn&Fswgt zs66}C`>SWR?6>~c?N|EwqWVN_$HU=iY^Pt+yDI>*+&DulAbykyqCgC#RcE+c`Ydm- z+s+#4*c*y)MOqbzkbX9579WLFD`kiTNu7qEhf0lFY<)^CZ9IKNxc;8`@LYkZMrnce zbrO<5IpNXL*q<48*7Dl>PjJ=l-NTBLbYduSHB@-~b}DLGIVv2*By`53T+bQ=3=6iR zN%{+0KRvnos(WkA+@bCFFz&nV{T|`F*}*i+47SS>G_J}-D)#Qc1p=Dcj-qRdQdZgh zzuPx0yKKFh{^1&Um5mj2f^ujHtq0qmmqh-uAK}>?ofJ|$qK>;Ek4abn@<&NoEjmjg zq0$}J5X1|MpLjRSJ9IlgFmndcZ!5G`ch?XrH8nEBE5@wU?bJeo)Wu1qI*OzLC6*v? ztViSt75-ffT_xF=t%15J8#IqehRunwJD)8WYM809@(AX{PZJD?iS|G{Kp@OBylq=kzAqz8O^lFvN|PRNKA-|&Qx?N zvCWgjSkk3su&Ci1sMSC5DndcdqQl^)|wbV{P<@ADYbJqQPKs)U~nH zRPFtvBvHXtn6CleVKqS&<{`7-!Vd`gs{`FjX#%AnH2?8WBi?2H%In1FS9mu zJ9jvk+O5rl#6`CAJAR}jQSM!}4HS6F9F!DlAzG-aG2`v)BZM=;$*rs;2j5M;?q2Eb z{Qb$+T&23)+qXPzHlo$-q^J9^uv8GmG*P)C;*kFUir&DQm;@4)(JN@2IZt}C-uAI! zc!>8=Md8U2r|QM0POvdmD^-v#RfSChuRzA<_^-O9-SE?O%=o;H4!UJZ3QXo%arrzP zo-oZzSy597r^wPI<&qgAW|YPTwb#o;KH`1S?#A6_z;kq?+{jj1S%YzuYaZByFYRlW%IWhkY_f=b?!JFdP+@q=DW6$x-#M z#%%QteJlG8e0;|lk(g5LJOrP_#cgE-fY8=f=Ac!knuyfIBoy$6Y19RglomoD_P_3@ z7SXzGoWt%m;|2ZH69sHMd9?h_|Rk$Rav{{VSb(bUN!P(1{~s*h`< z)1uNel`=Zi)G|#nphSr2VCo5e^d9WmOKoxOhQqi=bA53#%eu`I>r_-=@mU8-qqL7n zuC%iRRgNa3G=L-Lt^O&Ic1t-``@>G^Ng9{oh*Jm2+=4(MR}2_*(eQ$;sJ>}@VV)^T zNxO4vQOu7r!z6H4Rx~nrrXaqwX9nqFz!82=yb;{-X?dcWf*KDjid6L;M!Kbqe2W3r z`c&~8m&%WbSoURCljL^FCZZ&^mxFoWs|0egFqo{qB3J+hwE$dPdyckIORG>A1=NFw zo~oLkTw|eC!3zb&Ms!F$4r6X7(Dhm$G)aGx{{Sf_(>!Khl>Y!Cijy0pGKhOma-@>e z%EY9hC2cLI=-*u@k9cLy=ws&|Zeda+-Y)6sMVO3y#VBdl(`T_Rt?ZAoQK?d6Ms~Bi36dwW{bk`>-=PUBxaYt1nGA-aK1=Num+PW|H$)vQ}FQ*-g47tam&5$jc~Y zR+j%{dKYXYbC0@6GtT0_M3&)fNtTt zxwidCv20 znyh|8qK-zAStFgp>54f#(-hW(=p)_!^K8TJow>U%h{rlu0YFYboam_FboXZzHS_D{ zlkfgo=bfdvo-)rgw#>%A0c2JT!xhw_@Bl1V91lY0dZk@1)6T&|98LFh6)}~bQ6!LG zOEqLpGz4K8F0B~_ZglV+P6P6c)M!|pEQ^8U)vx8l{Z;FnTby!5CAms1rm&ID1~#JV*qolh*9a(FdIX&et6b*-bjb(O`FNhpa=VF8r`HY>zbkw?O*rlXP7 z*?gQe4O`UI54h?pX{s<8D&vf#+wfr$s+dsiDvCUuG^o`XB*Z64#c3thtESw;QOo;hQV2+Oz9_yr^W)m@7@xK|3SOhq*c5G41cO!vHxYP*xm z9G0`Uh9OwSfVRbD!7^)?CQ!Iv&CEHXpwfNLs;h}8BY?$GNRh@C zoibIGwn-XYYZQnT*UrdBFtk^xc+$rpdPZsh$ZccSg0B(lk34l0%Pew3bh6Gqu+_t{ zW}>JdqJTn)9jF^H8mAJE_fgADQaGM5`@TdT3A}R%Bx$>rVPujmP?Ze8px}&YMxf6QCp8$Yc=R2*)kSFvi9*rU zK?=E|jbDhcH3uexOM%)>yxoNYyt4)>vo5x!gy{{Mrz#js(l6EGxZv26`h7s(Bzbm5 zRE?B&5GsF!*MJ{BmF=wDK^iy{{2rA1dM`9I-+R2aojX9&Aj;IcNoGC;ixZHXf}nCB zDXX3hug5;+-KB(fo5YL6TND2P8c+>-kv6?3mq$?x;a47Jqd({CWd8u%c)*xjRcQny#bTRUM_8 z?JmT|SJr=do`)q>Ls3mhRXu%NsO=_DLE_k2*nZ@8{oEp70sJ)-jCU`DLmC5CEJJ>& zcVb&vW0U)JuGu}LR_DPe6cVvWUO5$o7DB`i6g>k5C5Y0sYJxh}SN;>_j_*CE@`w4h z>`nWF+xt_huw9iEeq#Z#w+1hAbhgj=2R`rK>oo^l<#xtnaqY~lWc^tIO7@|ws*}M> zO0`TRSdd42%Aeu};^P-UN~aXajmvQMmg1F65O~OUF1LPi_d~!(A!rE9cR7x8TXJ?sRdRl{Glvyn3zv(ZnP> z6Kz&QxgyI7TC0KhI_+!N;qyt}< z1O8q;4>pJoiMY&X)TO|teJfG&&qe+fDkZyzK21Dd(!w`3YyQXQ(V*BBIbFLR8ylF(P~|XUN_u*X zu2KZV&y4V66~hm={{SS&$E{|h>0lO1wN+n9ifQ`0A!y&?kDZ0Dr@uV@x2yCdYYadSjhaV#+1cQ*spQkGyAxA8kfE4v-q-6c zVU46%!PHAN07Ox#*!j^^7ScPKlu%fJcP{Bp`QKgVhxpgpdtYw#+H}u+bS59P^9@D5 zWZfIfX6}sU2M4$*@YuYb-^WyJZRfS9j&X7G@D^IgNm8EOt z*UR8<4dd~nX?B;!6WDX_j6Pp&WVQ|qa8qsRcEtwUhb2{2LB1+5OUIgZcVkG>b{}H z?0v^gH7kXyz%-j;jyi|inVe+P<1(1I;xw5&bwkn56p?y;q!y8-!Im(_Qb{@DPa4vM z`F_t+*Mg$z3TUB1ftpho1BVe`Tn|2~&whNX+}#KA=fA!Y?ONRa$F1Mr%wYVp$NZJ* z&D%xS-Hp|Ir{tH#UE#F;Lv2l=L$X?%X3H*nZFe0`CumL~qpjEtPdi4{l{H=}H$I*# z%UGb(SYi{Q#Y-trr7J;AW-+YLg0xy`t!)gZ8B$Qk##s^mRaPVt4Qf|cuN+PMG*&EBRdM|49k7aDQ@X6P`v9h}#wS}z(@y%`O{nwhOgJ=m!=cOijfs#XWBUOnc znu1GeHB(SS8q^U(UW!liCGHIW0K+eq8O_(z`+owP_xXkV2>6@W9pTt+nJj+d>aOzc z&Hb=@BO$xC9&c@A@%bDTD&@XAD<-Upc?RjZCeUV>$Yps^^;i0J8K@+Rei1?jHB%j4eqXOK7?^TclIyAZuS0K{{YPntZyFS?mhE{`F+z{$7lCW?w53R=JMG+V~xXY9iF&^h8#Zh z!tXpx-QSn2Y=vD-UOJy8ipNw#1djj$K>fcAsZ(cO(Q6RVB=)j`^(BQLMOLKNfaH;# zT53VV=_zQWn9E-dXw)ba!A)e608!kORmnMO3e@oU@4SE0mqm5IWp`EzUiIy+?CSlU zn(U6$>^a+TZj7Zq-@^^Ni`v^dts=(LY%aUo*i339J9`-tQHs{8t8^xEi2U}JtkMUy zUg9KUPUmu~S9U$lXaGu@A_YYOKPbw=^r8UDwu%6v+mZkXv>EWT0d_PsY<_Y9eAHdkcl^0^E%=C>?;ZG+mh z@NEitE6iJBD!GvZq|q!ICrD;h%jp@dKw7>&(gv@W+IsLT?I4m`>8ntAvBrIPocaBN zomeITsp4{=BA~8gI{wx`9#ZNBW0Pd&*z9>;8a_ zo_e}ExPO?>#Uo5*s*MG8WEDHMqB!G1$ z9)MG?3Y|{NrZ=vf8er1|{6HKN>w;pt6e8SNy#QINU9F-z{7joPtOysvqrE2=4)q z#>!bzpaW2fw_R-Ops zjprUiK8U0Yww58O(48u5KBwNwr~u}N{F&A(~^R-y- z;WNuqmW6S&#+~DsX{G)i@Xh9^t$~YqnY2b1(x(3Rpk(HsZhCJ~aJ5yfcv6G>_4Mjc z+d0~pT9SR!pQVnB64g}Cj9QAQdAt4z`otsojt;C?-; zSOG<&Hf!ffQ-yj?(veD{6HMd$8ROT^`~DVH{pgS7ufv)R!?>r-Q71w67Fz*LB|LOd z;_;ac_dy1Vs$?@qK7Ls!Om%fpO0ZQ!4LzWSNaQjgvbR{bo#KBHncg@7t$RZFlvN~f zsV$6ZW;Llj8Qjif*tUp*1&mzW98!gfTh+cqfCW7O#sTYDuZ=xL+kLsQ{zhVYYpweu zwDWjvrLcDv2p$8r8w$>633o;;NREs3B>_uQRfi3|ZMFq^&^`E6!c$!z|1-F{$H9 zRQmMe-5Y@z)>}e|#yA0hqvQ{tUs9^ww}z|E^@Px7KJYhI>>M1r)=ZMs(^K`fGHN`e zvOt2J{{V5da?7$r?o*mBW1bT=IQboS=iyE>bs=tgR{7fXZ7P~m0jip(`$Au8+U$4Q1`G%(ZF z(s>PeZ*Y_8C5kB}S*`CbO9JJWT+U_J8kQjyp^_{B4Oh5VJx=x?Pj)v55+e~(kXI5>E>yWMN zeW{n+bd-5M&Hn&p->3FQ?yh=?P~&jVzH%|rB~;Z=)X-EJ?rj}~j7@uTRy(C7V*u2k zE&7aj0L+DBsKHv3M~W071<7xxxH8VFb{)abD;r!so{po764!aTP6+V4>T#{hqQ%mlPud{69XdvL}rC)tpFxfK*$OE(bhW2T#fT^A??X!I?yPxr%2Y1uOLai zYUNX7dt4v)kL$;GkQf9jfy`gF%N3d76!p*FAlr6a19*>cAp#u$~%W?HP5 zVbVggAapa;)uc4b9-EkDSq7m0098NX?hWRM%X^-zDiIdZkNQ@6-#*{kM3xKpfBmLw*dV|yf~Y;nJ#~b+|T^=*RQFICL`KSo{K^In{52M zZTNYbaQTj^@8@#{&h@x182yg?azVYdZlnq=`28N|{{Uw}@Hvp4J|(dK0IEOi^~^87 z#eTQh^lT5N-WYo3_AVpx$5(Ig{x^r?uS%941edC|Ys9`yQjoY=UFI(89x+ig$4c9T z;ZB=-k@pg&>g9jcz<SEv7>x zOcF?gI{uT&`x-%C1wqa_AdvU5r*%*GPf4uZE-scTRmN6JP|r_KH9(dx85K<)nz&

DG= z-C3QNjhA?2Ha04^6@%Y9=7x?*a~-#u+VIIO9tV8(ZCsy!xYH7pm`U=_EnOuQ8qDx0 z=HBOWwB#du^$gce4uZ=Mh(PLlZxNmsb{Z$8obIiM5-483sE$l6=;b-l1PU1#cl!_N8O&+?bP$~(?1=gv#K1Y1a z=08`g%Y@B#(^K#I{Ql|PbUT-H?V9`^ z*Q4M2mj_>#imP#BQ)p9C?R*s;YFcHf2MbLOK2?)lG9pR<9{X(4Zd)eTZzP2zF=C+V z@XG34K$_|U3<;@LLU+}3Mw!`8*O?{V*(BjY5k-5B1_Oo_)Rt&yJ} zT}F)zs-Q>in`bQZL>}N=O}uU^acBFryPa}eLtwj!^LJixW z`Dy*PX4vc&9mL#j_NpQ-!F!)uD8t{LJ3J`1Jqp!L@Ar=;qy4aY4$SNx( z+%?j>%Mo(53mniLEXBY&O@^CW+=`oPN8-9(IHdprzGKfn>aS6Ab2Zoze~DX%Kxje% zLQP2k0rJOF8>hN9DCyEIjZ+{pHAB=vopUy{8eSV3Ql<&iS+xtP`di(NoP>ZbT7!TU zp#FYcQeJ7?BLYDb1;8~retZBuCNh0%(lpakR>QKgdfG`$pKZB3lT(6Jc+8SeFpLlI z1fOdn+f0gMdxOAd?ELdzPcJTzKRNDd{{W>71vPM?txv>7DWA8?psRZ9?zQcH!`VGM z(j9R&)!fv{SB>2JgEzXed)kvHQvyr4Gu?wGI-e0u4#eAA6K%%nR|PxHl?@4$v~oB? z6Wuq7b{Mx^%W}OBwZsOHsuk#?NsO~M>O9gA5~KzD3DY<7t&E$l+qFoL=-qA$6P5|2 zu+T^u007SBnG6PLR=>M=3VL=sF}PSv&Hci z8&pB2I;bsh>Uz%E49jN<;NuE8QxU)4?`-*w#qob*>q@)(Aca^#J>tx*44aRg{R%r-hKBtyA z+<>wwBy7RM9ZeEDt0hY>h(e%`eYV^Afc*q!;rCFrLbRn<9v_LU7f>3EOkf5KW55N1 zUxgnCJ`(h2V0F*)EX{o0!F-DAey8jG&9bx{{Xo& z*~oh)yMJx$T=}}XcyYAY+$h3s6-le=Vem~yP|rV`jpKK|Ykh`v-Y0=$i6?_n0|=4U zQ=mt!2_ml2XbK2d)K!+8w+_|HJ1~cE-Ro%_##vcp1(juRg(DR#&UAo@q_Jv{rD>#B z_@DA4<_F8KkJyio-A%daJ~{lR_%ZW-ZsY9_hyMU2w;yWs78i5;N|ztIE3khVJ8OGw z{ja<`HFi}NTYEsb%!cB`WH7tO8I7YAGuBNVbaX()w~=CqOz-tE#z-yth$Ub`nM7=g z$fTVKsG$n9s|8?Zv0h%oVI&t;i3P>a>May&NE%ZijZ3L9&rKpnK(Z>F5VAU(29x9u zVeSgOuS?V0t8Mh&{K##Mp|Ugk_p!GQcW>mn&wB2?@k`iPoOC}LH!fmbv4r@n`$`(B zZLOBd%~g}i;z#ig3DgCi(e8tJ4@1b`?t0;ub}dsCo+v|qws{X_O07>|)=J&_#sdE+6cIs`s?spX{iaM%#+EkV{r2Cnn zr;14(u%7M3l+)SMZ2FZe;;D{yMGomRL85>YUkp1dfW`Fi4G>%Jb~4{{9hA0_jn?Z- zM(Gg7tj=i5R%3CXiZoz{S^}ktQQu5o=2sTjlli)Qw;1Uv=EDl@i&2TGp{$!AV43=l zVⅅBGgtwlRHP?B|JvqO_V7mC0b4JkV)~MM7Sz~FfH8V0JMl~y&o(08r@>W&S zD)ef7pcDSDw}Ii%eX0A~l}?5djndkjDTk$6zC>WtImcf`uEMLp?Y)tj?S09%X!pHt zDv;IHrf!ltx(%ze;H&cPO0f)dStX;!ZM-Bkb+uAKO(kt;gTe%k(MAMYG*T*yh^J<} znL{&z3z`B}DDnsuI#x9x7bT8KBO~HsVM*Bw%S-`+Ni+a?3RfriK{+%BU(e#C zg7ac3MoxU5FK$xDkExoN(=`MNH>&}2Fpf!408m+nX=;@&1aHuP zomM2}&C7H*DIE4lvMG92O30CzR=iA#=R%QPbRY%_%6_{3x{^p0_gk=2Mv9cI>2PYS+ zUzw-F}8vCC*5=dYhiE1#cPl=$T#R_S+Oy0~IjkQu&& zpZ5Oh#D+BBY1WN%PxV)<;D+^hh*<^D52COD6UQOH*5lnvc8c{zrf4zLs3T|eF>Ncw zkKswUWh?a4fA^1Ul62H(JyDGSHK$qz{{T9=Ii>z*zbfT6)deq8#zz`lr%~-44lVk1 zr>mZQz})9Lj$oQLHLC;mXNOTAJ;)Q7S->OwUJv-`{{Rn0ldLdLQSry6=nhd~siNv_ zgO#8#ODd){CdA2H%an~$NT7;lX$utOm%9s=9`GA_zl?L=G0bEq#N2Ms`H@N3QGYN9 z`+CF9X<09CIffOwSmjIUolhMrt&JRT98G-36XpqKt=v_obS@s32=uizq6zVs%82pl zS(2q`TtzUUl33-PYNEJ_BXpD>pgzZf-pwr5=1bwJ0Sszr51xF#Jah-Lx7;PQ@nAym zmdK@R=f}t%0-YP4qQ+#AaaoLvwOe!e<|eAP8mdH&wz95=_*HlNkEO)IDpHy`@v(ri z&XLbgG)%586o5}MZcxo^ZFcyK?+mFEc^?o+0}|8(fsPdoQ9?oJOUv?2Z!~RrTX145 zth92<$V~zY=_NrGU>Qir$5w^#0~qr33{*1xyz581Gv+yAmFHG1Byybfha1(*>}^oc-zV~0d9B?u&+=tw5k0>hv8uV?nnqyhGH+%8#k`Sr8M{3hEC_j?oO z6=7XPJ8!Bf6oPmQ*V)OxK9YZW{QW=J`;$3r17hvwU;aC*{QXEgt_RcIxAfQi4c5?9 zl!FhN$JQzEy)89uLR1hDp_B-cIhBavqa+)jq569{Bv!P+6d&GDnN_qO`@^R?>sj^gi4(T?05za3uf%kElD+qkjSIm+5B{T@FnERgM~{^xR6 zJxo+WIBI05*2)U4o|@riSfdd}g@1%FBoIC-vsRSFC^+J$s_4?PvsAlMwemHopdP&o zUoCzN{7U(YxcZNEe1+Tlr!%~MI%KBJ^v+9eb{=16Qf)2H*_=M%{wbEhQAIv4bw=4- z1tEB9<0rz68afAK?$O*w32@f&Gn`emY5-T^D(m*-5nnF6(LEL|ZKGDA1u0rmxgL}s zXAX?{z~FbsOz(cb-&HkL8+){N#`D;l#(Xt@@GO;X4|?M3@LQGenJRR4!elCOnJI-l z@hNI)7&;56_L&(GJ`h%;2Z5)N;ZS%HQBjKY;4%q}h}3X+;}!G=96fq1zYG2wbO*tV z96c@Zq8-zX>Nd{qJ?%w--rKErzJC|Ew;etnpFC4=j9wmUjAc^cDcT5LBG52@TWTlT zi;IZvr&%I_A^~ZoOA%a})tQ?kjY;`asz)0nZndDV6X%YD?~s4X^W#@+{KMKG%nv11 z*f4yd>s_%)w6?8fHucAju#;?Kw#H*Wp3dVHNI6;p|%j#fpt zmg)g-EI&@3BOi{htRMHS1bJmEPd={5%<-3CLahMurhNX=Nk5RMLeI)Cik(^W1LF>V z<1cgMH;yN*yBT)1UgN6k%=R~H?-H9=F-M=q!H&*laC?e|o}O%#3}T@qqMc@dG-LqB z-6N7X8Q)Eh+=Iekg5LwN=T^u$RFYB-x7X1Z7+-+bG7Lk*=8QS_;q)Ku&4)lh=xsNR)X4N_uoxdjA0VW%O@E{J!sho4tL!yFV-2Una6S zMeRMey)#=+C)fD8O~<>iTf(Syf>62ijr%O%9*a)T$4P^MOkS|PyvDd0nm^9#s2`7$47rM9g);Meck)pw00IZ zq&KGH>@A;?>N@SCjmy^O_cj{=iKv5dKJVL`jydskux0VYNbMUYlSOIp&zA5tu!TovH3jHy*@rGIGPYx!|KTC5}z zDH@i9SLH)WeWN3)`Tk$O%G0MmmYp7VV03?B_BUf~KFQuR8_PLa+Ocgk+?b8Qior>N zijNm2&d1`YDsZ(lP9#2fOvy0dg(mM$EK-<^QIzr^xO)8Sp(*xI{l1z+bc#i-byLcm zKX1>aFU&9HZPdRi{#ty0`J=ddLw#)y()hiA+gpEPY^*Nc*?C=syXkhW`rKRoDEEd- zH5=}HW7lN2EcDFu3``JNp$RE=eXNiaba>mu$qXKV5r7J5A%$vwCHdBZn_#_+x1rY@9r~{S^t`&u0Wm6kV9aGY}YxWu%Q;tFO>%f#Q@sL|f1NJZ~e=rU@ z2Yv&59onA*`pav4ZrHoaKiJzJWmE22oxQv_ekTco-8l&NF5<{;TKas>Gj7Q)9s@yN zm6AAKHg}Q`ts^v-KJ_PpWC>7n@PVXix;ynyT1`xjH25W*?bKKLb|RU)Lta0sg9Y9 zc9iKhK8bAu535!%l{C^oYLQMShAJvDD~`MxPYPJ#AQ#dJH2_f8%l%cM=*j#z>IeAe zuy!X}Nj*N{UYx*ejjuk-*f9XVY%d$n!}xJGBr6cox-~@j2uEq9FeOH9zG!H}f6ee-k(5FLvX)cBA5z zcJIo;xAL8PTfQheB3<3M_CDZ~A6ZvJx_0E7bt!4~V^Ru%9a}Hn7Sm+X-iTPy#o|h2 zpwLjKZ4FMK;M7zM3RI7f>Y~VD4~nqf*2uh@m6yi5>Bw7*ZrX& zic+3qhgB@h4OW#aL0XI`2lmsT^W~57zwD0Q{$aZl=Z*uowoWHvb^b4@AE9Fzi7|%eS#_9?!pW1P5Hiigfe0F~wGpkj_ z9FbMi)45cVfqv@G_TXtxRrxmnk9gPjpap%bmFPS{xZ9Ch(zK8Y)5|_zmr#elU_T-q zX9D&EPqSb739p}~dOkaSmk#($n98*+6$LCm-Hfd?ZeZH=(L*vFwUmVUd#=PVizRKJm8@fw9+11%RbLTg0 zXIo&7ZzEYfLmHagWqekqqjNCN+{I1c0d&fFP!T5Z9t6-?^`st$u@V=DpI_X+@xdE0;uw79@zm zwy4ohXh_QGsO`~068%ZmJ0r0A*J*7H_1BwUedFNX^%#66AmZ_uP-MyEF;uW&Hrryq zg;e1_=uRoA{?Xv4if18FU0UXxqs_e8%Dl@Z{{SfO^V;qgmr$c8)G_hh%xVOyA#`ye zG%`pkDoZs5dX0AOZRb8v=99Q`KKXlRd2@4Z5so{L_bH@h0yasDB#%2bkn#e>+v4fh zyML6A#_#V&a*wUI$7gizas_GMYh+sw*;{WDxTMKtpvhpd*%zA)xsK1p7$K*ETB^s$ zBgHYDr6mEAWBcj*o6B3wyGJu}Ue&u=LnADbE4`$^ER3bq^c8 zy*rs++GHMLgIsRfk7&mn@XtdXukV$~_kI*RpSN4hy}>^eQd-W36(vb{iSrsr1d%`q zAaozqe=6UY@S0H-7e?jdtBL2N2eq&aYM~5NO7yu54J^?`C{w25hiSld_~6OrozKLPFwq-Th=uaQ9}(mtCFS0BXQHqG+q>EB~+Fo!=62i?LP9J#NVSk zb5v19jLU0t8P5PK4+{KQ`Sc*R`^I}QyEWCZ=IH~#L6AvndP>!6-TEz2r_hnoroZ4< z$x4W+A9Q~%KFzI3&cYqNaYJ(01C8n#^W?7;f5+gX}%)lw&b-`dB236`L-)D^%K%%F|+JW&3Uo8 z7$0oP)Dso`B#S@ms*e8?_`@RVPeO~n~B<|{&M>M z&K+i6-T04=o-~sc6-@4+M`g~{GP2uP3X-{HRpFY}A5v}Y#pga+RWd=iMpSVswXJ{J z^lNX({?f*urL%3U2Ords8T{=|!r})jYX}w9zNe}Cq*>Cj-dJQ&Ps0UV0;Gl@~iK9gVyoBLB9@whPy z1(_M8H7Fm*enL?a$nRws`Sm)x`IBz!MLd)3{{W90%OMnN z2DO+ z08a5m^RA{OVDZimuRunB`NZ~R1oBcY%-Q=MrfD0-o0}WE1#Do8Nh?D&4I-q(kE*qR z9FNbkxo>w+0JsJ->7@C5$r(BPxDJI8b42%$yxRuHZ+iy-(cQ%0pI*`hK2^!{r%^HA z&2zmoWX9dm)z~^|5u>y?m5QP`r1Y4)m31+eU+Zui{71UQJWfHMadkf>IP)Gy`S9o| zyYsiXRuy|6Z9HWh01o5xDKGgx&V;--^8oG|*mTeGi*3anN=IQsONCORH`JwD_=cu< z*w_cvV0iYZ4WY)FH%Un#V*`&5!HRkM`SllW{`7m-^w2BI^w2NZDe$kF;OWCr8r^FA6xr;9$o>wOXg~~@lwBTkTLS; z332bY-YQ9STXHHyYk(}|YSenN{{WW1KAEyVEjC44M@_muRrWUK5E&LMZVMqUNz6ry z3TkAhrJcM*{{R7i1HZHT7cD7{?q`^mDWB{{VdMd6qj}kCgWKK84WGU`9EgOZj+Gn&)#F{G*l{DZxiBf*rpFv)w3BKoleLdf6erMv7K@}7PQB(qFgZU}i zyPrSQoy*?>r*`zO`dQof&dQ|2(ZdxCn>z=a!`AN2vqyxXtHe$GTPe2Sh1s7Yeph@j_#L}Hm$%Oy$Fy@_ z8}?^hY)QJSYxgf&d{Wq77dPGuaLc%RbGJTQ^*-aRp0DIS*xG3!p^CQ~6*6jV4`6x;!gT&!jjfG1R^4c905>dlo>{~S5$Q_h~S_Co$q4YeaqeBvz{r1 zw%6dvG=Hj%D3BKsy+V%-O2^_Rv|@~?%&Zu9{Mo7V_%5CAe~@$=uD5-B0{&>CWoFVHTIUI@fXJg&@Fm*JpLkI~$Y2!;GkS8!wA#Ag5zjLz|+c52b@x zEVi+vg`>HBZuM5BUt7o+1FK$@?#biBgsZ=5U7qRVi^KvX3Wy63YM>A^gBG$#;i!yf zs>a^iXXJNi{Cepf^YD0Wj5l3;cG!CZZuiF9*nN$&cE4_8yY{zqWiij%8@H~vX6U2e zo11QS3|aabbjWSmO5M35(N5LzQb-7Oa>*3;){(W?4(p;g$f%ODD% za4bA>6UDh(bM1m3QDC$cJUsebCXBM_VpM_0jyV0DbsUtD$4?Av!^rN$7cwg-;U7)c z#KY|{6^c{Shd`F-OGX9^fk1ZKMg{f zJY^(P7^MstLA?I}bZqw+wyno$)nk0pyiejhWXTay)Nrn-z8KU2Q>l$Ay=7Om6K(VI zzTW$G;F8{0TdK~b3Gj@qBjjpYmeo)6+PL|sx6kr$!S7D4-ua$@J>R>&Mec37H}6gC ze$%GM;&F?L*jWgucV|at_ZCYpLlXB+^ubS6kfNh?n5|YWDr#g!tUk&1&BJHew8%Ma`YuGnU$lYAMUMW@|2vGk}rvCo#JlNnK>c|1#9^Ks?d>xnNnU9L$jVxEiO-Nqe|7hf89 z+7b~%AnaClF|ct_o}Jq*_j?F!V6?i8Zdx|gswX}fA&EtBsMQ_wts9B>=3@)u=s#;zVg4hVg z$vjuKcd+g%ZhTR$v9f>-O@1O+ohJbHiW82qP5hc$cu&{8C$zh3w&}h^(Cs>`rczDq z(%-?pHrMQ|d(A?-Pi%JbOC2R|bIDtaJ{(;nmGRDMS{bEBfHaBV-T7l4q<$eR=a ze^suMNt$NStHZVmtg#JDHNV0S4eJ6?+-)EhrB)>Zl84mx@` z>u77Kp7kc4Sz$iJ+^x+v+jlT+oVIpSZfBjLX=0USw}DDCLhCS4CTaALMG&afq!JH6 zpK~@Dd4rPot;)}L(P3_%QbR__*CH40g;AMVBU%XywxU=@DWH}h3~^CMpa>&&oz=*S z&g9y`q-zj^kEQ;;=50-=q5LP$<~qg6k#wP<(@Nvd{wt@7#z$ykH6LuzR49&_*_=ki zD;0zf^K9q!5^Zm(_L)wUVivXjWBk1sg3eteVyaYA?Z!viI(nn51Ve(A8N0FFlf1K?dy&la2g$rY zSl3~#U0Iy%X?FfQaqW$*OSfa9t*+nMeBLt^S3Wmy(gd3|Q%bNek&3}A1MeI+W0fw1 zR_!YZ)P+p8uv^0*8jp^HQ&AGSn5_ZpHodR#FYWf_jzx@3x2lIc5CE#|PxL@F98bal z=~eL0=RBVex_`00ZS22}Jv-mHzUbT=udI8wE!>nF<9=d3Khk69EAqH5sLJGU7)h|Z zYb)N;)z4j*sjl-$mV%0&o*Ee%jj7rOw*Bo6*LQEWn#^djDj{<38KNNy%Pxe}8%S0f zm=-k(K);Z7O}fo)Z%w?PRdFe(467nWriDQ$)TstSq^NC6nkc5nUm`b0$NK*Oj6WQ{ zPi-xezWzM_0JA61HC>gF_~X0w%Ht@y>tpTxgS5tER${8L*rdckw;v}-O9eYZ)VqOd zlDdu*5fLIw{{S8*FMe=HH_od(a z2ML_dcH+U3#CD%R)#IouI=^A>4Z*u8=xYTm`D(dmt!mmjNSbHJ(+#=i8>im)0@5nS z4Xhp{w4*807*y_E4Iv2ShOyZgWI zxv{T=o$2v?_G|wDGoIqe?_Jy4zc%}CWPBgoc}>H*uz7B`*=^Umt9NbPvqg^C`>Sx# zV>&-#XDasdW^)udTH2bn$;lMduq)(J8i0MYqR(!O#Sky8<(g(?5-P5s46-vS=#3Y( zVil~EZ9rBvJ8Qn}Zu0$FIe}zV3a)BaZw;f2DzT|@T(gxzptijsDnI;+-=7CdD@-v zfynQA^VK`!ZtvW#8Z7-LT6(?z0EpeVSTp&|Z(eQ_SzAv``9WDMazPY9PLx#ER<_nx z)^Y8dUGi;_1pv+Bj{1<&F`S2aWJ5yCUt7MSN!CU^TwU$3^9=SjoZ0)r&TkE-CK*N7 zij7*y;taH`3v-z+5qJ5{kzUv05v1@SEYqWPB+2WnLvb2wVC7f>J#?Qxvo-lpWb{!b2J6Y%3Stp}N7Pv@VNI{FcIZ7*i* ze0?@sth2pqM^l>Ji@Z0zA7IUvijQ-p9xgmj_j?afOIP<;3M$(8DJPa_>8cVYidOJH z+(@OkE}Lmc)h+;y%SaTGNqHAf43&>pcv!$E)x0ke*Id&(yt7eMm5CybDBqiR{rh@&c3aK9J6)y;l4XHQG?Pl2!b@`_ zX;~IB$H7SBM2(ahvzZ!00oD<=7v<&(HHN3|r`$P83fFkjO=lt36^UIlJY!2nO8T4V zcqfl*b|=!B1vHsv{ewT@^XO;G6G$y~!0%Z+cMLwzNBbk!t3lGr+KJRPD*bpMAHsoV zzx!@Ih(2C@4)g2OgRenkDR$?_As5naEVjLr5BI-%$Da6*t6wg#N#Sc@UHdX!BSne;u02Sd+A65tbfgfM%?Uxj#Fiv`DvSLNnWppU8C;Wdt@u%E7u@^M51Kp`X_2Xag zQ>bg)2Vd(H`9JPGzvO%{Iy~Jsvo!p9>q@Gc>Sl_kq&6ywT75>Wf4C}!mFj5OmPl(< z$P`$J<_a7Ree=V8-=I!;y-%kCn}y|AaIe(18~Rig1JLz}8=bk1=bB_PsE$jUgN`5; zli~*;`gt542ci+awv}4EV7U7!e<5!fg`!x~%3Uy8XQaPJ>W92PB z>Y7meyuZWMedVbLX#i8Du2kQiK)L?_4L_e^TUovqu6ooC$`EO(&3yXWTmBPEOk?V= zml7}mX77HtOP&qk>iNh4xw4Nb;@lJNRpq8v+g(Que19{K^YtWhvjb&!L&8u$k?Uz3 zQN;fM9iWdhLHtIJYFg-ODD`n!OjUJ49ZtAa!t)>_NaykF>roF+EhKa=;iU17qM&5b zpW*79f0v(6{{S&AsqDVzqW)n$kz3mF<$DJKKgJ!)Q@!>^?-ZR^O%CdO-33lRWJgaP z&dGUdaZ5EFaxAh-42@2U3i)arlFkc7x9~1}P~xqZBru?%)&&XA!`p%9fq5r++HTbm zkAwvaisHI>(}hVV=hFB2oOQSJAKZQ6@gH*h70MiUMq@W7F@A01;oW^pg{#Qy8h!7F ztgn`jZgvria&AAl*vBIb-`&YuB3)uchfxxXEtGdoWtQ*5(1wYr*IBJ|pizhdfH@1E z9X2imPzVwrWiRm%r0Jl-k~?#niXTJe(evy)M*7TrP3|fllBP5E+x33?Jsn8Zc${;| z*{O!De!GTR{mpzG1afDVnI)GYdQ^q>*+HMeR9Y4qt8Ke#>aTU4~0!h&-u)8f?6U-r-3cyMkNrZ@(~?J}!K zp=8xip+eK;Kqx%=47>Afe==$>=9h)6+Sszc%9d@9jGuW|)6?|jO;mlMFIeOZ&CF?jZN*qvW-Yr*3Rfe(mrN-1v&noVn7B!DZAg`E12>>!RM z6dlZ0yNNhrcv74I^Bo)C<`qTq*?to49FM@gvirZ~)ed)HFInKD$81cbRrq?Wqd~oe zbq8hDQ0(dG=`eCM{{ZC= z74xCg#}%nQMAno8%b{2Kx^D00FV{O)zQ`N1#DZM zn*m=}T{d1;+%Hp4EpDjnQDf3dvztj_Hs0~YH0E7EklLesa3Zk)qMT{R{2exK4C>@W zr~w}is(ro1kI2x|^Xf;=&hPp2*B{J7;}=czH$i4MZ^B;D+g*QM@DXh~sT{H%T@0QU>6w zJX2Br`ydWEIO_g9NgNS{Q#+HWon50=m7oMK4Chhd!=uUa`*?Q`SNsI-zSa2YuT2sc2`O3)f=1XswK4y&nRk;$k~8}@*7@cGieBhX9yulrBGyVIg} zCujVo>-z4d?`_YF+(WTCvb$z(PP=`Tkj8GT&KDm+9?IS|c@52iha-fcr>;e;o=Id% zm1}@N9+Jx9!sYDln^nRbnxO<7u4C*Xl&+jsyf}5eUNWnYtCN9WPnkS;@#v}1{HOVk zoc?S703iM#?v9PD+20L1-Se3qr1=cpQQFwJyF#ZOf!TQ)ZLv3O=JQi^Zenqh&e!ukQplV$dH{HMot{%2_KJpSO` zQeirtqK|UHHV(ILQd7rKG=hm5w$8G-jwigfmzR-$jHs+woS`&)J}3 zb92$*_KhWL$%WGrK1eLFL_BNllVP~oJ#W>tlh}0W3@K7ZTC~Fa=~2h0Wt!cclG#p` zC%BN+%>Wbw9)F!U3iK!c05$KO-Rynl&dxY|ZWYtS|30%Vf+WN_dov$&a^E=%5uf zuc+#)J-jg=8a-1p5WT@^Kn_NdTBP|A!_UgZy9agVddK3YdUl2jA5pxw7gBXEZFYtS z0~^$&+t)qUyGu8@aa(Z7hK9PlF6XSpr6DwtPdF1^6p_NI+Q!ctq5-Voc%1MYC{AgC zO7IjXt;OM)hlz;6HT;JGTxZLoLHw+KX77)kTO%#oo6}@t`s`tQ4>z%Kdv6;a`ihRe zn;Et?rgBZm;p|*a7ji}SRojwkFroub{zO?^vofnt+uqwUF5?kPl22(yLI;;?7AB+| z)}CBJ>ry-tSLxodW6xG;QYrwz;lqzXugL!Z<{`fN>-nMW59QT|>Zt4R8{UhqGOye< znZ4ZwRu><>y4ye48Ctk-(QR3_Wn~5yrv|vFl3cts5>GojCZ$Eni|QW z$kd=zYYY?`o*GZ3N#SN_(im9Lq&XuPt1!spS^!7-VU7fvKb}3{pAo(r8cu6wj7(=RwhA_|e(9UzGm<8@6|P<}ftd zUHeCEjmHkviz_C6mu^y~b2Em9o;=jp+%;xmo}xTps97G8naWDHjY#FFLx|)0fl11O zMGDZ7T2ZnH^f~IR%B;pL09X&04NCrhEFOW*(AiYmex8pdQm;!-O}Qdwl08$rvB^hM z5ssk-iKnM~{*@>}vA-5L`S+k`)7pEcmJuX>ye-C`%1VCDp^tq4Jclc31%9#+e=z?5 z>~)tK5KvQ363-MBG|wGdJxp~p`+|z#!5awCMKhv;6h@%4`qxB?>fE8+Cnk6r(%n|_ zJxXeIEb)H>U}<1GXfV_aDC0OzCyE^|0s1qBsi>F(@V5#NDh@tWHLB7YksTE+VXm#E z!q-G-cJ^szXNzj*DAq~eYVO)-2$C#)O&s1xr$l8&bf}CyDXNMxt+M7ABr%$`gS%=B z3p6a<$S5#S8qlctyMbCdbY#=Kfi9L)6`Z7`PN%ZkMFowt>JFqrgcV>70Z9}*UMNyy z@`|#S4T(J@(Mc4PxjJbQR%#WJB#eEexZ<-C%~4J&7sT+hR6`7fZzeufc%|L87dvz@ z%OG+<@Xji$#K$E#>8(^8t$PoKbb!9@(KIny$|%(uNu^B(!hEO!I!MR_fmquBheWkC zXJ63KNFYjd-1#SZN|_9G5zAtXhCtxAv;w2|ecU;|J^da_O2*os_^-K2t^k_ajG zehHGQj-qPXRi&PzEU;s1BB@B~arrt}z@BPJRER$1R#L@*5$8AATt~gy2(MwAZvESB z;jCqYB{iQ4MQ{R0s#MB~3M)4fN$BI8Birrwjk3)U9}dbUQiPb}g_=;P>fPxz0gT=lnYRXvaX(?(Uil$F9JI4%S1~OG7idIO>SCc}W zHceKwys?|OjBzNIL!^VmvX6?KDAn`x9;c%J0Hyl9p|4G^iE9LkvT0=v-BU#ss|LXo z%>ktVY9R3x&q=!N^}A%vI+nLk#ndoX1U8TX`)F7IXumpiE9FQ`H=N11uxTNCch=DaRuznBC0x~Y z5J4-bs0G%I(dwe8tjl3G$vCcFCl(@uwExta0P(5-7DX2|!KCMjEF`T|wmvA~GT%_svt}D8!7@kO3KwDeolqnZ5ll0_d76B4TV{3Vi_d;%NEz%3syFnV2 znL$RHHdR$w(a2-jqN;?Eq#-3VoBYHjt*F@e_A)k7nwvc(By?4eDb8%1g;Gy7 zV$(WH8-H~(EfDp(PZecE3PRJ?)63?Sxe^%TTXhTsB1a6aDJ*W9L#YG~#w0R29`5Ck zEQrIPq{|p_;>4N^rj1VMnW8u1H@pm<4I6KAh22! zUadFh{{Zr%_{851db?wMM(UlPA8K}9)!8{OjUOy>6m7b`MSRcSJHu;ZJ4r8&oq#1+rJdjZ&Hs0;zXo zLBP4xBTo`$9mKN%)>U2d{=vA|q*t3 z{JxKQ@0^}5vi>M4C;?>@HKG!>NvJe9OG0|_B&h*DIO?r|oB zkK14lv-@&fFb4k4zkThOEnAx*k^Ca3_GBNQ?eggJ{cry9ys{Dbcb+e&wLw);a3%x~ zFAjZwJ_90@uUS*$Z^J$P8@AHkna!zIfaSwbHyRyRh$<53wsZ4+`Nw!H$AyzwQL5ar9WdY1NnkF%D-&A`Lx_; zThDHJ?puA;2BQfk8-*Xzf=~;orw|_LFbHk5W`R!-lgPVDF^4iaz_SC=H z{u4d85M0I%3$O%7CJEH1ML@-P5pt)bx+~>v6J|E1dV{Zb{a>Z4OGiP6tgO@!!JWoW z=)i& zV3(dbHRG}7S*Tj>#WWJ+f<^A#+8OD^qY%r$v2n%ge0)RspYfxsPeyip+jA+^nGMY! zWo(U~B}UfCV%KtRd|oCBt=CPsshYbfiWz(c3Yzo+rbSW=JNHl&^7R$ zJIyqr5h{iFfT|rN5^4wl@vk1S4L;^x?vP@t-BtTTX}MCwT0fY&%1HZ9UCDQtutJyXf~67_6Q%J($^>iy4~RxN5qC zwDY)}&Nvt;vhl%DTS+?4O%##c)N^URSZ)?6b+%n3!c+v2TBUV%xIYVant@UW5&_OJ z^Oq;{2PE&?_bGE`-zBc`WD2^}6=3lPNg;oRSeac)xa~OxgdVIDVD*Rc?daMKfwsP8 zY>$;atG#!%Hp|R+Z*%;7-55LvPyA%X_KgNFDYbA-{9_AS9^>3Qdk>UZ@~>MSP8ydE z(ZH}2Mn$-Dmc?Ve*z(MV)NZnsA!K&(0;2+?Q!L-40Nl6tcevg8O8c2k z(R)3cM%ty0M24|k$aje^G1?pQ zuy`}La_p)AMPf_6N-BUV#d9ZDw9;XnWv6eBd@ zq-50eJp47@{{YS(;I_cu+jFLVKXxwu=&sV9x^B|=Yw{Q3zWMIHq1>5lnpI*mRa=Lv zDrq*Z?%DZVwlUItxA1JfK9e;}wC$6otazblr0!zneoEfjJNqtbv9{f&C7I&7w;{MG zG9yVwGzCG8m5DWNbf-hTm!9_vQ$EvkwOu?mq{ACa6w0NURmg&6UgTQ0YXXYJ=rTzx zIZlfCo4&KTt;yD(%I3SFvUPcS+@(fGrM@oqzg*F6YMhIgsHfT${h6HI6}v|n9=2E_ z$5bmqjcD9ibd}liS1Vb~Zx-jxwl11L(9q+lx^K2$nkRlaC6*-yHkl9hxOoo2j?h zFA-oJf(#jv%vLubA0Ou4%||lwwKacQw#*#=0F6Qa0739RUcE=F%3RbP6}fWzQxX6$ zzaBoEI+qW{zmdyVkb%BDch93qSAL@GB`M>GzK|PlgCvq5^r+>n#r^p6FD$SOywA3k zr|c+V_ORE(06uOb)LU%_@xGvM^dCZfu4~<}YX1Ot zb|CqGjKRbHa($zuO|fsJF#XSXO$Yi6oP9nY<*xaVx&taun+)i&BG24$%4nr4N8p#orT}kw^vawdHOS0X;HND>9VJ)@J1Xj`XNm;tXMG##F4a8Ym4Owb0rGE~LWAr^JpSS17%|{MCA>`L|cz9+H$q%-9CmHHU^LhHH4CDCnb<6BBkLa$c@PE4W)o!r=^>I@4IhS z@58&%G1)D-yl2mR*P-3r zYmCe7-IKYi>Apcy?@qg=A9ak*?QN%-s-pfcwrPCnEjC9T1dyw;v{R#6-o#^;cBiqq zNOo&hvb$Aw3aLp{jY!M|38xkQ5O4)gMG@TdB5oE@-CxWutz4?BNIyxc6~W0`eip4k zr7Mnw?%m6Lgsr6b%dxBT{{SSbdX9$&we$Ghp00fW+QU3rb z?%dHgD|?p&_qU!DJC5RE)?5*(Bw^u_YFAk-nn^%OE0fWnsoWjAO_9!0rta=aKjWLL z6}@uw*xZ)+qnkIpu(c9ZV0Z3DBxHvpxv`Zpm#4{))p4_2OMhZ-+}k{&*tXMR-%kTY z8D)fog~c8u{utPCK}DyRQ9X|D%=Wg%MBKMH=DB5>P^MtgN}{VQo^06o%}D?PNF60J zTZgf?7E3R=H*RaOw_f1R<*Ju6xc4CWbJGh~{WWJX6Rl@&ELt6%moiG#Z=jS2?7 zg|f>%pKr0YhSI{y+TPM2ra0qR(Nj%y(N=(I)YLpiqfRHJJBI7bJCyR>?w5Dh7p z$Yo}5;X?|LXc#K$0|!W`!0HUJWkpAhl9MJ%)gyl1GPKAYRA_`BwkV{q1e3+RsGix~ z8EONOj^XF|^qSg6PYI^8l*3Rfq3QmXw5ED>p{c1@sm@BCxh6F-q_r=Op6@f0sa`jT z8z$2X*&7~ly7oN??OH5;UAo`1<;h{=U9DMHNj(NjDv)Dl0!o-}LC+g1 z{^8tjZ)~m_z(uBi4K+HW5T-!C@UlZQ45E#CSSjjR_II2bJ?hJsW|>30rLEcNrDUNk z8Pq^NEeHvM%xJ6$p}fAP{%^GZ0Lv$T_MK19kL5+#za2h*_Le-<_YY@$d7or;_ey-s zuiN>oolPfh?oGFo-jrQKklyte&|~NBl;7L|EM~xBIs27G74} zEVnJON`U%|a>RrUKTrg0`0fe~7zLn-MF&}iyT;dSwcVnc)&eI?xa zdX42RHg>ZW7DBdcMrQ>i)aM+nM-*OgZ@G(Mea<&FJG57qTWDBW;1aY^QIT80Mnu$z z#Z=Ckh?z@AP#wV$@*d@Od1gJr$>4(a7jzOjqq4AKqCp$A8K_Q{Ds(v4K}G1C;Qs)d zU%_s^mb>7GL(p%n-O+gt`ovLhT+j0?_^F2ZLGfm2VO_>2UcPj8!caMoxt)sf9E^53awu-K}r0)>{p=WCflU4=V}~u@LHG6)JT) zND2yo&ycFNJ(YQ8%1yUtpX#m4Fa}3t1hZ<9)`_UliUn@g6>_TGTld7zoju9(i>SM! zbxYk}A2$SDJ@SKl^p4@p?#+*q=q|LQ+Bpnf*vj+}vhrjKys%aNL_? zJuhEkcYb!iVQ(6J?^9ibu7(_*Q*Z6cJiBj7+6?q6uLT_)L>X#^e*>yYNiV@2(#a4i zW3)+icy&@TJm_?vT9N?ur%(pzzigMB&9__aDz^)8@I@hLCh?uaklF`qg^G{>j0Sep zfon?YgZ#oU82SGIo2SjJb}DHiq1x3rNih^=uFpvg2U7L&idkhG!IdkV{@Nx6l}fP8tW{{T5i;qs+FVd!_vHgUzc#bpWriES7esT2jWc+^&u zZr~^mdKJHv(I$0viV z+?emWr=rW^o@ns$EHWUfqfBLFWUEA0WF?(jQTB1Qq+de>u>r07%N&x_rBB#9Ko}VV ziLOW42-X;ixpXn_CFJMwC5X641j2m6xWeP5K?@MJdTYBi3&j+zEVN}GBl8yixTfm_NSU z;FTov{eAmBop0tib^q4egtC@js8@5Q=y+g0gnc4 zHySlsz>qG=M;49Ok_jCD0EfRensBM>N6en2tFck^B#Y`N=*{|B0sS`o`)P@xuL@VH z8dE2yC`r(vt##FN!7>s)fq7AX_TJOTL7*Hd{;YJ-Zy-KZ{{SaiF#iBILZkVSe7=#D zRhC|~KtTnx4y4(dN7Gk2Y;Vo|;-|UQJnG6$OD%mkQ~6+Z2>XKIa~%E07Vv+^2S=}{ zny(+yJy{iBf(l6bORVBVrlMMEoQ+JFf4-)kuCA=eD)OmEQqYQz^Dhiy!;gIP=0}p_ zdcRmyXgi(hZrTi7%C%#~m@pw*_&a>M!!BXJmJ9x5ickaw>Qx#*4I%L)E2)~gq@xuM zJ4ylO2_(m`sB*NO<|VJA%uOER%wVeV4Hhz@vX-g_s-dKR;r{?*6w4%3(88tEkidpx zWg(1$kfU<-y4wLnwsm?iBrw!->0cq|z;y2}Z7OKjc#W0FQ(l4kF`b~ zve^?K*2bc>9lBI&T6x#(rgPGLo9Zq$?Y`d6a!}t-HC&1ne-(gIa%oH&WvVewt%utYM(#GMSSQF9i&-jqespDJfU z2i$yv+Oe}}H(#~t+;IVz{cI;BTkCV~T;(<|wMtL>_w(~O`5!;asXLUIHI3Qzn10Pa z>aSZXNsq{7GT7L$b45>G95u7iiHgMplfg{IBb2!zBawJwe@*%JA=0kM7}JkKNZ78O zUkPFPeEO~5gFnnqs=t_COMPWJgKu_*4-L~@gF&!2v>mmxF&i5^o5r?-Ctn;GjCLb+ z?#GsfnmkPDQTJ^_TLj7#>DN#tt8c3+jdci*CV((-eGNb!R3od-u*KpePgYaif(H^Q zpFCHkx6D803)SBb`}d*#K6ZL2q{i3TwELHDSLHIBnwMzBO}jG9xG|MG za*CTbkf%xJN@~WA8HBzw8pz36p5R=^6|`D`6=u|P~Zjpqk_C z=o$D!^7E|zb8NgHe{`KrRhIcd8EvTaEfM7vV*BrQjws)yToM9zrKvs`%3 z9B?s(ekUbD)`6%6b(2Ce7M1hq!jYmt%;3u6x@c=dUzGsC#cSu$g85(ai>-bae0`7P zPj=?=n|G)189lYN_YQ9fwep+GD~iePmZ*mY>wv?suc)J|s--Zri|C2nH4qy9?>n?n zc#*{N9aPe~LlS*8vM<|K9ah~IPZzi>YPDj0DhHt_j}Dao02q5m74i#X;=6lb`Q_Uk zskXM}?$|Z?OnpWczbUsj4n8W(4nr%5tkYeBsIQ}$8cJEfngU93u?p3JBu6ll0V~w;lgT?}-MQ{xca0PNO38BHr=t%jY^Shw_4b*i&`4zugWI^6p zjHcDPByS{o@@lfsTe&pTT zf|de;RsAYgVPc;@Yf@xYf!$~1Rh^*uTW!6$gCo7-Xp1g<*%L;>1zzX`G zhx|XcqQUVy=MO;q=7tWz_~pK7`!`|WGxghMvw2f(&Ed7ymvPfjQRHiIEsEcJdu->{ zXlQa2^0OLm30Y998~bhhp&2uriXV+oZq{1aLJUU#MfhM==Swy&_%AB z4O<#PS&*lmMx~T2Y!{l(aV$3x!Y$-|L*fWZk4m=z{%Un)i5euB$e=Ma8iu1oLTSg2 z1w9QobT;-MbnKsw-3^fL{?6SPp1%yn;dI#^W|vq*%_%RtEnY` zJdmZDHULL ziA|)z#EurH8`$43A3d&xqMHH-h1eN*hY);;g)QP&gIFMKMpbRrz4> zH39(QDT>q(4-OhmGtiOTUn+XXpt9JFr`dg@vijP$u%a++9l5%@6L0MNuVW;&U%_6V zYi;blQiCD8q&X^qM(IZlMwz8pn$04sIdgv5(J~U<;lW|C{1(B3}LsSLTk}0c) z3IUVTpGaC2xG|9lIBIe75?kx5nY+&)T z*4`Q_di>7dtDwYEO4b>SR8^?} znsLD5Px<-*DKc9-d{gcn!?R_?OT(uT?6a`;KAu=#2^$mVK! zUKxldQTL^|`otGLCZ%zP<6lEl#2+KoS$sACwn*~mp8S)*3QdtiSE4s>?==KhsE!FE zyph!fEe!f%m4M>RZOw-^_l|#hv}X2l^db`f0KDyJ0nhp^Y5uBzE}^e|Ru%U0<>vm( zUt8Dgq=V1>U!6KGTX!4x=}S{IzB)Nwsi&u>S)`L2S|e|^o~8g6XsN1RC3KJrF+z=| zMOHkgYgpPC?ckWnCZndG8aJA-^8|4DjXY?2!WbZH$A+YM3`(kic+k<98W0Tze8{1p zq3Ktf$-z~QmZ2J%GM{Nljm=@{{E3a3;zoFXr*8kmCq^ez{- zp5ZQ7%QG9KGyv2mgiT7h0P0}EqM#8_MOjEIuJ0q3+_4Cg_-h=ot#n=hYO;qF3hKl4 z6aiCNW6?*AiFe9+GY-m_MNqW?>nS0jg06I?sg4RzlYb7WQ59S=O+gJwlAU$H&j@*` zQK==gFp@K+JEYhPF z06ua3)dv3dn@pDPBRem|x@rK9y`)p&B>~7`n=Lf$lCG(WoMUM!X`)CVR*+S~>jFno-avllcp+{h zW&vFX;HhUbzIYnqV)bH-pn+N%ijT1L#^95+`^j$^f+-^bMNY5)qZ-#y1Mrhdt~{z> zK?Owxelo7S#{jFEhCoKT6{w~Jih8Oa2ksre*uTDkW7=y1k=jn5DGY3lC$hmDby3zPGuv@tM_=y-twCf=DBUM|E+) z4PK)ytuwkLR;ckkytPIl3}C1rYONUXZrZUNC<*BCu6ixUhuizHH=TTvQc+NfP3g8O z>YqKcclu)B6j_{|Wjruc)=}i^6USFliBCOD@=Vf4t{U2TWUgeIOZ&_1&hv1;D-zYO zV3uE~vfL=9!u!V18cSIm1$kG&npqv3pBfpUn=7tmmhRtdyT0BCoIw%#h@Vu@PSFCh zJEmX6Bne)M?#08XWtA8%-cVBI(KA&v$+vTfR`k2?Y0}ZeHvS@bAci*Fn`0+AlNR{x z*z>SVG7}y+g9=Xg`DrIe-*nv~+-^?qJ%rKk(%hBYZQ)g0da587HcZ9CEajQ}AxO~F zBYh;Wx)wZQ@nXAm7Q2vb7f@2Mt0>LHQl8HW;-|K}>5%uT{zzqb^5NuVQ9E%;ugLmCF&LCnQU6fUmR)GFLj zu__Fe4mf!kZbNVg`dIE6Y1e^jY-^KDB9_`(=sTe$ei|q91Hrg(~=?`zFwJ-Mj znN^E%R8tElkVdc0s3N(z2I?+7KF5J|?K_WdD-rt!u}b~CIv2*QcI(#DMXXiF!ZnIl z?Kt~-*rWM(;v&g)F7$)^o=Bf|z$+rDfokb$A)f^Va=}?f>d@6d@f|LX3c4{;2q)Qx zDa#^QT`&b%FIcG@ehA3@hdmZ;##EbdmMVCwBy2qRDdG+f3iV-m9@P1PkKMUCt()He z02%jIdwdKg#m3{lS#(VwV($*Q*f@=;ipFDlf8(Cy!gmJ5%x(?4xw0F3AGvb7Yb%Va zn{`^S)Ks&6Cu&uj%m6qj>NuBl+&8V%Zkx2huBT-+QApA?_);{f(t@R_Q>oqC@lb1x zz9Z_$db+Bowo|wYy*({f#H;EVwh~uU?{pG8Prc*cY2uq_ON?oQoMWazD!gQBh{!#P zcFiJtkRlG{DUv_}x%@3t!hqB5>O$pavX<{~j`!g(`V*_qX(|~-BRXe%Af=QC8 zmmYHFo#Z5c5{`i?tlVmqX&As*xB8wvi6hDYP*>K!>iwNa)_NK+sM#Gcz+r|al90<3 zs?%CkJ{cGG2)eW^qzfPG?aEY8{4_Q5^yz74p^ey-CxOWP>(cKF+dYx8vH04}zr1r0 zNHPC9^!ERabBXq`-VTb1X9^ z^UHRUvHW2IIOCAXrK|I=%Z56(9-sbZ+vl(LUNdiYta~rHHYQ^o6K*cD?My5?-)_g` zrm3R)%xoDtfuF;&)7CpgD5`WrA@X>glmKfE>2++tti&*&CY21eu9jW|9vQAU4x#Py z?&)eH7hI!$10gJsT%0N33^OK|fz($^BPClb-hBfIH{?rHad~PIMF9Aa z3Lhb<;jIZ~tvo#d3JooZi?Xxk4Evwjc^Syji zPdx1nga-+g%yF z^DyE1{{X#qq`5r*09nP8`&jDgcFyp}F-(_U@Axs*F|@d9$l#VKM5>K9icK-Y`&r47 zlO$I1paj=R(nrVwDl7A@DOy*o)U*5Rd*NuTt#h`?F;FWdzO6!pWTUFJC~^Qgg-AU? z*-hPBlN;K*Z#}oM`7No8*|@#$x+<}Iu54xrGgQW=J-xW%+fr7!+!aFz(x8e6OCtd^ zk}i=O3igeIY}hO$w%es56?_Noa$n-e1JjAX80rJ}L)^Y*_hWgv=8kLdTX!}h03lNx zN|6RBMJ&Z~YCt{iOJb*^vC$p%-+Qy;-Uhx;fZKoM^$$hvSO&rQBUy>;dMO_xfTo6* z2eUW+6K`hdHh;+|_9{>lj>gnc*VWO~>MwaMcdoXGj^nlN#ycas#T%p&$s8?ohzjEua2>!DXIb(>xr5mjOCOo zbWAcoDSIC;y*od)Hy-lH8w`=BNtb;F$si&&JWOm%R>bBk-2*H$+C*`OX&f*Ije&Rz0E;Ux5)VMrNNyR=?$5EckeSNv_8^-5+Q614p zRZs$|vXoTv0Ya*+YBc=19`ZjcJI7|!QtjMt$X?alFkvA3Q@Ez>&fYR-XQ~fbCREf( zyP&VHXy&SDW0tv1LqefVmc!W69%-7++TP3hwX}F})mOx}jidw6x38UZ_MVO}IXSmG ztNqLR&$`DY-5HiUi4_GGO%;C#px`J8siu18llg_*8-|-}8T*U4Yw~#N8u&L5&-VWS zW7lKmwoA>5{_82-CbJ1lD99Bm#mm$UX=UKPoa=Oe_vZYo;POqj)Zv6}gg&U(Y1@)cu`cqxoO*4xXxMY5P}o#d!dxk zKj%Nmd`{TU?H29)`%`D@FuAF6BY5^?yO$r8!+Dk}On&8)dK{iRYh@yswQU7Hgsh%8 z-bVCTmCe62`-Pt3`##^|!4n`sZy1Q`r*p#)H$WaQx@_Llxeey*HFiRI0PQor~Nof=GxkOA4m@2A)kmlFVCD z@ObvE`KEaapWHh(rT+kzIOuEguiL|qpGcwPRfP#0$-L<~BkJEIa3>i)gz)M1o9DmG z%5x0Z-;sOMA1|3JCYqD7JC2^F86aYjy)5x>&0~&i*Gv8_?K^LYA*8zw&{NatBd5&q z^vB3_rFlJ}Qql7c>L1ixup*!BeEjJ`dUQX`2j;wnNol@Ob|oc9R7u@CGq~!0;H>6j zRWubF;i;*r7CQj2sEOL_Kx6HpyhdFK*mi;ytN!98JjF6jDU5XbaWMYQBf*NEe=jeuTBwvFdv=JBmzH|nfi8!&rRYOtX)+p zGQasHMKGF@X<%p(0Fgs!V0jkyxZZ8<^=+!xBZ%=l_|z9a=JXvE+wB{?P>6qjU6dF# zD_nVk6jHu_I&|Yr^Vj)+&jiUA%*>=xO(Ol!ZLzk^JkYrdAw>QkAX%C24;n!ADGkrM z2{wWi8)<;3$TfP`{p@k|t~d^r{TBX{wCT(jK(XOf(~l}?;1A|}&rkU8p5M$KmQN4+ zI@zdc<7mWE!LoL%%8>|)OANHt7;q{Yq}hv^RkZ*vRNLBlS7mk9HmJd=sMROsoqk`- z`Sobv=0qf(WVto`R9fecXaHBs=RsWb^DpxP{$P?WnEq+U4~`QH>+3y?=BCE$S5d0~ z;wsfFSN7CsP%LkA?Xe!!R%2sY`a95kzATTok6wE%(TLZ2NjM~;en;WS9$#%bcZ27b z^9NA_ADQ@Cs)7Ww9G6M;g&F(#UiDrvwp$n*5+;XZc%05B?u<9eT!U2`QG>#CAz{ycR{IGo*N zmr>i=q?rEzMJfO{Bir$vxCJBX0Siia(op(-J_Gsm(B=Dw42=z-jGF%dVIQb8_%H$Z zM*-Gn`L**$FN>?hWWGaner;^L5v$xmfj>E(4Tpl&)aN9bQ<9AwQcAm_FSYe8MX3)iMT5Rq&5sPUlqd^4^*~F0r zPZ<%Y38VUWWx1LQo4*mwONreJ8rG~MDmd}-C%Tm+^kpX7cJW)rV}rqnQ2~!xQA!_( zk_{>bcy!^8{$SrcI(KWn$5UiM5?}4Qt~YO-|s+vc-;ujtWeMPLiDKXEld5 zSyWY@RIdYMwa4vJ0Vh0N%))vRcE<6@(aFQxZG}86Lg;SsxqQi zX*9&KjD=K>CZw7Idzrd{nfV#G`n7&K^<@ua{4M@x-^%|0Nc|N4x-sxQ@g%N z_B4&VGCO;yJI|`O_G7a9^K4>rJ)@S&>6rVYv1)!e(`?-LS?o=<@sf&@ zcFTyN&&TJnc)FeIw|6ZUZKiSxoV?Yu_AW9F zqMKs~ut|W(K+mwX%ZezU5?D%(|$;RS*)3MQp;1TUceSMs;-g;|9jZe=|RlzubM# zxOWcRpqFM^B}b`eeU_nvF&PHb|f(Q_6sv`E|O>{Q0Qb zIXTmqmCaf3{t1C@Lql-R#vDe(T9%y3URqXU5-;k?pP5vw9nE?+m(4j=NAS2hpQCwOjz#BEXaBCc}?@>ti_UETEBPXHW>T zfGu|YP4)F$etw7Fy7$_8#KBjUI!%-7VW3T_$+j_%D4Q?3ewxBIz z`dD*s_B{J7cBm^sr^=lupac`vXw^od7^mnW#Ob}Q^!kQB(*Eh>a(z0l5(k%4V+&#m z>h%=_-uD(DDf|<2aDKk@NzboUtq46hLva4ERc;kotQdY4#ETKAf426XN{SQ1{NL)& zOfaY*pFXr${%$QjSMw+NinQqSnDSkD5fG=4sDr6?Vl%jmHk6O`J6J8bKJjbZln>5~ zXiE~LeV^v^`E>|;h6{5Y&ITfcR-e#bk4IKy>+8CQt+2RERGB=LFH`kcrp3!7{{V6^ zw3~Ged*WJgJcgY_GQEs#8mzvNro-L=PqqurYTToe=4QK=_WVY)sK$8sGpLGU};p8WOZ2^MmDHg~~dq@%u9qkE^N5lkzd5MM`Bm~#RtC@9JJ&_Qy_YL8D)I*+-{EU}5~TIMyDodo zk`wYejyf;qIqA)O$3koMP5I$#U-R`}`N~H_BYg-W_ObNak^#4-#`g9ovYlON=5f{F zlwdf)^XqB9_)c9hgX8}I$ccj7R(yk|V#{#g()HHfi^jLIvgwczM__WuBrhf>cb{{YD{>$n=uKW33bU!R}y>tj=phJvm-%BXeHCN{MyKW&{nRRBRC zlF9)M6Oi|}2iTmQCj$T)^fLnr4Gw=U9Rqt$s(Np%y8u*mhgEF8qRek<=ru>O<6?-03(2w)nhg$>FNspyX;IJ8+>dIz{6H;ecQD6EiuSoH>TXkpo+f% zoX4Y}$m4TR5|cn!2@sL(h~;Ps$sGX(ppXp@mIx#Ef<9enuAt>j2&ktFdH&jw_G6@9 zLG=$vbWKZaFOPkBwYr0@@!!QWRQ+MGDJyZ?Q*Y)oG9_MXA&kY>*5oQ^C(ln3%R2cq zGl8TkfT7uEdx?y$tK!gbP=n<~P@rbK2cKG4v;-f7qWMD}G~gil0ZzH9ZT|o+4e)EUpKaDmxrD%1(95;Q@WJJxdW57VG?7QWo7p~) z*}5l!O>3cbR<)+OYo%*~)Z>n~;Ys2vu_l6pHJ~3aED0Xm@++t!=`WH!bGN%^ zsxx&sJ;9aOJF2rkL50a>cJoax3ncYhV=;lu#Xc&cc6gd9w6h;o#~$eg!`r$_ilx*V z22jGkHDE{b>snpI1ty1x29*HUKDqq5oALhuYHVJa+qBy+tElO=_g?k(FAad$`+kaP z>Zo>>+rZMrNrKzdQ`SvaS1vyXOA12?o=Ii#pw`T8PP}D#WtBh#n&480&V$H$dUdT7 z5wD#;mqpjFJ{S9PNHRJ|#d%x+Gub>F-1VpMGH#ki9M*=)2! zWNtmanWw64wLnZ66|1HH04ElYmc8xojkk&VQ89I)@en-*cvs;k&WAX!4zy!wQBzUV zTGN29`As?NW*Dq#$u7Hg=ux%#OU z%xJH}uoYT*(3AUX^56$dtZfpW(?W4yPbwduSo`X`N3iO0^?P!gCD(9j+j-GXK6b23XHfI3pgAEx_v1WDv!h0Yk?|c> z7^Wz|VxD02Z7%Hz)<{~=dUqB+UZkFfuH@-HqWLrNqjh|7?}|LeW2t*v1B}7%d^X

v*SJJGrMui^$HxYAmhmKY% zM^(3I47} z(D%?-Dqg4C^cz^7!2w>n-uCH`^7o zy~(+-`QE{x?Tz(=-t7)w4O_V@vD57-aT`ZzJ|2kAx~j!YGK!~|_}Qe?gtD8-ttVL8 z-r6`>Xb3{&HYf?!%|;${pz@%g>uMOZvp5BtkCzi)@bKwl^N0Cq{BHT#+rJ#U-?(=- zYGC^x;)q(Fp@(AbO|OjF6W6Zz#r7J{zHoWnsh+OSLoRC*6+E%h)??MEUDV!95+&le zwpgW#Yjt;O4Mmt0P*}y_OYJ9xS0sjC1`#LsThpl%10C0SN?LL*? zz7w@Oi?4V809J2bw~Csjn{RL2K0|Kjf6ckOa;I%q zb`075!H>aWvNU-thSb9C%r#~*nvZW&ic++3JY!m$i(AfZM3Ma*0vJM`z{S8M)SXS5 zpE~tZskJ+ryERGmpa6e^pv$*^m4`_0{{ZF*kN#&1*`0?+-+Ox(wsBP5bNn}BPt-XY zO`+D6{aKExs;HL_{rRNa3AeISOtq0$kY)=BK>;J%%`KzCP{T`%(Zifpl^Q8Z8hX~b z`5m!+aq2&&fB-4zPp{0A(UauXTCqb8y6S0vsn4;Rb**IQ;FhmVP*ha`(YN^MeuH;Eo^vz+6l!l)HLJdIAa}D zG>Qp`(a4~vsNxR~Jb}|M#(#|1FN=L2v%WfQoaJWe+WkYZ@S87eZal6#7l_Sgu{0Gm z)ez)!7>pnoOlC@XDjlbalr1_FWES^%v^0()uY>}HsVqPP%$%RJinRRP!*&1r$g zri06m4uSswm>7wNSL2cjQByTe@WsTG>t$I$hOSmkZjz{I#AJ)D$XkLBKJlyXSuca^ z-SmJG-@L838XgiH9QuF7br1XOjW4$sk*KLR*3=%q+7bts0bk3aV}h!xYKSLzo=ofs zPYq2xTB4`jRF+VbRT3K-e3VfI(;*givoO{d-znssAH%w_Ra>=eC&R1{Qhpa40in+j zM+_ykX@r59HQp;IU@#^0P~J=j;?8JD=}EZ_70!76SB_Kr1+tXywNfrH93$uT5F5DJ4gxFQTlA4(1O&^=Nt$jNd~QfLUJ11qq>IW z_W8h$?Nv3Pp$x4@jzG&%nyUrjLRb}G$uCPENwFZKsomtLra#qEY{tUHPJUW0LCqbJwRD?5=8mL_1aFFQpA#`$BpCH2WzqkuS3K+Lr)l5sLdtn@4>2?V7F zLtXoGxr=kVvb4CgzrMNK#B&>zeO9k1X6zw{hj$pxu~>18^dM;IC6R6iza3%TY~JNau0X8qv;cn z6f8pAML9XI`XD(h-i!qR9%D7@*AT~lwY}x6ts_9XNY|Q%qL{-Pssc`-S~eP-dc}&F zQvtdw9(}uvrH5zb>asBB;aQt2P_)p|(@lwvC7w)nW>ChNq%9f<O;!8<01x)bRfcIwS7Z{9 zPX?TYC;3?a0CBn9tnO~CrdW3U?%QjcJ4<$T@OLXW4lg!+z?lJk#X<>o;6aw-!;ix- z?iTS$b(2s$rYN@m0NssacNLj*w~!y!N&z*r@-|J(SbJi}#h59PK$auo1RIAZPxjE% z&^}Y_ak{9nm|BSG;oMYNJP4l_q=T1q${E6s&rifTpI> z4Svo7o>dg+DCA0R4ANw{B!R?^3O_O{>GpN6rtf>pJ)FxMNa3gd0Cv|&duarV_|Okg zwY1vc3j>n7GK1mNd?KUKf7$;4FG78|S0@AteS`e{2YXK6=@W0U8jN(CkSJub!XFhZ zax^T$(YA)M76p{@c>~z`7AI-kXfRAw`S*f9pF;?>9lq@sfiZr4;DCK|`#RW<`FUmN za9th0w=Pzqf{O=^?3_g=Un85zRA8{U++mr3$FbE|&W0Lp>VdSi+32*eHJvqvj5!~;uZE~dB$#D*#Flj?kT+*Nr39UHO z9Ub41Kk%Q3dxNlhQw@Oc{=4}>vo^*Hvv51FYWHp@v@l;Nx&wXD&}Mh6d#k9nr(M*? zpX^!6HZDE8hN(%m)^>w9^%T(vVxko}Cbt$_U7K53S{N*XRV}P6y0X`pjQ%T&}iRWtml{!;HBkUtkbNp(*9 z+&i0n)buttDMihg^%3*Mm9@720BFdnv&|89)87*N^Aap$JSoKLMc}dJNT6B+8AcL&_BW2l?q5kPDJTIv3m=l0Ow`XBZmPj!mA@_fI`(yMA|Vdq|*w@g#j zCN_1aZv`$N9}3GIJia#wjAYd?O${QJ^%8IGNd)RN#ed1tv=u-J&q=H{cQdx~FlDeg zI^0G^oZc$B3W+J^3T>)4Xv+B^kPA96DC@%lIQOmu5NO_`1ayY}!pC&9n#XdpihC&q z8aWg?pR_O{qli2~$ROvdxA>F%!SNJ$$$l{WrQ5M~ugC4>O#uHt0Kg7DvuR~kidnFA zwW!m@x;n!lkUlM)yRr54FEe8mrZt2B+p83I7NH-qWgB4R!kzlJg-r27$E*o?0OoehBPHCf$D}}Bt zPb9#|>oxZsu>u?GWo3nE4r)_T0*B3%lR#;T=9TDO?Ee71Da{vY$lTd;8uOJKz>!zO zk8q7twzW!?g6(5nQ`>_^0K7Vo8Wz2YhW_v6cXb>&Xmh!#db+weY9^e;4JO{Lf@xq% zO6jFkGgVVYsIpmD71E%BeUX`Clg28v3TRKM9$)Nv^^r3J;7nWLD&Mn72de<>8qbwq zAoh2~{@ChX>+3z0@b9BK`>8N>*loSpdnc!Og~3tb`vN}B>Tl!NZNs{I2XbZb z^>U?k4IV;FjCB#o z6a?c@`G#t+;e+MW4E1By<|?YBeR0%CDt!ziP-VM-p)8s}ZY%)ji+j}MnI$qBus*(h z4efuhi20T1#r0pux_-jyD&E-1cLvbw=dA6?`ZKS#w(G-X=7+GmGy9W`-xPQnz3D|! z{3~Hm&CGOSFWps7{^#+{Y-Bk|A^L~5KAU~tHFYg%@b({AtROkUi;P51rVv#C3?53;bk_cze_jlG`1)}4`_ zpvUHM6YUPwtev)A`rg%;T)jNd?W!2YPN|Hk4zo_huet0tTVk6x+@1N21WhC!6A1N6 zs_PUo*Hp5Eks6*Ft5oSGhMR+Vp5pYRTP&@!c#RmjR|JU_inoac14k0Fn#x>-S}_Aq z9WZo9O74E??Y*1ULVU+xrtFtLPW!uX?A^sxj>Ug>_O5Sr)xx;8iybysCs{*+mMUsU zrb%Xt7P#`4npeF_0%XzY}+V8g* zCWh(ZRU$a$jFYL=Dp(fMidYtU5Ths8p*-|f#LE8wcrl$%@)l0f-B_Nq+`WfIvopOR zzxro%ZrYu@Q9#h_J&}vwc>^x(+}WH2^;t-kgiOg#j+snseMzgmhR9sL-M7to`_Nm7 z77K_L7m=BP(4VMqBCLean$be>V2&N~@4=4d`)P_hFQ`b2v0N;No%lWu!_Ru{5aLw2(?aYy11C=zB}QbG+#ZwjGHgGM|CIyA7o8;o~T zrK=^f&hfNYoF_9jlBVOC>yrgpX-(#+*{-&{#gO3NPk z+&F6Ld}db%x1`mkvmrr|t%ezp5M!2PQ~HOu6J^{V_f%;WWW5e;#-;s187lOt8bXy} zR?;v?#(H*3%Q&9?IWCknv|>qzoN=<24&H#Ou@v$Lqmj6N7)7%BLkZp+&$jm@6j|Q7 z#BaE9hO57Og)0o|m0DM(L z9SAiA7hPWf8lH-$UTs{@U~iqPu<&MrEbjHp(_pZ#ld5`LR28!%lSw{8zBpAT z7bW~|SbzZa4`KbYYnOH0taj*TM4D$KQ+z5F8Qh|D*+aH&78es8zVJVWvq$00+mP;p zp;6Y1fRNOop;iZ?&8u~i_WJi~y|qYp2oYo=IXqPG*y$RdO43kB)POYsuCG*=R&~DN z?H%E_wq_!1Rw4|YWgF(VX5_0(M$_3_ed^$*uH3tmD=>IzXlPP>QADAqtCXy0rJCZ~ zF2y$Oc@43cMQN#gSxS~z)s8SIUE6{nI+)bqRhdjLZz0=ln(Ad|UKR!)_KfdxJsY`0%WnDjQCvsY1e< zw47JW`3{-sDp*INO)*58SRx{^W2e@P+LVUWK>*m>-3$x>ZFv4)>~ya|s3Mf(PM+0^ z)FV_%+7VEBl50ieC|c$l0K-VNxd8jRTk0B^jYUK)2w2eeEql!nid#$6nC9Pp|kmSLf1#gqcunyI2B#dKL*>_d!y{VT4|K~zS0r()cmV}cNWwZsIl4&7RXPx5NtKHFxl+TM4`)2A z0N$*_QiPw+wBUW5e=dRi@}TTT6)P&!<)8Lx)t2IcwqZHS4%OqZQ_V%NahrM<$<@`=G(jh*tAZ)R^W51<0kwJWlGTZl zYm2LzB(eZlNhENvWp;8=KmkxlP#b>Ts#*oIO)j*&jNGQ!t;LBG9 zLHr<-i}B-lZ?47ITd!#RkLxP>zV+%H-t+1{t@&lqSz3+p(>>?AzC2`~YIa9b_ommv z@9d{r;=A(?RJ6>Ui$RVxeS?LP39I0wpB6<*$YYA(;k;&o>PZnXKO1eqM$grG8s)`ETW@Y)f0{SUOg#;CPG1eS^BD2AYhJ2WD+$?KWhw0X-Kr^QB6flwBcCK{ zvNtWH107;5zDW`Qjd10CXj_duwQ>CM)<|C3+t}_F*6_J8MxCa$ry8wB4w6cS7&NaQ zgkR;+o031A-3JM%Ws&z*NXDqfIRmEL%#gliWiZIWeI#1P{eNXmMzy<>@d()G<^HZ6 z2Y2@^7S_RlVS5kCo!QT?r_P;jKZ)zD%ig_7+8tAj+go02KXApC!tTD-?7f>=klFoT zhQ{EtIZcI4h0C*JQzafxvi4*rH(L!<-@+=YseEue@vebKEo~Nw%fGy5mNt2u%cez* zyh5&ssG-3ID8jK)QICr9(2W_HISSU=*Jf+40LguJ?MD=(ar_!dpfwDv>qh`Saz#3% zACS+q{y1ko3Vf#P-I4q+sy=pngvIoa%8!l@xv<&ppsMVR>yOOR<2x^8b!OkmO}4t9 zwtA0#Y;3Ix=C<@yw7JYI5k~N!dYNlo<{n+!Bz3s6wzf<08-Ve^6-Y%w6@wz{C2^Gu zlm?)lkn{fDw>-DFZw|UQD-YDx3Z+yqSB;fGs_E{CR1oBGS_5{U95yc7+rKS(vG8=1 z*!m0wM(o5=&{06GNssb%_TpV@Cf>z4BdL&J z_3cI0+_D0|0He|c%941$*Yoe)YplBEb`2vfh*Tj+A%>Cx2G$I1&-nZIuUi$U$6X=S zVf6~v4$4+j;c6238<{y8^Al0xSVrkXHQMScB~aLsXTZ zp#K04G17tv4K{^2@z@O3y<47e(`wwgrL-uuA`ixVl(MiD}m(touA5cFM z0Dmj_KSBP--ibKQeE$H?)eS0YG1IhVU9~d;RH?WZ7qzZcxUnBgeLbdTt9Ec@G9gDW$fEjB1x<)P@ps&*G;_)? z5J3L`H}mQb=jR{RTh*ZeM+hH3(_W7cPf0u*6RyQwL*piXjo4}`N=r14NmIA!SWN~^ znVOm@qX3A#B&%st@1DHIbZ)oJ2x@-uy&{c6{k(wGd3le^=hhJJ^GgotzE1OadakYj z^#IKv3>)x*21g#3d2^P8W9Tv2Xp({|*)upf=9%fBhb_%C^hD5*vX&wgRfrl5~PpQR+B021Y@pI*)El<_M#Lt!EUbSh%1v3g#7%BkuK_ZQH3`(c$B#qDYZltJ2ivymn_=`+G06JRNvu5A zP(K%nX4F6-Rx|o)v|5w9@eAbc7pyvdn{QO(aG6SMc3VAD8cmd*ioIy+swAj@RM01b zRzc^IReeWKjZxE9_eklUZvKl<(f5(ycCJT7_h+TQ&tB} zC_L+xKG1uEwb=57t-a)m!q!PaD9NZqT)KFXwFr|@b>pOv(wS ztxpO4dtWg`kyjQJb5B_bq)6p>?;?Ta2I@7hBytC_P-YSnz!fh$vHc7P(sEh+;8 zPv`zls*m||{2A>pfi2j(GqyfLPx3~ev3p`s zS1CtWtvs^PO!QS_MBbT8MHQOb!q7rC*p@g=O92|jHJ?DFhR5P+A1ZmDc#^uwt;=@; z1xrvG*C+OVRq0Xl&*5LlKK=P?@gL-8P5166VD%3`<#4$U{pl9oeT#v}cg8Ohxejbn zQDOGY6<)>Mk57vaMAVttDI%UZ-&~R?NKMk$Y`Ay3yC>`8Nvu)4c(ZEmpa zIr6zY5$lclm4*|7-ZE!4%r!fk5ZijPC6~!Uk5d>@BU5svxRMD+fpZ}i>_BP?npZRx zTAE^&74_@Enkfu{14siE2h@TVzbcXBcywI9mM1`W*TsI2*}X0DueGQu(k-PtV0*II4i*m%4i^vetm0;(z^mGrSR9zPso#Hf9{HNAzc!$-H& z*!~lv!#_U2%oc~pF&=(>G^SZ2SDL0$bDHLW4AbTLo`Fr{@ek%EEBU1FkC#;)^+lNY z6P(zOgv5MirR{C^Q$E@3X}bFpw_@H;)0LQ{>sa6$){3Jj`8rDDUkIt@Kh&pBZDJz& zwP4$m6H%awCIHhVNHtJNQWl4WYDiGmGr58q1%VI)!z2Pp^~pRdntZ9zm;Ph@74nzl zZ^LOizr+Gs5=Vh~=;R@%CaHROTXKTeDVO-abb2q5)XW_y1Tkt;a^Nx`A0B#>%2 zRDOL9-wL+A;OqXm>+PG|b*-P@8(U}WOc!irDl+T2Cfysy54UktTjw~rxe|r9BzuQ7 z1yw@Un5oTJlt{@LVxr06$1zyI(7z9*Jg{@0Myd7BO+L3&EKi6=eQHgAZ&kVQyW^+x z7wMmpA0&5w&Hm%WcArXb{o=J>60n$#+KaIhs&?w{ZO2~Qdb12Mm}z!W$+4?(bfpTq z%RM6jcMlo8 z?aAm){%V~U{Kiro?0S0!S&OjidXtR*GWrnBHx=%WRL!{LF`lr;( z3?39Q)>eKrQ$?Tv0&+7_NX-EIIzO`D^BMmDkKMdzGx{L1y;YSDE8$<|Y0qsR6= zR@TnJ)zV~gITgrJ;vu2k&p_1`6$>;_BD2UHRe|(L8zaWeqg6p8@Ye*2dRDm4rfJo@ zO&20&P|6q*4r)C-tM(I5UaR-{V0FLGzO&eJVn3Nq;)iwok(+z&YRWCmN4_>b{GrKp zl=!{6Hq0xR>&T(o82Y?^VmzEpM7~MVFC3CMSrRz?C55im;u|}qo&($%G_R9NjZ*<8 zIM9j;_T#4fStngmkQ$B?-(`?8;I?g%%&T{g~CuXIiqaXvOpSl0Vl79vHWGkbgJZD)>q->d@RMj|aB zEEEn12ZBk-6(NcH2Uhxt5n+NcrlO2Wikh(|jZHvlpruBCZ$|$B=FZ&tPr5z`c0N1c zqR~IgnCNyq-73|!y9XUewM)EkBX^g`c9r%7Mm>!tLRgb13=_{9MRjLZR^qpc@ddoI zh@)aE<(X&(ek7}cX{Wb2>d{D$$nMAq@YpUYH5v?$Itu!Vj+=j%Mjzy6AEf%@AM+ju zruj%VoQvL+@=vs?p#JxNcyn>WXzDut`xa_iov^eL{{Xmx)Jr3>sb&m)>*?dPoo&)l zB9FyV+J~)MxSD!^dTHc&P&ptITme8m2SpdI@E^>_8T`fmRkz4&Tr?lc+4nx^pW&r- zD)k7Gs+D(U8a=U(mQ9x&y`e25?OCg5bGsy2)_8*1wIEu}V-zMkw7L$`0!jxbMOvb( zL8R%%4LEs{OQzxE0udMp6lR${pd9)ZsrB^52ScCpVNd2g2SxOjQ~6Ej_gJ~>{{3#M%h#XhDTE;Rk z3ph9&Xfs~570=SFuiBR>ewk;kt`YvYDGdcBQ7L%kxe{xMU6#f{nb zP?}oB+>eB&mp=s5wA!Plucgfy6HGwHthS7l0Q=Nv5#&l%l>)wW#ZQ)a)Kl{7T7yj! z$WD?}ntwWVRv*hhH~i4ES-!=8=6BYU^|s^3ZmqiqOH$M9O@XqpdxvXIn~nD+T@>AS zmdjCYAwcos)Jt5^RmbKc&P%_x2G;v|FD?H7)HIEQ;v||!{M!l=q~I_uLB}0#OQAWJ zLKTcLuN>zT4dqWUir1kN`Hb#g=0~)?QG83pd_3wp?c?!BchTb$<~Lwsy6bCiOpjk* zvW_byUrm|MW+-x-UL1d1N%ylhIvH7GMwM1sl@%2}-7VV-guGbdi~`BxM1}m#1A^|v zQBh+ernME%P5nTMIOFj3OjzcOaYYI-MHwfJNyRb5>~{@sY+=3|cg}m`?%F%&|GM6KH=7n{l@7?L1{Cn`mI9!g=VQIJsKEpwpRR6W+v+r@cW5oP9d5R$>4rNTp8_ zU$j%zusr&@OQuGV$7L9io*_*JGfh+&r$zJmbnfqz`}<{2xxQg_?&s=W;Hlnw&X$+2 zH+IOR>zw{Cu4tbcn=2)l+W73Ya~&Q>H51iIB}7#goG5P;Traj`vbwQkx4vXIgjKXU zNP?#UT{~KX2j^P#=_XnAm{Uvvg*{FMNv=gtmzO{fXm-Ez3d8>ZG%Tk@Q}kBjgZX(r zJ8tGNza?Vo9OGdsYpVK&EyI;%e&X*ePWtNHB`(Fl>^;TV`BvCFlP^<6zjqBj#M;>`K5H=ha~_dS(j`KrBxU7g zlS--awz#~6Lugc846dS}8Ut0UQ9(XgsXQ~*?cM~HjmP#N8Vb`omZXv71y9bMEdCVk zKF{C%0kLa+q)KHu%WWOFrV+sfo_bHg^^GMT&;n`4CZjbyCcb4-V{zSS zhpEWbPenln=Za*OnHU$YT55&HQcWWiYFZiRllLkCEf`Os)$biX^+MIXp4^SxQnD@7 zWdbN9$`VfxUU40Jq->BBP-m!v-uJYR+v~|MWOcR|aQp(Ky&NKcMOd7_6`&M4x*(#4 zO7Rr*N)BQ;#YlrPPFuC2W-kgs_D{03iP(x zTNx}atnO_CPlj26BTRtQfWHfCTB`$Ed_ZadiuCzWOFUSJ=%#vi`%0K$$5g9*^&SvU zGfuSg%L!Gf#pQLM4MQtJX4IrC=tD{S4ZCgaEv*5LJuTR3vMUTp6Yyo>tAhjD!%#E= zZqZ!9eIeGS+eHe4sEVCcQ|1Ws;Zju5xQBf^Jw#n|j-*PO=7Dnc615zDMV5`D%|O#v zP(<3JN##NNZk)Q0#ke)O@LK*^T~%L8QU3rD?G&Xr(A4LF>L%Z2nYSC1Qo;|@Y6IMq zRXUUUU~u!UIzO9*acPt_)Xwy#s|&ZP@+nxgbu|?9lZKv$DOV%a%`HUICbnHIW@IBu zUdq9nPh75gDWU*5H-`iCsG?e8e3TON3+FXS=dPb=yT2niDBGt$d@$5Qd zxb5*!Ey~D;Nh9G6h5i#kgXB&}MR7y6t^6@s-ihp4*;YWU9%)e_M;en~5gQ##T=wIs z`6U?4wQEmREnb5!-BBeBiw!*`MUn{GvTB*)nrYF7uS(c9mIZ=YZN`g>yOdalj~5j= z)VxJFfTtWyY3b6v#@^n?bEVbWNUBL?RiIR0D5dopmKnel28N^q(`52fD~ z_BB*A)8;8AhMt~+iW%MvL_(5fr$oyNo4{ITF|u$$l}j}vf@p5-WNUz6kQ&Fu+0Vp7 ze+XI}3}?%v&gp%%?uhm*@0ZvtwG89k-hM+A3=L zI?b(El?NbbYNv)c-EUDWOs1K9Y`%{ih_~eZPqF={Wu@dn5#6a;uV`9|u&xOM1AxwY z80`W9vRy63pqkz7ik)FvhNC1?PB?-Hr$=uUpZlyGB|hz@rFm)bG|*De7|u5H?3i)&bSn3KecF{Nl$Kvf5WE|S%CPy&{6NfbJaiiCn$nd_kY#K_bI zmYHe=Mq}PRj)%7Idhnje|R&l{|vpG>N&iRz9{i<^H^cvtQ=_og*7E0Ev@ySh^r>1HuU%RMjsxjpR za>DZ?XjKO6w;=sN{10uBq}#8|VL=`lH8d0r{vL+5C}p;}E2J6nj79uf_WMJWe+ev?2J5+`AWZZEWXx z>`XpKCzd!mUdqPHxc0bdU~HaZmaF`hO0ws(*z9H!2d=BpO-D+w zP*N9p36fc=CXhS1U))`_yeVvBwTd99ttW}4MJm!r>|RG>O;R^;ps2-2Lh9!K0D9d{ z^}AhLo2fuipaexhsDzCHI#d^S6=F*<$Uus^{P)J=>wJe=P|)wJH)hF=!c|k`F;zPj zvu9&7v^%t8YN;_58AsgI*=iGlS*LZYSW#-)>LPXZdlBt!?RerL5d~?INYPMQl=C2B zxb^5y%C>g4*Ap$=rQtA@pgc|pB+%nfsiz-2by54>w)^I4B*jIXj-F3aE>HMtRTXQH zW@}7Bt?lUvBq87jO46$suNrh43$uTTKcDeF>?u*zGERC~ z?t3j{iq~B!0);#k(*#`q08mu@Kc}>*omzO*^igfA#&%!g>d(3dcy1lz(iMAKF_M=d z7UkO+%q~qTDx9WHm1U`;5#-t0(=keD8b@ofWDZWQeTu9f$FaD9i6(@8&<#)6eE9W* z-tO#HJfZHE+05H@w}If@!8+&^(%r230`RFXMHucX1v&~k^B=Z0?^}0{=-fCg#JiVo z?b)WpLN|MLU&n5Mrlsi}?>A*{ zPm+{WJ4bQv&C$0d!c%o$U)FBzor&Cd?YWJijyb9`H5mGA>@d$=ERso5bvmsuJ_W9` zCG62!+JkK$XNbgxW(PVzBx$b-jBq5HfJ8QZzTVOmyS|YpxB$^u1)#1Jqj zGpLi?1e3wIpvT5zs+N;8k4Q)fqGKfLB1RHj0?KWvTha+2@$Bnt&C=%qTlRs`L^cg% zZdHXyU=Pnf=IB7oEU{#&BB?L8e1J! z@gJ8*AFcNu+S~sC5x(nx>^#=(+W3!`&$#;fr*3ZyCMy$=?z%pc!plRoyFUX^M(BrT z(e1hul1z>>TT54_oTiZ=kXN_gzTdL#H?nQ9To`vL+5+xEtilM1E`dpKwMR-7t1Sxv zO-QdHl5S*)EcYJ*>9)YKRy|*!ZW^r{Q~@r$XMiC35dE3$oxj|DZCltsAvU(;-&@nG zj^o1N=E3K2yEm_UGb7x4ioY>XH#RA#j#%b4u4=4LQ%kq1X+g=}k?K)shFICz$_gQ03vjx!IX#yAc6;#y}b43Zd=5 zqA3X)fXYb>tVS`@u-Ub}{FYGfu&tkp^EI_2Hx1%d*(9wu3afS*C$7q!nYt*X-ZX8J0~<+{*fbUOIip)JDNPj=kMsxK zxqouq=G|gnth%}@6~Uw2Nv0%d*iCW^GX!X3tbx=Q?V?qP9VFg%eU2TH{Sw~V${>oq zDnfv&_>r9yPzhNGSjtpXH8^x&>vl~pcXikAO{v)s_I6`!bcXG%*?%g#>*U_c?2fhS zy~npVUeci(rwzMy{?rdH_fw3jqMJ=lVj8+;Efk6u$dF4e<#}hhEKmzXA6YE3 zTuL;`k(G=%Y0^TqMBz}?LJ*KiR{5c`iaD$VF-dQZki3#mrnWXNTI{xvF);V zjwb*q>bx;igvrs%D@0zVQiZ$T-#>->?4%;uq_==*!%Xi3OfK071w3>@NI47zMO&lY zj{Xquw?{0^t>$>6kO0=Go)|W+LpD&pq{$i^Mx&$_Wb2OB+?!`@?5r+NWn?#QZ?88N zcXIq-%a7tzu~x3W931_RS-H11TXW&NuYX}GA}zb>@aZiv+0+?IC3vOBQZR@~CZnhe zF!^FnH^Zv=7%`~ogA*+G|9|1+m`6_S>MRo6;vU& ziI#>mZ0e(TE074`Ly|AhQx%Fg8MvAvu!Ng;-5USTwjH0qJq z3NDpE5m!I~f`APJ5Ny-KZ6tASLObuFHqktB=~%%b{6ehEWS7JNi?P(-h>~!a+g;31xHxE(J<2E+J-y7Q-m8k06#V#X%(o=06y`P^qwl>f49o3AlZ@9zLRY^|{P7xJS zyoK(5p408yw&AzVC$*R&nU+V40ilYqAu;(ME$yP3%GrIno1fYeC~^9ZzB(ydCIlhgZF z-yYMp*zNI1S~ymkjeCwuH3>R(F(fF$j0_Hu%OrCuk6dL){kZgiBvL=mFeQjAZE{7w z*7sj7j8pJ&t$KE%nxRjL*Vc&0(KLwa@q$^4nH%=>197J0``YQ!0Xzr#zn_;@04c7n zpXus6l)=eFkp`7U)^#F*shMN-0H{yX-kJM>ZU>L3^6J&gQy=HyUY#i_uKq+-mfecj?B?;KJZR{WsZh@oM(0oTE{Q9b~4oZPe6#oEMpH2fh%R>xiG9H>(%Cry=(;ifqCbpuV>eL<&Bl>$sdTP;t zduhl0U$d(gB{DOsso6@}ciKCU&ed_#G+0Ed`#4cV)11{KQ~l*Mx3b3kF-}VJZ)TjV z3Eyl2fv9Swf6|--}lwYIGu^rxf3*W~gwv2Cn1C1I|t zc>GLcW84w2#mb+JDN%lkh?2);&Hi*kH*cJ zw|-DT()IgqAk{&8E8~c2d~ajnGL>vX(WOw8kyL|2qo@z`B%o=IN_1aiG1Dn_FG9l=nnv?TkJxo?~{UCw>GcZxrw*WyIgs@uH@B~uePkxHJ| z2$dz3i8Q%S<-@S)b}s7d+RPsH`1_LISO~NE&hgq?r{n(e_`~uS0hXULJ~yLlu)S@x z;HcQSif+Q$^b_u*l)@Oy*o=#=;!omqjipZ8d1+-}%Wr>h@~~B8k~rO!oR+Abpfph+ z&`RM;A_Np#2RZWBdfvCKw%2{!E#nq&Pdrehw=pSD%0#IafYQq=6=wd>MG`R#6`P@p zH@Sbl`=f2cy!!)qMX>RmgSjg+v{>3&UB#8#l>3HxrO0M*_&EOngJSCP)s--*&?+E; zNSMhQ1}v`hv0ETFaze~}Af;6NRNw})roOClcoWt;?VG*M@ywewmgCG9M`(j`o#{a% z#AVc8P!&a4oGoZ{=_TVz)Hb&tH7I)E{{S)m^IfOdTc2{^n`~?cM1J0Qs z9CeU4X|;HJa@lTgG)n*hj7*w{CW4G=D^pWUQkktn%lUps6(`Sck1(uNA9q>2YF09a zBTp+!w=*h4(MzX71saQL`hkCFdtS=@{a@hdJWTl+W@0sG7 z)s3?2y3r&`^*SO}dcK^gcQma^sEwJ09)XI!cILyqS{IeJZv0t4l)XC@9EldDYadUD{Cf2c1zm@l@jy1<#9-VMjELCsF2G$@djbBg?(2slI zdhn_1vQ6#@^&12A1pP1m$KSa1z6S>#fB(_jXf}(5Pyls5QY?5M*37*7DkOkZ9CV=h zSJSM@r0YT#OOWJ)W!3a;ApJS|{{UNi(PG?BO`6b?)aVEV09CE7z?BPjTiD;!Re<+G zbMntxBBSTij2AJX^s<=;Ae~W?MbN3Y3;w;muWd35`J48o7 zP2seGDRml?t9DrZ4b8wLH}vP;Eqjgt=kOR;^#}5x{IEaE=hPj~p+Bt`hLt*C$J-Kc z_2~I@$|Yvp*tGLYlf_dnOZB`BE7GM_DP}uPhFD~&Mwia!q2db>Q~jVgU#B}cqF1+* zaFrrSWjmGc1Er{LWEK2@sUE#x?c%|Ax$jZWE61+-;4^8e>JrOMLyl+w1J9@0`6$>$ zRgg;m0KB2kih61_r82CQCZVLMS*n%(+6q#PjuDG%8jyiyZ)ogLte3F1V0&Fesi7o+ zrw2Sm3G%1Upd^w)B6D?k$VI^Lz)I>M_ah&LLE}u;gj0d&My#pD9jmpeXe(gxON_|L zQAZq)Q&EPkTFIWif;jZDLx!%Dhe*(pjHHWd_SVe=%XPX>IyRQM0fq*=4Kio(FT#FU z=u>p)HeHekZiO9NQfeikZxEM22%^Nq>IgD2eELspy{VVT>`HvR!m4PpnLOLkeH z>e3{JqLU{^#3eK`NSdkLS;UC08Bx@On4a3qud~<$KmZ1UpE2jd_GcXmIcCwJiPK9} zCSjf;oI&)@4?G^Kvm;F$RS#%l9zsNnv5iI+o!5IdSiB>aG0AJ43c_UxbP)~8}v+{yV-Q~4e}Y%5G|p?v|tBIGkYnDPN&ZU8^m z*pQM%2LYa>P_zQ0po@QQt<4y(gJpWqqq$!JG4WAbRR2pb9;a7vJ}-gSo2uZNTMjR zaMe?N-8YL;t0}5Npchb7pHKu5?NOu9k1>z+e7Z;Y)G#5dL-Nl+8SGBd5ye|KRAa#) zv|sPx4J2uEWejnI>L-$a2ixswI`O!VNf^QZ06$jM12t7!kFOl`$ywb!nH}Prr{Jhk zIn%nLKz_Fc8xH>fsDEE=HMPnRR%poo07~D>KeTmm;7O%Up`Xs4pKnlO`2*Ori{U*c z%AgXf2JfR0Tk?uOft?or0DJderMxUbcz~zRkL}^-*O%$dKT)e(;YZV8ceRvM7rUfFC8dLpPu0CB! zsQC}NYhf`}^mbZUfDGz)Mk+-h8>=cdEpAl*080>0yL~m-FGYy1oK&7ZhaceTx-F;* z+_(GAY4SS1msw@`AGltd?dR!T(c(pp!VSxb4!$N1in1*{ZV@z&c(~w;d#hXDX&@sBkgb~f_f@{GP(Kban02{iPL55wgcrF?ew?TY?c)HvlrJzxKEu?cm?N34%TzPEYOZ z6za_!XA3wWepURvM^fv)Q*G+#UJBl=?MY*hD!eI!#Jp}p2EY7#OQn?hfgId_vG=hB z@KAgRg8u-g^8WyM&tA}-%(IU{kMQ+Ao8^YrrKehS>%QDrl^Cpl-K>0$t9x==bAOy` zTyjAlk?x)y-9Y+qGyGWp00wF2!>xF92Dd9xeEmIsU0|j8O|mFzW~z^2cGOa28~22J zT9ApJ+HWLFxe+xoi|SjG&H3Zr%y)Ha+4p~@#eFOOa5~tD2|zC6(@g5FJ!?RC`BJ|= zxz>E7*fpXtQ?a{fBr+{bSK1K>h0b++4aPnL|1IIFMh^Ee%DD_Li45l}4%*P+hBy)Ae2+|>O3xWN1cT{NdJnrR-Ph!@82S|vyQo<&q`3oC?eEVl-XDsP4-3_sNdEuIOiXh1-U57)2~Bj&e8Nr<8%?SShR(c<4DB(%# ztCdHeA>lP->mqXoppMIX`4tJf6LalJCyC-fug|81PoDw&ztzK{;qs?r?!Lg<7!9ej z4H{+gS=xt`LZy-6q$HcF8=^QW5|uY)Z~l5ad}j7t(Nk(4=mxH zVx{R2R#_K79omCaPAkHzT|f`+7Q=na+_@&tw$72=NirI@!cYee4i6AV0bElYdLdhr zsrO$|;i%@^SsZ3e)>H~O;KIFB)l~Wql!+yto(~N$jXeTAQil2)U*A7{{rkCX9@TOT zT-Rm0zTvvP{7{5cD6xjr%_s*YLIG73A?j*ZtYzlkYu}Kz1l=dyQg)JW46JI^sjE~} z4I+YugqrZjK_+^VETc_XNV;+{i6)AYIDw9$GJyT;F)fljj+7!r0@4AfThu+_y@H9S zc8D|FyHM%lF&W3B3UT~HsCIQ*hSZe$ft3T{r}0yOe-XJi-(3YzV` zT|*6h4g6DX3JjCFK1zx?gfdF7Oo)|HLdU}@q`Ckh%-hS;NiNN8^%n{xSw@lgfM7si ze;}^EVIzU)DY=w?5z=K30|8zP-X=AuBBTxu1wbGYC_y2YO@>XChnAVDrh#XxmMZXc zxmC?Y8c@w1tpvv@NUnogo3)R#3)3vEG*P5t;VQvSDrln(=y=oT)G@n#K;EvTSpNW2 z08V>I0dhanV}?adI5S zZnn_b-^kDO(HnyzqAJ`vhLR}!Jwc+34L&7*QM;8_;p#@%tD^ggdUnaZ9FfZuk|jMN znij)GS*NXyotCrj>1L6n2QxNgg?>KZ(iqIQ)Fz6^>0ZM+3rC z-HN*2+&omdw2&KRdqnA+=*oK~zX4T@)o+qeV#+rEpC;9c-Xg)aZW9z1l3S;Q!aW5^KuivmIzp3B6`3f?Llr1MFOzK)^TNUxEF|(l zBTXzcb2|e0I;qHNq=>j6GLtD_bn0+Hj;`+Fs@cf;BA_ynQ$k1}iq(#yF+xe9^Wq)1 zQcDJ-F{M_ffS<-s8e{FR&#Hs@{GqmjQ%^kKbw=M|i^(hNO4>w}&pj+sA$oeeLq|~~ z#)JbwF%L*uIjSNV5AD3JCbWup^=QQh1zL78{k%xw6vpKBA8ru&s2c#>)$t14YYS2nfIoBsf+HyKZ}lJ146tc=r!JwAO3 zHt-v`{9b-SpXcZ(#>cCD?Gyo>nzJV>k`%_Fadk{W0sjCTz`yk4@_mo3Py49eobd3_ zf5ylBS3?U@e|GL95ELqae#aR-TwlX1((PWd?k&uel4TA81DTH<9B(t%OO3+RRmVr6 zW`W&mrHxUvx*ZHorM3OrmxQnN@Wud@<%w4yWYhziiVD{vp1nD;#@9E~TU3UT;!;H_ z6|0e4R1N^*w69ll-hazmuX^*PddCCu>*J0K3a99DtFk<;^?r|I0f6dorfMkigu*S)Yjx|aog>2L1nZ?i?=}$ z3LNp3ny&J@_>Au-##zHSLJ>_8Fu6^&?bf?ps@U1vh|^eZ%AHgka!V3;cQH80q3V`C zJmhEWHMFw%vMV~g%r4& zJeC%=rUjYt`36PPOC2Oo#yrWjTW!GISgwm{OpD>tfn94>QBy^Fd;_#nqvAbAob|O@ zSzcOS+W?|%T9kRR(9{o74H|%DL8VFRyt6pm9%rt*K9;5(jaR)WcE;SR>wG_9)zeer za&?n$d>%i3RBh@UjYTFCbZ>37*Ok@T3Mv}9m>aLpo%07BQd zC98v^5)f*oX;28MA^uoIYm0}Hnvw=#kO4d~>U{^=XlaU=-}Lk}*{Zr|PBLLnRgsFG zyBn-yvUF*Xni_ei;hI@yf}K$>0FkwrSZXAT`xhjDD532?>OBo0MMNP@XvUQD&mXhX zp#70VEu~ROYN4S`{VNykk^vww2mOz?s#uZbPvz3(IUtGxar-)N$eZFQKNhR11b<&l zc47X%(DV5BsKq2dXGdi3jY9uqKkP5cl&xXUlhB$Indpe)Z6ldXl%~)!tGt@ z9^tF#p390>>&?xO#u)3U@Y~`zWu%`mv@-S3DXhgb!jmToJQ9K>VeN8DJT0!u=fji+ zI*28H5&<9;tt(NHkTcR-{#50y>iW}k-ZpryF5;yNX9FX&f~A-6u~I>$FepbVthVIs zANFW>-aBl`CfwgOcunyR_5SP~kB!@NVIbU3xwcN#+tg26i8u^z@t4L^s?Q_RW2hmG zoU!&_Z*K5dz#dX`ni9kpV$=ngic?VJ|R%VP?1)tDmyl|rhM?IsFA7~N~&q9WP7ldQ&Fn#rrf>F?Qih*X|#=B8v9Cj&eC;(>zE@Nfp;zmoG>9S#w>Hv0*Y?HIg}9wb#;@nm?X7;A zAG7&&Wgi&&JbaJ%iMTr5pzQnvTO;LGW4EjK?#1fLPRGJl;~S$e8(M9lI@E7Hn>ucM zL`?Z38X3ycR7LC|3 zK>4_^9JjvhH!)tO<0bmKDOB*|Siy}}Qdlxf`iYb%AT&q;<5QV!H;cXVllRMOTXwR7 z34Wo(q>yGoREUWG09G}nRhf`BqC$gSp1Ui%dXKUC+N!X2mvvy;vu13)xq$d{wy{+^ zf2H;>YV5o&KX0DVtliC3Cd1u$n##I5{Jhi@c*AEl z5k!#6u40xoN360q{XI*jjKS!1bg}68^4~PN^S3(Furs}d7hqTR?_GAa4(HfiWwdHG zJs#TH8z()qr`i;hvuCyz%Gk9MSLcmIE+-y}k|Rx0u!R%9vmL8fFl_t1zV$Th$9P+} zy44h6TC20wFM-l*{NhAOz z9!G2ts!1$5QFSDniz88s+1-8CeZ$#V&wv}ZuzN3{W?i{O);T@zo89@`X5rl1Q@J*d z<<2HgZ*Hs>obvzS?&g9p$&#rIPb#Guv1R&x0npb(V%m zk^cZz;T7IyNU~Ls22n@pt<9_!6MMLBcF;w=TgL^_Ml-6SDAqL_haRhLmk!iM?HK4~Ugo0ESBF{t{^rWjiO3hFAkq_A=`7W-=u2+kjf$q%JBTr5PQ$@h0M^d4l7jYSqNc@r_ znN^O45u56f{{TrJn_Bkwpv1a*0sc<3y0sDNI&r0(nV(8T_OW@SC&eU0vWG)|+5qrB zJn}v5y8*{%m&pA3aL~CVXUqLxKAq`uajQ*v3~wS7iPb}hi6u%90Sl=QHwW=!??f@; zJGB1X^yZ*g0x|2;tQ7~%q3si*tYz$V%8E;eWlN|8eye+V8i!alCp}iDSU-le>HeO& zoN81p;E@?^9P9{?HlZ5^uu`w;1M)rJQv*=6sHgiqUaN{{2S3R5A#xIUgpM4@11gxw zBlgCVcfOKAA5X~szV=C|T8#eyF0H_4k5iz@fUy^fMFNy=a; z^2hjx;p}w z10Pjab}eq{%4YV(E_Sasj@%TPyrlR@D(NXPm3Zo?9=>Q9qY*RIL{aWCTpoDb$egM@ zt*V7R#Z*MP*;a=v)KEY)CnO5cDY0`V)yrPqo6W-EMCRsi4NWU6Rf@(cK+>u;u&AP| z=>@c_7VfqFWnK5wTmJy#whQH6YZ>yh;=fK-Wp_>^<4rUh2c))E>y`GV=Agi17khQ* zT;q2Z!R&p7yE0VSxbgKLeMM1Gj*bMFK{<2^n`?_XT-r0uIz-48Lgqaz3XsY~fhZZf zmNHR}sulqB{{SWXm9+Csn3CkfZF-G2W)ABvZjjWCV&ZN{)q}<-^$! z%=hN~+w=DpJ9X{K?YXwP^L2Kf_}kC8>6~J?A^@7GJs( zb^1%2seX*zO9R4^N8!N;xP=&r6qTA)2}(zrY6M(v*Q(!g?+hJ2D{taEAAD49Dulx9 ze4Qk-;`)uobmMGZHlG0+lQU zO-irZS_&U7pe{f{$9F1zXm%mjh7UWSbT*V*|GJ+JLVhW8*LKcRChL1jJZT+2% z{%9XA@DwqLvD-r#vgo$`9X3Lo((P^8N7S1D?tQNHRJBz!`Lx*kx~D0IEVEDLdNR)> zj-|*VM}lYH9s;h9E9qcxKw`R*n9{@oylSSsW;X3(XJvP9WfVmsj@VW`L5xyq4A8Rz zYvHkEYLZD6B=oiT0Tg5BSI0K03lqb?CA^|UG9-<*^C3JzuDY3R`hi}4p38hiOFQj! z{>gRLP z%e6@YgN~5Ik^$;$=luGZmnhf|X|l z!xlQK#;p5`vRK{n&F1oL5pV3-2$3j^$i|Nxlpm<2RF$uCK0|jhv7z|nB$L1P2a!Z_ zL%H`-I#Z(v!^N<2sVm4vqoKZx#M{|FEfCt7cv4U1Kg-b%w_Vn;c>#FT1O93CY~G+$ zhBgF%M~cEEQM_5(z56 zpT`$JPJR0wZoE%kvo{2SR_E#hxAg#v5fn+juBvTM=PkN7Qp>Q>cOm zKkPl09W~My{g1cTr@zbBG$b+9q%Rh+xmNtLx98RM2ityU)2)2G`khRQL&(Hx)E7tq zt6f=0CyO3${=?l37bMVstNHa(Kq9?4!>A|#ENyUG@{MLv2wU80{QF`;O8`!2KjO#Q zdSIR;aO*?=0OrQ=kLDlqxrkjyuy7HERu=_&(`T5LHXLcSuc&JGir(TDZhw&ZYN`HJ zug|DEpQzl?cC{HuJh%@HKh^8e_vy)+gK6y=n5C~_Nz{FF<*dWYrmi^KZP0(fd?dvE z)XZ6s6Zr+chU1=m%#lsGJTnFGpK!e6}UE<5xs{lP4R76ZnT znp4c?lpH+zb<4v8WHFUc&s~I|rOGX282h@kw)8BE(qCwu~#e;LbQd+aZ|=d6t9uR0O8W7sTz^`Xljt0WR-d5 z%2G5cwe-}oWh(p`*`U;sOH<{L!7D{(SisaY*!uuedz1Mz@dm6VPI=R+0E6jvGQhCY7e@wr^S73YFV zP3cD!elIzbq>cfJ-PkAuabPp`A#XqTwvrf{j;5i271XfPv!ruE-c0rO=ITq0qibnO z$jXW}&?^uC(yvT2Eps8Ox8i1?JsWKDLRIw&ZV}4DKqyvJ$A>4bs#RF|jW`sbsVv6? z#zA&a3b`Z5!snK?ferOP5%kUAz$k_Q%f3wy``*JDENIb>NpUfxv zzdo<}h!%;EDLVdw)*8RnT>k)44Xk+{#Anl~3sJ2+>BGvsW!}9ZH*fq~?>@WQb#T(} zoz1p$)D$|V`$?ypAx#u(0IJ}}9b`z<`iTk*ypXp(%pmaORDs%wT>YFuJbeEE!P98Z z6~f6(@cS`CPqMvy?6RK_K2L3K=&R^Tj+Ecn?dd_hAf{ZEZraJ>Fk5b)ADM=scgACL zWFe=-VsTg)U=_xz?k)@gU=Jyc8Eb8qR{Ev5P_|&@$r^P0xauc>Pzfw)PK)%jNMk@+ zL%vV{(nAqfQ9O;}iV8|-R`b=>)J(|*EhG!-l35vJjc!xL*_EB6^4C4^%(2U0<$eaVZ?$Ce$i3>Z?~mHeLsXlF?2`r$RtHDMxHQLM~zul z?gK5$HQSqgJ?JSKfpS4L&zITOfd@!YOlPit=z|4)Uu_l7*VE7SAo0gM`?;y0t_NBq zXGo&;@AN-`vjI$^Fu~a;XcY25{UdS z;nMNQtO@)ZD<#mcHy`8g%yn=i1J?da)+OnD59X31z!ngT{ZAjKkO#d~&JHJ@ zW2JWZAMh3<&F*7fNWJgrx7X?Px4&vWTzdAAG~EI92*a>y_U^GQ~g{zrjRK?pY>y`3(;tto_`+d8k~3@wxWW9wXQm= z@8*5e_^rRvbQRE2#tUu%8=n|kkKwiK%c($ZI)~7oue7^_fnba&#=3F&f2ee2wJ2%j z9*PM08vg*YdN&^%G3FnNeG7+*a|%CKb>22gg}O39QHP>Q+>>(~1dxXO`>CUNbtg$t zU$TRu-X1B_-L1bPQ|J8psITYKw5xV+VswVf-b=Z$pB-uTjdoWLj@#v;+dG4`C!VT` zn!k3%syb}b;c>Afbdc3a;-@tdOp*Dd5_?s90Mxh77Pu6JTI3-#%{VDMHE}#ELr#-S zOWUL&m?2_XpNY6AG|3B6Ksc$d5D!(w{JuLgbl`XX%|1VC zZ>-MY7^=)J5@~#*jy?YXwxp?ChBYMdNU#Y+Xwyj2qA@GSG>Wv0u&0pm25LTI1pTXC zBdzVzvq^OV5^cOKTulQ4G5L&<>H+I?x+gBBxk6Z6xYA5)2E8QuO^@LHKR(=Ql67(a z05?hy)l~U^pQc>gOI5ixWix$M^Rh0sR{*UfV!(lW*k7M)wG5G(;*I?2`#NSyYm8Sp z=#6~IGh=aET1r~UC?z|fsgVYjn8!s^DpRO%Vv)5SK_AkMSVg2qX&mc zp0=MD+aD7(BoRC;_QdbnDut*YrLWT$$3jSCG_v$&DxoH@3zFBoqS+#Ts;7b?*OkHrHTTf3(K#Z+G zAk*x?A3vW#&9*tD-XQVq6BYM_?N@FKc}3?;0A#CX{$$^GhAWGaipm7T7lkW!SP`JB~wRDY{IFmEB6CAE7ZWD=S( z4kVIQ2?nQ$3!DK_QKI~vRcFo`X9u2)YtJ-6&{^c&CA+67h$BKZ45~o03%2MR~~}ALEvFw@f>qXbY|mhp5luiOOL};*Jt3uW2y3RZJ25@ z)ceLfMmg(X-E_Ek)l5069knC<(m<&Vpps?rLhl?@y0g39@1nNbb}25ofo({XSt(}R z($+Vbt~>@Jx3OB8JW#X@B56}ZY|+O*vR!UQ!q(2!A}b%L@j!Bi}>tY8W{!TqM1 zASm(y8ZlK(?%YinS_P!Z)8^r?rKpo&?yNi#!kwRjYQMEwMxd3}TwYffHFQ^aXsPGOME?M3N0F_1VyeqUO}IN*MR8Jg5LCfj`7}56+n#P)_egEj)_)=aS;0Z8}6Nt*()PEDN3*->2xj z-`-Aa-xOk$ULaSGr$_sFVpUup4~QPWY593{5@C{Rt@E}T7=&@gb4*cx&NOi0s{FIH z&Ggy72G;ryawV`;+IMAR-JvV#{i5_awnbYD*vnK9pJ(=pdb(eMDzCKn)N>^(#V$)5 z6wp;hW}~QvYTiBmNGq&wc!+>|Vv{o$1p1y9d|ZgVtM%;s)*b@z>c6+nwyamGW0N*h@{3 zgROR_ZEqc?oS(1z-{Tf0JcVXAaMjb|u>FAz21TkM75N9PsjrZ2dCo?+xUt;|GZWYp zDQLmc1Cq`)5JzgVchG8*x$1V?y~Nulw<;JcJ;&eQBD;1vOxJdIj`gPSXLoK-W^6irkFxL-LHw2RZGDTiF>z5* z{p77tR{H0iV=o*KBi!%4q8RO=j%BljB-7$Z(m826o!Q-qW+e8Ckb|{I9Y=fTFy8Yf z_aW>&M*7UhG!dPsyB~3Fox3d- z=URaARqmGD*lgSxZM3vPK=jm!6>pd!M*~p;ZHc9hRgNf-zLW&EuGIWmLh+E|g}Xql zMMxl3%b!frTzyWuh)#_pe03DnP-?WV3J__USE{|jX3$y8(Jl(1fG z^l-%+Ew~2W#tOoR^sCV7)qhEJR-AM5=^Tb13mC%yJonZ?{{VFHZ6FJS?cuF}91o|j z59QH_2anIFnIZn-F~;}3Rb{@m`bT>Ud$J$YY*5psmi5xr_33%N1$=o71cwtYLI}2o z)DbOR4D}T6O-n!}KW#FLH8Zg~ink)_ZDZ|Bkv^#n2+e>#JrKavj{wq`vT}Xwmb9?w=1QYdQZGUNCp)@{6^7H7H z)sUAY=T}Q=YDqD@Rkiapek7>OZ!OCL1tll zi+g@-EJ!kRlTY^4{{RP z2%kJ5p0cdcBZx%uH8^=osaYHY_2=Hw-ZnBj0j!13`cqNUceg8PZ6(7gD2E_%HOJ@C z`T5nkdtbV9{dw8+J;9&s4~ctUsd|5`dWxrV?wzfJgQ*{^`e$Nn-OttApQ*O|I91wP zs~MNUO$9VCVuU#;WR9XLik5lgLe0G(`t8pC@krh-8H|LpI~5Gx8mVGHK&HA@iU~Lb zfK@c8Z0%vTWIK9*KtP~sAZjf@4xoE#)ieMCR)p3j$TU*!8NTE0VZ_Ul#{JZ^v8=Ta z(aBsASB55aNh$TI1NKYc;xzdV~H0(IwpsXGr{Cv!Ty71T;BHib`6@axq3C zSgT+s?dlMvlBlw41wf4_P z(fpR|EI-WH_u6%)OJ;WV>TQv>SEVpm+;?Z=X6niD4NEmf>cuWF!&zHAGHDm1xmlJ% z<*7HBId<0HVCD6_+!FfWmXZ@H!>$NKZyOgyNp+22l4xT}tqm9-zrg|KYfFp$@a^_T zZ7Q-X(MIm#b|on)y;Lc#6c9~yQlO0+GrRV#b7@Oi-MyQz@DgV7z2TMqVf``MyF!Bz z@*Ct|Y;Mes=BdK&Zlj_8>P?fz)>C6EF%3oo>aFY}j7MV@;`a+VbELMZWYos2#x@fw#} z0F+h&jzhNGxy-A!@5rA~9qYjyZi*32%*JTX)GWqRR<~4=RV5?wJWqy%#+7H5-+jIE zcB5=jo~g#}js3SVm2{MG^&ehjpLNr9{W?%Vx4QoTA%@zdq*;Fg|U?>Jds4kePNX9hkVclM&M6}ttT`uMQ;9=Y4 zloR7h3}#j?%_5fpgp*dT0iy&`6?B@4ye!toeQ@lH8=4Qy=oh6*j?d|u9?i%;leQAx^ zS?&GRd0ZuI6d&H+v)>zjp9PKacz|*-*Mcpx6PUx8%?@s?>9aE;^GK` z67LvFGoz{g*h;<|;4;RgXrM9ZpJe6pwBGEJ-CYA~WwXk&ktBWs38mK>N{ycmNZFm6 zxl6_;2`|xsAg{au^CN>$bA{dcQS|T7;omyhJ%#DrquwhPGvdG%Dao!AZLT z?QO=_x!PVwV|ixldn0L76lP~Fqd?GD7uDKQx`7}N4@hh`4ZCuV=6%0#hIk@0c18p# zrF*lA08LIP2^i_a1+e=YJG+NlV74yt&hN@r$Q*{j!)?s1e(t1fL~AZw)L?1pWXaQ< zY-}2&JYc{NuHN?s*|^m0n_ZIG(G`lOQJ2P^Px1FDCZdJkT-2O%O?&E|3QGm?H z1si>aa+#P3DP;>f22xZ4J*l_YH><^IEjHO5JX0M>RI9JVgIg}5Dn1(V9W`^j?N%!U zw|kTk$0`Rx&H!XTjDJJ=Tt7aOxm+IM+ch+lyQ6PscH`G2RJi&~{x2bip1CoZ3Go?G zM;&x9R7%+Vy(HANIsq_LM)9_mQazW?Z#A)l>S8L=Cbb6|lTlqm)paWhk1%>$Z*^~U zg{`iVSd&hoj2fEMGVrZ6DGWVVBd&#UZzYl>NdkpslUlDnrB}H6D7Dyop(9xg)fN8$ zCr^zvpf#`hzn4=Wsv<>)P0`tz3uylUHlxt7IOGfcLA}qrR)DhnKkBLJ-6*uxo}HSh zSI1)_PNXP0jpbDypln5?f9gH%tMOAEXquXp;D2xXJv-CaiiB3EhnH6~riBt2?PZx) zQjJKy_N;1kd_8Ot#=dm?y3Y+uI9+J;k;AQ2$*GoEOIkUJO+jyabHVp^s0?Y}H3LS?Kh%13o>!A= zZm&|jVw)2yroIGCnWKfID#uK^MTzHw&$FIW{XO!~mdUU39RvBvPwp8(!z_q@B1czU z@v^JqWnWu-Jm0?{d;b99*HmvWiTfL{caO&|zWJS1l*fE}@BD80-<#gMckJExa2Oor zZepKk?n!CtsUq;yWHI%U(pAyY0H!JPWe_;%h+g`~eGCRW<1!mM$o>Bz~Lq#3TD_V*G zM7l4u`-9~t%N_5q{y&|M)&0-j9ewgssXBkD{ucF@PHgVB?H%Klq}`pLhNRwGx4pB` zj844Esg4uG`5=j=^k-N(ke69HVQgSpNWS zRh<6-mP!lPYU6S+S=_?9&Xk%+q;bHOX(H?)nxz7OLXZdtx2&*|ErD$|i8gK4TZ=;r z5YGvZxH$nduvWp;q?PT`2Y1ELzwkYvrTNkE!(6pVSubJH#~BQ=#VZ^}QYj)gK2Il# z`bfCA=Z|PqtJ+>;EffC$Az$);sB}-hJ$7YcPl@#~AGWfn{{UcmaqD{?xcQUWJvp@K z_PXsIwb)yK3r{R~nrznPtk`)xMHdYP5@+c)*6N_H#!^Y?jV7XsXw~dzbyPrEwePpv zZ--^!EVd!2wIy8v@?9$0)P5Bp5HYHN05s(F$n_?7xwlC#iOaUVLHQl|7m9-(l=ZyteM&^*x7|rd(cAadwAe z=CPQZb!N$?!cxWjKM{nX#|iRCwRO@?X{h0+KA)JKZ6@&EHbOVG76sJd*n4D zp;c5@w6F{u=MH*@dfR8&cKyBMv}shdjOxuIplU9KQQ@l=)ZOgV3ZZ~4sLOn8pU2<5 zZ5!)WuHAd0*SjB2UghS!@2L4S8{g~go?B%M5FFM|`0x3;S?!wKOld$_ATMm%kt}w0_3@J3+?BDq zmD6hwN`h?P&@HY0_wU~>z3EP}sq~d5H7mgJql9`tG}UZ{OKa7!ISm2@an1_U=2 zBp>Rx{{Uaz8x^mY`9Ib9^->8QhP^t{$*ds^OsyisHE=@J8t6b0$`l!j2wvrFeCM_bwLWbdywZsk^u} z4Wt9&$}9Gh=kw`PR3e`xMKqDDwe?ee{WOt7P7&NIHrY7;50> zUhluRqcwZ)^?$q zuW(0*tPax4O;))Y%9^}(XHwk7A$ReW1~ngBp*lgl-mH0(b-UJ9SneWNW)$s|MIN{q zdBpMLR+?J1s*(hi$!O8?_Rj9a1L6c@T88l*iod6xnqwHpR2TEg69)XOh?Yfa%&g5u zi7ZiLo=TCbDs-5;EOHAQ2P`dT7YNOqe%BOjqS{E}(@-itdPfhJr^};Vm<7Dt2s9s1 zaZVg@pD*=Ss=do5sU%x6hPl>k0)0rhJlxxn`Tqc4-1E1!5HbCo53LI#RgNj2@>8wC zKjA+y%Ll=#^#e$5{{Zc2bl9GJ8%{G|M*;MHJ>)+pHobxZ4QlK^U|zCY+qVtN5HK~Z z#Gl9}Kh^$TudWJ+DZ;eUMGz-YXLVK7KOB)_zti*h_9G`5IO;$HAcjBc{{Syelv{@( zkE>e!x0n=_v8yR)*^7^X%QryD=-PY328RB95|> zEz=Iqt}jQbz9p- z*|d)wsIL_Qxc>l52%+=EeJRzzQdDWFBhJ6K8T&eS9haYfDvBIlyMEuULXn;=tJGPv zzdup#!dGL0pnae0_3bO>81d#p}(pKQ|1~~k8he-uBwzeb!tYjwETOJ4de|8S^B(meJY83P-n>V8s?)2ZFX9C8{{S~qBkb&oxQa{-JDmWt zEl^bq4w4ncz$E@THvIedh|7vCdZ{QYO;!H@2iwzxU7K8t`mhkPn-tSpy#7d%$(w^dFCU4%I!158KzM zD?)x%>niqy1X=d=X(RP%mIq(2HadYH?|%2Kzkq(;y-Jfpaq|9sb^etiR{(9A_lT$> zK~YQxsjZ{NUtP!4`?j|uDmZ%e?F0C+Pfm!3^91Ye)%h{gAKZSG!|f^!=N?%y6!krk znXSZab)^*3(^V|B7)m^bNo!1Ve#0zn8p&fIDRJ$Y;Wx1)KTxo+HPlqMREXI~v$Xvu+1}H%w9zE_r6@n{OR8q9!1_nI7&n}Xnpe)0=s(wPGllwXq`yBP} zYU~5n-TlCU6;`pGjJW2`p5B99l2 z$!>Ep&YO=d1v!}2R7E6FNM51knnsBOK9vLB?r)~Mk!8DWawwvV0HFT>ML-zh2m?9m zQKWFfZQwwvTBP}(mU!3K{Xq9ZrouO7<3wnH6%2VHTTr-A-_%^*-q4axeL8edDd@cX zk?)=}cP@Kx$)Bs+RdDRuItskTK3ugEyjdTz$=Bl{siLGb){z!rFQ{n; z*azHia5k@O_Deox-uC;On+YyN1#R?rid|WQ(neKax+qjIB(TU8AScco)wJ?%+XnT$ z_}{yX>k%<0h~bi+oKTXL(f>N9yHqRh)%k)zx@afszTi*WwZavBN{{U&&xk~Q#P2w%j#+ECKR)j1f zCq|=|WOoIDT?}bPC#-$qaJ5EBB!1YJ?czl>0CEXDLH_^` zNPelLMA#T9VaVbPRh2SH6){Ghw;3c^ps!U`PxkS~%Upd*sU!I#1U7=C1s8V=ZzfL- z)#C@a&?^$6nsc2Vbpt#qGt^7WaJTO(h8J;or$-u=N-EHmAXQC8DA@sq2{B-RTOy~Rwj<3XrYD}B94}oVyLT#v&9qxB~l+sDkG|@jvLkPIla5Jxsfd4gTOE< z{8c5}NYw047Le7O00By4i~Pen{`R}L+F>Hzc;i+y1H__$?zN_xoG8Hn4?Ogx*)u9< zqsrD(SHnj>BRP$ZqG@EFjcMb7(xN#br5Jvs9H8+*9XdliBJGd4Ww)WD+ZwW z>Om^RU<%;St@kt#aNaHQrD*0WUH#Dqo|&; znk;-0(~5XB0ar^EEj-H(P8wLkG<1-_hA^x`>tG`R41}==NZ#rb8y8?IKZp}vBLLLr z<)1E*++6N*!KQ22lGnsTrh~*)MLJ|rOa)%R3F1IeO-HCxNi95|aJz<{hNitl8A&Rj zVN4mwTx+##I%&wruL3khH1e-4psDtz+8CvYOqT3SQjH{5v>s#5h-qJ5lgi5yyzjYc zX`?G7MRCMVr$W%45uU!(tA@=;PaIe)h!#rg{b>VdYGn`I;xbNQkoP>b)DrC zyMT==81#Z%i(lM}0r9rE7FvRklA%e<>j4yjUfo8fwE%JGOJg99Yq^rSw|D% zv)wtmvQgCStiaVgEB6y>VNVrQZ6xwcwStb}wURBmNG(jj=J2<6_#|S38k-1s3M%$)=V{T5h=A@k>m! z(bH5)^s4VmB!-02NRj^lJZueV%p3GKHg?vtTzFFMw(vJIN0p(a$xlyC@BBWJc`71>vvPT2se(+bsF7=y8DgrH6$z!QNQ}du zZkAYlHE;}xDN>Dz1fU%0J^Dg}o&e#2Jq6_PG)(eDT0m49d1TR_%pWSSAmCxNldp#B zP+sp5@TAU>MPjp7$O*KLFKsb>0JyOK0Afy3Z3Tq_kQlB{@co@0SP)o78nRQ5lK%k3 z^b}(vVZQdOwt+93Fj=);(JmsW-6Q%ckZq{)-+^yq>sJl5Zzw(;5&qv0f2y4e?Ij<( zw-iuts89RY$LH0@d^F2c?XITo?a@n$rq9W>G4(sPJ-=I!pASc#ZLzm2GY1h>nx~`4 zRN&yqM@(R9*s1DXl_fIxW$}pFM=i8V_1-BO4DlANIB+~l@D=<+?Hw%GVuI&#dr8`s z(n%0v2vRCYG$#PiniJ>dIzGQ3{{WS46Fs~)uV(C>f!kj+z9{dSExA$hC#*2_iS*jB%VYjrkfZJFog4snhMgUcy6sipBY!)q6 zU_m6*6I(wCK1A=1)5Cm+>K?%Cik|s?jf7Hl-+$FZk%KeY-B+B)=kc2^vvj6nY4bnD zX{fL%BE^$0m8Ob!qN|X}Mx;dC$zg47-&tiNndvx;Z7@6?ja3 zCF@S!uWUs$6X&9qiL-5-N`JBushO%mc<;}%y`hL{w7J$%X-d|mfUZ1;ACT$ZT?Ovn zPM+A!Lr?-VoM-34nd+=J(ZkCnEObwYl2~Y<89J#pL}4FWM{_ zhXfB|@gWtVz~S@xo`&|a6i}jvAMsrV&m3YW(WC&b7%2n^JRYt<(s}yZk8dkiH1q!e z1v)ZEtq-42a>RcN#jnwo>Mj5P5$Pe1^=2Pa{vQ05GB?@M_zh#NJo+(P-?KMvHlJ>7 zNX8-@W+P(l7-%3A(lpYn_?lv8NfJonH8ZHY@CC1Xl6|`&J}a7&Q~NQ~@TkzA#Y&&s z(Q2!ymob_9iq=?Owx%yT!ioe+&aty1JEE3F90I@-`5x~Y(4agC>rP3oo*;B#^F2+u zGPT(!#8M@7JrlyR$u)i|f>_bwU$@s5Lbj2lmPA{)h&rMAk#TfUylaPQ7Worj*bnpS zIZg83IVLRt|33i0Ao#q2Ki~$P8vcps-M_oKH??xR-)F}y7slEe-puS>&z;NFVyL!m z)X(l+y|giSnn*D-rEX_0y*FM;l8TO*VyG`PsLJui#r>`Eniw8p6ryQSg2ma`g+;{& zs}n$@i5(1fd+Tk=AYhkNfD&kM6b>i$9DG&s>0duf^-g!;PhtGk=zO-wp{?tF;n}@2 z*d1+On%;Dsv9@S8?JZ>cZ+%kWvM}T}c1vaFGFblrwTfzdk;p|dwzyOziYa$^7Co&b z8f3YdlA1*WBxXVj1L&s!P-3JKI$L>a_d9;zsI1Y&8nI*W(6tRun`BT^Ja_}qL+&WL zFB^#3_&jb)u(Q42TS@#|v^OPGxCr{%izk;zEAe}KYtTVUCgZJ|f{vgJg>_Y2t36pQ z8b&ono(|1&$gn82MWA9yc5lSg;1|h9#p_W*QQPf_9lT6sVRFEh7|=Z_^QRgb98)!@ z8MEMTzOK73k|`-r$6|b%s)F4I(!dLw^Ut$wxv6rL^9TGLH+ZFD0B{5jhI*y9tu%22 zS3-SUC9Vl0Q0M)D_RZFAW%VbAMz%-%S}Oklt36l;QTC)APw+c`{lZ-XmT0N>DH7v92(NpV?f8o`2iKHV|^&%7_Y5YlRtJm zNj>xKGcu`>)WAFlN7RH&NN{6QCu)s!An^=tJ8jM9IPG%8x^1JdCPsKfvAT)>0I;ht z5xaaryPAQ!2sI7+lYVrz(D?rV@y~JYuAPROcI|$1a_ZZ2tfi53@5sipmuxRuu8w*izxeR$v#qii!cC z^j!qp)h9Gh8_XiO6U(I-%Fs2chAE~!1{Iamp$*~!8oG@`C~f(#us$nS=MBqip5D$YOK3i;#H?=#ghw5?UxCs-{by8qOx??-O808h?opSSCfp|d>2oMS z5&D?rGO-r~fT9ga;Uc3e>sVxE(oiX7((Dm@7vDQ?VP<|x=eK5GDMPlO;%5D$$x&^+ z>N@Xy?y5BGF0!h~ZQi%s#;%HSzaEyA>S$>pW_q=zk}{G*%}Is2(76 zXuAWnI@+hJJ8wCg?takOdjg+u^b-7d><)w76q~E$X7}pK{AXa!*&fZU%x899{L9zT zWUA(;&$W1@l8UwnDg09p1w`U&x%R0nn`*v}?&2YR6GLfXK{R&BZsH}7NVNewguX3g z@pMV%hoI~>TbQ}qygM6byeV<@Z*U|Q!hg_O#$#4r)Kvx`qq%izIBF05qw)>57k2!2 zq3d43>aXsmd*%jrBb&?9)a_iNb>&uXAJWvPwD7qKX`_Q>fS{tVD4o`}rK#q%2ehM87H56R`0CxOSq1zk(0A^+S*8!01FSzY&47<$yaM`<# zJeKW~b?&IBH#H|}Cu7j$Gh(u$YI>S%=i5a(D@P!wmq1xVi@e%5DlLNTw?WJv8JFp; zgaP#$6qddqCj^o_LP^I$SoVHkYyH0JJ<~eJT>^)%feN~@@c($_mfC-CfSi@nRn}}6XOH(w!&qGUI2`?E_ ztpb7z7FvLyf=Qq~AO6w9_cv73bjM%quGQK5#-nb0k=eV>m%eK|pJne%zH7TGqG*>T zwkxywyv27~bY232qOvIyB@$xtGkEH1VyBulGm2)4-)i0YX4hukZD88qy$&Q3FqO&h z{AR`RB6t2J*pYw>NiW_9tZZEV~o4@fZWy)i_+uZtBY6F}>AAkc$(vVBB$J zbmgIrzLz6C8p{+h%E}`T+1%JX{L`~sNfW)*^j9zj#4>>MNV@#nK$tg#Ga(d4sHiTs zTh!P&9`@GSSO(s+M<{rUG%CxZSAc1+O&3O>LbVx&nvkx{cgJJzo#~s~J!82(EN5}_ znSP^w-0QvRlF97JHiqTL>^dEt*&Dy9_k{byXyLamI|~*tP&~r3FIV@;6xv=pmR)tZ zN4oCU>nAf<#kNOs1hLFKFi~TUIlh&hYGiV*sH=ci1Ou<8?RJY>8yk7&u-!BfJ4Gxs zk=iGjriwe5)G=LpjF?qXT_ZRWyZ+i>hnzmkF->$bQ4OFChlGc@$ISv-y=MS#+f>m#18p7(^a=n6dS-(=av(I?F5`HjJ+#>^{8v0t-FLC?k^U#&uADmod0c zw_cqzCxNXGmr`p>Zjv%2vFoo5V!ts;*ZFkm6=6tM(4S>e9yF@)Ojc;)VW?Be>En>X z{4*gXTaSA&Po@oU$f+Q#by79vhe@R$yB)R8IQ8IriUU^wVz~hDsNyT+PadaC(!fl0 z9!hddQZ)@#Jk-@q45rZ4BsEb-Cy!E-sd#V4KKCL|YQ_tjc_O(KB^^qz2Z1WU5$EOQ z)r5%STyh3LX;mPK&>kSu?Hy00nPqi}y-cO-#zS^u2ulVe=yg2mvHt*L?utR7J!|IK z86USjPJ*IU0wFM0U}QoIJPjCaA~x3AqdI{Ef3f#=scHlAKQ68u;NqZDK0tq$)2Y$S zB9VZ7a>m+Kke>lrloeTZ@(^Cvx3o80QodvPj;{2fu04LwE}Z`EKj52{9q$bE6v9nW zERjURBS<`ULbs1n+!f^eI^{$D?=6%ZP}9`(5a$}M$12bh;;-zlugj~)=-=hRQQo~F z@Q>z4Z2ULJeEs-^)!lX69e2LEhpv7>({z7lb>8aBc8RH^-o1dQBeZkdlLxg`T6%0v z7Gf=QxhS#~zi&YdtyZI*?k?fy8{4}`?Pa+7XdzU&9jF3V!~xPsoU*x95+e#WrKF(> zhBi)dxA%ZkAK&+Ltj1wJcx6YsB*jm9OwvmJ1l zr*+J7!7-YFoJFKpLIwzqNM>YbX765%Z^n;{pC^BnE`NS(UGLug-_rfhyXkfo^Xx1S zRPTMe9yfB;~NJdvR(u2B~A2Zf1dyme(mxks z=_5|cOr4~wtr!ec)^()G*?qIHDYwNQa{)h{NMDbcQi35@E4W!vwxxRE{;fvoT@@j1V_XX0irgcv7OA zDT;Xta2;g=Kw(%do)%S(X_PKOMOmZ~f;fsUkk!d<?_)UhQr}@3{t0ZNNy(eVj z<&Hg04Mc+c0{2`ONpq9hFs+z|&@SmOCH3@))@5DXM3u!d77M@x>PRYPx4I%b1HZTNXZs3Y8SJ z@YG8%R;(2ALL=pFUy3c3Zef~@c<)3c0wYg=qSqo>0cI=>d@#wCX6j7jO^VXpBHf-9 zlJY|33sCrJ@asy0Lt3Rp2-HPsN>pFW-uB&}6#h|N2g@f}a{^W)_>-L=W8;b!<)mTl%kF9|CKIIy@>$~#A z64`D0#CF#9`>o;za{+R)NUNxefJj%KheNupRgh8GS5c2WY+H8Wx9_`!t)j)b*r}6Q z0zV!&>EaTrU0T#JMtTz38Hnx%&bm>am*t02QcO`kpcP z0d0R_?pt+|RdpSw#BbW4&!P@MAVqGdzwtLGfgh%G`QUw>TvsFUR=)r#<J{Z;$GF<6V!3?~$myUj%e_wPy zb;ndBjsvGCY$b=1z{wL5EL=Dvn=Sn;M<3LEeWs96sj8!oO&pqo^6Ns+=C@R3`SJ7K zbvF;(b!q8alJvVLY{D3QMW020{(yVMescl6!I%-j)kpIFe!o0*1oNp6&KICl5=6E2 z{WRnA>cqOc9JRPCE;cu(iU~Fj!H7#ZNnwVa_RcY$DC=qfUnKKH6-ZkTeDCI4wzr+G zDW4kRx$`r+)Q&V2$m;^yKdF;+K*$yD=O^S0j(DF_($jFmg-Xxj{{U-|!d7Ie=;ETl zCE9|Hj6))2GIbd`uQ{13E8r2qNTDZ%-&(suG=j~sr51+V%#!$VkXd-MY5)KR29!PA zLt}yB9o#;NZRfj4+AE2rjZzcvssMahjE!AEoM}jCu7v6g$$%ieb})6m(yNtIAzL;l zDM<7c`3RftAW0{U;E^DbDQMdtOQ6%aA?0Td*8<+@VHM(Tmx!_m;ELp(L2|9zKs`fL zl0OY7IvU-}XBR1Qh1ZATU6CLt%qmr0nNgJRmq|isUskMvK&$HtM#uDy-^ejA%xJRp za^b2bd7CATi!qX9uBVbkDD^n^L#ZRwQEw>Jfz#MSm~Gl_a^{4$kgef(%f{GCn{bKW z2{<#`y-AM`;gaZEOpDZ+%8*STD(zPi*I$OtRFZr|@n5`r(9{(i04y<%wf_M5)j!^E zpDw3*XElvMB(bb=r7O%`XlsHK8_P|sDmnFdw18SK8C>D^vWu{7>W)|hA8rR9^Z8fj zUZ2|^Rn6>(+LOenA0xnhpngZHzsW{S(xU-z#1OSI{K4pO8^(+IljCXez1>IJTaJrj$&14ErV|OcI#xU`+m~(b3MhJ^q}w$s zSGecO#~W3M^9c+pl}JceX5+9+9RY4k+OkQINLHBAPBhk)r=c7;2PL^{fJsoj^Z){) zp0qj5c+~#@F0uTmrT$@fU!T1pj_Ey;*+1p!n~NP$@?U#W?A?`;uGsa58(fn?OS-Z( zl5hM~HbXL$uF~S^G*i3iW|Ag&+s|NUov#hqNR=@Vk~P-AHAzA>u*%RWrU}3uU2XzL zZxX2Si=9nFPzeMI@U1K5QYbxoIln6+?`ltn9f!DnD{ZK^kIFng*vC)O8+M}`h|W@H zH)G}TsU|-qhR;t;hRS2+#kD|msgYw=D&+C)!w1yHEyThy!~*1n&_5B>MFulc4^6=$ z#Us17;c9U;YIgAX^dJ8KE{vziZQIei8z=KaYE*2GlDTXiS-YEKRc%TgjGJ>ZH(ueT z#Zkw!adT8+aI00bp~qBOnf!AZOu8XwFvoFbcIjHv#S%1htLj+;5-ahiV{xTZ7@#JV z>aQ!zh|U0JuM7cB9CKgt^j7fu!}*3o{K&h1thet}R&DR)(SqC6c}|V)bn9Ade7m!K zk+cN{*QxDDD{5==C2K2lYG~(zof;|;U;;-h?H#6MjrSLxu)Ccxi6c4&tZG0!L5$Uj z1X7tLL$X{(OlugxjA|yNm!?4Spf%z7la7Wj=DWSVbM+s`eT~>(%d@8??;i9!{tRC8 z*zk3gZ*EWij9Y8vYASP7J2xL+kFS#@OSz+>Pq>5bBuaOa_K)gUR>ob*NZ^8T6Xva| zB*&#?1vB{{PN@{}K@{dx)aOY+O95J)Wa%KBQi8PNXnH!I94IUIhgx7E>`DH^aAr2{ z)~VhnQ_!vhcVsr^Hmh{gQY_v_po0&%rl^S_CSMXn5VV%o-Vv-U@w$?VNI0cwgH9(s zQKffed~*BJI7ZKJTuh z#(am}^}7Rn?zwu7wC|6!tgZg^?d{XIHqT$-hW6ITTA6zw9X8D>$_M&dYOKw}L#aw}G-UfnbRfyY%zu0MoUwgua{J?XbT zCHG$b>O37+V)o9#>izq>x_4?zNt4J_b{_lN_=?KCm$U0JxQS@8_3OK`aKT8>Q%Ma& zG}cE$>I|$cJYE!FEUkq&I#}=~xF8&maZf(BrZI3#jYzUs@DvJ9p`}edc=S^L0F}RZ ze5d&p(wl3veqr?i=x){A*{$nJI<#%A>9V7z+4wA!7;GMTr)c&TQ!TvkSqz?1pCJpy zTPm4jrAgsI46(b_Y;Jbu5Z+C$>xsgx17$%7N`p-Ctq2SQRCPwUj&xHR0J^cn`DY|o zkL6w+20fMXN9L9*`J`?ih&xB)&K9TP?%(T-2WjPgQ`N)RR9Vb+GPh&mE3>$29l>9g zrRvPaa~s=Ph_F%NDQTz79Ao|OtR$@trrWOB+WcH;+bBR%oLo?7@d2))YQSlxkZQt$ zuZg1qDAq7#VV187SIU_@JpB4Jf6QCHJ8$Bb!pyJ8&Wh?fK-~MrLT~! zML3*v%u*y`R+6*{QA0|xWf(L*M4D5}rO&|r&)+{Hx&y3xPqg;b-Fdw`J7QwDM(yjB zk2yytT4u6!*&1nf%y907P0dF&6)hxF709AhFO+KpS(&)tlGTO1-F$VRdajeIg1xmm ze#)9~sq0cm97iN*K_KAgf%77j&z%QEPvd{iuaOA4jMmNBHJH;8ppprx1wBB8^pi2x2fB+r#?91j zh!$2DP_CH#Kjobc*3~=5us1fqOfFw(OSE!>aMR-IHrcI~p>otR ztTj=fg{;zh^!7WXtsTXhFVHChLQ+CNp)5nG&?umGu+3^%U^Ahu>7@P>&NU|uExdYsW!D{^T$)?@R(})7sqAH*D}RS>aa-c2fK)+o)VVl{Akc6K{aDc5WUCGhxj^bKMc$IwGmN? zr}RNI&OE8|=?DD0K2q-QnEfTOd*5*NzH_E&`!fYmxGpCddo*MehbK1ktDC8p&Z{y715unil&tZSqUu8f-SYS3^w zqO#WNkgkR^xCbC<%Id+@Q$g|>=*s^9GGCiizsuL-cGdYKnd{x@+msuNwe~kl#n<~2 zaNxGqvC(Q*dH4bdu6XCenIVq>h>AsHm%iAyKS{ZlSx9AMsVyc1RRD zsY=qMqPuaRpk614>8oD=c#_<)5Tex30!>XQDpU-bl1~77F<%(FXEogYS+n~uEr-kP zX*a&q+WW#ipSb)da_q@>9vYi5HqqS@QY3Ib;oEam8amL5s)1|dODN`Egbd2|o|05Gg&KH}=#twC3;1G*=wWC|x|Fwp|c zP&`6AA!pUgZ~}sT<9FV~YWA|xH2~kdRDq5m4M?dR2ikoB;nXGX;-m5;YW1MMh|px3 zBmBiE2{q%2Q_{9EwDHixNev;Ih_ZN-?Ldw_2^x@NZ7<<^lA4`=Qn##J7E#PAu^j@) z)Ll7c&yxOtASqDLBIk_~Aws2+?x4;+#+=Un`{aHyy?R5emZ3z}LY$vV_3 zq;=I%MXSVW5SW&!DdyC-B!&84^#U07_jf0X`3RIcezAqWmW}=R>?on;X}v#gQ%03kNdU05rE$S zp~)mD<6no3IzL;6q3ZV)MlQP`wa=8sW2BB^x@W4Y6mc|ooQ%y36!O(mz?x(vE|9tl z9$Va9x<=+@+$NdjkrhEClTuU))w_sOM5}S8J89AG_axU_&D;;UEyULdjLt<2WT4Xn z5*2l-j{g842nDJSP8(P4v3a@WNb$8XQQ@*W>FORyRur$N`+CZ-Y2GSnDzWs;Rb^wL zMU>x2a*{WDl)IW(&(!!wH2x9V0Q4uyxfRbyw!f#b-V#MI%NpBA0<}mQ*G!UNfvFUc zsNe!U19ZbzLy(F}TBB#6%2QM&6+_g=Jyuqp77;YKz|gD{eV32LP-ATZT_)gw8M`Z+ zS=7cmXN^X@9@2A0C)bMljE<4s*j>d9wcm?dOMq1vkX}_n6^aT`gjiQ)IztibLl&wk z8u}VmqQceHB0O?Q1hojpCsOb;xeMLl}wuI zA=HEb95Du(!mnitA3Y!r`)+Gndcov$(k+&V*%G;Ig?q8PUh&Z*lj-C}zhlEb-NH*fB z28MXG7t~rA-WctgMJKsqd?1R69Vf-xSuLd;BZ8+W2o z{{Zt2$ZfpuUOY*S+?93ve^B{D}E_$S0d7zM63?W%bt zv$SbV#Q{{Y&Nt^iOiW9~<_j7PNYpsfao{{Z9T_VhcmM2gP!Svx3|H2#?WMD=%H z%jzmBy`#VB@^sXd)RWiI(pKT}Q9DxQF_qZKXtJ~upm@a8Rg_XZGOnP{9E2^8KIybY zsvXO_9wJkPFs7$C^y}79D@}h{7NL-UeCb?|BSY1>x62OF>s_U_C+PZ4t^WXKYX`RR zeQUSALw7f2_J3SHxF>sNor8LT>GW8CUFU34rdx2zj*zRt&d&zg2 zpAnEE#1%lHW;%<9HP7i3t55=}@>gcl=zMQZV>{n9lBxbR+daX#do#BCzjzI;irBc_ z$Jslz^LebjCe_$jNNKU%d9d-7**Vu4g^0?OVre}=9b$-=d)+3#KqOO1;>I>Gwz@}-60H`f3ieiXx{w=FA~H~rR24o=-NaUa>Cf$`slCHC z5YEeurph8Nu4?M(rX@+ZAjeM-`hSP9iWU4wDNdvtREB_trFu^$lLP2U6kcFMvYVd| z9H;`;_UeTwDS=LmW6(Grq2>Yp7m07J%}U?%bzoUPkueWLD#!V(Yp{7xahC&tUS~`N0OiLC#0(j!y)U&6HAZ0ZN{GVq^ zP&S2Nb54t<^uc2=8JK7>8LEB31H&AjcS`Wf7?I^*AT3QKk-LRZO^@Vz@-UJ>s64>W znXg+v5);Jn>ey>`W;rt1x+dE@TQgS@r97i@;;V8m1v!E{$wehDLXBx^VmDIk7}yK@ zN+Q>!tgRSQX{LkE>^SQWPcq1EuF@7d)%c4xzG%H7@3vm@($ z*MZ+XeY*PRy83^&_Uh+)YqNT9d(+Zw?bWe6Gh|JZ#M9Mn480XJ5C|lkD;VQbI%PlyuW;_93#8}{gLz;pJ1PXaen|Gb3c6(jFZd=&oj*SR8br}qfppENoUz|hZ;iUy_`c_Ww0BB)e~X%Qq?r>LeyvdHRf`Mrm=Y9s{F#R&ZR7hBxB z#ES8qK|rsO>K@3FXUa+e1kEiTrf|hWJ#;`4679~badZ7Wm{_n&i1_LM04Ge|)WoVd zSE2873R--{To~x9BF4sI6lq-a^H#+hMz{N!XvwB&9zw)v{>`suzqIco%IzbHIX+z) zTL6$mgyx+b-+&n1*_-UX!p|mDE4Zk7qPLwUK{%9}-uQ!be1Snci|)RXlvSH!xV%S3}t0;Ee`1ENlK+pgPmGwt^_ zvu?L41*~!gGr-BEL)nxn0$I{Va3O%^@;zSCUW^9&rM zw;Pfq)7)4hh_%EavVbz_kVLF2cOj`oUicN7Ni{PnM`>l+C+4-av%PfOA-z_)ot&3> zov~vOU`dXEMaR2}4od9dm&0UaW#ToEGS#>`jxN zs6n@DvlKWw$>dbe)s==^Wm`p5%PB&jx3IqFwO#CY_BMsB<-L+Pr9m64i~5<4IVu9{ zE!ya6xusc8Lv6Qrvfbv~qOz7s+FZ4~x|NeeiaWHEO+iLOt}#%0wB7NvcJ@!_&thkL zzpP~1xrz^n+ZVR_YpynS*v8|AN4PepTlL1;qQ`Y7TUXXm;J2=8YhtBvEW z#k`VA%|zwoo3Ex$e&&f~adWy$3=&!p(S|d+KpmlG1}Nl-guW9nD-e%bsVcokwzJC@ zB10C-bkA-#Ib)UNE>F`u(z!CY8uYr94I+x2UI_;S^Ue@ex@9hNMo%f#ZP5F!K zKEtZab>7_T+Rx@Yv@kh&GaFYUwYT?P)kg-%hi&EM#Nz9-O-S)i4L|Ui7|ODSbQU`_ zZ*#fw{gYi>UOdps(Zh8LUZDzHB-iY^WR5n{#3Is3Spy0ca>d;7Nwe&*e(thOvId$U zl1BdkyCrQX>|6I#_KfXRa?=9`WK4f;kR_$)9JxTHHI{yGG+fsGr z=f_jwHt^m%X8}x;V(^)oh_l(P(O0?TsXL~UiYX(;?l~)=P$G?eg*QFF>Z9gu`r7u( z_iR_b7zo--jM_yZj+H8=y31*+24P)Y3^r}r-pg<0Ew=tkuiiKQActBOCri5xY`w9j zjXn)?;b;bjqp#H29i@%vE}6&I)62L%KW}e{+4wtqXwoh^ljGN0cTOK}?kfDpY4<*I zNNSTW+xwGwQDEq?*eEKfWye;-6;$f3)axM1SG8VUyWOCJ#oE_o5I(5@w}xF5Wk^W^ zOS5o8GjY_w1$JOSPj-e!-}geSslCU!MDR9}Zzh9U1&Z9zXtqfFW@!sBVX0REsa8Ad zp?gEAy2qls6S8rbN?o(^H)GWAZnMbH?i?O|ZNr7ey)70-r!j`2o@%@lg1V&@pskHH ztJr-Q2=8#RHZfU6HN;Z2&8p0*m13&urB+bN0CE^=QK$o{2@I^FO0(VUFZXTY!pKM_ zv7J&t$W&E{^mhCEW%c3t0rAsv{Gq{Px%+AA?w2pPv0HfN-j16vv`bT4MGZogCt9+Lck^inHqCp?f30r&d?aWJ=+nmv zAy$cM3=v7G3}A&J7CMOQ&`)H!+&^>k6~8XY^&6~v#QF@ZLGY!NH;5#bitVRak6&#? z4hKeibz%BLJ=^r#-w`%1v3I;b4|)T1bnemk=dp0OY~I>gD(dlLc=ab*@2GLxKD#fE z+7YHoo?4xG9kmiO)zf*%huQ1Brsulz16xSfe8F=KlEzT2yrMG_iHuUQc%mXL4I$FT z5LyrprX3N%F7Ioy%V{;dmexPMF2v1r%_6$6E#Xe_{-Z0++6vM+i2+!t2cq>$w6;Fn z&3xUb-`lI>=Jwoqj*NqQ?aBU4PeV!E+jn~Bq?We7ZS07!QML|0lN)xTf49lgQnEuU ztS+&nZzNzTa{GSK2RrQI@+qB`6;_fpnrD9LBt(=QDDgN6Jje+$6{@O+Dj|+r+nYX7 zlFG*NI3vFZeu(I|XcQG$Bvzw+3k<4I9C0I$503c0@u%syI|7qp&AYm0hHcljDEfD9 zZH>6o{FdDLItsCpt?j8DYBKpfqq8U(X(Y)r($q9mu+Y*iM39(dUAMuz9ffx-LTH3? zq!ykmaiIV=i*a(5Qy>*S7$?P%)Mz0A4{i2cp|=*YlHuaqnGxRLhd)UeBS5z_qDbex zLUw{$NeBecd#~*-$Lt=Ur^0q-8l$MXTNTn9HE6rnV|O{t^v`0&fS(7pm#HfDjF@pv zxAU8xj8?&wfiewSN0Om+QLX%B#_C(Ey}h?SVZ4R8eZ{azp`C!add40HU1hvK3^Paq zAXiGM1#newX|>vK?fbP&#`gEpyW33w62>HEV{np?H7sXIjFLf(fjFTm?AAN0Q@Fa3 z@_F3$%IMCv?0Ilqch+6aTh~%_R_ej-y}6deZLQbw;%%jrsLNMNfXhQcoXOYarh1Hs znwn(r%pC)vtgQFD4c_+Ut(Iq;B0mc{pn*>`o0 z2@;%*K+xuUz`vVVK zzB_8G7~QeiI|^DFD(q(MpBqn4NmIAF+4oG9kzw)fjMVO~WMeZ)az1E?+1ql~*)_k1 zb#DyXgGu7e;kl2(Gd)Qxz&Rd5tN|nw(2JH#6K)%=?SX-Ixox2$D|KbIhEU85N?Q_3 z;psBTjaZ-yLDhenm`|1THl-vpI{+jXyWD`fWB!NOS~HCNJq=Z>Rc@SPt%y8D2}D2{ zR#sVK0oK~JAOVD|e!pLCY9A0>*F9;1lEd+JmGU6?{3NEMX}u&euw!J`VkH*(+CPG4;qsz3R&u!b$rnZOzCxL1R6)dSi|YK2J*nBQ-qUlkk}?Hc z0#BjnFU)YP`&5YI0EVYqL3|F~+jrtG#~P29`_tuT-{HGY;9qHcNb3Ip<@L1cb9GzW zu)BXH-5c9GPuyGE6;mvGYYDdYt}0hdet1z%W5?y{U>P`M)rhXwxJhYq&HJ=AmWEzw zxVC{RP%KvVp%j^3U|S@&WKIE;f~btc#EcKJ^H$Nx+=ctYecjPE)wrFK5J8$*jeIyF zg1Y4=N!KE&SP`|#!aAOem&U%z*%1XRk25 z{ej+i4aZrux1KL~;d8rUxwjWo?<~|cD@#iCZ4|iZ@=`;sV08y`Hrusd%i!*Dq;{yX z7!0wj&{W`-Nf~3-p_mPIaE$spS&D@Hu;xqdY~-$A+V);`mulv1w(=Ld@WS}h#}mAP zR;-NH^HqF98x_|ciIi$ehrcPi6KroPUx|GwOWs4}Z)AK)_}`D}4*2cB}BD$fh;dp*Uz-Kuc%Ta8m8@E=1$nJ(TYfOLi+5>;4$ri%N={TDaS4#JaUc2{C< z?T`EyX4LJC=e~Nzhhc9$>6edUVWF$W=XQP%FIA7*IP|MYQX2P`cdCX3l32u(7En61 ztc!asq!$SrS3*rBQb?Gg@g#_NZAxQE7@*=Q)?`~pv&(C?Nwn{>-CCHKiJl^lA=GQA zHj}Eg3`&fy0j+v9-w7Uf`K|H7q`{@>dovSQ3rkNBF{KrFW?7|hut^rH>Lc-Q&$LVk zhH^;6Z;w%=F+nMby3r%Fy z@YDq!2`ud^GnN&Niz`u7x)9_EHHATEC3B>EJl7j;{UZ&VR;bw{*Cb}7%Cy#@(Xi0~ z6_!Hb+@q<6toxs6{FeEHzIt~R@@K4i+v7jQ-;Ujdw!6b(d~MrXzL&W>o3ne{YT)vi zO{dr$_ucr)8XdP)w)*vRnF;WiY#cBOnu_B-P3okAl)xn2xvAwhH%)Ys+{mRNiYSU& z+J*`|RA&n$w+@b*-!|G>}VrG&(MVbi2Oc7&u zrn2Sx0aX=dAl-CMc3FOI^lCJ(P-`+9qwZu_-f$kPuQy^xF^vzFITlVDLNuUjo;{Ls zo^LKAP;`jo`Q#up`BI%4`+p>jJ+Q6~-=C+3O)LJP)#b4VO@X*Sq^-RmfKB)pKhxOf z=U%4K<_8YDU{=-^)yXW^QZ4{ixBJJxb-ue*Tj{XWH4j%HpX#80f&Tzs-o`j}?y@D% z_Kk(Ov9PxU+xtaN*Ze)}uTvd=|JB<_F%FK36-aApA&EBNYCM7u7XF^fkNUn{KGhU8 z&r;%lPbIhon%G`6 zL{@LbX|?YtZSk}af<9|T*EpdRsWoAd4k)BY88r};nC$EX9HUB9kd zwND$Ef0R*wtL@KLlhqI=7YT~UWog#7j-z00N=h0U+O?*E>nV12IL8zt#>}}2Ylm14 zfh!9ZzdrfjzHRevSBjSR2^mS`F2f|N%;uh*!lUKZ3Qu>e`hmaw#rKWU8UdVw#@4N=IVU!GW^eH@(5P zU7hCeF_XZSM46a3YYO%i97EI){zMA-^ewmE1l*;vUc&43HnTmr@guB=#*ZqOAgr~gvb(dc z@jI6(vrgvDZ5-Cg$S&-}V=&olramk#cnaw$DX2FM8;YbY46P#|K1k$MYB#ug_|UXs zw4-UM;gO}7Y5eQ!PMwrMqx79za3ojlr*H9H{E_TB z8hoC_*pcl$)m4h!IC|_QZsLZrJ?T%5n`-0r;qkQ&W2&f$ypXg<_Xtzwl2o1T(k6X0 zCB~f~5KT!e50L~awGSE$^=}0{80IVny6F`qi3WsV5GZ{}#(E!n{{X+XU&bDZ%Y20G zT(H|6MX@L`H5=b?LyFF4 z*qiSJ*`0&B>M^-|C-D*yn4dk6+w|KrCmk&L>I=n1k*KLftBKk*R@Lo=o>M%L_znWGU1R`; zlm|;zr-%cz1|aDshK|V!s)T16$kYcC0UCvAfl-m?!n{X9kILVeeKGK-YHeP@`6byH zPNwVKdI}iFicHozzLG4KJ0VIWNXs@thIrL_@4$+ zpyDdy0+pwT$xA91)f)ho+UU&giwlUs;>uJtML|+WaQTdU`gUl3pI>^J0imG>&XvJ5 zHS#n#;nVMU{MzVGj$MPcdVjh*i(z%2Vs>Q?HovYm9_Y_k!sC%N&{W1?D#p$%CZAo>zLG|vptLEyU<6$Me5K(FFp2vTTiQayNe<$y^K)H^6l ztw~kNflvV;wg})4A6|w`=Val!&#E(Br@87e`zv8=>~&`2-x=KXd{|sY#lX6%zS}tL-f9}7iNMtEeD*^Zji$A(4Ak@ZR59`aiets)~?5%TKe30D0H0`meNh&un9Bdmpdz82#gn-87W> zoObKLWvH|GjrU1dpwee>yM}^#ymo$;x;3;_aZ4<7+tTgs(Mb0R8>k~t8fprfd0>D? z%Ag*bkrop|*aJV8NGvbQzL)L&(~#ni$8lVPWQ z;j{3$yoP6DPf3>5MJTSOrDdrm0yW)zw-w-$Ng`Dxl+m!j16mpq0=9h#>G|#aAZj!{ zD^F4D(3#l3Bz9*-OG5`>c1F?ah<8a^91ULc>|LwZw0pv?jiYA8ZOJ!AZwVgc%F?w` zlSfKts81@L7IA%DUoPBXdFBWh(M@Sn=stBL9COx^(XL{VqlmJtH4-WXazDU-Vf5+O zZSLGe8&@Z~F;o*lgh#5$R;Z0>#S{=D)mLO^N79tkRPjdA%IsBRj2AXgNK>uKyxJ&0 zB!lHll77x7_Vm()X#yOQKp#5b56^(n2=UUUN%Wm-E zRMRFqXhHO?2>EpLyZggpV5;l(F6++iY7DH=#Ze~9%kB-S2I$DrRbHNtDUI4$9E^LD zBSTeV9X(w=GsNz!sQQ(F)Vrv)mOE#<2=aU>tOEMGMHao6B2;>`^Kik{w(C8=oD^xY<43X;I;Ll_2pa!qjQ&T_cTr^LDi=z9AnlX~*n8=ILph z&TWc%99A!M;W0U?P_#KZ7GN2rRb+yAm1-%NYerMg zyS?e#z?{rt1XEtU10dB&sNy`UpH7-snrekoNaKo-K7THwYi+;$dMe*M z#Ix)jj|>3J@@~q;jaX>(!HbedWMOhz+}QsBOAmOl_rjE~wR=!h1h(w71bRkINBMqT zL0@<_3&{2;W2-jewEIL-llwX%G#Ip(8$myXH7$f9o@a`X%@?7ijdeRB!dU9k3j%JO z-F@>5aMfrbfX1RHu9*QKHE2R&q*FNK{5cdjc?2qKBaxP>gw%`$ApAr2@gHc;I!^9t zZw)e)nR;B?2 zvD!6uV+Cb63LJ(cM%qQ=WnnCBPpZJr68GyA^u{yjeq)IFbQ5@zB$0(n01lEtAQM4P z=?|BY^yxd)m5@WWFc8a4QB#aVN*Y*dWTl%+WtU8KMUj?Bp?^{>zN>5VaGw4Kl4pMy zB!H4dD^A?gJV^fl4^ck%IxjHaB#~Ah5;D{}Tj3QA>*}M-ih1;TGO^?4%~#7oC2d7m zrp1hvF(RwWK=e*%vJ^g4Mx&l+hxtre%f^S)LVJs^WoV@_$cmPwbt~4j!0kCX9BJfg zI#Ia647XFfah7l1k#V9XssF>8mEl!I`S7#L*fFXliO<#=dGg zDr%WyO4;Q`WS(f~se+RVpCr+N8T5$m!HC;Od2tj5T1Ht^5Tu?e2|o=^0sK68bzO>m zzUuYucNyB=&0{F?2+Y13u>stuI@u#i7L7Zcc8|kYRmPf&F9j72b+dSCdbu7N`Xf6A z!&L%OC@8Y9!8Qjds(o~C3V~Gjl|+i5w`|7Z)?22rF~-zugju|=4H2$ zqqJaStw=c1nJNHs-~X0mKmw&=1i78o+{ea z8sMd4EUOV>1W+k5Gk_Qo+)%CF-F0Nli5o;0#BvrmwMrLJdUlNWKjB)pmqX32aGa;Q z-8qL;EE=q#kR50PKae>Je+sXA8UxasamQV=YqxDS<(v2h=BCS4ZT#~9GNUb%(H=^w z8VdX_LnV!=qpPKp%N*45OAL$3zN@N$_g-Gyc6+;PnG-byNVhvZECA zt(T|H(j^R;2$m*_ETnZ}b+QVVnldWmVRkxnkTjbckUjV%*p@h?um(XJ3RAS7PB~(K zZ$#Fj-f}N3?-gJYi~%QzX@KPXLYeZQra1IO{$wQ^b^hg!e1tKpq(T~6d9yDZwNc2X zmU(H7Gb+VUujCR;x)7T?0(qPLwtC&|%9a{#6rD!{O8J6KKFSJ`cyuY+7E`*;9#NqM zK<=YcBZ%VIYF7vB>VUVFDzXfPO(Vq*mJp5t)I#YrazX zhZVHof~HBTH+FWDC0l{o@I!^xyN5YRhos15YB1PmwDl`bPc)tcW2V6SW0&T(Shpi^ zU+DzM8%XY@G7_W$#9>Jw0&+kHuX6e%yP=Neo)MJ+I)cz1dj9~lb{1~| zChy5@8s??TJ`$!HOht6WK+Tjf!n;gy*jS4v3dT5)#8Q+`^io*sH8oda7sMox2m`FC zwXwCbju`Bsk_%)}+e((9p(L7;&N4x$)5EmWq8;$}u)BI1FO@$RyU};a%KTNS&24R) zne16(%64rA(aYj<(qVQE_00XQId@$?-iDGXF&SMEtk|l8l%P<>MFbGvGVL(!lS=mS zcvjLQ0T>h!vYj+vB}Q6R02){l0M$VibEe;AXSvzB1y33?Aqh%qQURd!I)EdELHYDW zs@EQNFJ>)dJ#N*bsrRYdP1)HUu}6)Mb!ejg2?o`Rc7?}P?}=t(_5m4YiBd=9btyaA z42td+a-RS+_?x^`Vz{MCe23@K?o8T&6398e`HicE8L}AiZikkt5aKPstSo9oELnt#6 zkU{mQ_&N@}Y2%wpC;-XAuwkq1xi?=&*X#8c_iB~}iSqvdH%gJHY12k${w+A4>a*5H z06Y*3WH4XqOM7x6OpJI`SEEZ-1|~G~{{SaLKVfaml$ojOqobH&hSAxw($rLAYwDt_ z`+OA&r8PBeJtTls)Ks(BE1yWS@I9%LH+OeXX|Diq;4%JQmPSBC2Y_Gl`t$}?Q%R1> z(k)FjRy3@%)3Q}kyi>&)m0Qd9^(haK00|cwTHjlH*s4gng*4Nx7O4z6+8+V8Hh){? z`yQvTwl_)cy6WnxJXREUHbc4aIlZYdN?ha{vu|x)x2nd`ZzwZ+X0k|zH!CoTS%o~& zIv{T`UDWsXf;)RwlT#6?mKf$MKyg!jY`9 zOAE&>1EiEjLh-dlP?|c5)B{oid`H1#_xJNB_<_~?IWqEf=HvN2voqdJ??r*!c^$8^ zde=Ko*!!!n`v!sv2=LX|{ejn;UniWackyDeaL}~1Od^Tq3wFD-g6*#_q)65aca@vO z@X|jGOS=hNfTsWgPNGN&R;6ceWbQ2PA9S`znYUtLp;cq6G-W`bkQzb&Uod#-tp)!8 z=gafYVSMoJ-s#`J87g~TKZ%ET?EF?9E#;ie<+`J@dzWL<<+kSJ`76{L4{%LUPto<; z`)s5bc_GEekDqhm@nb8LrjEY4rZ~v<^$yQ`mYxK2O3oCiMLo=9 z;t<-ACw^#j zcKW;&ug{~U&>NOcoA}|sd+TNFovpn)QlsP+(diRUzBcYle_(04*D==lefeC}yE7S) z#ZOI^n{?rzh~-*G{{SYLsen@VBaMa)#d&eAIex(0Z&L1l6oFA@VQwJ~pu|zi#$+TJ z7f-}PHWq<>>@EKJx9r!qj|SFk<(i?)HJM~c*Y#?-2<&ufrUOvYy(_VpxFqO5=0CME zof8LM!?1E+AG;fD?Ton3?tSUg`-dsr7(KC>+oyU~ifOV~RoeMU%#ma%8c5P*m0mv^ zGx=<8&nxrF9kpYQ+iIA*z= zo4Jh`_$x(>R)vVBwOIOfH%pi~w|3i6(vnYWq|5!BY2YE5A|Q|PiE3Ij%~@S znVQ^$+mi=Fx~inBp~BQl9VI0UlESWBw9h1N5jFR?+h)ac1I@QbJ*vkNsw1hI-rh$w z2ulwT_>HcrBMm^Hu^_#s-S+-m<_*rudFoKgLrmE-6wG8cjT>?-m+$Ae6H5pxm-_Q$3umr zr>yWrQ(Z`^($c~dk=pH>4ZW`OH!@pHlMT`0N(Dq!Q6%h2>0(}B0!KkaEvl5rb@_*J zYaUM)KPem;oc_`Gc8+5=x`WlQPRB zCMX$MN)pi$80#Q9f-0w=7jX3U+QNJotL(gf$vNEBKgE~eEmX8MT}yGVG+ z(y^dW0H&bb%zMG;Ne1V9{M-Az?&OZt?MXM%mf48^w&>!4RT<+P8ucLeKFh{(+if|9b>aC)> z;(enD%I7iku~p7iSg|^bJhBd+%GN~Nu6LVRCBBXB8m${YZ$`p+tG1wg|i0&_# zT{Dx<>|LGmAFO+iWOgiDGiLSmTz>>=tMa`~wxf%2Lnaq-R>hd>+U=WFkf$)$RkTBQ zL3T^pMfQpd8Go!dbMM01;#qe2q-gKrTVop!(~QdudWNN?VkuE5{Z^(=M^f)EWy+hc z?%UbyuPo(`vjW?fWUo-j#19u(3>hg%IE+z37vjDjXJPt_fA;=UYwcX7Q)_&hq}V&Y zE#KDop7Y#UZnismEaGgvgS5959zz{Pzp@*Mv=6&A#E{XfvQ6cQ0(;*l$ERc4q_$Z+ zLwr(XgejJ2yg2knBQ-=;<5aRp&4!>I!~xR&W|m8x({0;km@TaKEg~~Y&?4MxR9R(o zWn!p?q7V&OfHa)+X>l11t+h99C*tQ@^oDz{Q#;wctF$`*0J$@J7i@PYP~>Uqv(-6T zET3X#b5&99Na;3gb$`L?==|lFEM7SX^#d3_qWi$v?Q9m$W+Lel@MvpzktLKYlY)dH zBorFmNuVo2SD@UINjfU4n7ji zDXMAeG8pQ7x(e;P4ob3v9g>DDh&A+7g7T(5w<@b7FwU{Gu{5E@$gzs-(ib)|3pH?A z4vq!IK`~ThYZX#PMyibUEwqKTcMzp;NXW+$Kcj+23{$Ioi>~lp_BIb);1?5y>70)3 z+qmuD)$)99pQt;VqxPOxAD5f2w*J-aZQ8jM?JT7xR}3h(J#I1w{lD^>fhPZ6boXs`wbv4&$-qN6Dk=#_kk*qt-6Yqp%dRoT<;YMhlldTvY&Zu{GPzL;ui z3WF9eHA~uCCJG(53CUC$VViHu0@qO(mU6~9)F>lyI~R!o*tGah7N-bVqXh8M??+~A z>jY3x5kS=FQL$d{cX8Ye;>e_6jSgdI8I3!T!o`l28c38HHFVIGC#8?WZHd-<}L9P?5dA(qIW9%mo7O*(zX9+(>3l(m%U7mo;#6CiMzLBG;x?cwLxWW~ zrA9GMmva2?aj@*y69*DCta`O&nu-Rpb6s@S51nh!I3>InV{q{^2T{qDP2()9Vib?B z1KDiUCbj6<%}`@Je!)(rM_7$RUmS^{8eCv`So#%>d>*qB=p_k1*WTeU1Q&(b9+~1w=cOA2uH<2oq*&wvGo!?Vw zjirspg4JCDKp~P)74?|PmOv`R7Y8KmJmJU|aNb+R`^l%8D|s{$=;(C`JU|CymQ|K2 zkjh8n2ve`+L$m%B{H^(wpXvU|IVH|uI?(Puu-g>5F$Oby?)Jyh?i|id<)leoQ`XyZ zt{Tj8N@SqQO!Wq(8EDoTpy$-wk$PnVS$Bwf$EJX=AI9V`LVg7m15*NluWoq_rB)bvh3Jk#$<9b3~fJ(H>84UndWv!6qp8zm3RD!jKwYKvA z0DJbP&`!qdh_QR`3nnKU*m*3KG1}d6n%=mItab}Gyz&#Ylz0j)t+*;+lOa}osgH|X zlE%*zkb9-Y&4tCa)OQlJR@!LAlnMbtS#=dw1InzRo+J$Q337iaZW|Xq^1Yn*@SAI> zU&FXiNVk$$SVqrKbZL`Lry77p)&mezsvY@Pyf$9^{$ZWlpV`|FsJiQB!#>*Edp8Ht zdlMhl-Em&K4{hUiU4Ho5n@bH@Rg8!IBWJKxxtFSmh^FfMq@9?UmbFn@BCzD1$^=1yzbkBW(=vh3yfuDJTb#ub)OM z;TCE+ertSorFQ+Z*wkgTMkH-8;<9r12B6KPyn2u1{XU+`Py3BIxqB#D6Rgo1Y>!{{TkP{B-#VRhiw{u86Jd?X?VDIr2Z_t#<0n=KB+(tl+-&Oq~Pb+0;+fA0h{ZJprwx8i7f2-%!8~OC>Lf4ug;F2CNc{X4jEN#K(>QA)K z>GSE91PXaqub=nxJ($b$-{+;QRlDbS=^xq)9wQWlkT?#d4gS3SKOXUan-BbrF4~>K zVfK7q%v18~9y!#J&s(6caJr8kzo!;IXI8I)jyO8TF-o zHdUyYNi8~LjI5HVJRl5D0DI@uQbiWg&jM0;^B9e>l*v)jR9Alk zea}far^V!$Lhw?}QwvecR#FyVWEUFl&9~caYjP}Q5nwcgD>^H(sF22cnE@)&DtD@C zdQnXaw(d*a?qHK}YnTK&42-QQO=_x0p#wsaFom!fjZ_sN+EQB~*ZDc9(k!e|WGS9J zm0eVHc^W8dsS#d0o;b*mRo8u}@k`-V3}X&B^!o{>>?GZ6?QWw;9bqMrK_IdnI+2cP z#ERh7oh^>W-cDY*lF>ukrOY&P;46EJ@Bj_IEO~s?1-8=DUs~bv)pqwqkNUEh@ z@b}OGs)JIgs9>k5bCez6*!I}(bYA{C{CD`<@uFOg*!a<~usv0>^IMNIzBdNP+gTjuLlrjh&p|;? zn%ywPxH6fFymYxbTtzG5Pz8NkiSz1$ zCWsNtmi!qUAfmCH{IPaljzR!+msvItaq+9f*sYgtMWMvO(x@{ps7l#NM)+U zRMF%X2x_5O0ghE=byfs2gYJ>f^zy{v6^i5r8ii?0gU8qXj<-Tp=~Yrl$Ir{`{{Syd zKO6d&sQx$XtRGkOtrz!usJib39us5jX|tIv%{J7*#a&yG7`ZnNcBZ>GmW?a26G*ex z&ouUZEaU-iJj)|Ip;SI96dD2m0|cHRROcq7=dUPb2!{Z0uM_5Y3V$KcLy!1v@iS|D zknAs)U46CccK-m$UfzLmot?g)e{Nj9FM8sB;}KAla_qdFeNNiMS4MDDi4{!@H1aHP zXg3b}wr?Yn1-CH70`Op@Imtc8RSikcZB79sC<9?647#@x1TagH$@bI8j7zEPB$N5p zqQ5UMPP{{h01SXJ$A=HLofF@SzXEFhk0Vt*Oj z)Uf0srOM(e^Ayom;bTO~P9&!iOpOeJUB=l=2Hf#)GQ1 zveHQ*CD_!H=6IU^)6%2l*TK(-KP)?&rMvgM_Lf(5cGt%ghL@=8skgOu6Kvzsk2zJk zX()Gw)}e_;@W#+?$&)1nGE`HPs)z#36U!8qhV?DW>W(&gP!|N~G^JEmO=wLED^Qw@ z^|=+KRa0LK6HhGQobk;E<mdQWzx)+D)ukNu!0MG^&C))`#t(2A^RaSO=@=G;$Bm;uJr$ z5;_OIAbdmU--Np(Z*;fEgSn{sqi@fi%u_+VH%e~(;Z?Y|4O&-c^LhQn9zPEbLTr?f zMxkM(rGglsjx>w~B;IM@no{tf=mZMDV3Dyn_Emnm?fmk z=eG9h#>0%5W@lQIG%oU?0VIiruX?wd8+Q*pD=H9sNnj0d4OE85$dAvh5g|e&Y91T` z^9RoyK>q*-1JcXlmrLzWiv4Y|x?5pn@);h#>K&uE_GZJX+!E1L=Z@Xm{zH!&hNB-z zL5``)8D(QEkki2wgxzCL(i?Y;rj_9oRy;KmqyfWG$)~Bw^Xqy^L`VJ;$Im33a2#+4 zMH8WamJi2Iir*zZK>Vudy}`cgyD#Mi~0SDUn~EY0}I2jQ;>FK85~f7=DezcUNR~S6}}CviY3fo1bJ<^}Qa;$bS&cb`Cdc zW3nf5(QhnfMmec*YqTjPq*_;|b)2&~dmvWhmem6bi&HAF6#YhzNUdAp2Ue;IgH9Z1 zNG_885srYzT9ACsk`&Z>RQ`1Nf^@K3QaQTce0BD3BJe@HHjeVxnHXxQg8s60o@9a1J_Xxw4csUK*jNc%@s z{{Z~Ezm_jl{{Sp)v$?w4rMpvo_LkD$o6{e@b2(1O+uKJ0p2TLcyK+6VO-Vydvw~x? zG!+yOtdh+-nx~uf5&-t?+uBNFdsv+*T84iTwWSC;R-7rM3LZG%8&xT(2?W$|`B(h? zVfkPDsrtX=56<3={$V*z>fU=xv;IEqj=bADXRPs?8))WsPU(ZKbGxf?;-5FVvN$)_xN#i6NXS_-S1TBx0dd17 ztXuphpJ(S&S@MVD7T@`a@VmIaA@5z+U9j+d-?OosOE0`}7;0_JmD=-Qw}#!`*v!s1 z1y_{9Qst(m&FyMy!zEoh$q`|#Nd!_Bf+vhz255l`#N;W3)O0tL1rm&tu~2AlsD{hN$H0Yx0%z=J!@(E%&wA z8DYupozq=gm6imU(owZ(rlnM;h9w)4Sj@&nCq)1NflvkjG@xTjRp<*Ek~7s5Q4v27 z89t=(H1ZyU$WU}wDE|PI&cfNh%zL>%na1Ajoc3F>J9cg7QCHNJdrpFfZ{cO^EEW@P zZi<-qqV5{3mToFcZUQIAQOS>|N@=H^+DQqGQPz7oEl5OvtZGz}x&Q>6C|yB~a!Vhx zHS2E9%^6?_QO7kjP@q$V02TGG%N-8C%!~PY?0@EA@!Mg1e&79#xjMT6v^!&NcIezY zM;#tVIagDK+S{9Hz9ODEvN-B!#a1(QRFslqG%-%8BSPgA24hM| zW@&5in?rBWZTu}&TU1Ll^4HCd#zprsJ2Oc!XC#wvY1vT^Yjz$Or`Rdv2LbkVRMZxP z)X-P{FQAv^jXKutU5g7$^r$xuUZxq9HM7l2ie`ZVsTyN4HH-cMy^qu0DgE!`l22^* zMTn5&a**T52r_?Z6!hu}`@;_tl6KTG6#oDp)EEloVUmOFHOc!rEq!T-{_#?0aW#_D zPmHh1cvl-Tg{bq=(X~=O7O*UMxU#XUGb9f2Pf(hb)s&;I0&?ctWxH*=os9PnCA{pB zyizZ2q>Y_g8Hn(sypE-!S}RDTtLj}PanqJ<;oR+SY@NZkd9;+J2q8mJTADTIwMh)Z zpn@oR4L6Pnu(h>Db%`n|M1N-zmpJ;$SpzL0req3QqM<d(AkzmF~qxm<;&Z= zn^n;7qBK+IOwhl;>%i5GSA|v8(z=m>4(>KBV=VfSRgs33;)PGbRM1qPP%uFTgb~$i z{GmvW3Dz+jRHJb~T}Y0WY<@*xo>q=H1X5GW01bDIT^g3)$F7=22`=pq7~3LP9FyWu zt6=1M3|7CFn86?cH#Hh(n%_vc*G3#Lazctw=g1MK1xA|DEwCe~8#iez)aJ;9aUiWuAOGYxS z39blL90qWGGwGg|A!J%=9q%TPAI|_9k;k_uIO$KfrFuBB z?^RX%QBl+V)je#2fs!d@I_d;){_N`sn^IG-*CLhFOl+VeF-Ig9V^?_sht;Y+eq$bk zr5k%m9G5LE3}PT?-LwSKv>9qvs;4Xf$p(Tf5M%4>p*YZmp{O)*R~aXQb`$9_PbL(u zh}MoE@%d#e(z}5*rby4Ua!+v$y>5XEKv{4|0<~RUbu_^EY4hpnBC@)sR$KewflMXFj9iKlmoe&-(} z%5|9dCyRc4jpU6VY<+CNnD_(Q4x?K65lmC;=-+IXSUF>Lrmqcdc&Q3|glkh@i3v0% ze!x2BXk??Nrl6jZCa6E;6?mqH&n+6!Fz``PsM22^Ra!{QC1y5mII)hScmzeDxe>w% zs2#Q9apVak)OzIc=~+o(jvH|b_yK$~5FZDJfE0fLrBtmBI+I;pyJ#{}Y;9>&27FqH@(|-Gu`f~f)wIz(Z#8DG_zY;Kr#;}m9_^IL+sU%W`Ulk;R0aH`?ZS3LP&A!iW?{3J1Tu2^0TGSa4 zqhdsF8XDu^Y5Y2=BgTb~;{DA(Z4)BawSKWno$ zr1MbF*2g|(jtMEU^fcK#O=TpQp-qy-WUFcq%3R&73s9khaK_eq^?LNt^VcZ%f zD&lZK96)TP_>oq>RQ{2n@% zixE9WR+g1&Op|5LaYJo+X?t?^(u@xW>EA$cL7C9JRXI>gg>1*91yMKJdxG;>B(m(U zHQY>fpAdy|DMofw?F2De5D6<@52Z_^@LhU2x zEblYcNhXoIdDW_&>N5EXRNK3bhkDUuXc*HP356+z z?J`ZMTiD-YJ{*%D3^CHVB#IGQ@Z(zf`HqA;eD>DD_}oOyN+?P&6kyq{L8u~}GAL=r zqOp5A9it6YBLjucV{J?f<0+k@%9*CW6T;NEym*Emz)~37^XyoXcPY}K5$aDvZIXE9 zRL~lP=D$DlbQ;0qXc)$>gG~DMxPQ|CwX6k?KI~ef3qeEv9*%*bJv?Q$>{D%Rm5_>4 zD9cH@%}N5R_LJgjBZ(mzbv2A^uXX^PU(=s%LTd73f)Dcl0Gp$GAUrl6b$@#=}obPen}~BoWg=1td{JXkuMV0C#J%62y}Blkpd7pPx#w z28|+v9U^nvyKwKEwl1@CKuC~of)nj78rWK)eONulCtUSvmUc-I@`_tV1}hGf?s zvSuq#D;gT>sKGjb1cd-_=&p1Zc3}P+e=}Z$-ub+a+}`^`s;BJAZs*SIjKBBuW9}}z z?Vh9F9Xr^Wo|oS{Mz8p8`=`w8?e&xX?Br=@`!SeUW08tQBKxEks`nRgy19*%#sI39 zW;$pA8rH3(4N3?Zpuy`l{io%--Hv_2@_SW=i4sN&DQb$lc&Z68xFvN)^k6VWxq zw5WPZt9u*bKX&bX`O*IXB>D=kYv+33ExERZR@RT@H^%vD=y5%9wENGmGTEhzqWk-+ z`uevYpTkeL=_SYRylnXzTC1+>8$Xr(HACJv~~wQWwMtg1LGsiLb5 zAcA@u-SX{(S2r7!K&;X+I;#D|vWfs-PMuoG>;&qlJ*o{t_6Jz+?z)F))^ClwS+-Yx z?Yw^T+LZY=i7N8DPca%);dckxtGu+h?A0uSdPbBfo&qFMp_Pm1=ip;0GNvKx- z5=J!-#Jp7DsA@VtiUSmC8BJ(Bh~vZZ^gIujSoQ=pu}v;qQdEBrrODwSe2Jx!N*L<~ zLOPVAX__{sYMCO8xP^|VMJGuB`!Kg3sHB5JNc`!a_I)ZkNw`p=4?5@U=vd9p^Hoh! zY#O3Qk;RhdEd#iW$=ULeMQ{xYk~ITEq>yRkY18J@?#|%Z z7#-iWHg{@o-Ltj(7EFYliMDZDj=C&P{A{%qRSrr`;Y%aRGtFB=SuAd6)JSq~dl1}m zTtx#}Lv<{6hPtCyVH*+vC6ExTSO5uNNdldEdkwzodt1A!2xPf~`zB;k(eVDv)3THw z4LEe$hwP5P!sBtcY)<>#nEVzOZ0}8(iNn$6>!HNZ?HNnM{CBAgp=~9e^?9nCV(*B$89%B$7r?SCY=kW-`lX3(90i)KN=# zk<-JHw63`5G&O1fpfu?w3~d&Gi0D(tByORVgIp2GI*_TiJlo!=q-m#VAIqf~1RU3; z+Z5O;J+;15aO9JB?dpB2iiZidDX{s&H{a0HZOkn^baZHr z1wAq>X=MO=vdub6>7s--XO-Gj=HO-w~iOLhe`gL*T9z7>0=|~=M_@_0cLqZ)`|7V|Q%gs*D|d;j zmB!($+Vr!$bQ4sEl9o4RLIFPX?(*sq%9tID-hnBB+c#3yA0jfW!j9XblB=RAW1{y0CRSi!qArp2o%3Z+a|N6M9$E?#zsm zZwei|hC6o+L%6=;Y5xFU9&m8m`)5je;+7&Q{3Z6Kf zl9Vcds8XCTh&WIM^xO_FZ)uV+AH)g_gi^H4Jw19}WOBMo8dkLV`t;=(jkU)j8KPum zmLQ}6t@R<4hE~7yu^!)ek&vr^a5(<}tIMw`&_Px@xP$4?p}0GDw6}&sWo7qYV{hHf znbQ4o=0~@Q&16^iy#>wApm)FmJ1sTSni^=u(ygC>*A`$in7+V@c*;;!l2M(&OV|g$Wuj9zC>Ad=weFP zlY2)!%nVu?=7_rKV;iz+Q&FX~5vWj+LyVE;dZp!^mg5|7?luryLa(h>R7nE02-Km0 zqfn7iLrire1K8XD0BLQl$Flae{oYs&mAs6SZvCZ-+<9z%-`wv!A7wn5%v2RZj=ox& zQ{tJOOHCLGdF7+qrUB9M0+PF452CHl|9eJGAn-jrF*4HT!QX zSxRyBd0Z83MSIlat81~$)bh(4E6EELVnHCKG|`9m<9jV5OMp)G*Yg zMh-ehZ?v^% zUBaD9Z|m)pP@TLJAMrz_xR#QzaJx(&Np1O{*DOoEiYUw9R zni|?kKv^lO>1K%}ibN{$$bo^l9^6{gF!+Ticv7BV`4Q#w>q-HwIG@>^8vVRJeL2_V zD)LoznOvSoV@jw)s+%7l1(Es%Oe&fl25%Y z5EWX}{ak%bc%D5}Ac!hPiWCX}1^^hK0{{W!Fb58^RmzaXL}F{BLN&0E$lgV5B_&g4 zhy%z6fP%I2l-SDroiTt-M=b*wXISQpDXxM&Zxou6NLgF_ zZSQskey-3K!H|6VA>S+ezIOxR{{SvO%hurk024chJ)QUy@xS5UTz03%{+{0d03dda zPS)PFQ&R36SIE85))k$Vyl0~R{O^1Q6FVL^qm<^Wu}hGtSnKLit>`EP)~%UuJ0w!` zjN5JQ=|9j!AedVSnWAX~OQD^~q>Kz0>;N2r-!S-fxM>meK77*4pCgd2LO^ zj6=k(1?We zXna5=fYgUp;Ad9FWEymUO+geoO-(rh*Lvk!n{HnEnB>|dCRnZ`bpSaOk!^}(Xpu6l zlsVN?PK57~ooCS>2|jQ9#Q4qAd#|weZr9qKhfBLQ^Jl7}-FvrfaOJtYvL(aR@9`lgFt;qIu>cNn-{jQxNN_1;ic<+ zmzCO^zLP55CsRe-`AwBmn!&0*JzFu0*gJP|zT@#hk;>xa2PKLXFA~X9Br81BCJ`H@ z(@8Xas=)w4PAaNpZV6o_i2(5jhf%vlu}ixozgKX)l|8GGC{&u^X#mWzAZYufE&57K zs+82A)kPEce#q$^sq=4pU^=I=doyg|=edn2zQ+Z*pSxGQ$O1huiRAFzNKOCS+I-yf1WaE;Z zlqZP0T`gWd^a|m|XUBZzdmKqOIWk4zR zb+?Y>O`p4ZM||{`Z0xMxWMZEyKKtnWF51dsHoZpQ?R=&WJGLv=b8aoknWn`#*&x!0R>cjMb-{8;Et z>f3$uwKk?(vo_yw_TPSXw!+)F4YSkv-Rqm#Sc)#Z>i(qZ%r;)AVRpVEvn^4Pu9d5D zQ^_fWQyE`#df!5`2vKKP~>;+vVkc zTb4$&k~q>^qG{s7fHK>_h*wH87V+L?tBNYd20_pG@WwxseJ|yGGB)Ymtx*(;Jd?=% zX}DpAO-dBT7H1Y5>T3h+x0THcMo*N3<-?CgUfZe*Yb6AVUhqC=!ZqRLUaqZ}*>(Li zmGqCNA5xe8zQ#Bug-26YmtJC_L2X*N{Xh?(;2te&{twi9-f51v8Cg* zzFlY~{K#;VP4jc-J#f&v{z3K(3n3t~MzK=Hton~4HIMrJJ>ow&U&kLj?ob-GnSaZU zvCEv8FFkVr1l4b21J8so=j}Xtwwx9=ioa>CG*q(F!F&udRC!F$2@?s5NfH?(bqWBC zE`mzf@O|^b?tADbv}a)76%8n9sfyS3l22Gma}BfXH}EHFHN%p?)kRnq6*;M(sNtT7 zwlfb-z3rA1OG?txZ`!j3JqeO}Sj9Bc$kCzJWM)Y&UNFQ4Bn}6;18})}jiMnjG;3tk zP7O$0`hADb?L7=q$rG0+g$OLR^v4QlAK1lk_>xsdmp}@~LMm!}4i%F9YL8z zB*!@Rc<*gwgKWRJ63t}tK=shm306W#d6Af0C;RSVSW2{T?^Zns?$%RvZx!NF{uySD ze1j*5ju5P_rIt?&sa0^tw;Gv3^-WpA9-x73HzqY>`>>y_+<$3W*ZTbrxod9#D5(2= z582S3#1e>UpFdAbb-AbVHHoSJ0GF>>ay8GtJDR0I00lt$zh6P~b{0)Vu6-x=zMoJ% z+9{wfY~{dm6LDDgWZ{YbhMak?JnSg8j8FHb`GvVRRvs8yTdd}Y(e%WDze8UPTEzL zhmHZk;gk7i)1lHxW0o1IT4tWT5Rc`9@xSGV#xA>`u6}8D`}gN_OTKrOdXuz|U~Uf1 zizBcykzf;QVApi+s#;9^5@M&Kt(r`1>ghn$MPreWg-flam5~r_`c0r1ATs8;1UL;^ zQ#l7TBzGD-vdyigddOV*aG=cwIM<|4$Zv}uJTkw`qh$Pt>%QQMkNJ6HcD)rhYV<4} zq-b(EefJj2+_+}XQS}U%@3h=lnRjgXYUw48t!Ig#sG7;33257Wl+sCl(}B3~2z*)< z0Ax^jAl9|jM*jdzNTP+hkrFr~#B`$?EnA5hrl1A~9QqDD8^4>qQSv*vJ{@k(y!eB^ zX*#dv21T}YcUE?LZj{*xwWY;o>1+2DHD2VFlOg;zhjQSdn;h-pdws^gPK`p%6}{wU z(&}9{?UHKX)Nssw{Cw9xBhwJd@UuvVI!MS2GfpbNgN$&+YC4_pH)8iT!s%|m*}o_< zgL3!&6J=s?{o}b`H9@**_eT6#t4?Dx4&=oXiQE+Rl+OqiRN+!$rHE!M?BR+lIZQA~ zt^t7AAc5#y2RW@ZfZn3LX_=(~o8mS3aQO@ml?O!ouKFA2?$7!4-#v@m`}h07@K13? z6n_^w_aD8sepxm?;GZ$KB&nZ0vayT(@7tAe(NSd9Dw>(3q^L^3SQcoKo}WPk5&c-Y zSGi(CAZZSjB(UvZBNV{w$j?tpc4T1^p%5xiU{_HCRagy8+zA?qpy5s(2|vxNsDGHJ zX7uM!{{X{aZwzL~?#wRu%~W=^ZcBCbzR{08))klvN_F^6Kv#s;nSq460Rh z`)L}1m%|)L72)#7^XuQ}$jtqsgpuh{tMjF3Jot52zspNv{{S)#r<&~t{$!E;w&$w(T zxMp7FSCQy_DJ2Tz&;=TC#=LgZ{Xw{8jK>zLDv$?lPH;|6Jowju>F4LqR(~@s!}Ckx z{zKvRt9@tfQawQ~v z9!H)#e(krt2Igy>4;?6h-An1Kdei*D4g?6|TR=`j@55bq%-(Wq&$Yf}(huzCiW zl*%kG?ylTB_7!t-L zk>wIuw6$9i971s|R1(4bL8-DpdJRE%RARLPpj6bz)1otq9Yj+D0~N=wAKB~B54y0Q z%%+?9nsx;ZPAKC)mF6!8{BvgRNwyBgrkgprt9CvLjy;u)>8N3_wXqYN(b+5d_xLMYpm$gl5(|j|NPgdXWjB_yb4^f=RCeXb2hO=qFoIEUy@P zr2smJsUoI|LHKJ-@y`%C8NLkAc0O08b^?5q#MEFrlR2~YeP4ZGq{qdA{sq{z*y>l` zc*=Z6I(n)s8OPUo5ou{8mIxhf6S9DP*)7Gq#uja0V48v(0%!d6veH{K~at_UZtp0+qz424W1nT*OR+iaG)Zlt<02O~=BjkIwr3ZM+3 zaHClzv*=GxOL8Q6qk<5yf@nsn)5|PPamJLP`D39s`KtC8^9SlYr^d?9<^A#RIo`Be z(=opy`7=?7>im~yzhCW41MF!wrA-=9ZVVdjeD3R~$>x@tqES3EK0InMgd$tXwq5Q> zO`X7rqxid^QuRHelLM(h3}3^e(v)G>mf|R3(WD!K#+B7Tx_I{amf>7fQii=)Jv|mu zev9n7y|OYH&DVw4ospjF`eu%7jz>Gau$xykli2uaD5>6-e5Cok#Z5^_^pQMIQ{^#6 z$jq!fh^0(HJB>gdgz(AqK4%`duU+aD46Vjjgyd zzsv`s@?RYLe-FLRD+jPD`pO?|Kb5MMJl#!I9MuA7;@1d4 z8nVB-%eLI@l4-k`$XKycSeR)P7-%SjR;IMo<(?*n;LeDF08vB0@iixnP6Y=Xe=eH7 zTKAvMuDSkX9YxT+N%7M$yS@?cou}5>KG69iA6<4~ZtK*MdRChOj_0|JvSMgU}dElFFVQh*>P1(9J0p($jrlT_M|1mrQgkp>8^i= z$bW{F7$c_SluX2=VG}eJ2A+byXZg7FOLjNQUzt0v`I7vJ_@TPKIKIaCtH4m_rIUQPpr^}htmbcTXW4cYB}HZ_YPW7SmloA^?G`mwu!$sv zicFT9Z@<5YMYhxGhFIv?E)SXrGYMOvJdDrF9 z!1&R+H%{>C-Lbj%#ThW?ukbFviHwD$%4a}TYZA+k zj01423X*shvmQO-$KLKnUvD{jHT-wegPLQ(QD2y;{{U5bgnj#&VdY(T@ZPgPTn{x`O^tTN?ep`@frT8+0+lC?JX+m*EQ zNBl!+gEbwxl~{mFD!64B<-gcTXK^$-NVqI$1$YLfYCx`%Ji?QjfI(h^ZnTW9 z)!VQ?+$AIt(8)DAqnenKJj8O%Nf}b&Hc$`b+z>$e4`}COspO3{2Gv?)P@xt1o}j(m zoA=%LW@dy+rL^%hp=x>>XQSNfo953RgVMdP~$ z(@Gv7P+(L2Rp_E?yPM;07=Ww08kWb1b!Ck>A6is-^$#mn43vgkrA<^ZG!Vr~(a%=M zs}#`%qLOmZ)8gnHol43Cj7b-eYAQC{c;=xt>=f0A280@eslI22$YZMA-A*EwXPC^$ z$hu8g02t97aHzaU00tzUIWcymRoP9EylAnbC6$%4lhDc{nF>@?c=5IA9Sm~BKJFL< zVcAo~DL;|G_Bmy5qEQkN;{zI~Gz`R+6&`-RL+8+kVpp4%_n6Tpm73&6XlfY#lYoHy zL1|J28~F~L>9M(tW8^EUFp%W`0Li1QqOQv1RgxOTf)>Y$>JdDTnp(i@k<$l`Mv$vB zM)9dJ(Xna3jwVDANk*j!H8datijFm*3M*eOkKq@#27SU!wPtXdm8EXfY7Y#$R6 zP}Z1<9SV~qWn%4?+lArUZY^LoWEWSEu7=dKaHE0JplhuNz@fqEcGm{;YbB2DV{qxb zk~OSu5u#XJm>Oaj7|Thl!UaQ7*bqx8DPJqLe`Dk}7USG`d@kUo#I-}_Gkt+jCCgyx zY9m&lo{^xTD@R8LN~W=4haoGP|ysD?WfXi)gP4s{{U7q)Pu8JK9xX> zWKs#J#~uLuzuD*yz=uu!hYD%Jtu}rcWiGQBqBzFXVrN6)n0i2DvjK5`t>q{hn=a(W zy}~?tcaPiDk7n$fW${2sV4QJExc>l9>hOL7Pmjm-*JWjLyOV5etR6cqwONhry^}dU z$=Y<3ctcV*7Vd{_V>4Tg_U18TFIDz5RaF8obfFirj$Dcc@!`99)!+`DhH{{Yj6XH{jgDY`nVrZ-j-F;lYgTf=VSaq+z@F+Rtp z$5V-W@dvKnj=u3N2OY0I8`Y)!MGrBop92dG?n6>d%rrA>0eRa+{aqRc7JZn9Sc| zQPyMoDvJR!g%0+IF{lSA4KeL6|Cg4bay9a$c_^o7Juc(-UZr3v%shy2Y>y_TP> zX4!Fcx?~q>Qe%5jx|G$@(&W2;35(nGo5MEvI-GqrBOA2$6w`Szl^80A#N;a=$W;hw z%!?TmnbK>fWtN};UeWQS6plE58(tOWS6^xcLrK?)Jdi4ch4OkUK0Gd^D00&JM zP&zHZ$vrUrd~!_xYae?E*hD-bh%Y17ct)khrk zxZc(^GtG{tikBLdo26hzs;Ck?nP{3NEM;{@gHVhD0-tRpferB_=~&bJygfMddu-t& zE%<+)7PMl}!X8g8Lj08iK2=%2(u zOAPvdtIMY&eQ2(v5Jz2LVE+Jfm^OH&l0V|Orj|6ayQ9}Ytr{B;3*O3XdG_oKd|1H# zA^sk`9xp7ZPRZkn3;?kPKE2)l2QRyX`O&YM8MSmtoE0S>DgoBVxdgT`{bAI8rZnswU zsR!uY36e&QB#{|((@QmQqyiWCwQ#AeN_^ehnEkoFX?KHVv%8CQ_7*EwVrO4xW4hyG zLzDh6a(NoPgF&>TgJ|vSHcFEw)fKqRT`oG06;^!kCW^3-vuh>9clCB+>qpka7HKL= zHZ!Y*KOi_%^dH+!XNQ=T&7`WFOipb9FLM;?CvpWIgtnS6waVE5;dKGWH({+2y_WL}@?jnI0v7jwQ z3X4j75hw$;f~Jj~Boj`^?3~wNuE(Xz;x>*NJ%h0@n+F`5Lu=zUu+CB8Wv-e%&%1^) zD2C_XnQy(*kj&KTtgT34Sr~|t%HfE|B(BcPWNP)F9Qa}r&O=r#l? z{F{9*uaoH`k9zVfJi7G>$DdLX=vpQ>I!V?I!MOzq=HE+yt?xvDE9=&{=c!ShL?{PT zWFJ>I2lMy_EM{< zOrR@jvYvS=KdPUt{nf}W1#mj?BD^~C&dA^gZaEjX0B~2I?Ee6d^!HFmI5_LTk-+sn z8O?wN$qpGnhLG?58yY*Y;Dbso`E7OfwW%&4FS`BTywndO#t62HfADc4JzA zaZL4cD^s4cwB>M-LkEo6zPBWQL+$0LqiM+*`+Yyn*7S^Z&MDNYq`qdemAC*Rt+bHeM+KXkeJ$@n z&yxQD#r0xx3veA})>S!nCs|bin@JbAL8KB0`u_kzKgZpHqKzZB{Z;EgiUH-+w4AHh z79&U!7EnhVhAJ(>pQpQk3hF#Oy1#D@AbIsRDxi?KKm!H}eJ=Wuxe7`2fDh>hpLOD( z5uUw*H6Ne+Us;x>O)6IZ{x=W^HBuJLzjXzKD_v?2e>fDNhtRJ(YecMT~m_AmWUS4x1^_?mF zzF^orO+{6|wl_j=P5s+_(A$G|V-`NW-+P-sv^MWtM-B@)gQ2C}dv>*E&EPWBVobdq zOnRel3QRqjbLFM%yw|uh$e+7Ky|`1Syvp&95jB&Ls-ToWD6;A;Q=~+0yYTQ;LUZ>w!9j0+zY?JJbttKxKLy^W|D62*?ng??A?^jb$6PY(S zyeoL6jPY2j66-ANTU^r;T1q)IRul?C-hN^EIZy4gTB?>uikAIy)kP7&TRh zV2M=Kj<4+ynk{g<_}$k%otx~A>Fxddzq*^QsJBi(WNunsr1=xLdw+F&s@;j%l5Sf4 zq1K-s_6A06$-O%#6R`1EoL)C}ZVc99Pwtk|@Z`hI1uTgBmIc|G+iE?R1W_Z7Fm*Bj z&r_%*Fo0S{Y?dG*hI5wv+Sz$~nSP^i-1h~8ceI02ODk1mwvmKy2#hPdvT6#E6jfN6 z=t{;|rK9xzH+*LMk7!~llWFdD$MR_}q>TgK_SjrHgTFOm}Yf zJXp-Rp~t)A@b!6Tf`w}8Je27mb~`n8lH^`$yLuwKl%gvU*uEg})DuqW0nizUH498= z%+Fqu6!Wt-X!dk?y=U>XWZ3Fncp>(YzJ=hi_){m<+akDm=1e>1pygSh1NZ zspx*@rRfap9`S|A-L4gotc>gml28K22*fF1zX)wBs)d4pM^k0(m8RKq6^*{wEv@0I ztXkEIQ1NXH>a0yz$F201p=RUIiSVkZR{Yrb-qX4~(DpSFq>n2j(??5;$jbpxfCW0h zSeV@Ee zE3Aru%+4GT;nzq~042Jq{{WwxTebfHl^1P%N9<4UF6iE$3%*cybYB@eTd(^Ex^q3> zp6TA<-`H%ncc=HaM(!Q=v$pSJZEd_MwzgF>n98i)XA4yfAMhHIt?8=Hw~kobHOXpsu68(Qu=Dm+ASNOHE6@Hw`4K5d!Qw`!=RTWw?={B$I9k=KjmMVuiI4 z*hHuD(0}5-b?Cp_$~+db1_TS^N_rTmK3q>%B0#w}HVhBrQL*|r;D3$1j70_j9ZbD) zCgI5@*S?EdLZ-GBek+W98art&fH}UvTspA;SpKEcq>WZTsC^H%$>Tvm(`4fZ&yUZi3P=14#u$w^8f?rC ztzySW2k1qteX!tHjy(FQ287f7UVSLB&e2pv8vaI-KT@`!U0fABl9o2P{=U*kLldM? zYts%uIXMEk`SqZm^9##0SIobf@RtO)$sWb>_{Y*CUXe?n$?1I|ZR)W90AM}g=Qi6Q z=dIdfk>VdeFnE66vA>)M9Ou5U;%?EuKMEf|pY8JM*Ea5@+jy3M8j52r14&Ig=&7!r z99_AaqtK_EuvV+>_=PHMc9U`7E_&N?OILlNDd~hJtnpNsjwFty;(x4zP$@ zQy0J1LEH>mt(wnn#ja5zQm(WIK~*G?ifI_8YfN;i9(LQ;X`g42Cu!u1!v$1%DDMQ3 zMaE4lUoMO-3{+9|#Y|Ja7*s)@q^PE>lQjy})zV3WnwGAXJYU*M^};#h_0%JQ48c?A z;QI~ucXs^8A#hAjYzP`^s6@35tAOpsgTxZUhecNMK{qEdNb#ic?okycRSfZ)cUA%| zB)AL#X%vkurB5E0wE5rfPQb=ya+w^H%92!1O}QvBu@=SVsM_n2nJMHFD&wSyOS*-; z0ESkx0$UU@w=r&)H*w1y+TE*o!%vc_ih{a}DWyJC3z5{fv|k;=m#pq2mD=+pN~i@X z@oJ~=kVltqku~a_zHnw2CAcD%uGqZ&-c8}PBBhBj82!qW^ot(t+A~u_5)He*F%1Pw zl&(JJj=3aPX(E!H##Qq1l3Ad+xQzX5ktlbfs>lGMww0h)84S8Y=NZ+|i*A-VRyl|Q z?U;#BVMP^mIvP}@iggg($ki2KLv>dfh`-8YXDgw(5BY6e+T;MGM>qbz>_@p`&FL6b zI&DgX51Z{e@Bn@VUuEu4l1RjoT1esq+kwZ>aqlO2 zFG_Nj%|la359VZSeq28;vcubPPDj|rNv!Ag%>Mx3;nkOS{{H}em*^hi@4AX?mS-8# zy?MAhFFUsI?LwK&(}vqLzjs@O+tTEo9CTZTx-Uf<&gm1(LbDA+*o~J`N>KNTP#S^$Cg zbnTo5CwxhPn|BKRqftvin8;MV+^MX@EvRbhVFZ-mtXKi% z+*J*0{Tz99Nm>GmVFrNE)KfJ16aF58t^WZ0$~LCU{$X@q%UY{w@9N&_%HZ2|wTG-*!yF0V73-N z2a(v^z)$T=)qW=viDVP{n>+KWob8j_>-Ah3|=?*-go$g925;{ zr!qwG%jsysv~K9_W}al%EwjX=;4wm2P#r@`w6RY#!L%U1f>HY&@Q8X=SiG&vItAmJVG0^rxIz!o=l3o2d7-tIe?VTRngKjQ@`q}Q~9!N~w>I#h~z@urqIOaf_K zD-v#*1v@|gTg zxeR6^jiRc{$xmIAiA)fmBOxrH*pF_yzk<^sEg%5UP!=T8i>QUE`H((is>XrjWc)NH zzJLmvjyyg`q-Vr0mHm73Gh*ZWlcp-`vb}Yes@zzOxwvzCb0@U&m3ck2l9vshr>onU zxZ=v=l7}e^C8Yz%2BrG@rK`&_29`2~f$b$p8S^SxPY=S!tx4gdFNAAOG^nBDO!=i`G@pr2V_kUlu(A~7SsxRQ%W}ABC){}eIVv}a&=cU=z zk>naWYRMnON`PcmQ9~@k<*kHF7zR4Kbd?kYiZN~`oys%vp*Il3RbRy8LI?U`s16>P z^YrLo`EBzLs6G$%CI`DdL~lA?z3M!!=fd^vF6onQZynajz4N$?=64T)Tpq^2?o9lj z#4%fHzEzoNOc5z4$v-R#lY!8y(LI+3dhHA^V0FB7*=%0_0K#qj_Ql9XvrxsluzQ|{mnXM!UOM=w z>gZQ3L01#TwJ8j-2LeS#1Pj6?lrFKQ>A?9{Iq8QAhNxKPZX0vGY-hann`A&Y{(e zPaKY(DP@(Nd2fjLd!RWu2Q7-TJ{{Yxq zTetRhCox}uef_k5j~q27;-jRZt;ucS{pG@7GOJq!9zvdJN89*}b0Jo1`(oO6xC-7I zqIqjZM&bM{0j6nMaj#yL6&{+^o8&>K=CvQQsNIY6o1nVyyYc@36}P`>Y>ZFHjmb-k zt=s(oW9--~o3nWb7611xT3mTpj z3JE`u`I-uzs~W2k385Lu0~`+=dH!{v>kmrzuU~wG!%}vCQSK}kVQl@ujHsV(Z{4?$ zY^L1aR8*DKc)4c7WaWwpYU$|mv=h>~c-5nx7mR>Zfv6^Vz+(|nK|sKR`GP7w!}j%8 zL_#z$BRn{I{hza>96vUC1Ag{S;`rT)?X7{lyO*zPb5vW`q_F$Wi!s<8b5nrH!He8a zxi*47-C&mkmZ*jb)&kH}N{Hk;0qwCni5*o=qDUu8Q?$_c>Ci=ZQH^}K8a(inMJzxh z0tHsIBU0cULaUsP9Sc3B@-t%me8=D`dn)W3>`7n#S67>{0D$7Kr3a={=6;x(W@G6AO=3eu#|WYe!f z16*q{f=Yp27_JBHBg@k?8R`43w^jpr;r{@<+i<|xyve1>Qdd(vQqpDV>nUQYqRddu z12sKe4n~$(=7w0wNn>#8NML>3$Ycv4T2y}{!nOHy$WRIH1k=l++4D`p;yTnwlF1Rz zW*TK%t&mewCzT4HBb8_M0c&60BYpBD)5u(+pcZf5QqX$VBoz7a;nqF<@)$Owf`spCp~`V4x`2@+bYwhJNrCcSF@(xOVbElZ)aO-YZJfgq;LECT8-UE>;B zIaP0goRM#$_TqiM^xN)AQaMh5YH;z!&4OZ=PEZ;%#<@um4^WRRq(IMcX>?+gJs6d! z92r#Cg2_rBQZPdS(6y767;zDQ39XZB#fi&4W}5LwEWJ;?t7vK^%F^y!Wo;E*JiT+e zF*%7UB#}h)A!_wc581rpo@iN2_WOOd*>f(~Y;KL#v{Gl#22usQt089iqpNpD5V%_0{$p5yH(AUp zspxi&@uBQ3p9cQ`>QP%wQCC?zZS16Y?#bEJ6{YgoUcbl795~}pm6BKEE2@PKRvLiR z8A;B)#7NVZt*$O!9k-a{x`176(UNUtLkz1P;kUbndF>4XX?Z@P&Pfft-%%Kb=0IP$ z7H=lsb2N|(P39@>{<7avpBu2MT*X?uLXAjCSMgzHXl_zL;M}ne>-Tu}w$_cRYF?$G z!+5Ic>7h|j-^FA7=JF_tYKU}&A+(7!omTe)X)i6)CuvP&RQxAN;5`o!>DC!7h}usWp;?w3bi; z4g(MgQ41|gu7JH@Jo znuRHq9z)CzUW4+Br4T^(2+^X{XvtF5uA@Lzhy;<4Jg`q(tE=6OHAFMViKz)R5#;5X zVlUx%s%S$9oJ1-j{{S_q4xz+l}EUM8aC_Tp`tJzp?ky}eA?yE*gLXz!PV5E|YKTu~K&7|q=CWM30H~B}D+_CID-U5B8 zl)>XNbhzTaai6D#qKcy-C4MYX$u@0qxokpYgG&SWY9dO&=hH3iDDt-5^fK7o+}lL6 z)D&$93snZER;7EF1cEBK;3?3LX-)ds^jui@cCJ6B2AxH~O177eRa&$oT}^d$NIS}o zQ%hegNi49^1_mOUq*)e1lhiz`!o-qur}6&7-bUQR1ewb)Sa}qhj(uj zt43k|$X~Sd4Pj_%={M#+I>l(4>@zZ~WCH9T97=}L%%jr4ll1=pWA041nklwx)`)_- zqyA6SmuB$IwoN2rs9Ao@H=pO#>Hh#PI(ka3w%*H;qM*s+s`JugayZPiLZcg%$5&xt zqsU^bsX>jZsB#o?yi-T1bt92*P5swx4kNvI*a;G4Ao&KoAM4`;_OGZ9Y@+tB0Tl1~De zB$7!cnnom>#^i6xs;`G=vFVL#r~t;Kl6dOHe3d{^z_S21jpp~5H&5PotiCga2&+P? z8lKb)0M=?tyo73z*qSN@MX2d=y<33m&D$?$^|0({D`na6ZCbJ18Q!3MpO&P|*HvaG zNwHWR!%4ly=fj_}G&PV!v}FZUGc1dxhC39V57cV6j!4dt+*lFEC{Tl59BR18=*^|H zhT8ovY}!_nK#xmlD9Xj0(u^Hha78;n)DIr3m*nnGsIxWLW7i#Pp4d^xMJwg0^4+;7 zX0Ak3vb`kKl2q+2w^53LBMbn%>nJxGZODjR#c?>2-q9h5#xNbE1m>+)$kpk7YF;n8NuZ!B$0Cm*{uO%+z=#2GPlS!i-qRC7-y6SX-R z8aNtiIcgE3vq>9idt487NM=F}y~QDH(ty+KCp{LMS*;~_(q~iz_R^qwfO<&n>gng* z+h9_dDGA)zH>Oq!&_gK7QkY(2AU;TRBuhsjO{j?Xyi|4)y0M1`*rsgS0FK;d}7XG`#)z=(^g|gUMjm(L7T#)o0-9UPZbtE@mSwb zsU#@=&BaADoD)HnJ!eO>!(_JFuC|@OaD}&+r>JQD7K}3}Q0%?>si~Az^payW0H~Yu zE9EZB-FxfjAAIx$cX##Y#^0HpiL!eKuevYfe@fGCOi#-Gz=Ic`Uy=RCyE`8RxZh}X zXKM7{eQ%7W=%uFHEjBRKXDO&Dg*62oJp(ZI^W4cD#pFI6;hJWRqF@#%OoS@Yi7sS~ zQD5TFbqdoM+CgvO_~5|Gt)<3ZO(Y#FYK z5_*}~>Xf#XA@va8DxLzLbt5L7DvG*OJO@q6%%;}#lY4$R`rq^Z9{pMnYt!6%oivov z3Uf}gtezrjmQNprX4XQjDMRFFOh9tuP;34@*`y3W;g8$bzb?5%B}5Y43hPuloN5jA z7f;j@-=C+wiBAG+*2X%|7%Mc2@F|pv1EN(af zu5G7_f<60E&{0h~-gBO_td<%`2IL+I47xxB3w>0MNcZBwfhUh%r&Ho`#`0?8^BsX@ zKVCm4-ov7{MO1ZM3Uw?y+!Lg!umOJ-;Ce~m*!$m!UM;|XF16M~klDfdSP^bYomSA= zh~d4_oKS)Jb-E1oDkfhvLUs_w&1ak;ltQIR1jMHD0(c-B``3!uB;udo>t8Oril9fY zQ1rR7gL_zTt;ZmP?_yJ=V<)du_H{XGnlP+mBUOQG@Wc^+>&X6}PV_mP5%JRk4U)yqn>_%SP$#{LHDyLIRcgIbtKoRX;y*xLv(FSRrpt7em;Zg^go|| z5|SyvaO+~E1qUOn?_2vmKNuvr3qGT)f^Vgh^nicWe@}by&JeH9t)2#>J!MIk{NVDb z5g%5e<7*HKt@$huAJ^Ztu-963Lr{3<{f?#@(L5<=hms;gIu_R=abYL+Pm7xoWBq;X z&Pd9PQ>~hs1LQi8D+6i^DUBGZAn+wNvX=Z6Ru;JD-;DSHH+fq8dlc&4Strj)ajwJOec|Y82@tE5(=oDNG#y-b~X$- zx7XX&%ni-9GpqeW_HDV|8 znY^ED*Hv~0du>X+RIQ+1)4eujQA-?~gyr!=!#W;4!;ny*ith6G{!0lZ2)|#$3r<*UhFwj&$YDHR8F*0vb-*XHiTg_Wo zo<@P1)WngjWCeSYn!%cP?YDt@Xv)o{OGtt)ROQWv!pmXYwmqghQue+qff$fvWg(-} zRj-kq$R?pU=cVt;{{WKvL*@s}F7WvqvVJjSx)A&tsq3$gUA@qK!=LM2xxKNOxH~g{ z?QNaDaC>8~Hv}04{u{jV3YiGD^=9Iv#&quKGn@?~_ymGrA0fpV0p{OdT8aUelwRb&s9}Bo> zzlb_VDo;^QFWMGmyMU}^F||u5eyRs+a_QQdbsC&y`$c^9W2_?OyN$DS_XcCS?vq<> zpGA7}JW3>#4-ACx<2aB9DOz_0sZhjF(znPAKTG32Yi~?PP;XAo-2HQm+Iva%j#IIE z;{~#Je7VTB#W&pTy8W|(%vWOZn|~S!N^FE~&pNL$S%ic&A%;iY7+Xsk>N-`K7_JxM zWIAX~X{NZPXh{Pp_WNF6gJam&WZmv=tW_S5EM6NEsE~wU;F1Z_DN1B#q4VH;@c#g_ z;qjc$H1Nv(hfm}nM$l;(Jiw0ZZos636L3X`_4Zr;01!6?AlJc@)A)KvzDg5qx7Q&G zZXw}MDOCCX%5}WAOnk)dE{4O)vGF~1wfl= z9yX_B?tQnKuBm#OU*dImimZK1(#7{RG|x>98ad{f=;*qv+f(+|AqI~#uXhh@zd+EQ8O)*aGfGlRyB}sx+Vu&X=G4!yC5Q zd&^s0jFDK%+Gd%Wj_FPjg(XI;u4_bQI+&HwWf^NUd zLRcwfSYksVC-bL(3AeKTSyCJz_&}5A_ze$6zS&AmjktBws{GRc5WX0o1JjS?)ycCH z#-qw62nLubOCa_+m<8!x8vUb06w>q<<}() zO~#S|)1-?FUe+g@-230BUh6RhoBKT6Xda@Y=v(XQ=Z}8t+3Ww&+SExZ`pGgN9;n?# zmgE8jxcZ;RvfL7Q{{X9pPMt&ns-vl^b@ZuFKvvWBATJ-bTY}t+i}F3TbH|7Jxb<3% zAbHoP7-bFPVRGfPonNJ7w+Q3_%cy@}&)3@y2iexDDMjJu)8zvnxrIv$3E<#^`EY)t zfCuDzOeh+a#d>Y14yx1V*UyvZon+1PFXsE7T$KL+B)d$4&0!_C1jqpl2No6={C$1m ze>Xyp&O3ned0Mpc>m2#PRP&znrDzT4sUPVh^#1@4R@1jC>tn)Xsq1Ia{0^gTWFf#c z8c$b~r>w$L(ZwRvPa&pinmWlepjj^@PEM`>_knkEMHStoal{%qZOvq;8eJUKe#R6d z(Dl!a!YNl`RcQlgoXO#7%YsVk4a2s$UoczH0_yZQ{HV^k8eYC@GLW{1@Oj(4O(g~+r!N8uS7OVmmonBvt3CgS0Hw( zl0aih6Olq`j-pM9j+bvOMAX!BQpYw{N_nYbM4FaBMbs`K#ZyiS+VpP!Myo)AAwixA_D9nZ=cZWl5HqEYHWfEOp zM-`pT(bab0iMIzz6)L2Lh9><+Z6)-V(kh`$^RPv42QO^)t8)-}l07#pN~A!s?U5H& z5E{)Qs}bA+lDVlb<^zJyVYi(w2Xs(NhTU6MihaG9!B#94c^$PZ5=W4w!yM%#&q=tp zoVeR~o4_B*f^-87F~=1)`k_x|#z@ z21wj8^nGy^-qU!yUg-~oy4y(cOBn;Unpp^NNRl}fwZzNXRO(hC$5mC6qLhbiB$pCi z5|89Xx2iz4u;Y+P{{V^iBic?obMX290F$FzYo#m@a0idi)2-0|0Fz}nrT72^K>EJ{ z(6F|$UOo9zz>O?C{gb;K5AjyF*PH(Utza_4lm$6gVmvDw9B`+I`TJ|uV*7S~hd5QC`sdj9~$^d4+F9=O16e3chpZ5_3-)B#*bIUEj3&FLLe(ds{u!y>fdFl19X1JGO4L+sWCOww^PN zlLbTCkB0vB(@|B^15GUo*9azvnBFqHd%4~xTXVG=w-(IRF;r9WVh8}FkIG^A8rTRQ`2`-ao1g$*mX+V zo3eJE&7#}8yR+7wq*eW{?%Y(=@Xx#Br>g>0`-YXFkOBy`z4~p!dz6aa;!?>N8dpk< zBRmKIpNO22GJSfmiNTUXnhG5L-_NCocJ+70{{F_{_Ls=6km~OB!tDBqvb%o;+S@Xp zc+l;frBysoRA;b|)uC)YMxvfIMyQ36o;3=^myd2keRpQgZDcCc1f2@i10uTBfT7Jt z140i}@XUc%8czXQf2)s6t*?^Xm>sQMPX$S>+j&*3$4NBOJh06{kf)Z4uNzS~I^~Lb zNnRGY^+rhcon!@8P`$OU^XmFoNuz@bSLNqX{!W2@mgp~w9SM?bKgLd*>wbm9<}#nh zHy+LE>~=>Dg4`LH=@%ak;;+S5WU?wUaO2}zaV%an@hDQa=i8HB8>dq!Ul0lnD2b1l zMNm)7iuFSi#u}ppgZ^xJbnn`oG4WTm`x|NZ4`uZaUG9$S>m+(^w(Y#_9dqxVw^WX% z6-~L2iy==#1aLKEl17y@^$QH`=8Po4WEP70NMe=}2ZY!)RVO@X)GW0ggkuLCd7$xL zC(=zg3Yvb((Efccw|>s*e#hzD&rEj~+Q9ZNRB!A&crD$t_avDJ@Egks1zj#iIt+xE zn%r(hVEgJQY6DZ$Ln2EWvaloDaZTVnZWg6-Dxrtw4MF<|J#X~^WJ-o?8e<2D{P-S| z{SnkX8S(!B4~p2IAGU7V>rSlNxVh=@eRZ^2zDyS0ih8N?HM7&nm9EO>DynjM3Ylsu zs%t80DrzT@o#bMD-fOnHndfjkYEXcoMLejg0*rbA>*v;z6B@@IC1Nn)6`;z z_K(;r!=)F=ACCV37rt8cjvJGeG?X}lt3^vQz_}mr`X5*=<<*AEn;P&keHZyPHDeG$GsHv75 zJq;vLLi5P-l#FX;Yq4dgNgd=sG?Tz^A0Rw{@*lIRsxTo4HR!!`@51khpB;DCV0I73 zF15k+p7QQJ)gJEcoR&XwZf(In`OK|dZbnIbJC`|_i*HfBS0zzc)HtQ1pnADlQx3f( zJ2mQD1dGFo3euVvNn!;7YJ5Zt0(eyVp10vlJXs_x)$>1XPY+%v*Qd{w-wpmE{LadC zZd2r*&dl#D$3@ic8t$u~7ug%TW5u=do2GmPPT;Md6}GapIPJjsGqtE=l`=6@r-Bn2 zg;^h0qPm71LR&~Asap7oSdAv5PDY&MpE?TT9ayZ!IwXuEI=BH!kwfKLmB-oh=yD_?@!*KeV>S_Siegan+54pEI<33k{On+p`@-k;k+%VQO+XOua-YJt;|P znZv?Wl}Kbs8j{WfrE8pno(I$)Pd>b*^;K}={wvR-`SDBPPsXo=*r~QB#jIB5+TD4R z%}cp*J8yUP7GJWm6#2Ho;&%GYjLzrR_?0FiEItyNB%-@V8zVZKyL)M0I+=-Mz?$Zsy*3rW0FrA#Q%^1ffZ<-7yNlpg#UAJRSG7KF?zlJc`8}|3+e2^c zt;I#zb5d*^W-no5vpB7_M_tzqjGr5jNGbOPW6I4sJI^tY6*_}iZtc7$ic3gLrnHdi z@fM@-(Si?3=q8`HtA&`D*Tg0)cF+(g#l0(1eClz~x$+z1e@^_f_}RI>FZavtX}ZIG ze|2WuiLp04dp~sj*2vtL&D*ys@SB!QepmQ(v^$3lO)+n`m0b{{3o-XdW{L?BxCaOxu#p5xU*r1}Lp=z1rn3Y{}&n%M2&n%AZrodj&;XDXFW-R3x;^98$+lOkUiQ^43Te1+|SP6s(J@Thg@F3l;Mw zimROGuNdUiBqpE=QlDV2+dv1|^F0Y)Ha-aaZvJ5V52-ryY_Q1du?%Bz(HJ>giz{=?0ZF&jK;&h9bG+QJ#z+RP1^#y4v{dnU1OzxP7^g#9*+M z46rQegu&wJaX6S}j+rBgW~ZQ{jToYZI&KF((@IsDnGb0v&xhyo>%nyP(wHB!%cAY` zHkP`wF0g|d(HT=Kn%cBTyYY7$O^bZ6obMOP z8qZQ_wY+HiF09f_7QI5z)*W6PqLC9E?{DKle7SOq9FSf{#(89BMHp8LK_qqm0Ddo; zoDqtKrA?{DRPNdxyGKV^K}BBpdQ67S%@%1!a|H}}EQMEC=VMr*tQsnkY?3T-)XPb& z>fj|)D?=t`Z5A_cG4jlJH}Ju7@y6B@S1zDP=W3lBM2-uq+ysSWc-vg?m6j{}X{E?5 zj^>szK{7{3$A>Q(#=6<9q^Q@Xx~0G^9a=>+7ZJ5he=*1+euctrEHyR@GuMZ>vAF%A zm8rqD+wHH7o5byGl)Izjp8o)&tXjHS?XQ!^f4N#3BxI=9jU6L>?%+pbjCR5B?N#T|TD+C-K)C$N&=!>{hYltZ*Ow5zLQD zbmWlQo(6VkUE>xjIkNM~7C!NoK((28_DNdco+JDO3oI@ZbN$kU-n#u ziM&*(A!tDiR1&%Fpd^6D1P@M?-p2}Vn~Nml!Kwoy)Fy&}(L;bqj=D2I)a}6st{5pA z3_V2#M=1^>44r9%_`X7pvZgvWH18!1N0Noh2C8_%YDH@jSyNIzq}zmkEwoZYZd}JE z5ouB|917zDC(Q8at)=0FNo9L~^wv|c{a03XjOb$k_p0=Ns)s~V|dYvd$d-wo-;6# z2`AK)Nq=#=?Y1`(Y%cmPEtW+~gq1+iCA`k1KCU79kV&KIuHz49a-u@5A1B+A z5AckhUJPwzO%+}$llVRZa?njYo?Mbs*Ddf9IiJIj$JV0?S!8&awIPY3SuXW$y6zT- zYQKU@s3C1LL>eeA;jXV2K>_WjMlJOg?zLH2z^%Ilh~6E!O4`pKhjDZxXAK(oamuVo z52gE}Ii!)xUk!^XB`A8X&zn?RdWWlU`3$85{{Y7EJE~{fFHR+@#%+pfwSyhGI`?=7 zt9pzc%iUr~s&O^Z#Qsc{IUt>)V;Pb`*cB(*BJkR`a>&JiKdA~OG!h#G5=%l5k`<*6 zC>Kkx*jtUR?n&SLby}zrr^BNtXx^u`HdZDg0R}}X$KmT<&F4<>P~}?7P775_A_))D zO6$iOt;(T>|7mj2m-*URPb{{WMqUWKHn?5s$I z#f=Ver03D%7`HMf^wLeZ=aI*`KW$MLF5gsnr}KPuBkjns?6Rm7%Krez{{X|)-Fz5X z=(>k{)xhw>ST`h#OHn*wsp)5W8VDkuXtchlVR^%l6|bhmbIFG+MlbGG$QJ!;xZ@#e zSn2=(00fe2fGTQno}JijKD&8aRzIgL%xO?^alm>LT79Oy1fMd#5$!GL?SZ4FUcl@f z)wp*wb-k~cpxhN*m7k&7RhUYC&G2oU)mz-=L-N&%&@SBY`{ueiu zl6R9OlG=3}a&@Gch1(fZ1Q#hxgu(pFwOj47hP6PJ^6EN4?MGG%BA~{UCm>RRi%dq+(z2l2eh-l!er~}dVHp9X>V+G4rYfjL-%pc)M_J!o>ebr@wmH}F5=Ig$AVT~_PbJNtiizEf{g!GqZypSUR# zFN3Yb)IKI0bn&7(()L3?($7q?T3hm`?g7%_NdQ&SLGXaRTl*w8m{6a)|juurzn z7Txso+xYTR#WB*JI7rowFd}{^ssKPJa!6W0%Y{mJ@mtef7$c^#>6)q{dhj^vPcdo z^F10{&hWKHLE;ZcxuJMmdWlkO7!&@rkNAP@N;0^uICN(e!d#3ur%DZ*PHH!P)2AxM zs&_613oq*;T&*g4HCSplu>5;^JV_ogsDFp5-8PF`rmYB#v*|#3+DCO|DOa)gKb}}! zDfd=R?oIrN_0q?pHT43(4MM<@eeTLe@FT}*Oi=u~^V-ob1r=ez)E|=LTCadZTk=_U&wy zSS)5+6-iB!T3GFqr>dD~o=~;sd?wuA;aqx>kW))P&1z zv5xi28xGmF$@H*W29D(sTwfmO$!R5_B4FEoKH!B~JtDh>D-w;$|1pCBfTz<_^f>Uy#h z_$ebP3VInfX5EDJj`-bUazpn}c86YV+4g#6)Kr=}>~`SD$Ga*pMEM?;3YtSl6>W%( z=4go;#-&iSX70ssWM*;m04UF;3BmK>GlNWE3Cv)j0iw`Sh&J?d)t}UQGTf zDw9l;O-$@ei6OZWyQ>kbr#$;LYX}?%`s4zhXZduFE#2Wh8`#R!Vk!so=@wP0V>5?_ zSR+8n@yh}bk)Ie*8I@U>9&PnMUu178tGefp9)y6^RlP@CDd)s8GtZZ$f>d^d(#jw1 zNeIuaQGG2D2u7fPQ3L8nzZsAyAxZqY-jiA$x`L{fq6w<$Bgs@_>E%dkE1|_z$w@%c z4N?8%$c&WWt;h^Tz$f3lQRcKi%=PMUq3hD+@wCZysc#&}B!k6GB%Wy1-X)O;)KPVz zxN948@7_0%LtpT9>T%9G@Xq42B%-2qi-rFHfU~md3Uyo&!ym1`+k3g1j6g%GoI14t zrgPGcnmS5|p{Y!TJ4E+IB-%kDsCJFvW)g-~BF$|l>3@3hfX0GP`m@)7C#41>4IWA= ziB~C&r;ZwVs#;3gsA!r<;5uZ20X(R+H5#mZX?G)#J=D$s%9{0}4L}@vpB5Vw*k9vy zTf=TpQ5l|&nkva^TP0mv7*~>xmWrM!XVj6tqa%fgTE(xyt6Wg15V??^0ALSV`gP*1 zQ>TFc09HEbpxa8Q6MJA@Nis2G7MDe1RJB9t)l#HFAzV_k0q154P5%I=y_v!IVR}-z zr~0e%>snY>96!s}a}M3pP#=2jz?5q3G4WTB#u*H698wB>Gfm_c2)8UOMaMq$CZ>EQ zr(4o}I>{wI(1=FQ*jsVYsi~(e6*g7;A9UJdNmNqm^F{TQKrI;MhrNkuj{&Lqf1j$+ zy*hKI#BIu|D!i39VeH0&f|{bDNF=PQrN}Z;uv&(L89h4GR51i-2nmz>H}~%!NE)MX z$I70*RpHjaYWz4K;XP!>;2`D`Uf5G$Xz%l$i3j1rNs5f;IzAL?cIzd{~&m3EOGugCQJ=IwhIEiy+zK<7^ zrKY8*pn6CeD9EVtypmbYZe|(t?S39XFaL3XJIqbQpfhYhBlI2D&b`kVpm6* z8}`rXW(S@<_}!gD{90W^e811vsA@s~00`=Iv+PP*XeOVvHZ40etxOOsaJQC?&IqrNqCE#f7lR>|Ry zpO$g<^=+Ath@;9+kM7@iiSrtjw#SIEcx~X$p`QqMQgPUm-pV;c4>A zUDW;efv3!7bFBEjt{Xppw`6P$^GlDz?`^l&mD{LOV5qa%Sg=`$Dk*nm99X(0tfiU{ z8cKxw1KUCMvhEgA?UKE`fT;|zv=ahMa-6&AilK&?bu&job!7Bg$-e1bY&%Vi*V`G7 zXO3x_&PTfqaNZP}4wQxu(S1axhUA8BU|kW@Jqy(x9{Wc(wl^&o$cmc$E<(S3 z=C?Krvi6?t&SkI=uW9b>)0@acwzvNPTvJb3Pfoi_A3|~wQ~2v!GbK#ylY2I4A&!<1 zLY@RAl}uww_-Y1OPZ=47D4<4>01}3wg8t@nTwK#>ChL6!v2Rkch!#Muz7(akiJe$F zn9+`gtCyLJIMS!1b=Optb(@zDOO5L7z1p=H?VFvS57)U247;X>u`6--Up+o6CA6`7 zmu=Sf0a@ewnticLmBq=q9u=WlnEd6vuZ>;eXNyZpToqRe>NEIJ${}i2f!Hl*TLY-0 zkztnW+--)*wmWN-w6VA=5I`F2tX~A(!|IrPX$UFe71Lar)Zfh>wb=Uy`JDW!*&AO5 z_zkbLcJ9~Q+jneL=I5=c+4&vE)cXr`S8Y1zWT~#mZR+i*}`LkpBP* zny#u^GdzLGjABjr)iBHkoTzX>U=Id5fec4&Yp1r9%8kor+jgm7vD+<-J8%V~iIky6 zapDv)>T?|#i13TCj-DB3)2Pb$C7}H0_|qeeC;cJQgDOe%)rHDxUVSO$Cd8ZAA7pyM z*DC^bTOGC@<}Z?V-8*A z>kFF%+_xJjr`8OLuOSK}QZ#8qD$OLVt5TA~!_Yt#C#hSK`4?!q+oRt%s08gPtWgql z1@e)A(!{k6k*KbatwXF*vi@B5M__y>?azqar5@bvw)hG2i?HhYf}ddb-rmOKI}_r! zZ04z(C)K%qk=qpcypLgKb}wdPan(}GvUk#d5y1V0RG7NTh~#QoA8y>BmJZ3c#o%0| zM6@X3;bx&`RV39V$TU;o)D;Rc7kur>8#?S)8@|zKVVcoPGN@`v5TJ75iJ@POWS}$z zHA7TbFUHu?r{sTFyLu6K4)Jh95Wjax*V$>37rv`3pU`lAoL>IY@}LC^gV{+b>Tm~0 z{j*YFv~C0IANfR2^8Ww^dbrZsp2&Cvg0FrX^Q8Sv@BSm$wu93hO?4FE*COFntO&io z*Zd0*Kga9u-e#j6Z_xGJY-|;-MfhZ}0{;L&59Awr*vR46y5)bt;Dc*`JwV*w>vref z{QBSL*ZDml>bvii=id5d^m1EWg^xS=Z zfG-E1!MC>Q)kz)Uc${?SPoRUSmE?^?o-~UxT!E`k`1?;L0RI37msJ!1jt$f9G=G&+ zfnrTe48UIYGa*6^&Y{OP_Lz#59#tJQLDSkR^7ZTIne%o-SMv|&G`IC1l3lgJ+-Q|| zeQamaMxmjjAY1Y86?w9&&9ep~zB~Pdf5ma@A33Oh$j5)F1pQF_`xA|QM^^c@o=RG( zhNX^3=BdPO@3W;!n2ZY&8YrT3B#QD=v@UfOjDe?~2*195ZUtmW6_gc0CQU|YPCnl= z=hgyAtXV?H7_&x7IM!N=(5RGqT`*iW#%XKqqb6Ciag8&Eyq*YrYqlI{J9T4s|_UR3*YUPx(11kI_ z_>R&l0jUOr=BBhgIb~M5i?6W9BD%3Tnmo_i&qW-bX=||3!%0(1P^w-p1V(t~^sVf` zgZcKl2U)idsE$Hqg}{&=8eD2pJxNeSK1UrLT%+1@_Q&JmE8B@oL{_B0LOMT{0bt`9 z$CpEX&BNd$+8ubg?X6Lo%+Tynn8*=d7+s|+1XkKlfyYQLX2dSsWnVo-pK^oW7 z=y1&)T_%>3wyQfEEyl`S%V2BW!6SL2gh;vI#KHuJ|S5)d(gAq!Y%8kK{#zRw(uf|}vRel>OmBVDSxTN~L6tR54LfxmBo!X=R#6Q0T%v7hg~5c#rm%fG)pVetnEB8A^bn zl;i$>o3&&s98stPHTyk&eQsy`qY>ix8S(dvAK_c3LK#P|&%gIu-E3GJ1_Jya>MwtJ zcgetxQ`i=t=mgXKyHNgpX1})q7m+zoD$sp9f7RIye?Rc_eZEC>{SV0h0E_+m@zS$# zw$P8fdh;dMGj8~)WUQ>(@MUT!DkaZj>7bSgWUj~kmEr97hg3dMV$_XW?#R;2%qD?~Yl{(WdT+cC~Kt%}v@+ zVX|9p9m_uL-1XVirA#hsC6~%$VZhK$4IoKsWfDAZD(P1WHY2ov6|#s&Y6cfdu6+Ac zkSp>(ZhEPAbqygcE_D(~<4-f6Drca3et#`(^FQ-F%zrWrXMSMo`u_kUwQ^f>PmIrx z-%(}g@>yMh4$7$AnEapd2{r@YArfR}hDvo}BC@C4`069t!M7Hk?P0Fyzzt?JtuQDg zuDWR)Da7%oPI&hv?c#GwXwyjUIU=;ww5JosrvMM1MyL6Nd`#XyIDQ=EzB%=`bW!|% z-udmzvo}sJwq#w-@?hcG&s#lK5#MG{2I7W`avFuFsqnLb5W7U=DEGCB!sEk(ab0#* zs|^bI@@))4oi(ozeF!<~i7d9_W`?UHrkd1(G8oX0S^@SG(2wxPsq@_h)m?McTk~;I z?`_A{J$te?KIGoi(&Z(g-}zmow{iGPp6{oVahW#+(C&JwCaNbQ&s==JzQ#>Q-E_ro zF-v-VGW-||+Bj7~Ay23TfxuLCRt)G2hq!@L#MkZf`+6n69sUIOKgVyDUnzb>Z_kia zox#@~{{XqLHT_N1l)2u(u9Kl?que=6zIPigCw5RpwCHK-sVAkSrJo5QV-!xZswuPk z={C!FRqa>&az?DD!&Tx*!-r;ZQ;k7s!ks@g!_OlO6FnqOtikqXTGrNx?y*zuPv$nk-ZEaoCHq>>)R@ZfSmZp4`(p|e#B?K8b zo{o3Ox_PNVc?-z~)pYuII_On8DH_N%8eoQHD^X72QYd>(dTZ(@irwP2Br`Qh4MIgI z2MmCCkItP~76Wd*S5tNl)uf=Np~_|Up7qRM;m+CJ8#m^E$b5IoPQcu~lT*3&muBNTBeQ!dn+dXJ+W0(Y_aFG5Y+yFt7 zeuAp9IvRR&K&w%%HrCQA?rSZw$i$mdlW(StRM2$_0a2;zftIaJbDZ_*C%K%txN^;_ z75VX{FaS6JaPpv_>Eq@1!ylO)pY!XXeoFMm$o~NDN5u_|w>I7*zJ4?g#@{$vKFr8% z={GH2Lvzvf-X9rJu=jpvamSUUp{Z=0O(e0!LlnyHV-dHFp5Jm!-0}l`AHWD~fDHzq zbb<-3Sx6%uoor7$QAckXVHqZ;v<~L2YfV@frAL)1o{eYAPMz;w@Ax^|ol)_7vEu1( zl3Sk#v{R^iN^Q-P*=@2j*lp{!vw6uz?!nOHvwLnl?$pOu;$^9&f=Q!}y{s4YD`pF8 zs9w(Th_!G7p6ZHZ(?@nl1GLtkv#P}-Lee-&u~u3dV!RGB%uK#Va#LsWd3?ooMhsp*ab@Xfayk5F(Zx>&H7g~jr!^v+$gv_a zk9v;U+Q-ASv2Aw9v<*fYi8UsSOA3?0i8Q5sI@GesIoBxtLQXM(!e)i2}eg$T$cLi@od~;sN8mr>>xm2)gEnuCr9t`I;J~ zX-#RWN__ymOwXgYScj7OIaJ@j#Dm4{&Re+nL=^x4gHURm0hgq?k<3vlm5ERaP-KMw z{K+J0EKkawgBSBa=^-B1>I#gfO^unmary19 zPr9=-HT1P|)$aQIHCodJQprg2209FG;j^{e)LUI$M+8(PGl@#-90Blq=yGU#O(=3f z>6De>M+k(o5t;))Do+r2D*>fz=;!_{eg2Kf2>%6gBmyHh9pz2q1ExA)~{ z+1NZ#*_62*tzC}7941a$is4m`mY^gsm_zDI3wu)=$A9CNqYv#4fl3hGCl@WA!KFuS zO$8sC>8=ZYh(#6j1d`ao;Av4qlT(_U^sD}8-97x!_m^q>Q`|qxk0p-9b(SIWN9FE5 zuYB~@(|yZC+vjc6Vxl;X&ypl%?D7-}|PfZ!*iX9QtS#oMsO%{p(1cRp`jw!@cng9>CV{NVVoA|-r*iMJ1 zjvnKmtNT`$yLL^xnv1Ds$ky&LE*g?5E!6Z)Q27m1VFP`|p!yF$7$9{S<*E%U2_dvWm_h#3=FlR1c=nCy8-U<*+*jR zBD(S8EJ$r`zzhJO$OHKnq4oTOUNcS(w4#79K)zWtpyGWvaOnl|17!aIG&*nQdxWa% zoEy@Q$j*}sX+)(wFK=0__g0CYN$VjTIdtGTxxL}(cl)8igY0QMy zO|@qt{9XVQ8pYxeSbzYebSiw?1xeybpaS1hp;9p(K+99+$Bk+5l^i(Zh&4CgJF!13 zC-`5T%6u5xpWd&P_^kf`Sw6(V{jXnFHb-aAxv6QpLYz?crDi{3RMbbarR#>Bvq>KUF#;o=8Z<+M;dUk8Ab1ZSirXar+4ov{2 zaB6CB1u?`Phi~R*QT)L6_QL5*r}F0NEEjC{HhXjS4hOcWbNI|IPZhKF!fZNvuC?AZ zubt0fDY4l49r%(hVnt$?ljdi0Ny_A>HBE@=;ur(!$EmpK4b%xZ`u8^Xkh$IyU zt-)}X!cy^Ug$SQ6sqO8?>FQcGqpz!J5*4)Rr|NUR7!sZ!D!X zSa%C>+Kg^~p6zREaump~3kF9oOfl18I}3JYw_j6aG89{@XLknI!0w7%p4iXr%IN2; z?0t`grVw^6$gDPMZ0;H*smpEr#9zcH(s-t|UDe}UT5gae zt2fkJ$`$tr?dBC+g2&^Yq_X*E>m=1XlKv(B9mZz zmFwJo8n1P2&FzuOZPbfr$J-khC6@A3W9TWP#MMV%E^`4TH6>0@6%^y|U5v5WY?s&1 zaV^ZVgtfa+8XLE+{YYnYoq!$S+cM)IBGzewv zHrv&-V9#$e7?oj;^3FywG%>2c=_6iPGD9Txu@GH>1st0jWknS`#ASzWAP_9Ze2}WH zidbByo^=iTfo&KOk_Cr8@tRXF)Lx@FAb5l9pdqvQS3O~V^$Jb7-Xla7=jy_epz4sC zP|~MAgiry2iu7@F)YLVmW|Y1*x;RZGPCBu2F{HH=k?5$Xfh$$$j!6?mH1I-WRFy`s zji~#M4A*e(vxbS9GFQDo29BdbfC*qJ-B$8qMmjLv?P6$_OPIcv;1^#EhXP#&lE}fT zz9Ql#MbZ_3s0OE}B$F4L+7rW#ol8Sh($6JbGUMmV31dMdHIPhn%~_9FN_is-6Fh3k z#hILUdl+p+%sM;UNYo7v5^6k~=jDS=9VKV9zT28B34ynah9#FnNJs>uDZ?~lvZ^$a zp_ZV6Q0BE(vY1oJ6THvheLAG9nx!vRum~J7%`9=m(n}&JG9TSrIB3d<;hy4>n8}S# zXdZsFrbrw>@)+q6nO@=+wTo5zPK?+S<4mPON3OZ?? zC8{#fRO*qVrm3Nu_?-n^T)LJ-Z7@q8C5ED*RfcY$NrMYOYCy?WAH)s_BAg9D`#RLp z+C8C3{{Y;>B?6VIXe1KK!?|QFTprTCd7usOMi}<~?V=TuQlz`q3Q2Nh7{^T*Y8FY7 zkn5JW!yP*p(WJ0X)P0X72-deER3gyAl&7YmP6rSN0gv0!md)Wsx89`JB^2%mtn{rH zvWyoc$N<$v4F?{Nme7RaYv!q~lMj%suZ<{RuWDtd!ew!p8Dl1sEgY_qLAEl5BbnVw zNl7egC}om0KH@FIbenCyakpN^Ho~D^X;7F=ysQ#LzK@KyGbKD>hmDj=8C!^vhEQ$w zwYs>PZvsgl3gJS>By7NdYlVtRDJH$72CY;cl$+PB#^21$o0bj3kG?`VJ1ZH8IO?s# zhsk}bJ~uhE-bI>)^OO)co--Rg2JfJ=NBge9hWj<7+`G*aZCuT?ZjtS_H!+>g-rj3> zyh$aDycag}FlZ#XFu1w1m0#&MyFn5w2~M&nyVz0-#gg>gMQ~oXNSayIsYEexQqi31 z8j|%W!%LH@qyGSzrYHNc*E=GPYMNZn_pWB#`!BL~#Z=hdwC}#Rqo|J+{pP~pt6`qA z9oYL5JL039p(g>>ifBJ)d8Q=%P-!LrJRr3u_oh--~2s}c0;D>+;E~}{pX~+ zSY*A4zX(zX+ozyo9UNcj83Qv!>50xg7>yJp^L>m;A(S8N=w@sG09793{k@p-ia*JmPWG;u;$L<>uabom_6}Hmc?Y~D=M-1JXT{B z4l^N-$YZip62Vs@+-1t0}t=efA#o-_;O4`0NhB%VH!< z=H}f$ZjsW_$)=P+O^=6K(!>s_C#jaAqG0~}yGy%DWO#&j@t{c3rSyu9E@)kt{7gX9 z0Kfos9qwDz&iA`ZeRAr|^aDtuq)S~2f~OT`YSh)3o)iMLwyyr_uD02G$0^%iAGYtv zJVtJ-W8?66t;5L1a*otZMLcmLBKcNJf{Z!Xrk)sY zd>G+r3&;JSVg?vdbTA;2e`p;py?vc+Ctc#w=38>(NP=Gl!+^w+z%gag2qVkl^60z# zgY6%TyZW7Jb`Qb2O^;hHE?0)X74mO*?ntVZ3RRkFq@>7o&OV&QNn*_;k|bdPCBU)v zc=wV?6FWz596(eu2d!`xx}C5+23Y>im-6M$D#t4Q3|oSobsja}hzb4>JT)MS(w=nv zl?>F>mEUlf$}vw1W@iacS6r3RDzt86jcXb@b(_Sd+Q$#|1KElLp$m`=Kh=*erKgn^ zJ$h)rE!*pGHu5>C)+Yn&1O5z@PP z(q#oWe8oS*(jnuxA%(}&k;nTH^yk}^?$gnVxu_!tr9Q%04*l3k3o6we?X^~xXI~=6 zDb7)7H3*@aL{=ifK_m-%P>-msMnM(n>!~AszVle&6W8q0dcA+gp z&+Tk4%Dj(a=Qd|-;%lg9)3NY41Tfdp(91@JmO7^L zr@OcD&4fs$cH;uRE8c2VQID8S1iFGdiiW7F^^4xZdug%{-dxkX*~NKq+C{jKE5<5h zS*2*tZo00NSpz6mG6f7FkX4_?uIlZKmu>8gtCZduUEz(+S5@Md8^5cvTc;IBYhadn z*_R74Bf6*NnF<4f0#dVQg+u}#`uk^wYIJ!Z|%Gm z-o#PuY!JfBl$#TSrpD!W?(JE!+33$?Z*SqWiJzMjH4YOgCOVd`JarvMm`JAWF9|YT zO;u?@R2WoIfIps~rnXOJwmU|0gbRpeiT&(wQUlA{zf>oHwN0KLED;n9KGH2V^Nj{S~Ns?)Y9 z`-iN2I`l0A^_5m9btQSFA`dIq!@D7)GO3qHiIjvU>@5L4J(39MOUOwaFrtIy=TBVp zTKX0#otv~R0RELv`6>2v7iO`Aa#fnlfW1tN&PJvrzpdCGQycrK3Mw&!(V%TXO?UzR z4w<8c12~pl3Iv8H@%adlaD|a)q)f1 zApHTgt_L7}H3B`mk2A-wXUnNeIhHp`8RTXfBjt3f`fgcR8|y)CEPuz|spNk?y_`_> z-90P)dlH`rHG_7rOEF{{Ug`!`ILJop0yUr9LvK)G21Ag;Bx@Ds-A@91vDB z^$a8?+}L~Ar9r9dRrBk=v6+l49yAqm)I!k$s*tn|X&OZr5yUU){{RoCzhb920>A3{ z^}1({dd(Icgfp{LQ!EHnpCp#^F$953EomD^H#YvB{n``?aq{~**Qn{iu`}8#ct1mLm2fb7r^rk9GvPr{~tI!H*B{b(X5O zjjC#DYU%u$7h_E^NYvSIx z80s=m#Ws;56tih!5Ls2f)i2fT{{ZYg*d}P*RFhmBQ>T1R*`}?^Qd6`>a`jP#bp$CT zfL2B2k^cZA-Ql(~$cv-3jXJEe_%Xbp=u}ts4!(f>FY&W&Z-3;C@yFyJU2YBG)n6!n zGkjm%JF1hgwua=XqQvk1yTxui>=~}P-T29>zlN?}yKB_craG!P>FXh^riETvAa;zJ z^NQP@=Ked|MUu^hsvP&#k|Y3;LR3^#5=NSg1DIEtxmB;D_OZNatXn;0(cE#*^8 zCy6A8K@10qfshabD`{<7MwTcPebuxNQtkw#O@WIvJv*}SRkU>br!8B#qRU}1Ln(}) z+t_{MkjrHsE5ADecYM&Gk)ffiSmZ{A0mv#y?&H3nxwOf6-Kh{okps~+l*X81t0^?r z)g%_jSgmEv?6z{*?Yk|VzPo#LkRfMgbPTO=`mE(l}A- zZ~p+CUkrL{b#~Ut%`U>*eTTWSSvd0QIxg-X{zAZi2_1oRkmbq2%ijmeDa?~ohvm!mdacU|Q& znQqR;=XOqi1-AD3ZED=!)!zGeH(X=1MwX-V3yyL6J+Of+c~}EvW0e*pT&ZbJ4Ym1 z;+_J!yJp~|fYF+(syec*8~2tgq~`h2*wno@zPk^1b%Jf3s|L*6`}br)uy+>b-Bf!s z9@~<$EwrSsoM13{O~RFvP)X&QX{g!)M!6eG4<0*+Z>Ba9TI;KK zj4_Pq)qzS=sd^~(sJU-rgKgYpxP^7QO(JNO-Po{K6*MVd4fu^qUW|vqyfmlg=f>$L zjr>o)U^0ngSt$HN6_fJ)&X+%Kp|~w53JDkB`zs|<*6`#X1@lV&6Z<~igS*U4`?d#a z>iUSN2&k`$wIA%Bx10Fw^Bb}{7K0nrv|VWra_o$rrz4f3 z84kn9VKz?Y+4&5t@>J6a^4Qw!Wb(@h`?_f<(up3$yv<~HWdHw$AqNACP_Bv<60(Wp2L3I|{oqw6|o?I$Zb63}DC{ajY000;8vPqpEO z-xrD~<8W$Mj$%=P`+p#MxZhiXjUf(y)Ua33xAn(if2Y&)>|kAW1SceQHd8%$S@bug z>b8{P-$84e@E`nr+vQAk?>@O8Bk8F~Hg>t<_PGFkN%|A?_pw}czOpd{*&TzZ7Emm$ zf2bq!0OyZ-t#Q`B!Po!O+MQoklCR1D7=2dc{!Okvzw3K1#!A=LzFj%z$3073T4W5- zgUMAcK(mX6R!|q@Ja9K~0IR5|;e+TG&rXx#?^+Ew{USqGF*UajMKQex82?Cav zWBkYjsKw zFjaHw{$8$=00lt$zh-O7ZavnECz?8JT_m|$#i&>&t)-@e5m4R$%5=!Vw72$HkU<}w zb#DeZ>~^6eXbzNGgFsj?%|Dl?SRZWZEt?SfnPGCx!m6Ye6!pLcwCU2aYPzSWLtK%; zg`SQ|NUIFcOPGf?lc$3ZPSg_Pswya{0=-PHEE35Q6A+N=P@391TQZ=QNv7_o$U_+e zORzOvM39&wxMDC#OzR_9ZWGCQ6iow0(Zt$=OX8g*LNpZpHKWK~k&6ESW*mkA^FI!E zJF@Xunj+4Ei!+dh2y5boqAZ~Bq?Pf-`*G6JO+ca<6qOYYMvz%S_O8}Tdl_MpVgs~= z3mTOp@P?=2QfeE>RB*3LZ~nJ%<^7^1(DB7|?@eGgh*K;EG^UI&tt4ttRcp|Xwzsux zy=8>jmi+;^_4k|nmfHD0 zmZTNZ*7*62P5!U9tn2pLkL~{eCrG4~YamDbv_qy1l?vBj|5_c;nv5G#$Ag;p@!R;3&BK>DFbh zip&cRPcecUNcwYdNjEn)_po%8BzJlBvcalc*X90W)>x~fjx9=KDsRf2ARZ2r_+mxw z54{hcTk$FQM+|i#YU6bBe%+Y*e?tX8PPAYFkzL8SCy#z6p=-yc!9ILC=PhMCmKvgz zCumPP3ZS(Heq)S=E$V>Nyr|H{$jH{tvxVC68V# zqz@zhuk!WII*7%j0wByalj-#}w1NOUx&=Hp`wx3L13Bwq>rq-CGuB3)2|Q#KkyrNv z6j0HhrI&)o{tRu$y>ZmtXs}_PKkEMg4^o=CA^;4dN`k9$D z2pRmk&lOZD8w9WnR`v>X7B?+m0m$@c;dL0@OAx}=1W901lEA6{&_CAR>Inw4;nl$! ztHjWsv#iNg6lvl`IuH#B$W1GI#;?K9xB3nTzffe-wd$dcjU$H>*Q1&Qk>s-Z3Ui?7 zk;nT}F$Psp_&-Z~@g#xi*42WLPucc=pZxjjD@_#3ra>Hmm_4{QBGxI-_7B(k`@L&i zXRTF2ubDsK>PW3wfd$AQtYrF`{{SOVxw~>L#{=Gn9B}=eTD3|F3gFj|UBxm&tQN>w z^&cBDi5T!*g^0O7U(fja^BjZ2t!os(01r<-xwNpe!z1Z08N6;av5oYNWmpi=+>2P> z--#e+ho@Vrkf4$F{{XA~N37+eu6Xt2byA>;k>~!dKR&!BfodbE3;t55 zP&oqc6N~5!zo;EtAIHB`kXOt69cXA{sg6&kJi6ymI?fszh($#+6%xlQmmmTNA(q-( z`dHrM-j`4~K3#d)2mlO!t36GIwL%!wTTNdOywOCaRj-~E4e&M0x#fCjYT z)HsB2$n6>-mQvD7r$A|0KpsXa1e4=<=iU|l^`tOzuO!YMF{0{X73fw*tOG$)@d7GXVxV!Q zYmQ%d=0UP@v2Yq8bu$oYogyCG`sTFFICKosZzY-xjJQ~r5r>6pWty8Ik(Qxec@<2w zIEb1Lw5Z9|NKA-}8WM^@ZAu^CIxl&O<{@#pa{k*LhTg}*12Q*qQPD7{d`1kx{4gU< z(n|$?vAg%fGhHo`tQPTykcW`cyh=tXq`Q&|paP&|)C1Es1lj%Jj@@+dZoCBzb~c|9 z_#9SmFP<5^lhoEp=6$Zv(N<&V>*?i?Lm;lGf-1GBF@{hJDR(E_Z@0Hn*nawZhr5<2 z;*MpWMvalnqepPHOI0MaYvaF%F>@FI_YZ6-yYmz~_Kp75C$x?!B8pk$6HTs4NNrb3 zD>P)NeM~hg(+aG@wLVhzM)1V!gU~y$R9Ed?t=P%BcGV{1q{*)M>FvQuhsfiyJ5z0C zsw?UxPPoj$k!qPRc4}y=gmu(xfu%`i`%T}Nq2=j4zQ2(E>D%u-SfH5{y|j!7m2IV~ zGACUtiP9O@fVtn`&WQ9Vgi2-KLf)A)6sI62F%n0=Q&&)fB%!TUb0r zFE8gub48YlPi`s*1Jsd2o*hDat-xF9mEyNm7vPBsktrYm3$_Gt-b}I>2@Wy_>z=#m3bj zONqr=CLO6Mq1RAwtT3uDyap-)&DVO0=K2%A{Y}NCvnt0eR5*Ys1`q`lXmf(Z%OV=P zYoi$WjMQ^ssPS|)5N_?$m944DO+brV0mI>G)uO7))Xr!EHdYx?8gh*E{uf2mN}p$z ze6*XCswe#$L|O)XhGM|7D%T+3YB?kj1rJGf#qn%o)p-@&?9v&+$F8uVR5_BVPZdZE z!D^lxAPh(~%|n5p$w5ns$kPlK`e<_h0AZZV)SBI`x^ooSC&**zt1CgKgJtD^h9Xi$ zS}H|5S1P?it4yoxSp2!P&i??r;Jp3YxYUw%xYkpG6kA5ke?td1!RZ)CJu_s8({?Bkf8Gj*vS&VV7%f zbaOpKvhH?@ni-{u+)XoMVh*&i$0&?`CL%k@!m8F7P%mr6Xjo* zo;rVEdv&wiE!eYM8``KO8XwaGv{ry*W8xSbIG(*(Gz*50qEp{B}Y z=#f^UqZza)YQ-q2(kYA7D5!+0#7?DU3m_kD*tY5KlW~^$BGKZ-d1WM`8SkQ?V;zu? zM;jH9HOP%|2BRNqq=6P(s^!aZ0DlhkO!k zG4hD3@{PAAp{c@AQ#;lut>7tFEY|dY#vWgutN72#F}Qtn`99mC!?bKI^h= z@>^-LxlO&Sq>IB65jC7|BFW&fF{r$?W<@NTP$?qf1d8Dbv3=(=EYX1t#L{i;su1y& z1_Ep0#i^FF#-Iwi&_t(HI%EKKQ@=d_0KL0kV`R2Gxkk@)-cNqxca%7HtE9+{ui2G& zx|*zp>c&dCs%bN|c;=RiBVSDEPm_vW6DgMHxk1SHTdlo}n_OF@$+i7kvfDhGqVWnU zv#QmR$WW`}C&i_8WG_u#jpuE*z1h}a`y{fY)~)-u;d%cTHBu*%UHE9e(W3<96cYX|Oo7sSQs)R<( zG4{KaY?E}m8*|RFEcby~nZf{?6uTEB1fqsIiBP;r13hn*_T=4pjt#y>V3XY{FjJD6 zL0~DGnjboWk;9#o&6d;;stbZ43u$U^Y)XHT$TdR6^Hr+Sb8*i((cW&n}n}26F zbZ+gHpTqR+8Ov^52Ij(JvN-<0G&vNnmXXCIRB~TZO3_F(<-53Stv81^jRfwA8ZwCq zs}WYDUGzW;60{(GA;+rhQCmxN;_gV66^cT9O(iNJk%1wZ0V_b+bQA`xqNF{1nyL6- zn#A{|W;=82><@h7w}-^cKYY_=db)lA4^|G?3N%q+1q(($&*wu-FTUhhqj58Phyz}p1 zvmPLxoUpwv31_Mg@bSmXpl+)bQ3c6{P%rf{vXT8bEA2sWKx6wlJBHz2p1z$s^~6#C z0HnUTS!xoJGr#t5nyN|TrH+y>?+!o7QzcZzVWy51yBQdTKnW(p+lbV0UIWkN$E9=X zlFso}dyFmz%#}19Y=^mfgKln~hV9>lo$rh4p3?a9x%&>Mv-;a7i{Jfsx4U=aH+9Qh zPPvZD>0ZKrB$1PxZsg7T+`dn=-FAoM4Z`Np(6SM!qiDhG41^sZXrol8 z^#{d{f!LeE3f-mHn;#FjC!VT<7rA@4xqANqZ_;9@vT#a?3*=GpSWI}(`TWr>~V$!tRAqUtaRP>?sKiso`+AJPT5k zBzot|s*L{tM*D)AqENJ=rk)vC32Ei0mF_MAx<@OjOa7~ydw0i=Nbc^ZS;(8Z%?irU zNV2f5k~n{{UKr@Xb(YiqE7UvtVkQcflYH(D+3EVNySVZ>3OsHys~BP3cQ2IAiI0ids^<<-d5K)gC{ zdMbj>@*u#fu`SH553XFD!8XwJUC;nKV?&PUkrzyY^RVo{)7+@ziDqZ^y^jg zu4&ZyG4=C(uzERcQD8=7WLFTIgw{r%+YN8+A>KvHbm}FLx84*K| z)Cl@=KsK=d01wBy=wJcUjy-Qt1J~26g%36kMaj7bfIhbz*pGFl4MsZI%|~4T2?342 z7yOUuaryV^j34!9t=64AQ@n7*Bk-uKU1QA8VCykmDA6#t?Sb_NoBQ<-!{yb06yu(p zzTsq&W|d-yFpZ+8NdN(ng8-oF3<(6>^JD%V?d9rv@fG_z%N<=iK@eDgo*5^apqVY^ zic%NH7xZ8`x%!`brYKHv{?A&bc;lxyr;2I`Vo0Z!pHjI+c$8^G(yu!ZWKfJRW%~Qw zdx`7ZG3V2jCPIdWq+}zGrJ<1kWYrOlG86#{fpB9-7XE@#^ zPhCSj3{-N6sw476F;y)T?5fgmmvf>;BwLFTexCQHl&b(g!PfZsbdzR=W{#d|Ehzs0 zfb~(KJP*)Hfyph!{kSU1bmtg7RPoOalWUI2O;uSdQr1gpC0Qi!%)!fkrcvYMTl4O# zZy{Cfs6BYNQZ)Y!{1xtTkJ=?%=3u&fl)l90j)PByU z%Yv$;F$rgFi{VnH63 zWhCC;Pj4&|RIyr|a3AW=pG_I#1f5l5(395tYPPFCO0?Mgg=vC#C#Xs)N{X3cPapxz zaK`Ma$AC}g{C%5kmX{B8Y!U`<)KDm-)RVwd&!U~i=}b~Ba8%RR1FxXZ#;xOn*`M&9 zDtyL!_--3)?vIK)>tyY${MEFNRk*jV5kQEh~iNb&@#B><_;cK;fZ_Qh+@hM{l-FzAHGVw_i zNGtf=*;QBZIiRWQUHWW2GaO7O8yx0>T1ua`o>N6tUrkQXOFa_Th^oHO*3&CSCs?F0 z77i8k=`A@7?5?Lnas9n>cWJyf_tuguSw=!f0?MQoUpiD&S0q-xU0+v8?T?6gzJSDT zy`k`H ztSh40n5>md^ro^Xv<04CXkEJR>2}?sJJeGe193Y>fu)egSC%s-pADL8hK+T`S~w#N ztj?LS%GNsu@w9DmZJfAow#I9b;oQh)SVZOlD@f@OD9#tLsM4PbN@^@5=z`@W_`|;U zug6ZUs;+LG=}xTpn?cYU^K#;b-`X3d8r%=@z0v$jbMFfLKIz0~YI7UUEZBN|!IZ+q zl&VQiM<9Y}o>1kr(YYe>_RM%u&2Esz-m1|+p(08|OMt+dggvRHHC0P=ZSF+8vvJLP z4#gJrZ{b6<+}qu+4_$0sx0c!4 zA7Np(Hg5y6vfI6PMnhz0Yx=`x$6GBVZ!zpQB=Euh&B{I2w!Kd?s=}Ds)Y`3DJRH>RT&774svGz--8%xkwRKnza zx=;8z1#fdk+eB!!ua6EsVpTunuUmZNdcSVg^h53}%pI?k?C$W~nZB<0uhhK*y|7(Z z-5rI!_RcoDGnCysKY8w4R^!{0J6@VxeMEbMF_NQ$9kVbv%G|8YSuC{BA+Ia)#fISo zGVW2^xVVB#fYV6v!EbL7D(^GIRneT3F`(5fh2mIaV&wH8`+dn)Tb|iJGH(`bJOhMf z3yKyo>d@V?7jgnA0aHnLVx*L!&4==H=V!#8;OY7wm^tdNl3xn`Pxppj9@Am?8+)keO(@Js{0cmg1~OB`}pS+nOb^WPU_Fl(fpmow})%tXCa0s(2AFAB&Za*Jiex^k_+0Wb8|J2%rBnWO5 zRI+K(NFa}|tLSwLU;2+_<&OetDbu5@$XS$vRGaX>+F`*OTKBg<<9~F>`+B8EraE_~ zm6k;XEUW_m0ALoe^-7tRGMS0Fe1D<`R9E7!#)@1$Ibn}Ff{K|-o1yBf+EaArr?<~l+vpoRi|8tVSC#C z@wc7hXgPvu0ur7$CloXwXY4=V&rn}AM$q$SFcedoX5)%cqrqZuWnG(yfqT&wWFSi?msM_U&p?5b49Jj-wu?wJ{7Ih@X4x# zjS@%!(^{V2F~h7I8zkv_%oYy{tk6$9R3?MAM$=RMAfVIb(%&~gwDt6|Raazka#QX} zYccrhxai}7@a+OVZ!J9N-YKTB(@jXaJY`IZ7_nbrou+4+3&w)pA*$U$Vo9W`YN}My zi>D?0%>m(Ff>Wd>2wvh@Br9^oBW*d4PwGg|!MIX18g!bltw;l2#iGGvY3MLnS{UV_ z$YW}0QzK8Ia#Rt>WsaJ7W{x8zLkj4UG>Cw!tC40S-r~8_a+6ILjUSFw$DJg&pdyqt zK*8t;4N6y|-Ic5^W477u?Nr)KwGKbDj0))>fl@U9flUCdO+`TpjQI_a{QJp|R24QXCA!4U0xi(A^o;VZ}VvN|g@46&NFgp`T{rHNWo2ZjIur1p-|+H1Rv zndff^#Ztvq@T_%7j;yMgsaRv`sg^kBqpG8gBpjDkEzc@Fo$XtUcDFlY=x4G*JVGhn z0r)Z1A^mk!vWnmqkjUJVa*Tq4QqP|$jI6vji2+rf{EFE6y&c~0WSHzn6qr#cw zc;02ysw)Y7F0go!oQJSC0P}Bh5$2&8l4waV5`H00+V)#mK>}JJp+S6R^7PwzJ!NXJXo-O}n<`#qI2@7`hs{=BbvSA0}H9S6>YkRddNI zL}V(Oj*TGO*rw0j9(CIGVcT*B~^m}E95W@O)Jo=W%pB_d4Fz$ zX4!Ys9@_!^G%&#~jcuus43V=H)JY0S0<>BR4vjv+`2q7^a>1IKUhd3?#Z=M9AN%yS zVAJ<7yr4+yf(td3cq|V;Uvh`HT=CCb)nR*cbw>|F&YeUWa5xmlQtvB! zjn5mm?*+ZxQH)Zmf%NbWBT=acKWCRpnR~MQlJ_O))gmrAhaJD)E!^5Q-o2Z=mtaplsb=FVjb8Kt)^ zTGPQyQ^@-MeP;gvW^d)teE+TsPH!g@I-MqwDnc`(ASu9Ir4=0USU~ zdT~>c!oO)XJzR5NF%SofZKjnY!C$hq`EjQM=hXN7q-E@;M({duCnFnN$rs^p&Xp07HoWSzM3jn%2ElxxbjmUk~YZfuGVJv<*U}{?C_0 z#=H5be=!_p<<4!$dk3oOmjjZ|so=@AmY5I}R7rb+Q?ng4( z%PNifeM=^aXtw}lhM+JKIA9WK>t2DIue%)Ex0!T}yo8rY{{R=MpkfVwQ;*D0*QKUM z`Jw*+FdS6yDBitISWO)y^CX=$g)uW!(xpKKsWLFSmehGtSx4zMes$P-?#Ob7JXb-A4~NZAdf}{{VarC+G6%)9<%9 z=_Ze>V@GsO1G`M@$I_uH8>prX~$(C7mhvbS@*3Ci-7g zCd88)akxG1=ACqta!OQ;!);UO01$Bp@*@BPlI&jnb3fzT_PY7f83rkueyPbh2h$un z%zvAo&xA>8O&>$oLq@_Hn3Jt@^zN!if(hgcy-B8yS=bLzHgloAs@~QA0IxqbmvEbu zLZBSMZd6eDevs5i!Tg8=Jt|**Ie@FzX4_eXK_O-o9$4{s{QUZIr~YuCJIWQP+y4L` zWn_@bL+oAK2Dpe-3XdN68d(@>AL@?;eoZF#znfsGTgy_U4mR;|t$dVY$o}58p8an{ zPyB~=_9WB_&L}*Iq@I3%W+~K^{&PPz;$?X@N5}fgISGtE_hWp)JhNWtq{Y43H9*3| zl>m>Wh_|;R_q&~0N;TbxoC=!SuMacY%b!3nDZ|gDYww=xP+ykz{0})U06#I@czST@ z)}Q&&e9=)S+;wlqxlC7DigAkUs&52r+R}fx{`yNCsIeQJD|7nSjYHns-wtchRJyPw ztE8K1*T@0{qlcD9&#nIeug&mf)5|s|wUjQj-!JJ_Hm~WffR>rx zOmz{-+4QA({eBnS6&kFz)V8~iP&!EWul4cfw__5^w~4}vskU$D{xCS?gXP2L(?j2_ z%B5G8Yzy!ens6~smk&Oi;r@3YD#33rM06WQr0ICGeU})hHva%S7Ob?|mA;ns6+Hbt z-M#PTxX9Hu-fQLbt%37DQ~M7ODstAo_NB4_epd=RObThw^qd zG0XASqvm&w^%ysYVpIM#1-nU55%hy^#s2`W)7{hGE@Gf1>R`%OMy<1PBlGMe(*CGgZ}_hZOH_W_bO4V(TC|b zpAdYw9-ij@cRlchp_k(~SJWb2D)Sd*Z)gm0-IhTVX9FV`v>jTHH{hG{biV#?AkgjB z9w6b_E`2NhFfsWbTIPe%{otf!@8p;OsNr`Z^5K|2pO>dos6U;jb)-|%NAZKL7ww_* zQA9g)cLlFP)|wMlCe)c?sfAoLXmuG@;YeX(rGD@mgu2`JRe;hvyJr+2R|Cf(wS3uW zz*osY_wpl3@@j+gyfopQ{Xgu+cyuP=f1Dq6Whcebug2}24Ec(PsgVz5?gJbTEGASb zBke%5-$4s~8ost4Pic0KyiV=BZt(1|a@B&%A)sROjsTt-+L#smRN?dKPTTLAZa1)5 zj!e=deG1=Jek`1WZ|UVxQ~Np+BmQVz;7*yoJ8hd2>M{04RY^P>uDzzgNMJ?2pP$bX zFZ$qfAX=S*$hJ65ARqD5`+69UaL}n!uo|EEc*oECKQ5)k{L;I1JYs*1*rRd+`1?Ag zS3-gq{^rYL}eLSnv-|K|~DPyq7iUCR1ht|KR zjBxe!>BgJ+qxO^N5Anu`E49E*&SVM~i>p4&vkRU<9@~F%d4*}CmMsiqf67DDAD?Fr z*ni7W?j5;OPQfm(`L4h9ug{?uZ2tf-p2*y93}5IrEP0&q{{H}_s*M|xps)9C4RO7! zKAij4`sHtgs-9W3t9o2Me{6r@;q&WX>xphiRoEpY@cm^UxAgj7Zy%gn+hV5GeAiU9 zTW-hA)6vIAx#5ARzk)+YRZz7}QHyUlo+{<>=?kQTsGE;qPjG(m7k=Gs+h*gqayr~c zb1aG#Zu~NaJr($%ZB-62K}r)-fNOE?J-wN=7d*Fc48_9IWTN&GPYiTW(Zdu;IU0JIuc2(WA${ZDDcL7Bb6vK?Vlmsu5d#2RLlr@qQiBwY8(f6&064{*#%)rQD01`_m6#e#&Kj|3rlhNi zo}^UAU5!Ba%=QZ}NUN?2gkw)C$1FzT%x%k$Z^<0_&pQs|W^U)(qFz*(7x@|YIRBnrCMD&cW zYDmT=GLl~6M-3*j*@;3%2~Yy7w#F{CE4J3!tBI>5#!HFB(NtojHPo`=a5(f|wTgJr z8KH_`O8qQFjjinyy|Tf1bdRP95RzX7UPd{m&a|gced{*ixG0pDou%w3b*Y33=>&Rb z{VDUuMhhv46UkhWO_uw*g?XMD3FdmJ(wY>bTDpmJh$$)Kos-DU7V&VTsU!rg*kv~M?po8 z&C&J7-Noi8sb?E~=F8)tX?KlI))eNdx}y;j#ZNTw>y7HAk>q4mRQ4v=?Kew^p5E+< z5iTWo*s)`#q`=Y@00$Ky0ZXcIIOL8?h ziHMEZ5~fL6*^~`EB5}FgzW&3}8k#!#>}Fo7k1dCK%D*etQRH#UQC|}A zt1TFTuS1~%q|}0y1XHEnc+pqKQ$Y;{D9BC{q6o3*5`v0>>Y6%PF!e7qw6*zjN=h|9 z9yN9-sA(~rhm@^B zOlbs_=^wJT-CWp?#fuV&jGRGLYHX5A8%r#7kYr#8;Z`;-Vv;DLRx&9Bi*f95R!fwX z-fFVI=9)=TV{d_Ia_lidoRT_wWZUIyP0mXg#5V%9Su08f4!y#Fl0yw3*Y@;aHzsOb z(~63>8IRmGSS`l|B)GP%se($(Jw-h%Ln$ssx|*29xa(Sz{GMl%z$8MgD)|8RPrpk( z@oBhtJ2l*!B)59visEq3XFa-%nGk=B)+T7yS(OXM%F+)JddMB#@LpRqws2fF-*SoJ z>nhSApw?ZK9~MnNrtR1W%L76!_{D zYJFdGR|(ehN)`n`#=wtZ{zLY+fA>Rt=BRdtOIO;gBc0Xc3}!E=ss}Vx464AAK#U5o zD^j8^Qsj%B_j8A8H=p9kY}ZBE0+O26Bv_DPWG))bzN@ zoNY;^$W*koII7Hy37w9vhg`^$VsmX%u4*cXOVL&%v~x)uoXz}?3~kHXCG2S}yl@#~ z5HTdi%OMgN$;u>*S;_)aQ6)*OdcQJTuE}|M%R(x`sT_cshXMP=XlOw-1Qi8bY6OGT zA$By2Nl8^t52iVul1Vi%2_KoBNemzZWmn*RKEKo6O>)>WPYkXq;al^j2TW|1@-*Hg ztfYWI{{UCmIt6yZ`THuu=GZ*j+v&>F)2JfcFy{9E0Aub{x2kgU3Vt}p?PJu386UbL z3Jo8_cVJGn4XVIuCmgIU{K#}U8w-U|Y0 zy5|d@$@T`<>wlE>SZp;c71;0ZCe@?f2L&B2H!T)R8A_FNOBO!j?>5^zwe76d`)g{6 zB#bM?8--SOit1Dv9G2F|;rufoU~0-t&felrcChZ2{HA1#Q^yWuAh;9*#z4W7!_nUH zs|`9>1uH`Dfa%S*(tR=6dshc0LboTHsqDVN?48S+$57$(+xxb+q-#;V_r7Zthk`6# z0;4NaNeoo@ibP5*T@^fZ@#-ri(u4PX!d=M3<}$HI8X_Tfl8B^Gmu~4C)~_Q9x#9qz z5sm)$x$jraf4SVO(@CDt7BDG=i3LI@m{DAkNhF?#CdDrP*xAHmR^N+f!t8(?5hjv4@_Xb}FkDF#Z zU1491tAWi;Ed$JeNc2}lB$uR`?n`K`#@S|yY?2A-9?QRS zeADuLEy`0WM-#}&0ZP;5W}h21 zblDb;K*=piM<0$5!$LXN$*}g!j>Y1MY7~mG9B2r~^U3_WwT10vX!U-cjbEK;2khg~ zf6rlBF*31`x)aHexi=TP64oWZKGp^YH1g<6YkXbKl6`s&PBJ!>t0A!@5NrVk{+l1i zKkR+HvN5J{(bC?q0P5?6yMCQl(@hvZ;)+K+{cXXww*%Iqzn@CtznP61R?nSJNqXFT zbnMCzM?88*=JvPOgYUvho{b>7c>?zmdTKC#w10^I09*S10Ilu7!_TF@FZ8XRC=@Bp!_COXcfj>VEOrX9>GP`SLZjz(%Bn>e`n!~Gh4Ct_Rzv@ErYZTbreS% z6<#kF43bANrSa5?2s}UuE@V*ZebacB*45s_ZPz4;+VZ;=CA{cKs}aJr{OTBV&8@`q zMlWs@Br*Y^7X*Qf&;X$Er9UBFk6*+80F$4~JG{2{`zxO_{xWS}iM^M-t0KpBNAo!N z@mrjqDb)Rsm#N2MaCwiBog3I2s(!!TeJM26Qp>ph#-@Z*W8z^;OHEra&tt=~-R?DC z5mH-iKu{=25ePbtv0oaEq=juIS6eA|3mFnx$z^tiGb2TDLPn#h8HEa`k&Jv@)paeP zFhtbqQ9D!Pe*O64@=Lh>E_S5*Un#%(gLP!K+wLu;;>v9e?T?C#T)|}==@XQ4Ksgm;_=v4)q-0RA95otOsK1`~ zjn9_BxsFfMRvsWcKx5iS@*v=kn8s<=7`9eGM##|P&6RA;ilOq@SO6t46QJAa`Sv#+ z-|ga`rqn+^qlWh?{lZdVL;ExS3Uw}Bky_BKQbUhu;`K)v$5MJ4bNjA>#49$DsE&B| z<>XDdNg5iyv>seKsrMH7h@{|>J$*mbj*$D;uX1z$0Cy;9p~cfSYat~P&ovYj&?!L@ zq_fm%vP6w9sgL8?4*kj&ma#%$N*yf6hm|@Ja<@C&UrBuOJytbZWd0(5&Co5jKe*Yv z=H9^3)b6Nv92q^qj^8o09ulW*rLjwvM6k@iCq{)sQ_#mWn{6pvKN< z-LLKTtIMlsBk+|$QcG$KcxxOfT6{bOYwOhWw4`l4n%v06%MD5Z;CzS9n9eKEbK4jJ zv3KrkY|__Dk;hXCN{R~E;aDo}-JjUleVc&K(%^D6(brVdSJxv{ zQ$lE|q?w{fEx+#Qvh+LSpuoa|E1Q9VsOlMD_TCUvEpqSz%8q-E6Ef`ARZ0!q7r6tEW()1s%6Qv1`_q4){x70W_0rwJeK!cK0ph4n=T*&m za>nO7TM1E)uA$s?>iEaV3MHR!ZR+|&iy;J*)sa+DRAXePsfK8!APE$dUTXIB^YHlRy+yu^~VtfMgC?<{jSh#V@a1KZw;t2(>xEpixqMtBPlb zM{DA5V|;Miy}8%ef1iILJIi?V#Giba1r{A}JEk0n)=*!x4gI_G}%*2mm+_*rMeMEE`L9uAKkS6W(vvIUtE zO0(`xx7hif;vKf`_UaAUU5sHQmKI=xQPAHGq{|9vET9zEM{c#g+?!iA-F8!JcWBF6 zsS=>hkV7dX0!1`93_F8RfC{HM@>jWYJ&DnEy@RyywA-SauC~W-=lc7wI+gIm9wy=KG5%wpEvHMkD-e+RlaTnas>nR8>@wOlzgh0VSG+ zNh7B`g*_(WtgOmZ;&J$yGF8=CWue=&Erh}2Ca$WQwn}Zgj*eNE3x=YSV;wajGeu8M zs}lNDdk_BexrG%xV$=gIlRzjnA2vQ`6*=n_cRlI}ZmurdVz!EDBrFyX$r5T}bjFo! z5veppsnVb=O)Js&=-IlSZ+8Cx^8}~Q?pzeO{{Z7VqoVo`I|VjQrD2w{Cz)Js{KsUgvGsM( zw3973``;UYk~FGao}YEwZkVcU_tC&53>U|=Bq%fhHld1FG{r_Sr=s-c4`U{ScN=c= zzNY1QY|*sx*|f3`5QdbwWdVz@tDQB?Ly{_KSG_P@Awly8bVJmAm)pC~VbkqhpFRh0 zcCTLJc7FQGZwJ9g7HAkSE+oPb*nD-QL#9Xe`W) z;YTCKBcgv!NWey`RIZRaO4I{U)RiCgadv&AY#Y_()tQL*+#wPd)lCGF8NA6QR4qaP zz-s7T_;@0d=I_Tum8KOVuxVq7Kt_$sxV)0AT#Zq&xzcPv`hIdyO6yvK^789(Es59|?W2;~+k1C)XKD6+&aa1kY|Y~jU-z9R->#Rh zH?g44L9;O3f7yG3ZEYR99Y*=YM)@k;tGRZ4W=e)_HNSo1XlGN(e9ksxYge^}qf!|i z$f01tlt{7yjw2g_zo*vX#N2`Gua(?}l}I%@>F4GC zs`UQ=wMD*&Ga5J5fuAv>*YoP(?8C z%oVscHXsX&+=4H0dwcdjXI7>LbJkF{TQO2ks9acZc{~yH{C{7^zj@<_Tdy9nGnbhx z`j6=Z+xKh-s17c`eGTvL*z+B0%RPVp)!J!V%18>*Uf-w!#{U3OtA+u2_JW#=Ek!?= z{{U8cbp4%XRdB?vkQGM^*5>|~0l5OlkLm7(e5*f9>!OC3Kou75h??CLA$t0o(a7eJp5SZQ2SQeb?+q5SF5fc{@Q@{4-(mdK=zZ@SEM z_V~$l4q}!ncxh@IY;LEh-gScT8w$bs!1BNi9F-9eHS>ikCfcNl?6hUU=}%nZUAdq@zwf* zgN06B_r#?pb0LeZ6w8QLriDf}oob#udq)mW7_`z z>WXnd0Ag06o@i=~=RygmPHbqh%`N0n$>2yBYGu-_XbzE6Oo}?vox+1XF8BW1i+&0n z&$p;(@wuFJ6&*I|rb85lvI;eV8eP*-K~ibuuX@>sj=j+sMp0xOG^g2@EptWHt-Dxn z?pozqn!KJRAEwI0ljEfd$PGiF3@KdzRk{_u@VA|&)eNz~i*pvG8iLRz$Q`7+w`{Zq zfGZl&+p6l{^cStl)1p#VNsOsqFrc03Ol&8SB$60iq^79H&np8NwvazTvG*?}B84uZ zP|(PL*A&hwK4;Bo<<)I&9`@0$VSPZTtqp0%9B62N*ytIq#LG|{BDnDIP}BXqjaMX6 zNhGCP?W5I7s#-+ksCyH|?{8}w>fUb-2bPSqujFt#tZN}?OA-ePf0y?3>x0?S)a9}H z3F)LtYUy$GEii_vIU|yd!%oc`DQTjG7)IhF!;$nS+HKzcIIJF6n5YRMp%f;A%k${j zBxRn}oezbrK_aBo5Nl654^FJ#u9?MM1ht>&f??J8I__x!yVK`te1E%$TAIA zy8S)Rzjg;*+m!i&>{Q6NFfDjivAbXo%x5(QnCm3{w}EFo$uL?lxQ>JELtpT8HdOTu z8^j5vU1#XtFuaq?06*0?`w{Ocp|+t_E1Z7LrBP=}4puLN1_T$d~h{2O=8oUn#O2ipo&=xa@SW$1XEN)3_|kC$s4jNvuSbZ zCqr|2(j`VBGW4!a0pdWZpyFr=pujyQXJH_NSOtisa0N{&!~$prO#w6pgQ&T_uY(m7 zbyN(wTom=wVRBuU1p>8FfosiyTU;x4GD&2uK1Vp7lFxxKju{81C0z~`Bo6^%y42JXD}YB3XiA<8xgRMF))ab{I3Sgwj)YcLK~Vz7 zRSI~}R+;HymE@+!!sF8Nu(FY>(`E`J+!i>>!y^_-SA#hti)kDe&pbGsXRG*HB%ouU zCa+fcnhpSYSN)!*9-^zP`vjxKSJXq3lSLF%)ZR&}ktdFq$pG}3Jaux%35XKLM+n+j zp=6QnQnP^?YLS7{UI!sfJhcKvN6dK<(x}4?5!=SiE42aRs8*OBwKS)#J$l7IQ8=ck zuX-1XiyvCp9Q;d1B2;0s-g#--f~OZQjD!_NrV|k+FtSdjB37YvHlJ|12_;#zqxf%A zNm5f>I#*CpLZFZrP$^wl>e3|a9O*QULmZU^7~B%2Sx;~viV#4fcKlfCXz54DO18yK z1vLdH-qxicns)nYXgu>*GZQ1l9D#h2pbjEBnO91>1naw8E1cEzRjEp2i67FZ5Gqc5 z!Rq4O+^A4=g*7A446*e2`gPt%s@18Xd8lJp>jkK)mIV=gv;`2wN&_&CXaj?LmOym? z(J<1U=XahmWerzshOhEJXA(a?wqlSPx8es+%nwiV{(U4r(V9T=!8I!kd`T)HNDcAT zDIi69k}l~P)HRYrCG~PG?#aKrk&3YsuM=9-aiAV+>*>;G*0JbyG*g4=^8S57ldTaQ zY3gEDqN~!O!l{xe0+w2ZDWl0Bl|quY0b5nLBihSte$=O5Ar~(@O=8a>R$jxPLcqprF}oa)93m#kIXV`l+#kj`;?XQW2UdCi6Z|1KaI`N z#TCU$BLML~rLLfxkbRa#xZG8zidJiSolc;(g1IWg%LfFJ#Cr6sMIwH#rPL@uH6u@{ z1NKv>*lmwb1~+!pHa{0p3sF*uan%bD$gC3N;`=Pl9i%>JX@u8WlvX}i$c{}iDiU>P zyUY8tc<^OHJRnFoVlzfkf8S@~1C2mz=si*=rLEh7z8O)(4Rj1BR=EPd6*!JQT^kOp z>iDYnFI+^>#G<2d(o-cl@=4?~Vyos8q;2&P#Fh_iT0Ruc$s7LIre7ZaD(-gX#tq`@!vS?9Yw+s#VZhzkW z=YrX`kZDQ}%l<2=_-){ptYb*|e~0JS6VlYYN%n|HM$lOo(_%Qat$knb9{2PCTC6(< z%g^Q3{{VN!q%$GYULK!1eE$H!*BXACfr&+=RWY$7Isk4!Cft641&8!L+dFt_5<8B1 zZ}(yVXojc!6#jhFs{Q60J*2Cj)Rh=J8j+U0HS8efCS4~eWb5>ELxa<`yQq|GI&pa^I zUhzAshtSsgA9$hnzF6O2Uupu=j_Q_xpurt!xZmOMOFQOcyvQXt7f0Gk63HDN&fCG)=23YbE>>e3FBWTKkRg7aQ%}rZ5lkSH9VAU zPbE|2a@2K=47G-eFX8hARq?e1l(bHQz70VngvUDptKP2m4rtsgCg%%H&EeYx3-~J9 zmV0sF%48`=jzJ5lok3J@)P^(E;5#@xaMU0sUTM{p03q7t$-EK$g zhD05qL-v4*B?g&6z#7z0)bsnBx+_8r{c{nt$FD>DN@#1^iU2kZv5^&JQH z#)UVlSne5?)->+G585hpf@lM^GH@4B%{o}NR*O8+H9m5>qJpZaXSBDiFTP1(>&cba=9W78Tc_sY((mDorvvQ9BFSCl>phl0zd= zA45X2uAuEm&vubo5Zp+vkO&RK^j7Bzv$NP_ZS&`tSF;f+Z zFI5Z?fK-0zaDS({yI|QOw~Eru13a<>XCsYG316{t1$Y6`bTQp-`~KNtHF%G3i$Q=9 zTC70w8W)W!X;ad(t@!XLgoGj#{x*kHt-m%1K$5pC3#oj!B)U z=W2+lq+q(3Ixo3x@yE9_ z=AIXd3fS^=ni1NTC1{vDg=ApM?iAi6+&2C6Ti?WGmUUSzn^045g+)kWJAxXePvVTA zIOt!zY?n1)b|Z-97@Y59vP_pMkItF94IZSF)nsOx5s1cPOigl4Y7fF zc9!j%tg-o=Mk5TH)v(xlytP+eRAzBh^ks9^az|4+mb}W36cWFe$rXgP$@?w$x%;#{ zgSvBUR@h9wl0B5k;r#H*in3DC%%EbeTx2C6(~!?ww5x9%p∾^Soi4Oe?HDWxM{PbDt5djz zs14N%{N0aj&^;#Zpj_2_*;)^LPtTz~(%~-JHTWoL^B{5m053td!(T6F*fOS^E_g80s4}%ZI_XPWK~h1#^yBO9 zNG;&<d{!-Own7|wG^ zY`b3Z4b+mVOGW)O@fxfE4ge}^AI1n}I)dpS(1LxRaJI0R&2za6R3b?A65&~-x0w(U zip@gI4ixaP&v*qO8N^E2;ZzZJgz9+5Y)H)0ZblvNL%S`%U{1<=;nctrkL^ zVmWtu($`X0Mo+&@GD&A-BMsWjx{A<}v8_+@AD`LLcJ+H5?S;+cQ%2C6+5;JKhxl>h`aeUXZ%l16Z*2xQw8ZtY>I*=I0?55j^7{YKu>mnLXU zKLdY+W9QLDrQhpFNC1cypDzCZ^4E_*X5*j>OxG$d8qP1IfpNk5aDP732||EYw6E+R z@qGz)o1IdFT2#}ZmY$sqSJXvmPJw9)5i$%zy2_ z!}@=%#~$_^k%69<2mQTcW%^t3z!v-;_Vzy9Ru}|v>A>82IG+zQ8%u8PYP{ECU}Mhp zz8imZes{5{+aZ+2J#SxOdlHW!zP8kP8d{mL)DrG}r43~~bra*OXNEuxJ45@TK{qPN zG+Vq=z!b|Gxf-x5ppaOM&>Wr|Jcmhl1&UY}8H;Fhri0H>02+LW90>V?(x2u2&dlQe zZ2YdH-CIvR*HJ%tZ_U?^+Ix!_xSakculK%kt9NyDGsN$&Z#P zqGp7lA!}%+v$BF2SUu2Dt2NZ*Ri3_ui8b@CI=20BTb~jTN;P!UP*4-c(@3R9*g7nE z>R=(Os1QX>LljczrwWpIpwd8Bk=Im^HmHJg7y?rLQ@AOe5M zPO)8HN+RnRuk7;e6Lzh8UOH4c?`JZiw^r=;fbjw3eA zR$n9#Etw zTgwr;vU1g9@%ioRxnQ6aSh*&WzK%z#7}mjLL=oY#70}j51ds*~8jW_*WA6!f8z?tj zs$HqeQe>tvLti840OQtRZ2PKh`-Pt1(H2O`nh<=Jna`>9^y#Cpc7D{{o5L%T&F)>- zx3bREvDV@D1{V~WT1JkZ5{9Ij`f!4xosvlIgH&t{$RPWs%V}@1ZLn>yK+O^oMG5mH zpDgE(OSi6R{pWox{MOF0Fau2}Xa+HydS~a;RwJWuTaOKt&TahO^3Tv=vMG(JrN?c2 zOu2bvm&R776NY@~%4TUJX%tFm;hCb;8P!wO?D1xa^cRGzj0p>`y8@@nAL{ez5^ifE zJ1kwRLUZbA^7G^A#N()2o2NFm(Zo?@Gh2ss`D&|81o&D_sRWs<6+y?-Wa5u=QA?1G zF!R*GREr!kKbXF+PL(I$nsiA_UJ)jh!whDWtuy?(Q61@$KNSF_X~#AH09Wnu=@$5Y ztcXTma_@SFmt161?Ob1uo}ma;j;)(5=?(bO8sDFO69cF$Cj{qL59R*=7uAKw5CEt? zy+>#|u?$Lc8|}`gh`f7y4AkR8>0p1{sF6wfn*s>;UlONM#ZmV9eqCS2)uhx?na`h5 z*!3msxo!UdsBi(>*fP9vsZa56!ATba-$UV4``@zj)KS&7HcM~ha75#DY%d@ci^Q*Sz>+9T4U148i?w#J-cer=1)b0KES+;jpW1+Be(v;qnI}FfM zKITX&sq3*=n#8G%Wltbj3*D>sj@M|~PlyucQcjgRSVV=0k;MY3tu(bm)`V7_WroQM z!?RxB+E7VrXrVGYDgx`L5ZX!b*nT_%$DqR#gV8lKaG(e-G#)rx58G?l=_0^;gT_c= z;8WM<&>DM#Ni}4VkM(@|8g`{dM+=athaX*p#jf((SLK%hBZP!xR?lzZJ?nKc@8ltuBV0aEWrYJ|KBOM%aEVmPH z?_{~Ro*5QVUedIvua*x3$A||ermt<*Wb)Z=v&d#L+0DmUPt;p43m#i>R?S_NN-RQE zQcz=#LR^kQrzJ;pg98m?fHStstHCV+6K+4lK$Z2tflw$68W{B`RJeV@>sQSw)QZM}o@ z`*iHSsqRj_qwOpvLwHhl4^2{Sd9Yh5uXb#;t=#Wf_Yj%ktQ8cLf4vr&5m*|dI&4L4 zCx$!5fGmC?gewQUkUHv^gI%ykA|D?;*6jII(vBAEp2X|D|=+Mwqqp80;h&xS8YNkk6Vc3qjw-;6x0AI zK|kTW5UBaT@xoSxj;_X}I+(H|m~nX~`hW$~P5Jgy7%OFZt=fDEKjWu|_&N)2Wxj?a zRym$8On##J{{X1s=&vX*xN^P)#q_I4gC8Kr+h`YvinhCpL#AQ5`teY z7jIC{~7cjTkvzfdM6k1+isoB z@eAe-@uljXsP1a~Cdt}ctF1eeC4-{O?H8uN?OgS4^UQUw`--I#BZ}PEs(S6OQ6!&f zTS1hcU74T_=JUWgwjECRE8zk`Qpk34LItNz_tXaWgsz6{sU{?GEHu{b~ z*!vio06*3C^)rn;K;zc}Y}$ZJ0t4}=aBOuF11LB8@z1+Zig})`n%2E@Dm4!nEQQU% zZbuieC+q&V_Z=Dt3YTlJvw{sJ*W>Shnt0`bjub?R;D+MH9@;;u^ z$g5IM5A|gAQ&U9;1N~pfbwz*9+v6QaarF@1JAWSad&6PEn~Mmr!mU$T1s=cRxPZVH z(~+ViA;0TY%-ym8NUQsye!$Bxw$s(*ovNq zDNT_kSrY+|ru0%G+(gzFI%R|?Rno-w z$E9@uubC~iJx)PY;9@>wv9RU~9iy2hP>4ja$rZY+at0=!OsM7BiHYG*!p?|R2bM}o7YWK;d0F|ZBe^0vXf)%W3zKE;kUid zgx)+2rL;Kh3sbE8j|ve&0O+aQ5gkQ%WB`MNpivId4H(vK(b(0SuI<+3Ye#Al5QYGe zniE4nIDyseIj(qaE#TZNDDK4-jyqKRRILDSE+?g|5^p*va5S)N&7}=4(=~N9`B-yX zjORDjN}5xrBO6rFHZGQ*A4nAlrh#LXBM&1qjl=uB&fB}$+3lr3g<;WEN=U`ln&*>I z)N6$SS4hFtK)~_&#@;2jw*Ab}%>&3@O>SQ0l++amwl!6v_AMDkwk3~3#?kpH-1`n4 z!H~dh?zWE+x+bK{wI*ttD_tVhV;~s$s%R%a!|Ez1Y87;=<$E@3)-M%)Z%e zw;L}jZ%U9z=w%!#>~Vb@@+_2fkbqHi zF%B6Sl=;?*A0IB3E%O(?XVpy(+v;Dr5dGrAQHsvQ^%QZt3Yn1(SRGLR0Gwqk3PPog z@9sr!e!awB4^Hc1BWeOh-lmPj49QWe03H>_Iu?(-rTnh8*8IN&*E(5%5zCQE)`D7< zUpi8h$)^uN^E0_CQk{RgJxG$tSxZWkZ$Y^lw8Kk3Kw!T{+PXly{YgRX6&n zx%CY?l*Tii#vZo6jreRnn0%!{~7AeHEZA=KK9GD6g~ z0I8=6nspuTUhJLGHyP!#L=(>MKnbHcXQJetAo}KmrJnTMySF=2k<3tRjit6Qb=3GQ z1X%1w@=D4oS*S3v_|>JzA<0bD6x7W-&fq4d&|RDALAPv{_VGt+`|eq;)mfRE5~b9; zQwns{6Q+a6R)BO(d(TkrXX>EZg}tkY(PNE^s9?3AXYXRlrHMQZMNde~b8h;0@rw@H zqLPCrS5rX{8T@r5mAR*B3r)8_TcN9Bd(Tc+HCf-mt|twlA5azos(x|>n4jQwb3bM zhN_;DYI!2dy=_Gebg3OR4NPzC_d6}j2^`SIf;8_$BuC;6Z6wuYF0~;9Q3E0@W=LOJ z>28c|eaq!}gcjx-ly+1^3bFV>>U?6du@WgoDq&p=vX^+BkSaNYmhG{T%~WKEPem1U z)KwHxmEI8j>(Ruk40M}>H9WCyy1XT77zI@RI-G?FfK1||k}27Xxg@=4=VvK(ts^3!)OOUfE|Mx6;uS05=iR2_IW7|0O|mE^vK)c{?xNKR zU{<2F!(h}DoSTPptJK1J(3(g@>eL{0>iF`!Lyv%yyLUSbtKc7G$Iv1KpIPN)Ybe{Bypt;IQ2JeSLA5sk?OWi@W#UM#ZgHeHa?Ph zp{9xyuUgasy?*A2X&ofgtTZXqqQ~9Z1o~;M;@n_qnoo^e;WZ;j#dT@~X*3-?oaM1c zDow6I5%@p=_UYBA)rV*u)fF_z9SO<3t01SB?fUz9P*mnAXqKZJirUF8KeVXjtDo#E zg8u*$s(P%}sSKK8R5P$K5J4cPwq}6~ChHMt30a1q6ofi}m{3uYtWcb-NF<{X(f9T9 zVv0L|0y}{B3JR}=7*4K#OvW`5Sr~W=MUDx~l+zVr)>SH?lkA(4F0MHP+?#H2hv{yiw}HS7DOF}@%w-vZ zk`CKQIV`WSYznu-k?)8bzI3>Wrm$6Axjj~as}={_m*$>lI8g0S8htV zBULo5^}9C;@bLJ7k}Jchu0Om_BbQMg%eoPzi6Gk*RR>O{B76X8Q%ZtqO5>-f{#*6b zm1#vESazLbIXYVv4%f(pC7EI~UoT8yf@K#j)>Rzd*Ru`xndO}*>B$?255rZ}s^ppg zNuc!2X+!coD}&$eM4f<3ZNSM&&@2poL;G>Z*N4y2e4i-#_MSv(dgHVsf>e1@pi^xb zbSlWvx;n?XS%_H>fJMVt*#7`jtM{nnw`n09ox66iQ%P+Yh8U$hKnSQbVA%u^Dbl%p z@#M&rUVXoESXft9hzO_HE(ykXRAA8buG@b!dS-?>qRDmlb3;d_!oEGVwyG)SXxT+t zM@~0PRSc`BX>ba=5Cy%jPrTPBu!=Y3E!ZmoT0NT(N#Iw0y2 z+*S<%gZ(-X2jUbH>Zsr-2sP;=@~^)3PiO6(nW)%%6S4928*+W$kk2;d+BnP<*%-4F zczR4slvOl&TGy_qrv4u)%qNiyLC`2X`+&ai9_RAkySooB>>Rsqb!|4^bu^N-$AjV4 zMO0No1hSSRNi0YLnrT`ZA?D9|y}y0GWP2%Z4J4JDR0@n$l~hyp4x?3}8oO(rfZSg0 z$3sn3E8}-WHT9C>>Y=U}37TpcBBqQ@s;A5nAqzPgf*(@cYQMZ^kC*4SfLnb^9So;Z zFbrH&0HpbO`i`+?@0@m7ZtrIcI7V?GV;I6#rl(P+isS%zV4jwHSA9`!{VhH>d7YJ= zpB;zn7&g^p7`?@lp<07eklgzZDY@x?fubno_1$($JZa;I* z!W*#*1(rz5YI$uQMbIwe3s|F-ddHWnZXf5>(4&kk;#%#*!y8K=@H(gZwx+)sY zrJCK?I<Ro zv?N078`?Y-mJ5U+r0$7v5W@$TRm6U&Ct(Mc_ zuquPjvQQQ}lD(Ys<1mYXpoUC#PO7$}D+VH1VL5fgR>w0`i6W_HpB?v=v7|7&%^TId zl!IeoCn?xnUtjo=ylro%CZG*q_Nn|e0FzA6P@W>H=CYmbMT$c3T(sUIqk-ZyP8(BD zQeyVZ2+3Zcw5u#8NZFONt~~P&*EZ?5UJEa$R<%Z% zMwV;FhaXajf{bHv;-q4X=fQ$;qZUJd& znvFqtFtfILQ>Pm#x-FdR7c zLAGCwy@R|<0s|W(g4&6tRDoSV!J(~dNw}L@lsJWDI&;{2NFiYg-?pBBMbuQ9SV{`L2sN-V&i9nD~@b$Zr}`6f5-Az zYPO)?*=Sl-`-yUR%$$OcF_oi98DW}F9bIux+~n)_zT=p!rrox!$9}v+eCiS9BA-;M zdz#?niMZ&Q!7c*$%xF(XmlwB^h??rXD^S z0}PJX+i2aQwwGf|c~y%)iyD~Sq99Qvi{M#eD!}++jjFns0D5~?%wF!-Z}6V;wY)_v zx}z)bG)>x)!oY{o@e){)2t85PU}R}gt7z%#Qm!ScjU%XsUy8CCd1Pc{jlpHQur0|U zxWBn)W3^?KBr0eXh_4Y`56|V%_SbG=ok>50(BpygKQrmjZ?$)3Cuwgg-PM}KWiuF< zv2`>PE)nS>uc2&-r%3DLO4o*(p;2IEXr4&RYPeuWGF_I@F7L72SwkwLtcb+Dbea~y zBBWQ1Xn1hwYaP6IHV|7Gv`83a)QXQIO#Pi&$5?#L>F$=I>t4Cs_#Afd#Bbf_QMWtq zZf}?~TW-ImI@Ag%+cj|Rj7DDpxZY)=g03+&3K>MBTwtu&c~gDcMf4Lg z!6mbqfmQK5TJTu=mo!>cl=l#&Xlf5Ou2;FSx4n~amEphfRiM#Rtl-x=O45|!QcWp> zIzPS9^TVfWzB~MD>tBqY%*z$A^IsTypLg#z`3Kw?y~o>q&5VyRg54WWXY8GfwUJM< zJ5O(IzPrv0W+JaSfqm76p~OHbWeMk!q-Sfs?o!xo$T@3vw2@K7q^px7$jn?U{wbCy ziWLD_RK!9?ghYW%uX)V7(rmVo+U%^`tO`6qDL}MJqB;fF;wy1yZ8_E{QX8W2use6* zM_TnwcS-dxe&Dx$dntt98{W3BajyEx_8)F;oV7ddUG>^~=WypXt}>T#?hVC5NcD47 znUM}Yjbepu0AFOAggf@KUiMT4!Rx#czH~q%$>vr5} zBfC}D5K$;FlmzKS9iS3gwP!5Fn8({2uc>*HXT{1jycuAGTmcw-0Hn^p-Hs4V_ z)5jo@12jS?gZ5Mqva>qSj^qnaMnNHc$6&D9H!a6{*<;+ct83JPNc=~I(p?PSrcuzz z+I%?%r3gtC)CdCyW%ZZEjps`a#UDs zQer7~=3lJowzg5B+gK@}#?@o;V{HgwNTQxJh{f#6VRN>$TSQxa-XMz9%-U_P>cF6p z$dosN%C6LDS%Ik}jbsjl_M2BM-dkAi*8Ht$8c%Lzh9;ijUqC}9jb0XplTUH)XDq<8 zxFq#gb(^=N{{Y!vpL0#|T7mXk{FkbxJ2F3#J-11a8Hedpl8-wU?fxAuLsH`x?F|Hw zJuxb?DOYDc-}<8-)oXJ#oCdSa`e4WxP>wTDb!)Diai9ysB=t*8=VE<@t`}@8WG+=S zX;z^+m+EEPNew%0GiBg9kI8&lW}!sALkFqbnN_a zso7Y~+g*o;Y~{8FHoN=dwzl5krx_|Kb>Sp{HEkV4v4wK=@-?l~#^T6N1Ws91E{Py% zHCAF2C0Gqww6k`Bo`hER`&@86^p;k_S$6c1Rpdb;#LiA3(yHve+S~&8pgLBdg?2VS zqNeDqe`n%;JmhxPLn+&vgQ~vX50G2;aAW9c@S7JCy&%a`{{R}mFsrStY{80Hol-Q8 z0LaA1RyJo~qT5U{#?PqK85@BBVcg>(q(3?#$s!v#p7QyCKWg4M<1M)hBzUskzt}3Cuy1}XI)HLRE|`U z^)_81DL+k1sP!QJUR3$?wT%~2j@~>63RZ;r)2B?GH(oBt$L_j*zRkrwUg*m0x|%fX z3dyO2SgbZbCM%L@Fs4IYP}vU|iosP=Rn7RKzMl{D*Gua2IMPS?`24P1u$)GEsx zAkf0#vJl196nO;(KgfC$M9Q&>3>5@^eFbu2B3ekQ{Bx9&d7;zfUOY;y)?$_?)IZkt z;iXjR8UFwXK7BeS6b88A)=BpFfJz)Mk{HC2LMqVCfU32c6B@W7Tpz~<{_jN^sY)*% zKbKB;rAB%-pBOsomvU_0=gF6MtE5eXiKf9K<0h}kQRcFln6g!r%T)*QAF{^1H8`j= z(yE`hMVVL>AZ^GpSwX*BJ=BP#hoED`g|GN%IuG+D+{?GGf`zL7Rj(BThvs;22ZvWz z@xSKR!`=7On@8iX^K1A)y*^#-u9)js`iJ9R$_|ar<91KWK8Wglw=|SnC#EW=sNMZj zj^BF|t+SQ2a_#D@p5T<@4MdbR7|etd$bG%ce7=!=LFMhr%HqOVgZOefEYY#lC?<4f zXsR%!>r<6|I=VgDxsJl_$symZY_Z|=n>USPMZIfSjjZe7W-_Bfu0wP`WCb_b596;)A;rJEo{ zOiYUs#!~Ivv?ee|KJ#Z}7y$C4nPvb3;xrnxq*6Ef9E`G`tO5K%az|}QEzoVYXuBFL&QE$a*~)LN!MS6usjSZBDeH0-HFZ_<`SLka zEeN-oMgC#gtwtC_WMlW#I$=dlDGc)B>o9$}a^4OVa>049O z2AZ{`GJvO1AT6!H1?@Yr5ukW7tNBxf8c=lSQ;p%**TTRUcEGs#n! z-C0lWJ!L?t++BISdb@E_If{B(b;xaM{C#58)FZu8E4GNGgxzIW*;z$nmN_G7Ok+s$ zH4Vgy5O^B&<;$(4vPJa@;V@YkGLz&%Q<1`;WM|Ky*Rn9(e?iyuncOX3YfF{hnT(24 zR%faIPT(o{g@t>j6;B?w~RDY~}s){*#ip*gK-PNi4vjE*W=ihB4ZhFVrdoA;?_OUS74_@$e7KqDvf{{Syf`+pHZ9MrSrYBDtR(+MOpQc}TDI7B*iM;x-EvHIK-?&zov zrU!@ldO>{ZP!%JGpH>Ceoo6o2r_N=nC_4%vxVphISemS+3vENUayXpe$7S(#)cIU) z;K)@>)6gM*0EJ{i8D$9QQ`nQ0-X-QuwN|=>rA|Si^glfMbPDDe$L^++yHH(XgUG3& zHT)!ccUGQN>20-l-ZO4(tbPX}h09G@O<7k^)pW^DVU`-He6fg@S!0k%pz^jqOW&V) zNo{d0vY7k=V*`(;%l7>GfVX{?UE6Sb=x^afXw`JJY6^;10Mrxt^s*Q zkvN+~{wha~c){_38ES=JB017Qu?OALbdZ9LX5J^52R$GhpL!I5xZ0YE3hLqqo-x-) zw|0vIO1RC+jPn8nuu(RKzNJXp??);{h(6RNyFl;>>rLfDkFLb-?X_C*{{R=kWO236CO&B$wLK`6 z)*~vSNWwOIggK{W9L2WDZy4~et5}|u(&K>0BRnz~4~VIt9Zg)LyGdr2R=caC(KJd@ zq!r)@#YqB-4QeZ%~7t9#?(hhBA`a^b1> z1shi4@w=~N?|+jU9^Y2NKGqenpl zS=r2KR@0;Om`n%?RzzkbF$5t5buY!sTb=AlbGGhw(nNrg>0~EWSu5Db#f+(_p)EtG zFbl!DqaT?a&GFi%x^BDaex~?!mB!$(mH1tu*gqe7cX0Iv>xQ!m`68+%TLm04XUhM*Px5u zY;*0qZPw*?WY%&zfRpWJ>5DUIBU;M3gAxQ|!e#(5B!j1`OUu#x4(pAPmF$iA@UU&J zs@w4Y0C_V#r@B9se|KT_CKqL8DRI@*nd;8Ke~=BgWW?0c<|$s1K`fHYDiI=ym-@U) z1ZprLjEqWYBSVz{a0^^?7w<0B{!Ti#fxZ3=@dzZ04mw#^VS@vEgAhjNB=6Z{N zW2-89!l7rTIDF}brmjk72{KPKGEC;J6}_x7o!4o;`sjdHD%OQGnhxIcR<0fuu7W$X zigg^z>}JJit#@zDTY%dZ0dOWeWQv+}l8(*d{sjTE`l`90#dZ4bt)tM}1LZz)ldir) z!`U5K2HC^q_P=dz9*y7q3ys|yvPuZXkd~DPT_31o~Lth+jf|X=vM+`;9 z@9e#sR1<=yS&79Be}%li!O|_j>a~F;T`q26rA0I1DHZe;9d6n2$K*EZ+qj**@!NPu zn8VXlZc{_m8}dH4m$Gp*uxF&mJwDCsZL1sOvsjq+?&GSB@VUxKWTTpjK~G*O4IkXr zs^wl{hS&T@bCmrs6-hO$VI!}@E45Wr9@yNCI%us%P+nW)9%{D{TXN0)%B9bUR^8kZ zk5=u0^w1+IG)HoXQB*UDDXyD8m}WcWZ_VEK>8=3(KLEg??VOJIlj6_BuaVgP_0R7< z!Rg(((Oajm`=4ddZcV$_n9i};7|izI-0*dlCW|*&InC!?X33hy(F9SYJd=rcefw%# zcfQ-K+9Tn#QN-5?aO~|(Q%vzBamEsaBx|jh@guk^p5b$J=?3-6c2Q8Xgq~p;jUzw^ zA~P|PNrcGdRnR17P?J~bsB^dR{;w@l^Bb#al8(B3M0EL_wR1s9RP?k`RP9a095wZF zLXssdII0oGC6tJ@I;O2m0SR(?m$<$$sqi93ub`+33G}Hn9;c$uZVM!l!yISn&Bm$# zXuY`nhpETUtE<$?x`n_eg#%G*eRU9Ts2|7U*yoNqoBHN~)P|GRtU(vLm2biN-%YR2 zKJ`je0Zz6t_I1&4FJ*Eya8DWuCie?#f< znXJTfV;dfA?@fvjai81%ujkgQO!b-~%5;%%r&5qXxaQ;%0XF(u+hpJ<;5wx$YfSw5 zaDr2)f_QQJWy!EB$QnhoANBpwhYwDwMJrz{^n>mFnM1v{W#HAK+04*0O0FT zKB|A$`u_m2_JU=oWgqJKbkxWs6ekD#ALr{wALb454=2&xgPz@(JUo(h*5IwHsLW7D z1I-2!uD)r$>QN4jD}}DqOW%m(Vh8|>L|oa+t!+E*)+?tVoi!R;j=!*;C&>J|i+PJ@ zdwH7b*+^4T#Bc_03W+cbIlIu#N+7p*G=yHt#{kO*t=sN zSq*j*sCPc)tZJ#Tot3qj5BE1U;}0YeEma}{{V5lzO~q;-ubg`ux8}@($a1= z@r+qcNM^f^B@`BNxbY^_U!=NYK9OxBwZ1*`mcezjO?AzCOhxv#ALF*`LE()+{Y-tQ z!&1~G;~JopvlTY-%!byo+lv8}t{G|?8ikf;ti}zcT}e^5_Xa+pXD>~Z$56ppQB91g zrkX!JP7QJe@wM8gpqiqdL{!I4X63+;&vUijfW9>lNQp@hsRi4^Ef|r|g^^X68;EA( z)I+*k*~xo0@3+;VaiwE!$psFmwTvY!e~O%uFsp#yyOZiZT>IIY7un=4NR zEky1Sqsam0}4A$G_W(W%`B*0q;Vo3I>8{?_UnkEhD)1Dt+P=RgAi$2e7weJ zXhE+)O~TKDZ6~mcQVe9BL6nw2)W}*@i*W}? z$mt}O2?p8q_80R!28vLH4771c8Ff&93Wci^+-Qdp7bI$G%{a(N(8o-*HEpNC5;5@_ z>Dki4?Thfy)DoMT`jyj4NcE)I~Dj6~-XJw{na?1@hMFmt5~L`)O}bgO?;J{&(ajwC=*+0$#6H|}D1j{U8r%CB&U)ww~5Vs%;`#GOr-Jqb7&-5mUva5NloJ|SJus(Ic`SdZ5 zllh7^f@v&L2da=nlDnRE;lFsg` z`STeXYAx%W&ZRv~f1e*m1hP`C8hyPjQ{$;=Y4+UMyi8WBhM81FEKJ_ANho5pTO^ln z+ht{r1+Nnz##|jlv+2oGQgqYHpmy`-Sr*-sdPsnZ$9%84@t6x*=4KHdxoa zV^tcIu?$Hi>o1Jz%%&k83KrVgC~4zLdN^jR&*N*Rghq1jNmUiA0mykTOx`xt;$X!| z1ca@w`HJ6hfX?E5wo=E$S|JoargZSq2Wtw{5;*l_wc0l;H~M9JYlTEA3D%FMo+}69 zy0um?MNWdeNF^6j)f9P}>XyS+U?r!gTx=!gtrXbmda8)TkcO}Od(`V7hG$fP>n3`xr#(?H1YHU*@d?0EU~S%wzr-@ zX+{NTYRAv`MNLTQ0D}7N^3KXTW_yVU5rVX8XSf4OfkQ*UQ>KXaT`g`pt~hCN)h3f8 zR?yTXOsSEnjM&RWk~0XJ8gm$t4wWv&u1F`^_vV2VHqbO-VFH@8lFkhXsq&`)C@IAB zo;k#}GFq$0@>> z#8XKuquVEaa`yKYG3!w&R*T`1M{op6q|gmcbe&#g4_=k++iPw!Cf^h?&3|(|X%fJO zMlN4LRgD8lD@X_kk*Q)*eKG(emL2Q9vqAKO+lxq74@O5za($6 z^9Jj&M`p9nX)c%0CODUUvfHoTR% zz}FGJ!y+pq0KO_zVt|uef##=)HO(kYuT;|Yr*3VXn!6V%hH8qeNZhGzUw=;Nb zKIP5U)zfV=xNtB+Hy*{rWne85{{Rx9YFDX_DMaEYcR)tNp%b;bi9=)9HVD(w;OBAw(usnx|KeY#d%#IASS1ZHeSgU zl!cH)`jsXJp=&wR%hH>ha^bfv8C2W3z2A=6Td(+1WAVG1pJwDgySeP8btXmfwGl~K zkd;E?#9!pIyGGJTp(SVepZBX-ZC9cfi)_Evs!J(%@FZB|BSSGqj#|Yox+^l17NiyE zGrQ~;9@}$H{{Xb^P-5Ed<{LYwi%d6dW<+-qcy3-qt2+Mxi#nE#&X#9g4#4!?dqgFm zpr&Z5=_;rxGSw2jacWxU5zj0UIIf8;lBI=;mUSeL(!_gca|5H@O7fW59H5|~QBX+0 z!m;27?C2l#VG`aYVI*D>F*R(lu9c$->QV6%jNtL=FxjD?rkScj(V1#vSt@HO#YHr9 z(3FCLD5Cw}wRnz%m9G?tG}wJT-8Z;bS&XoqnP{L_iK%`ZD^uo29+{HeDuw4!6&kva zny>b2P9m5Gff)4Z**1lIZIG+~04Rv#v2hw?qIl_{hB%6)EnOtY0!>lIy>XD`jlnJL zx81Cq!)%u!m6(?&%#)R^GxG<_96C^hyCktV){y}aO0JzG=_-7PH6tObT4$!*cE;RU zVTs4$=_SlhxvH>O&Ap7Hl2&}aR=%`jakOtr@-w$++I z*J3$i*Qk+|Tpe66ppNg$k4bGKmhf8b)^_bZ-Q@5?1WQuW&ohXjjTiB|$m)>~H*f*Z zPdTldy0BS1zB@6Gt-)pX?Led4n5?J!j;O;{Q!~Le4D^0z<@>0mh2W}Kne<9DwX9FQ zO4gRL+*)5;k#Q8S8!Z7oBC!s*#ZZcI`E>T>V}G`8SJoSaqucIwcbkb)jCGuC}#BEDajeAv2E6QQ>QH6nQaKNB3CQT!X!q1f+tkMKt)zxhi1~PZZHNibnzmQr}T; zblhw%t{@WImXZkMG$^5!h{4SbLvaLWf$8pFv)oywW42Exiy4iXBX$G^?eNO+Ac`$} zO-RV6Pt^OX2~|f=;K@8tRMrX%b0th>=_8&HLi5CA9XFjwk#b46f|&o;Z|kwvo6WhADKmRLqRDOC}I8j4wFrxI97BWAy~8#T&J0J@q2!6gBi2y`{= zWnv9OrV9*FPo8=W?mJ4kk`XkqXsXg+$nnLksLr}h8NrM?5~02@hoK8_V>cFaZ*6VC zh@r;E9MtqRD-CsiQjsR46+qVIp{1P5;($#Em2|LKi)tJYzRGVS+pIV1t3+92g5@G(gHoV#*y0cS?$C6+r-u_xxN49U;v=>ZG44 zYbmjRX+?@TqQ7;Q9!zYR1u{JtYGdV|t>09NE{kR=)*jZ|$F*ETY*FP&-hT`N2ga&$ z)HnbRK7VgPSGK*jUCFLI7Pd=cHlF$zwfBYXsV(@a+9*hDbi0!yk;u?f#gfP3CZ>j= za@3}5y!A4JBr%qyRZ$wup(8qyLZmPp*!x2~$rk4fkzBN_6_$ixRMeXJRjEpvQ=@xr z!Z)yr-e@8gq1IHZl2=e2n4qOAP~RicK75sCM=yZJCN^5QGgSi_j--Z$DmogGS16*O zjwu*fEJ<-=2d5ryfp_?GN>dyRJM1lvK3n|HG{^~=cr_p1(7(+ zoKxiSRk-=psxZ{K8f)R}mWrhw8i8g4Z9~XYL1ayPCi4>AZTpL@z6z4Pu9|yYwNZvX zA1V+)sp#JN9nX_5XXWktZi)A6H*0ycN*SSO&wLutv`%7h%Oy1pbphFEOMX*)B4XDt z^_exw?E{kSicm48gN6z_y*f{HXU9GJ@_Vz>Y{iky zQ{rHrD&60{>*kjuNwaoUHB^iiCz?qTvptn2WWu8^x{B#dOo1Vcx4e}0TiVIJ%iY$| zV{1-I+sZ!Ua}WW)Q@C0{NYZaE)pUR=ZQ#{#*i=^+au2o}@46hwd3GzAcGvl4n0yK;uj4#8u~8%El;`yG|CL2nB1jyT2uW0LH{#F5D@B&D5=SoNrO^u%vo zpx<%R{pDuc-g`4SMV#9?q*JO4jwZ2dF!{PW*i=BZ6zi@sbh>Me#fcvA({tFCGk3IZ zmSRg;Vrb-3!Q*gMfId|R2a2^15!3;DvUpE(w_n<7fsm`I#!St0I@X!11&QVedTz$;<8>{o3i zr0)&&s1huyp;qG9lbY9pl?gZi>2MfnpgkEJrUxINXt#dbim!9j|aDAa`LNZ#=uZZ&BQCdliS&%CY#jF05Ik z(hEG%Bay0i1zK362DD=oMT>Mryz=;Wi+tGOdD>`MnIO^txIko>PZ|OvnPFvfX&Q!T z^xQ&TCSn2x+<5G69!j|DD=PBv&6bb+*fC^8e)df&Wg;17u&o%{woEfp+) z)tCtZ0=ieZjmbS71qS7%!DaUD-`te7b@*h?O$@mcjG&NH)=*_XhtxYQOG*RjMwMQf zH)uX`E#Un=zG_tgG z<_Ia^D=~@=Y}TLlP3`O~2vEl(8F#EwchlPgkm z;{!RZcvl{MSH|1h{{Y1HM`>gY8ArxJv09mHd5Uq6&sEd9i2}Jm6>h}-r22cxo>Kv~ z{q2LPktDYi`4*5GpDrKB^&-!A9CpRlU`Q1-$sNFbo_@U>9qY8Zvvc&e>e>4TUwiPZ2a!vxhcCJKa1KBWTL0qIi0ghUqweuu+n5= zXjv;DlI~+B&_fla+)DsM{xC#j#@t;}fJz-AVl_>m652?u@yM^5~lB zgCFWHZO6T+uFl1eckcoK_5T1CQ~NW}ZLc5tzcuAQP+UZxEQyco?fs*xcj%9gSe%FQ z{>$XC8!zN;@~_+dak#seHgWiVm!;g4HP1s+TebFf=GztBmYs*Zf0xB-V=H$=-)WAe z-34*an5K$MX{x1}UHVG4R@RZMit)s`O$I>*7JV+MeKMZ0N)i$FI&Y#zChqqCUK^5pCqJtxr_yv~S8OoXRnJl045TLHA z&DDCL$k#W;3j3l|1xWthmYGpvg+j$o2vv;~9!f6}A=);f3I&hru4(9hLLNS3{PKS; zpj-R7=k~ViMFc~3w@?SdfJJb`3}ZTc>P0;%(fy^wr!#=)oz>s@ zOlH7~qUcV|r`(AxX4u-h{)=?>H~0SlJ^a7-CQBbvoP!UF#zDBwKAL=-N#T$|?8|f8 zmQ9{LzSbg<+K45RIj+hO@2YU#0;m!Yr&2*70U;^cWHstwbQqB9jZBPYG-N7F}(u;|vIPn$eCuUuFCO~PdU&n!vYLCGF+wu0QdZ?aqW%5P@!8r1;e&NdowV7C9b8L<*>txxVPY_*1pq zygzckGCKyHY00}7qUdd!&nW(}c?yHaq+6bSlU$Ha+-hs4LHz5|J(20jMql}UVgCRb zhtJFol5|*Yjg{%G>9<7PwLbgW-9bg!n2ew(e#nJEmyNJte{>#T_GxR%;E3j#? zS=xuhOM{kN?k=V{WSbdNj+&wAPN#KSMYlw1#-P=h15=s>;?&P>3a)&zD2u_K!bM>t zPv8P6K}s?Y;^D`QYAc1PC==vxh`%3p)>ar161%szl^H@0f###w`)X3!w6TcDvig(~ z0q6WZ)=GGGXV=9400{p8H${+2=WIzeANMCsKEz-1^z*-VCJs)nlBTme+6|t^><5Kt4&ji-&xAN*^18X&9{i9s71nNv9$S^<`H;nDI^0_RVS*XK^XFS5CqzH~=%kybfvs_-Z;Tm6(wh(8Ns9g%f7; zVP%jq#@-5Q8?Tbu3ZQ>i^uPG~dBX_dKWYABq>DN5=s0Sx^5{_9doD4wtI;XD1m!l~ z8wZoi`+p4D7+wZEd75O;m zc5J&gXg8KKbyP&XuM=*l`wwm923HkKFj)$Gb#5A_QuNi$PgeAjJJ%v3Y@jLDvQnCb z0H76Q_^KFy8-{f8=^pJZY_26nkjRZ0r~s%9uAz>qsU!lJU_dz($a%T(C;b!k{Y>py zQ4N0N?4*(umA`2yPTPr+Akw1iWSEs(u98n9QMx&iJR2U&Qcy>)c;WNtE^bJ%NgccV zW~FOPD$xCdg+JNo*LJ4W-gEVLXZ9Xywv#<9Z`2riz2~*pc4D_J7An4v3l7H5_AP(# zjlYh}R(2g6QeyI0`nr00tUYxFGl40WSG(S-g(7K5XPK%!Xhk)7oYb{NHJlQ72`=8? z*xgR5Br(MZ)B^&Gr?JieC4eeJ9Yac;GzO((c2(!9I38vwUH>m)Gv8*ykw2Z?|<{-ELI{?9~jxZM3cjIA*w zI|`pIAvBMe1J|Q-+gmHPzuA1<-JiQEskaW^n|Jj#-NE)g-rW0^UBg9JU4(|OZ4KOL zCCAfGxpxi+A3YZ4qR&#tS&zxnQ%wMAT+Gkjs*PyZ3hUyNMe=SGVta@j50H8a^dr1W zwA=4D35vXWVNlfW%6wSjXehymBS`HvBcidm>o-I_S=F^ia_=CyioVyTt$c3d%O!1X zEgs>)$0RPtBLdGdEQG?Y;X{5`pKZw$LJh2#`&A{aIMc-y13%^j(!B@dzq*dv)@7EO zowGsY7vjOF&kWb+(AU^IB8PVMzjXE<+TI;8zF_OE&(<`X?{RfnRc-v-)SJQayKk=Z zIr@Fsw{~W0e?hwH7GL9WP|`_|z~|!A#eb>89JTDMBiptacB?^#oK;frGfl*Vd zUjfIX-NM!7w7;GkxaW=pjFwVVGLXIMB+^(G)~%#eI28b}UW@MMz$`su)m7{X8A|@q z66lOGK)B4_8l8e2NFCW^)&VMSV0h==rBmS9fDKAHKl6}^51&E1iAvd6%1^}7epJ)Z z!tGv<-1xqO-2JZzOb`!tqC*{SNM)B+lc)kUd6C}A!vWI$J5}M4KKC)(6Gk2Z0sSK;FZj>Fv3jO2SAW>Rf%T{;G7ITdgrbNvG1zyIz_MFsqUs zp+P*9*og75VCv%jFPg{rOUIw8ql;V>&}9oTsH=m=;;D#5A_n@qAr;e7T=!sL4=?an z^XXKw5S1s11CLzh+V4+>+0{~0$fqTVtDRFulOji0B3DEGq;N%#=KkoeDkw+9!k;nz zZi#Mgzr~tB)B)K?+7DIt#irXGT@FT*r7?S_8@S=lnEO|6?foZM_}i(HDZvtQ}Y`z|kvC(xph^RfATQJu>e7;oMQ|3@&G;Hz#Fo&b-_( z?zY_d3A*nOlgn+>{Ca^gxIOb*PlC(Eh|b_Ab4W6jlGD*uNI-%{5(O!rb=*}fhT*u$ z1?G|f`ho+MBo>cT26SwY4O{`;N*<6x@rxAktt~~{YiTquZj~Wb(^V-MB#;k!<5dVf z9X^oReb3!ir(Ori&{>#>Pn|8Hk zKjM`6e4Ocs-g|C`t0T@}A=tJ50KfRw_WE8DCmhOTNT8JVe5L>-Jl=-~FJ zLibiHqjOc*{{V(ry}h|GooTT*Z3k*&x}v9Xb*E=l+y;vBv9mts^1@U`mIgiJ5^_0lY8{w#XeG zUF_CI(I&RqWs7iYa%c*O#Ew9WY2qF*7!##ci!DNGJ{d&p{7-&$&q#E?W^OKyrP=%2 zE4e$vYIi2!-@g_H9zD0Yu{+BZj_Qr6yJ_=#LXL-HX0jV*8o4pF60IdpemY4iDbjX^ zViHe#y~zgMYX>u41z6nkSE60rcP*D^id43_iK3T8$5RSw zKEJChcQ~Ax&E-+!6dRW zL?V(+ejIv1GCfM2XnUH8N9|Q1NoTjHO}{K|8=10CrAugn&SmYH-Gb30Wl}Y|{sLr- zP)kijs%Nb}Z~V~d&V=c_pIUDYx5ZIrV(m?o~rHDlt%D)u6% zpa56P%c$3R_am6LZd=*z_Nk(bYL+b`DBHFH85QvnsM?*VYEQ$ex_Y}V%=wk_8V`+o z!nyR|aSVY}Qw!Mqr*QQ37NJzNC!CVw9Ponb8EE9B5Do`xTE<<-BnxEKRhrpr8dso z9es$W&tS9IoP|DKEPdgtn%lLUPbKx-Hnz6+GLog?iAC1ETDztyd}fhIV&g!ILDi|4 zDVsOPwvUtff@HLrXNzTo%XC~-+ISQeRm@UaO-D<4qpXW^f-wwwT3EI2`Hj_kGa=MH zUEN(%wD+bjsWLgf+M&!tycP_;PpfxbZhHXqeRr74W1gmb_SVN%(pA#!{QT%2BSf&p zR97O;9E`xbgx32^7osD$x=W|Suj}}7Y4H^}s~#^H281zQ&Jm{7Fg&ZvvZRrTo=cHM zsHj#z4saOIlC||905qe1@aPz}R?F);cJSJ}v%UA%U~D~|f!=u?r@43j?96<8+Y#ija^-T{ceOSpES32o2IJdL z=GvQrqcul?lO<2$5VcFBaVfavy9--GJ&ws~X{H?>GRC2iim6`(Kv=+YP)!+|fYXv` zbGRg%R_Ac*adEjvZ5_bU5iQ~o{-lvyC`!@d?uu2BQ(YE7MKo+1{F-|sb@rdipOO3b za`>^5?w*f16Sk-;^Al~nOtpQJw`5#i+oH_Z*UdpkM60Suk%EH3fB=vy%9asXL%Bq> zX{ixuG^&{xyoH#B#!1JZz^_hy-+8k0n|;RTtGS~wS&gC(4i#r;qANL4R52q{FZPX% zOlv_0N3@oj}^xB%A6c*1g9b#Q;&5*Q~em&knj-6y46E6Z>=Ad=V=x_*fNo%g>LdTF3hGH4*e2L|v`2?#e8cQj?xnF1iCZW1|gp-k8xkf^dLkr)Zuc(Wgl^3}d z`u%;?g(yBb`zh z{CUH61|Ka)S&OBtr>&)$HjZj>BFvI22Z~f}L(~uZZ)Nv3!d39tf2)lTs6Jz)7dGNv z-5})g$l=0=tw+99{{S!j)z?+oOs3AoO_kb?@=H~>TU?d21WY7X#mi;YPYdaF1c@Uf z(!_!8G2S_9YiVBdZBix8Ql7j*`4B~FrxdT2I*#`(hI@GydjM8|;<@3P9t3e3PZ5la zbkWqGIyV;BIPI14Myq>gBE`lq_>SAhJxyNq#A6Z$iY!NN;3r0@?5rLsqftwdrw27k z8~0YLNRcs1n|+Xhmgas+v$us<>V3Lj(}XZNJA8(M)z}lN-a;+SKS`knNymO}_N6Y~ z>i+sMg3f&uCI^d`x?{1(e&}fwpq# z8_{n~p7G@9UYA6nX)8nvC0;tZ6kS4_D@>J8kO?4*dxCGdW@}l--EkcDm-gdJTh65< zQYrXb4y2lEjhP7GNb4Q9TM6y1-)i1=>8$rbhKgh-qfR@$YA#ZN4Z#D*V27rW&H0KJk2 znP-*5m3)KzQKK%FO+z5nfTs?NUKy>@)g^>@afb?4g{!CZ*{e{>t(FuGl0mKu%=_Yk zNuMK=YOJnWm+nS7ts=(2C}SdD6xf)Wq8NiKORK=qHwEl;5TP3K{m_aSEhSj(+0v@T zjem$a$plbQfyo)qMY7L!_g}oO!urTVnHM^-?Z2q#uf zrjSyUWjbl(0AZYTs@7X|v{(|&R`sMT?kW^S5NSXNCk<90@g|%pO!S+QeDzIhLm%9x zKB!mCTJl9hC-C}qiboZ3Jj}Iqb0i8&jV>6G$o8=<+R1GolIKipz8WbNO-y)$O4G;# z=nZ-%yJxtn+r$Hj3n|D@wH4#Q8dUKh{JMM0?H!e!$3cmcH!GZk2R9gjY4JHa8pV;T zv2jO7H2w|CN~s}s`+3$>JUCJTDx$v|Jc#LL^TACL>K_RwOMpc{%?K6`nh2+t z#gwMaXmrZOBves>46*A1ar>5153xKv;L*iww>I~e4M32Ju87rqjYU`yK!6_5Gl~H$ z!|opCxZAzG{2``^Q%9G?Xxi~oLW~+$SHx-1AGUryMYi__3v%Rl^cgBFc0!MFQ&3^? z6;!zzV?k8aG_*A}wKerHK`gRBx2RMvX1c}?vpvgyebUP6(haPkky<7W%0UECmNB$_j|^aACaDZb>pCqx{6H6oxrtGN|MT!+VBpzUDibouqlB(HOPy z4wFD>BX;N-YOX;lMxl|^eYIJe(uH?bveO$on}^b96zfn`NRgbKD7;>y=hVm9^bjo_ z>R_6pt~j13p_&@F=b@&A2x9WVDTmVR{_^gM}CjMl~97^2R!IrpLvNudK<{QqbfvhJq+@)OmWEn3|6z zsxwJ77x4PnOU0pH8i<&pD!-K(WKc_gMJi33S#BHkBvemU%d~QB`1shaVHajmfNtB9`bcVh0 z6q1=Lp^mb8g8u+-s2j)WwxjKtFE<#a+n_Tv$um(&j)XAJIpnnYxMzVey{t-%QJxy(!gwN%d1&Ym4z%EMJn-34Ot{pSm>-AIRm90=j%jlteKn> zN0QxmjF#n(Ihf5<ad$YseUeY6 zbOe>6fC*)y>iFtc;#^jv6wXe8_^p`f{>94Xa=VU`B>RH{i^akGKN*##mKf0x{Nh>z05Ou^;umWhn5P0Nt0Or1O zOWRv}81`AAk=Bpgi-@dNATK?G>-99>=zwW@HrnG4-MO@V|ER@noOHRonfO?%N)_X^NtpM`5uD~=s87R7xkTkb;0$rDw0S5%C(1S;pljYg-E zfj}VnH5%f>Zs{K%NHO#j(BkGw+R4_cBLxL(f@Ox1nph-UoD~U16{4t(gl%TCCCIZa zp1X+z=B+{KPG|`8QVFR%bMomF78}%YeHFc~n}nFiP71ECIuJvOrveBVG}1}w&Zloz zR^u{RI-C|_zN;ZqEmk`vPa&hHifU0D+9UoHf-D@c%_6#$2?|UBUqzW}Qt75a94Ykf zp(G4LmRyE15^BJTju{+%Ix|~Ki6%Fh5WBGNc9yVq)8g@sJ&#S zG>u@qj9H_8nLt$}P${7WJiZkG05p!A+_r7nE8EC7ZK>OsTU?huG=h2Kk%)a$Nv-uu zBOPqz-JG+AVpx*PvM@W=X)>s*QAvl!Bz40!t3iQj zsP{(aU4}+PGdPepm}(Mu91IWgbY*eP+j)hjCRKnOcCn!JIQfIo#Oj`{pRP7;$;0HU z>Zo#iTW@aM#!8NA=5d70=CW^@J9iY6($rGcV=3W@Rw&?a8%I>?Iw>GMZ zjU;A6N;Hoelrmrsh*E_25Ic!IM*H^QyT0Jpb4by|kvJ8qvG_u2UM$Y24GBDW0tZHe z9N)yYrWQ)b<*kaUo{w=$g?aK+*%{@@nrfOLC?`~i$Br@GL11;I!2A#fVB|QclgQwC8l~!XLgJ%miH0vLMx!AG zFM+=9IgXoDMNc@AYMM!D+U!b{k~Z~y6#IQAQ$K|*&2=w!GRQItmB$JZn(@a(({igp z;lXbU!*LlBP@x4|ijbsLmrimBDs$6*TCzHX$=78vSn27q6(t-&PX#VIl1QoJi}-rt zn8i;|M;4OttUxUDIcEm;FId^_!6RE#xt>tp7JNq;%M-`fSIBx(qZy#N+?Q~k?lcQK zDw-%*z*GtqV;!oPtpFOBmTHnuNIZsL3sFLt+$J8f9Ckw;B_={@xE@-Zr4=rh6_HU* z5Smz?cvRGiB!VW;3pfe@IJesF7HGbt2t;F2Ek>dZelIVF;n%{ZgQN{_wY8^#1)*Ch zqVS~ROo4bEK0uH)XbKH0igX}sKC$dCkvrmj$C<9Fs-UfcpA}WRbJW!19Y>1CLj^51 zGi~B=)YKTRtD8l&;KGB76CxRER|qsz()+F|2Dek)Q~g zR79kgoKx>>axcY z0Fj~~1K&n@e_+`8UuD~QW0p46v*p`0A}Car?s|BWOCj!>;!-tDJNHP`;Hs**;mUli zvT|<6ZOi<>Y2j_CbrQ!^vq(Sc>DG{{WVuzYM`b%mxVK>z`15eNe{I z><;z#McuUf?`1qVecg(Q@cG-SAP%Pd!#8s$*K3N{F3nF_p-b z5SxcdAg*xaJ04-%W!U%l9caL*nkx03)(2|c7R08118oXOh2Fh@v-cGzeZ#`roF zI?_a_WNcB=v(ksEs}y1H6gnhog&DvdiMq4OC$eID)E zc{&*;t)i-2WGzQezcxnSGt^aMGx*nzu9`U|iDiM>dKSaJW#ygQ+pFi;w={IHxs7}o z;$o0p$c?MUw{u?xNa?HTWTf#iET!UMBgHY>@7$%mU2$}|N&y+sZ8%L#jEclDcy&7} z7fYCjiXo84B#9xXsL07#jmXpEXqydDM@NduR1~YmwQg@CkEpAVty^Sc##8Q$TV<yQHSMJc4Oq*7xWM{p-M=y5=ddF5C<_1R<$Rk%FdHC^oCe*!M@3H zMufbPRC%j~E2~En=vb-sh{*`YK++3_%QnWw-r6YJ^%hBrnym;G)-cT{kpy{~R-H!o z5bot<8>Y5XK^puj3h-iaN&;4chYl1S0$Hgu=|hvQ+i}-m>l%()S}dyKkuwle)xjin z89l8>J5<%;q-sQ#F;NAX4a%?%EF-jxM|p0y(P|UqM4;%U3(UG9hZwr>~t9k@KaLI#|Wd1?&eM$&1~^WX(WW(yQ4C*N>CN41ZpLL1pXRS z(-Z@t*yoEj+OGD?yD4P1C=xRx7iiN;rkIHpP(r9Wiwz)(4m~6>oi`RU)y_wvYTAFUaA}Ck%QV~{Z(b7KZpK?jL8<1qAQU@$EQ7?wz_Kt@w;(!ZcnH8Ui#ZrU8A^r zQwN0HeUDL%&+Wd%%XF&scG%uHO~JKjuryK9Z2tfo%LN`nJe4H%aRlZ*A^9v9xynduw(7 z0ABCj*`?~(_dfIMj<(wypCv(p!&FXbsVS@79LljkBDK!#Z*ZbHZe(bcbb+n>IuOGv z#f=!PS&bLxp091qsShpe`&4qw4X7GqR*YN`qr&jsZv+;ECFa5* zUmNSXUHa!QC!fFQJ7$k6+tU?3;Da2UVO`htTYi?Zi*8e5@%w&Cc8RB^ksh*okreUI z8brwNw(D;!Hny(G;3LTR)s}Td$)!L6a0krS%c|M#9JZXjKHLERKLEfj-^MqQxGdE= zLO3}HGgi>m1dtTe6*Vv$%fG%v?@y08UYm=vswr?gr>rntKiC^PZEQ}Z!B4*WZ*Nc} zI9{&Y6|?nyRynsG7N&-c;N4WqNx4+OO63uzscDqo@2PtIT|Km=2ST`c!rs=mHh?aa3csFI?@7 zvkbJkm@#l-srHmLI1r0MWNQBa;u_~;;3z%#&lxcS-=?Ab@lrvrtxiDnrgCf2wr#aG zn5|jYU(^<*4!RTqrKzU40CC4pyT5zpvilP|h;6mkGww|O8)i{f?kX*lSsrU2O@-TW z?ajvq)2gq^)zNKD-@UQ4RIzRf+E^16Twn&4l8#HtZg&-$d74Q(3k=|DIH^8>(}&8w zWD|(5cHs|%C0$JvW6bGgsA>~jve8W_zGFQW4E|Cd^l!IzLE6F%$BFD6*SSu1rm{z= zZLylcU~%znnQ<^uCN@|h%HrO!D@^S;X&Mn2LS2rz7+7OiXOcvtQD^`}@(QLYFCXFNxcKd@uv)=Jv?x%NIIZ!R*0vKZ~jpUWEc zLfJpF%TZ$~#yNsCbn#=Oo`}qZ`6lwSS&@Av#$+ZSC7@L!^DSESQx&g;q&`bm`BI*g z^EK$m;X93{=w8IySv-GJV*68aZw;xGso$_{3jYA~r@r=l4y%~iR2z>SBJCZgMsiWb zmCjXEQpYxNDCub;WMq&}scwl03~flu63hSukPaQGsgkD(KNT48!h4uvoi_-mnN9_vDJNpgX*|&JR=iPe)*YDY-@%em?@eG}EY5|3wM{{X)`TYmPAb2+@e{{SIR znWWo0tNXn8U9FA8Q%O&@{{V$m*3i9txe3JiSgR@4C|(LzktVshQf-s!0E!i2JA1V| zmSd}p01HH>8m(INoTk_|m~Dxz%F0+A>Izjs9+WM^%x1L3Mh)NGk#3)k&$mX)>b!(^-W8H+#8RuC=EvEN&`<0P{T~|!3wO)D{pqv zUI_lE{Sb|t0Cz}A(^=zy2^90CYfhIOR!$vAl8_! zpwDz}tTlJXu9(>vEw?ImhSlu;@XBvZ!G;mYrDDu*} znrUQ_kz{GmFoW8eZ)25gVT^#VM$Tj)s>hQ}!^$J0r%)xKe^9xh<{3nt;?{Q&P+e zEqDNg3h@~=Q{%xkl$O^K#Um_gh{TY}x{Df6QK^6dAO!=7=}(s3-AkGHDY5oE_=#8L z_7CKbcxRU*gT~1{1~Z{^+i$5x%G>*^Gn-l*Mn7s~_fg#SG%#SL$>$`=(4@H~qoy>? zQCY8D?riPU{{V}}Y~;uQAE?t37QY)27_A3l)P5sVrh{lZERi&$>O5}M?k7%!)I|tU zR@IgV6$_eC=W2J8?mWI0o8%{2{CUsy)=LSSr0nWmx7hVt7qqwbe!uu9k9cl9=SPyS zTu$lA*5PQ*TCW2|PHM4{*Fyy~H8p0TX>)sUkz5Na()TUEI9(dqi!%VBPOOp(HxQtj zDC+lDFwbhf1W?CwMN=W8FaeXqbWH#WodYU0XspG^EnQH)Ms}uuw!SlUuHUM~^d?`m z@Lm1e85;f9v?=mf?en!da;s`>=(@M4`r~5wvDkjU`0J0Xp1z`H$&9vdC7!0E{{Sh6 z?Q2@Dw%0JHfn<*<3l_JMK~{N76(&it&mmA7!%`zqS?Q^ki_`Ztr!QOWa5Pcbq~t{& zv#kb&W^E(l5;HM(VN&cxPepC}hjiibIXWD#Nql3?R_C^+XKZGxGFv}0N)Oh&yy#6uJ?azvMj@R1#aaXzNH&@QQH^{ul zWM;c=9iv~d_t#SF3~$AgyQuoF6Bgmb?TxM337fB`{_4**Zm%K#00X>K%TBUualFxK z16o97xrHiJC_0&(kVc{dNC52xf~e!f)x@;2oowQFg;VOHVq0B8CX*#fwkuZ62%wq0;ZeKhsN&Q&J!bT z&qGSo8&;-@7$>5kO7!v{8H&h*_k{8|s@17Z0<72-H~=vPjYz=h`DC`18IvsfS?K$JE>6$>T(E4--P7O9pKffeyM^qnvDq6pZhWRqquU*u-Jcus zai$kJvYV>*4`0;OZTu!bIwGk|X6Ba{mdH_VC}X6^($wH4oe|~Sew{8Y{+vx0>gg{>UC^{WL$Rr8Hs6^!O6=7E)s3QO#*DUnXr476sx%90R*Kt3EdQlX} z2a5}EV%kQO3<+sT2~7YBWEqc#za{#&YT;m>l*) zF#FOynbh5dzc8~cR^Fi4yVt5`nwL98Oxe%kvr|y!7ECQeR8&S}`1l?iH}0urP~9MfBt)IbDz zf~H#@Ubw zdamO5zeUv>Z>l>Bt0S$9?|p%`t9wFh4{u-_4ZD)R9lswTNxe6QRq2;xNfTo0KJrMz zRoe4-*d}I*Esee02D|t=ZWcCEbks%!}Nr>chr_Yj;2+ZtQ@kFzr0Oa}Dmv`|fEzp6(`$K`mr? z6%Lq@)v4P+{#spyHY;ookO_^)_pfVZwg+I%f%%P-?3_;W z+So3-ZOwtsPhd;8BqqRX`maUUKb@;kL)NZYm>;xJC3OZJ#sD%<}fOGy8*kZy0)Gb#FXoZi6?l;*SYgPZrL{?T)3z?pjW{#n(0qW=*&7 zIq4lKy5~Dkay0bb4K(ibTh7(E3wdX`f&yf7B!%fDi%|0EV$7mBoFg>;9;p=+AfxoR znfX&^eqO!hnQtbX&XL%ySzQeVn{;FaRazuQiX5-f%-YJ0AxVDCe=FaL`@gk1-{DSY zghd%Bll<)YYQvN4--zpgNKI|g05Q1dlz2hEs@sv1gh z<)xN+d^eqkMZ;WQ+qTziu93HkNVPNgjUz~1TS^kk8nO7n64Wk-1>bu)$}-E#JcAwG z%zJ!N+*}l5rsh|=iZy7&h^1APp%UgXsU^`FZ6Sen`HPd>7>=6Fbq>bB&~8dD%*l4& zUgh__Pi|y$y;HJwR>4h~x3+%&0NZ~bv6zaQ6Oip}ekNHkSc)3tz-&y!bv4-89wvsG zB3QS%Zsl3hTUCl{b8|E4lgD}IlsAHbq|q8^?wUpgq(xZO6|yhR*74bG9L38?10A|( z+Rhn1ph*M*-F!BizzP`a(rFrgid->t8dkjq*sqA&e`T*ybwnN4km@e)>Q9NEBDb#H z-oq!b>2^h5Zg-~R>%G?Lyk@PUZ|{dy?ffX4DTms$?3>G795a2xNgKMa+@*+m@B=Y=wS1NMt>z@`oN$(Uhs0}oN z5*V=sk{TM5|7i8>=eGh2$T$`$^8?vRU z-&?CC*-`*OaO<;3kr$VU!dniLOH6>nE#xW1Ygq-GN^jhZ)oN|aad zmBR%!Q>JMU>WzV`9XUPRZFzbaZ|<(V8%^1^^j9&}ppXC~j#;BsG6OgPt;%Vj6_~~t zOrY0iw_s*AzgKk!Y4tel>Mh${*Dc(CAa~yC*f`z4jOpFM+4MU&~j%cvRgT zxzrfAC97y?SRHNm89SkqfBT#Y)M zNP$ZzKu)0N?jBU1mlnr#VP!Hr&l|)W<0rQ2MP_wz8nK1Lme(2`Y%o}8?B2iFy>+nr zd*W`)pSwGQk zWV0bFFwRh&A8JXJXOx_sCuHa=A=yDh|Wy z+=jy2IE}}X!`0_!&h4$+x3gH;F}eI1pKjMhym8G`@zVKVsuR-)!ntHmYqqP47$&+; zt6g_OFsr}^R&%5=Ibx>*l*S1rfREUoR$g4^j%T`ARZZUBuxO|(%>=6Y)Te1l1D4Q9 zbt-BA9c&Csb97*JGLTAwP5%JK+}zmQaqRw-!RsnUYu6oZbtd|kQiV2PsyHK1{By;< z=L?J2Me z^bD_I#hTm^f5+qAh^G&?^6N!#dYFx+Y#Dh`W5tP6ZUycQ{{Yw#?xwWC$5lT*Bdi%r zeLiZ9>8FY|StBZ}Y`RGV6$ZxRkFVp~E`XAJx~mG;9T9Hi=xly^Dy5Q!2}GgJhm6_4 zy~7I;&pdrDIQEuk1Fa7qUrv$B0>}?<&+Pj;rw;o5Ui&|G&0i%>-lloTmEx+3BLz}O zz=0^Ji9?sLy^o}k^!6OS*RtQ1diQY2s5VP(Wh*h2bs{j!8f04@)bQk>Ww)ZKCXH?SNcIulIUi`= z?M;sFVHMSg1O%BDKs@S|?u?V>g-tpL?%bPUx!MaG>v*p00W^-{HI+f)bX00e`IRbu zeJn8>OXcnwqL6N6>u$yHz$vD#&FwnPy|`+CH}g-I*|nIsW~m^5oO)6i^2&Y3TZgbb zwR0S!Z@;{>u2oV&ENV#Mrgf3R*BE>Oj-sv8*dA8Ad1l*wuF7{}K#pxuiswj4(pC%R zK#)^_r%SmXxCAW}{aBHz!y3&#BYosx5~Ompim)ifLkB2~%z1$yB&Pq(}xKlD;`q=<~k zy+|pkLnzj8O7b!ygX9I&+TUMkf8caF%!$m3N&YAeK1QA;D18oV_H>>8?^}Z+GIM%> zMGb9_?P^V04xJ&+_H_Y=?Ru*@Pgb()mT}n86sUxF$n=f98F?AWCtbi&2h@8lpYG#( zavnK(lG&g?4Q-pXzDLEyJw-G2^w<0k8-!tW^HgQe8rm8W!vn|r4*_01K2vUP&YH37 zW$TRHJxHi(xMhoY;iMGR60eV0S+EZj@&xp=6a|MQU)l+N?w6{M5#FuXFaZ9Og2W$D zC48zg^3P32><0TBuw28=QLNA&#`;rGMMY`ipV&diSmxY&&WO6r)jOuJN|B+GJ^PG~ zMvfpEk<6G@k(fBYsF2`u?uYLG0L+&Nz85jtBP$wK2{@YP4m`d<*Q;842fskYk2WKN zO8)?hwm|v#we&gZk0-nLw3AmY4^(cN9DMg*3>)tY_X?$hK;f4M9BM_4^e5`z5Iw4k z?)AJP#q~SwoVQ8^Nrp;S%!3kyNcTGwML+MU4t(>k z&&$)TKd?NMJC@#Ff}_BYsX56S{{Ww^db#!+n6$KWhtgBd0bo7t3(n${)$_HF8=2`BmJC-PCmYAI$vMNkU=0FSo^-PY*%el**2 zpc(xs7d$GXQ6T!~s;{v;$dCGa?WTX>4~m+ajYQMb17EYJC_6`cqCo_^FSG=(22)c< znA%ZPuxphN%OMELj^x?E0^AGxK>q-D4aJPigKcP>iUwI|Df0P`Kikud>~AyGSZ`Kb zF<9jU8so^**RJUMUwPAg%SnOm5M^ZXtJG~eDjmeuL}nM4xv1 z)+$wY;U)z~in>P{fuz*>40S{7S2lwzvG3LmA>&x(@A4<$IidJZ8gc4MceeSCni?~- zJ7PZryGK-$Z7Hf=U0jIdp07cPR>2X&1_%5t?F^rG&DrHMHN}R2X{Ysc)Mrtm{6~+k zO`l`=zyVF`ZtPlo67jDS*g>epDZ>W6C^0`HHSgMg3zX3_GVEx#4wsn?Gp4H||1~-#sL7=TyBya|Vk2;L?b@r#+Wjf?LZj#yV za898{p%4rjenzyX6Ps;(rmLo|q&4~8*u-Pc+tXLc4^iSW)fEvnS(aMGqIZP7QL zsT{2V&Z@;y2*n7;kq12v*{_>jawV%fcW?H+1wzWPE_Cb`r;2J9qx)LgC@^1m-(w7q zW`=(v$gww#qP@rir`=cGdD$Ozx7&(1u7PpfvIeTLkVX}aFjYl00z-9Y_OG7d)NJvpww{62{D4?$Bc}_x)S1%PlPKOy!latBeRe!mf zVEnK@pJ}ar>N};B#`+Fjxm(6yTz>JaRp6|#yA)m~q9C*X|-dUk{6wFONzC0x_hV>dM|8K7FMcUtds!_SV^i6k$I$efs@ znWKu%(XmcHZBy{WecZYB(rdeQ+U1vSbvZW>8Ig&tL#~iPJSqtzi8Sbv{{Y)>a_%Iy zxo%do7YL!3P*(tSsiXO@QiH))pQeuyC2c&l?!8sLXUxT=1%(BB z;{~WvIQW1gIG5?edn23f>(4?{r)Ru38c7tmx6t+eHPwc%oj@ax%GR8V?*)ar*sm?v zi$-uu8DMEeC@3WH>7W5xX{BmI3X#-x`RBFjv9xqDWOlk$V@6hze7baZXHr#eDr(B+ znwGmHlF-cr+k+DYqe(uT>uHk9a%7!4<3nS`^S*v(d%NYGNU;=3aQeYmM_h-rtr#FBEPYcz4_3?zjdxNhb(oT)l+8~~&W zpak@Qt?zxUTJ0>I`@JaSXp)|upBX{hbXfX2YG~sS&GuixLL|hCxQMQ{yB>Y7kJ?Ul zDH`2-TjGJ2X+^8M6Yn?8Cnk?3=K{x#;2)C z+dF3|;8?yv@8eV{ky+ke&y!x6nnk6jYOE-#OS_knH;_ifh_%nUN9^}K_=HF8JU$y5 zC@E`-4~r7eiV9#QK1JqfYc608uh03*WJ1Ayk)T5WT+|PNqV}pk)*DpKCLH%F9uu?M?#j>*!#aT zQB5v5WUyj&;8*wN^JQad!iimfm$C%kZ_^nUXN#7^nOP% zSxsNPGPzyTS}Ez_5!aaDqKcJ00+A`{;z{0-gL?dqPaUK z?@iV|?;7@!1z>domgDqA8!N0xMl+7G3zmI~yx%3Ccic*Ve0n4To=XC8U+Bp0 zIMfhn)thy;%BRLtQv(c8$4?r>h_Rw1F(QPGB8V!-5=NF9Q~;ysE$(-7B+k-I<(icI zhX6c)8~_*t107E`_UvPdFrY+$1yBG~P$(4?P%43dpa2H}PKUT>3abchD3?`LZU&oJ zHO;@+-`>SNG1A10u;Geh{hqt3hC1p=sihv4E}ZE)SdtZ#+^9w$*Mt7Qw<)L)4Nv;N zXHJB{Mkh~1tSM7Ue=d^CZ&lJqZ_BD` z`7Q9%1-;|1hPw*|Qn-;&ya>l#$qxf*@<$?`ZY*#4_CbBJ+ubXyk&>RDZ zjvw2OeC79s9%1(CYlc-nuLN;is*#$RZJDG3nEh1^Km`HEQC~80k2Xg4cQWkP4QfJ` z5HY!lLW+=q3uKX~(lyl8G_Meoe|KkP;wvZ2VY`20(mjHV=3(A9MHd~stk^eIPD zl>Y$T>a0{TOt8BeQydXXOF7o0lVB&=IeV8{F9~*?#@R&{MQ^K8)I1N0rL;c@1$%%4 z9R;De+?x7Zi=Do4aLDS_w0QKai$X$(kyNVu8bH!&MtZ9r*X*vs%F|YD>WtppsK?dh z8mA*BHlGfaStePP>7lKwiz_nEO$3M?Ry0ewC5sDMV%RxnWwx3-$gL+5s*trVRcbOq zl^Gz=lU#77dXe@muWZu|#FjEFk*fg3Tnvg50Us4HUn-h(cK-mCmsf5sz=PyYXCEdZ z@;F+)u*KBZF{T> z&~V8#^Evq)?ly@cM%If(QNV(^t|^b(_ImYdIWLWUwObF~(#?T1@e(JD&MW za>y}W6gC`weVrs$##0;JDQa-et{gz)PoF{Si0{P8rQq>+d`J8ReE!aoQhaOe@&IhM z(Pi}6lPyrr5Rz1CIM6j;{C_^w3wRk5Ma4&+4QsmDb8S5Os7JGrWKmNP!eSJ9X3Z;rn`Z zrTF{W^!Ulrs!hDoJzP@9Q%{^E2+>>=WqM_G)=1M}L0(U{5iNvt@rDgB4Nq33*VB}E z0PX}3!-jbIkFu1{QO`hjJ$);hZ{XylYQ9IxGOEb|w2LjN-r7rgezzR^vHDZ>KpL{``e9CxW6eF7bq z{JXoGa^R}}0LgZo(nTDyEUmg}79ez+7MRnBqh~zY{{Z5ByBwD3R$Ik7c=o@RX~WZ@ zF3G#yt;|q;ImxScCO<7)M^%H6_;cRdYdKemd|uv@!6^mc-I$3W0H02&yr4Kgf zVhC<+ZefkqVNaN0`!U1q=x+O(cx+zTwNpP1KF;jd0x{-b++FYncgfrQFy_W5!0>r1+*cy!xHNyp&w`Rd2Zpx1bOEAEK1 zc=(Rq!qiP!9cS9b2I;}vtSKAMB=0p$NfkO=0L1c7=i887!V5+x86I`=H1z)fXQ2g_ z@grHz-UO6VDV6=77xUrs=?78p)4mMGo;{&NvW8$l+`E6qrB_)EQTP4@7Wy$@8|V+U zLgo{!c<4y`bM{n!E}s4HtiTwazc4?~{;w{eufu1d8yfcQ!^3VA?(B9$(Pw{Cgri4&&{Ky1+{{YL5vcvHEzEeX5b-?klM=m4DKaG@+&8|86bM4VIL`Vg~&{Dj7{D-gjIP=+-0DU%cA612j zlQfJNYa9`NFZ2e^G>|S@dHsriKCAoM-?Q{&uO0&+am8`+tqJn#8+;}CA_$D^ ziVa#p(;o8K&tMLnZ=*EU=kxg-k9$cV3<$VdAN1egrE~J(=hokQfi+UzN&#L2hs!@c zxlQncOlvmmgM~Xa{%w1H=7Ctv2-tX%yQ_ ztWZ>GrwmZ)rhmi7sVCsy$#qmR?CeNlrcEooHgoAh+H6rXF2d*Nq-rCP$F{_l>PSh_ zlpn?WczX2k-6*~*Tet*&MzkL-Tz}&Dbt;qK_sL2*A!&9-CRpm@v>pxZv!@Qvt-_a! zFi}c)&c1Ahz?+ag-^I2?09`Jx_S`=;^YZGyy<@8^mhx#dr8Jyz<6r00iM|MYpJopa zT~UED2~>Z5c22N_fFHy&#z>Km`k)W`-t-<4QGTv7T!IPt{{TmimsV}iEp*ySM*;BT zJbo@6cNf7=m8cbyud#(#GZs7ZVtN9bIcshf(&Taz^{^ZR?yca^vAc?x^KU;YX|6o+ z(qp?I41SVA!-vD==~miKZC|7kG?y0sBA~caAv$T@#+9cEaQV}x?YAc~6ljfI8_j4b_8R$c$?0{2_)qeh zlPLx!9;&FR$ka?};G(46dmg4qB}G zKc7VRSHfKyE#zX}Km(|Jv-<()Yp3`v^8$J?I`o}e!E}pR-TiT^TgGKjupQs$;S}G| z=_1WyKq#6d4p-{pucoi|IwgCp1gW)>m8EDY_Ex{~UVS689|%5C;@xZOI%hc$il!Q7 zl02r=sEuo+Vc??zlRG=C^R<#YfQ-i4ukXv@CZ_S@B;yPXY4(4Ihf0$4&W?|3AdiMc za&QM9_^zyL<8Q(L0GiwDX{~M(;)iGE=<&%h{wYI4wx^_uC{c{E7Hs;oY5Q&X8j6rE zMZKfG+oT}e{dKAhISo8u;8bF!r_g=91LoLwYpaQx!(h0W1!4+?r98%15ndlY1EKRB z@LT1bWo<15C&z8+U6HJjBc;dDQ*FwrCzhb-T6K6cazzZ459tXjA!Z*>&$89Bo!kLD zI29z#9+8eD>Y)DsCq&V0yS>cIZyv#O0>(tSZsXJw;_^8v#*`j*guE@yJO>ovU1IETq|L1Z?)Yh8DV)+pi*xB$?pw$)dN7 z7!FQGl2`&r$fi$6lX9OlK!Qp6V&KI?s)iyofs(*IRDGlJrxC7K}6AKkkt3D35qvA;9;K0F3wrmyjsJ6QQw z#N$FZbc*AXcfS$iUQf6(I`GjKdIBr>fFVr{IQfCcqaD-V%U`p1Elvs!;rQ>{oqMz~ zIUKTNYAZT&x#{q5!HcSqav1t~F;!Fv6Vwf#mZJg8AVCeTHcS>$*TxLo-(e{`+DhE4rz-hC!eiWpq)c*iw4&o%PzvFV0HGtO z6u%g^)-Iv2na-8%y}!5Of{~n8^q%#`(j^p3VvwyRX4;0I_UZssOIu$9)II86T)l%^ z$+y3Rl%|r6h8>`3CyxqwaG>an@`mSZd>f6H?l_nRHHE1_XwGrueSFVPa{OoPT51Qc zq3Uk;uUR5_RVcbQvHUS3dT8LOs!g`g`DBcOet|xR-BV)RO1j0jOQ;HxO4B*@srj7z z`ZFA%xg-MO9j5%F3e)MO6d2MN(v>(Ow5O*QHq#Uo{M-wK`?sP*X>*iOiWmKu(&->|Qc z)Ck{UZn|oj8bu(=DCWZ~kh3WLWF9`g_4}gvT&c2~#R9a_Ym-XX*UO^GMA1=F((A)w z4q=w0lj)-#d`AvFKTu&e)T*<=)_sK$jsYWmzg}+(MI2g@<_0_?Dn@~ik%g3Vayj~8#BG{h5PpJI9w{Kv0DKGVSNI=UqlJ8yC0 zs%d7X$|237*kyBCdnrUozFOjIA;n1L1x8Q@P`hsuAH{hFr z&mPqDY1T4JU6rmlz0U^!0A7BIN56c!_w(zK13&}nY;W|jzx!4Gqu#T_t&YF{(%Jbg z3o3#WN#)p$4fWwqC2hsOKVN9g4S&hg{{WX+;gqyNB?^-Ifa6KJ`hZ`-qOWXh^O&by7V}I?fr5j)1PDmIPn@sF2qL1|0G3q-iuGs`-+0)X3XPg#nlVWYR8g za9f7@kz@J%`>7b=$E|Sl&rz~;6q!nM6zZ848Y0Oz0=JJQq>hP5iQ4pjJoCdB=2ENnQp zwq6BoLr9@LG+_W!6hGkU12;rtots4x1_~O+H35O;fNLEm>-GA3WZIzAq)>F6+JoCc zKtGpFa&#UtO<|}IlD1nQ3=itDDlEkQebsH~RF8`tHf-b3@YbC*)O02_f}o;ADlV#H zSJQ48RB5qLf7^R(T7lva1%K849-B5X(CAa7pY!zsPJ+j^$)QdKyoGoM*3uZK7j6$9 zpLF_Vp#f+B;nu#D7}3xYJo@Q+7aL=yg%;!;LM3Zj!uBKU&o(~UYb5}UIO?rw5aPM} zI)gXI{A-)N0@$&)r9*2fRQlBhk^L{nyL}1;B7(o?{{S~$YdF-92Y1=iWBhu?vbvfm z57X#~TI78QHq_dO*5msB0EfMcH8>y>^B$cx)@s!G@u9eCO$MxZrU%cw`=rZfUlhC3EE1~7PYb=C@y zr{0aArjj#X+Ip+mCn#45}3?DzA{8#hqf_!Pl6$Nq11^6BkG>`2oE}j7Y z0C>N>HK?K0@YBorbl>jeRcffxeLVV?{>x4__89o}YUHe9#eSfvDh-9d+xw$ht8r1o zryj)#D(W--uiMvO?6hNCDEk!v1|eQCV_{)tDR4PI?fteaQ;RKY^Yr<2+1pTY%}#!Q z@m+Tp#!PS^jC^1XK!AuXV{4EA)Or5^Vm;Vd9y};|s_ke7oKyUt@qKdt0A-gPp_Os! zEaiytDuJu&K+|$KAL1|Wrp0wsrbo~HRO`*Q0#1-BC_Z0rQq$umHJu2cPC~IEMxX&D z)ZBiP_&(|Tx;j)X2bbH`2GJN&2?W-^FSDty@uwPKFv*TY1nM9niz50FuhUq9RB)1?Q-Omu94 zv5GXXZevxkQ>c_7NF*EI-P3MFp&;tuKEglE)rQj$Ij*nrf5mhyZNHCL`f{OY(MT%D zS~Owm1e6%56TQrKM<5X@VUfTq2S*fo~gH_9XIt zp4FrP918yctIws;+9(S}&qj-AY;>lMKP@3!G*iVDG)W9dju0^gxK|faf3K*4&*R>}!5&rr00&C~1=0tXS&~-rT_e5N zoi^2AK@5N!+cyeSOiBRT%OA0543*5GT7G6us-wloF-ZaW4pA8 z9*qIj2P!x=CdA*^Cv)43cXt;N7O!bPvX%RP&0ju>_kD~saLsJLtg1=!u5tN_bwGK1 zW+EwMAHwm`vN#&mZRIzedOlIRDeAYt+L*d}xpyQR6B?Bj&qyJarC18O7)zCQO{niT zTRzenZBxkg@W*(G5VV>rjcfo3PlUFwERgSeckeCFVY0c@ZChTg9}oeSpkR;)&1u_{ z<<~CW+5N@8a9gwFZ^n<2KPfkVarMkOUFAGDZou8O-I^O=WfG5gygg;JQ#*qH07qCz zYN@ihc{5O87a2mP3V`vL;FN21$-J(1p#)r~Z4_Z@3#c+upb{=H{vwQq*3xV5QW%b; zU){SjmbV*Zdo8chuW3Sos0{#K+Q?Xprxwnt@jYBe!B3hPpOqgLdXKjIyL@8$3vljE z#LWD7?Jm>8Y$e{?OJH_&4Lwufdse4lMOBB#P;5-i9Zoi@EM%TMRte^-tf&#<>Bv~| zd33JzXS127mMMP{X%d*|SXZ=-c+glOB=?1_K!wwkw#Da>%d_4x?Tbk@F$%#MLxg7F zJCB8{6cl1X1oRqw#Qsm8&5vg9UGLrfLGr7%r%ju&bG^y5JDYEJwLO2vzRKHJ3JCHz zYzt84H&)Z6>MW+<70cTTbjS5s-L4yLQEgJ`vY*|#s-$+a4S5)fGwFT_*^a>Vf}S-7=o4?{P?f03QD z^4H>E-SxEnGqHYEZOzZvy&bvshjMlVeL>YZ?~r|d*qUq(+&hX4URs|8ne6HJ1q?X+ zH8f=^b1x+%Gt*PNb44HAa?6d%9jYDCBS|wHtUOIiT!jdKQc4B^fzs5}6^~;=6LMv& z{OSE(hW49#fhcoDA|fgyU05HN^P4%zQ7liSOG{Qci=3AChuQfDzSox89N7hl$Ol~w|)?Vzf~E_MS`j%fE=5GqaXnwAz0ov%QGl8ov8_u3K;PRWEqvA;!{mw_|TfFf>^V zp4saC$}{v;`Lv;?kkLq$D^C)@(5e7r<(7|gvf6&J#5WGAB>`Gd87EeiJ+CsTqLbRr zLlMP#g>HF1)p^l5buLfQIY+59VH+Cwb)f~p1r>!co+6zJUorj=cRxXNe)#z@2X%bi z`5oIEXR300?uWkr0G3zCJ-buU{a@T0E2t8(JSTGeW!yr$6<_h@Zo#Ch%jW7ae`#Mn z-GVrgB&n&Wr;K+mEApJyw{{yw&tq{6Ulh{PE7QOi*0Q+|rAZ2mSy;6gd}4JRv9a1( zLt(gVaV@Niq*5T`ffZ>PM3rvUE?EBn6>3N!AHy%7xsQ}T2CIADaN>6J_ioDE8UCu@ zc>H}7xNVWSH|{Er7nj@HzZXT0g_j$Q+`Df#O;uS%Op(Nu@KhuV1Tw^t0cYi@{{VaK zdpuWC2rgVGmVup8r&%l73#y6&XbTX;8W3Rp&yy{n=OM8Nb+C0w0}>g8EnQrAuw`Tw zuaWAv{!HV3YeBI7IQE_&l=%(Vm2?;#+qiK3f42H}Vbg8s`rikb+M9l~ z^^P+EyCj-=+-^R)lA^Aro@X*iJWPa1o1Y}|R2Sd4cKxb0iYP~kaK)NaD^P&bk|Zui z#L<-s#HiA$V_BBZm$n;yy&;ETv`a>pN(Mk=WeG-YUml}FQpT;4C=CuDjejOL2g(kJ z{{Tw4Yz+YIj85#AthbIc2}KPCD>u9(r^HlYH&rGk2qL7zP;M$*ELm zww9nmu|)AifTY-7-tx<8ic(>f!mBavQCcu3&43>l%n~^D9q)X<9k()D?U6p4IYP2` zRM3*78vg(Z1O_D5qPz`x{G9lw@)nARth=ABJMX-D*D<^?Ir=(1wL_NNc+IINY3yF6 zuidciUAadVLJhCFs(TlG;OED_Iw_@-Z#`5IH91+$fQ%+5jU{5QPZwDbdm|#VygW>M}5rkkug8*6qB-Fo~o<0iw! zgy_A4naTE6{;SR=NI_GLqoS!=Xa4{ z@742ftUqUVe_Qq@>fUr1E}PpMcM-TLq{lu#HImyoj1J|*V@)MiYcIbyB@D)%hN>S9 zKLLxLy#3gd$Lwn_E9@|6+lVsWGJ^63s+S{FXb3b^3fkqAFafls0aH=58&=z8461h6 z9^F7f(kN$YP?xC(IiLUnO??Ff{{V!)BddFFWbfg>6K+=azeevWO^3R3I9XxC?Tzz|q!oHpFu9Vfqf{--HJ*B>DJ3wZV}FRL(}8(*<;nP{=t{gb>m>s4d6)_$v1 zDTgX=N2l%ljLXw^{8?BcWCCWpE_#W+FyCp;n2jLICNfKzSI|$J>7`?YnKO zEyPhx8A1-USKtPq8%dx9kUd74kU=1X{Au|Cy?YiPkX=dMlv@ffk^cY_H|>90cAjId z4FT)z{T@E6F@vDr7zr^Hkl`b!sm^VB_^XaSIA|tAPgPA%3eM1=BXZkif=CwLM`)yz zK-4lCx@g=hnvh5am~7OT@0)pPZ1=ss8yYR8;q4W!hN#v7sU<*lE1C+B4FIBNvASpE zuV`&5{_NSk!Mb|?0B&KasW!gE*!vT*_U~HOXZ}R*F_WO`EseK3Enu#|Z)}$PY)x+N zuES*(mluTCJAS@Qg>5x`T_j$|HyowQ*7i`uu$i|h29Y!Pfk_}U6%_&@0)`SkrD-H8 zu>+*CkL)%Lj@CJCWZNTi8j{Y*soQ`HLt3knG=V^SiJ%#c{JefgZ{L@A{rlE?`xUpV z`_rX!ds}Q}HwM}`U7@r4Ckd9Vt=jlq-nhcx{EO;nTMQNs)=#YF=`4ihavnTQ+q<&QG zT79MRPvSjQO#P8r76ON5u73dqT-fZ4o3m(R7A!W~-_ z$ZV`0TN(ZN$K-R{(-hS?Rj3iuc%Dcks)9O*UP`#-UPs#OEbVtlUH35oc9c0{(@Uiz ziAs*hyiiJZnHz{G9Vjf?Iek$?F>TRI%GybF4%7m!K;jOQK)e@;;Al?18TRLN?vB^* z{{V&GB%{J^Kaw9DGnlM=d(&@YP8oY&50}egcEuc0VP74Bf%iQoV>3Y1^~+C4`C2T3 zy+lhjJd@M``G=RL+3s4>DzzukMq%2_YQ5zA2gtEB99WF>2bq4 z5841;7$JbC8rFlRUz2-7@M_PZ;4Nbf{`Cv1$( zS2cAg@1wx}#-hW5=? zD8Y4fp~RXn0Ie3P2qJ(3L&Tb#efiV<)!6$|yLk1^_ud;H7mcFI(qZN6e9qm#ZVc|_ z$K#iG%UcFVHq=!cj~7d}adnW^(WP|+1*<8iqB6?_@i2zVl=iEwq~2~HEF>lii1i9Q?l&VD;2s+WF)v?D(0*KKMJCcI*>^Mx=F|cberg(lKq#r z{$1~XhCTJUFny;j2F*MF0OPlPV6fYB1DNc-zj_bvmJ|IWL$w7y2PvM)Y#Prp>G8K(Pwvb=3U0_9}`mzR`HRgf>l?w zv{aX3$zL#8RYkw$ZS$vebSKR`kMi949+-a2>#vqQWw^X++IQ7yC9sh=$mr~> zV~|J)XN;68(YlrgI+Y0>AB%0LWS-{c+@P|Zgc2N`5)x4Y{6uPI2|7+{{QmZ#!x z&CHI#+?$84s_Xi5bkt9N;3&?aiZ=_U$(9%!zWzE4HZZ=kQDb02P`@&1Pq-5{kiM0c)x10DqQwGUsf7 z-(QtGlZ0;!)P-uC9VVKW3{6iRIzdxXCrk5l=P$|MkQ=_}vVr(qVTV_dHkE)s+WI3t|Y;2X4O-WK-t~`{{V~V$q zSC4BlMPYdNR#7TQBYiSFT7lA5;bTc9E8Maq#!^THUND*@Hs;5=wB@Ol@wd5HqL%UCS8s_m6u!7nmLPi#Mv z9~}M`{{S%Thf;T53+2|`%3%5v<|j;T)$7_kXL8^^_Mb7ayFX}R_YQkyZhfPiulst9 zxw|l*!sDu>si&E#B@C)NYWrxk~B2btfo<^q%#l% zT^#Ome(reXy>ihxpB#*|iFY=O-xx{K=4q;;{>n-g_!8XR8Pr0m@0!P@w$ ziacbKVQFY3-FvSoxAj-nRqb59;DWM;7l)(D)5RopNkLaFWN9>RBZwo4cfXhN>0^1QDd*p$q}2tw`WH zs1KEW-|{2jkIYYweGA>4#QlZwujaj0U#vbm_oh}%Ud`;jviU7R8)Rv^N4=;v%?<}; z?{2#7Nb2a5Xl{xcDqOBJEcH}*XeFhNp1wxzHW@7DPp90jWU&E%+=db|iYR7j)ljiA zYIEYLqPSEcVrqnWyO*xbkM9kt@s>0pB#qyWy7!3*1$%``uw}_Qqfn~HL%nx*%`>rb zdrRUT*TiP`eg`+VBHdk!xbyH-Vrcg)ryEtfb`IRyH5IuAp{mAHyi?>Wt6I8-nWdhZ z7|lZy5rvl5ceqI;GHx$twa0M7TxOC?6q?WxNKs_%eJJfU4u(ZmENiyeN_N;plTI83 zW(dVdaG*MAENPzNq_C;S9MdPs4*dCB@Rz^7CUu|BT&}~;_5T3PnX^`;Z?9SKz@mAvUJIiB6bNRpH)D@G`*6o}o&b!tB01grZC0253 zdW=HUMI|hc6++ml*)|s4ZEWr)mN8=>Vkstx9IG-CSoWl0m4E=Wj=&u%xn?;#m%hHm zFD|E$T5BSTSQgXqX(QCsRAW^^H5BTx`xoYKYy4*J9=h3|De~BsN`~zMwTT z6mycupc1CF{5(MDQW!U)b!MiE;?&$69*Iijr*Bw(q82ilKPT<8* zZX7;ua_8j1)6`3i#>Xu!HAIW9YN+9kQS7^I+Na&+NgjU#X^*;BQQ}Pcf6!u!ikGUR zPRimR5IBlbCRP^Me30#rfnh_?pBr=x-0nn$K zc_3L?nYQUJJXm1yS~&$nEi&P;O-cg_fDW$Eduw}t9mPoLt)kVlLp58?xh0mOl3`I# zSSH+A8ELEFsSM(-p0a{SWsYmGc-=@O5Pga^wb8Y0iTIWpAGcE<=UVhMAkQ1+upji zI_3tT0XHkpBH)kl`VKwstqua5djHee@G-h@NpbZ3OLK6fH_)#i>-$7N8Kn>UtI~?* zhlgB|h+(ZCQnM7XVoKW1RhV6Z{{TD#%DfadFAN>e2{P zYw}bP!S~`Sv>k4QW`ezO)U1FpBo=EI8dM+fwZ@zO0AI(t)2a#|E}_psM=qr?#x)i7 zg$%5JwxDxhz<;gpLbVk=RghyoeK)?}p(R={BNvkXg=OSgz!B;m^mD4cdq)s|;=X-C zZLdphY9rO;4Q(JWW%`t1aeICZkH2Q7r>Yq1!~I|Ebrx-_PV8M(3)zi;3RpMSNcs{_ z*XVuJu0cFH@mkRN*Qo8Z>0?3rD&A)C6ben;`jFi5a7QQozq)8sP!C#VTCgC{{{TL) zF3hL(X^8So)6y(-oj?{JQcdi5_g7r$^Z9kE9GyL2eUhvQ5rl0#UdL90$YpQ$pKfUt z2Az1V1!<47tPirGa7sp@h*HYR8LUSZu(Jz;^yGV>PV9_zpfRd~okwkv8-b=34KFse z?c-Y&4n@V!{8Qe_R}{xyD_W`hdWSa2h=sC){dFMzwqb4$2H#KiKI~%yfd2qLUMX5? z0<`^|VLK%_(F&OWD;kA2Ag-avTXIFg_gyt?tp{ER7KVboavLL6f~Ovm%2XTNeHVhm z{15c^zYTNKWdSER{{Rg-#@iY#JVrEt2vUl`GMf;L0rZjnx4&r^prPu;MhM4PKe(t1 zX^J2U0#{0bs9#A0gK&O;{SUop;z`e5&;~&3!(v1f0RVAjFK`d1^#&Yrf2sP9erUrS z{3rZ9dqAc~9YZxG7Kjro7UKqeDjCF-}EL?|z#DE<~)y3`zxIEwe=RTMpVqU3p2 zy>`8S5wQ?zP*`%H8#0hCrr?!7QGQ3gv|^xuEB;=zVpigM<^91xqzF`%3&xcL@y)>C zkI&%y){5kx_`bX&TI5%(jj&>I>Vzvj!zuu}4Xhb&a!U>^$GvE!Kp*j5W38CQYM@rX zm*>|wwj3^0c(oKNq-fGjiPQ831CRK6(?m0;1objqhaI%EHnQmlN7M2{ zSXgTQy!+6E4(=nbcqvsUjVb=G^L4>G`2#BWgI>Xa3vetOS3g^Wd;UG&!vq53KP+|Q z5^xJc*EHA>b9m8#9+oHxR{Y!*7AKC&!s z6pm8=06;&W{+{=Y`t@{53~=dD7m76Ss##M10H={th$Z=0C6mY8~TfoMb5kNz&}y-_j&-_F;2Ee>>Xf6xRHp}V`L)W*o{Eyz4;&1 zTi&#S2&&2vA5M~aJ*^E$c_T>Q zK+^HGfw4R_#{}s-4n6OU06jEg9=PcPU$CKI;i3vgxf9YZZa=^f)<0X@--z_;rZ%lQ zrN8D4*Esy7*$Ahl5+mbhS6LNeRFgxUYHU~OYZK4c*$vEIB$ptH1A>1q^7XmmR*o@F z0RGOjhWRmt#BHtr0F_SW^ zDAfL6@m&?EYDL?Nuhz%wZ^sAnJ((n4bjdw1uuy-i{YR~;zmvbm%!gV0S;zOBInDKh zpXI2e+<3jk)!VL3huK>?gQ+)XX!Ukpr(y3|DRWR@cO^tw3H)_QO7KL*sjA|ZIUIW- z-M1<2uf?Pit282|Llk9MQ%P1RLlDBOI8 zofWrwp1ZRsC~NkfROI&t!;5%st({xD(Xw>4wCeE1PA#$K+amJ4lfJ6ay_vwc9(R^*!zAO_;VQCRemcqkEDiz zlAzW?ade4CRMST_L2zEkH#&}hTMC<0lKMbXA;rkw$|X1f|6*3669+zlFf}_ zyYrpC>16A;JaKM}v8zt85hAJpjix0g31xK^6G^0NI^H4)PNhAs-8)^lr8arq-B(dn zl}fy&OB_l1u*M{!g-Hkz-U!MNJTq9{}> zO2<>dq84WTSV8q$$xvhP0Z8B7`GAw-7{%G%mYc zazm+EWGcXvl2fbn<{?6mKTkLDu?K}%_8E$2fg}n#xCO(wMFi}$~0AA_7O)dSLyL6@`wMAHUQJRZVOEC>sYLio}sM0FMbu?dd z&3mQKFwe}lNP_9)#9)?8verE^gU^jsE}huCmob6E*c0Z;PE9q zb4oW(eit`VT+U-ylBG4pslFeIk&PH;B~X&p8p+O)E=TS+Ev$QSvo{XKKUq{|T+lM= zl#M_TXnR-j40Kw)FML;r;=fwMvFP*flipKq*X$kJx~TDxQPDpAcg9rX>hL%mlvNZl zVm7hFQLP;%RBa7Ng^b9HJH(;8-Q{j>t*5hMBZis_Q(5ya+(xE3rbPe;R!ITh^A+vx z`ZuZ6Awq&Q8CcOtDw>GzV8pvS4(2qbkQbwu+5L~bHiuPwUhV#%+PHo7@>i)oO?Ni; zpW;~GioX!6_V;A%JkHhJox$3BS9s(0{{Uv~$@i{bJ5iF``(Fv3-B4}nIHRShubE?{ zdSNniG*Sx*t!`G|cNWqk%c1-jYuKo!1tSlw=&CaL~Akxh#G~CHmMrvLhMN-kVSN<)T^n4Ka*b} zK3VQA;N9EzY4m2~&TkFvyoUDL`>UvX&JMfk8FzkCzINUFqcgTQO*VhHx)NRKRT}1U zdqNG>m7$@{)np$ToSufJDI*{39OG?iXB=<0Sw7^3zC4=3q3&^8a0r!^ivFmPY6SvT zih`S-bl7KBd2S_*8EK#=h)JNRSKz*S0}K&fgFce@*_guYUg*eoT}}gVcBjd0`JC-8 z>!|DOW*cB_N*&RhsjSJ-<2w3>Y+-RYoxe-9GL_O+)3rSkQX2LkLeMIy0q#4hhp}53 zUD5zbyp=4@#1>}YbeaIGiU3Fm8$!nW&o*6e8_C_)HHtXsu%XG&8nu##FC|W}rwc{a zSTnPqdURgi*i`=j8aL<1)a_o^%Te^M@t3+b_8)O*=g)1bdg{n>m31;zK@=kkK5(&`=6j2ac-lp`j3U0JRgji0O9VR9 zid9f(1c6);)Q)+xm*?9dyE~Ick6#ikEi8z`0;qs?>Z>6vrxpC63$_n9nv#C7H~# z!9)(J#kM@wFYjdBwlW)%(3t8JrB$_LY zCFBKl1(cJ3b?RjbYK|0WED=yBs3(6Bej3l#xGw(O{ozN7t=-=zQcMo}*w`HPMoSmB z`kisvEFx?N-7{0iCVxAU#N?f_c@=>v<*3o3HxcS`E@IzS`r&*jb-K;s7a)qsT7aR6 zIwRn^yN{m$OmDw)WSgGjVR^Qz!E0?0@Rh(0B-9z?eI}HBC^TxI3tSf}wxN*uqw;sC z`uD2^J~O<#19|nu4K^EXcQ3~ekUKLEN4e_u9>=ZgjfCBo@YlUC_1#m|JIiu)(qr-2 zjPBfh)wF9XsjISa;;8FuQyvVq{$#O~uhs3=?=FTcrb!?!?s8g4(zWd*I)0!9Pzn+R zk+<{a&v9pMEzR7qT}bGxpm_cr6ps+<2s9I@6$XZZmNbA*3sIpMFt0Mb;jS?^qWHywkqp({wo2F%5Mz5BO6UVZzD-bK@CNGCRiz; z*4H85FKr&)+ikaDDv2IPdQzSJ0|>Hw3bqz%oS)SSb)MK!EtEbXFTfY26W zqOF2|gev6VGgrKTE_MYCJY9F!9i6>;^Ko}a$Zw7LAC4VghuVEz-#_Sk75v10H}wu^ zR$;au&h5LrKJqMf`|50FHVV3J_lO&_8M<;_G{|GIlNwWw6>NOv9lvGGox9#S8f20n z#vcs`Sp>&A3E9mB1^n)aK`xo)Q3g`LvUIU-p=dBX+P!YTu&hN%Fc_*uG#nXr3L7ih zA&kM$e;CTuktRa6o>{a<=V9!Nn76Zi5Vw-^>Tcz6B+`WN(V16DtWlBK8jJ-sz)F^2 z&hfuAa~kf~kbdm7YkjiQSAneRkh@b`$U)PB0;pUNS*insjYaYos`?LWZEV+K^jE}= z&FWs?%jB!DblZ#Kk7jLr)m0uUS}Nt+6=|35&D%lRdmDUYA*yJ17Vg`Wl2g>^i2~C2 zB91{$&F&Pl%MjmSwYoxc41>ajfN#@Ms*Hv><5i6Kh1y1|IuK|F798)g-)+{n)0wTe z1#K>hrga*L8q3xN0r{ZFr@r&c;{{XG+p2YbP-dHRzUGDwO)_8uI>y4GN zGm_?Ny3b)@=rPpdqc6N!n<2RS8zKBU8mgSEl51MyH-%}SFjBxt%=^&XeymMDiE%uI zq-9+I05qyZ7J)*jQK)euyh&yba~CwO_a(ipqRAHB2qY3|B$BmP#3MQa0z_h?jaXoH zZ+pAurq_>ic=vb3{^r}8Be=Fc=-9tBGan3l3$J#@H{``ubFH^t!Ng}Oy0@^i-Ft@E zd2BS<=gd^qe;t~NOq`4-6Rk~h)LPS+uJ;H5-C~Mch_!fCm62SLMKV%0DiF|x9wiFZ z0)iK*0>_+ohqZ;?;p4rMi!~HBk_W_pr>J{ZF;&wl3AgZLPUMgT-b$HnV6^*1ZijW3Vb?tj*@B>2=dpZY_-5ZvTlRjxSf~R8?U9iR}J1&6kC~K!t5@^>3lz4@134@bi0|d zxhD1}l|q^EgRRb5rB z2reCc@z-_dzDw*L+T3)Q%5ACfTcmTp8M+^FtwK$?yN6{C#q1o$#qBNOw`r?u@V#xB z+x=I&Xm+sM)O9&(c#bs8wXzK*$~R5bWwW?NmsQNFsXz*F;ggBs7|t z9aMY~=~}Bl1d9N-7HW=*k6HD8{P~gm#_%6MGdnM_x*M!ID-GPg=&$3x{oPRREMH&e zw<_eYV{~i^Y(_5!jOo~O8&0}|Az8EV^%;m_-f?8Ju+~$G;R{=N++kg!>N$jB@_SW@ zglz5@u%nRd)DGiTtq6#qjWuIHQ_VceoA#ZjWLtr26~j+7vH=)WgSlcvTCigvSp%2W zK&Sv@UUtU*V4d+zoxtpV%gFCKJQR5xYiG1YXd_bhVfG25-P!@fr)#P#iwSt6h~tbnTq2~b&=O;jG$ zrCon4dzoW*4ZWWHL|35bG6a#)TLM*b4bJj9f>H2H3d}-RA*!b-r{qet<(?7 z8$yYcTn4(jc-bTUCRbZ~TAIkFi{nhnqP0{Gp=9XWb@qP^v%5x_buP$@u_x=Ov-^_+xbmAzvvw96C5GO;VVv3<+LfyC`}-ICRveDh$<*WPMIB5L zrBj@(%zhT$yt{ao-%PTD8`V(g?)@1V*sFlgBLb^d)S<9|F{dhTmhCI-n}x}?-XR)b z43w_3A8OK| S|w}<*gs5GXdTD{-VeYM-)%n#$X&fI-92VL}E^5E``MTPLsJ+AHZMp@Mlq{f=>mGPoasgC|C1EC*+wscuP})?g zhAc{y2-nNepEA1NsI%D4zU`bI@!Fd|5nWR@1Ge!L8?&>v&35?QxtxVPUfj#$@l;!f zG18bi>|0Q+EL8N%g3Q-_)XgOX$Rn;L<=y5uV@SDdzKZKB!k-QwJ1Vgoon6W38iR_@T+6|p9SCrU+EWl};vng0N8(|KyM5tQ)SX_o%z*tIoeLV>HeU^?o3o$qdM6d%=LN9lBS{qSWx;+&e|zn>gb`eM5Ia$UTIqdm8WD;uM*8!3zMZ)5vA8XbC%Bz(LXKh zn}E3A?w`ZBWl~_ZgGnr&FT*X&*a2eHuu((5it;1}ClUP06XLGpmuB}K!^cf{%Fj@BwRF8h zG7!%|^kgUra}YvWuKxg=Uw3XF<~g~#GvjB+S^Gab@%Db!>mK0wCELB7)p>5J*|>~X zP~~4Ou{LKx?LO7nxPH;6-&=<*ldr7YJC=ehd>?H~MURT6vYw)@nw&>2<7sVj*Rovc zf)#2-tTWFuC<;Oh#T+9APLl5B$f5$;=YDzGto9wlYuYD{^L4w7!a^z0ZjM1ErDau- z*-oHgc|w3=eJov2?DT)mjmz-2us0#@+)nu2pA36P%e`^^fv`4~>FizM@!PqnVH6v; zYwrHN+E~58yK|i@+BiIV=O}Xcnpr9_d#P%v8jhhd0(xM_EZ;WS6qaoalUuxis9iOP z5m#y!QqhJ5jWsaUMOLq9dy=`cZ`y1>b?(<<8+CHYD*{2*>b?~fO(@4%ZavQAlvdD6 zzn$l7^yl+u*&hu0PvXa3@4fw++FvEMe}C={^6Y+-?Ou%9J6EBwn`?UDx8C2|d)u@2 zp26&Cs(TYRki!ia8Y$>1KZT^TR3z|G1{*cqwX~8=xE6pyy0o~Yj!g(vgq>iJLjxk9 z10b3a(4(3;=awusOX#exqrTp5BQZw|LQDq-^$o_64wa=F!;(U^B0!C#FvX0`Z7reS zn>w$&sW;4j7keVJXkhnV`P+ZPa=31>-Md#PYWCeHeeIg8MP6(D4)4gqQ&aDJEnPlG zX>MsD716FHwxY6_CCfXQ+qVfWZsJO_7Y$ZjE>xugg<$GSS4q?OyQzW?JE^^qY$WE2(CdqahYWqpPN*c?6rL z=3Z+HF94;YA~A2%)jMlokz1k)=td=2uv!FAHF$&|;(sJ7lxrwL0X zWLXF)>pX@!9Xg#9ww^9IH?xZ38%ucZZQdF55>dq&3p*Vwyi|ZkX~?ff9H#}vuP<0z zT_Ib9)T9wZhBT=1G~zx~=-8HP5&$;;08#X7assXSztjDHYQHXoJ#yD>2y6bJ3i^Oy zYjQ^e^Zh;gzq6})p1TeWm>UnFum<<~>E^{r{{Ua#zI|(rJ$nDt*~wTa^*)=ARlzDq zHx?JLH~yAB(SgIzboMGedXfx;fg=Yj!O#P9!20R6f{=ckA9|qA%dPRII>@XPh}{{D zj)QdrQjuX|ZZ3En@$ba(HKls-u1z|~2uIY{E2`RxfYGyk0}I;L)47%k5R&42O#0C@LO0jmrQb*z3}b_*5_b+WRs3wABTD=RIu>0p1u zpLGRL)H}^%i)lUQgJql9``M%V?sW zGOMYTj8hFOBNL^F{?8u#6>+Q2Bd-8xdd*KH(Zy=B5ttDh7(>LiRv{ll6Mak191cgn zFaVl$On!8EX0Mf`9k$=Pg09*3F4|*b$^XtHQb<|!dRIHj?#UirY zvijq{jsE~Q;QR3$DaWl9@~%3{B_6#lSxH||0FnGT{{Ufs>F;Dz{Q9i{u6pIIK+;&2Qp={+Wncl+KDJUhx`I^w-_ zWkxF^xh%4PY@*5-0zu-$5$|*ydeIdGj=BtWmC%IQv=$cx5JM;+8?}wV%l%K&{qgtW zbrDSUP@sYK^_-*}x7&sxQMH4lj!nk{*Y&@>Q0Kb6dV|x4T-G>s1EWRO$4Cd0^}7E6 zMh4gZzV$;>O7&m|mma$iLR|jJaq0{XomcdoR`ilb)PG<0{_a+l&sEX|N3UEKlAJ8I zQ~HdF_|y0yPvo!k_wE(14!i&d107^q7>PEC9a_xC(i>fdkO2c#$MyPq_Hb+E*Qf~u z@jY-_XbzCb3%3L)3J(MYZfsjm`+t7Oq4{;~AZN?`9c7LvLfgcnOBH1z%m}dr8x33z zIpf}`>BN7l9e60I#yZX5rzH=FfpApVASys5Km@5H@$Y4E*7V?kgVuG1kgw?hnTT7c z7XGYj2cH`M z0I2nuX=%6xEE`E?P%e#f1hzN2k~!wU`_(v}yc7~DG5)OeoYT^kvo5gA%5;u@NU&wU z>iqsLJ^GXw80z5#KRo{co35Icky1BcimPy3lEGC$A&DAJg}?M9d+-FGpHv7Abz`n; z3??+IrijW=CNioSA6>b<=_~8EltnxIqRC2K(Xrj3nIBKU_sWp z-sQmj0&nibjw2j=ztzX8fJdHs=9ai{00V^}k`xcB>0|1-{15gX_375zt}CH#gOw$; zvXgLs09@Pvf2Z{K>YfABt(;S=w`99|m(mrR@o%U<)viA$@$bf}0I!hiKnl~WQ=LdZ zKqfapSR0nHztDh9tU>qVhR0i=^79>2@6L!8qxg@GC0Syjonw6(kE%Dn1Zp4xZVw{< z%I1xMm{*A>_71NukRhk1^Xo)^kR36+w?AiYyo&z-ntZ)yfFwu9;uF7&0dfG-{hN?K z2itabVImrvAZMV({BCb2G_4!`K>eKnQv7z_fO=zcLog@A);IcF{fFn;@omKLuSo>yo;!Gd^D83=ces(e@l;V4U*i@oxTit)a3e8M+$$%bnxZAUT)*G#X&($70=mP zetk$!=0UYmHB;7qB47ZS0;Mj+mOX5BIX3JCaVD#OuY3Ej*zFFcHV_F<3Lp9uept`T ztFJ3^+0-N3A~IJ!xc>kTuN+gUYy8PJbE5;XK1L!Ew}r5KGE(;S63_mTd`eaL1QLIz zwvNdQPz|mlgTUt;F;71~PoG*mt;| zm3HROGCZW}@PeI^rGkNTApl<7enW$0w9%z@*tCICHGhX5xcfS%^*feGRvTm>0DQmH z51}4iK$H28Z5pYPWZB;$VuBcDrfONX&d!;gmsE|S5CHzS{I{^Gas zGq*w*kK)Bo5yScUb>qq$xW!|WX@KL<)6$=B`m5ARpXNcg44w$KFMi1rHQC<-wBjF5 z2#9tYv1^V1uonLSVeP@o)?k7xA_M_ZQffb8{{TIHS?a&k&Rgse?J$G>l<@xmFQ$5x z2lFJ`B@df!{D6i#6*O{fZMz`^dPzo2{_yzh0l8&7+fTZGS8Rig8(c<%EvWkXdi?lx zuj+3t65sBo066|E9v|xRuURTTnFht47pJM(Um&EWk~T*JXl=$vTY`XT>>WxZ=En9G zKc9B~uiG!dw#QIM;yL`deV^d#W0JXK7I?O}RE%+Ill~7*lGA+m>B(K5t73QDt#u4v zX=2&fDzLd_>_Vg=0eL!)*4%q^?Fkch?Xi{g4NUrGl>2&6{Hd|BGQEs!z|$p%%YgJX z>!15S9XQ4Xk7Ret`SjEB zcP@=2SS%nda)0Ul)W z1bnN5_VlO5eBs(LahsEVSH@fSo}XjnDU9!??Iwk(rG+oe{)ebh4D`LRO3!AVci6d^DI+CrQP!I=G~nvD zDH$J6>+j37FNgzez=7we53q5rbH55`u^#L;txY9%+9?#Su|wE*KmtWV+Z!Ua3~E%Oya@V4-(>6ix||hKEE}I}NwUzl_={?8 z6miEGt3H1=f^<={oK!MjaL1r zdfRf93xCRqymnB3#Gh^rjv^}CTZX5bB?rsnCcl+BaPnrtXzgk}2XXS?J!os6_^zd= z&!3LzAB{IBZ3SYd)z$m3tZo5fB0jPd5}}i zF1V+k$4vQg;hJ@JRNpC_~!vr7U=BA&<1NKT5mHma&9Eo zM6s(dJbs~TT>d@Tc1XS>x3JHfEou2V^Yi2K>&KEdG!nuC*?YrxjKADM(I#JD?-<$|GG#MJVV@cHW>hEu0o;JV+xk*XggF6hN`dAae}=Ws z`l;8OlXhYmR@4(p3OS+t@sB#=raV{9y^3K6aPKVZzmH6*2Vd`RD>c+!^w@`{Rbk5M zZA0=s`E~?R{^7AcUF)B=r-w`)OW9e0eZ6o$-=FbkrAqwx=~{IAb=J7ic-P>V_)D_#oKBb2bmv;}#r~d${TOy&2Y?g+!?>s(d%k1^*(){h{ zs>u8j?k)UQJIP_!yZcfp0Qw4JKmos{$NO)0{lyNI{{RxB@c4(Xk*z3r`j5A&#mRdz zBKUSnwI_p-LOl9tKQ}%*Qly1*o9;p7)O2jU{5PZMH<7c&LxuMWqcOe65vw`o~1Y9nI9HjD0*(m8kpiTKp!@RXbE7;vo98guN~BaZI-W%5UTsk!lFKB~2?kDDarP(J$lPTiozFNyAAQT~?OpSU() z2=8p+@GHT6_WRM_m%R&Gwrqkc{v{7%aI0%$DY{>X8SW}iq8Yzc3Thqdd=VLQ}FM=iCME=5Su?Uyz09mmMsU%x%J zF$qhlbXTvYHZ|xneP_4}{{D>R-H!}XspAtValswEuF(AZ?TfUre)z;^;VUs?V~-(b zw_qs1A7V?dy1tp|L4vC}&{J>bNqIjQke#|?vy+; zgoS3#He1rwEAnpafDGl+q#dER;J;nT(R2DKVKLDs5Em+yM{D=%=bz%TKQE`9wy|-R ziEcn&qqr^l5~gzD@7|CqDpVi->!AFk2lssVvH8r(%BbZ-uEAiu#&Ri2<_+9$X9qyC z@8GU;fEQH*ADt~r@Eb6U6z1(IbuU6m&+Lnr`^+Vq4>!f-IwPPIBFLuFn7N){{?${;9Pz6-w#P1 z$Inz$6eWd+G@lr&Ee{IPlmF8E?plUGHBdz)bRN7(RkLRZwpHF^D&PjIaz;e7R!Bn? zqp_$viu+Z}N79o|d!Ov=?$9aj?0{nEQV_C)18n19R=2gUeqYr!AlK%WR$W?us?L!7 zY1iV5_m0W@i(`T{rbZG2erjARmG8~?jiXWF*@|F|PL@fFK*~l%oOzN$5%S@~g98zt zq}kzJjee3#%l`MVgPV#SM(5>@NZL;8-^!$2G3t&=$y%d@`kEu2(@_oI#GU^=1^i-a zbG?r_xks*O+TnfI{%==FC2@-z{;l=ssAKpI2Y6wsKWc3;Mi)|bw5+-Zzw4hd{?%UQ zTjS;X8NpUf_&9}6%V(1|w%1Sdf;UEMRM`oKC<)Z(36Zw#z2sRO4>`kdBrc!6H6`Sh}Z4@%q_*mYzSy!okBEL2E zU*hf1zFDVdjd~dq&Nm-?Ggo{@a(r>dFxM^lR$FB!p>?HrsIqWvL#fbEd|iOoLbh+= zPAbvUV5Zkss7;3^?sFmkFP((5|M%0{dd3IHo7C_}5t~I%n?PIn2wDkjdeqjTN(omU z7dg7JGq4#0m-F(P1aaSj2V&DI3&gg9opYcgdjb6P|`>5XGmg&Xg8MCn| zbu+{Ve&JODYNg(!!i(3}TI zY3a1-_^x|~dyaP_$gZde?{`Vtp{N=lX8&<^M7(p$RRe)y_|p?e7umX-q}QN~(sr%8 z2l8(kDL$4<=>Uo+cKZ-AUk?2jHRJqNLXu}{c5V;$_u?99Y>qkcsDm@{4pv z0{tSB(#W5_O_%$Q)$*co06flJKWz~GrWQ(k|rG~cv)#2>G8FXXAhkRx>Y9?vZT#UYS2w@D@2jk6w zMrRcxX7$)Nf_|hy8}slx!PBxF8idt=J}Ar5mIb@oA$;cXT{VAvqpv9?^&M~kgEp`6 z1NxBHEp(_QPcFdZ4o+Hwq;P<#!x22e9BhF1IiZJ`dv$~)N~u>j@Lbm60PZ>e5e&bJ zQKQF-P_?YAjw`?ig5hV{QI7mVVo1bk&3zPc6LnHPoYKOTPtCRH%5NVzrW|h2^ID$P_`+4dP$;9&`qVs&I*;!q#+5{=e{Ott4`Tc36bJCN2b2Fm$plm*S+qM} z@&dJ5&^9%Ejc_s9{?+$c73mQWnSgI@H z0QfM=i#f3op+Xy>dKc&L83^J(OZEPt8U@nr`g40ax}5}e@7m_v!yU>vw``!hO^i8}7?h4u>#I|Z# zFkjMB7_QsKWK)eJjC?v*N}&O|(o%^)6WF04_K^h`PKm#XvLP09d_UJYV z@*p}?fUQYq)VQ?%nj~=@|4c2+cTQjroh^>9)jf|QJY~P0BcIu&nygH^4Pq=b#HfJ) zrFGqEC+-Fc9*>iIAACUndL}<4@J(Cb9Tm%o;Oe#!4$yhndVB%Nzz)z0uB%O3Pn8NVhIughs2#DWQijcXdkFa=lHJ9%qbN4&L|wRiK9sLHta=rL zTu`2P|LKakTY<^ai(4??Dl|pBUD83#X?`n?lAL4PYNx!mxR9sy@3$ zqt{+io;bE+-YG6lm-Q%f@^7KOczMd*OZz9tIuTH`JO@`2EEq>;EY$vf)UhoN&`U)A&M{N6S}*ine%sK%ASl%n zH9AR3bP2zq6In9hkB!3JO7!In%2Vmwa}+l+q3B@-!Wn#dt^d}6)R%vl_+`6p?M^Gh z(fF$2c$7@6`9kVF%SHG)ow8{tdb@>yET3I999eEc*`F>rTitb$ z2@cMQu2BV9p^{!5*j>xGD^Qv@yxo+74lFl=<=Q(n@DxMagVQ4p_Ly5$Id-rK+nRIo z;bK%V)Y(gJp6jpV!WDN-fkW-28j|%h=ZAXN-Jz=!mrB#I&nN9ALtyo%pFp2tWxNT3>$q)M~4%Vk%BE zD%{}1-Z3%WVA~c2+14HE^ZoA_P=2){4+{U}^0`zVZwoaTZaH>}-=(aoGq?vxEDIjq z-Jwb!1(bnz(8&_COHaI#J}<{R9qw^++Y)~%2Q}TaP~71Fy6!Vew%T#v-t2c}%YFPA zd2~sMV7B=?&>z@1awOAGZ7A0ghP7YZ@5jhtf91?d%CdN(noaQ^rg~59)Q%y7ptY{Sko5@n7V`ONvqh^d(YV;;V4c{Gn)=b!RbR6@2qxI_b3zRT3h`>h!<-5$q2qVE%I3m2y?LUb=I&#+eK zKJgmIm4v>iPsnQ2?AN!lUcM%eH1e0XMu#4gi8E}2nQV5mhv_Jd;;jhdD>lL73EKhU zfn%8&)ds{Ljfk#24ZW_z`L5GOvmfHz%+jPB+S%TLzG>|hCvJV}(>oviu|N{i!d;PR zGt8W$_>Lnw1uW0=yH)KIG9^`wGtQV5J67lDwev<7&&G#sP>jkH(DW+jQBhE72P$3a z)pt~Tiwsy^^g@2qkNCs|-!)d;WQQg3G`o)8P;MxFb@J9eKFv>Lt2&cqvM0*bW$n{j z3Y&^;jF`TwhiEE_9MpE=00tc#AP_FrlpA4@oSt|y1L?*t6TsTb(atGt)m(dbS@JyE_j3c7{4+s76|D!}p)Z!-y_P1!j*DgG>-!`NW*9pq zL~)7B)uyb#0WfZLzV+WA!BsYKW|D@kP21uC0d<&dbLpz>fLDV4P`moF>laN<-mGEM zjiyDUIY8}^Y^=q8Vp;}!eus`>4mJ zHQws%z-#GSR+;CFx(-Di;FXlmaI<_1oln*zp-rK%LbsX4P23OF z*?DY9Ia=R6!7|sQ&e&duU|bvK$knF#$fEyR`C~2Z%4aoWXyX~QIk3$_$^EVV{;V=$ zja^4yNQ-S5Es5X&fr_V`X3n0Xymh`d)YIAj!%zaYqlv@|CAfZygW!@0R#_vcJ4E}L zMGZ}dnKR-Ww&h%pCG@A};rkq*k+Ik<1Tls0#~~TXXvQZMA#<<7MFV-TnX>cQOfEpo zmx^fgw>daEoV-$}JXYjt2YHkUGk_Xa@5eqF?^{w>wIBQCP;rupUZ|E>&I;L#m#^lH zMIU{bE8ZIIXt{Ir6Cv3$#3@9NlXsjsn7RwxL) zmzC#r_FG%;_x!NRwftc`SF_R*!`>J* zJ>e?vo42O+8C9)6J3sg1MJ6ynqkfeh@qY&OgFk+L?M2$JOOw*6X}*CQS%kt8)vT)roXDwD z2HvJ&Da8-z^T*BJ=!=)9>Dsk{%^bo|^lrvFS4X@G3bu>b#Mv9-cb9D2MUoF=&DuVW zG_j;H~ zIdAlRMA(BKkkxnmz82Bw<4=fQ`Zu%bvZ58W3p&1fthX>7BRmh!Z2bk(nb^D+EK?;dqc^b$(f zcCTMcS-hX(Pc@TvsE<6OPW6V#h-AI zVIl~N^`fUIigDAFSYjN2K$F4l&HbHZawdN?@C&^6%xxQgcoA*RES9^zmz{bZQ=P=i zp;6|e;)$Zz3Ie+<_l)JjR04bEXK>ycxjoGl8W@ZIbY&3cVNlinMA#0?{NMKGr^l^l zsPQKCcTaJERWYQ4#Z;Ut#-TxnmKdL!ghKQS8C3(C@tC2u=K zdTBHnL}S#614|eW`S1h!ryWu4%YNFz-n=Br;w;7C4a^5R*3NEAW z7Ji@Dxo2{Q55AszXf1d)3%Xu?ZP@32(O5kaJKj^+TV0@L6xjZDvAcE3la}PAi#7Z z6#ju%K4oGLz+I=Ec~-?Zfa{MV=E!}SJ9SpFVvnPx&)+sKPkW~1>87hjX3nrsNI%sX z>@L08-s_RK<(1jNI;fS)7hLIm16&fS++fYbr_IpNgjAo@IyeYgz8oGBE?i|Fp+xC)cqj~PPh%|V<8vmTJLTCnOM+Y}<;QtMEk_O8h4uy6^i6Z6 zfU#7UO8q9}0@##n7bw##8fR)jmykFL52LqrW(!5e&}&WPVK+wS^7{1lmRk7ce<@lEElc(u6cWMIxaY_udY zyGCk2Mx<6XzQm?>jZVYj!0^}&e-WZf^)&)&ikkgwyKeTfQlVe>%mj-U9q{$7B%|R~ z%SACtN3aof5)rQWdl0Vjaoq}xS6IdL9PMtr?WP9kRox>ULBl&fRPiX^kVL$75w-|1 zNviMt!%v?3qsDne#<^jun8wbl+LN*0deig}J@ck1r$l ziX?cJ5uYEd8uWvVpXk-8E-6AvXseli=U8kNq?Z@0;$= z?BxYx_vR>5c)2?}l!`=a5f#Lb!toPNj`Jk0Yf$3TBh`)tPcP+c^jM8q_E5eWnqKDL zM-CE|0!)dNbHe2nwSrB>qCzPHO8+e+{MF`3b7lE%d&esMw`PIaMdSp!Fp&vkcT`Nc zj9Li+5uq?V!vRox4;w&EeFpB-Nssq*37RimkJQKUeUX#N6 zDU%4D(PhL!X6lV5Xwn(AN6OW4MiKxYT?D6NFnM=pA`NBme5{}!?ln)mH-44XQE&n( zZSa0OI3k!8w|^p$|6gY9ByAKOLDlz;vb|RR6crwSZq+`-C5+I{^i0~AstSjE|A&mG zekET zHl_x+iT8$yUKk(qO4Mg^aic#v_t=6jZ8m|{#y|hQD3z^ASmR3_t|!;y2OnFATR=i3 zCLJ_1V_9LrEa>JJS3>q#MWS2>?q(ksb*Q#nKTEI8U{54pi%nde#M|3jjn$=-FS}Xp zZ8XD$75jSTMcWO_Jb{(gx(BB(95hdNeus&E3X^>*Rd~$yk8!vXw=)S;z z1t;U@!*cDY*H7vUam}FK6kp3mm$!;L@c&M#%piN%#p^^jF!83Mu|tC#)C?{PA+1_4 zQ?q90nTJ#TDzU+A;WuJ3DZ^go-i|-vGx*z{r^MD;>(s+xGrFBJK!h*-4ndqKr&#xz zfL}jWwvTX{oUq%lM=$>@t^b%OSW>T z6^b>Y|9{mS;DQm&bAQ5k%ffezb`!P7W_6E`zDI6(fP6K#==sP`1pM2 zcN3|~JNQq55O|GtS)KQ@v}OMlaW{^BJ$5eK2MQ8Y?;aQG9v5MgJ`lt&01;toyrjdZ* z1ge{fiLI6*4im&Cuv(KBsSrt3>Csx=1{zTZPO$)5hiMFFe-#mdae6~Xq#nJbWAeG1 z`Hjc@PFh_3Xz8q6gFzp2g3FZ{87hZQvXhm^ zA`W0!#BKSUKghWf5*~v{~mSFujZ|er%))S&NnJN(MB}itx#UV@bCGt`I;++ zUm+v>_McFn*(4thVCpo>{@9dIt!zTLZ+M#rW5>^m+H~r^wg{Ox4#xV})>iHWi>d;B z*lCubpsWtpmo8s=YM0A1IyX^VTt$@~R_Ie)t9-xyUUo9iS#y6x`1^zb7@2w4YQzKT zLoBxNOMxluxNxZJKg(KG83p{$GH)0zXQ_(cMK zsp;`H8_uC|e{CXgFbc^B7v_z6E$!kE|3j8op_2|`Ims&K9l)^hwRZ-RdWpQBf>aFV z+I5{rd>uy3+|&oY)4;{K>VX&M2E;COVLi3=waCRae>TfT&Zj(oJ`x@h-hJ``fURbf z^*!eQf~qNTG(SzMhyAI^79BEs)%`3$c8UYk^YfgF$6}BdYRwG1z3PP@F%7_cZ@e{T zexA*((OYuCo*0=ovXhy(F<;a3#J`QX9Ts#3fB%n)$`IQJZ?a_m@dXF4qkLUl5qf^v zg#$qPWaW!H{_AZn?f#X=m#>-UE0Y5gx+Vxcfd)i8tbzmFIf^?ZAQCEg4H7K$i+v}B z>bYi<*bR(VamcAfedcc|H)NcL>44%|>=d{s>`&Y#LE4F)G0-&?6&hW7{~F7Dl$o%E zC3c2aL4F)UIOHEqU*dFq>E`KKDET;{zke?Z+^IZnV|Y4=R3983UF$XdOHcKnott9h zqmDwl@Y_*8RizHqzi$2O-xh#RRSp%Y29NneHy*!$x*o|!Njo)gEoAo=t0fTX%)^Cq zc{xDue5S<`#-Nj$RUr?nfhy%UO47w)_P3dC+o<6VG*JGFI{7UKxt9JKRB3&KU!vJt zsGWbbC&`l;J96$>61jQOO-X5rEBP_+edFS&kHxjxT{DMcBE23<1V`~*YLe)$#2Vhl zc7+~`VA&Iz<(V8nAB+G?p7x+Gn&XD*LT;UVJ)X>rPjG$_dfx`kzr8`1HgUkQypZ3Q zdh2?+!am%ERdIwjr^_$%SSHs)p`k; zz{_%Ci{lF<<4{QXPD;|ZBI`1hw z69=!;e|b6m?pmOp&2{c&wwyBrM&k<|VEW+du0v86cdmX{m?yrPKh<3#Vt`jr{keAC zlBrZ%IyEH9;{P zK%?n3w_nlmrxu>YZWg?ws}#`hc?_LJDXEZC;s8m65dl8g@OzSm`g#sdQ$BsA+QJ|Q zehFRvxx|-_i$o^I2PdkxJ?uqPglNg-_P8GvCFeAi%4V_xw&H%oB2I4$zq#DLMCLV< z9QAbfhW%LKX1XWn$HilPhdYa;1Hiwi0Z(NgjJ9DMp7Lg;+QzAfsJR}hqlgAHanHRw ztgO}qM-pD}(g{oX)Y12smBqgTm?-Y9=8R zx}K3jfD=6~v{L1>Q-ZG)pVgER*IA<2q`c(-X|W?pelA$b(gd0&MQyyQmBU8}3=K6A z%o3Z8jMEp1U#fa710eu_h);*w*8o(tvCyY{_1?O~1>_TUDGj8rM{n#ay;y(qh098G zfs$9T7nT~umO0(e+8izQcH**8&U*Xe*a@L0<1rV<(K92wsozui=bzT!Tb+2H1zAjS z!Wx=951W!dLh1(F>A!)^;R#<%JTjt@L>}kpr zn6fmPdio{ei}ny7ze~e4Ob`F)*H8-=?i^O!WMW@{Ex zUruKb3=HoK6Hl5rPCBeeX=l>8BR@``2}7KNSDd8n{rZOHRb|&9y7n3F5>B_AWD=^& z$>Ey&ZSp}~ouXn#UBhJjF7;)oa~k&m0H_^@mpjHEXS7yYae!L3CXw4%nZ$CVW+Qkl zb?pXaEuG~7!%hxB+>a%1ugcRYkJNpd)Y7_>0&kC>OlXi~3f)>$JQC?l=yoKGZ*e8l z7mVlT-9B~MpAU^ujbe8#d$9LZd!Jln`QGs)MR3bL$dy>iTT>Iu?sqH3j%$O$9_S6{ zT&E6n-&rAh3{wQq4Gklf5&chY8|0k<+wU{VKvLS&j~z8#6r$JLTi~h%IgmUv7QSMnYzkMK~7pQxHHp>g9rPudrw?5Nw00pZ6kQt1qeQzE}7Un#<;IjCsEdD6(Q z#`2uiNrYOrPv16Mj@B(Mw04MW(2q!4suTA5=xJSkN%TkIpI3tx3(yaR42m=W{F(sO zjAxWS;Q*maw&wq{yWsGp{un|>M=704&o6a*qhK+m`4BmSNfJ|vK5hEu^!J#8FJCI% zL~V;fp&*?_#)3#t0=GDR?UjK$#WgqMYL#0>XTA#i1BI9j~ldYX=&jmyjZQomn zk%TLR>d`4~J)_;qz$~`DKw?E5wJpc0K3PQHfd0!O8}t4Gg7g!Qz4PdG5Ew}KFJE%?58dVPk!FTx${l=T0Lhyx+<$P z39BwlJk9|;G4b^_s_-3p&1gFn%kX~4ci!&0i>{hUoZ(oUDSY{Gu7*3Kw9}^}q$N4m zIkalw)G>LH;VQ<`T&sFyRmuJ9*NDPzHKuJ53SdL~n^pZb<64a;D&iluby5ibiz2^& zD(e^0k&K-=W&*-LZRVz_88s_+EzKusKp{V4GhqhpRpf-wYv<7_XIix!+}y*06TXh` zKsWmUhmyN~PFZtRneU|ClFf}P6vNMc4pB61_v8R~!NiV29sw4%(324H4}IwH?WxT3 z|8W6pUfW%ySc2{5_B`d+NKWH1i2gTUA|c8RN97Vc=}h#6KGAtkR@i3u(nu+xc4g9Z z=47KzR$qyZz^mWOqU42K=z3eh%M1j;xeD_9oxixmU5!tD=xZ240u3{XVrF-N$Q6vGhp-ei3dz;2Cr8`>LInftvRD{gEHOM#}zKabGPU_G3JcTY< zoPYTLTb_Ia1jvMq9z92=FOn;VQ0#ii>9IpuF_#mUzzj1fELH>FZ~I2@AtL9^=#|=g zf%IcPt+Le*7CC^eCMupb9z`NZ7bT2`ZM=DmxJC2Ysmx^_h*K=`AzW_Qp zfZXeS-VaF$tm_7}x|q{c+xG}?1LCD0-f}$WxSGI^koaTVYpgPn)wzi$JYYJiak81L zm|WSJtaYJy`j1r(eS+m$JX0#t=~N=$SVoQJNuW+%+KP^RJW|C_bWoP?3xzp<{EsF} z>^fys9ts{N-a1Jo)qQ@W7&}+;gh$9wusC;GfF+Rht(?vXUD^HoYi&ZvGzd93;~<%# zg^Scq@E5L>Y?s%R4+8tHZFEdYyB_`Y)DIr_-FOLks@1@g2>{1nc9K~l?^L(TzG_Xf zw8k6XD2|{4;LB|)mN4TpF%2-^9)__6!IS8O8LmqTE+4^29S{C=UxFHZC08@<-$nMG z?;@m2ll~B~DB{I8X6BzM#W(L@`odf_fa#eKdi^N2{*_9w<7Ae>-1~QS$B%E#-lOF( zLn1AgBfQkFZ9QCy+&{r??(Iwny?FJ(7H&H~)7V`^6}8y!6=Uktpd03 z@>cj$x9~X1-*Y+!&-~k2wp@@9o`wj#lh_?Q5wZ- zJfHwp0blpkNRK6o5Smf;=!iM*Zj)St0D%wT-@W2JKCXn2_T%H2ScCWR-qD_i=RZTz z)l)t*6Dw2dVG@cMlKGWE$XvQDVbbWbs@RDGb`p-rcY&gh`8`yDtEIU_$R?&;h< z|6J(8LZSxBRgwpc8#{`7?PzDQwrll>N)A$_?aT&AyqyR);##6%W5oslSBwXZ=tciw zDarq5Fb3wCI>D-se>F$9$|w2|wC$GaLu%1W4V&=nq*EYZA7@I=q{Hx^4%$CP$GTGCABhktWx)3;>k0D1*lQ_~h zn8*6i3Bi-Deu@Q`rHbns2dn{H`YA)*Ro2bn&T44OJ}MA4Jo)YJBjzWW>;BZCoLZ|C zt_9y>v~kV>!}gjYn&?xhEg;uEIH@6a3PF)iFL2@78&@+_Tw}#eov=e`(jU@^g$VrtU+C=ai1-^uhAIrYX z3!6Bge~|qbZ$JC7EVOyPYDy>9ua6EywduT_>$6ROIve1Xi5t~6O!Z92m zm3U`&mum2ODKzwa+E{H>UMytrq?_q%ieP5O?l$d*?BkS_X12;hXcgO?HL63=U98^z-k$l{wh@1MMQj>{R(u<|S&{ zJIjh&KWaJ--u8|e-}*(qHZE)RhZ%`A<53^rU%QDaU!0>%2=GObQ?Vxyg$~X4)N6gR z2j*u2<>xU29Ke?uyCucfwe5X(tDAIy{B>!$Hb_!8vp64d(NdBnT*fkAqHa!=mHmZL zj%p`a$Ck*KyDbI>1sViA|9o#^Ytn9uupTm&vgQDUqlfUj%wC{Pt^B1MvrGSMQcd3u z4A&_eh+k#Lx7xxKC+!{u{x}mo$5eAi)dHaw6Z>-O*BX>E=nIhSCNLGDLnmZ@NHIEk zl|$nIp4jNhAj@v5v$hnqeU4obDNVxkMh#Qg6PX-9@#j|~yy6)Wvn$L+{@@7uAcJ|W zM5!=XS6`FaWYES>=^Fc)C8b63sk%z4zgN38*pYNsIoRv$&UMAokYEh1qb;KP5V99R z*3ND|e*D7F?Imk|-*QR$>;_WaO^7k^+b){Lqwl!M0~yqmriyMA=s_ps6KDATlB!dJD4k}u4Wz8q+y$D z&ReHmnYs+3F&Yysmpl+3AQ-IIGajz`=}m9KyRuXG%P{RiJBwNJo0c4mBK3(gD9hF#yKp5Qr6ER z@XW-Ap3)Aj#sXy*$3?^FKGC3eK$Th8c$}^Tlly>C-j|a{#^;!fS4`kbb?w7y3Ysr{ zkE}qMsSdAV5dc~nNpJQxB+Ev5mdOu%P!_jPBv){NTlsw3zJE|Nhd-8j+vyzvsW;i) zx5jyCe;_?O``x^RuiZ?p*A# zYDNKRh`-L&2V2xpbYqurfRn$o+-m*;h!O}CvkYF(eY1pNYPF%l5Y^ab36-m@n$#St zY)k3q5~~yOpe1Z&=cLxOg-0%`&^g<#TFx-~1)C2cW@DR-e9APl>3{o{9;dl~boc=M zs3Y{5wv6g{&*K}CmyF9BXjxK#MFUUnEX&{nt0x??Eq<*EGI)8_^}8{RDba|4;>UaObE|nPm?6?C&xa{3KsUWgqiYMNAffd@}vBYd0 z@FTAtK@Sy`es|uL&Y)*6-t^=8LE$Bw1LouB)5S+usAE<0=anl5N~}21oq0h$azf|B{$rH#6lZ zE`!rX9~z?ubXwO9Qnxp4?DMs`i6{)jdpGq-|_2|tD@$+S+cB%%6?^5rO zSINPtcUG*6tIs`@l>XQt4DBilvn5j+n9$+M zw3)eWToymk2RvN&)ixv&ZFyEOQ$>pUc4B~@jhezB4iK*?kgsrKrF?C(Fp7-GpZKn^ zi39GrPZl^i!pF)EC)14N>VLDyk`YxsM$GK4Qgbo|y1pdcIAO>tu}YVPR~8$_bORpL z@TvvM;y2Lh&wCiG=Rpzu`H1PM&wu!!{$wAa5dbxDN@SIV=@N# zVR6#VGkw+z)yCMAf7C(OJ3xGmShA`fT^4Mk`DwHX9VlWDYIkiQTi~{e zR%hvoEXQ2eT(}VBO(IM_w(OjlCC&wA@Jiqox0`b(%ZfWLtm@NVJNR$s?D%4fZ1670 zi&r3#^y%2UtH`?hy*Uxx+}j6?^^rS-hf5gm^U_*8>Mf#%Zzr9yY>E@r4;U2K30DF; znyMz%cIBK9f$x?5gm`}awFCuSt=f2ti$`(uK%Niut^|?R@vl^%v~@ViCsh21>0!N*K8X-WSn%oaYIE9hdMq72LW(MKi`?6{bhuG_A4g*p;STrrMJS9e-* z`hS*Y$fncRsL6g|%MB_-R3UdA!6kLR%O0GnSR%;*LPff6jka(A*CC>?Y`AX653X7+ z2M%Dw9*g+g+TPXa^b%G3mwMw-$CoCZ5?||hR5LDJRrt|MmJ!3_)Llys06XZIFBERn zop>f|HF>LjIT6*uPj==2WsGKY*HzNd&%0oI^3CVjb%qXSY&PpDVIPadR8d6O(&o6F z`6@f~&7)ef)Q~1MMA~B^C(dxI4K_hK1Z|qP2mq##JsTB%AAl16q3jr~l~7xp7cayC z=HjLz0I=`OWc8zt-@dMuPnv<6zI%b}azc2tF2DicNOAse`BX1{x%St3ASu4a;2#No z@kIsmSn9^xawU2gywELOl&qM0-2eIn<<|$S5A<(sA4Zc7nm`UM#|+l;j##{vdnK|5 zUz&&-?!@+)++n#~uY3(|UMKK9nHg(ROnmzGA*KR>b(WNYeBq5KXsBez{^=&5J z5{3L}Y-;^hUe}cK^(zO6usLXb%cvy4CJrGJF=W}u-BYLj9A};D6+C`yMV+qe=@ti_ z5&$Ny$$5uJ8wr5Jkl3`65g(R`MX^h1N%EfMk>TaMMsEjZbnN51ru&%dW#kj_Jq z;F`WK%>l^F!)?1*^K7aYq~Gya(dEaM{+T}4MN&TMjoK`!GxLwFV(6WJxJ|{yiJo6$ z=(;q#X>hH0j^b_Fv(Rga@#zu$A4+K;?QZU2f;f*|IJHp8yXU;yRX1V&k;ca5csMf` zI>YbG7ZdM&_jKMr^rw!FQ59x=spCD`(5&1q@4cVL-+#!c!&lnYAUc2`KIF69>kPJEpp3~&G>6gH9{w<4DX6$^haOWpnT>{-rPT;48#blAqdJK1NC`^)3Ip(1rBeMUY zbG7s>zog$6)0d6spIpoq&IubPV;<1YU(rKQT%S;Lp)E}fisOd0N$8A4gqzDNGreMe8kJN1vXOsf?(TeCxGs4PQ&|`PYJuw* z*ms*z){TaXXzn3LNM0p*R!#pqciUeBW;yl^ZNw8rW0z9Tjg^&(Q={=D;R^H9=!*1W zby{8kdm^m*gh3fQZtAikVdNmIX^o5W*RKMS94P77E3ySMVH+HopY|Fp3Cj|OEWdf5 z#r5ZyQ&S0mhf(4?68?)UCM>GV51}y;7Y9oMPbpq%VpmTg6IjE4xHT7h=cz zW&n*r894=^OO(kq46v^%d%o^y=p=*&;fYXqoCJ(K*CYa_Bk5gmEix$elEioB{GodI?7UC<4*$6`(MtIOhAWm! zbD4VNYt$dVR(#&ErBDrO3#w;xDkthK`Ds}OFIjPi7V<$$rH)tHgTFP@?S= zF|QT5*Z4=I8T6=b9j3^?M35JvUa^|q!hV;+oq3@zQe3a=S3OE`=8j$!+-3J5`tx4d zDRCie5?z7=IBA$yv>k>$D6f3f@g0^{5+P<3BR{upqERtcyGEmxs*_~W56Lh1#|T^8 zvVn)L>JQY{E@?}=^O#Ml{`mxK9lLdAV3+EPby&MMQJH~%5WS#HOSHUb2`@j_HFenW z$ajb!lR+aUKJQT95L2D*f%7n*l>=GvrAIVzoOHk{d)NmoB;wVt3uFnjAD2Mu0Y z`c(SK4eSCnzVvndZLIgljvvJ8n9rI4vFF;Ig0b``OLJYlyUsL82i*Xo2inMOZi%T4`@z5%`^o2;+corGEu9OERjMl|0kcNVx}Pa z7Tsdp4sy-|jcu>UjE;w;+SG}GVOzQLF=>>}SB+!6f*b%3n|7qZk~T>RIG`#qFSsk0#3G7G+c82OfG zo6`C4W}u1{P$6Q!9H*g8TxFrk8LxtZS0}$lt&#sPkPUD0Vwmby5$n5LAYxgyUg!Kk z{)6fG_u<3m){mtz)2$^s{Rt%8Dz2SGbI)$+s)9;2fx+@JK zK8_0#4_9gDzUii{!kuovx2C3~*DPQvwzfB4NwEgz+yP(>`1j@2TpS8@;sp=c z(1nb}6@U_e*@<05*sZzJ2`yrNp52gld|q8Pxd0KKoqvR^zp5Q2tODuNa(VIv;?2iC z=|VAHu4$Zg$uUS+{?)XBYbB5PxNB-wC-6T$^--jKy?aUF^6Q`Ql>tLV=vFW41O1OY zomM|lYy0&F+m9}{r0`+aU&B`Fs;_k*B#Uz2LPsE9mEhmrv{t9DRD(b|^5W804$9G( z$0dIQl06n+-|TJuJ??-GJbKk~LE+X##w&j34RBGt4Wxi?Yc0m1YySX;zfpJ^^|6ui z9d`I}#-#{C`d>QzwrsI-*)SsE-*SmqwSpNWq099?Jm;ug>EG_^%fLH7KxWB!M zQ0J`>YhOC`*u;UULKCAP{21*qAwtqHaKIExFgGe~^#lEh9`16gJv!QOBh2)u z^D%R6As7%rU))l+JX+zDAMpeOZ*}3*l+AkN_9T*u0~pI#aLNH6kD*`39`#TUUg6gw z`iian795rWKt+JR^#}dy-@SVFYs0KW2;3ji!Gm%|fhUU&0l(+^d$A>{UcHY_yJuos zQZOftQM!hZo_M#Uu>7BT>)v!8oqzw**?tdy@KA++5#L(3B@9_1{kPkLsThI#MO9EEI@&5o3?_m0Hr&`bD z*C2puxb&4DM!T*4ftKKDzvuDq+&bUc*MTICR9?XHFJ=T=k_Y4bed>c0{JQsDhAcvX zV{k?F3lKlDN&Ni}zX3t>r&{5P^~&XojVg5|iks-S0>xY8GDXb*lc}u@Y=`As~`<9!9f&py%tyzkj8rI`HB}dh9S{R{clQ ztwFmlHq;5=>9_jc{3;ItO7)}Hj*tUt*Z8{|dRzV0$MIr5zVz7DPCa^pwc>i@j8F@D z!52_X#e?#K)**i$^hT3Wnk^oBse`egp+3mFv_P1Y@ox zjr6GW_}5AN=?9;$3|IZ*-mpfaO!clfuU!2gokWli*ZWEj9Dh^Ix%_+BJOw!Z!Pl}X zPguYKY$UvVfTVhmFZd6rKTqrL#N+@lPI})DJay%30-B2ts;LK3U5U8VJs^EJ=iaG8 zNE8FFeY`r#9J&V#1)A5rm>XEFj~|bI1OR=1%h!(%8LwQ4kOi(aoBYAQ)Kwc6JL z*R%dT?@t=}^{gHpb9P`{NQE@A-oR*n3DiZnYg_5>M>YF8-(0vX2xidA2p6~nj%*Er zpUD3J4|}JP_3Ov3g}{FsaeFc`HgBnK8y~H{w)}lP>wwQ*#RnR7!Cj-4MroCyVmwhui>4=v!Pz7M zT^WJ>2hx6`-u4avr3vf6@UP|8ZETWA5tNV{=q?#gI*GZ`Y<*wh@543ETc&GHvo3-R zimJYiEE?Km{{U1715L%aZ>jg{(uA6d_2Lg`^Zx(`Spx#v(S&*$))xK5wZ@@qexvw2 zd(|inJ}>ZBtq@5guKb$x^1vM|pq9Ef^I0fh2>f#8}z25(5HnVpsiv_p&NRp`N$qI?SbsVX1Yi z5&=4wMbGyC0JCxa$KI$-LY&hcop}A7aQm3rVFCSZ8pu(Axkn^w);Iv^(#*PGO>^nyfa-?-AE-a8pQHVzaNi&&1;(f0Gq8-=htY`0ed0jupd<+jjjF${{T=p z2j2c?k6ZQYkvu8UugC(e{W^jDNhi|9ZGXY{;!Q<3b+2BzhCr%p7VOFg3{;<|1L_GD z_oGY$!1e6)h8g0ih>;wqu+H%Z(h50<=w?C~kr^a_PxLRf((Y?H^#bvaGf>B0IN z{Zv}S=py3c_xF5cb)pCZ8S5b)mSCm9yD36{O8%`^;8^?c&jHryiurZqA$>rO7WS|l ze@;obKkdiA5s^XHhpl?bt}SExMLkC3{*rDqo^HJJ??8H**R6_B0gkc>${j}Jk#VTl zDIbvEPH*qVwIi=qhp#iSzL_+Os{+6VxV7w~lJ@+4KR)~b9~WCE9j(_VW8!o&2H+ch zLb>380Sd$DN6`D;GfytHsFmZ=T1o)YN#-o&mr1)=FutT@C^Y^)p6YP5AMt%^xa)|= zD*^;-a7aIn2L`}jO9C(Nz`0^i4!!d0AfYj^W*`fN`dkZfq=CZ%K8M}7oQ~S{s?xo4 zY-n5ESeuJ5x%3_dh3>34+q6k)+CJwr?WM?Ur{M-H{au4zKge@Ni1m=99v3{#Q%u0JQA zd#7HmYu7cR0dy509&YGBP%O6mi~U9K?^NsA^WoNULaIm#2E8^M3u!#*{{V0O4?g!n zjCH*EjP(M#gG3B;km?TvT${Da06@@ef7bU#J%o<7xnMdBD(RtmnFZLcySQV|_%IFl zQ~uxHqhb(aJ$bTolh$O1)9N9@*d>7FLHvM84gG)C_k5o$^`b`}qE^#tk5g*0kmlb- z2Y@&poBsfZx{9y>j1kuV0KwB&+iE}utA_rkNF0N!{ZIT)yP6zztmCd}OwOX$BHBP; zx=#Yvy^foXJ@3-JXn7w#yeU{{4Wp7TXSrKkhOxf`-l{9duOCWdsc=%Dsfdwl+~1B* z=j-XQBZK}w*WHCkCV=(hgVM2Sl%?Hoa;!fLRE;M|TmC=T-`+jub{5^6o4JP`m;@7tZ z+yYc{tw{QQJ?xCruU7_~dhvrtsDih+Wqn$S;_q{Da6cbke)~9eQRmkrj_a<&Nk3E1 z7vvpB(toJ;S`p{fy=r>pEhttYc%_4Bg z`V~U@blcLR`~ti$*Yoe*Up}=;9*AxbyXTtr*|595M8=;uCtY=17YicUd{X&|@t zQU$#OQ+}IT!`{Y5cy;RJdUWMU2~7&t9FSi@7i-)OE_Ep$?Lp*DIDMXHs{P_jDcO z%c{2zpF-vz9vYWP7dO(P%cv;jMx$Y`ix2SkXXAsPPOTRMsC4>hkg5{05-bC00zgkb zp{NU=q4!EtRR#?|+3Mr22Oh5{taGFVApLl;EC(l%&${UYQiImX&1u&)pyU%}BX#AzdZanTnSmLR1?A^dsK1*179ybc%87FrYTpi=%=p2m6Is1CY_6l4bN*IM8f(^-U$lw(#H8I^aP~ zCD{FWVh0xd1ssrnujk(IXnOT2=hqVI;E4*Yj-lxNAb&tfHY4kQe&NHde5; Date: Sat, 28 Oct 2023 19:18:59 +0200 Subject: [PATCH 104/310] Bugfix version detection logic and better message --- WifiInterface.cpp | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/WifiInterface.cpp b/WifiInterface.cpp index ab36957..27830bb 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -206,12 +206,13 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, while(!wifiStream->available()); version[i]=wifiStream->read(); StringFormatter::printEscape(version[i]); - if ((version[0] == '0') || - (version[0] == '2' && version[2] == '0') || - (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) { - SSid = F("DCCEX_SAYS_BROKEN_FIRMWARE"); - forceAP = true; - } + } + if ((version[0] == '0') || + (version[0] == '2' && version[2] == '0') || + (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) { + DIAG(F("You need to up/downgrade the ESP firmware")); + SSid = F("UPDATE_ESP_FIRMWARE"); + forceAP = true; } } checkForOK(2000, true, false); From 24e0f189e18283d6f2399c402e507f8e84cca263 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 1 Nov 2023 20:19:59 +0000 Subject: [PATCH 105/310] fix TURNOUTL --- EXRAILMacros.h | 2 ++ version.h | 3 ++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8e7fbb9..8954f6d 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -204,6 +204,8 @@ void RMFT2::printMessage(uint16_t id) { #include "EXRAIL2MacroReset.h" #undef TURNOUT #define TURNOUT(id,addr,subaddr,description...) O_DESC(id,description) +#undef TURNOUTL +#define TURNOUTL(id,addr,description...) O_DESC(id,description) #undef PIN_TURNOUT #define PIN_TURNOUT(id,pin,description...) O_DESC(id,description) #undef SERVO_TURNOUT diff --git a/version.h b/version.h index 4daafba..5ba1d33 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.17" +#define VERSION "5.1.18" +// 5.1.8 TURNOUTL bugfix // 5.1.17 - Divide out C for config and D for diag commands // 5.1.16 - Remove I2C address from EXTT_TURNTABLE macro to work with MUX, requires separate HAL macro to create // 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. From 043e6fdb263b99d3c48ec7df1e93520f83547ae1 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 6 Nov 2023 22:11:31 +0100 Subject: [PATCH 106/310] Only flag 2.2.0.0-dev as broken, not 2.2.0.0 --- WifiInterface.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 27830bb..8b2251a 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -201,15 +201,16 @@ wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password, // Display the AT version information StringFormatter::send(wifiStream, F("AT+GMR\r\n")); if (checkForOK(2000, F("AT version:"), true, false)) { - char version[] = "0.0.0.0"; - for (int i=0; i<8;i++) { + char version[] = "0.0.0.0-xxx"; + for (int i=0; i<11;i++) { while(!wifiStream->available()); version[i]=wifiStream->read(); StringFormatter::printEscape(version[i]); } if ((version[0] == '0') || (version[0] == '2' && version[2] == '0') || - (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0')) { + (version[0] == '2' && version[2] == '2' && version[4] == '0' && version[6] == '0' + && version[7] == '-' && version[8] == 'd' && version[9] == 'e' && version[10] == 'v')) { DIAG(F("You need to up/downgrade the ESP firmware")); SSid = F("UPDATE_ESP_FIRMWARE"); forceAP = true; From f2ff1ba22aa8919f0a322472f7a9dda31bb1ef92 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 6 Nov 2023 22:14:39 +0100 Subject: [PATCH 107/310] version 5.1.19 --- version.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/version.h b/version.h index 5ba1d33..9d5a7e1 100644 --- a/version.h +++ b/version.h @@ -3,8 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.1.18" -// 5.1.8 TURNOUTL bugfix +#define VERSION "5.1.19" +// 5.1.19 - Only flag 2.2.0.0-dev as broken, not 2.2.0.0 +// 5.1.18 - TURNOUTL bugfix // 5.1.17 - Divide out C for config and D for diag commands // 5.1.16 - Remove I2C address from EXTT_TURNTABLE macro to work with MUX, requires separate HAL macro to create // 5.1.15 - LCC/Adapter support and Exrail feature-compile-out. From 4e08177b7bc3417475fb90e8ec28f63f9f553115 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 7 Nov 2023 16:27:26 +0000 Subject: [PATCH 108/310] Route state management (part 1) --- CommandDistributor.cpp | 8 ++++++++ CommandDistributor.h | 4 ++++ EXRAIL2.cpp | 11 ++++++++++- EXRAIL2.h | 1 + EXRAIL2MacroReset.h | 8 ++++++++ EXRAILMacros.h | 10 ++++++++++ 6 files changed, 41 insertions(+), 1 deletion(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 1651771..efd4778 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -272,3 +272,11 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); } + +void CommandDistributor::broadcastRouteState(uint16_t routeId, RouteState state ) { + broadcastReply(COMMAND_TYPE, F("\n"),routeId,state); +} + +void CommandDistributor::broadcastRouteCaption(uint16_t routeId, const FSH* caption ) { + broadcastReply(COMMAND_TYPE, F("\n"),routeId,caption); +} diff --git a/CommandDistributor.h b/CommandDistributor.h index d54ef31..839bcbf 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -37,6 +37,7 @@ class CommandDistributor { public: enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE}; + enum RouteState: byte {STATE_ACTIVE,STATE_INACTIVE,STATE_HIDDEN}; private: static void broadcastToClients(clientType type); static StringBuffer * broadcastBufferWriter; @@ -58,6 +59,9 @@ public : static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); + static void broadcastRouteState(uint16_t routeId,RouteState state); + static void broadcastRouteCaption(uint16_t routeId,const FSH * caption); + }; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index c902708..634df29 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1130,7 +1130,16 @@ void RMFT2::loop2() { case OPCODE_PRINT: printMessage(operand); break; - + case OPCODE_ROUTE_HIDDEN: + CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_HIDDEN); + break; + case OPCODE_ROUTE_ACTIVE: + CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_ACTIVE); + break; + case OPCODE_ROUTE_INACTIVE: + CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_INACTIVE); + break; + case OPCODE_ROUTE: case OPCODE_AUTOMATION: case OPCODE_SEQUENCE: diff --git a/EXRAIL2.h b/EXRAIL2.h index de14f11..1898b26 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -68,6 +68,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONROTATE,OPCODE_ROTATE,OPCODE_WAITFORTT, OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC, OPCODE_ONOVERLOAD, + OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index d44b244..9bfad1b 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -126,6 +126,10 @@ #undef ROTATE #undef ROTATE_DCC #undef ROUTE +#undef ROUTE_ACTVE +#undef ROUTE_INACTVE +#undef ROUTE_HIDDEN +#undef ROUTE_CAPTION #undef SENDLOCO #undef SEQUENCE #undef SERIAL @@ -267,6 +271,10 @@ #define ROTATE_DCC(turntable_id,position) #define ROSTER(cab,name,funcmap...) #define ROUTE(id,description) +#define ROUTE_ACTIVE(id) +#define ROUTE_INACTIVE(id) +#define ROUTE_HIDDEN(id) +#define ROUTE_CAPTION(id,caption) #define SENDLOCO(cab,route) #define SEQUENCE(id) #define SERIAL(msg) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8954f6d..e11b5db 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -153,6 +153,12 @@ const int StringMacroTracker1=__COUNTER__; #define PRINT(msg) THRUNGE(msg,thrunge_print) #undef LCN #define LCN(msg) THRUNGE(msg,thrunge_lcn) +#undef ROUTE_CAPTION +#define ROUTE_CAPTION(id,caption) \ +case (__COUNTER__ - StringMacroTracker1) : {\ + CommandDistributor::broadcastRouteCaption(id,F(caption));\ + return;\ + } #undef SERIAL #define SERIAL(msg) THRUNGE(msg,thrunge_serial) #undef SERIAL1 @@ -440,6 +446,10 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ROTATE_DCC(id,position) OPCODE_ROTATE,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(0), #endif #define ROUTE(id, description) OPCODE_ROUTE, V(id), +#define ROUTE_ACTIVE(id) OPCODE_ROUTE_ACTIVE,V(id), +#define ROUTE_INACTIVE(id) OPCODE_ROUTE_INACTIVE,V(id), +#define ROUTE_HIDDEN(id) OPCODE_ROUTE_HIDDEN,V(id), +#define ROUTE_CAPTION(id,caption) PRINT(caption) #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), #define SERIAL(msg) PRINT(msg) From 26cf28dff7396e3d836117bb2003d78220fa237b Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 9 Nov 2023 19:27:52 +0000 Subject: [PATCH 109/310] fixups --- CommandDistributor.cpp | 2 +- CommandDistributor.h | 3 +-- EXRAIL2.cpp | 28 +++++++++++++++++++++++++--- EXRAIL2.h | 6 +++++- EXRAIL2MacroReset.h | 4 ++-- 5 files changed, 34 insertions(+), 9 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index efd4778..351a18d 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -273,7 +273,7 @@ void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); } -void CommandDistributor::broadcastRouteState(uint16_t routeId, RouteState state ) { +void CommandDistributor::broadcastRouteState(uint16_t routeId, byte state ) { broadcastReply(COMMAND_TYPE, F("\n"),routeId,state); } diff --git a/CommandDistributor.h b/CommandDistributor.h index 839bcbf..83bfbbd 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -37,7 +37,6 @@ class CommandDistributor { public: enum clientType: byte {NONE_TYPE,COMMAND_TYPE,WITHROTTLE_TYPE}; - enum RouteState: byte {STATE_ACTIVE,STATE_INACTIVE,STATE_HIDDEN}; private: static void broadcastToClients(clientType type); static StringBuffer * broadcastBufferWriter; @@ -59,7 +58,7 @@ public : static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); - static void broadcastRouteState(uint16_t routeId,RouteState state); + static void broadcastRouteState(uint16_t routeId,byte state); static void broadcastRouteCaption(uint16_t routeId,const FSH * caption); diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 634df29..870ff6d 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -100,6 +100,7 @@ LookList * RMFT2::onClockLookup=NULL; LookList * RMFT2::onRotateLookup=NULL; #endif LookList * RMFT2::onOverloadLookup=NULL; +byte * RMFT2::routeStateArray=nullptr; #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -139,6 +140,15 @@ int16_t LookList::find(int16_t value) { } return -1; } +int16_t LookList::findPosition(int16_t value) { + for (int16_t i=0;isize(),sizeof(byte)); onThrowLookup=LookListLoader(OPCODE_ONTHROW); onCloseLookup=LookListLoader(OPCODE_ONCLOSE); onActivateLookup=LookListLoader(OPCODE_ONACTIVATE); @@ -1131,13 +1142,13 @@ void RMFT2::loop2() { printMessage(operand); break; case OPCODE_ROUTE_HIDDEN: - CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_HIDDEN); + manageRoute(operand,2); break; case OPCODE_ROUTE_ACTIVE: - CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_ACTIVE); + manageRoute(operand,0); break; case OPCODE_ROUTE_INACTIVE: - CommandDistributor::broadcastRouteState(operand,CommandDistributor::RouteState::STATE_INACTIVE); + manageRoute(operand,1); break; case OPCODE_ROUTE: @@ -1462,3 +1473,14 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) { break; } } + +void RMFT2::manageRoute(uint16_t id, byte state) { + CommandDistributor::broadcastRouteState(id,state); + // Route state must be maintained for when new throttles connect. + // locate route id in the Routes lookup + int16_t position=sequenceLookup->findPosition(id); + if (position<0) return; + // set state beside it + routeStateArray[position]=state; +} + \ No newline at end of file diff --git a/EXRAIL2.h b/EXRAIL2.h index 1898b26..ed3e459 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -121,7 +121,9 @@ class LookList { public: LookList(int16_t size); void add(int16_t lookup, int16_t result); - int16_t find(int16_t value); + int16_t find(int16_t value); // finds result value + int16_t findPosition(int16_t value); // finds index + int16_t size(); private: int16_t m_size; int16_t m_loaded; @@ -217,6 +219,8 @@ private: static const int countLCCLookup; static int onLCCLookup[]; static const byte compileFeatures; + static void manageRoute(uint16_t id, byte state); + static byte * routeStateArray; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 9bfad1b..ff8dc8d 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -126,8 +126,8 @@ #undef ROTATE #undef ROTATE_DCC #undef ROUTE -#undef ROUTE_ACTVE -#undef ROUTE_INACTVE +#undef ROUTE_ACTIVE +#undef ROUTE_INACTIVE #undef ROUTE_HIDDEN #undef ROUTE_CAPTION #undef SENDLOCO From 2cbcecf9e653477a2032fc572e63481ecaa062d2 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 9 Nov 2023 20:25:10 +0000 Subject: [PATCH 110/310] separate routes and sequences, handle state and captions. --- EXRAIL2.cpp | 56 ++++++++++++++++++++++++++++++++++++----------------- EXRAIL2.h | 10 +++++++--- 2 files changed, 45 insertions(+), 21 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 870ff6d..7b6107d 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -86,7 +86,7 @@ RMFT2 * RMFT2::pausingTask=NULL; // Task causing a PAUSE. // and all others will have their locos stopped, then resumed after the pausing task resumes. byte RMFT2::flags[MAX_FLAGS]; Print * RMFT2::LCCSerial=0; -LookList * RMFT2::sequenceLookup=NULL; +LookList * RMFT2::routeLookup=NULL; LookList * RMFT2::onThrowLookup=NULL; LookList * RMFT2::onCloseLookup=NULL; LookList * RMFT2::onActivateLookup=NULL; @@ -101,6 +101,7 @@ LookList * RMFT2::onRotateLookup=NULL; #endif LookList * RMFT2::onOverloadLookup=NULL; byte * RMFT2::routeStateArray=nullptr; +const FSH * * RMFT2::routeCaptionArray=nullptr; #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 @@ -121,6 +122,7 @@ uint16_t RMFT2::getOperand(int progCounter,byte n) { LookList::LookList(int16_t size) { m_size=size; m_loaded=0; + m_chain=nullptr; if (size) { m_lookupArray=new int16_t[size]; m_resultArray=new int16_t[size]; @@ -138,8 +140,12 @@ int16_t LookList::find(int16_t value) { for (int16_t i=0;ifind(value) :-1; } +void LookList::chain(LookList * chain) { + m_chain=chain; +} + int16_t LookList::findPosition(int16_t value) { for (int16_t i=0;isize(),sizeof(byte)); + routeLookup=LookListLoader(OPCODE_ROUTE, OPCODE_AUTOMATION); + routeLookup->chain(LookListLoader(OPCODE_SEQUENCE)); + routeStateArray=(byte *)calloc(routeLookup->size(),sizeof(byte)); + routeCaptionArray=(const FSH * *)calloc(routeLookup->size(),sizeof(const FSH *)); + onThrowLookup=LookListLoader(OPCODE_ONTHROW); onCloseLookup=LookListLoader(OPCODE_ONCLOSE); onActivateLookup=LookListLoader(OPCODE_ONACTIVATE); @@ -485,7 +494,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { { int route=(paramCount==2) ? p[1] : p[2]; uint16_t cab=(paramCount==2)? 0 : p[1]; - int pc=sequenceLookup->find(route); + int pc=routeLookup->find(route); if (pc<0) return false; RMFT2* task=new RMFT2(pc); task->loco=cab; @@ -605,7 +614,7 @@ RMFT2::~RMFT2() { } void RMFT2::createNewTask(int route, uint16_t cab) { - int pc=sequenceLookup->find(route); + int pc=routeLookup->find(route); if (pc<0) return; RMFT2* task=new RMFT2(pc); task->loco=cab; @@ -1006,7 +1015,7 @@ void RMFT2::loop2() { } case OPCODE_FOLLOW: - progCounter=sequenceLookup->find(operand); + progCounter=routeLookup->find(operand); if (progCounter<0) kill(F("FOLLOW unknown"), operand); return; @@ -1016,7 +1025,7 @@ void RMFT2::loop2() { return; } callStack[stackDepth++]=progCounter+3; - progCounter=sequenceLookup->find(operand); + progCounter=routeLookup->find(operand); if (progCounter<0) kill(F("CALL unknown"),operand); return; @@ -1079,7 +1088,7 @@ void RMFT2::loop2() { case OPCODE_START: { - int newPc=sequenceLookup->find(operand); + int newPc=routeLookup->find(operand); if (newPc<0) break; new RMFT2(newPc); } @@ -1087,7 +1096,7 @@ void RMFT2::loop2() { case OPCODE_SENDLOCO: // cab, route { - int newPc=sequenceLookup->find(getOperand(1)); + int newPc=routeLookup->find(getOperand(1)); if (newPc<0) break; RMFT2* newtask=new RMFT2(newPc); // create new task newtask->loco=operand; @@ -1142,13 +1151,13 @@ void RMFT2::loop2() { printMessage(operand); break; case OPCODE_ROUTE_HIDDEN: - manageRoute(operand,2); + manageRouteState(operand,2); break; case OPCODE_ROUTE_ACTIVE: - manageRoute(operand,0); + manageRouteState(operand,0); break; case OPCODE_ROUTE_INACTIVE: - manageRoute(operand,1); + manageRouteState(operand,1); break; case OPCODE_ROUTE: @@ -1474,13 +1483,24 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) { } } -void RMFT2::manageRoute(uint16_t id, byte state) { - CommandDistributor::broadcastRouteState(id,state); +void RMFT2::manageRouteState(uint16_t id, byte state) { // Route state must be maintained for when new throttles connect. // locate route id in the Routes lookup - int16_t position=sequenceLookup->findPosition(id); + int16_t position=routeLookup->findPosition(id); if (position<0) return; // set state beside it - routeStateArray[position]=state; + if (routeStateArray[position]==state) return; + routeStateArray[position]=state; + CommandDistributor::broadcastRouteState(id,state); } - \ No newline at end of file +void RMFT2::manageRouteCaption(uint16_t id,const FSH* caption) { + // Route state must be maintained for when new throttles connect. + // locate route id in the Routes lookup + int16_t position=routeLookup->findPosition(id); + if (position<0) return; + // set state beside it + if (routeCaptionArray[position]==caption) return; + routeCaptionArray[position]=caption; + CommandDistributor::broadcastRouteCaption(id,caption); +} + diff --git a/EXRAIL2.h b/EXRAIL2.h index ed3e459..e5db1d9 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -120,6 +120,7 @@ enum thrunger: byte { class LookList { public: LookList(int16_t size); + void chain(LookList* chainTo); void add(int16_t lookup, int16_t result); int16_t find(int16_t value); // finds result value int16_t findPosition(int16_t value); // finds index @@ -128,7 +129,8 @@ class LookList { int16_t m_size; int16_t m_loaded; int16_t * m_lookupArray; - int16_t * m_resultArray; + int16_t * m_resultArray; + LookList* m_chain; }; class RMFT2 { @@ -201,7 +203,7 @@ private: static const HIGHFLASH int16_t SignalDefinitions[]; static byte flags[MAX_FLAGS]; static Print * LCCSerial; - static LookList * sequenceLookup; + static LookList * routeLookup; static LookList * onThrowLookup; static LookList * onCloseLookup; static LookList * onActivateLookup; @@ -219,8 +221,10 @@ private: static const int countLCCLookup; static int onLCCLookup[]; static const byte compileFeatures; - static void manageRoute(uint16_t id, byte state); + static void manageRouteState(uint16_t id, byte state); + static void manageRouteCaption(uint16_t id, const FSH* caption); static byte * routeStateArray; + static const FSH * * routeCaptionArray; // Local variables - exist for each instance/task RMFT2 *next; // loop chain From a4eabf235e47f48918ce991d069372cbc14b4ad3 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 19:25:24 +0000 Subject: [PATCH 111/310] EXRAIL ROUTE_STATE and ROUTE_CAPTION --- DCCEXParser.cpp | 29 ++--- EXRAIL2.cpp | 303 ++++++---------------------------------------- EXRAIL2.h | 10 +- EXRAIL2Parser.cpp | 287 +++++++++++++++++++++++++++++++++++++++++++ EXRAILMacros.h | 10 +- 5 files changed, 348 insertions(+), 291 deletions(-) create mode 100644 EXRAIL2Parser.cpp diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index d79136f..96596c6 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -781,27 +781,11 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) TrackManager::reportCurrent(stream); // return; - case HASH_KEYWORD_A: // returns automations/routes - StringFormatter::send(stream, F(" -#ifdef EXRAIL_ACTIVE - SENDFLASHLIST(stream,RMFT2::routeIdList) - SENDFLASHLIST(stream,RMFT2::automationIdList) -#endif - } - else { // - StringFormatter::send(stream,F(" %d %c \"%S\""), - id, -#ifdef EXRAIL_ACTIVE - RMFT2::getRouteType(id), // A/R - RMFT2::getRouteDescription(id) -#else - 'X',F("") -#endif - ); - } - StringFormatter::send(stream, F(">\n")); - return; + case HASH_KEYWORD_A: // intercepted by EXRAIL// returns automations/routes + if (params!=1) break; // + StringFormatter::send(stream, F("\n")); + return; + case HASH_KEYWORD_R: // returns rosters StringFormatter::send(stream, F(" 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off switch (p[0]) { #ifndef DISABLE_PROG @@ -1159,6 +1142,8 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // } } else { + bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + DIAG(F("Ack diag %S"), onOff ? F("on") : F("off")); Diag::ACK = onOff; } diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 7b6107d..61e0264 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -55,22 +55,6 @@ #include "Turntables.h" #include "IODevice.h" -// Command parsing keywords -const int16_t HASH_KEYWORD_EXRAIL=15435; -const int16_t HASH_KEYWORD_ON = 2657; -const int16_t HASH_KEYWORD_START=23232; -const int16_t HASH_KEYWORD_RESERVE=11392; -const int16_t HASH_KEYWORD_FREE=-23052; -const int16_t HASH_KEYWORD_LATCH=1618; -const int16_t HASH_KEYWORD_UNLATCH=1353; -const int16_t HASH_KEYWORD_PAUSE=-4142; -const int16_t HASH_KEYWORD_RESUME=27609; -const int16_t HASH_KEYWORD_KILL=5218; -const int16_t HASH_KEYWORD_ALL=3457; -const int16_t HASH_KEYWORD_ROUTES=-3702; -const int16_t HASH_KEYWORD_RED=26099; -const int16_t HASH_KEYWORD_AMBER=18713; -const int16_t HASH_KEYWORD_GREEN=-31493; // One instance of RMFT clas is used for each "thread" in the automation. // Each thread manages a loco on a journey through the layout, and/or may manage a scenery automation. @@ -103,9 +87,6 @@ LookList * RMFT2::onOverloadLookup=NULL; byte * RMFT2::routeStateArray=nullptr; const FSH * * RMFT2::routeCaptionArray=nullptr; -#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) -#define SKIPOP progCounter+=3 - // getOperand instance version, uses progCounter from instance. uint16_t RMFT2::getOperand(byte n) { return getOperand(progCounter,n); @@ -146,6 +127,13 @@ void LookList::chain(LookList * chain) { m_chain=chain; } +void LookList::stream(Print * _stream) { + for (int16_t i=0;iprint(" "); + _stream->print(m_lookupArray[i]); + } +} + int16_t LookList::findPosition(int16_t value) { for (int16_t i=0;ichain(LookListLoader(OPCODE_SEQUENCE)); - routeStateArray=(byte *)calloc(routeLookup->size(),sizeof(byte)); - routeCaptionArray=(const FSH * *)calloc(routeLookup->size(),sizeof(const FSH *)); - + if (compileFeatures && FEATURE_ROUTESTATE) { + routeStateArray=(byte *)calloc(routeLookup->size(),sizeof(byte)); + routeCaptionArray=(const FSH * *)calloc(routeLookup->size(),sizeof(const FSH *)); + } onThrowLookup=LookListLoader(OPCODE_ONTHROW); onCloseLookup=LookListLoader(OPCODE_ONCLOSE); onActivateLookup=LookListLoader(OPCODE_ONACTIVATE); @@ -334,238 +323,15 @@ void RMFT2::setTurntableHiddenState(Turntable * tto) { #endif char RMFT2::getRouteType(int16_t id) { - for (int16_t i=0;;i+=2) { - int16_t rid= GETHIGHFLASHW(routeIdList,i); - if (rid==INT16_MAX) break; - if (rid==id) return 'R'; - } - for (int16_t i=0;;i+=2) { - int16_t rid= GETHIGHFLASHW(automationIdList,i); - if (rid==INT16_MAX) break; - if (rid==id) return 'A'; + int16_t progCounter=routeLookup->find(id); + if (progCounter>=0) { + OPCODE type=GET_OPCODE; + if (type==OPCODE_ROUTE) return 'R'; + if (type==OPCODE_AUTOMATION) return 'A'; } return 'X'; } -// This filter intercepts <> commands to do the following: -// - Implement RMFT specific commands/diagnostics -// - Reject/modify JMRI commands that would interfere with RMFT processing -void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) { - (void)stream; // avoid compiler warning if we don't access this parameter - bool reject=false; - switch(opcode) { - - case 'D': - if (p[0]==HASH_KEYWORD_EXRAIL) { // - diag = paramCount==2 && (p[1]==HASH_KEYWORD_ON || p[1]==1); - opcode=0; - } - break; - - case '/': // New EXRAIL command - reject=!parseSlash(stream,paramCount,p); - opcode=0; - break; - case 'L': - if (compileFeatures & FEATURE_LCC) { - // This entire code block is compiled out if LLC macros not used - if (paramCount==0) { // LCC adapter introducing self - LCCSerial=stream; // now we know where to send events we raise - - // loop through all possible sent events - for (int progCounter=0;; SKIPOP) { - byte opcode=GET_OPCODE; - if (opcode==OPCODE_ENDEXRAIL) break; - if (opcode==OPCODE_LCC) StringFormatter::send(stream,F("\n"),getOperand(progCounter,0)); - if (opcode==OPCODE_LCCX) { // long form LCC - StringFormatter::send(stream,F("\n"), - getOperand(progCounter,1), - getOperand(progCounter,2), - getOperand(progCounter,3), - getOperand(progCounter,0) - ); - }} - - // we stream the hex events we wish to listen to - // and at the same time build the event index looku. - - - int eventIndex=0; - for (int progCounter=0;; SKIPOP) { - byte opcode=GET_OPCODE; - if (opcode==OPCODE_ENDEXRAIL) break; - if (opcode==OPCODE_ONLCC) { - onLCCLookup[eventIndex]=progCounter; // TODO skip... - StringFormatter::send(stream,F("\n"), - eventIndex, - getOperand(progCounter,1), - getOperand(progCounter,2), - getOperand(progCounter,3), - getOperand(progCounter,0) - ); - eventIndex++; - } - } - StringFormatter::send(stream,F("\n")); // Ready to rumble - opcode=0; - break; - } - if (paramCount==1) { // LCC event arrived from adapter - int16_t eventid=p[0]; - reject=eventid<0 || eventid>=countLCCLookup; - if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]); - opcode=0; - } - } - break; - - default: // other commands pass through - break; - } - if (reject) { - opcode=0; - StringFormatter::send(stream,F("\n")); - } -} - -bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { - - if (paramCount==0) { // STATUS - StringFormatter::send(stream, F("<* EXRAIL STATUS")); - RMFT2 * task=loopTask; - while(task) { - StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"), - (int)(task->taskId),task->progCounter,task->loco, - task->invert?'I':' ', - task->speedo, - task->forward?'F':'R' - ); - task=task->next; - if (task==loopTask) break; - } - // Now stream the flags - for (int id=0;id\n")); - return true; - } - switch (p[0]) { - case HASH_KEYWORD_PAUSE: // - if (paramCount!=1) return false; - DCC::setThrottle(0,1,true); // pause all locos on the track - pausingTask=(RMFT2 *)1; // Impossible task address - return true; - - case HASH_KEYWORD_RESUME: // - if (paramCount!=1) return false; - pausingTask=NULL; - { - RMFT2 * task=loopTask; - while(task) { - if (task->loco) task->driveLoco(task->speedo); - task=task->next; - if (task==loopTask) break; - } - } - return true; - - - case HASH_KEYWORD_START: // - if (paramCount<2 || paramCount>3) return false; - { - int route=(paramCount==2) ? p[1] : p[2]; - uint16_t cab=(paramCount==2)? 0 : p[1]; - int pc=routeLookup->find(route); - if (pc<0) return false; - RMFT2* task=new RMFT2(pc); - task->loco=cab; - } - return true; - - default: - break; - } - - // check KILL ALL here, otherwise the next validation confuses ALL with a flag - if (p[0]==HASH_KEYWORD_KILL && p[1]==HASH_KEYWORD_ALL) { - while (loopTask) loopTask->kill(F("KILL ALL")); // destructor changes loopTask - return true; - } - - // all other / commands take 1 parameter - if (paramCount!=2 ) return false; - - switch (p[0]) { - case HASH_KEYWORD_KILL: // Kill taskid|ALL - { - if ( p[1]<0 || p[1]>=MAX_FLAGS) return false; - RMFT2 * task=loopTask; - while(task) { - if (task->taskId==p[1]) { - task->kill(F("KILL")); - return true; - } - task=task->next; - if (task==loopTask) break; - } - } - return false; - - case HASH_KEYWORD_RESERVE: // force reserve a section - return setFlag(p[1],SECTION_FLAG); - - case HASH_KEYWORD_FREE: // force free a section - return setFlag(p[1],0,SECTION_FLAG); - - case HASH_KEYWORD_LATCH: - return setFlag(p[1], LATCH_FLAG); - - case HASH_KEYWORD_UNLATCH: - return setFlag(p[1], 0, LATCH_FLAG); - - case HASH_KEYWORD_RED: - doSignal(p[1],SIGNAL_RED); - return true; - - case HASH_KEYWORD_AMBER: - doSignal(p[1],SIGNAL_AMBER); - return true; - - case HASH_KEYWORD_GREEN: - doSignal(p[1],SIGNAL_GREEN); - return true; - - default: - return false; - } -} - - -// This emits Routes and Automations to Withrottle -// Automations are given a state to set the button to "handoff" which implies -// handing over the loco to the automation. -// Routes are given "Set" buttons and do not cause the loco to be handed over. - - RMFT2::RMFT2(int progCtr) { progCounter=progCtr; @@ -1484,23 +1250,28 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) { } void RMFT2::manageRouteState(uint16_t id, byte state) { - // Route state must be maintained for when new throttles connect. - // locate route id in the Routes lookup - int16_t position=routeLookup->findPosition(id); - if (position<0) return; - // set state beside it - if (routeStateArray[position]==state) return; - routeStateArray[position]=state; - CommandDistributor::broadcastRouteState(id,state); + if (compileFeatures && FEATURE_ROUTESTATE) { + // Route state must be maintained for when new throttles connect. + // locate route id in the Routes lookup + int16_t position=routeLookup->findPosition(id); + if (position<0) return; + // set state beside it + if (routeStateArray[position]==state) return; + routeStateArray[position]=state; + CommandDistributor::broadcastRouteState(id,state); + } } void RMFT2::manageRouteCaption(uint16_t id,const FSH* caption) { - // Route state must be maintained for when new throttles connect. - // locate route id in the Routes lookup - int16_t position=routeLookup->findPosition(id); - if (position<0) return; - // set state beside it - if (routeCaptionArray[position]==caption) return; - routeCaptionArray[position]=caption; - CommandDistributor::broadcastRouteCaption(id,caption); + if (compileFeatures && FEATURE_ROUTESTATE) { + // Route state must be maintained for when new throttles connect. + // locate route id in the Routes lookup + int16_t position=routeLookup->findPosition(id); + if (position<0) return; + // set state beside it + if (routeCaptionArray[position]==caption) return; + routeCaptionArray[position]=caption; + DIAG(F("rCA[%d]=%d, c=%d"),position,routeStateArray[position],caption); + CommandDistributor::broadcastRouteCaption(id,caption); + } } diff --git a/EXRAIL2.h b/EXRAIL2.h index e5db1d9..bcb517e 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -100,6 +100,7 @@ enum thrunger: byte { static const byte FEATURE_SIGNAL= 0x80; static const byte FEATURE_LCC = 0x40; static const byte FEATURE_ROSTER= 0x20; + static const byte FEATURE_ROUTESTATE= 0x10; // Flag bits for status of hardware and TPL @@ -124,7 +125,8 @@ class LookList { void add(int16_t lookup, int16_t result); int16_t find(int16_t value); // finds result value int16_t findPosition(int16_t value); // finds index - int16_t size(); + int16_t size(); + void stream(Print * _stream); private: int16_t m_size; int16_t m_loaded; @@ -224,7 +226,7 @@ private: static void manageRouteState(uint16_t id, byte state); static void manageRouteCaption(uint16_t id, const FSH* caption); static byte * routeStateArray; - static const FSH * * routeCaptionArray; + static const FSH ** routeCaptionArray; // Local variables - exist for each instance/task RMFT2 *next; // loop chain @@ -246,4 +248,8 @@ private: byte stackDepth; int callStack[MAX_STACK_DEPTH]; }; + +#define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) +#define SKIPOP progCounter+=3 + #endif diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp new file mode 100644 index 0000000..7670118 --- /dev/null +++ b/EXRAIL2Parser.cpp @@ -0,0 +1,287 @@ +/* + * © 2021 Neil McKechnie + * © 2021-2023 Harald Barth + * © 2020-2023 Chris Harlow + * © 2022-2023 Colin Murdoch + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +// THIS file is an extension of the RMFT2 class +// normally found in EXRAIL2.cpp + +#include +#include "defines.h" +#include "EXRAIL2.h" +#include "DCC.h" +// Command parsing keywords +const int16_t HASH_KEYWORD_EXRAIL=15435; +const int16_t HASH_KEYWORD_ON = 2657; +const int16_t HASH_KEYWORD_START=23232; +const int16_t HASH_KEYWORD_RESERVE=11392; +const int16_t HASH_KEYWORD_FREE=-23052; +const int16_t HASH_KEYWORD_LATCH=1618; +const int16_t HASH_KEYWORD_UNLATCH=1353; +const int16_t HASH_KEYWORD_PAUSE=-4142; +const int16_t HASH_KEYWORD_RESUME=27609; +const int16_t HASH_KEYWORD_KILL=5218; +const int16_t HASH_KEYWORD_ALL=3457; +const int16_t HASH_KEYWORD_ROUTES=-3702; +const int16_t HASH_KEYWORD_RED=26099; +const int16_t HASH_KEYWORD_AMBER=18713; +const int16_t HASH_KEYWORD_GREEN=-31493; +const int16_t HASH_KEYWORD_A='A'; + +// This filter intercepts <> commands to do the following: +// - Implement RMFT specific commands/diagnostics +// - Reject/modify JMRI commands that would interfere with RMFT processing + +void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) { + (void)stream; // avoid compiler warning if we don't access this parameter + bool reject=false; + switch(opcode) { + + case 'D': + if (p[0]==HASH_KEYWORD_EXRAIL) { // + diag = paramCount==2 && (p[1]==HASH_KEYWORD_ON || p[1]==1); + opcode=0; + } + break; + + case '/': // New EXRAIL command + reject=!parseSlash(stream,paramCount,p); + opcode=0; + break; + + case 'L': + // This entire code block is compiled out if LLC macros not used + if (!(compileFeatures & FEATURE_LCC)) return; + + if (paramCount==0) { // LCC adapter introducing self + LCCSerial=stream; // now we know where to send events we raise + + // loop through all possible sent events + for (int progCounter=0;; SKIPOP) { + byte opcode=GET_OPCODE; + if (opcode==OPCODE_ENDEXRAIL) break; + if (opcode==OPCODE_LCC) StringFormatter::send(stream,F("\n"),getOperand(progCounter,0)); + if (opcode==OPCODE_LCCX) { // long form LCC + StringFormatter::send(stream,F("\n"), + getOperand(progCounter,1), + getOperand(progCounter,2), + getOperand(progCounter,3), + getOperand(progCounter,0) + ); + }} + + // we stream the hex events we wish to listen to + // and at the same time build the event index looku. + + + int eventIndex=0; + for (int progCounter=0;; SKIPOP) { + byte opcode=GET_OPCODE; + if (opcode==OPCODE_ENDEXRAIL) break; + if (opcode==OPCODE_ONLCC) { + onLCCLookup[eventIndex]=progCounter; // TODO skip... + StringFormatter::send(stream,F("\n"), + eventIndex, + getOperand(progCounter,1), + getOperand(progCounter,2), + getOperand(progCounter,3), + getOperand(progCounter,0) + ); + eventIndex++; + } + } + StringFormatter::send(stream,F("\n")); // Ready to rumble + opcode=0; + break; + } + if (paramCount==1) { // LCC event arrived from adapter + int16_t eventid=p[0]; + reject=eventid<0 || eventid>=countLCCLookup; + if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]); + opcode=0; + } + break; + + case 'J': // throttle info commands + // This entire code block is compiled out if FEATURE_ROUTESTATE macros not used + if (paramCount<1 || !(compileFeatures & FEATURE_ROUTESTATE)) return; + switch(p[0]) + case HASH_KEYWORD_A: // returns automations/routes + if (paramCount==1) {// + StringFormatter::send(stream, F("stream(stream); + StringFormatter::send(stream, F(">\n")); + opcode=0; + return; + } + if (paramCount==2) { // + uint16_t id=p[1]; + StringFormatter::send(stream,F("\n"), + id, getRouteType(id), getRouteDescription(id)); + + // Send any non-default button states or captions + int16_t statePos=routeLookup->findPosition(id); + if (statePos>=0) { + if (routeStateArray[statePos]) + StringFormatter::send(stream,F("\n"), id, routeStateArray[statePos]); + if (routeCaptionArray[statePos]) + StringFormatter::send(stream,F("\n"), id,routeCaptionArray[statePos]); + } + opcode=0; + return; + } + break; + default: // other commands pass through + break; + } +} + +bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { + + if (paramCount==0) { // STATUS + StringFormatter::send(stream, F("<* EXRAIL STATUS")); + RMFT2 * task=loopTask; + while(task) { + StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"), + (int)(task->taskId),task->progCounter,task->loco, + task->invert?'I':' ', + task->speedo, + task->forward?'F':'R' + ); + task=task->next; + if (task==loopTask) break; + } + // Now stream the flags + for (int id=0;id\n")); + return true; + } + switch (p[0]) { + case HASH_KEYWORD_PAUSE: // + if (paramCount!=1) return false; + DCC::setThrottle(0,1,true); // pause all locos on the track + pausingTask=(RMFT2 *)1; // Impossible task address + return true; + + case HASH_KEYWORD_RESUME: // + if (paramCount!=1) return false; + pausingTask=NULL; + { + RMFT2 * task=loopTask; + while(task) { + if (task->loco) task->driveLoco(task->speedo); + task=task->next; + if (task==loopTask) break; + } + } + return true; + + + case HASH_KEYWORD_START: // + if (paramCount<2 || paramCount>3) return false; + { + int route=(paramCount==2) ? p[1] : p[2]; + uint16_t cab=(paramCount==2)? 0 : p[1]; + int pc=routeLookup->find(route); + if (pc<0) return false; + RMFT2* task=new RMFT2(pc); + task->loco=cab; + } + return true; + + default: + break; + } + + // check KILL ALL here, otherwise the next validation confuses ALL with a flag + if (p[0]==HASH_KEYWORD_KILL && p[1]==HASH_KEYWORD_ALL) { + while (loopTask) loopTask->kill(F("KILL ALL")); // destructor changes loopTask + return true; + } + + // all other / commands take 1 parameter + if (paramCount!=2 ) return false; + + switch (p[0]) { + case HASH_KEYWORD_KILL: // Kill taskid|ALL + { + if ( p[1]<0 || p[1]>=MAX_FLAGS) return false; + RMFT2 * task=loopTask; + while(task) { + if (task->taskId==p[1]) { + task->kill(F("KILL")); + return true; + } + task=task->next; + if (task==loopTask) break; + } + } + return false; + + case HASH_KEYWORD_RESERVE: // force reserve a section + return setFlag(p[1],SECTION_FLAG); + + case HASH_KEYWORD_FREE: // force free a section + return setFlag(p[1],0,SECTION_FLAG); + + case HASH_KEYWORD_LATCH: + return setFlag(p[1], LATCH_FLAG); + + case HASH_KEYWORD_UNLATCH: + return setFlag(p[1], 0, LATCH_FLAG); + + case HASH_KEYWORD_RED: + doSignal(p[1],SIGNAL_RED); + return true; + + case HASH_KEYWORD_AMBER: + doSignal(p[1],SIGNAL_AMBER); + return true; + + case HASH_KEYWORD_GREEN: + doSignal(p[1],SIGNAL_GREEN); + return true; + + default: + return false; + } +} + diff --git a/EXRAILMacros.h b/EXRAILMacros.h index e11b5db..3c58699 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -102,6 +102,14 @@ void exrailHalSetup() { #define LCCX(senderid,eventid) | FEATURE_LCC #undef ONLCC #define ONLCC(senderid,eventid) | FEATURE_LCC +#undef ROUTE_ACTIVE +#define ROUTE_ACTIVE(id) | FEATURE_ROUTESTATE +#undef ROUTE_INACTIVE +#define ROUTE_INACTIVE(id) | FEATURE_ROUTESTATE +#undef ROUTE_HIDDEN +#define ROUTE_HIDDEN(id) | FEATURE_ROUTESTATE +#undef ROUTE_CAPTION +#define ROUTE_CAPTION(id,caption) | FEATURE_ROUTESTATE const byte RMFT2::compileFeatures = 0 #include "myAutomation.h" @@ -156,7 +164,7 @@ const int StringMacroTracker1=__COUNTER__; #undef ROUTE_CAPTION #define ROUTE_CAPTION(id,caption) \ case (__COUNTER__ - StringMacroTracker1) : {\ - CommandDistributor::broadcastRouteCaption(id,F(caption));\ + manageRouteCaption(id,F(caption));\ return;\ } #undef SERIAL From 670645db4be574c27eb9d4d59b30490ac6ff7254 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 19:28:29 +0000 Subject: [PATCH 112/310] Version 20 --- EXRAIL2.cpp | 1 - version.h | 3 ++- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 61e0264..bb672a5 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1270,7 +1270,6 @@ void RMFT2::manageRouteCaption(uint16_t id,const FSH* caption) { // set state beside it if (routeCaptionArray[position]==caption) return; routeCaptionArray[position]=caption; - DIAG(F("rCA[%d]=%d, c=%d"),position,routeStateArray[position],caption); CommandDistributor::broadcastRouteCaption(id,caption); } } diff --git a/version.h b/version.h index 9d5a7e1..44975df 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.19" +#define VERSION "5.1.20" +// 5.1.20 - EXRAIL Tidy and ROUTE_STATE, ROUTE_CAPTION // 5.1.19 - Only flag 2.2.0.0-dev as broken, not 2.2.0.0 // 5.1.18 - TURNOUTL bugfix // 5.1.17 - Divide out C for config and D for diag commands From 337af77a030ca57f9bfa5e1343965fe4069aa7aa Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 10 Nov 2023 20:33:14 +0100 Subject: [PATCH 113/310] booster test --- MotorDriver.cpp | 4 ++++ MotorDriver.h | 38 ++++++++++++++++++++++++++++++++++++-- TrackManager.cpp | 19 +++++++++++++------ 3 files changed, 53 insertions(+), 8 deletions(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 61e229f..15b5607 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -605,6 +605,10 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { DIAG(F("TRACK %c ALERT FAULT"), trackno + 'A'); } setPower(POWERMODE::ALERT); + if (trackMode & (TRACK_MODE_MAIN|TRACK_MODE_EXT)){ // add (&& isAutoreverse) later + DIAG(F("TRACK %c INVERT"), trackno + 'A'); + invertOutput(); + } break; } // all well diff --git a/MotorDriver.h b/MotorDriver.h index 20a91d3..c6e06b8 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -148,7 +148,9 @@ class MotorDriver { // otherwise the call from interrupt context can undo whatever we do // from outside interrupt void setBrake( bool on, bool interruptContext=false); - __attribute__((always_inline)) inline void setSignal( bool high) { + __attribute__((always_inline)) inline void setSignal( bool high) { + if (invertPhase) + high = !high; if (trackPWM) { DCCTimer::setPWM(signalPin,high); } @@ -168,6 +170,12 @@ class MotorDriver { pinMode(signalPin, OUTPUT); else pinMode(signalPin, INPUT); + if (signalPin2 != UNUSED_PIN) { + if (on) + pinMode(signalPin2, OUTPUT); + else + pinMode(signalPin2, INPUT); + } }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; void setDCSignal(byte speedByte); @@ -232,6 +240,32 @@ class MotorDriver { #endif inline void setMode(TRACK_MODE m) { trackMode = m; + invertOutput(trackMode & TRACK_MODE_DCX);// change later to TRACK_MODE_INVERTED? + }; + inline void invertOutput() { // toggles output inversion + invertPhase = !invertPhase; + invertOutput(invertPhase); + }; + inline void invertOutput(bool b) { // sets output inverted or not + if (b) + invertPhase = 1; + else + invertPhase = 0; +#if defined(ARDUINO_ARCH_ESP32) + pinpair p = getSignalPin(); + uint32_t *outreg = (uint32_t *)(GPIO_FUNC0_OUT_SEL_CFG_REG + 4*p.pin); + if (invertPhase) // set or clear the invert bit in the gpio out register + *outreg |= ((uint32_t)0x1 << GPIO_FUNC0_OUT_INV_SEL_S); + else + *outreg &= ~((uint32_t)0x1 << GPIO_FUNC0_OUT_INV_SEL_S); + if (p.invpin != UNUSED_PIN) { + outreg = (uint32_t *)(GPIO_FUNC0_OUT_SEL_CFG_REG + 4*p.invpin); + if (invertPhase) // clear or set the invert bit in the gpio out register + *outreg &= ~((uint32_t)0x1 << GPIO_FUNC0_OUT_INV_SEL_S); + else + *outreg |= ((uint32_t)0x1 << GPIO_FUNC0_OUT_INV_SEL_S); + } +#endif }; inline TRACK_MODE getMode() { return trackMode; @@ -263,7 +297,7 @@ class MotorDriver { bool invertBrake; // brake pin passed as negative means pin is inverted bool invertPower; // power pin passed as negative means pin is inverted bool invertFault; // fault pin passed as negative means pin is inverted - + bool invertPhase = 0; // phase of out pin is inverted // Raw to milliamp conversion factors avoiding float data types. // Milliamps=rawADCreading * sensefactorInternal / senseScale // diff --git a/TrackManager.cpp b/TrackManager.cpp index dedf45e..772f64e 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -197,8 +197,8 @@ void TrackManager::setPROGSignal( bool on) { void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { FOR_EACH_TRACK(t) { if (trackDCAddr[t]!=cab && cab != 0) continue; - if (track[t]->getMode()==TRACK_MODE_DC) track[t]->setDCSignal(speedbyte); - else if (track[t]->getMode()==TRACK_MODE_DCX) track[t]->setDCSignal(speedbyte ^ 128); + if (track[t]->getMode() & (TRACK_MODE_DC|TRACK_MODE_DCX)) + track[t]->setDCSignal(speedbyte); } } @@ -223,11 +223,18 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr pinpair p = track[trackToSet]->getSignalPin(); //DIAG(F("Track=%c remove pin %d"),trackToSet+'A', p.pin); gpio_reset_pin((gpio_num_t)p.pin); - pinMode(p.pin, OUTPUT); // gpio_reset_pin may reset to input if (p.invpin != UNUSED_PIN) { //DIAG(F("Track=%c remove ^pin %d"),trackToSet+'A', p.invpin); gpio_reset_pin((gpio_num_t)p.invpin); - pinMode(p.invpin, OUTPUT); // gpio_reset_pin may reset to input + } + + if (mode == TRACK_MODE_EXT) { + pinMode(26, INPUT); + gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback + gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false); + if (p.invpin != UNUSED_PIN) { + gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false); + } } #endif #ifndef DISABLE_PROG @@ -261,10 +268,12 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr track[trackToSet]->setBrake(false); } +#ifndef ARDUINO_ARCH_ESP32 // EXT is a special case where the signal pin is // turned off. So unless that is set, the signal // pin should be turned on track[trackToSet]->enableSignal(mode != TRACK_MODE_EXT); +#endif #ifndef ARDUINO_ARCH_ESP32 // re-evaluate HighAccuracy mode @@ -320,8 +329,6 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr void TrackManager::applyDCSpeed(byte t) { uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]); - if (track[t]->getMode()==TRACK_MODE_DCX) - speedByte = speedByte ^ 128; // reverse direction bit track[t]->setDCSignal(speedByte); } From d2d7a5cd1606b41830c814a047245204ff724d3d Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 20:13:33 +0000 Subject: [PATCH 114/310] EXRAIL multiple ON events --- EXRAIL2.cpp | 37 +++++++++++++++++++------------------ EXRAIL2.h | 7 ++++--- version.h | 3 ++- 3 files changed, 25 insertions(+), 22 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index bb672a5..6a9ee40 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -126,6 +126,13 @@ int16_t LookList::find(int16_t value) { void LookList::chain(LookList * chain) { m_chain=chain; } +void LookList::handleEvent(const FSH* reason,int16_t id) { + // New feature... create multiple ONhandlers + for (int i=0;ihandleEvent(F("RED"),id); + else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id); + else onAmberLookup->handleEvent(F("AMBER"),id); int16_t sigslot=getSignalSlot(id); if (sigslot<0) return; @@ -1084,26 +1091,26 @@ int16_t RMFT2::getSignalSlot(int16_t id) { void RMFT2::turnoutEvent(int16_t turnoutId, bool closed) { // Hunt for an ONTHROW/ONCLOSE for this turnout - if (closed) handleEvent(F("CLOSE"),onCloseLookup,turnoutId); - else handleEvent(F("THROW"),onThrowLookup,turnoutId); + if (closed) onCloseLookup->handleEvent(F("CLOSE"),turnoutId); + else onThrowLookup->handleEvent(F("THROW"),turnoutId); } void RMFT2::activateEvent(int16_t addr, bool activate) { // Hunt for an ONACTIVATE/ONDEACTIVATE for this accessory - if (activate) handleEvent(F("ACTIVATE"),onActivateLookup,addr); - else handleEvent(F("DEACTIVATE"),onDeactivateLookup,addr); + if (activate) onActivateLookup->handleEvent(F("ACTIVATE"),addr); + else onDeactivateLookup->handleEvent(F("DEACTIVATE"),addr); } void RMFT2::changeEvent(int16_t vpin, bool change) { // Hunt for an ONCHANGE for this sensor - if (change) handleEvent(F("CHANGE"),onChangeLookup,vpin); + if (change) onChangeLookup->handleEvent(F("CHANGE"),vpin); } #ifndef IO_NO_HAL void RMFT2::rotateEvent(int16_t turntableId, bool change) { // Hunt or an ONROTATE for this turntable - if (change) handleEvent(F("ROTATE"),onRotateLookup,turntableId); + if (change) onRotateLookup->handleEvent(F("ROTATE"),turntableId); } #endif @@ -1112,8 +1119,8 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) { if (Diag::CMD) DIAG(F("Looking for clock event at : %d"), clocktime); if (change) { - handleEvent(F("CLOCK"),onClockLookup,clocktime); - handleEvent(F("CLOCK"),onClockLookup,25*60+clocktime%60); + onClockLookup->handleEvent(F("CLOCK"),clocktime); + onClockLookup->handleEvent(F("CLOCK"),25*60+clocktime%60); } } @@ -1122,16 +1129,10 @@ void RMFT2::powerEvent(int16_t track, bool overload) { if (Diag::CMD) DIAG(F("Looking for Power event on track : %c"), track); if (overload) { - handleEvent(F("POWER"),onOverloadLookup,track); + onOverloadLookup->handleEvent(F("POWER"),track); } } - -void RMFT2::handleEvent(const FSH* reason,LookList* handlers, int16_t id) { - int pc= handlers->find(id); - if (pc>=0) startNonRecursiveTask(reason,id,pc); -} - void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) { // Check we dont already have a task running this handler RMFT2 * task=loopTask; diff --git a/EXRAIL2.h b/EXRAIL2.h index bcb517e..a4c0e5f 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -127,6 +127,8 @@ class LookList { int16_t findPosition(int16_t value); // finds index int16_t size(); void stream(Print * _stream); + void handleEvent(const FSH* reason,int16_t id); + private: int16_t m_size; int16_t m_loaded; @@ -166,7 +168,8 @@ class LookList { static const FSH * getRosterFunctions(int16_t id); static const FSH * getTurntableDescription(int16_t id); static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); - + static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); + private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); static bool parseSlash(Print * stream, byte & paramCount, int16_t p[]) ; @@ -183,9 +186,7 @@ private: #endif static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); - static void handleEvent(const FSH* reason,LookList* handlers, int16_t id); static uint16_t getOperand(int progCounter,byte n); - static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); static RMFT2 * loopTask; static RMFT2 * pausingTask; void delayMe(long millisecs); diff --git a/version.h b/version.h index 44975df..242d730 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.20" +#define VERSION "5.1.21" +// 5.1.21 - EXRAIL invoke multiple ON handlers for same event // 5.1.20 - EXRAIL Tidy and ROUTE_STATE, ROUTE_CAPTION // 5.1.19 - Only flag 2.2.0.0-dev as broken, not 2.2.0.0 // 5.1.18 - TURNOUTL bugfix From 2f3d489f1836d5ed1f6650b65bafc7d7a104ac54 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 10 Nov 2023 23:58:30 +0100 Subject: [PATCH 115/310] ESP32: autoreverse and booster prototype --- EXRAIL2.cpp | 2 +- MotorDriver.cpp | 2 +- MotorDriver.h | 12 +++- TrackManager.cpp | 162 ++++++++++++++++++++++++++--------------------- TrackManager.h | 2 +- 5 files changed, 102 insertions(+), 78 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index c902708..2e9761a 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -857,7 +857,7 @@ void RMFT2::loop2() { // If DC/DCX use my loco for DC address { TRACK_MODE mode = (TRACK_MODE)(operand>>8); - int16_t cab=(mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) ? loco : 0; + int16_t cab=(mode & TRACK_MODE_DC) ? loco : 0; TrackManager::setTrackMode(operand & 0x0F, mode, cab); } break; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 15b5607..c9b820e 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -605,7 +605,7 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { DIAG(F("TRACK %c ALERT FAULT"), trackno + 'A'); } setPower(POWERMODE::ALERT); - if (trackMode & (TRACK_MODE_MAIN|TRACK_MODE_EXT)){ // add (&& isAutoreverse) later + if ((trackMode & TRACK_MODE_AUTOINV) && (trackMode & (TRACK_MODE_MAIN|TRACK_MODE_EXT|TRACK_MODE_BOOST))){ DIAG(F("TRACK %c INVERT"), trackno + 'A'); invertOutput(); } diff --git a/MotorDriver.h b/MotorDriver.h index c6e06b8..db2ccc5 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -3,7 +3,7 @@ * © 2021 Mike S * © 2021 Fred Decker * © 2020 Chris Harlow - * © 2022 Harald Barth + * © 2022,2023 Harald Barth * All rights reserved. * * This file is part of CommandStation-EX @@ -28,8 +28,14 @@ #include "DCCTimer.h" // use powers of two so we can do logical and/or on the track modes in if clauses. +// RACK_MODE_DCX is (TRACK_MODE_DC|TRACK_MODE_INV) +template inline T operator~ (T a) { return (T)~(int)a; } +template inline T operator| (T a, T b) { return (T)((int)a | (int)b); } +template inline T operator& (T a, T b) { return (T)((int)a & (int)b); } +template inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); } enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4, - TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32}; + TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32, + TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72, TRACK_MODE_AUTOINV = 128}; #define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH #define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW @@ -240,7 +246,7 @@ class MotorDriver { #endif inline void setMode(TRACK_MODE m) { trackMode = m; - invertOutput(trackMode & TRACK_MODE_DCX);// change later to TRACK_MODE_INVERTED? + invertOutput(trackMode & TRACK_MODE_INV); }; inline void invertOutput() { // toggles output inversion invertPhase = !invertPhase; diff --git a/TrackManager.cpp b/TrackManager.cpp index 772f64e..1fffb0b 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -1,6 +1,6 @@ /* * © 2022 Chris Harlow - * © 2022 Harald Barth + * © 2022,2023 Harald Barth * © 2023 Colin Murdoch * All rights reserved. * @@ -45,6 +45,9 @@ const int16_t HASH_KEYWORD_DC = 2183; const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii. +const int16_t HASH_KEYWORD_AUTO = -5457; +const int16_t HASH_KEYWORD_BOOST = 11269; +const int16_t HASH_KEYWORD_INV = 11857; MotorDriver * TrackManager::track[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS]; @@ -87,7 +90,7 @@ void TrackManager::sampleCurrent() { if (!waiting) { // look for a valid track to sample or until we are around while (true) { - if (track[tr]->getMode() & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_DCX|TRACK_MODE_EXT )) { + if (track[tr]->getMode() & ( TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_BOOST|TRACK_MODE_EXT )) { track[tr]->startCurrentFromHW(); // for scope debug track[1]->setBrake(1); waiting = true; @@ -197,7 +200,7 @@ void TrackManager::setPROGSignal( bool on) { void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { FOR_EACH_TRACK(t) { if (trackDCAddr[t]!=cab && cab != 0) continue; - if (track[t]->getMode() & (TRACK_MODE_DC|TRACK_MODE_DCX)) + if (track[t]->getMode() & TRACK_MODE_DC) track[t]->setDCSignal(speedbyte); } } @@ -207,7 +210,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr //DIAG(F("Track=%c Mode=%d"),trackToSet+'A', mode); // DC tracks require a motorDriver that can set brake! - if (mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) { + if (mode & TRACK_MODE_DC) { #if defined(ARDUINO_AVR_UNO) DIAG(F("Uno has no PWM timers available for DC")); return false; @@ -227,24 +230,30 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr //DIAG(F("Track=%c remove ^pin %d"),trackToSet+'A', p.invpin); gpio_reset_pin((gpio_num_t)p.invpin); } - - if (mode == TRACK_MODE_EXT) { - pinMode(26, INPUT); + if (mode & TRACK_MODE_BOOST) { + DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin); + pinMode(26, INPUT); // hardcoded XXX gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false); if (p.invpin != UNUSED_PIN) { gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false); } + } else if (mode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_DC)) { + // gpio_reset_pin may reset to input + pinMode(p.pin, OUTPUT); + if (p.invpin != UNUSED_PIN) + pinMode(p.invpin, OUTPUT); } + #endif #ifndef DISABLE_PROG - if (mode==TRACK_MODE_PROG) { + if (mode & TRACK_MODE_PROG) { #else if (false) { #endif // only allow 1 track to be prog FOR_EACH_TRACK(t) - if (track[t]->getMode()==TRACK_MODE_PROG && t != trackToSet) { + if ( (track[t]->getMode() & TRACK_MODE_PROG) && t != trackToSet) { track[t]->setPower(POWERMODE::OFF); track[t]->setMode(TRACK_MODE_NONE); track[t]->makeProgTrack(false); // revoke prog track special handling @@ -262,18 +271,20 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr // state, otherwise trains run away or just dont move. // This can be done BEFORE the PWM-Timer evaluation (methinks) - if (!(mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX)) { + if (!(mode & TRACK_MODE_DC)) { // DCC tracks need to have set the PWM to zero or they will not work. track[trackToSet]->detachDCSignal(); track[trackToSet]->setBrake(false); } -#ifndef ARDUINO_ARCH_ESP32 - // EXT is a special case where the signal pin is - // turned off. So unless that is set, the signal - // pin should be turned on - track[trackToSet]->enableSignal(mode != TRACK_MODE_EXT); -#endif + // BOOST: + // Leave it as is + // otherwise: + // EXT is a special case where the signal pin is + // turned off. So unless that is set, the signal + // pin should be turned on + if (!(mode & TRACK_MODE_BOOST)) + track[trackToSet]->enableSignal(!(mode & TRACK_MODE_EXT)); #ifndef ARDUINO_ARCH_ESP32 // re-evaluate HighAccuracy mode @@ -283,7 +294,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr // DC tracks must not have the DCC PWM switched on // so we globally turn it off if one of the PWM // capable tracks is now DC or DCX. - if (track[t]->getMode()==TRACK_MODE_DC || track[t]->getMode()==TRACK_MODE_DCX) { + if (track[t]->getMode() & TRACK_MODE_DC) { if (track[t]->isPWMCapable()) { canDo=false; // this track is capable but can not run PWM break; // in this mode, so abort and prevent globally below @@ -291,7 +302,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr track[t]->trackPWM=false; // this track sure can not run with PWM //DIAG(F("Track %c trackPWM 0 (not capable)"), t+'A'); } - } else if (track[t]->getMode()==TRACK_MODE_MAIN || track[t]->getMode()==TRACK_MODE_PROG) { + } else if (track[t]->getMode() & (TRACK_MODE_MAIN |TRACK_MODE_PROG)) { track[t]->trackPWM = track[t]->isPWMCapable(); // trackPWM is still a guess here //DIAG(F("Track %c trackPWM %d"), t+'A', track[t]->trackPWM); canDo &= track[t]->trackPWM; @@ -309,10 +320,12 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr #else // For ESP32 we just reinitialize the DCC Waveform DCCWaveform::begin(); + // setMode() again AFTER Waveform::begin() of ESP32 fixes INVERTED signal + track[trackToSet]->setMode(mode); #endif // This block must be AFTER the PWM-Timer modifications - if (mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX) { + if (mode & TRACK_MODE_DC) { // DC tracks need to be given speed of the throttle for that cab address // otherwise will not match other tracks on same cab. // This also needs to allow for inverted DCX @@ -321,7 +334,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr // Normal running tracks are set to the global power state track[trackToSet]->setPower( - (mode==TRACK_MODE_MAIN || mode==TRACK_MODE_DC || mode==TRACK_MODE_DCX || mode==TRACK_MODE_EXT) ? + (mode & (TRACK_MODE_MAIN | TRACK_MODE_DC | TRACK_MODE_EXT | TRACK_MODE_BOOST)) ? mainPowerGuess : POWERMODE::OFF); //DIAG(F("TrackMode=%d"),mode); return true; @@ -361,11 +374,20 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT> return setTrackMode(p[0],TRACK_MODE_EXT); + if (params==2 && p[1]==HASH_KEYWORD_BOOST) // <= id BOOST> + return setTrackMode(p[0],TRACK_MODE_BOOST); + + if (params==2 && p[1]==HASH_KEYWORD_AUTO) // <= id AUTO> + return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV); + + if (params==2 && p[1]==HASH_KEYWORD_INV) // <= id AUTO> + return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_INV); + if (params==3 && p[1]==HASH_KEYWORD_DC && p[2]>0) // <= id DC cab> return setTrackMode(p[0],TRACK_MODE_DC,p[2]); if (params==3 && p[1]==HASH_KEYWORD_DCX && p[2]>0) // <= id DCX cab> - return setTrackMode(p[0],TRACK_MODE_DCX,p[2]); + return setTrackMode(p[0],TRACK_MODE_DC|TRACK_MODE_INV,p[2]); return false; } @@ -374,35 +396,38 @@ void TrackManager::streamTrackState(Print* stream, byte t) { // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; auto format=F(""); - bool pstate = TrackManager::isPowerOn(t); - - switch(track[t]->getMode()) { - case TRACK_MODE_MAIN: - if (pstate) {format=F("<= %c MAIN ON>\n");} else {format = F("<= %c MAIN OFF>\n");} - break; +// bool pstate = TrackManager::isPowerOn(t); +// char *statestr; +// if (pstate) +// statestr = (char *)"ON"; +// else +// statestr = (char *)"OFF"; + TRACK_MODE tm = track[t]->getMode(); + if (tm & TRACK_MODE_MAIN) + format=F("<= %c MAIN>\n"); #ifndef DISABLE_PROG - case TRACK_MODE_PROG: - if (pstate) {format=F("<= %c PROG ON>\n");} else {format=F("<= %c PROG OFF>\n");} - break; + else if (tm & TRACK_MODE_PROG) + format=F("<= %c PROG>\n"); #endif - case TRACK_MODE_NONE: - if (pstate) {format=F("<= %c NONE ON>\n");} else {format=F("<= %c NONE OFF>\n");} - break; - case TRACK_MODE_EXT: - if (pstate) {format=F("<= %c EXT ON>\n");} else {format=F("<= %c EXT OFF>\n");} - break; - case TRACK_MODE_DC: - if (pstate) {format=F("<= %c DC %d ON>\n");} else {format=F("<= %c DC %d OFF>\n");} - break; - case TRACK_MODE_DCX: - if (pstate) {format=F("<= %c DCX %d ON>\n");} else {format=F("<= %c DCX %d OFF>\n");} - break; - default: - break; // unknown, dont care + else if (tm & TRACK_MODE_NONE) + format=F("<= %c NONE>\n"); + else if(tm & TRACK_MODE_EXT) + format=F("<= %c EXT>\n"); + else if(tm & TRACK_MODE_BOOST) + format=F("<= %c BOOST>\n"); + else if (tm & TRACK_MODE_DC) { + if (tm & TRACK_MODE_INV) + format=F("<= %c DCX>\n"); + else + format=F("<= %c DC>\n"); } + else + format=F("<= %c XXX>\n"); - if (stream) StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); - else CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + if (stream) + StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + else + CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); } @@ -418,13 +443,13 @@ void TrackManager::loop() { if (nextCycleTrack>lastTrack) nextCycleTrack=0; if (track[nextCycleTrack]==NULL) return; MotorDriver * motorDriver=track[nextCycleTrack]; - bool useProgLimit=dontLimitProg? false: track[nextCycleTrack]->getMode()==TRACK_MODE_PROG; + bool useProgLimit=dontLimitProg ? false : (bool)(track[nextCycleTrack]->getMode() & TRACK_MODE_PROG); motorDriver->checkPowerOverload(useProgLimit, nextCycleTrack); } MotorDriver * TrackManager::getProgDriver() { FOR_EACH_TRACK(t) - if (track[t]->getMode()==TRACK_MODE_PROG) return track[t]; + if (track[t]->getMode() & TRACK_MODE_PROG) return track[t]; return NULL; } @@ -432,7 +457,7 @@ MotorDriver * TrackManager::getProgDriver() { std::vectorTrackManager::getMainDrivers() { std::vector v; FOR_EACH_TRACK(t) - if (track[t]->getMode()==TRACK_MODE_MAIN) v.push_back(track[t]); + if (track[t]->getMode() & TRACK_MODE_MAIN) v.push_back(track[t]); return v; } #endif @@ -453,40 +478,33 @@ void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byt MotorDriver * driver=track[thistrack]; if (!driver) return; - switch (track[thistrack]->getMode()) { - case TRACK_MODE_MAIN: - if (setProg) break; + TRACK_MODE tm = track[thistrack]->getMode(); + if ( (tm & TRACK_MODE_MAIN) + && !setProg ){ // toggle brake before turning power on - resets overcurrent error // on the Pololu board if brake is wired to ^D2. // XXX see if we can make this conditional driver->setBrake(true); driver->setBrake(false); // DCC runs with brake off - driver->setPower(mode); - break; - case TRACK_MODE_DC: - case TRACK_MODE_DCX: - //DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); - if (setProg || setJoin) break; + driver->setPower(mode); + } else if ( (tm & TRACK_MODE_DC) + && !(setProg || setJoin)){ + //DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); driver->setBrake(true); // DC starts with brake on applyDCSpeed(thistrack); // speed match DCC throttles driver->setPower(mode); - break; - case TRACK_MODE_PROG: - if (!setProg && !setJoin) break; + } else if ( (tm & TRACK_MODE_PROG) + && (setProg || setJoin) ){ driver->setBrake(true); driver->setBrake(false); driver->setPower(mode); - break; - case TRACK_MODE_EXT: + } else if ( (tm & TRACK_MODE_EXT) + || (tm & TRACK_MODE_BOOST)){ driver->setBrake(true); driver->setBrake(false); driver->setPower(mode); - break; - case TRACK_MODE_NONE: - break; - } - - } + } +} void TrackManager::reportPowerChange(Print* stream, byte thistrack) { // This function is for backward JMRI compatibility only @@ -499,7 +517,7 @@ void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byt POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) - if (track[t]->getMode()==TRACK_MODE_PROG) + if (track[t]->getMode() & TRACK_MODE_PROG) return track[t]->getPower(); return POWERMODE::OFF; } @@ -544,7 +562,7 @@ void TrackManager::setJoin(bool joined) { #ifdef ARDUINO_ARCH_ESP32 if (joined) { FOR_EACH_TRACK(t) { - if (track[t]->getMode()==TRACK_MODE_PROG) { + if (track[t]->getMode() & TRACK_MODE_PROG) { tempProgTrack = t; setTrackMode(t, TRACK_MODE_MAIN); break; @@ -573,7 +591,7 @@ bool TrackManager::isPowerOn(byte t) { } bool TrackManager::isProg(byte t) { - if (track[t]->getMode()==TRACK_MODE_PROG) + if (track[t]->getMode() & TRACK_MODE_PROG) return true; return false; } diff --git a/TrackManager.h b/TrackManager.h index d197751..d1edca2 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -112,7 +112,7 @@ class TrackManager { static POWERMODE mainPowerGuess; static void applyDCSpeed(byte t); - static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC or TRACK_MODE_DCX + static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC #ifdef ARDUINO_ARCH_ESP32 static byte tempProgTrack; // holds the prog track number during join #endif From 1c5f299b0e225e36c799dcc08c6bbb08c97f4adb Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 23:28:41 +0000 Subject: [PATCH 116/310] Fix ESP32 cast issue --- EXRAIL2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6a9ee40..9efd98b 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -332,7 +332,7 @@ void RMFT2::setTurntableHiddenState(Turntable * tto) { char RMFT2::getRouteType(int16_t id) { int16_t progCounter=routeLookup->find(id); if (progCounter>=0) { - OPCODE type=GET_OPCODE; + byte type=GET_OPCODE; if (type==OPCODE_ROUTE) return 'R'; if (type==OPCODE_AUTOMATION) return 'A'; } From 6c18226cb592f3244cc314d2a7d4ae280c4d2475 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 23:46:17 +0000 Subject: [PATCH 117/310] Fix non-exrail crash --- MotorDriver.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 61e229f..af322b8 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -676,8 +676,10 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { power_sample_overload_wait *= 2; if (power_sample_overload_wait > POWER_SAMPLE_RETRY_MAX) power_sample_overload_wait = POWER_SAMPLE_RETRY_MAX; + #ifdef EXRAIL_ACTIVE DIAG(F("Calling EXRAIL")); RMFT2::powerEvent(trackno, true); // Tell EXRAIL we have an overload + #endif // power on test DIAG(F("TRACK %c POWER RESTORE (after %4M)"), trackno + 'A', mslpc); setPower(POWERMODE::ALERT); From d877fc315ee1ddaedaf463ae883041974f63d36f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 10 Nov 2023 23:56:41 +0000 Subject: [PATCH 118/310] Fix non-routestate code eliminator --- EXRAIL2Parser.cpp | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index 7670118..7b241d0 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -122,7 +122,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 case 'J': // throttle info commands // This entire code block is compiled out if FEATURE_ROUTESTATE macros not used - if (paramCount<1 || !(compileFeatures & FEATURE_ROUTESTATE)) return; + if (paramCount<1) return; switch(p[0]) case HASH_KEYWORD_A: // returns automations/routes if (paramCount==1) {// @@ -136,14 +136,16 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 uint16_t id=p[1]; StringFormatter::send(stream,F("\n"), id, getRouteType(id), getRouteDescription(id)); - - // Send any non-default button states or captions - int16_t statePos=routeLookup->findPosition(id); - if (statePos>=0) { - if (routeStateArray[statePos]) - StringFormatter::send(stream,F("\n"), id, routeStateArray[statePos]); - if (routeCaptionArray[statePos]) - StringFormatter::send(stream,F("\n"), id,routeCaptionArray[statePos]); + + if (compileFeatures & FEATURE_ROUTESTATE) { + // Send any non-default button states or captions + int16_t statePos=routeLookup->findPosition(id); + if (statePos>=0) { + if (routeStateArray[statePos]) + StringFormatter::send(stream,F("\n"), id, routeStateArray[statePos]); + if (routeCaptionArray[statePos]) + StringFormatter::send(stream,F("\n"), id,routeCaptionArray[statePos]); + } } opcode=0; return; From 9ce95c07aaeda5ae710455368245fb1199783e1e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 Nov 2023 08:03:59 +0100 Subject: [PATCH 119/310] Booster mode configured by defined booster pin. New mode name output --- TrackManager.cpp | 39 ++++++++++++++++++++++++++++----------- config.example.h | 6 ++++++ 2 files changed, 34 insertions(+), 11 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 1fffb0b..3b380f1 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -46,7 +46,9 @@ const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii. const int16_t HASH_KEYWORD_AUTO = -5457; +#ifdef BOOSTER_INPUT const int16_t HASH_KEYWORD_BOOST = 11269; +#endif const int16_t HASH_KEYWORD_INV = 11857; MotorDriver * TrackManager::track[MAX_TRACKS]; @@ -230,15 +232,18 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr //DIAG(F("Track=%c remove ^pin %d"),trackToSet+'A', p.invpin); gpio_reset_pin((gpio_num_t)p.invpin); } +#ifdef BOOSTER_INPUT if (mode & TRACK_MODE_BOOST) { - DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin); - pinMode(26, INPUT); // hardcoded XXX + //DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin); + pinMode(BOOSTER_INPUT, INPUT); gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false); if (p.invpin != UNUSED_PIN) { gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false); } - } else if (mode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_DC)) { + } else // elseif clause continues +#endif + if (mode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_DC)) { // gpio_reset_pin may reset to input pinMode(p.pin, OUTPUT); if (p.invpin != UNUSED_PIN) @@ -373,10 +378,10 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT> return setTrackMode(p[0],TRACK_MODE_EXT); - +#ifdef BOOSTER_INPUT if (params==2 && p[1]==HASH_KEYWORD_BOOST) // <= id BOOST> return setTrackMode(p[0],TRACK_MODE_BOOST); - +#endif if (params==2 && p[1]==HASH_KEYWORD_AUTO) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV); @@ -403,8 +408,14 @@ void TrackManager::streamTrackState(Print* stream, byte t) { // else // statestr = (char *)"OFF"; TRACK_MODE tm = track[t]->getMode(); - if (tm & TRACK_MODE_MAIN) - format=F("<= %c MAIN>\n"); + if (tm & TRACK_MODE_MAIN) { + if(tm & TRACK_MODE_AUTOINV) + format=F("<= %c MAIN AUTOINV>\n"); + else if (tm & TRACK_MODE_INV) + format=F("<= %c MAIN INV>\n"); + else + format=F("<= %c MAIN>\n"); + } #ifndef DISABLE_PROG else if (tm & TRACK_MODE_PROG) format=F("<= %c PROG>\n"); @@ -413,13 +424,19 @@ void TrackManager::streamTrackState(Print* stream, byte t) { format=F("<= %c NONE>\n"); else if(tm & TRACK_MODE_EXT) format=F("<= %c EXT>\n"); - else if(tm & TRACK_MODE_BOOST) - format=F("<= %c BOOST>\n"); + else if(tm & TRACK_MODE_BOOST) { + if(tm & TRACK_MODE_AUTOINV) + format=F("<= %c BOOST AUTOINV>\n"); + else if (tm & TRACK_MODE_INV) + format=F("<= %c BOOST INV>\n"); + else + format=F("<= %c BOOST>\n"); + } else if (tm & TRACK_MODE_DC) { if (tm & TRACK_MODE_INV) - format=F("<= %c DCX>\n"); + format=F("<= %c DCX %d>\n"); else - format=F("<= %c DC>\n"); + format=F("<= %c DC %d>\n"); } else format=F("<= %c XXX>\n"); diff --git a/config.example.h b/config.example.h index 0f136f9..de31743 100644 --- a/config.example.h +++ b/config.example.h @@ -266,6 +266,12 @@ The configuration file for DCC-EX Command Station // //#define SERIAL_BT_COMMANDS +// BOOSTER PIN INPUT ON ESP32 +// On ESP32 you have the possibility to define a pin as booster input +// Arduio pin D2 is GPIO 26 on ESPDuino32 +// +//#define BOOSTER_INPUT 26 + // SABERTOOTH // // This is a very special option and only useful if you happen to have a From befcfebec7d2d6021389e37b714ae3f6baffe97d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 Nov 2023 08:15:15 +0100 Subject: [PATCH 120/310] version 5.2.0 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index d2a7fd1..867619e 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202310230944Z" +#define GITHUB_SHA "devel-202311110712Z" diff --git a/version.h b/version.h index 242d730..4258cf4 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.1.21" +#define VERSION "5.2.0" +// 5.2.0 - ESP32: Autoreverse and booster mode support // 5.1.21 - EXRAIL invoke multiple ON handlers for same event // 5.1.20 - EXRAIL Tidy and ROUTE_STATE, ROUTE_CAPTION // 5.1.19 - Only flag 2.2.0.0-dev as broken, not 2.2.0.0 From e8b9f80c8cd232cf1736c8740c7a534b776abf03 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 Nov 2023 09:45:28 +0100 Subject: [PATCH 121/310] Reformat reply to <=> --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- TrackManager.cpp | 35 +++++++++++++++-------------------- 3 files changed, 18 insertions(+), 23 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 351a18d..653bbef 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,8 +269,8 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter, dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, byte pstate, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format,trackLetter, pstate, dcAddr); } void CommandDistributor::broadcastRouteState(uint16_t routeId, byte state ) { diff --git a/CommandDistributor.h b/CommandDistributor.h index 83bfbbd..7dfcdf6 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter, byte pstate, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); static void broadcastRouteState(uint16_t routeId,byte state); diff --git a/TrackManager.cpp b/TrackManager.cpp index 3b380f1..647f07c 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -401,50 +401,45 @@ void TrackManager::streamTrackState(Print* stream, byte t) { // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; auto format=F(""); -// bool pstate = TrackManager::isPowerOn(t); -// char *statestr; -// if (pstate) -// statestr = (char *)"ON"; -// else -// statestr = (char *)"OFF"; + byte pstate = TrackManager::isPowerOn(t) ? 1 : 0; TRACK_MODE tm = track[t]->getMode(); if (tm & TRACK_MODE_MAIN) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c MAIN AUTOINV>\n"); + format=F("<= %c %d MAIN AUTOINV>\n"); else if (tm & TRACK_MODE_INV) - format=F("<= %c MAIN INV>\n"); + format=F("<= %c %d MAIN INV>\n"); else - format=F("<= %c MAIN>\n"); + format=F("<= %c %d MAIN>\n"); } #ifndef DISABLE_PROG else if (tm & TRACK_MODE_PROG) - format=F("<= %c PROG>\n"); + format=F("<= %c %d PROG>\n"); #endif else if (tm & TRACK_MODE_NONE) - format=F("<= %c NONE>\n"); + format=F("<= %c %d NONE>\n"); else if(tm & TRACK_MODE_EXT) - format=F("<= %c EXT>\n"); + format=F("<= %c %d EXT>\n"); else if(tm & TRACK_MODE_BOOST) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c BOOST AUTOINV>\n"); + format=F("<= %c %d BOOST AUTOINV>\n"); else if (tm & TRACK_MODE_INV) - format=F("<= %c BOOST INV>\n"); + format=F("<= %c %d BOOST INV>\n"); else - format=F("<= %c BOOST>\n"); + format=F("<= %c %d BOOST>\n"); } else if (tm & TRACK_MODE_DC) { if (tm & TRACK_MODE_INV) - format=F("<= %c DCX %d>\n"); + format=F("<= %c %d DCX %d>\n"); else - format=F("<= %c DC %d>\n"); + format=F("<= %c %d DC %d>\n"); } else - format=F("<= %c XXX>\n"); + format=F("<= %c %d XXX>\n"); if (stream) - StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + StringFormatter::send(stream,format,'A'+t, pstate, trackDCAddr[t]); else - CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + CommandDistributor::broadcastTrackState(format,'A'+t, pstate, trackDCAddr[t]); } From 4c89b26c791faca7abfc09903aea93afeb1dae09 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 11 Nov 2023 09:12:08 +0000 Subject: [PATCH 122/310] fix returns automations/routes if (paramCount==1) {// StringFormatter::send(stream, F(" Date: Sat, 11 Nov 2023 17:31:38 +0000 Subject: [PATCH 123/310] Fix returns automations/routes From 86ed8ff8a6aeb45abaf0a25def6d0d3e10815c82 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 13 Nov 2023 17:16:58 +0100 Subject: [PATCH 124/310] remove power state from <=> answer --- CommandDistributor.cpp | 4 ++-- CommandDistributor.h | 2 +- TrackManager.cpp | 31 ++++++++++++++----------------- 3 files changed, 17 insertions(+), 20 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 653bbef..cd9e89e 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -269,8 +269,8 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, byte pstate, int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format,trackLetter, pstate, dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format, trackLetter, dcAddr); } void CommandDistributor::broadcastRouteState(uint16_t routeId, byte state ) { diff --git a/CommandDistributor.h b/CommandDistributor.h index 7dfcdf6..83bfbbd 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter, byte pstate, int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); static void broadcastRouteState(uint16_t routeId,byte state); diff --git a/TrackManager.cpp b/TrackManager.cpp index 647f07c..8cdadb2 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -400,46 +400,43 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) void TrackManager::streamTrackState(Print* stream, byte t) { // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; - auto format=F(""); - byte pstate = TrackManager::isPowerOn(t) ? 1 : 0; + auto format=F("<= %d XXX>\n"); TRACK_MODE tm = track[t]->getMode(); if (tm & TRACK_MODE_MAIN) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c %d MAIN AUTOINV>\n"); + format=F("<= %c MAIN A>\n"); else if (tm & TRACK_MODE_INV) - format=F("<= %c %d MAIN INV>\n"); + format=F("<= %c MAIN I>\n"); else - format=F("<= %c %d MAIN>\n"); + format=F("<= %c MAIN>\n"); } #ifndef DISABLE_PROG else if (tm & TRACK_MODE_PROG) - format=F("<= %c %d PROG>\n"); + format=F("<= %c PROG>\n"); #endif else if (tm & TRACK_MODE_NONE) - format=F("<= %c %d NONE>\n"); + format=F("<= %c NONE>\n"); else if(tm & TRACK_MODE_EXT) - format=F("<= %c %d EXT>\n"); + format=F("<= %c EXT>\n"); else if(tm & TRACK_MODE_BOOST) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c %d BOOST AUTOINV>\n"); + format=F("<= %c B A>\n"); else if (tm & TRACK_MODE_INV) - format=F("<= %c %d BOOST INV>\n"); + format=F("<= %c B I>\n"); else - format=F("<= %c %d BOOST>\n"); + format=F("<= %c B>\n"); } else if (tm & TRACK_MODE_DC) { if (tm & TRACK_MODE_INV) - format=F("<= %c %d DCX %d>\n"); + format=F("<= %c DCX %d>\n"); else - format=F("<= %c %d DC %d>\n"); + format=F("<= %c DC %d>\n"); } - else - format=F("<= %c %d XXX>\n"); if (stream) - StringFormatter::send(stream,format,'A'+t, pstate, trackDCAddr[t]); + StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); else - CommandDistributor::broadcastTrackState(format,'A'+t, pstate, trackDCAddr[t]); + CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); } From 582ff890f4e41dafc00c54cebadbfc9a6d37db8f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 14 Nov 2023 00:05:18 +0100 Subject: [PATCH 125/310] Trackmanager rework for simpler structure --- CommandDistributor.cpp | 5 ++ DCCEXParser.cpp | 147 ++++++++++++----------------------------- EXRAIL2.cpp | 4 +- MotorDriver.h | 3 +- TrackManager.cpp | 115 +++++++++++++++++++------------- TrackManager.h | 15 ++--- 6 files changed, 126 insertions(+), 163 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index cd9e89e..89c8714 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -248,6 +248,11 @@ void CommandDistributor::broadcastLoco(byte slot) { } void CommandDistributor::broadcastPower() { + char pstr[] = "? x"; + for(byte t=0; t<8; t++) + if (TrackManager::getPower(t, pstr)) + broadcastReply(COMMAND_TYPE, F("\n"),pstr); + bool main=TrackManager::getMainPower()==POWERMODE::ON; bool prog=TrackManager::getProgPower()==POWERMODE::ON; bool join=TrackManager::isJoined(); diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 96596c6..3b91d86 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -553,131 +553,66 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case '1': // POWERON <1 [MAIN|PROG|JOIN]> { - bool main=false; - bool prog=false; - bool join=false; - bool singletrack=false; - //byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> - main=true; + if (params > 1) break; + if (params==0) { // All + TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::ON); + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> + TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::ON); } #ifndef DISABLE_PROG else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> - main=true; - prog=true; - join=true; + TrackManager::setJoin(true); + TrackManager::setTrackPower(TRACK_MODE_MAIN|TRACK_MODE_PROG, POWERMODE::ON); } else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> - prog=true; + TrackManager::setJoin(false); + TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::ON); } #endif - //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> - byte t = (p[0] - 'A'); - //DIAG(F("Processing track - %d "), t); - if (TrackManager::isProg(t)) { - main = false; - prog = true; - } - else - { - main=true; - prog=false; - } - singletrack=true; - if (main) TrackManager::setTrackPower(false, false, POWERMODE::ON, t); - if (prog) TrackManager::setTrackPower(true, false, POWERMODE::ON, t); - - StringFormatter::send(stream, F("<1 %c>\n"), t+'A'); - //CommandDistributor::broadcastPower(); - //TrackManager::streamTrackState(NULL,t); - return; + byte t = (p[0] - 'A'); + TrackManager::setTrackPower(POWERMODE::ON, t); + //StringFormatter::send(stream, F("\n"), t+'A'); } - else break; // will reply - } - - if (!singletrack) { - TrackManager::setJoin(join); - if (join) TrackManager::setJoinPower(POWERMODE::ON); - else { - if (main) TrackManager::setMainPower(POWERMODE::ON); - if (prog) TrackManager::setProgPower(POWERMODE::ON); - } - CommandDistributor::broadcastPower(); + } + CommandDistributor::broadcastPower(); + //TrackManager::streamTrackState(NULL,t); - return; - } + return; + } - } - case '0': // POWEROFF <0 [MAIN | PROG] > { - bool main=false; - bool prog=false; - bool singletrack=false; - //byte t=0; - if (params > 1) break; - if (params==0) { // All - main=true; - prog=true; - } - if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> - main=true; - } + if (params > 1) break; + if (params==0) { // All + TrackManager::setJoin(false); + TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::OFF); + } + if (params==1) { + if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> + TrackManager::setJoin(false); + TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::OFF); + } #ifndef DISABLE_PROG else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> - prog=true; + TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off + TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::OFF); } #endif - //else if (p[0] >= 'A' && p[0] <= 'H') { // <1 A-H> - else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> - byte t = (p[0] - 'A'); - //DIAG(F("Processing track - %d "), t); - if (TrackManager::isProg(t)) { - main = false; - prog = true; - } - else - { - main=true; - prog=false; - } - singletrack=true; - TrackManager::setJoin(false); - if (main) TrackManager::setTrackPower(false, false, POWERMODE::OFF, t); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setTrackPower(true, false, POWERMODE::OFF, t); - } - StringFormatter::send(stream, F("<0 %c>\n"), t+'A'); - //CommandDistributor::broadcastPower(); - //TrackManager::streamTrackState(NULL, t); - return; - } - - else break; // will reply + else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> + byte t = (p[0] - 'A'); + TrackManager::setJoin(false); + TrackManager::setTrackPower(POWERMODE::OFF, t); + //StringFormatter::send(stream, F("\n"), t+'A'); } - - if (!singletrack) { - TrackManager::setJoin(false); - - if (main) TrackManager::setMainPower(POWERMODE::OFF); - if (prog) { - TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off - TrackManager::setProgPower(POWERMODE::OFF); - } - CommandDistributor::broadcastPower(); - return; - } - } + else break; // will reply + } + CommandDistributor::broadcastPower(); + return; + } case '!': // ESTOP ALL DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 8e6a6b5..933650c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -636,10 +636,10 @@ void RMFT2::loop2() { //byte thistrack=getOperand(1); switch (operand) { case TRACK_POWER_0: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::OFF, getOperand(1)); + TrackManager::setTrackPower(POWERMODE::OFF, getOperand(1)); break; case TRACK_POWER_1: - TrackManager::setTrackPower(TrackManager::isProg(getOperand(1)), false, POWERMODE::ON, getOperand(1)); + TrackManager::setTrackPower(POWERMODE::ON, getOperand(1)); break; } diff --git a/MotorDriver.h b/MotorDriver.h index db2ccc5..19bfd13 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -35,7 +35,8 @@ template inline T operator& (T a, T b) { return (T)((int)a & (int)b); } template inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); } enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4, TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32, - TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72, TRACK_MODE_AUTOINV = 128}; + TRACK_MODE_ALL = 62, // only to operate all tracks + TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72 /*DC + INV*/, TRACK_MODE_AUTOINV = 128}; #define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH #define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW diff --git a/TrackManager.cpp b/TrackManager.cpp index 8cdadb2..ff56001 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -471,51 +471,48 @@ std::vectorTrackManager::getMainDrivers() { } #endif -void TrackManager::setPower2(bool setProg,bool setJoin, POWERMODE mode) { - if (!setProg) mainPowerGuess=mode; - FOR_EACH_TRACK(t) { - - TrackManager::setTrackPower(setProg, setJoin, mode, t); - - } - return; -} - -void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack) { - - //DIAG(F("SetTrackPower Processing Track %d"), thistrack); - MotorDriver * driver=track[thistrack]; - if (!driver) return; - - TRACK_MODE tm = track[thistrack]->getMode(); - if ( (tm & TRACK_MODE_MAIN) - && !setProg ){ - // toggle brake before turning power on - resets overcurrent error - // on the Pololu board if brake is wired to ^D2. - // XXX see if we can make this conditional - driver->setBrake(true); - driver->setBrake(false); // DCC runs with brake off - driver->setPower(mode); - } else if ( (tm & TRACK_MODE_DC) - && !(setProg || setJoin)){ - //DIAG(F("Processing track - %d setProg %d"), thistrack, setProg); - driver->setBrake(true); // DC starts with brake on - applyDCSpeed(thistrack); // speed match DCC throttles - driver->setPower(mode); - } else if ( (tm & TRACK_MODE_PROG) - && (setProg || setJoin) ){ - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); - } else if ( (tm & TRACK_MODE_EXT) - || (tm & TRACK_MODE_BOOST)){ - driver->setBrake(true); - driver->setBrake(false); - driver->setPower(mode); +// Set track power for all tracks with this mode +void TrackManager::setTrackPower(TRACK_MODE trackmode, POWERMODE powermode) { + FOR_EACH_TRACK(t) { + MotorDriver *driver=track[t]; + if (trackmode & driver->getMode()) { + if (powermode == POWERMODE::ON) { + if (trackmode & TRACK_MODE_DC) { + driver->setBrake(true); // DC starts with brake on + applyDCSpeed(t); // speed match DCC throttles + } else { + // toggle brake before turning power on - resets overcurrent error + // on the Pololu board if brake is wired to ^D2. + driver->setBrake(true); + driver->setBrake(false); // DCC runs with brake off + } } + driver->setPower(powermode); + } + } } - void TrackManager::reportPowerChange(Print* stream, byte thistrack) { +// Set track power for this track, inependent of mode +void TrackManager::setTrackPower(POWERMODE powermode, byte t) { + MotorDriver *driver=track[t]; + TRACK_MODE trackmode = driver->getMode(); + if (trackmode & TRACK_MODE_DC) { + if (powermode == POWERMODE::ON) { + driver->setBrake(true); // DC starts with brake on + applyDCSpeed(t); // speed match DCC throttles + } + } else { + if (powermode == POWERMODE::ON) { + // toggle brake before turning power on - resets overcurrent error + // on the Pololu board if brake is wired to ^D2. + driver->setBrake(true); + driver->setBrake(false); // DCC runs with brake off + } + } + driver->setPower(powermode); +} + +void TrackManager::reportPowerChange(Print* stream, byte thistrack) { // This function is for backward JMRI compatibility only // It reports the first track only, as main, regardless of track settings. // @@ -524,12 +521,38 @@ void TrackManager::setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byt track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); } +// returns state of the one and only prog track POWERMODE TrackManager::getProgPower() { - FOR_EACH_TRACK(t) - if (track[t]->getMode() & TRACK_MODE_PROG) - return track[t]->getPower(); - return POWERMODE::OFF; + FOR_EACH_TRACK(t) + if (track[t]->getMode() & TRACK_MODE_PROG) + return track[t]->getPower(); // optimize: there is max one prog track + return POWERMODE::OFF; +} + +// returns on if all are on. returns off otherwise +POWERMODE TrackManager::getMainPower() { + POWERMODE result = POWERMODE::OFF; + FOR_EACH_TRACK(t) { + if (track[t]->getMode() & TRACK_MODE_MAIN) { + POWERMODE p = track[t]->getPower(); + if (p == POWERMODE::OFF) + return POWERMODE::OFF; // done and out + if (p == POWERMODE::ON) + result = POWERMODE::ON; + } } + return result; +} + +bool TrackManager::getPower(byte t, char s[]) { + if (track[t]) { + s[0] = track[t]->getPower() == POWERMODE::ON ? '1' : '0'; + s[2] = t + 'A'; + return true; + } + return false; +} + void TrackManager::reportObsoleteCurrent(Print* stream) { // This function is for backward JMRI compatibility only diff --git a/TrackManager.h b/TrackManager.h index d1edca2..644c45a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -62,23 +62,22 @@ class TrackManager { static void setDCSignal(int16_t cab, byte speedbyte); static MotorDriver * getProgDriver(); #ifdef ARDUINO_ARCH_ESP32 - static std::vectorgetMainDrivers(); + static std::vectorgetMainDrivers(); #endif - static void setPower2(bool progTrack,bool joinTrack,POWERMODE mode); static void setPower(POWERMODE mode) {setMainPower(mode); setProgPower(mode);} - static void setMainPower(POWERMODE mode) {setPower2(false,false,mode);} - static void setProgPower(POWERMODE mode) {setPower2(true,false,mode);} - static void setJoinPower(POWERMODE mode) {setPower2(false,true,mode);} - static void setTrackPower(bool setProg, bool setJoin, POWERMODE mode, byte thistrack); - + static void setTrackPower(POWERMODE mode, byte t); + static void setTrackPower(TRACK_MODE trackmode, POWERMODE powermode); + static void setMainPower(POWERMODE mode) {setTrackPower(TRACK_MODE_MAIN, mode);} + static void setProgPower(POWERMODE mode) {setTrackPower(TRACK_MODE_PROG, mode);} static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); static bool parseJ(Print * stream, int16_t params, int16_t p[]); static void loop(); - static POWERMODE getMainPower() {return mainPowerGuess;} + static POWERMODE getMainPower(); static POWERMODE getProgPower(); + static bool getPower(byte t, char s[]); static void setJoin(bool join); static bool isJoined() { return progTrackSyncMain;} static void setJoinRelayPin(byte joinRelayPin); From 503378f1bbee6d8bb55d60ae3728a2b60f6a908b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 14 Nov 2023 00:06:53 +0100 Subject: [PATCH 126/310] version 5.2.1 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 867619e..71069ca 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311110712Z" +#define GITHUB_SHA "devel-202311132306Z" diff --git a/version.h b/version.h index 4258cf4..5640feb 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.0" +#define VERSION "5.2.1" +// 5.2.1 - Trackmanager rework for simpler structure // 5.2.0 - ESP32: Autoreverse and booster mode support // 5.1.21 - EXRAIL invoke multiple ON handlers for same event // 5.1.20 - EXRAIL Tidy and ROUTE_STATE, ROUTE_CAPTION From 763ef8be34743835308ad7eaad31a1d59db8b471 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 14 Nov 2023 11:12:14 +0100 Subject: [PATCH 127/310] prettier MAX_TRACKS --- CommandDistributor.cpp | 2 +- TrackManager.cpp | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 89c8714..4269492 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -249,7 +249,7 @@ void CommandDistributor::broadcastLoco(byte slot) { void CommandDistributor::broadcastPower() { char pstr[] = "? x"; - for(byte t=0; t<8; t++) + for(byte t=0; t\n"),pstr); diff --git a/TrackManager.cpp b/TrackManager.cpp index ff56001..7c1e651 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -526,7 +526,7 @@ POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) if (track[t]->getMode() & TRACK_MODE_PROG) return track[t]->getPower(); // optimize: there is max one prog track - return POWERMODE::OFF; + return POWERMODE::OFF; } // returns on if all are on. returns off otherwise @@ -545,6 +545,8 @@ POWERMODE TrackManager::getMainPower() { } bool TrackManager::getPower(byte t, char s[]) { + if (t > lastTrack) + return false; if (track[t]) { s[0] = track[t]->getPower() == POWERMODE::ON ? '1' : '0'; s[2] = t + 'A'; From 1af5132e6aca4dea56636ba5df9f2533d538f17a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 14 Nov 2023 11:16:54 +0100 Subject: [PATCH 128/310] version 5.2.1 timestamp --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 71069ca..3f9b1e1 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311132306Z" +#define GITHUB_SHA "devel-202311141013Z" From 566ce1b7f80066d92e1873ad091ef221ccb11d9d Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 14 Nov 2023 19:41:05 +0000 Subject: [PATCH 129/310] Virtual LCD phase 1 --- CommandDistributor.cpp | 49 ++++++++++++++++++++++++++++++++++++++++++ CommandDistributor.h | 9 +++++++- DCCEXParser.cpp | 6 +++++- StringFormatter.cpp | 17 +++++++++++++++ StringFormatter.h | 1 - 5 files changed, 79 insertions(+), 3 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 351a18d..788e4e6 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -105,6 +105,7 @@ void CommandDistributor::parse(byte clientId,byte * buffer, RingStream * stream void CommandDistributor::forget(byte clientId) { if (clients[clientId]==WITHROTTLE_TYPE) WiThrottle::forget(clientId); clients[clientId]=NONE_TYPE; + if (virtualLCDClient==clientId) virtualLCDClient=RingStream::NO_CLIENT; } #endif @@ -280,3 +281,51 @@ void CommandDistributor::broadcastRouteState(uint16_t routeId, byte state ) { void CommandDistributor::broadcastRouteCaption(uint16_t routeId, const FSH* caption ) { broadcastReply(COMMAND_TYPE, F("\n"),routeId,caption); } + +Print * CommandDistributor::getVirtualLCDSerial(byte screen, byte row) { + Print * stream=virtualLCDSerial; + #ifdef CD_HANDLE_RING + rememberVLCDClient=RingStream::NO_CLIENT; + if (!stream && virtualLCDClient!=RingStream::NO_CLIENT) { + // If we are broadcasting from a wifi/eth process we need to complete its output + // before merging broadcasts in the ring, then reinstate it in case + // the process continues to output to its client. + if ((rememberVLCDClient = ring->peekTargetMark()) != RingStream::NO_CLIENT) { + ring->commit(); + } + ring->mark(virtualLCDClient); + stream=ring; + } + #endif + if (stream) StringFormatter::send(stream,F("<@ %d %d \""), screen,row); + return stream; +} + +void CommandDistributor::commitVirtualLCDSerial() { + #ifdef CD_HANDLE_RING + if (virtualLCDClient!=RingStream::NO_CLIENT) { + StringFormatter::send(ring,F("\">\n")); + ring->commit(); + if (rememberVLCDClient!=RingStream::NO_CLIENT) ring->mark(rememberVLCDClient); + return; + } + #endif + StringFormatter::send(virtualLCDSerial,F("\">\n")); +} + +void CommandDistributor::setVirtualLCDSerial(Print * stream) { + #ifdef CD_HANDLE_RING + virtualLCDClient=RingStream::NO_CLIENT; + if (stream && stream->availableForWrite()==RingStream::THIS_IS_A_RINGSTREAM) { + virtualLCDClient=((RingStream *) stream)->peekTargetMark(); + virtualLCDSerial=nullptr; + return; + } + #endif + virtualLCDSerial=stream; +} + +Print* CommandDistributor::virtualLCDSerial=nullptr; +byte CommandDistributor::virtualLCDClient=0xFF; +byte CommandDistributor::rememberVLCDClient=0; + diff --git a/CommandDistributor.h b/CommandDistributor.h index 83bfbbd..359c0fe 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -60,8 +60,15 @@ public : static void forget(byte clientId); static void broadcastRouteState(uint16_t routeId,byte state); static void broadcastRouteCaption(uint16_t routeId,const FSH * caption); - + // Handling code for virtual LCD receiver. + static Print * getVirtualLCDSerial(byte screen, byte row); + static void commitVirtualLCDSerial(); + static void setVirtualLCDSerial(Print * stream); + private: + static Print * virtualLCDSerial; + static byte virtualLCDClient; + static byte rememberVLCDClient; }; #endif diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 96596c6..369d941 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -724,7 +724,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) return; break; #endif - case '=': // TACK MANAGER CONTROL <= [params]> + case '=': // TRACK MANAGER CONTROL <= [params]> if (TrackManager::parseJ(stream, params, p)) return; break; @@ -897,6 +897,10 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case 'L': // LCC interface implemented in EXRAIL parser break; // Will if not intercepted by EXRAIL + case '@': // JMRI saying "give me virtual LCD msgs" + CommandDistributor::setVirtualLCDSerial(stream); + return; + default: //anything else will diagnose and drop out to DIAG(F("Opcode=%c params=%d"), opcode, params); for (int i = 0; i < params; i++) diff --git a/StringFormatter.cpp b/StringFormatter.cpp index b40de1c..218e617 100644 --- a/StringFormatter.cpp +++ b/StringFormatter.cpp @@ -19,6 +19,7 @@ #include "StringFormatter.h" #include #include "DisplayInterface.h" +#include "CommandDistributor.h" bool Diag::ACK=false; bool Diag::CMD=false; @@ -45,6 +46,14 @@ void StringFormatter::lcd(byte row, const FSH* input...) { send2(&USB_SERIAL,input,args); send(&USB_SERIAL,F(" *>\n")); + // send to virtual LCD collector (if any) + Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(0,row); + if (virtualLCD) { + va_start(args, input); + send2(virtualLCD,input,args); + CommandDistributor::commitVirtualLCDSerial(); + } + DisplayInterface::setRow(row); va_start(args, input); send2(DisplayInterface::getDisplayHandler(),input,args); @@ -52,6 +61,14 @@ void StringFormatter::lcd(byte row, const FSH* input...) { void StringFormatter::lcd2(uint8_t display, byte row, const FSH* input...) { va_list args; + + // send to virtual LCD collector (if any) + Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(display,row); + if (virtualLCD) { + va_start(args, input); + send2(virtualLCD,input,args); + CommandDistributor::commitVirtualLCDSerial(); + } DisplayInterface::setRow(display, row); va_start(args, input); diff --git a/StringFormatter.h b/StringFormatter.h index 1231d54..25d15e2 100644 --- a/StringFormatter.h +++ b/StringFormatter.h @@ -54,6 +54,5 @@ class StringFormatter private: static void send2(Print * serial, const FSH* input,va_list args); static void printPadded(Print* stream, long value, byte width, bool formatLeft); - }; #endif From 6da3153dd5d1b7dfa218727d64153f4aed572b97 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Wed, 15 Nov 2023 19:29:24 +0000 Subject: [PATCH 130/310] Define scroll rows in config Allow the definition of MAX_CHARACTER_ROWS in config.h --- Display.h | 2 ++ config.example.h | 8 ++++++++ 2 files changed, 10 insertions(+) diff --git a/Display.h b/Display.h index af36d43..467424f 100644 --- a/Display.h +++ b/Display.h @@ -37,7 +37,9 @@ class Display : public DisplayInterface { public: Display(DisplayDevice *deviceDriver); +#if !defined (MAX_CHARACTER_ROWS) static const int MAX_CHARACTER_ROWS = 8; +#endif static const int MAX_CHARACTER_COLS = MAX_MSG_SIZE; static const long DISPLAY_SCROLL_TIME = 3000; // 3 seconds diff --git a/config.example.h b/config.example.h index de31743..9909371 100644 --- a/config.example.h +++ b/config.example.h @@ -167,6 +167,14 @@ The configuration file for DCC-EX Command Station // * #define SCROLLMODE 2 is by row (move up 1 row at a time). #define SCROLLMODE 1 +// In order to avoid wasting memory the current scroll buffer is limited +// to 8 lines. Some users wishing to display additional information +// such as TrackManager power states have requested additional rows aware +// of the warning that this will take extra RAM. if you wish to include additional rows +// uncomment the following #define and set the number of lines you need. +//#define MAX_CHARACTER_ROWS 12 + + ///////////////////////////////////////////////////////////////////////////////////// // DISABLE EEPROM // From b472230b47b86d169a21b26f4566e94c7eb4abf4 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Wed, 15 Nov 2023 19:41:56 +0000 Subject: [PATCH 131/310] Update version.h Updated version.h --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 5640feb..3030981 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.1" +#define VERSION "5.2.2" +// 5.2.2 - Added option to allow MAX_CHARACTER_ROWS to be defined in config.h // 5.2.1 - Trackmanager rework for simpler structure // 5.2.0 - ESP32: Autoreverse and booster mode support // 5.1.21 - EXRAIL invoke multiple ON handlers for same event From 7bd2ba9b418bb2f5768c5e572ee26242780e3353 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 16 Nov 2023 00:27:23 +0100 Subject: [PATCH 132/310] Bugfix: Catch stange input to parser --- DCCEXParser.cpp | 23 +++++++++++++++++------ SerialManager.cpp | 17 +++++++++-------- 2 files changed, 26 insertions(+), 14 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 3b91d86..82a1042 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -210,8 +210,10 @@ int16_t DCCEXParser::splitValues(int16_t result[MAX_COMMAND_PARAMS], const byte case 1: // skipping spaces before a param if (hot == ' ') break; - if (hot == '\0' || hot == '>') - return parameterCount; + if (hot == '\0') + return -1; + if (hot == '>') + return parameterCount; state = 2; continue; @@ -304,14 +306,19 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) #ifndef DISABLE_EEPROM (void)EEPROM; // tell compiler not to warn this is unused #endif + byte params = 0; if (Diag::CMD) DIAG(F("PARSING:%s"), com); int16_t p[MAX_COMMAND_PARAMS]; while (com[0] == '<' || com[0] == ' ') com++; // strip off any number of < or spaces byte opcode = com[0]; - byte params = splitValues(p, com, opcode=='M' || opcode=='P'); - + int16_t splitnum = splitValues(p, com, opcode=='M' || opcode=='P'); + if (splitnum < 0 || splitnum >= MAX_COMMAND_PARAMS) // if arguments are broken, leave but via printing + goto out; + // Because of check above we are now inside byte size + params = splitnum; + if (filterCallback) filterCallback(stream, opcode, params, p); if (filterRMFTCallback && opcode!='\0') @@ -833,14 +840,18 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) break; // Will if not intercepted by EXRAIL default: //anything else will diagnose and drop out to + if (opcode >= ' ' && opcode <= '~') { DIAG(F("Opcode=%c params=%d"), opcode, params); for (int i = 0; i < params; i++) DIAG(F("p[%d]=%d (0x%x)"), i, p[i], p[i]); - break; + } else { + DIAG(F("Unprintable %x"), opcode); + } + break; } // end of opcode switch - // Any fallout here sends an +out:// Any fallout here sends an StringFormatter::send(stream, F("\n")); } diff --git a/SerialManager.cpp b/SerialManager.cpp index bacfceb..88bc7cd 100644 --- a/SerialManager.cpp +++ b/SerialManager.cpp @@ -111,14 +111,15 @@ void SerialManager::loop2() { bufferLength = 0; buffer[0] = '\0'; } - else if (ch == '>') { - buffer[bufferLength] = '\0'; - DCCEXParser::parse(serial, buffer, NULL); - inCommandPayload = false; - break; - } - else if (inCommandPayload) { - if (bufferLength < (COMMAND_BUFFER_SIZE-1)) buffer[bufferLength++] = ch; + else if (inCommandPayload) { + if (bufferLength < (COMMAND_BUFFER_SIZE-1)) + buffer[bufferLength++] = ch; + if (ch == '>') { + buffer[bufferLength] = '\0'; + DCCEXParser::parse(serial, buffer, NULL); + inCommandPayload = false; + break; + } } } From 102d6078a7c290b05eb2d531bae5ab7bbbd37c78 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 16 Nov 2023 08:38:39 +0100 Subject: [PATCH 133/310] version 5.2.3 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 3f9b1e1..2a558fc 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311141013Z" +#define GITHUB_SHA "devel-202311160737Z" diff --git a/version.h b/version.h index 3030981..c14d2b0 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.2" +#define VERSION "5.2.3" +// 5.2.3 - Bugfix: Catch stange input to parser // 5.2.2 - Added option to allow MAX_CHARACTER_ROWS to be defined in config.h // 5.2.1 - Trackmanager rework for simpler structure // 5.2.0 - ESP32: Autoreverse and booster mode support From 2ba5adc8b42bfd5323e09f4bf2b6585321129a8e Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 17 Nov 2023 10:45:36 +0000 Subject: [PATCH 134/310] 5.2.3 @ and ROUTE_DISABLED --- DCCEXParser.cpp | 4 ++++ EXRAIL2.cpp | 3 +++ EXRAIL2.h | 1 + EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 3 +++ StringFormatter.cpp | 15 +++++++++------ version.h | 2 ++ 7 files changed, 24 insertions(+), 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 4ceedea..aed185b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -115,6 +115,7 @@ Once a new OPCODE is decided upon, update this list. #include "DCCTimer.h" #include "EXRAIL2.h" #include "Turntables.h" +#include "version.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -841,6 +842,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case '@': // JMRI saying "give me virtual LCD msgs" CommandDistributor::setVirtualLCDSerial(stream); + StringFormatter::send(stream, + F("<@ 0 0 \"DCC-EX v" VERSION "\">\n" + "<@ 0 1 \"Lic GPLv3\">\n")); return; default: //anything else will diagnose and drop out to diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index ccd4d9e..6f0a835 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -932,6 +932,9 @@ void RMFT2::loop2() { case OPCODE_ROUTE_ACTIVE: manageRouteState(operand,1); break; + case OPCODE_ROUTE_DISABLED: + manageRouteState(operand,4); + break; case OPCODE_ROUTE: case OPCODE_AUTOMATION: diff --git a/EXRAIL2.h b/EXRAIL2.h index a4c0e5f..8f777f4 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -69,6 +69,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_LCC,OPCODE_LCCX,OPCODE_ONLCC, OPCODE_ONOVERLOAD, OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN, + OPCODE_ROUTE_DISABLED, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index ff8dc8d..ee240ed 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -129,6 +129,7 @@ #undef ROUTE_ACTIVE #undef ROUTE_INACTIVE #undef ROUTE_HIDDEN +#undef ROUTE_DISABLED #undef ROUTE_CAPTION #undef SENDLOCO #undef SEQUENCE @@ -274,6 +275,7 @@ #define ROUTE_ACTIVE(id) #define ROUTE_INACTIVE(id) #define ROUTE_HIDDEN(id) +#define ROUTE_DISABLED(id) #define ROUTE_CAPTION(id,caption) #define SENDLOCO(cab,route) #define SEQUENCE(id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 3c58699..6024290 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -108,6 +108,8 @@ void exrailHalSetup() { #define ROUTE_INACTIVE(id) | FEATURE_ROUTESTATE #undef ROUTE_HIDDEN #define ROUTE_HIDDEN(id) | FEATURE_ROUTESTATE +#undef ROUTE_DISABLED +#define ROUTE_DISABLED(id) | FEATURE_ROUTESTATE #undef ROUTE_CAPTION #define ROUTE_CAPTION(id,caption) | FEATURE_ROUTESTATE @@ -457,6 +459,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ROUTE_ACTIVE(id) OPCODE_ROUTE_ACTIVE,V(id), #define ROUTE_INACTIVE(id) OPCODE_ROUTE_INACTIVE,V(id), #define ROUTE_HIDDEN(id) OPCODE_ROUTE_HIDDEN,V(id), +#define ROUTE_DISABLED(id) OPCODE_ROUTE_DISABLED,V(id), #define ROUTE_CAPTION(id,caption) PRINT(caption) #define SENDLOCO(cab,route) OPCODE_SENDLOCO,V(cab),OPCODE_PAD,V(route), #define SEQUENCE(id) OPCODE_SEQUENCE, V(id), diff --git a/StringFormatter.cpp b/StringFormatter.cpp index 218e617..13b5825 100644 --- a/StringFormatter.cpp +++ b/StringFormatter.cpp @@ -39,15 +39,18 @@ void StringFormatter::diag( const FSH* input...) { void StringFormatter::lcd(byte row, const FSH* input...) { va_list args; - + Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(0,row); + // Issue the LCD as a diag first - send(&USB_SERIAL,F("<* LCD%d:"),row); - va_start(args, input); - send2(&USB_SERIAL,input,args); - send(&USB_SERIAL,F(" *>\n")); + // Unless the same serial is asking for the virtual @ respomnse + if (virtualLCD!=&USB_SERIAL) { + send(&USB_SERIAL,F("<* LCD%d:"),row); + va_start(args, input); + send2(&USB_SERIAL,input,args); + send(&USB_SERIAL,F(" *>\n")); + } // send to virtual LCD collector (if any) - Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(0,row); if (virtualLCD) { va_start(args, input); send2(virtualLCD,input,args); diff --git a/version.h b/version.h index c14d2b0..57d154a 100644 --- a/version.h +++ b/version.h @@ -4,6 +4,8 @@ #include "StringFormatter.h" #define VERSION "5.2.3" +// 5.2.4 - LCD macro will not do diag if that duplicates @ to same target. +// - Added ROUTE_DISABLED macro in EXRAIL // 5.2.3 - Bugfix: Catch stange input to parser // 5.2.2 - Added option to allow MAX_CHARACTER_ROWS to be defined in config.h // 5.2.1 - Trackmanager rework for simpler structure From 74d11ccb1e9e30f395f18bafeed0f656650e2889 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 20 Nov 2023 09:27:57 +0100 Subject: [PATCH 135/310] Trackmanager: Do not treat TRACK_MODE_ALL as TRACK_MODE_DC --- TrackManager.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 7c1e651..2f528bd 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -472,12 +472,13 @@ std::vectorTrackManager::getMainDrivers() { #endif // Set track power for all tracks with this mode -void TrackManager::setTrackPower(TRACK_MODE trackmode, POWERMODE powermode) { +void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermode) { FOR_EACH_TRACK(t) { - MotorDriver *driver=track[t]; - if (trackmode & driver->getMode()) { + MotorDriver *driver=track[t]; + TRACK_MODE trackmodeOfTrack = driver->getMode(); + if (trackmodeToMatch & trackmodeOfTrack) { if (powermode == POWERMODE::ON) { - if (trackmode & TRACK_MODE_DC) { + if (trackmodeOfTrack & TRACK_MODE_DC) { driver->setBrake(true); // DC starts with brake on applyDCSpeed(t); // speed match DCC throttles } else { From a7096e782c148f0d07dc694612a9048c2818cdb4 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 20 Nov 2023 09:32:22 +0100 Subject: [PATCH 136/310] version 5.2.5 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 2a558fc..e03b498 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311160737Z" +#define GITHUB_SHA "devel-202311200731Z" diff --git a/version.h b/version.h index 57d154a..e3a71d2 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.3" +#define VERSION "5.2.5" +// 5.2.5 - Trackmanager: Do not treat TRACK_MODE_ALL as TRACK_MODE_DC // 5.2.4 - LCD macro will not do diag if that duplicates @ to same target. // - Added ROUTE_DISABLED macro in EXRAIL // 5.2.3 - Bugfix: Catch stange input to parser From e6f33cfdee7aacc37e8071f3fe4e1659b77d8924 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 11:51:26 +0100 Subject: [PATCH 137/310] Trackmanager broadcast power state on track mode change --- DCCEXParser.cpp | 2 +- TrackManager.cpp | 10 ++++++---- TrackManager.h | 2 +- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aed185b..8a81616 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -668,7 +668,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) break; #endif case '=': // TRACK MANAGER CONTROL <= [params]> - if (TrackManager::parseJ(stream, params, p)) + if (TrackManager::parseEqualSign(stream, params, p)) return; break; diff --git a/TrackManager.cpp b/TrackManager.cpp index 2f528bd..58a5c30 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -350,7 +350,7 @@ void TrackManager::applyDCSpeed(byte t) { track[t]->setDCSignal(speedByte); } -bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) +bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) { if (params==0) { // <=> List track assignments @@ -397,8 +397,8 @@ bool TrackManager::parseJ(Print *stream, int16_t params, int16_t p[]) return false; } +// null stream means send to commandDistributor for broadcast void TrackManager::streamTrackState(Print* stream, byte t) { - // null stream means send to commandDistributor for broadcast if (track[t]==NULL) return; auto format=F("<= %d XXX>\n"); TRACK_MODE tm = track[t]->getMode(); @@ -433,10 +433,12 @@ void TrackManager::streamTrackState(Print* stream, byte t) { format=F("<= %c DC %d>\n"); } - if (stream) + if (stream) { // null stream means send to commandDistributor for broadcast StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); - else + } else { CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + CommandDistributor::broadcastPower(); + } } diff --git a/TrackManager.h b/TrackManager.h index 644c45a..8092f0a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -73,7 +73,7 @@ class TrackManager { static const int16_t MAX_TRACKS=8; static bool setTrackMode(byte track, TRACK_MODE mode, int16_t DCaddr=0); - static bool parseJ(Print * stream, int16_t params, int16_t p[]); + static bool parseEqualSign(Print * stream, int16_t params, int16_t p[]); static void loop(); static POWERMODE getMainPower(); static POWERMODE getProgPower(); From 29ea7460621b7948c45703121a131b6ea95662e2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 11:54:43 +0100 Subject: [PATCH 138/310] version 5.2.6 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index e03b498..683f81d 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311200731Z" +#define GITHUB_SHA "devel-202311211053Z" diff --git a/version.h b/version.h index e3a71d2..0f26a21 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.5" +#define VERSION "5.2.6" +// 5.2.6 - Trackmanager broadcast power state on track mode change // 5.2.5 - Trackmanager: Do not treat TRACK_MODE_ALL as TRACK_MODE_DC // 5.2.4 - LCD macro will not do diag if that duplicates @ to same target. // - Added ROUTE_DISABLED macro in EXRAIL From 4e1fad48325608888da61a2e30f9068366f0139e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 15:37:08 +0100 Subject: [PATCH 139/310] Trackmanager consolidate getModeName --- CommandDistributor.cpp | 4 +-- CommandDistributor.h | 2 +- EXRAILMacros.h | 16 +++++------ TrackManager.cpp | 63 ++++++++++++++++++++---------------------- TrackManager.h | 2 +- 5 files changed, 42 insertions(+), 45 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index fa70e0c..1f11e28 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -275,8 +275,8 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } -void CommandDistributor::broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr) { - broadcastReply(COMMAND_TYPE, format, trackLetter, dcAddr); +void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) { + broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr); } void CommandDistributor::broadcastRouteState(uint16_t routeId, byte state ) { diff --git a/CommandDistributor.h b/CommandDistributor.h index 359c0fe..e4dff5d 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -55,7 +55,7 @@ public : static int16_t retClockTime(); static void broadcastPower(); static void broadcastRaw(clientType type,char * msg); - static void broadcastTrackState(const FSH* format,byte trackLetter, int16_t dcAddr); + static void broadcastTrackState(const FSH* format,byte trackLetter, const FSH* modename, int16_t dcAddr); template static void broadcastReply(clientType type, Targs... msg); static void forget(byte clientId); static void broadcastRouteState(uint16_t routeId,byte state); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 6024290..8edbd2b 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -121,14 +121,14 @@ const byte RMFT2::compileFeatures = 0 #include "EXRAIL2MacroReset.h" #undef ROUTE #define ROUTE(id, description) id, -const int16_t HIGHFLASH RMFT2::routeIdList[]= { +const int16_t HIGHFLASH const RMFT2::routeIdList[]= { #include "myAutomation.h" INT16_MAX}; // Pass 2a create throttle automation list #include "EXRAIL2MacroReset.h" #undef AUTOMATION #define AUTOMATION(id, description) id, -const int16_t HIGHFLASH RMFT2::automationIdList[]= { +const int16_t HIGHFLASH const RMFT2::automationIdList[]= { #include "myAutomation.h" INT16_MAX}; @@ -150,7 +150,7 @@ const FSH * RMFT2::getRouteDescription(int16_t id) { const int StringMacroTracker1=__COUNTER__; #define THRUNGE(msg,mode) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH thrunge[]=msg;\ + static const char HIGHFLASH const thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=mode;\ break;\ @@ -186,7 +186,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef LCD #define LCD(id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH thrunge[]=msg;\ + static const char HIGHFLASH const thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=thrunge_lcd; \ lcdid=id;\ @@ -195,7 +195,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef SCREEN #define SCREEN(display,id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH thrunge[]=msg;\ + static const char HIGHFLASH const thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=(thrunger)(thrunge_lcd+display); \ lcdid=id;\ @@ -274,7 +274,7 @@ const byte RMFT2::rosterNameCount=0 #include "EXRAIL2MacroReset.h" #undef ROSTER #define ROSTER(cabid,name,funcmap...) cabid, -const int16_t HIGHFLASH RMFT2::rosterIdList[]={ +const int16_t HIGHFLASH const RMFT2::rosterIdList[]={ #include "myAutomation.h" INT16_MAX}; @@ -314,7 +314,7 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) { #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) id,0,0,0, -const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { +const HIGHFLASH int16_t const RMFT2::SignalDefinitions[] = { #include "myAutomation.h" 0,0,0,0 }; @@ -503,7 +503,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; // Build RouteCode const int StringMacroTracker2=__COUNTER__; -const HIGHFLASH byte RMFT2::RouteCode[] = { +const HIGHFLASH byte const RMFT2::RouteCode[] = { #include "myAutomation.h" OPCODE_ENDTASK,0,0,OPCODE_ENDEXRAIL,0,0 }; diff --git a/TrackManager.cpp b/TrackManager.cpp index 58a5c30..a7998f4 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -397,46 +397,58 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) return false; } -// null stream means send to commandDistributor for broadcast -void TrackManager::streamTrackState(Print* stream, byte t) { - if (track[t]==NULL) return; - auto format=F("<= %d XXX>\n"); - TRACK_MODE tm = track[t]->getMode(); +const FSH* TrackManager::getModeName(TRACK_MODE tm) { + const FSH *modename=F("---"); + if (tm & TRACK_MODE_MAIN) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c MAIN A>\n"); + modename=F("MAIN A"); else if (tm & TRACK_MODE_INV) - format=F("<= %c MAIN I>\n"); + modename=F("MAIN I>\n"); else - format=F("<= %c MAIN>\n"); + modename=F("MAIN"); } #ifndef DISABLE_PROG else if (tm & TRACK_MODE_PROG) - format=F("<= %c PROG>\n"); + modename=F("PROG"); #endif else if (tm & TRACK_MODE_NONE) - format=F("<= %c NONE>\n"); + modename=F("NONE"); else if(tm & TRACK_MODE_EXT) - format=F("<= %c EXT>\n"); + modename=F("EXT"); else if(tm & TRACK_MODE_BOOST) { if(tm & TRACK_MODE_AUTOINV) - format=F("<= %c B A>\n"); + modename=F("B A"); else if (tm & TRACK_MODE_INV) - format=F("<= %c B I>\n"); + modename=F("B I"); else - format=F("<= %c B>\n"); + modename=F("B"); } else if (tm & TRACK_MODE_DC) { if (tm & TRACK_MODE_INV) - format=F("<= %c DCX %d>\n"); + modename=F("DCX"); else - format=F("<= %c DC %d>\n"); + modename=F("DC"); } + return modename; +} +// null stream means send to commandDistributor for broadcast +void TrackManager::streamTrackState(Print* stream, byte t) { + const FSH *format; + + if (track[t]==NULL) return; + TRACK_MODE tm = track[t]->getMode(); + if (tm & TRACK_MODE_DC) + format=F("<= %c %S %d>\n"); + else + format=F("<= %c %S>\n"); + + const FSH *modename=getModeName(tm); if (stream) { // null stream means send to commandDistributor for broadcast - StringFormatter::send(stream,format,'A'+t, trackDCAddr[t]); + StringFormatter::send(stream,format,'A'+t, modename, trackDCAddr[t]); } else { - CommandDistributor::broadcastTrackState(format,'A'+t, trackDCAddr[t]); + CommandDistributor::broadcastTrackState(format,'A'+t, modename, trackDCAddr[t]); CommandDistributor::broadcastPower(); } @@ -641,18 +653,3 @@ int16_t TrackManager::returnDCAddr(byte t) { return (trackDCAddr[t]); } -const char* TrackManager::getModeName(byte Mode) { - - //DIAG(F("PowerMode %d"), Mode); - -switch (Mode) - { - case 1: return "NONE"; - case 2: return "MAIN"; - case 4: return "PROG"; - case 8: return "DC"; - case 16: return "DCX"; - case 32: return "EXT"; - default: return "----"; - } -} diff --git a/TrackManager.h b/TrackManager.h index 8092f0a..f2a357d 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -91,7 +91,7 @@ class TrackManager { static bool isProg(byte t); static byte returnMode(byte t); static int16_t returnDCAddr(byte t); - static const char* getModeName(byte Mode); + static const FSH* getModeName(TRACK_MODE Mode); static int16_t joinRelay; static bool progTrackSyncMain; // true when prog track is a siding switched to main From 263ed18b253faff69227a843ad5fd419c4487027 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 15:37:47 +0100 Subject: [PATCH 140/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 683f81d..1fc5a39 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311211053Z" +#define GITHUB_SHA "devel-202311211437Z" From e7c4af5d4a64c49ce637c5f7cd65b045e75e5265 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 21:16:20 +0100 Subject: [PATCH 141/310] back out wrong const change --- EXRAILMacros.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8edbd2b..6024290 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -121,14 +121,14 @@ const byte RMFT2::compileFeatures = 0 #include "EXRAIL2MacroReset.h" #undef ROUTE #define ROUTE(id, description) id, -const int16_t HIGHFLASH const RMFT2::routeIdList[]= { +const int16_t HIGHFLASH RMFT2::routeIdList[]= { #include "myAutomation.h" INT16_MAX}; // Pass 2a create throttle automation list #include "EXRAIL2MacroReset.h" #undef AUTOMATION #define AUTOMATION(id, description) id, -const int16_t HIGHFLASH const RMFT2::automationIdList[]= { +const int16_t HIGHFLASH RMFT2::automationIdList[]= { #include "myAutomation.h" INT16_MAX}; @@ -150,7 +150,7 @@ const FSH * RMFT2::getRouteDescription(int16_t id) { const int StringMacroTracker1=__COUNTER__; #define THRUNGE(msg,mode) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=mode;\ break;\ @@ -186,7 +186,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef LCD #define LCD(id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=thrunge_lcd; \ lcdid=id;\ @@ -195,7 +195,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef SCREEN #define SCREEN(display,id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=(thrunger)(thrunge_lcd+display); \ lcdid=id;\ @@ -274,7 +274,7 @@ const byte RMFT2::rosterNameCount=0 #include "EXRAIL2MacroReset.h" #undef ROSTER #define ROSTER(cabid,name,funcmap...) cabid, -const int16_t HIGHFLASH const RMFT2::rosterIdList[]={ +const int16_t HIGHFLASH RMFT2::rosterIdList[]={ #include "myAutomation.h" INT16_MAX}; @@ -314,7 +314,7 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) { #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) id,0,0,0, -const HIGHFLASH int16_t const RMFT2::SignalDefinitions[] = { +const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #include "myAutomation.h" 0,0,0,0 }; @@ -503,7 +503,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; // Build RouteCode const int StringMacroTracker2=__COUNTER__; -const HIGHFLASH byte const RMFT2::RouteCode[] = { +const HIGHFLASH byte RMFT2::RouteCode[] = { #include "myAutomation.h" OPCODE_ENDTASK,0,0,OPCODE_ENDEXRAIL,0,0 }; From 2c1b3e0a8fc4f43d0d48527a940de34d30dc9a4a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 21:16:42 +0100 Subject: [PATCH 142/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 1fc5a39..3710cad 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311211437Z" +#define GITHUB_SHA "devel-202311212016Z" From 478e9661bb2110b3bbb50c49c6ccb8ec30f565cf Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 21 Nov 2023 21:14:54 +0000 Subject: [PATCH 143/310] EXRAIL ling segment --- EXRAIL2.h | 2 +- EXRAILMacros.h | 16 ++++++++-------- FSH.h | 3 +++ 3 files changed, 12 insertions(+), 9 deletions(-) diff --git a/EXRAIL2.h b/EXRAIL2.h index 8f777f4..5249f72 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -203,7 +203,7 @@ private: uint16_t getOperand(byte n); static bool diag; - static const HIGHFLASH byte RouteCode[]; + static const HIGHFLASH3 byte RouteCode[]; static const HIGHFLASH int16_t SignalDefinitions[]; static byte flags[MAX_FLAGS]; static Print * LCCSerial; diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8edbd2b..9048973 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -121,14 +121,14 @@ const byte RMFT2::compileFeatures = 0 #include "EXRAIL2MacroReset.h" #undef ROUTE #define ROUTE(id, description) id, -const int16_t HIGHFLASH const RMFT2::routeIdList[]= { +const int16_t HIGHFLASH RMFT2::routeIdList[]= { #include "myAutomation.h" INT16_MAX}; // Pass 2a create throttle automation list #include "EXRAIL2MacroReset.h" #undef AUTOMATION #define AUTOMATION(id, description) id, -const int16_t HIGHFLASH const RMFT2::automationIdList[]= { +const int16_t HIGHFLASH RMFT2::automationIdList[]= { #include "myAutomation.h" INT16_MAX}; @@ -150,7 +150,7 @@ const FSH * RMFT2::getRouteDescription(int16_t id) { const int StringMacroTracker1=__COUNTER__; #define THRUNGE(msg,mode) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=mode;\ break;\ @@ -186,7 +186,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef LCD #define LCD(id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=thrunge_lcd; \ lcdid=id;\ @@ -195,7 +195,7 @@ case (__COUNTER__ - StringMacroTracker1) : {\ #undef SCREEN #define SCREEN(display,id,msg) \ case (__COUNTER__ - StringMacroTracker1) : {\ - static const char HIGHFLASH const thrunge[]=msg;\ + static const char HIGHFLASH thrunge[]=msg;\ strfar=(uint32_t)GETFARPTR(thrunge);\ tmode=(thrunger)(thrunge_lcd+display); \ lcdid=id;\ @@ -274,7 +274,7 @@ const byte RMFT2::rosterNameCount=0 #include "EXRAIL2MacroReset.h" #undef ROSTER #define ROSTER(cabid,name,funcmap...) cabid, -const int16_t HIGHFLASH const RMFT2::rosterIdList[]={ +const int16_t HIGHFLASH RMFT2::rosterIdList[]={ #include "myAutomation.h" INT16_MAX}; @@ -314,7 +314,7 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) { #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) id,0,0,0, -const HIGHFLASH int16_t const RMFT2::SignalDefinitions[] = { +const HIGHFLASH int16_t RMFT2::SignalDefinitions[] = { #include "myAutomation.h" 0,0,0,0 }; @@ -503,7 +503,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; // Build RouteCode const int StringMacroTracker2=__COUNTER__; -const HIGHFLASH byte const RMFT2::RouteCode[] = { +const HIGHFLASH3 byte RMFT2::RouteCode[] = { #include "myAutomation.h" OPCODE_ENDTASK,0,0,OPCODE_ENDEXRAIL,0,0 }; diff --git a/FSH.h b/FSH.h index d031935..280d37e 100644 --- a/FSH.h +++ b/FSH.h @@ -56,6 +56,7 @@ typedef __FlashStringHelper FSH; #if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) // AVR_MEGA memory deliberately placed at end of link may need _far functions #define HIGHFLASH __attribute__((section(".fini2"))) +#define HIGHFLASH3 __attribute__((section(".fini3"))) #define GETFARPTR(data) pgm_get_far_address(data) #define GETHIGHFLASH(data,offset) pgm_read_byte_far(GETFARPTR(data)+offset) #define GETHIGHFLASHW(data,offset) pgm_read_word_far(GETFARPTR(data)+offset) @@ -63,6 +64,7 @@ typedef __FlashStringHelper FSH; // AVR_UNO/NANO runtime does not support _far functions so just use _near equivalent // as there is no progmem above 32kb anyway. #define HIGHFLASH PROGMEM +#define HIGHFLASH3 PROGMEM #define GETFARPTR(data) ((uint32_t)(data)) #define GETHIGHFLASH(data,offset) pgm_read_byte_near(GETFARPTR(data)+(offset)) #define GETHIGHFLASHW(data,offset) pgm_read_word_near(GETFARPTR(data)+(offset)) @@ -80,6 +82,7 @@ typedef __FlashStringHelper FSH; typedef char FSH; #define FLASH #define HIGHFLASH +#define HIGHFLASH3 #define GETFARPTR(data) ((uint32_t)(data)) #define GETFLASH(addr) (*(const byte *)(addr)) #define GETHIGHFLASH(data,offset) (*(const byte *)(GETFARPTR(data)+offset)) From ac4af407aa26b8773d2fc074d641f4dcaf243a15 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 22:47:48 +0100 Subject: [PATCH 144/310] On ESP32, the inversion is already done in HW --- MotorDriver.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/MotorDriver.h b/MotorDriver.h index 19bfd13..07ff93f 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -156,8 +156,10 @@ class MotorDriver { // from outside interrupt void setBrake( bool on, bool interruptContext=false); __attribute__((always_inline)) inline void setSignal( bool high) { +#ifndef ARDUINO_ARCH_ESP32 if (invertPhase) high = !high; +#endif if (trackPWM) { DCCTimer::setPWM(signalPin,high); } From d0df9f3c33d10e30ca54f939758f5c8394b39582 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 22:48:35 +0100 Subject: [PATCH 145/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 3710cad..d69d7ae 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311212016Z" +#define GITHUB_SHA "devel-202311212148Z" From 4308739c2b7663e47411c6624f626e4087cef268 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 21 Nov 2023 23:04:05 +0100 Subject: [PATCH 146/310] version 5.2.7 --- version.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 0f26a21..b2829c7 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,10 @@ #include "StringFormatter.h" -#define VERSION "5.2.6" +#define VERSION "5.2.7" +// 5.2.7 - Bugfix: EXRAIL ling segment +// - Bugfix: Back out wrongly added const +// - Bugfix ESP32: Do not inverse DCX direction signal twice // 5.2.6 - Trackmanager broadcast power state on track mode change // 5.2.5 - Trackmanager: Do not treat TRACK_MODE_ALL as TRACK_MODE_DC // 5.2.4 - LCD macro will not do diag if that duplicates @ to same target. From 03db06f2ee52bc0838b37f581ae20195d335d4e4 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 22 Nov 2023 10:53:34 +0100 Subject: [PATCH 147/310] Bugfix: Do not turn on track with trackmode NONE --- TrackManager.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index a7998f4..846c163 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -511,12 +511,15 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod void TrackManager::setTrackPower(POWERMODE powermode, byte t) { MotorDriver *driver=track[t]; TRACK_MODE trackmode = driver->getMode(); - if (trackmode & TRACK_MODE_DC) { + if (trackmode & TRACK_MODE_NONE) { + driver->setBrake(true); // Track is unused. Brake is good to have. + powermode = POWERMODE::OFF; // Track is unused. Force it to OFF + } else if (trackmode & TRACK_MODE_DC) { // includes inverted DC (called DCX) if (powermode == POWERMODE::ON) { driver->setBrake(true); // DC starts with brake on applyDCSpeed(t); // speed match DCC throttles } - } else { + } else /* MAIN PROG EXT BOOST */ { if (powermode == POWERMODE::ON) { // toggle brake before turning power on - resets overcurrent error // on the Pololu board if brake is wired to ^D2. From ef47257d67afc8b66f33b0cbbaea10e4cdddb6e7 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 22 Nov 2023 10:54:01 +0100 Subject: [PATCH 148/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index d69d7ae..42f43fd 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311212148Z" +#define GITHUB_SHA "devel-202311220953Z" From b478056a9fbbe9b0f45ba49fd2748f080d78f99f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 23 Nov 2023 09:00:49 +0000 Subject: [PATCH 149/310] Fix @ reporting on startup --- CommandDistributor.cpp | 2 +- CommandStation-EX.ino | 2 +- Display_Implementation.h | 4 +++- myHalKCS.cpp | 1 + 4 files changed, 6 insertions(+), 3 deletions(-) create mode 100644 myHalKCS.cpp diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 1f11e28..aef024b 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -330,7 +330,7 @@ void CommandDistributor::setVirtualLCDSerial(Print * stream) { virtualLCDSerial=stream; } -Print* CommandDistributor::virtualLCDSerial=nullptr; +Print* CommandDistributor::virtualLCDSerial=&USB_SERIAL; byte CommandDistributor::virtualLCDClient=0xFF; byte CommandDistributor::rememberVLCDClient=0; diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 77e8f40..205babf 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -87,7 +87,7 @@ void setup() DISPLAY_START ( // This block is still executed for DIAGS if display not in use - LCD(0,F("DCC-EX v%S"),F(VERSION)); + LCD(0,F("DCC-EX v" VERSION)); LCD(1,F("Lic GPLv3")); ); diff --git a/Display_Implementation.h b/Display_Implementation.h index ca19bd7..6a3c995 100644 --- a/Display_Implementation.h +++ b/Display_Implementation.h @@ -54,7 +54,9 @@ xxx; \ t->refresh();} #else - #define DISPLAY_START(xxx) {} + #define DISPLAY_START(xxx) { \ + xxx; \ + } #endif #endif // LCD_Implementation_h diff --git a/myHalKCS.cpp b/myHalKCS.cpp new file mode 100644 index 0000000..a330ae7 --- /dev/null +++ b/myHalKCS.cpp @@ -0,0 +1 @@ +// If you are planning to use multiple mux devices, perhaps it is good to use the 3-position syntax for all. From 784934024ef9a0b7db67fcf831a02688102e021b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 Nov 2023 10:47:43 +0100 Subject: [PATCH 150/310] Bugfix: Do not turn off all tracks on change ; give better power messages --- CommandDistributor.cpp | 53 +++++++++++++++++++++++++++++++++++------- TrackManager.cpp | 16 +++++++------ TrackManager.h | 5 +++- 3 files changed, 57 insertions(+), 17 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 1f11e28..a30fcd3 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -254,21 +254,56 @@ void CommandDistributor::broadcastPower() { if (TrackManager::getPower(t, pstr)) broadcastReply(COMMAND_TYPE, F("\n"),pstr); + byte trackcount=0; + byte oncount=0; + byte offcount=0; + for(byte t=0; t\n"),state,reason); + if (join) { + reason = F("JOIN"); + broadcastReply(COMMAND_TYPE, F("\n"),reason); + } else { + if (main) { + //reason = F("MAIN"); + broadcastReply(COMMAND_TYPE, F("\n")); + } + if (prog) { + //reason = F("PROG"); + broadcastReply(COMMAND_TYPE, F("\n")); + } + } + + if (state != '2') + broadcastReply(COMMAND_TYPE, F("\n"),state); #ifdef CD_HANDLE_RING - broadcastReply(WITHROTTLE_TYPE, F("PPA%c\n"), main?'1':'0'); + // send '1' if all main are on, otherwise global state (which in that case is '0' or '2') + broadcastReply(WITHROTTLE_TYPE, F("PPA%c\n"), main?'1': state); #endif - LCD(2,F("Power %S%S"),state=='1'?F("On"):F("Off"),reason); + + LCD(2,F("Power %S %S"),state=='1'?F("On"): ( state=='0'? F("Off") : F("SC") ),reason); } void CommandDistributor::broadcastRaw(clientType type, char * msg) { diff --git a/TrackManager.cpp b/TrackManager.cpp index 846c163..ac44c76 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -54,7 +54,6 @@ const int16_t HASH_KEYWORD_INV = 11857; MotorDriver * TrackManager::track[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS]; -POWERMODE TrackManager::mainPowerGuess=POWERMODE::OFF; byte TrackManager::lastTrack=0; bool TrackManager::progTrackSyncMain=false; bool TrackManager::progTrackBoosted=false; @@ -210,6 +209,9 @@ void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr) { if (trackToSet>lastTrack || track[trackToSet]==NULL) return false; + // Remember track mode we came from for later + TRACK_MODE oldmode = track[trackToSet]->getMode(); + //DIAG(F("Track=%c Mode=%d"),trackToSet+'A', mode); // DC tracks require a motorDriver that can set brake! if (mode & TRACK_MODE_DC) { @@ -262,7 +264,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr track[t]->setPower(POWERMODE::OFF); track[t]->setMode(TRACK_MODE_NONE); track[t]->makeProgTrack(false); // revoke prog track special handling - streamTrackState(NULL,t); + streamTrackState(NULL,t); } track[trackToSet]->makeProgTrack(true); // set for prog track special handling } else { @@ -270,7 +272,6 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr } track[trackToSet]->setMode(mode); trackDCAddr[trackToSet]=dcAddr; - streamTrackState(NULL,trackToSet); // When a track is switched, we must clear any side effects of its previous // state, otherwise trains run away or just dont move. @@ -337,10 +338,11 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr applyDCSpeed(trackToSet); } - // Normal running tracks are set to the global power state - track[trackToSet]->setPower( - (mode & (TRACK_MODE_MAIN | TRACK_MODE_DC | TRACK_MODE_EXT | TRACK_MODE_BOOST)) ? - mainPowerGuess : POWERMODE::OFF); + // Turn off power if we changed the mode of this track + if (mode != oldmode) + track[trackToSet]->setPower(POWERMODE::OFF); + streamTrackState(NULL,trackToSet); + //DIAG(F("TrackMode=%d"),mode); return true; } diff --git a/TrackManager.h b/TrackManager.h index f2a357d..12adb4e 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -77,9 +77,13 @@ class TrackManager { static void loop(); static POWERMODE getMainPower(); static POWERMODE getProgPower(); + static inline POWERMODE getPower(byte t) { return track[t]->getPower(); } static bool getPower(byte t, char s[]); static void setJoin(bool join); static bool isJoined() { return progTrackSyncMain;} + static inline bool isActive (byte tr) { + if (tr > lastTrack) return false; + return track[tr]->getMode() & (TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_BOOST|TRACK_MODE_EXT);} static void setJoinRelayPin(byte joinRelayPin); static void sampleCurrent(); static void reportGauges(Print* stream); @@ -108,7 +112,6 @@ class TrackManager { static void addTrack(byte t, MotorDriver* driver); static byte lastTrack; static byte nextCycleTrack; - static POWERMODE mainPowerGuess; static void applyDCSpeed(byte t); static int16_t trackDCAddr[MAX_TRACKS]; // dc address if TRACK_MODE_DC From a16214790ee5cc003204c80864a6e6afe43711b2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 Nov 2023 10:49:15 +0100 Subject: [PATCH 151/310] version 5.2.8 --- GITHUB_SHA.h | 2 +- version.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 42f43fd..28aa3fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311220953Z" +#define GITHUB_SHA "devel-202311230948Z" diff --git a/version.h b/version.h index b2829c7..a39bdc3 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.7" +#define VERSION "5.2.8" +// 5.2.8 - Bugfix: Do not turn off all tracks on change +// give better power messages // 5.2.7 - Bugfix: EXRAIL ling segment // - Bugfix: Back out wrongly added const // - Bugfix ESP32: Do not inverse DCX direction signal twice From 2075bc50e827851c2ed8ad5f918c945377f6320f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 23 Nov 2023 10:41:35 +0000 Subject: [PATCH 152/310] EXRAIL basic stash implementation --- EXRAIL2.cpp | 46 +++++++++++++++++++++++++++++++++++++++++++-- EXRAIL2.h | 4 ++++ EXRAIL2MacroReset.h | 12 ++++++++++-- EXRAILMacros.h | 13 +++++++++++++ myHalKCS.cpp | 1 - 5 files changed, 71 insertions(+), 5 deletions(-) delete mode 100644 myHalKCS.cpp diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6f0a835..f085700 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -86,6 +86,8 @@ LookList * RMFT2::onRotateLookup=NULL; LookList * RMFT2::onOverloadLookup=NULL; byte * RMFT2::routeStateArray=nullptr; const FSH * * RMFT2::routeCaptionArray=nullptr; +int16_t * RMFT2::stashArray=nullptr; +int16_t RMFT2::maxStashId=0; // getOperand instance version, uses progCounter from instance. uint16_t RMFT2::getOperand(byte n) { @@ -232,6 +234,12 @@ if (compileFeatures & FEATURE_SIGNAL) { IODevice::configureInput((VPIN)pin,true); break; } + case OPCODE_STASH: + case OPCODE_CLEAR_STASH: + case OPCODE_PICKUP_STASH: { + maxStashId=max(maxStashId,((int16_t)operand)); + break; + } case OPCODE_ATGTE: case OPCODE_ATLT: @@ -311,8 +319,14 @@ if (compileFeatures & FEATURE_SIGNAL) { } } SKIPOP; // include ENDROUTES opcode - - DIAG(F("EXRAIL %db, fl=%d"),progCounter,MAX_FLAGS); + + if (compileFeatures & FEATURE_STASH) { + // create the stash array from the highest id found + if (maxStashId>0) stashArray=(int16_t*)calloc(maxStashId+1, sizeof(int16_t)); + //TODO check EEPROM and fetch stashArray + } + + DIAG(F("EXRAIL %db, fl=%d, stash=%d"),progCounter,MAX_FLAGS, maxStashArray); // Removed for 4.2.31 new RMFT2(0); // add the startup route diag=saved_diag; @@ -935,6 +949,34 @@ void RMFT2::loop2() { case OPCODE_ROUTE_DISABLED: manageRouteState(operand,4); break; + + case OPCODE_STASH: + if (compileFeatures & FEATURE_STASH) + stashArray[operand] = invert? -loco : loco; + break; + + case OPCODE_CLEAR_STASH: + if (compileFeatures & FEATURE_STASH) + stashArray[operand] = 0; + break; + + case OPCODE_CLEAR_ALL_STASH: + if (compileFeatures & FEATURE_STASH) + for (int i=0;i<=maxStashId;i++) stashArray[operand]=0; + break; + + case OPCODE_PICKUP_STASH: + if (compileFeatures & FEATURE_STASH) { + int16_t x=stashArray[operand]; + if (x>=0) { + loco=x; + invert=false; + break; + } + loco=-x; + invert=true; + } + break; case OPCODE_ROUTE: case OPCODE_AUTOMATION: diff --git a/EXRAIL2.h b/EXRAIL2.h index 5249f72..30a2f45 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -70,6 +70,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ONOVERLOAD, OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN, OPCODE_ROUTE_DISABLED, + OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group @@ -102,6 +103,7 @@ enum thrunger: byte { static const byte FEATURE_LCC = 0x40; static const byte FEATURE_ROSTER= 0x20; static const byte FEATURE_ROUTESTATE= 0x10; + static const byte FEATURE_STASH = 0x08; // Flag bits for status of hardware and TPL @@ -229,6 +231,8 @@ private: static void manageRouteCaption(uint16_t id, const FSH* caption); static byte * routeStateArray; static const FSH ** routeCaptionArray; + static int16_t * stashArray; + static int16_t maxStashId; // Local variables - exist for each instance/task RMFT2 *next; // loop chain diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index ee240ed..9d23f04 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -39,6 +39,8 @@ #undef AUTOSTART #undef BROADCAST #undef CALL +#undef CLEAR_STASH +#undef CLEAR_ALL_STASH #undef CLOSE #undef DCC_SIGNAL #undef DCC_TURNTABLE @@ -108,6 +110,7 @@ #undef ONCHANGE #undef PARSE #undef PAUSE +#undef PICKUP_STASH #undef PIN_TURNOUT #undef PRINT #ifndef DISABLE_PROG @@ -152,6 +155,7 @@ #undef SIGNALH #undef SPEED #undef START +#undef STASH #undef STOP #undef THROW #undef TT_ADDPOSITION @@ -184,7 +188,9 @@ #define AUTOMATION(id,description) #define AUTOSTART #define BROADCAST(msg) -#define CALL(route) +#define CALL(route) +#define CLEAR_STASH(id) +#define CLEAR_ALL_STASH(id) #define CLOSE(id) #define DCC_SIGNAL(id,add,subaddr) #define DCC_TURNTABLE(id,home,description) @@ -256,6 +262,7 @@ #define PIN_TURNOUT(id,pin,description...) #define PRINT(msg) #define PARSE(msg) +#define PICKUP_STASH(id) #ifndef DISABLE_PROG #define POM(cv,value) #endif @@ -297,7 +304,8 @@ #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) -#define START(route) +#define START(route) +#define STASH(id) #define STOP #define THROW(id) #define TT_ADDPOSITION(turntable_id,position,value,angle,description...) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 0e9842c..ac76efc 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -113,6 +113,15 @@ void exrailHalSetup() { #undef ROUTE_CAPTION #define ROUTE_CAPTION(id,caption) | FEATURE_ROUTESTATE +#undef CLEAR_STASH +#define CLEAR_STASH(id) | FEATURE_STASH +#undef CLEAR_ALL_STASH +#define CLEAR_ALL_STASH | FEATURE_STASH +#undef PICKUP_STASH +#define PICKUP_STASH(id) | FEATURE_STASH +#undef STASH +#define STASH(id) | FEATURE_STASH + const byte RMFT2::compileFeatures = 0 #include "myAutomation.h" ; @@ -353,6 +362,8 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define AUTOSTART OPCODE_AUTOSTART,0,0, #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), +#define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id), +#define CLEAR_ALL_STASH OPCODE_CLEAR_ALL_STASH,V(0), #define CLOSE(id) OPCODE_CLOSE,V(id), #ifndef IO_NO_HAL #define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), @@ -435,6 +446,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, +#define PICKUP_STASH(id) OPCODE_PICKUP_STASH,V(id), #define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin), #ifndef DISABLE_PROG #define POM(cv,value) OPCODE_POM,V(cv),OPCODE_PAD,V(value), @@ -482,6 +494,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) OPCODE_SPEED,V(speed), #define START(route) OPCODE_START,V(route), +#define STASH(id) OPCODE_STASH,V(id), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), #ifndef IO_NO_HAL diff --git a/myHalKCS.cpp b/myHalKCS.cpp deleted file mode 100644 index a330ae7..0000000 --- a/myHalKCS.cpp +++ /dev/null @@ -1 +0,0 @@ -// If you are planning to use multiple mux devices, perhaps it is good to use the 3-position syntax for all. From a5ccb2e29e297d3743f3b8e8a3edcc17fd807842 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 23 Nov 2023 14:15:58 +0000 Subject: [PATCH 153/310] EXRAIL STASH --- DCCEXParser.cpp | 7 +++++++ EXRAIL2.cpp | 2 +- EXRAIL2Parser.cpp | 41 +++++++++++++++++++++++++++++++++++++++-- version.h | 4 +++- 4 files changed, 50 insertions(+), 4 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 8a81616..abbf54a 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -160,6 +160,7 @@ const int16_t HASH_KEYWORD_C='C'; const int16_t HASH_KEYWORD_G='G'; const int16_t HASH_KEYWORD_H='H'; const int16_t HASH_KEYWORD_I='I'; +const int16_t HASH_KEYWORD_M='M'; const int16_t HASH_KEYWORD_O='O'; const int16_t HASH_KEYWORD_P='P'; const int16_t HASH_KEYWORD_R='R'; @@ -729,6 +730,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) StringFormatter::send(stream, F("\n")); return; + case HASH_KEYWORD_M: // intercepted by EXRAIL + if (params>1) break; // invalid cant do + // requests stash size so say none. + StringFormatter::send(stream,F("\n")); + return; + case HASH_KEYWORD_R: // returns rosters StringFormatter::send(stream, F(" commands to do the following: // - Implement RMFT specific commands/diagnostics @@ -149,7 +151,33 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 opcode=0; return; } - break; + break; + case HASH_KEYWORD_M: + // NOTE: we only need to handle valid calls here because + // DCCEXParser has to have code to handle the cases where + // exrail isnt involved anyway. + // This entire code block is compiled out if STASH macros not used + if (!(compileFeatures & FEATURE_STASH)) return; + if (paramCount==1) { // + StringFormatter::send(stream,F("\n"),maxStashId); + opcode=0; + break; + } + if (paramCount==2) { // + if (p[1]<=0 || p[1]>maxStashId) break; + StringFormatter::send(stream,F("\n"), + p[1],stashArray[p[1]]); + opcode=0; + break; + } + if (paramCount==3) { // + if (p[1]<=0 || p[1]>maxStashId) break; + stashArray[p[1]]=p[2]; + opcode=0; + break; + } + break; + default: break; } @@ -195,6 +223,15 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { sigid & SIGNAL_ID_MASK); } } + + if (compileFeatures & FEATURE_STASH) { + for (int i=1;i<=maxStashId;i++) { + if (stashArray[i]) + StringFormatter::send(stream,F("\nSTASH[%d] Loco=%d"), + i, stashArray[i]); + } + } + StringFormatter::send(stream,F(" *>\n")); return true; } diff --git a/version.h b/version.h index a39bdc3..2d89cd0 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.8" +#define VERSION "5.2.9" +// 5.2.9 - Bugfix LCD startup with no LCD, uses <@ +// 5.2.9 - EXRAIL STASH feature // 5.2.8 - Bugfix: Do not turn off all tracks on change // give better power messages // 5.2.7 - Bugfix: EXRAIL ling segment From c8e307db7a63a0a3c16a990e32d6fc1cdab2245d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 Nov 2023 22:11:00 +0100 Subject: [PATCH 154/310] remove unused TrackManager::reportPowerChange(...) --- TrackManager.cpp | 9 --------- TrackManager.h | 1 - 2 files changed, 10 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index ac44c76..4021240 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -532,15 +532,6 @@ void TrackManager::setTrackPower(POWERMODE powermode, byte t) { driver->setPower(powermode); } -void TrackManager::reportPowerChange(Print* stream, byte thistrack) { - // This function is for backward JMRI compatibility only - // It reports the first track only, as main, regardless of track settings. - // - int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); - StringFormatter::send(stream, F("\n"), - track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); -} - // returns state of the one and only prog track POWERMODE TrackManager::getProgPower() { FOR_EACH_TRACK(t) diff --git a/TrackManager.h b/TrackManager.h index 12adb4e..dd38b72 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -88,7 +88,6 @@ class TrackManager { static void sampleCurrent(); static void reportGauges(Print* stream); static void reportCurrent(Print* stream); - static void reportPowerChange(Print* stream, byte thistrack); static void reportObsoleteCurrent(Print* stream); static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); From 697f228a05d990e028d4085ab1c6d36553d46519 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 Nov 2023 22:14:24 +0100 Subject: [PATCH 155/310] Save progmem with DISABLE_VDPY on Uno --- DCCEXParser.cpp | 4 +++- StringFormatter.cpp | 11 ++++++++--- config.example.h | 12 ++++++++++++ defines.h | 9 ++++----- 4 files changed, 27 insertions(+), 9 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index abbf54a..f3cdfb2 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -847,13 +847,14 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case 'L': // LCC interface implemented in EXRAIL parser break; // Will if not intercepted by EXRAIL +#ifndef DISABLE_VDPY case '@': // JMRI saying "give me virtual LCD msgs" CommandDistributor::setVirtualLCDSerial(stream); StringFormatter::send(stream, F("<@ 0 0 \"DCC-EX v" VERSION "\">\n" "<@ 0 1 \"Lic GPLv3\">\n")); return; - +#endif default: //anything else will diagnose and drop out to if (opcode >= ' ' && opcode <= '~') { DIAG(F("Opcode=%c params=%d"), opcode, params); @@ -1064,6 +1065,7 @@ bool DCCEXParser::parseS(Print *stream, int16_t params, int16_t p[]) } bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { + (void)stream; // arg not used, maybe later? if (params == 0) return false; switch (p[0]) diff --git a/StringFormatter.cpp b/StringFormatter.cpp index 13b5825..9c69877 100644 --- a/StringFormatter.cpp +++ b/StringFormatter.cpp @@ -39,8 +39,11 @@ void StringFormatter::diag( const FSH* input...) { void StringFormatter::lcd(byte row, const FSH* input...) { va_list args; +#ifndef DISABLE_VDPY Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(0,row); - +#else + Print * virtualLCD=NULL; +#endif // Issue the LCD as a diag first // Unless the same serial is asking for the virtual @ respomnse if (virtualLCD!=&USB_SERIAL) { @@ -50,13 +53,14 @@ void StringFormatter::lcd(byte row, const FSH* input...) { send(&USB_SERIAL,F(" *>\n")); } +#ifndef DISABLE_VDPY // send to virtual LCD collector (if any) if (virtualLCD) { va_start(args, input); send2(virtualLCD,input,args); CommandDistributor::commitVirtualLCDSerial(); } - +#endif DisplayInterface::setRow(row); va_start(args, input); send2(DisplayInterface::getDisplayHandler(),input,args); @@ -66,12 +70,14 @@ void StringFormatter::lcd2(uint8_t display, byte row, const FSH* input...) { va_list args; // send to virtual LCD collector (if any) +#ifndef DISABLE_VDPY Print * virtualLCD=CommandDistributor::getVirtualLCDSerial(display,row); if (virtualLCD) { va_start(args, input); send2(virtualLCD,input,args); CommandDistributor::commitVirtualLCDSerial(); } +#endif DisplayInterface::setRow(display, row); va_start(args, input); @@ -250,4 +256,3 @@ void StringFormatter::printHex(Print * stream,uint16_t value) { result[4]='\0'; stream->print(result); } - \ No newline at end of file diff --git a/config.example.h b/config.example.h index 9909371..89d6c1f 100644 --- a/config.example.h +++ b/config.example.h @@ -199,6 +199,18 @@ The configuration file for DCC-EX Command Station // // #define DISABLE_PROG +///////////////////////////////////////////////////////////////////////////////////// +// DISABLE / ENABLE VDPY +// +// The Virtual display "VDPY" feature is by default enabled everywhere +// but on Uno and Nano. If you think you can fit it (for example +// having disabled some of the features above) you can enable it with +// ENABLE_VDPY. You can even disable it on all other CPUs with +// DISABLE_VDPY +// +// #define DISABLE_VDPY +// #define ENABLE_VDPY + ///////////////////////////////////////////////////////////////////////////////////// // REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address // is 127 and the first long address is 128. There are manufacturers which have diff --git a/defines.h b/defines.h index e90d7f4..14dd1c5 100644 --- a/defines.h +++ b/defines.h @@ -219,11 +219,10 @@ // The HAL is disabled by default on Nano and Uno platforms, because of limited flash space. // #if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) - #if defined(DISABLE_DIAG) && defined(DISABLE_EEPROM) && defined(DISABLE_PROG) - #warning you have sacrificed DIAG for HAL - #else - #define IO_NO_HAL - #endif +#define IO_NO_HAL // HAL too big whatever you disable otherwise +#ifndef ENABLE_VDPY +#define DISABLE_VDPY +#endif #endif #if __has_include ( "myAutomation.h") From ebaf1b984ef66084b5534083ef1a81500c57b79d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 Nov 2023 22:15:03 +0100 Subject: [PATCH 156/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 28aa3fe..42d5594 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311230948Z" +#define GITHUB_SHA "devel-202311232114Z" From 96fdbfdc89843a75ec69a1b8ded71161ba1de2e1 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sun, 26 Nov 2023 12:31:41 +0000 Subject: [PATCH 157/310] Trainbrains block occupancy --- IODevice.h | 2 + IO_trainbrains.h | 98 ++++++++++++++++++++++++++++++++++++++++++++++++ version.h | 4 +- 3 files changed, 103 insertions(+), 1 deletion(-) create mode 100644 IO_trainbrains.h diff --git a/IODevice.h b/IODevice.h index 74fe49b..d12fafd 100644 --- a/IODevice.h +++ b/IODevice.h @@ -542,8 +542,10 @@ protected: #include "IO_MCP23017.h" #include "IO_PCF8574.h" #include "IO_PCF8575.h" +#include "IO_PCA9555.h" #include "IO_duinoNodes.h" #include "IO_EXIOExpander.h" +#include "IO_trainbrains.h" #endif // iodevice_h diff --git a/IO_trainbrains.h b/IO_trainbrains.h new file mode 100644 index 0000000..058fe02 --- /dev/null +++ b/IO_trainbrains.h @@ -0,0 +1,98 @@ +/* + * © 2023, Chris Harlow. All rights reserved. + * © 2021, Neil McKechnie. All rights reserved. + * + * This file is part of DCC++EX API + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +#ifndef io_trainbrains_h +#define io_trainbrains_h + +#include "IO_GPIOBase.h" +#include "FSH.h" + +///////////////////////////////////////////////////////////////////////////////////////////////////// +/* + * IODevice subclass for trainbrains 3-block occupancy detector. + * For details see http://trainbrains.eu + */ + + enum TrackUnoccupancy +{ + TRACK_UNOCCUPANCY_UNKNOWN = 0, + TRACK_OCCUPIED = 1, + TRACK_UNOCCUPIED = 2 +}; + +class Trainbrains02 : public GPIOBase { +public: + static void create(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress) { + if (checkNoOverlap(vpin, nPins, i2cAddress)) new Trainbrains02(vpin, nPins, i2cAddress); + } + +private: + // Constructor + Trainbrains02(VPIN vpin, uint8_t nPins, I2CAddress i2cAddress, int interruptPin=-1) + : GPIOBase((FSH *)F("Trainbrains02"), vpin, nPins, i2cAddress, interruptPin) + { + requestBlock.setRequestParams(_I2CAddress, inputBuffer, sizeof(inputBuffer), + outputBuffer, sizeof(outputBuffer)); + + outputBuffer[0] = (uint8_t)_I2CAddress; // strips away the mux part. + outputBuffer[1] =14; + outputBuffer[2] =1; + outputBuffer[3] =0; // This is the channel updated at each poling call + outputBuffer[4] =0; + outputBuffer[5] =0; + outputBuffer[6] =0; + outputBuffer[7] =0; + outputBuffer[8] =0; + outputBuffer[9] =0; + } + + void _writeGpioPort() override {} + + void _readGpioPort(bool immediate) override { + // cycle channel on device each time + outputBuffer[3]=channelInProgress+1; // 1-origin + channelInProgress++; + if(channelInProgress>=_nPins) channelInProgress=0; + + if (immediate) { + _processCompletion(I2CManager.read(_I2CAddress, inputBuffer, sizeof(inputBuffer), + outputBuffer, sizeof(outputBuffer))); + } else { + // Queue new request + requestBlock.wait(); // Wait for preceding operation to complete + // Issue new request to read GPIO register + I2CManager.queueRequest(&requestBlock); + } + } + + // This function is invoked when an I/O operation on the requestBlock completes. + void _processCompletion(uint8_t status) override { + if (status != I2C_STATUS_OK) inputBuffer[6]=TRACK_UNOCCUPANCY_UNKNOWN; + if (inputBuffer[6] == TRACK_UNOCCUPIED ) _portInputState |= 0x01 < Date: Mon, 27 Nov 2023 08:15:07 +0100 Subject: [PATCH 158/310] Change from TrackManager::returnMode to TrackManager::getMode --- GITHUB_SHA.h | 2 +- TrackManager.cpp | 2 +- TrackManager.h | 2 +- version.h | 3 ++- 4 files changed, 5 insertions(+), 4 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 42d5594..23c6a6e 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311232114Z" +#define GITHUB_SHA "devel-202311270714Z" diff --git a/TrackManager.cpp b/TrackManager.cpp index 4021240..7d2b36b 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -641,7 +641,7 @@ bool TrackManager::isProg(byte t) { return false; } -byte TrackManager::returnMode(byte t) { +TRACK_MODE TrackManager::getMode(byte t) { return (track[t]->getMode()); } diff --git a/TrackManager.h b/TrackManager.h index dd38b72..6310030 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -92,7 +92,7 @@ class TrackManager { static void streamTrackState(Print* stream, byte t); static bool isPowerOn(byte t); static bool isProg(byte t); - static byte returnMode(byte t); + static TRACK_MODE getMode(byte t); static int16_t returnDCAddr(byte t); static const FSH* getModeName(TRACK_MODE Mode); diff --git a/version.h b/version.h index 3937937..e8a5e81 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.10" +#define VERSION "5.2.11" +// 5.2.11 - Change from TrackManager::returnMode to TrackManager::getMode // 5.2.10 - Include trainbrains.eu block unoccupancy driver // - include IO_PCA9555 // 5.2.9 - Bugfix LCD startup with no LCD, uses <@ From 07fd4bc309c333e9fccc98f4287ec1866a8cd0aa Mon Sep 17 00:00:00 2001 From: Asbelos Date: Mon, 27 Nov 2023 16:49:02 +0000 Subject: [PATCH 159/310] Window --- DCC.cpp | 2 +- DCCWaveform.cpp | 67 +++++++++++++++++++++++++++++++------------------ DCCWaveform.h | 4 ++- 3 files changed, 46 insertions(+), 27 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 30fcf5f..e576812 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -595,7 +595,7 @@ void DCC::loop() { void DCC::issueReminders() { // if the main track transmitter still has a pending packet, skip this time around. - if ( DCCWaveform::mainTrack.getPacketPending()) return; + if (!DCCWaveform::mainTrack.isReminderWindowOpen()) return; // Move to next loco slot. If occupied, send a reminder. int reg = lastLocoReminder+1; if (reg > highestUsedReg) reg = 0; // Go to start of table diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 4a99997..0e9667a 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -106,6 +106,7 @@ void DCCWaveform::interruptHandler() { DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { isMainTrack = isMain; packetPending = false; + reminderWindowOpen = false; memcpy(transmitPacket, idlePacket, sizeof(idlePacket)); state = WAVE_START; // The +1 below is to allow the preamble generator to create the stop bit @@ -127,9 +128,15 @@ void DCCWaveform::interrupt2() { if (remainingPreambles > 0 ) { state=WAVE_MID_1; // switch state to trigger LOW on next interrupt remainingPreambles--; + + // As we get to the end of the preambles, open the reminder window. + // This delays any reminder insertion until the last moment so + // that the reminder doesn't block a more urgent packet. + reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1; + if (remainingPreambles==1) promotePendingPacket(); // Update free memory diagnostic as we don't have anything else to do this time. // Allow for checkAck and its called functions using 22 bytes more. - DCCTimer::updateMinimumFreeMemoryISR(22); + else DCCTimer::updateMinimumFreeMemoryISR(22); return; } @@ -148,30 +155,9 @@ void DCCWaveform::interrupt2() { if (bytes_sent >= transmitLength) { // end of transmission buffer... repeat or switch to next message bytes_sent = 0; + // preamble for next packet will start... remainingPreambles = requiredPreambles; - - if (transmitRepeats > 0) { - transmitRepeats--; } - else if (packetPending) { - // Copy pending packet to transmit packet - // a fixed length memcpy is faster than a variable length loop for these small lengths - // for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b]; - memcpy( transmitPacket, pendingPacket, sizeof(pendingPacket)); - - transmitLength = pendingLength; - transmitRepeats = pendingRepeats; - packetPending = false; - clearResets(); - } - else { - // Fortunately reset and idle packets are the same length - memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); - transmitLength = sizeof(idlePacket); - transmitRepeats = 0; - if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) - } - } } } #pragma GCC pop_options @@ -193,8 +179,39 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea packetPending = true; clearResets(); } -bool DCCWaveform::getPacketPending() { - return packetPending; + +bool DCCWaveform::isReminderWindowOpen() { + return reminderWindowOpen && ! packetPending; +} + +void DCCWaveform::promotePendingPacket() { + // fill the transmission packet from the pending packet + + // Just keep going if repeating + if (transmitRepeats > 0) { + transmitRepeats--; + return; + } + + if (packetPending) { + // Copy pending packet to transmit packet + // a fixed length memcpy is faster than a variable length loop for these small lengths + // for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b]; + memcpy( transmitPacket, pendingPacket, sizeof(pendingPacket)); + + transmitLength = pendingLength; + transmitRepeats = pendingRepeats; + packetPending = false; + clearResets(); + return; + } + + // nothing to do, just send idles or resets + // Fortunately reset and idle packets are the same length + memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); + transmitLength = sizeof(idlePacket); + transmitRepeats = 0; + if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) } #endif diff --git a/DCCWaveform.h b/DCCWaveform.h index 1dad1b2..2202b53 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -76,11 +76,13 @@ class DCCWaveform { }; #endif void schedulePacket(const byte buffer[], byte byteCount, byte repeats); - bool getPacketPending(); + bool isReminderWindowOpen(); + void promotePendingPacket(); private: #ifndef ARDUINO_ARCH_ESP32 volatile bool packetPending; + volatile bool reminderWindowOpen; volatile byte sentResetsSincePacket; #else volatile uint32_t resetPacketBase; From 3f4099520aaa75c56f7bdbc3a222f094acc4210e Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 28 Nov 2023 19:57:14 +0000 Subject: [PATCH 160/310] ESP32 update for reminders --- DCCWaveform.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 0e9667a..93b21a2 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -283,15 +283,15 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea } } -bool DCCWaveform::getPacketPending() { +bool DCCWaveform::isReminderWindowOpen() { if(isMainTrack) { if (rmtMainChannel == NULL) - return true; - return rmtMainChannel->busy(); + return false; + return !rmtMainChannel->busy(); } else { if (rmtProgChannel == NULL) - return true; - return rmtProgChannel->busy(); + return false; + return !rmtProgChannel->busy(); } } void IRAM_ATTR DCCWaveform::loop() { From 753567427ed99de4bd7a1016826c1439d79062d4 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Thu, 30 Nov 2023 14:38:16 +0800 Subject: [PATCH 161/310] ESP32 LCD messages, STM32 minor updates --- DCCTimerSTM32.cpp | 15 ++++++++++----- WifiESP32.cpp | 12 +++++++++--- version.h | 5 ++++- 3 files changed, 23 insertions(+), 9 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f2d51ff..f24adc2 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -50,11 +50,16 @@ HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 // via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. // On the F446RE, Serial3 and Serial5 are easy to use: HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE -HardwareSerial Serial5(PD2, PC12); // Rx=PC7, Tx=PC6 -- UART5 - F446RE +HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5 - F446RE // On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins -#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) +#elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F446ZE) || \ + defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI) // Nucleo-144 boards don't have Serial1 defined by default HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 +HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5 +#if !defined(ARDUINO_NUCLEO_F412ZG) + HardwareSerial Serial2(PD6, PD5); // Rx=PD6, Tx=PD5 -- UART5 +#endif // Serial3 is defined to use USART3 by default, but is in fact used as the diag console // via the debugger on the Nucleo-144. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. #else @@ -215,9 +220,9 @@ void DCCTimer::clearPWM() { } void DCCTimer::getSimulatedMacAddress(byte mac[6]) { - volatile uint32_t *serno1 = (volatile uint32_t *)0x1FFF7A10; - volatile uint32_t *serno2 = (volatile uint32_t *)0x1FFF7A14; - // volatile uint32_t *serno3 = (volatile uint32_t *)0x1FFF7A18; + volatile uint32_t *serno1 = (volatile uint32_t *)UID_BASE; + volatile uint32_t *serno2 = (volatile uint32_t *)UID_BASE+4; + // volatile uint32_t *serno3 = (volatile uint32_t *)UID_BASE+8; volatile uint32_t m1 = *serno1; volatile uint32_t m2 = *serno2; diff --git a/WifiESP32.cpp b/WifiESP32.cpp index 28a15fe..f0a857f 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -163,7 +163,9 @@ bool WifiESP::setup(const char *SSid, delay(500); } if (WiFi.status() == WL_CONNECTED) { - DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str()); + // DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str()); + DIAG(F("Wifi in STA mode")); + LCD(7, F("IP: %s"), WiFi.softAPIP().toString().c_str()); wifiUp = true; } else { DIAG(F("Could not connect to Wifi SSID %s"),SSid); @@ -209,8 +211,12 @@ bool WifiESP::setup(const char *SSid, if (WiFi.softAP(strSSID.c_str(), havePassword ? password : strPass.c_str(), channel, false, 8)) { - DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str()); - DIAG(F("Wifi AP IP %s"),WiFi.softAPIP().toString().c_str()); + // DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str()); + DIAG(F("Wifi in AP mode")); + LCD(5, F("Wifi: %s"), strSSID.c_str()); + LCD(6, F("PASS: %s"),havePassword ? password : strPass.c_str()); + // DIAG(F("Wifi AP IP %s"),WiFi.softAPIP().toString().c_str()); + LCD(7, F("IP: %s"),WiFi.softAPIP().toString().c_str()); wifiUp = true; APmode = true; } else { diff --git a/version.h b/version.h index e8a5e81..a0cb16a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,10 @@ #include "StringFormatter.h" -#define VERSION "5.2.11" +#define VERSION "5.2.12" +// 5.2.12 - ESP32 add AP mode LCD messages with SSID/PW for +// - STM32 change to UID_BASE constants in DCCTimerSTM32 rather than raw hex addresses for UID registers +// - STM32 extra UART/USARTs for larger Nucleo models // 5.2.11 - Change from TrackManager::returnMode to TrackManager::getMode // 5.2.10 - Include trainbrains.eu block unoccupancy driver // - include IO_PCA9555 From 763c9d8ae6d2d46fe09cbaff4f4ac82bef94496a Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 30 Nov 2023 11:32:39 +0000 Subject: [PATCH 162/310] STEALTH --- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 3 +++ version.h | 3 ++- 3 files changed, 7 insertions(+), 1 deletion(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 9d23f04..7811a0d 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -156,6 +156,7 @@ #undef SPEED #undef START #undef STASH +#undef STEALTH #undef STOP #undef THROW #undef TT_ADDPOSITION @@ -306,6 +307,7 @@ #define SPEED(speed) #define START(route) #define STASH(id) +#define STEALTH(code...) #define STOP #define THROW(id) #define TT_ADDPOSITION(turntable_id,position,value,angle,description...) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index ac76efc..f79693d 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -210,6 +210,8 @@ case (__COUNTER__ - StringMacroTracker1) : {\ lcdid=id;\ break;\ } +#undef STEALTH +#define STEALTH(code...) case (__COUNTER__ - StringMacroTracker1) : {code} return; #undef WITHROTTLE #define WITHROTTLE(msg) THRUNGE(msg,thrunge_withrottle) @@ -422,6 +424,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; OPCODE_PAD,V((((uint64_t)sender)>>0)&0xFFFF), #define LCD(id,msg) PRINT(msg) #define SCREEN(display,id,msg) PRINT(msg) +#define STEALTH(code...) PRINT(dummy) #define LCN(msg) PRINT(msg) #define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0), #define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr), diff --git a/version.h b/version.h index a0cb16a..0304500 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.12" +#define VERSION "5.2.13" +// 5.2.13 - EXRAIL STEALTH // 5.2.12 - ESP32 add AP mode LCD messages with SSID/PW for // - STM32 change to UID_BASE constants in DCCTimerSTM32 rather than raw hex addresses for UID registers // - STM32 extra UART/USARTs for larger Nucleo models From a69017f8bbd71aa09e1c8bd53f6b44fe8d62d677 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 30 Nov 2023 19:48:02 +0000 Subject: [PATCH 163/310] Optional DISABLE_FUNCTION_REMINDERS --- DCC.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/DCC.cpp b/DCC.cpp index e576812..60c07df 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -620,14 +620,23 @@ bool DCC::issueReminder(int reg) { case 1: // remind function group 1 (F0-F4) if (flags & FN_GROUP_1) setFunctionInternal(loco,0, 128 | ((functions>>1)& 0x0F) | ((functions & 0x01)<<4)); // 100D DDDD +#ifdef DISABLE_FUNCTION_REMINDERS + flags&= ~FN_GROUP_1; // dont send them again +#endif break; case 2: // remind function group 2 F5-F8 if (flags & FN_GROUP_2) setFunctionInternal(loco,0, 176 | ((functions>>5)& 0x0F)); // 1011 DDDD +#ifdef DISABLE_FUNCTION_REMINDERS + flags&= ~FN_GROUP_2; // dont send them again +#endif break; case 3: // remind function group 3 F9-F12 if (flags & FN_GROUP_3) setFunctionInternal(loco,0, 160 | ((functions>>9)& 0x0F)); // 1010 DDDD +#ifdef DISABLE_FUNCTION_REMINDERS + flags&= ~FN_GROUP_3; // dont send them again +#endif break; case 4: // remind function group 4 F13-F20 if (flags & FN_GROUP_4) From 08f0a2b37de4297e045f7a2597c1b6786242b077 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 30 Nov 2023 19:56:58 +0000 Subject: [PATCH 164/310] 5.2.13 --- version.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 0304500..a6265d8 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.13" +#define VERSION "5.2.14" +// 5.2.14 - Reminder window DCC packet optimization +// - Optional #define DISABLE_FUNCTION_REMINDERS // 5.2.13 - EXRAIL STEALTH // 5.2.12 - ESP32 add AP mode LCD messages with SSID/PW for // - STM32 change to UID_BASE constants in DCCTimerSTM32 rather than raw hex addresses for UID registers From a1accec79af3b83f77db3f2e41cba5ae318190e2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 13 Dec 2023 10:55:58 +0100 Subject: [PATCH 165/310] add repeats to function packets that are not reminded in accordance with accessory packets --- DCC.cpp | 26 ++++++++++++++++---------- DCC.h | 2 +- 2 files changed, 17 insertions(+), 11 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 60c07df..0c5148a 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -122,7 +122,7 @@ void DCC::setThrottle2( uint16_t cab, byte speedCode) { DCCWaveform::mainTrack.schedulePacket(b, nB, 0); } -void DCC::setFunctionInternal(int cab, byte byte1, byte byte2) { +void DCC::setFunctionInternal(int cab, byte byte1, byte byte2, byte count) { // DIAG(F("setFunctionInternal %d %x %x"),cab,byte1,byte2); byte b[4]; byte nB = 0; @@ -133,7 +133,7 @@ void DCC::setFunctionInternal(int cab, byte byte1, byte byte2) { if (byte1!=0) b[nB++] = byte1; b[nB++] = byte2; - DCCWaveform::mainTrack.schedulePacket(b, nB, 0); + DCCWaveform::mainTrack.schedulePacket(b, nB, count); } // returns speed steps 0 to 127 (1 == emergency stop) @@ -619,33 +619,39 @@ bool DCC::issueReminder(int reg) { break; case 1: // remind function group 1 (F0-F4) if (flags & FN_GROUP_1) - setFunctionInternal(loco,0, 128 | ((functions>>1)& 0x0F) | ((functions & 0x01)<<4)); // 100D DDDD -#ifdef DISABLE_FUNCTION_REMINDERS +#ifndef DISABLE_FUNCTION_REMINDERS + setFunctionInternal(loco,0, 128 | ((functions>>1)& 0x0F) | ((functions & 0x01)<<4),0); // 100D DDDD +#else + setFunctionInternal(loco,0, 128 | ((functions>>1)& 0x0F) | ((functions & 0x01)<<4),2); flags&= ~FN_GROUP_1; // dont send them again #endif break; case 2: // remind function group 2 F5-F8 if (flags & FN_GROUP_2) - setFunctionInternal(loco,0, 176 | ((functions>>5)& 0x0F)); // 1011 DDDD -#ifdef DISABLE_FUNCTION_REMINDERS +#ifndef DISABLE_FUNCTION_REMINDERS + setFunctionInternal(loco,0, 176 | ((functions>>5)& 0x0F),0); // 1011 DDDD +#else + setFunctionInternal(loco,0, 176 | ((functions>>5)& 0x0F),2); flags&= ~FN_GROUP_2; // dont send them again #endif break; case 3: // remind function group 3 F9-F12 if (flags & FN_GROUP_3) - setFunctionInternal(loco,0, 160 | ((functions>>9)& 0x0F)); // 1010 DDDD -#ifdef DISABLE_FUNCTION_REMINDERS +#ifndef DISABLE_FUNCTION_REMINDERS + setFunctionInternal(loco,0, 160 | ((functions>>9)& 0x0F),0); // 1010 DDDD +#else + setFunctionInternal(loco,0, 160 | ((functions>>9)& 0x0F),2); flags&= ~FN_GROUP_3; // dont send them again #endif break; case 4: // remind function group 4 F13-F20 if (flags & FN_GROUP_4) - setFunctionInternal(loco,222, ((functions>>13)& 0xFF)); + setFunctionInternal(loco,222, ((functions>>13)& 0xFF),2); flags&= ~FN_GROUP_4; // dont send them again break; case 5: // remind function group 5 F21-F28 if (flags & FN_GROUP_5) - setFunctionInternal(loco,223, ((functions>>21)& 0xFF)); + setFunctionInternal(loco,223, ((functions>>21)& 0xFF),2); flags&= ~FN_GROUP_5; // dont send them again break; } diff --git a/DCC.h b/DCC.h index 74b4e77..3bf0cf5 100644 --- a/DCC.h +++ b/DCC.h @@ -109,7 +109,7 @@ private: static byte loopStatus; static void setThrottle2(uint16_t cab, uint8_t speedCode); static void updateLocoReminder(int loco, byte speedCode); - static void setFunctionInternal(int cab, byte fByte, byte eByte); + static void setFunctionInternal(int cab, byte fByte, byte eByte, byte count); static bool issueReminder(int reg); static int lastLocoReminder; static int highestUsedReg; From 18116a391c5fa0a54c58fc976b1872157e927dd5 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 13 Dec 2023 11:40:15 +0100 Subject: [PATCH 166/310] move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions --- CommandDistributor.cpp | 4 ++-- DCCEXParser.cpp | 2 -- EXRAIL2.cpp | 5 ----- TrackManager.cpp | 8 ++++++++ WiThrottle.cpp | 2 -- 5 files changed, 10 insertions(+), 11 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 6770e7a..e8404de 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -283,7 +283,7 @@ void CommandDistributor::broadcastPower() { //DIAG(F("m=%d p=%d j=%d"), main, prog, join); const FSH * reason=F(""); if (join) { - reason = F("JOIN"); + reason = F(" JOIN"); // with space at start so we can append without space broadcastReply(COMMAND_TYPE, F("\n"),reason); } else { if (main) { @@ -303,7 +303,7 @@ void CommandDistributor::broadcastPower() { broadcastReply(WITHROTTLE_TYPE, F("PPA%c\n"), main?'1': state); #endif - LCD(2,F("Power %S %S"),state=='1'?F("On"): ( state=='0'? F("Off") : F("SC") ),reason); + LCD(2,F("Power %S%S"),state=='1'?F("On"): ( state=='0'? F("Off") : F("SC") ),reason); } void CommandDistributor::broadcastRaw(clientType type, char * msg) { diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index f3cdfb2..aefed4c 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -587,7 +587,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } else break; // will reply } - CommandDistributor::broadcastPower(); //TrackManager::streamTrackState(NULL,t); return; @@ -619,7 +618,6 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } else break; // will reply } - CommandDistributor::broadcastPower(); return; } diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 3e55620..cc3269b 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -414,7 +414,6 @@ void RMFT2::driveLoco(byte speed) { power on appropriate track if DC or main if dcc if (TrackManager::getMainPowerMode()==POWERMODE::OFF) { TrackManager::setMainPower(POWERMODE::ON); - CommandDistributor::broadcastPower(); } **********/ @@ -642,7 +641,6 @@ void RMFT2::loop2() { case OPCODE_POWEROFF: TrackManager::setPower(POWERMODE::OFF); TrackManager::setJoin(false); - CommandDistributor::broadcastPower(); break; case OPCODE_SET_POWER: @@ -837,12 +835,10 @@ void RMFT2::loop2() { case OPCODE_JOIN: TrackManager::setPower(POWERMODE::ON); TrackManager::setJoin(true); - CommandDistributor::broadcastPower(); break; case OPCODE_UNJOIN: TrackManager::setJoin(false); - CommandDistributor::broadcastPower(); break; case OPCODE_READ_LOCO1: // READ_LOCO is implemented as 2 separate opcodes @@ -870,7 +866,6 @@ void RMFT2::loop2() { case OPCODE_POWERON: TrackManager::setMainPower(POWERMODE::ON); TrackManager::setJoin(false); - CommandDistributor::broadcastPower(); break; case OPCODE_START: diff --git a/TrackManager.cpp b/TrackManager.cpp index 7d2b36b..4a501a1 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -489,10 +489,13 @@ std::vectorTrackManager::getMainDrivers() { // Set track power for all tracks with this mode void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermode) { + bool didChange=false; FOR_EACH_TRACK(t) { MotorDriver *driver=track[t]; TRACK_MODE trackmodeOfTrack = driver->getMode(); if (trackmodeToMatch & trackmodeOfTrack) { + if (powermode != driver->getPower()) + didChange=true; if (powermode == POWERMODE::ON) { if (trackmodeOfTrack & TRACK_MODE_DC) { driver->setBrake(true); // DC starts with brake on @@ -507,12 +510,15 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod driver->setPower(powermode); } } + if (didChange) + CommandDistributor::broadcastPower(); } // Set track power for this track, inependent of mode void TrackManager::setTrackPower(POWERMODE powermode, byte t) { MotorDriver *driver=track[t]; TRACK_MODE trackmode = driver->getMode(); + POWERMODE oldpower = driver->getPower(); if (trackmode & TRACK_MODE_NONE) { driver->setBrake(true); // Track is unused. Brake is good to have. powermode = POWERMODE::OFF; // Track is unused. Force it to OFF @@ -530,6 +536,8 @@ void TrackManager::setTrackPower(POWERMODE powermode, byte t) { } } driver->setPower(powermode); + if (oldpower != driver->getPower()) + CommandDistributor::broadcastPower(); } // returns state of the one and only prog track diff --git a/WiThrottle.cpp b/WiThrottle.cpp index 4eb0a25..244dfd8 100644 --- a/WiThrottle.cpp +++ b/WiThrottle.cpp @@ -150,7 +150,6 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) { DCCWaveform::progTrack.setPowerMode(cmd[3]=='1'?POWERMODE::ON:POWERMODE::OFF); */ - CommandDistributor::broadcastPower(); } #if defined(EXRAIL_ACTIVE) else if (cmd[1]=='R' && cmd[2]=='A' && cmd[3]=='2' ) { // Route activate @@ -496,7 +495,6 @@ void WiThrottle::getLocoCallback(int16_t locoid) { TrackManager::setJoin(true); // <1 JOIN> so we can drive loco away DIAG(F("LocoCallback commit success")); stashStream->commit(); - CommandDistributor::broadcastPower(); } void WiThrottle::sendIntro(Print* stream) { From 1881d4c9ad0c5e2eeba2ef1643dd7ead1f5de7ed Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 13 Dec 2023 11:41:57 +0100 Subject: [PATCH 167/310] version 5.2.15 --- GITHUB_SHA.h | 2 +- version.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 23c6a6e..0a5110a 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202311270714Z" +#define GITHUB_SHA "devel-202312131041Z" diff --git a/version.h b/version.h index a6265d8..b74cbd2 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.14" +#define VERSION "5.2.15" +// 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions +// - add repeats to function packets that are not reminded in accordance with accessory packets // 5.2.14 - Reminder window DCC packet optimization // - Optional #define DISABLE_FUNCTION_REMINDERS // 5.2.13 - EXRAIL STEALTH From 797028b2233e04057a37237fb0738c73e97940d3 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 19 Dec 2023 07:30:15 +1000 Subject: [PATCH 168/310] Ready to test --- IO_EXIOExpander.h | 56 ++++++++++++++++++++++++----------------------- version.h | 3 ++- 2 files changed, 31 insertions(+), 28 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index 675d66c..c8bcba0 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -22,13 +22,10 @@ * This device driver will configure the device on startup, along with * interacting with the device for all input/output duties. * -* To create EX-IOExpander devices, these are defined in myHal.cpp: +* To create EX-IOExpander devices, these are defined in myAutomation.h: * (Note the device driver is included by default) * -* void halSetup() { -* // EXIOExpander::create(vpin, num_vpins, i2c_address); -* EXIOExpander::create(800, 18, 0x65); -* } +* HAL(EXIOExpander,800,18,0x65) * * All pins on an EX-IOExpander device are allocated according to the pin map for the specific * device in use. There is no way for the device driver to sanity check pins are used for the @@ -98,25 +95,30 @@ private: _numAnaloguePins = receiveBuffer[2]; // See if we already have suitable buffers assigned - size_t digitalBytesNeeded = (_numDigitalPins + 7) / 8; - if (_digitalPinBytes < digitalBytesNeeded) { - // Not enough space, free any existing buffer and allocate a new one - if (_digitalPinBytes > 0) free(_digitalInputStates); - _digitalInputStates = (byte*) calloc(_digitalPinBytes, 1); - _digitalPinBytes = digitalBytesNeeded; - } - size_t analogueBytesNeeded = _numAnaloguePins * 2; - if (_analoguePinBytes < analogueBytesNeeded) { - // Free any existing buffers and allocate new ones. - if (_analoguePinBytes > 0) { - free(_analogueInputBuffer); - free(_analogueInputStates); - free(_analoguePinMap); + if (_numDigitalPins>0) { + size_t digitalBytesNeeded = (_numDigitalPins + 7) / 8; + if (_digitalPinBytes < digitalBytesNeeded) { + // Not enough space, free any existing buffer and allocate a new one + if (_digitalPinBytes > 0) free(_digitalInputStates); + _digitalInputStates = (byte*) calloc(_digitalPinBytes, 1); + _digitalPinBytes = digitalBytesNeeded; + } + } + + if (_numAnaloguePins>0) { + size_t analogueBytesNeeded = _numAnaloguePins * 2; + if (_analoguePinBytes < analogueBytesNeeded) { + // Free any existing buffers and allocate new ones. + if (_analoguePinBytes > 0) { + free(_analogueInputBuffer); + free(_analogueInputStates); + free(_analoguePinMap); + } + _analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1); + _analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1); + _analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1); + _analoguePinBytes = analogueBytesNeeded; } - _analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1); - _analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1); - _analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1); - _analoguePinBytes = analogueBytesNeeded; } } else { DIAG(F("EX-IOExpander I2C:%s ERROR configuring device"), _I2CAddress.toString()); @@ -124,8 +126,8 @@ private: return; } } - // We now need to retrieve the analogue pin map - if (status == I2C_STATUS_OK) { + // We now need to retrieve the analogue pin map if there are analogue pins + if (status == I2C_STATUS_OK && _numAnaloguePins>0) { commandBuffer[0] = EXIOINITA; status = I2CManager.read(_I2CAddress, _analoguePinMap, _numAnaloguePins, commandBuffer, 1); } @@ -239,7 +241,7 @@ private: // If we're not doing anything now, check to see if a new input transfer is due. if (_readState == RDS_IDLE) { - if (currentMicros - _lastDigitalRead > _digitalRefresh) { // Delay for digital read refresh + if (currentMicros - _lastDigitalRead > _digitalRefresh && _numDigitalPins>0) { // Delay for digital read refresh // Issue new read request for digital states. As the request is non-blocking, the buffer has to // be allocated from heap (object state). _readCommandBuffer[0] = EXIORDD; @@ -247,7 +249,7 @@ private: // non-blocking read _lastDigitalRead = currentMicros; _readState = RDS_DIGITAL; - } else if (currentMicros - _lastAnalogueRead > _analogueRefresh) { // Delay for analogue read refresh + } else if (currentMicros - _lastAnalogueRead > _analogueRefresh && _numAnaloguePins>0) { // Delay for analogue read refresh // Issue new read for analogue input states _readCommandBuffer[0] = EXIORDAN; I2CManager.read(_I2CAddress, _analogueInputBuffer, diff --git a/version.h b/version.h index b74cbd2..3da0307 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.15" +#define VERSION "5.2.16" +// 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions // - add repeats to function packets that are not reminded in accordance with accessory packets // 5.2.14 - Reminder window DCC packet optimization From 198d762a212321ef632f2edf5cb6984c7254622d Mon Sep 17 00:00:00 2001 From: pmantoine Date: Fri, 22 Dec 2023 12:29:17 +0800 Subject: [PATCH 169/310] Add F439ZI serial setup in WifiInterface --- WifiInterface.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 8b2251a..87d5437 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -68,7 +68,9 @@ Stream * WifiInterface::wifiStream; #define NUM_SERIAL 3 #define SERIAL1 Serial3 #define SERIAL3 Serial5 -#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) +#elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) \ + || defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) \ + || defined(ARDUINO_NUCLEO_F439ZI) #define NUM_SERIAL 2 #define SERIAL1 Serial6 #else From 041a6534da3c73693b232521096b7bda9fdd0717 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 24 Dec 2023 12:03:42 +0100 Subject: [PATCH 170/310] more diag and inUse tests --- WifiESP32.cpp | 21 ++++++++++----------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/WifiESP32.cpp b/WifiESP32.cpp index f0a857f..ab5274b 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -80,16 +80,15 @@ public: }; bool recycle(WiFiClient c) { - if (inUse == true) return false; - - // return false here until we have - // implemented a LRU timer - // if (LRU too recent) return false; + if (wifi == c) { + if (inUse == true) + DIAG(F("WARNING: Duplicate")); + else + DIAG(F("Returning")); + inUse = true; + return true; + } return false; - - wifi = c; - inUse = true; - return true; }; WiFiClient wifi; bool inUse = true; @@ -299,14 +298,14 @@ void WifiESP::loop() { while (client = server->available()) { for (clientId=0; clientId=clients.size()) { NetworkClient nc(client); clients.push_back(nc); - DIAG(F("New client %d, %s"), clientId, client.remoteIP().toString().c_str()); + DIAG(F("New client %d, %s:%d"), clientId, client.remoteIP().toString().c_str(),client.remotePort()); } } } From e3bab887a289b4fef5ecb14a336b8558fb31137c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 25 Dec 2023 17:32:39 +0100 Subject: [PATCH 171/310] simplify WifiESP32 --- WifiESP32.cpp | 42 +++++++++++++++++++++++------------------- 1 file changed, 23 insertions(+), 19 deletions(-) diff --git a/WifiESP32.cpp b/WifiESP32.cpp index ab5274b..1103dfc 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -74,12 +74,21 @@ class NetworkClient { public: NetworkClient(WiFiClient c) { wifi = c; + inUse = true; }; - bool ok() { - return (inUse && wifi.connected()); - }; + bool active(byte clientId) { + if (!inUse) + return false; + if(!wifi.connected()) { + DIAG(F("Remove client %d"), clientId); + CommandDistributor::forget(clientId); + wifi.stop(); + inUse = false; + return false; + } + return true; + } bool recycle(WiFiClient c) { - if (wifi == c) { if (inUse == true) DIAG(F("WARNING: Duplicate")); @@ -88,10 +97,16 @@ public: inUse = true; return true; } + if (inUse == false) { + wifi = c; + inUse = true; + return true; + } return false; }; WiFiClient wifi; - bool inUse = true; +private: + bool inUse; }; static std::vector clients; // a list to hold all clients @@ -281,18 +296,6 @@ void WifiESP::loop() { // really no good way to check for LISTEN especially in AP mode? wl_status_t wlStatus; if (APmode || (wlStatus = WiFi.status()) == WL_CONNECTED) { - // loop over all clients and remove inactive - for (clientId=0; clientIdhasClient()) { WiFiClient client; while (client = server->available()) { @@ -310,8 +313,9 @@ void WifiESP::loop() { } } // loop over all connected clients + // this removes as a side effect inactive clients when checking ::active() for (clientId=0; clientId 0) { // read data from client @@ -349,7 +353,7 @@ void WifiESP::loop() { } // buffer filled, end with '\0' so we can use it as C string buffer[count]='\0'; - if((unsigned int)clientId <= clients.size() && clients[clientId].ok()) { + if((unsigned int)clientId <= clients.size() && clients[clientId].active(clientId)) { if (Diag::CMD || Diag::WITHROTTLE) DIAG(F("SEND %d:%s"), clientId, buffer); clients[clientId].wifi.write(buffer,count); From e7d3d92c23417898cfc3772339b1679ed5ed8b78 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 25 Dec 2023 17:40:29 +0100 Subject: [PATCH 172/310] as no other tasks run on core1, yield() not necessary --- WifiESP32.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/WifiESP32.cpp b/WifiESP32.cpp index 1103dfc..c990495 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -386,8 +386,9 @@ void WifiESP::loop() { // prio task. On core1 this is not a problem // as there the wdt is disabled by the // arduio IDE startup routines. - if (xPortGetCoreID() == 0) + if (xPortGetCoreID() == 0) { feedTheDog0(); - yield(); + yield(); + } } #endif //ESP32 From bd44184f574b108d6eee700c635181e43e1b5588 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 25 Dec 2023 17:49:16 +0100 Subject: [PATCH 173/310] version 5.2.17 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 0a5110a..42646fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202312131041Z" +#define GITHUB_SHA "devel-202312251647Z" diff --git a/version.h b/version.h index 3da0307..bc79b3e 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.16" +#define VERSION "5.2.17" +// 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions // - add repeats to function packets that are not reminded in accordance with accessory packets From adb8b56c92eafd4a925cf5d21cd58c1d8315a27c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 30 Dec 2023 21:23:44 +0100 Subject: [PATCH 174/310] variable frequency step #1 --- DCCTimer.h | 1 + DCCTimerAVR.cpp | 71 ++++++++++++++++++++++++++++++++++++ DCCTimerESP.cpp | 16 +++++++- DCCTimerSTM32.cpp | 15 +++++++- MotorDriver.cpp | 93 ++++++++--------------------------------------- 5 files changed, 115 insertions(+), 81 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 3b14fd6..5cc5ce8 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -85,6 +85,7 @@ class DCCTimer { static void reset(); private: + static void DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency); static int freeMemory(); static volatile int minimum_free_memory; static const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 3e6c436..b27a906 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -29,6 +29,7 @@ #include #include #include "DCCTimer.h" +#include "DIAG.h" #ifdef DEBUG_ADC #include "TrackManager.h" #endif @@ -125,6 +126,76 @@ void DCCTimer::reset() { } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); +} +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { +#if defined(ARDUINO_AVR_UNO) + // Not worth doin something here as: + // If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source. + // If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc. + // We are most likely not on pin 3 or 11 as no known motor shield has that as brake. +#endif +#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) + uint8_t abits; + uint8_t bbits; + if (pin == 9 || pin == 10) { // timer 2 is different + + if (fbits >= 3) + abits = B11; + else + abits = B01; + + if (fbits >= 3) + bbits = B0001; + else if (fbits == 2) + bbits = B0010; + else if (fbits == 1) + bbits = B0100; + else + bbits = B0110; + + TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1 + TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler + DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B); + + } else { // not timer 9 or 10 + abits = B01; + + if (fbits >= 3) + bbits = B1001; + else if (fbits == 2) + bbits = B0010; + else if (fbits == 1) + bbits = B0011; + else + bbits = B0100; + + switch (pin) { + // case 9 and 10 taken care of above by if() + case 6: + case 7: + case 8: + // Timer4 + TCCR4A = (TCCR4A & B11111100) | abits; // set WGM0 and WGM1 + TCCR4B = (TCCR4B & B11100000) | bbits; // set WGM2 and WGM3 and divisor + DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B); + break; + case 46: + case 45: + case 44: + // Timer5 + TCCR5A = (TCCR5A & B11111100) | abits; // set WGM0 and WGM1 + TCCR5B = (TCCR5B & B11100000) | bbits; // set WGM2 and WGM3 and divisor + DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B); + break; + default: + break; + } + } +#endif +} + #if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) #define NUM_ADC_INPUTS 16 #else diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index 7ed3f28..dbd4e9d 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -151,10 +151,22 @@ void DCCTimer::reset() { ESP.restart(); } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { + if (f >= 16) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); + else if (f >= 3) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500); + else if (f == 2) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400); + else if (f == 1) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480); + else + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131); +} + #include "esp32-hal.h" #include "soc/soc_caps.h" - #ifdef SOC_LEDC_SUPPORT_HS_MODE #define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM<<1) #else @@ -164,7 +176,7 @@ void DCCTimer::reset() { static int8_t pin_to_channel[SOC_GPIO_PIN_COUNT] = { 0 }; static int cnt_channel = LEDC_CHANNELS; -void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) { +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency) { if (pin < SOC_GPIO_PIN_COUNT) { if (pin_to_channel[pin] != 0) { ledcSetup(pin_to_channel[pin], frequency, 8); diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f24adc2..c220620 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -257,6 +257,19 @@ void DCCTimer::reset() { while(true) {}; } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { + if (f >= 16) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); + else if (f >= 3) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500); + else if (f == 2) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400); + else if (f == 1) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480); + else + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 131); +} + // TODO: rationalise the size of these... could really use sparse arrays etc. static HardwareTimer * pin_timer[100] = {0}; static uint32_t channel_frequency[100] = {0}; @@ -267,7 +280,7 @@ static uint32_t pin_channel[100] = {0}; // sophisticated about detecting any clash between the timer we'd like to use for PWM and the ones // currently used for HA so they don't interfere with one another. For now we'll just make PWM // work well... then work backwards to integrate with HA mode if we can. -void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency) { if (pin_timer[pin] == NULL) { // Automatically retrieve TIM instance and channel associated to pin diff --git a/MotorDriver.cpp b/MotorDriver.cpp index bd25be4..cdbd667 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -328,45 +328,19 @@ uint16_t taurustones[28] = { 165, 175, 196, 220, void MotorDriver::setDCSignal(byte speedcode) { if (brakePin == UNUSED_PIN) return; - switch(brakePin) { -#if defined(ARDUINO_AVR_UNO) - // Not worth doin something here as: - // If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source. - // If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc. - // We are most likely not on pin 3 or 11 as no known motor shield has that as brake. -#endif -#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) - case 9: - case 10: - // Timer2 (is differnet) - TCCR2A = (TCCR2A & B11111100) | B00000001; // set WGM1=0 and WGM0=1 phase correct PWM - TCCR2B = (TCCR2B & B11110000) | B00000110; // set WGM2=0 ; set divisor on timer 2 to 1/256 for 122.55Hz - //DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B); - break; - case 6: - case 7: - case 8: - // Timer4 - TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit - TCCR4B = (TCCR4B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz - break; - case 46: - case 45: - case 44: - // Timer5 - TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for normal PWM 8-bit - TCCR5B = (TCCR5B & B11100000) | B00000100; // set WGM2=0 and WGM3=0 for normal PWM 8 bit and div 1/256 for 122.55Hz - break; -#endif - default: - break; - } // spedcoode is a dcc speed & direction byte tSpeed=speedcode & 0x7F; // DCC Speed with 0,1 stop and speed steps 2 to 127 byte tDir=speedcode & 0x80; byte brake; + + if (tSpeed <= 1) brake = 255; + else if (tSpeed >= 127) brake = 0; + else brake = 2 * (128-tSpeed); + if (invertBrake) + brake=255-brake; + + { // new block because of variable f #if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) - { int f = 131; #ifdef VARIABLE_TONES if (tSpeed > 2) { @@ -376,18 +350,13 @@ void MotorDriver::setDCSignal(byte speedcode) { } #endif DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup + DCCTimer::DCCEXanalogWrite(brakePin,brake); +#else // all AVR here + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 0); // 0 is lowest possible f, like 120Hz + analogWrite(brakePin,brake); +#endif } -#endif - if (tSpeed <= 1) brake = 255; - else if (tSpeed >= 127) brake = 0; - else brake = 2 * (128-tSpeed); - if (invertBrake) - brake=255-brake; -#if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) - DCCTimer::DCCEXanalogWrite(brakePin,brake); -#else - analogWrite(brakePin,brake); -#endif + //DIAG(F("DCSignal %d"), speedcode); if (HAVE_PORTA(fastSignalPin.shadowinout == &PORTA)) { noInterrupts(); @@ -455,39 +424,7 @@ void MotorDriver::throttleInrush(bool on) { } #else if(on){ - switch(brakePin) { -#if defined(ARDUINO_AVR_UNO) - // Not worth doin something here as: - // If we are on pin 9 or 10 we are on Timer1 and we can not touch Timer1 as that is our DCC source. - // If we are on pin 5 or 6 we are on Timer 0 ad we can not touch Timer0 as that is millis() etc. - // We are most likely not on pin 3 or 11 as no known motor shield has that as brake. -#endif -#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) - case 9: - case 10: - // Timer2 (is different) - TCCR2A = (TCCR2A & B11111100) | B00000011; // set WGM0=1 and WGM1=1 for fast PWM - TCCR2B = (TCCR2B & B11110000) | B00000001; // set WGM2=0 and prescaler div=1 (max) - DIAG(F("2 A=%x B=%x"), TCCR2A, TCCR2B); - break; - case 6: - case 7: - case 8: - // Timer4 - TCCR4A = (TCCR4A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit - TCCR4B = (TCCR4B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max) - break; - case 46: - case 45: - case 44: - // Timer5 - TCCR5A = (TCCR5A & B11111100) | B00000001; // set WGM0=1 and WGM1=0 for fast PWM 8-bit - TCCR5B = (TCCR5B & B11100000) | B00001001; // set WGM2=1 and WGM3=0 for fast PWM 8 bit and div=1 (max) - break; -#endif - default: - break; - } + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 3); } analogWrite(brakePin,duty); #endif From 67387d2dc320f04bbd9887abf41057a59d4d867f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 30 Dec 2023 22:09:01 +0100 Subject: [PATCH 175/310] function bits to freqency step #2 --- DCC.cpp | 12 ++++++++++-- DCC.h | 1 + MotorDriver.cpp | 6 +++--- MotorDriver.h | 2 +- TrackManager.cpp | 7 +++++-- 5 files changed, 20 insertions(+), 8 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 0c5148a..bd07b84 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -138,7 +138,7 @@ void DCC::setFunctionInternal(int cab, byte byte1, byte byte2, byte count) { // returns speed steps 0 to 127 (1 == emergency stop) // or -1 on "loco not found" -int8_t DCC::getThrottleSpeed(int cab) { +static int8_t DCC::getThrottleSpeed(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) return -1; return speedTable[reg].speedCode & 0x7F; @@ -146,13 +146,21 @@ int8_t DCC::getThrottleSpeed(int cab) { // returns speed code byte // or 128 (speed 0, dir forward) on "loco not found". -uint8_t DCC::getThrottleSpeedByte(int cab) { +static uint8_t DCC::getThrottleSpeedByte(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) return 128; return speedTable[reg].speedCode; } +// returns -1 for fault, 0 to 3 for frequency +static int8_t DCC::getThrottleFrequency(int cab) { + int reg=lookupSpeedTable(cab); + if (reg<0) + return -1; + return (int8_t)(speedTable[reg].functions >>29); // shift out first 29 bits so we have the "frequency bits" left +} + // returns direction on loco // or true/forward on "loco not found" bool DCC::getThrottleDirection(int cab) { diff --git a/DCC.h b/DCC.h index 3bf0cf5..cbc5372 100644 --- a/DCC.h +++ b/DCC.h @@ -61,6 +61,7 @@ public: static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection); static int8_t getThrottleSpeed(int cab); static uint8_t getThrottleSpeedByte(int cab); + static int8_t getThrottleFrequency(int cab); static bool getThrottleDirection(int cab); static void writeCVByteMain(int cab, int cv, byte bValue); static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue); diff --git a/MotorDriver.cpp b/MotorDriver.cpp index cdbd667..c1c9492 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -325,7 +325,7 @@ uint16_t taurustones[28] = { 165, 175, 196, 220, 220, 196, 175, 165 }; #endif #endif -void MotorDriver::setDCSignal(byte speedcode) { +void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) { if (brakePin == UNUSED_PIN) return; // spedcoode is a dcc speed & direction @@ -341,7 +341,7 @@ void MotorDriver::setDCSignal(byte speedcode) { { // new block because of variable f #if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) - int f = 131; + int f = frequency; #ifdef VARIABLE_TONES if (tSpeed > 2) { if (tSpeed <= 58) { @@ -352,7 +352,7 @@ void MotorDriver::setDCSignal(byte speedcode) { DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCTimer::DCCEXanalogWrite(brakePin,brake); #else // all AVR here - DCCTimer::DCCEXanalogWriteFrequency(brakePin, 0); // 0 is lowest possible f, like 120Hz + DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps 0 to 3 analogWrite(brakePin,brake); #endif } diff --git a/MotorDriver.h b/MotorDriver.h index 07ff93f..b678a84 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -187,7 +187,7 @@ class MotorDriver { } }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; - void setDCSignal(byte speedByte); + void setDCSignal(byte speedByte, uint8_t frequency=0); void throttleInrush(bool on); inline void detachDCSignal() { #if defined(__arm__) diff --git a/TrackManager.cpp b/TrackManager.cpp index 4a501a1..f7be01a 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -348,8 +348,11 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr } void TrackManager::applyDCSpeed(byte t) { - uint8_t speedByte=DCC::getThrottleSpeedByte(trackDCAddr[t]); - track[t]->setDCSignal(speedByte); + int8_t frequency = DCC::getThrottleFrequency(trackDCAddr[t]); + if (frequency <0) // loco was not found + frequency = 0; // default + uint8_t speedByte = DCC::getThrottleSpeedByte(trackDCAddr[t]); + track[t]->setDCSignal(speedByte, (uint8_t)frequency); } bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) From bf17f2018b83ae8227b273333b337ec53b0fee76 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 30 Dec 2023 22:20:41 +0100 Subject: [PATCH 176/310] fix type and static warning step #3 --- DCC.cpp | 10 +++++----- DCC.h | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index bd07b84..c3cd66f 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -138,7 +138,7 @@ void DCC::setFunctionInternal(int cab, byte byte1, byte byte2, byte count) { // returns speed steps 0 to 127 (1 == emergency stop) // or -1 on "loco not found" -static int8_t DCC::getThrottleSpeed(int cab) { +int8_t DCC::getThrottleSpeed(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) return -1; return speedTable[reg].speedCode & 0x7F; @@ -146,7 +146,7 @@ static int8_t DCC::getThrottleSpeed(int cab) { // returns speed code byte // or 128 (speed 0, dir forward) on "loco not found". -static uint8_t DCC::getThrottleSpeedByte(int cab) { +uint8_t DCC::getThrottleSpeedByte(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) return 128; @@ -154,7 +154,7 @@ static uint8_t DCC::getThrottleSpeedByte(int cab) { } // returns -1 for fault, 0 to 3 for frequency -static int8_t DCC::getThrottleFrequency(int cab) { +int8_t DCC::getThrottleFrequency(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) return -1; @@ -199,8 +199,8 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { // Take care of functions: // Set state of function - unsigned long previous=speedTable[reg].functions; - unsigned long funcmask = (1UL< Date: Sun, 31 Dec 2023 10:48:48 +0100 Subject: [PATCH 177/310] DC frequency fix bit shifting (debug code) step #4 --- DCC.cpp | 19 ++++++++++++------- DCC.h | 2 +- DCCTimerAVR.cpp | 4 ++-- GITHUB_SHA.h | 2 +- MotorDriver.cpp | 1 + TrackManager.cpp | 9 +++------ 6 files changed, 20 insertions(+), 17 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index c3cd66f..d857cb8 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -153,12 +153,14 @@ uint8_t DCC::getThrottleSpeedByte(int cab) { return speedTable[reg].speedCode; } -// returns -1 for fault, 0 to 3 for frequency -int8_t DCC::getThrottleFrequency(int cab) { +// returns 0 to 3 for frequency +uint8_t DCC::getThrottleFrequency(int cab) { int reg=lookupSpeedTable(cab); if (reg<0) - return -1; - return (int8_t)(speedTable[reg].functions >>29); // shift out first 29 bits so we have the "frequency bits" left + return 0; // use default frequency + uint8_t res = (uint8_t)(speedTable[reg].functions >>30); + DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res); + return res; // shift out first 29 bits so we have the "frequency bits" left } // returns direction on loco @@ -191,9 +193,12 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { b[nB++] = functionNumber >>7 ; // high order bits } DCCWaveform::mainTrack.schedulePacket(b, nB, 4); - return true; } - + // We use the reminder table up to 28 for normal functions. + // We use 29 to 31 for DC frequency as well. + if (functionNumber > 31) + return true; + int reg = lookupSpeedTable(cab); if (reg<0) return false; @@ -206,7 +211,7 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { } else { speedTable[reg].functions &= ~funcmask; } - if (speedTable[reg].functions != previous) { + if (speedTable[reg].functions != previous && functionNumber > 28) { updateGroupflags(speedTable[reg].groupFlags, functionNumber); CommandDistributor::broadcastLoco(reg); } diff --git a/DCC.h b/DCC.h index bccdd24..b5cb0e9 100644 --- a/DCC.h +++ b/DCC.h @@ -61,7 +61,7 @@ public: static void setThrottle(uint16_t cab, uint8_t tSpeed, bool tDirection); static int8_t getThrottleSpeed(int cab); static uint8_t getThrottleSpeedByte(int cab); - static int8_t getThrottleFrequency(int cab); + static uint8_t getThrottleFrequency(int cab); static bool getThrottleDirection(int cab); static void writeCVByteMain(int cab, int cv, byte bValue); static void writeCVBitMain(int cab, int cv, byte bNum, bool bValue); diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index b27a906..90d43a7 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -142,9 +142,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { if (pin == 9 || pin == 10) { // timer 2 is different if (fbits >= 3) - abits = B11; + abits = B00000011; else - abits = B01; + abits = B00000001; if (fbits >= 3) bbits = B0001; diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 42646fe..1ccc6e5 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202312251647Z" +#define GITHUB_SHA "devel-202312310824Z" diff --git a/MotorDriver.cpp b/MotorDriver.cpp index c1c9492..265c8ed 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -349,6 +349,7 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) } } #endif + DIAG(F("Brake %d freqencybits %x"), brakePin, f); DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCTimer::DCCEXanalogWrite(brakePin,brake); #else // all AVR here diff --git a/TrackManager.cpp b/TrackManager.cpp index f7be01a..e2d4d27 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -202,7 +202,7 @@ void TrackManager::setDCSignal(int16_t cab, byte speedbyte) { FOR_EACH_TRACK(t) { if (trackDCAddr[t]!=cab && cab != 0) continue; if (track[t]->getMode() & TRACK_MODE_DC) - track[t]->setDCSignal(speedbyte); + track[t]->setDCSignal(speedbyte, DCC::getThrottleFrequency(trackDCAddr[t])); } } @@ -348,11 +348,8 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr } void TrackManager::applyDCSpeed(byte t) { - int8_t frequency = DCC::getThrottleFrequency(trackDCAddr[t]); - if (frequency <0) // loco was not found - frequency = 0; // default - uint8_t speedByte = DCC::getThrottleSpeedByte(trackDCAddr[t]); - track[t]->setDCSignal(speedByte, (uint8_t)frequency); + track[t]->setDCSignal(DCC::getThrottleSpeedByte(trackDCAddr[t]), + DCC::getThrottleFrequency(trackDCAddr[t])); } bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) From d4f0a7c8f35da240412a671514e45cd40866836a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 31 Dec 2023 13:18:28 +0100 Subject: [PATCH 178/310] DC frequency uno does not have timers anyway step #5 --- DCC.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/DCC.cpp b/DCC.cpp index d857cb8..ea6e910 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -155,12 +155,17 @@ uint8_t DCC::getThrottleSpeedByte(int cab) { // returns 0 to 3 for frequency uint8_t DCC::getThrottleFrequency(int cab) { +#if defined(ARDUINO_AVR_UNO) + (void)cab; + return 0; +#else int reg=lookupSpeedTable(cab); if (reg<0) return 0; // use default frequency uint8_t res = (uint8_t)(speedTable[reg].functions >>30); DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res); return res; // shift out first 29 bits so we have the "frequency bits" left +#endif } // returns direction on loco From ab58c38e7bbc4f132caf8d2459fa4475e337db37 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 31 Dec 2023 13:22:34 +0100 Subject: [PATCH 179/310] motordriver frequency diag --- MotorDriver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 265c8ed..b304204 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -349,7 +349,7 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) } } #endif - DIAG(F("Brake %d freqencybits %x"), brakePin, f); + DIAG(F("Brake %d freqency %d"), brakePin, f); DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCTimer::DCCEXanalogWrite(brakePin,brake); #else // all AVR here @@ -423,7 +423,7 @@ void MotorDriver::throttleInrush(bool on) { } else { pinMode(brakePin, OUTPUT); } -#else +#else // all AVR here if(on){ DCCTimer::DCCEXanalogWriteFrequency(brakePin, 3); } From bba74a08f6710dc59457f3fafcdd19ce127c1d0e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 31 Dec 2023 13:22:42 +0100 Subject: [PATCH 180/310] Do not support obsolete on memory tight arch --- DCCEXParser.cpp | 3 ++- TrackManager.cpp | 5 +++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aefed4c..0c4a4d8 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -625,12 +625,13 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. return; +#ifdef HAVE_ENOUGH_MEMORY case 'c': // SEND METER RESPONSES // No longer useful because of multiple tracks See and if (params>0) break; TrackManager::reportObsoleteCurrent(stream); return; - +#endif case 'Q': // SENSORS Sensor::printAll(stream); return; diff --git a/TrackManager.cpp b/TrackManager.cpp index e2d4d27..1e2f88d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -574,14 +574,15 @@ bool TrackManager::getPower(byte t, char s[]) { return false; } - void TrackManager::reportObsoleteCurrent(Print* stream) { // This function is for backward JMRI compatibility only // It reports the first track only, as main, regardless of track settings. // +#ifdef HAVE_ENOUGH_MEMORY int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); StringFormatter::send(stream, F("\n"), - track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); + track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); +#endif } void TrackManager::reportCurrent(Print* stream) { From 36cc46e88ded2e9653088348e7839c2ba6e0bc24 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 31 Dec 2023 13:52:37 +0100 Subject: [PATCH 181/310] DC frequency dummy functions for odd architectures step #6 --- DCCTimerMEGAAVR.cpp | 5 +++++ DCCTimerSAMD.cpp | 5 +++++ DCCTimerTEENSY.cpp | 5 +++++ 3 files changed, 15 insertions(+) diff --git a/DCCTimerMEGAAVR.cpp b/DCCTimerMEGAAVR.cpp index 2b2bdab..f7badfd 100644 --- a/DCCTimerMEGAAVR.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -125,6 +125,11 @@ void DCCTimer::reset() { while(true){} } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { +} +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { +} + int16_t ADCee::ADCmax() { return 4095; } diff --git a/DCCTimerSAMD.cpp b/DCCTimerSAMD.cpp index f878ae5..4929ab8 100644 --- a/DCCTimerSAMD.cpp +++ b/DCCTimerSAMD.cpp @@ -156,6 +156,11 @@ void DCCTimer::reset() { while(true) {}; } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { +} +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { +} + #define NUM_ADC_INPUTS NUM_ANALOG_INPUTS uint16_t ADCee::usedpins = 0; diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp index 0619e21..fd512e9 100644 --- a/DCCTimerTEENSY.cpp +++ b/DCCTimerTEENSY.cpp @@ -141,6 +141,11 @@ void DCCTimer::reset() { SCB_AIRCR = 0x05FA0004; } +void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { +} +void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { +} + int16_t ADCee::ADCmax() { return 4095; } From 19efa749b8c5e7b00e63ee9fe6ca7daa32c5f36f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 31 Dec 2023 17:57:30 +0100 Subject: [PATCH 182/310] Typo fix HAS vs HAVE --- DCCEXParser.cpp | 2 +- TrackManager.cpp | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 0c4a4d8..23b80ab 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -625,7 +625,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) DCC::setThrottle(0,1,1); // this broadcasts speed 1(estop) and sets all reminders to speed 1. return; -#ifdef HAVE_ENOUGH_MEMORY +#ifdef HAS_ENOUGH_MEMORY case 'c': // SEND METER RESPONSES // No longer useful because of multiple tracks See and if (params>0) break; diff --git a/TrackManager.cpp b/TrackManager.cpp index 1e2f88d..b76bb8b 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -19,6 +19,7 @@ * You should have received a copy of the GNU General Public License * along with CommandStation. If not, see . */ +#include "defines.h" #include "TrackManager.h" #include "FSH.h" #include "DCCWaveform.h" @@ -578,10 +579,12 @@ void TrackManager::reportObsoleteCurrent(Print* stream) { // This function is for backward JMRI compatibility only // It reports the first track only, as main, regardless of track settings. // -#ifdef HAVE_ENOUGH_MEMORY +#ifdef HAS_ENOUGH_MEMORY int maxCurrent=track[0]->raw2mA(track[0]->getRawCurrentTripValue()); StringFormatter::send(stream, F("\n"), track[0]->raw2mA(track[0]->getCurrentRaw(false)), maxCurrent, maxCurrent); +#else + (void)stream; #endif } From 9ebb1c5fb1b3abd3b2fc23d5411615c80937a922 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 1 Jan 2024 21:25:43 +0100 Subject: [PATCH 183/310] less debug diag --- DCC.cpp | 4 ++-- DCCTimerAVR.cpp | 6 +++--- MotorDriver.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index ea6e910..59e08c9 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -163,8 +163,8 @@ uint8_t DCC::getThrottleFrequency(int cab) { if (reg<0) return 0; // use default frequency uint8_t res = (uint8_t)(speedTable[reg].functions >>30); - DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res); - return res; // shift out first 29 bits so we have the "frequency bits" left + //DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res); + return res; // shift out first 30 bits so we have the "frequency bits" left #endif } diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 90d43a7..e0fe941 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -157,7 +157,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1 TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler - DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B); + //DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B); } else { // not timer 9 or 10 abits = B01; @@ -179,7 +179,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { // Timer4 TCCR4A = (TCCR4A & B11111100) | abits; // set WGM0 and WGM1 TCCR4B = (TCCR4B & B11100000) | bbits; // set WGM2 and WGM3 and divisor - DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B); + //DIAG(F("Timer 4 A=%x B=%x"), TCCR4A, TCCR4B); break; case 46: case 45: @@ -187,7 +187,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { // Timer5 TCCR5A = (TCCR5A & B11111100) | abits; // set WGM0 and WGM1 TCCR5B = (TCCR5B & B11100000) | bbits; // set WGM2 and WGM3 and divisor - DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B); + //DIAG(F("Timer 5 A=%x B=%x"), TCCR5A, TCCR5B); break; default: break; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index b304204..3c207f2 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -349,7 +349,7 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) } } #endif - DIAG(F("Brake %d freqency %d"), brakePin, f); + //DIAG(F("Brake pin %d freqency %d"), brakePin, f); DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup DCCTimer::DCCEXanalogWrite(brakePin,brake); #else // all AVR here From 3ce9d2ec8876953a000e15fe18756010ecb6bfd8 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 1 Jan 2024 22:08:04 +0100 Subject: [PATCH 184/310] DC frequency fix broadcast messages step #7 --- CommandDistributor.cpp | 4 +++- DCC.cpp | 20 +++++++++++++------- 2 files changed, 16 insertions(+), 8 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index e8404de..f838fd2 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -209,7 +209,9 @@ int16_t CommandDistributor::retClockTime() { void CommandDistributor::broadcastLoco(byte slot) { DCC::LOCO * sp=&DCC::speedTable[slot]; - broadcastReply(COMMAND_TYPE, F("\n"), sp->loco,slot,sp->speedCode,sp->functions); + uint32_t func = sp->functions; + func = func & 0x1fffffff; // mask out bits 0-28 + broadcastReply(COMMAND_TYPE, F("\n"), sp->loco,slot,sp->speedCode,func); #ifdef SABERTOOTH if (Serial2 && sp->loco == SABERTOOTH) { static uint8_t rampingmode = 0; diff --git a/DCC.cpp b/DCC.cpp index 59e08c9..76e1509 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -216,28 +216,34 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { } else { speedTable[reg].functions &= ~funcmask; } - if (speedTable[reg].functions != previous && functionNumber > 28) { + if (speedTable[reg].functions != previous && functionNumber <= 28) { updateGroupflags(speedTable[reg].groupFlags, functionNumber); CommandDistributor::broadcastLoco(reg); } return true; } -// Flip function state +// Flip function state (used from withrottle protocol) void DCC::changeFn( int cab, int16_t functionNumber) { - if (cab<=0 || functionNumber>28) return; + if (cab<=0 || functionNumber>31) return; int reg = lookupSpeedTable(cab); if (reg<0) return; unsigned long funcmask = (1UL<28) return -1; // unknown + if (cab<=0 || functionNumber>28) + return -1; // unknown int reg = lookupSpeedTable(cab); - if (reg<0) return -1; + if (reg<0) + return -1; unsigned long funcmask = (1UL< Date: Mon, 1 Jan 2024 22:08:59 +0100 Subject: [PATCH 185/310] Make return type of DCC::getFn int8_t --- DCC.cpp | 2 +- DCC.h | 2 +- WiThrottle.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 76e1509..dbc72e3 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -238,7 +238,7 @@ void DCC::changeFn( int cab, int16_t functionNumber) { // Report function state (used from withrottle protocol) // returns 0 false, 1 true or -1 for do not know -int DCC::getFn( int cab, int16_t functionNumber) { +int8_t DCC::getFn( int cab, int16_t functionNumber) { if (cab<=0 || functionNumber>28) return -1; // unknown int reg = lookupSpeedTable(cab); diff --git a/DCC.h b/DCC.h index b5cb0e9..1deaf71 100644 --- a/DCC.h +++ b/DCC.h @@ -68,7 +68,7 @@ public: static void setFunction(int cab, byte fByte, byte eByte); static bool setFn(int cab, int16_t functionNumber, bool on); static void changeFn(int cab, int16_t functionNumber); - static int getFn(int cab, int16_t functionNumber); + static int8_t getFn(int cab, int16_t functionNumber); static uint32_t getFunctionMap(int cab); static void updateGroupflags(byte &flags, int16_t functionNumber); static void setAccessory(int address, byte port, bool gate, byte onoff = 2); diff --git a/WiThrottle.cpp b/WiThrottle.cpp index 244dfd8..e71c1cd 100644 --- a/WiThrottle.cpp +++ b/WiThrottle.cpp @@ -618,7 +618,7 @@ void WiThrottle::sendFunctions(Print* stream, byte loco) { #endif for(int fKey=0; fKey=0) StringFormatter::send(stream,F("M%cA%c%d<;>F%d%d\n"),myLocos[loco].throttle,LorS(locoid),locoid,fstate,fKey); } } From 6f076720f74acbe9d26c8939959a2c21574eb593 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 1 Jan 2024 22:17:47 +0100 Subject: [PATCH 186/310] temp version tag --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 1ccc6e5..c09f13c 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202312310824Z" +#define GITHUB_SHA "devel-202401012116Z" diff --git a/version.h b/version.h index bc79b3e..80711eb 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.17" +#define VERSION "5.2.XX" +// 5.2.XX - Variable frequency for DC mode // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions From 74f7af16751095deabe2fbfa9ebf59707c4a2cea Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 3 Jan 2024 02:36:07 +0100 Subject: [PATCH 187/310] Display network IP fix --- GITHUB_SHA.h | 2 +- WifiESP32.cpp | 2 +- version.h | 3 ++- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 42646fe..4ece558 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202312251647Z" +#define GITHUB_SHA "devel-202401030135Z" diff --git a/WifiESP32.cpp b/WifiESP32.cpp index c990495..2aef5d1 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -179,7 +179,7 @@ bool WifiESP::setup(const char *SSid, if (WiFi.status() == WL_CONNECTED) { // DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str()); DIAG(F("Wifi in STA mode")); - LCD(7, F("IP: %s"), WiFi.softAPIP().toString().c_str()); + LCD(7, F("IP: %s"), WiFi.localIP().toString().c_str()); wifiUp = true; } else { DIAG(F("Could not connect to Wifi SSID %s"),SSid); diff --git a/version.h b/version.h index bc79b3e..4ac82a5 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.17" +#define VERSION "5.2.18" +// 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions From 8036ba1c4857e71746830dbf54ab76a1ffd77070 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 3 Jan 2024 02:44:15 +0100 Subject: [PATCH 188/310] temp version tag --- GITHUB_SHA.h | 2 +- WifiESP32.cpp | 2 +- version.h | 1 + 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index c09f13c..affe86c 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401012116Z" +#define GITHUB_SHA "devel-202401030142Z" diff --git a/WifiESP32.cpp b/WifiESP32.cpp index c990495..2aef5d1 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -179,7 +179,7 @@ bool WifiESP::setup(const char *SSid, if (WiFi.status() == WL_CONNECTED) { // DIAG(F("Wifi STA IP %s"),WiFi.localIP().toString().c_str()); DIAG(F("Wifi in STA mode")); - LCD(7, F("IP: %s"), WiFi.softAPIP().toString().c_str()); + LCD(7, F("IP: %s"), WiFi.localIP().toString().c_str()); wifiUp = true; } else { DIAG(F("Could not connect to Wifi SSID %s"),SSid); diff --git a/version.h b/version.h index 80711eb..1677a49 100644 --- a/version.h +++ b/version.h @@ -5,6 +5,7 @@ #define VERSION "5.2.XX" // 5.2.XX - Variable frequency for DC mode +// 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins // 5.2.15 - move call to CommandDistributor::broadcastPower() into the TrackManager::setTrackPower(*) functions From 4a3d3228a93622d8a7ab48cf1b0000079a51b208 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 7 Jan 2024 22:22:38 +0100 Subject: [PATCH 189/310] ESP32: Use SOC_RMT_MEM_WORDS_PER_CHANNEL to determine if the RMT hardware can handle DCC --- DCCRMT.cpp | 50 +++++++++++++++++++++++++++++++++++--------------- DCCWaveform.h | 8 ++++---- 2 files changed, 39 insertions(+), 19 deletions(-) diff --git a/DCCRMT.cpp b/DCCRMT.cpp index cbd9af6..afada7b 100644 --- a/DCCRMT.cpp +++ b/DCCRMT.cpp @@ -1,5 +1,5 @@ /* - * © 2021-2022, Harald Barth. + * © 2021-2024, Harald Barth. * * This file is part of DCC-EX * @@ -25,6 +25,18 @@ #include "DCCWaveform.h" // for MAX_PACKET_SIZE #include "soc/gpio_sig_map.h" +// check for right type of ESP32 +#include "soc/soc_caps.h" +#ifndef SOC_RMT_MEM_WORDS_PER_CHANNEL +#error This symobol should be defined +#endif +#if SOC_RMT_MEM_WORDS_PER_CHANNEL < 64 +#warning This is not an ESP32-WROOM but some other unsupported variant +#warning You are outside of the DCC-EX supported hardware +#endif + +static const byte RMT_CHAN_PER_DCC_CHAN = 2; + // Number of bits resulting out of X bytes of DCC payload data // Each byte has one bit extra and at the end we have one EOF marker #define DATA_LEN(X) ((X)*9+1) @@ -75,12 +87,30 @@ void IRAM_ATTR interrupt(rmt_channel_t channel, void *t) { RMTChannel::RMTChannel(pinpair pins, bool isMain) { byte ch; byte plen; + + // Below we check if the DCC packet actually fits into the RMT hardware + // Currently MAX_PACKET_SIZE = 5 so with checksum there are + // MAX_PACKET_SIZE+1 data packets. Each need DATA_LEN (9) bits. + // To that we add the preamble length, the fencepost DCC end bit + // and the RMT EOF marker. + // SOC_RMT_MEM_WORDS_PER_CHANNEL is either 64 (original WROOM) or + // 48 (all other ESP32 like the -C3 or -S2 + // The formula to get the possible MAX_PACKET_SIZE is + // + // ALLOCATED = RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL + // MAX_PACKET_SIZE = floor((ALLOCATED - PREAMBLE_LEN - 2)/9 - 1) + // + if (isMain) { ch = 0; plen = PREAMBLE_BITS_MAIN; + static_assert (DATA_LEN(MAX_PACKET_SIZE+1) + PREAMBLE_BITS_MAIN + 2 <= RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL, + "Number of DCC packet bits greater than ESP32 RMT memory available"); } else { - ch = 2; + ch = RMT_CHAN_PER_DCC_CHAN; // number == offset plen = PREAMBLE_BITS_PROG; + static_assert (DATA_LEN(MAX_PACKET_SIZE+1) + PREAMBLE_BITS_PROG + 2 <= RMT_CHAN_PER_DCC_CHAN * SOC_RMT_MEM_WORDS_PER_CHANNEL, + "Number of DCC packet bits greater than ESP32 RMT memory available"); } // preamble @@ -115,7 +145,7 @@ RMTChannel::RMTChannel(pinpair pins, bool isMain) { // data: max packet size today is 5 + checksum maxDataLen = DATA_LEN(MAX_PACKET_SIZE+1); // plus checksum data = (rmt_item32_t*)malloc(maxDataLen*sizeof(rmt_item32_t)); - + rmt_config_t config; // Configure the RMT channel for TX bzero(&config, sizeof(rmt_config_t)); @@ -123,20 +153,10 @@ RMTChannel::RMTChannel(pinpair pins, bool isMain) { config.channel = channel = (rmt_channel_t)ch; config.clk_div = RMT_CLOCK_DIVIDER; config.gpio_num = (gpio_num_t)pins.pin; - config.mem_block_num = 2; // With longest DCC packet 11 inc checksum (future expansion) - // number of bits needed is 22preamble + start + - // 11*9 + extrazero + EOT = 124 - // 2 mem block of 64 RMT items should be enough - + config.mem_block_num = RMT_CHAN_PER_DCC_CHAN; + // use config ESP_ERROR_CHECK(rmt_config(&config)); addPin(pins.invpin, true); - /* - // test: config another gpio pin - gpio_num_t gpioNum = (gpio_num_t)(pin-1); - PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpioNum], PIN_FUNC_GPIO); - gpio_set_direction(gpioNum, GPIO_MODE_OUTPUT); - gpio_matrix_out(gpioNum, RMT_SIG_OUT0_IDX, 0, 0); - */ // NOTE: ESP_INTR_FLAG_IRAM is *NOT* included in this bitmask ESP_ERROR_CHECK(rmt_driver_install(config.channel, 0, ESP_INTR_FLAG_LOWMED|ESP_INTR_FLAG_SHARED)); diff --git a/DCCWaveform.h b/DCCWaveform.h index 2202b53..1392288 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -2,7 +2,7 @@ * © 2021 M Steve Todd * © 2021 Mike S * © 2021 Fred Decker - * © 2020-2021 Harald Barth + * © 2020-2024 Harald Barth * © 2020-2021 Chris Harlow * All rights reserved. * @@ -33,9 +33,9 @@ // Number of preamble bits. -const int PREAMBLE_BITS_MAIN = 16; -const int PREAMBLE_BITS_PROG = 22; -const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum. +const byte PREAMBLE_BITS_MAIN = 16; +const byte PREAMBLE_BITS_PROG = 22; +const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload size WITHOUT checksum. // The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic From 39d0cbb791020e69be0a1da37a4ba7dcdc3a33e5 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 7 Jan 2024 22:24:15 +0100 Subject: [PATCH 190/310] version 5.2.19 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 4ece558..79fd3fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401030135Z" +#define GITHUB_SHA "devel-202401072123Z" diff --git a/version.h b/version.h index 4ac82a5..ee6bd24 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.18" +#define VERSION "5.2.19" +// 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins From 70a1b9538c303613328cadc554af13d5bb23c9bf Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 8 Jan 2024 13:19:22 +0100 Subject: [PATCH 191/310] Check return of Ethernet.begin() in all code variants --- EthernetInterface.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/EthernetInterface.cpp b/EthernetInterface.cpp index 5cf531c..7d8d7b0 100644 --- a/EthernetInterface.cpp +++ b/EthernetInterface.cpp @@ -59,15 +59,15 @@ EthernetInterface::EthernetInterface() DCCTimer::getSimulatedMacAddress(mac); connected=false; - #ifdef IP_ADDRESS - Ethernet.begin(mac, IP_ADDRESS); - #else +#ifdef IP_ADDRESS + if (Ethernet.begin(mac, IP_ADDRESS) == 0) +#else if (Ethernet.begin(mac) == 0) +#endif { DIAG(F("Ethernet.begin FAILED")); return; } - #endif if (Ethernet.hardwareStatus() == EthernetNoHardware) { DIAG(F("Ethernet shield not found or W5100")); } From 718e78fca686c4dee836e0e84ab3c9a1556ab054 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 8 Jan 2024 13:20:29 +0100 Subject: [PATCH 192/310] version 5.2.20 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 79fd3fe..1cc285a 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401072123Z" +#define GITHUB_SHA "devel-202401081219Z" diff --git a/version.h b/version.h index ee6bd24..75c2899 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.19" +#define VERSION "5.2.20" +// 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic From b51a8fe126d75bddc96ab5e6f1742a0c6be2da61 Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 9 Jan 2024 10:41:29 +1000 Subject: [PATCH 193/310] Add STARTUP_DELAY --- CommandStation-EX.ino | 5 +++++ config.example.h | 8 ++++++++ version.h | 3 ++- 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 205babf..9c94606 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -76,6 +76,11 @@ void setup() DIAG(F("License GPLv3 fsf.org (c) dcc-ex.com")); +// If user has defined a startup delay, delay here before starting IO +#if defined(STARTUP_DELAY) + delay(STARTUP_DELAY) +#endif + // Initialise HAL layer before reading EEprom or setting up MotorDrivers IODevice::begin(); diff --git a/config.example.h b/config.example.h index 89d6c1f..a2e08b2 100644 --- a/config.example.h +++ b/config.example.h @@ -222,6 +222,14 @@ The configuration file for DCC-EX Command Station // We do not support to use the same address, for example 100(long) and 100(short) // at the same time, there must be a border. +///////////////////////////////////////////////////////////////////////////////////// +// Some newer 32bit microcontrollers boot very quickly, so powering on I2C and other +// peripheral devices at the same time may result in the CommandStation booting too +// quickly to detect them. +// To work around this, uncomment the STARTUP_DELAY line below and set a value in +// milliseconds that works for your environment, default is 3000 (3 seconds). +// #define STARTUP_DELAY 3000 + ///////////////////////////////////////////////////////////////////////////////////// // // DEFINE TURNOUTS/ACCESSORIES FOLLOW NORM RCN-213 diff --git a/version.h b/version.h index 75c2899..9f19afe 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.20" +#define VERSION "5.2.21" +// 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC // 5.2.18 - Display network IP fix From 5ac26ce505b28c7f0a0a76b2d4e39b6b51b6cc5c Mon Sep 17 00:00:00 2001 From: peteGSX <97784652+peteGSX@users.noreply.github.com> Date: Tue, 9 Jan 2024 10:49:22 +1000 Subject: [PATCH 194/310] Add missing ; and DIAG message --- CommandStation-EX.ino | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 9c94606..2cd9d33 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -78,7 +78,8 @@ void setup() // If user has defined a startup delay, delay here before starting IO #if defined(STARTUP_DELAY) - delay(STARTUP_DELAY) + DIAG(F("Delaying startup for %dms"), STARTUP_DELAY); + delay(STARTUP_DELAY); #endif // Initialise HAL layer before reading EEprom or setting up MotorDrivers From ca380d11dcaf01459614d2527577a08eb00cb43b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:15:30 +0100 Subject: [PATCH 195/310] Do not crash on turnouts or turntables without description --- EXRAIL2.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index cc3269b..8a2eadf 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -333,13 +333,15 @@ if (compileFeatures & FEATURE_SIGNAL) { } void RMFT2::setTurnoutHiddenState(Turnout * t) { - // turnout descriptions are in low flash F strings - t->setHidden(GETFLASH(getTurnoutDescription(t->getId()))==0x01); + // turnout descriptions are in low flash F strings + const FSH *desc = getTurnoutDescription(t->getId()); + if (desc) t->setHidden(GETFLASH(desc)==0x01); } #ifndef IO_NO_HAL void RMFT2::setTurntableHiddenState(Turntable * tto) { - tto->setHidden(GETFLASH(getTurntableDescription(tto->getId()))==0x01); + const FSH *desc = getTurntableDescription(tto->getId()); + if (desc) tto->setHidden(GETFLASH(desc)==0x01); } #endif From 27bd4448845e82b8d5d614dcc2d412bbde975c1c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:18:14 +0100 Subject: [PATCH 196/310] Numbers for automations/routes can be negative --- EXRAIL2Parser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index b049699..d231342 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -134,7 +134,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 return; } if (paramCount==2) { // - uint16_t id=p[1]; + int16_t id=p[1]; StringFormatter::send(stream,F("\n"), id, getRouteType(id), getRouteDescription(id)); From 796d5c47748a4c189f2b04c1e3215f6f54a2c9b2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 08:20:14 +0100 Subject: [PATCH 197/310] version 5.2.22 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 1cc285a..a53b57a 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401081219Z" +#define GITHUB_SHA "devel-202401100719Z" diff --git a/version.h b/version.h index 9f19afe..3c33933 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.21" +#define VERSION "5.2.22" +// 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC From 2e4995cab364893b37796cffd79ce992c1b1e47f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 11:58:30 +0000 Subject: [PATCH 198/310] Keyword Hasher _hk --- DCCEXParser.cpp | 154 ++++++++++++++++------------------------------ EXRAIL2Parser.cpp | 52 +++++----------- KeywordHasher.h | 57 +++++++++++++++++ TrackManager.cpp | 36 ++++------- 4 files changed, 137 insertions(+), 162 deletions(-) create mode 100644 KeywordHasher.h diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index aefed4c..47665c5 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -116,6 +116,7 @@ Once a new OPCODE is decided upon, update this list. #include "EXRAIL2.h" #include "Turntables.h" #include "version.h" +#include "KeywordHasher.h" // This macro can't be created easily as a portable function because the // flashlist requires a far pointer for high flash access. @@ -126,57 +127,6 @@ Once a new OPCODE is decided upon, update this list. StringFormatter::send(stream,F(" %d"),value); \ } - -// These keywords are used in the <1> command. The number is what you get if you use the keyword as a parameter. -// To discover new keyword numbers , use the <$ YOURKEYWORD> command -const int16_t HASH_KEYWORD_MAIN = 11339; -const int16_t HASH_KEYWORD_CABS = -11981; -const int16_t HASH_KEYWORD_RAM = 25982; -const int16_t HASH_KEYWORD_CMD = 9962; -const int16_t HASH_KEYWORD_ACK = 3113; -const int16_t HASH_KEYWORD_ON = 2657; -const int16_t HASH_KEYWORD_DCC = 6436; -const int16_t HASH_KEYWORD_SLOW = -17209; -#ifndef DISABLE_PROG -const int16_t HASH_KEYWORD_JOIN = -30750; -const int16_t HASH_KEYWORD_PROG = -29718; -const int16_t HASH_KEYWORD_PROGBOOST = -6353; -#endif -#ifndef DISABLE_EEPROM -const int16_t HASH_KEYWORD_EEPROM = -7168; -#endif -const int16_t HASH_KEYWORD_LIMIT = 27413; -const int16_t HASH_KEYWORD_MAX = 16244; -const int16_t HASH_KEYWORD_MIN = 15978; -const int16_t HASH_KEYWORD_RESET = 26133; -const int16_t HASH_KEYWORD_RETRY = 25704; -const int16_t HASH_KEYWORD_SPEED28 = -17064; -const int16_t HASH_KEYWORD_SPEED128 = 25816; -const int16_t HASH_KEYWORD_SERVO=27709; -const int16_t HASH_KEYWORD_TT=2688; -const int16_t HASH_KEYWORD_VPIN=-415; -const int16_t HASH_KEYWORD_A='A'; -const int16_t HASH_KEYWORD_C='C'; -const int16_t HASH_KEYWORD_G='G'; -const int16_t HASH_KEYWORD_H='H'; -const int16_t HASH_KEYWORD_I='I'; -const int16_t HASH_KEYWORD_M='M'; -const int16_t HASH_KEYWORD_O='O'; -const int16_t HASH_KEYWORD_P='P'; -const int16_t HASH_KEYWORD_R='R'; -const int16_t HASH_KEYWORD_T='T'; -const int16_t HASH_KEYWORD_X='X'; -const int16_t HASH_KEYWORD_LCN = 15137; -const int16_t HASH_KEYWORD_HAL = 10853; -const int16_t HASH_KEYWORD_SHOW = -21309; -const int16_t HASH_KEYWORD_ANIN = -10424; -const int16_t HASH_KEYWORD_ANOUT = -26399; -const int16_t HASH_KEYWORD_WIFI = -5583; -const int16_t HASH_KEYWORD_ETHERNET = -30767; -const int16_t HASH_KEYWORD_WIT = 31594; -const int16_t HASH_KEYWORD_EXTT = 8573; -const int16_t HASH_KEYWORD_ADD = 3201; - int16_t DCCEXParser::stashP[MAX_COMMAND_PARAMS]; bool DCCEXParser::stashBusy; Print *DCCEXParser::stashStream = NULL; @@ -567,20 +517,20 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::ON); } if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <1 MAIN> + if (p[0]=="MAIN"_hk) { // <1 MAIN> TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::ON); } #ifndef DISABLE_PROG - else if (p[0] == HASH_KEYWORD_JOIN) { // <1 JOIN> + else if (p[0] == "JOIN"_hk) { // <1 JOIN> TrackManager::setJoin(true); TrackManager::setTrackPower(TRACK_MODE_MAIN|TRACK_MODE_PROG, POWERMODE::ON); } - else if (p[0]==HASH_KEYWORD_PROG) { // <1 PROG> + else if (p[0]=="PROG"_hk) { // <1 PROG> TrackManager::setJoin(false); TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::ON); } #endif - else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> + else if (p[0] >= "A"_hk && p[0] <= "H"_hk) { // <1 A-H> byte t = (p[0] - 'A'); TrackManager::setTrackPower(POWERMODE::ON, t); //StringFormatter::send(stream, F("\n"), t+'A'); @@ -600,17 +550,17 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) TrackManager::setTrackPower(TRACK_MODE_ALL, POWERMODE::OFF); } if (params==1) { - if (p[0]==HASH_KEYWORD_MAIN) { // <0 MAIN> + if (p[0]=="MAIN"_hk) { // <0 MAIN> TrackManager::setJoin(false); TrackManager::setTrackPower(TRACK_MODE_MAIN, POWERMODE::OFF); } #ifndef DISABLE_PROG - else if (p[0]==HASH_KEYWORD_PROG) { // <0 PROG> + else if (p[0]=="PROG"_hk) { // <0 PROG> TrackManager::progTrackBoosted=false; // Prog track boost mode will not outlive prog track off TrackManager::setTrackPower(TRACK_MODE_PROG, POWERMODE::OFF); } #endif - else if (p[0] >= HASH_KEYWORD_A && p[0] <= HASH_KEYWORD_H) { // <1 A-H> + else if (p[0] >= "A"_hk && p[0] <= "H"_hk) { // <1 A-H> byte t = (p[0] - 'A'); TrackManager::setJoin(false); TrackManager::setTrackPower(POWERMODE::OFF, t); @@ -704,7 +654,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) //if ((params<1) | (params>2)) break; // int16_t id=(params==2)?p[1]:0; switch(p[0]) { - case HASH_KEYWORD_C: // sets time and speed + case "C"_hk: // sets time and speed if (params==1) { // returns latest time int16_t x = CommandDistributor::retClockTime(); StringFormatter::send(stream, F("\n"), x); @@ -713,28 +663,28 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) CommandDistributor::setClockTime(p[1], p[2], 1); return; - case HASH_KEYWORD_G: // current gauge limits + case "G"_hk: // current gauge limits if (params>1) break; TrackManager::reportGauges(stream); // return; - case HASH_KEYWORD_I: // current values + case "I"_hk: // current values if (params>1) break; TrackManager::reportCurrent(stream); // return; - case HASH_KEYWORD_A: // intercepted by EXRAIL// returns automations/routes + case "A"_hk: // intercepted by EXRAIL// returns automations/routes if (params!=1) break; // StringFormatter::send(stream, F("\n")); return; - case HASH_KEYWORD_M: // intercepted by EXRAIL + case "M"_hk: // intercepted by EXRAIL if (params>1) break; // invalid cant do // requests stash size so say none. StringFormatter::send(stream,F("\n")); return; - case HASH_KEYWORD_R: // returns rosters + case "R"_hk: // returns rosters StringFormatter::send(stream, F("\n")); return; - case HASH_KEYWORD_T: // returns turnout list + case "T"_hk: // returns turnout list StringFormatter::send(stream, F(" for ( Turnout * t=Turnout::first(); t; t=t->next()) { @@ -780,7 +730,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) return; // No turntables without HAL support #ifndef IO_NO_HAL - case HASH_KEYWORD_O: // for (Turntable * tto=Turntable::first(); tto; tto=tto->next()) { @@ -805,7 +755,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } } return; - case HASH_KEYWORD_P: // returns turntable position list for the turntable id + case "P"_hk: // returns turntable position list for the turntable id if (params==2) { // Turntable *tto=Turntable::get(id); if (!tto || tto->isHidden()) { @@ -972,14 +922,14 @@ bool DCCEXParser::parseT(Print *stream, int16_t params, int16_t p[]) switch (p[1]) { // Turnout messages use 1=throw, 0=close. case 0: - case HASH_KEYWORD_C: + case "C"_hk: state = true; break; case 1: - case HASH_KEYWORD_T: + case "T"_hk: state= false; break; - case HASH_KEYWORD_X: + case "X"_hk: { Turnout *tt = Turnout::get(p[0]); if (tt) { @@ -996,14 +946,14 @@ bool DCCEXParser::parseT(Print *stream, int16_t params, int16_t p[]) } default: // Anything else is some kind of turnout create function. - if (params == 6 && p[1] == HASH_KEYWORD_SERVO) { // + if (params == 6 && p[1] == "SERVO"_hk) { // if (!ServoTurnout::create(p[0], (VPIN)p[2], (uint16_t)p[3], (uint16_t)p[4], (uint8_t)p[5])) return false; } else - if (params == 3 && p[1] == HASH_KEYWORD_VPIN) { // + if (params == 3 && p[1] == "VPIN"_hk) { // if (!VpinTurnout::create(p[0], p[2])) return false; } else - if (params >= 3 && p[1] == HASH_KEYWORD_DCC) { + if (params >= 3 && p[1] == "DCC"_hk) { // 0<=addr<=511, 0<=subadd<=3 (like command). if (params==4 && p[2]>=0 && p[2]<512 && p[3]>=0 && p[3]<4) { // if (!DCCTurnout::create(p[0], p[2], p[3])) return false; @@ -1069,41 +1019,41 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { switch (p[0]) { #ifndef DISABLE_PROG - case HASH_KEYWORD_PROGBOOST: + case "PROGBOOST"_hk: TrackManager::progTrackBoosted=true; return true; #endif - case HASH_KEYWORD_RESET: + case "RESET"_hk: DCCTimer::reset(); break; // and if we didnt restart - case HASH_KEYWORD_SPEED28: + case "SPEED28"_hk: DCC::setGlobalSpeedsteps(28); DIAG(F("28 Speedsteps")); return true; - case HASH_KEYWORD_SPEED128: + case "SPEED128"_hk: DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; #ifndef DISABLE_PROG - case HASH_KEYWORD_ACK: // + case "ACK"_hk: // if (params >= 3) { - if (p[1] == HASH_KEYWORD_LIMIT) { + if (p[1] == "LIMIT"_hk) { DCCACK::setAckLimit(p[2]); LCD(1, F("Ack Limit=%dmA"), p[2]); // - } else if (p[1] == HASH_KEYWORD_MIN) { + } else if (p[1] == "MIN"_hk) { DCCACK::setMinAckPulseDuration(p[2]); LCD(0, F("Ack Min=%uus"), p[2]); // - } else if (p[1] == HASH_KEYWORD_MAX) { + } else if (p[1] == "MAX"_hk) { DCCACK::setMaxAckPulseDuration(p[2]); LCD(0, F("Ack Max=%uus"), p[2]); // - } else if (p[1] == HASH_KEYWORD_RETRY) { + } else if (p[1] == "RETRY"_hk) { if (p[2] >255) p[2]=3; LCD(0, F("Ack Retry=%d Sum=%d"), p[2], DCCACK::setAckRetry(p[2])); // } } else { - bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + bool onOff = (params > 0) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off DIAG(F("Ack diag %S"), onOff ? F("on") : F("off")); Diag::ACK = onOff; @@ -1121,64 +1071,64 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) { if (params == 0) return false; - bool onOff = (params > 0) && (p[1] == 1 || p[1] == HASH_KEYWORD_ON); // dont care if other stuff or missing... just means off + bool onOff = (params > 0) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off switch (p[0]) { - case HASH_KEYWORD_CABS: // + case "CABS"_hk: // DCC::displayCabList(stream); return true; - case HASH_KEYWORD_RAM: // + case "RAM"_hk: // DIAG(F("Free memory=%d"), DCCTimer::getMinimumFreeMemory()); return true; - case HASH_KEYWORD_CMD: // + case "CMD"_hk: // Diag::CMD = onOff; return true; #ifdef HAS_ENOUGH_MEMORY - case HASH_KEYWORD_WIFI: // + case "WIFI"_hk: // Diag::WIFI = onOff; return true; - case HASH_KEYWORD_ETHERNET: // + case "ETHERNET"_hk: // Diag::ETHERNET = onOff; return true; - case HASH_KEYWORD_WIT: // + case "WIT"_hk: // Diag::WITHROTTLE = onOff; return true; - case HASH_KEYWORD_LCN: // + case "LCN"_hk: // Diag::LCN = onOff; return true; #endif #ifndef DISABLE_EEPROM - case HASH_KEYWORD_EEPROM: // + case "EEPROM"_hk: // if (params >= 2) EEStore::dump(p[1]); return true; #endif - case HASH_KEYWORD_SERVO: // + case "SERVO"_hk: // - case HASH_KEYWORD_ANOUT: // + case "ANOUT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); break; - case HASH_KEYWORD_ANIN: // Display analogue input value + case "ANIN"_hk: // Display analogue input value DIAG(F("VPIN=%u value=%d"), p[1], IODevice::readAnalogue(p[1])); break; #if !defined(IO_NO_HAL) - case HASH_KEYWORD_HAL: - if (p[1] == HASH_KEYWORD_SHOW) + case "HAL"_hk: + if (p[1] == "SHOW"_hk) IODevice::DumpAll(); - else if (p[1] == HASH_KEYWORD_RESET) + else if (p[1] == "RESET"_hk) IODevice::reset(); break; #endif - case HASH_KEYWORD_TT: // + case "TT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); break; @@ -1232,7 +1182,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 3: // | - rotate to position for EX-Turntable or create DCC turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_DCC) { + if (p[1] == "DCC"_hk) { if (tto || p[2] < 0 || p[2] > 3600) return false; if (!DCCTurntable::create(p[0])) return false; Turntable *tto = Turntable::get(p[0]); @@ -1249,7 +1199,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 4: // create an EXTT turntable { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_EXTT) { + if (p[1] == "EXTT"_hk) { if (tto || p[3] < 0 || p[3] > 3600) return false; if (!EXTTTurntable::create(p[0], (VPIN)p[2])) return false; Turntable *tto = Turntable::get(p[0]); @@ -1264,7 +1214,7 @@ bool DCCEXParser::parseI(Print *stream, int16_t params, int16_t p[]) case 5: // add a position { Turntable *tto = Turntable::get(p[0]); - if (p[1] == HASH_KEYWORD_ADD) { + if (p[1] == "ADD"_hk) { // tto must exist, no more than 48 positions, angle 0 - 3600 if (!tto || p[2] > 48 || p[4] < 0 || p[4] > 3600) return false; tto->addPosition(p[2], p[3], p[4]); diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index b049699..872d27a 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -28,25 +28,7 @@ #include "defines.h" #include "EXRAIL2.h" #include "DCC.h" -// Command parsing keywords -const int16_t HASH_KEYWORD_EXRAIL=15435; -const int16_t HASH_KEYWORD_ON = 2657; -const int16_t HASH_KEYWORD_START=23232; -const int16_t HASH_KEYWORD_RESERVE=11392; -const int16_t HASH_KEYWORD_FREE=-23052; -const int16_t HASH_KEYWORD_LATCH=1618; -const int16_t HASH_KEYWORD_UNLATCH=1353; -const int16_t HASH_KEYWORD_PAUSE=-4142; -const int16_t HASH_KEYWORD_RESUME=27609; -const int16_t HASH_KEYWORD_KILL=5218; -const int16_t HASH_KEYWORD_ALL=3457; -const int16_t HASH_KEYWORD_ROUTES=-3702; -const int16_t HASH_KEYWORD_RED=26099; -const int16_t HASH_KEYWORD_AMBER=18713; -const int16_t HASH_KEYWORD_GREEN=-31493; -const int16_t HASH_KEYWORD_A='A'; -const int16_t HASH_KEYWORD_M='M'; - +#include "KeywordHasher.h" // This filter intercepts <> commands to do the following: // - Implement RMFT specific commands/diagnostics @@ -58,8 +40,8 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 switch(opcode) { case 'D': - if (p[0]==HASH_KEYWORD_EXRAIL) { // - diag = paramCount==2 && (p[1]==HASH_KEYWORD_ON || p[1]==1); + if (p[0]=="EXRAIL"_hk) { // + diag = paramCount==2 && (p[1]=="ON"_hk || p[1]==1); opcode=0; } break; @@ -125,7 +107,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 case 'J': // throttle info commands if (paramCount<1) return; switch(p[0]) { - case HASH_KEYWORD_A: // returns automations/routes + case "A"_hk: // returns automations/routes if (paramCount==1) {// StringFormatter::send(stream, F("stream(stream); @@ -152,7 +134,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 return; } break; - case HASH_KEYWORD_M: + case "M"_hk: // NOTE: we only need to handle valid calls here because // DCCEXParser has to have code to handle the cases where // exrail isnt involved anyway. @@ -236,13 +218,13 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { return true; } switch (p[0]) { - case HASH_KEYWORD_PAUSE: // + case "PAUSE"_hk: // if (paramCount!=1) return false; DCC::setThrottle(0,1,true); // pause all locos on the track pausingTask=(RMFT2 *)1; // Impossible task address return true; - case HASH_KEYWORD_RESUME: // + case "RESUME"_hk: // if (paramCount!=1) return false; pausingTask=NULL; { @@ -256,7 +238,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { return true; - case HASH_KEYWORD_START: // + case "START"_hk: // if (paramCount<2 || paramCount>3) return false; { int route=(paramCount==2) ? p[1] : p[2]; @@ -273,7 +255,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { } // check KILL ALL here, otherwise the next validation confuses ALL with a flag - if (p[0]==HASH_KEYWORD_KILL && p[1]==HASH_KEYWORD_ALL) { + if (p[0]=="KILL"_hk && p[1]=="ALL"_hk) { while (loopTask) loopTask->kill(F("KILL ALL")); // destructor changes loopTask return true; } @@ -282,7 +264,7 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { if (paramCount!=2 ) return false; switch (p[0]) { - case HASH_KEYWORD_KILL: // Kill taskid|ALL + case "KILL"_hk: // Kill taskid|ALL { if ( p[1]<0 || p[1]>=MAX_FLAGS) return false; RMFT2 * task=loopTask; @@ -297,27 +279,27 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { } return false; - case HASH_KEYWORD_RESERVE: // force reserve a section + case "RESERVE"_hk: // force reserve a section return setFlag(p[1],SECTION_FLAG); - case HASH_KEYWORD_FREE: // force free a section + case "FREE"_hk: // force free a section return setFlag(p[1],0,SECTION_FLAG); - case HASH_KEYWORD_LATCH: + case "LATCH"_hk: return setFlag(p[1], LATCH_FLAG); - case HASH_KEYWORD_UNLATCH: + case "UNLATCH"_hk: return setFlag(p[1], 0, LATCH_FLAG); - case HASH_KEYWORD_RED: + case "RED"_hk: doSignal(p[1],SIGNAL_RED); return true; - case HASH_KEYWORD_AMBER: + case "AMBER"_hk: doSignal(p[1],SIGNAL_AMBER); return true; - case HASH_KEYWORD_GREEN: + case "GREEN"_hk: doSignal(p[1],SIGNAL_GREEN); return true; diff --git a/KeywordHasher.h b/KeywordHasher.h new file mode 100644 index 0000000..d30f566 --- /dev/null +++ b/KeywordHasher.h @@ -0,0 +1,57 @@ +/* + * © 2024 Vincent Hamp and Chris Harlow + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + + +/* Reader be aware: + This function implements the _hk data type so that a string keyword + is hashed to the same value as the DCCEXParser uses to hash incoming + keywords. + Thus "MAIN"_hk generates exactly the same run time vakue + as const int16_t HASH_KEYWORD_MAIN=11339 +*/ +#ifndef KeywordHAsher_h +#define KeywordHasher_h + +#include +constexpr uint16_t CompiletimeKeywordHasher(const char * sv, uint16_t running=0) { + return (*sv==0) ? running : CompiletimeKeywordHasher(sv+1, + (*sv >= '0' && *sv <= '9') + ? (10*running+*sv-'0') // Numeric hash + : ((running << 5) + running) ^ *sv + ); // +} + +constexpr int16_t operator""_hk(const char * keyword, size_t len) +{ + return (int16_t) CompiletimeKeywordHasher(keyword,len*0); +} + +/* Some historical values for testing: +const int16_t HASH_KEYWORD_MAIN = 11339; +const int16_t HASH_KEYWORD_SLOW = -17209; +const int16_t HASH_KEYWORD_SPEED28 = -17064; +const int16_t HASH_KEYWORD_SPEED128 = 25816; +*/ + +static_assert("MAIN"_hk == 11339); +static_assert("SLOW"_hk == -17209); +static_assert("SPEED28"_hk == -17064); +static_assert("SPEED128"_hk == 25816); +#endif \ No newline at end of file diff --git a/TrackManager.cpp b/TrackManager.cpp index 4a501a1..da96832 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -28,6 +28,7 @@ #include "DIAG.h" #include "CommandDistributor.h" #include "DCCEXParser.h" +#include "KeywordHasher.h" // Virtualised Motor shield multi-track hardware Interface #define FOR_EACH_TRACK(t) for (byte t=0;t<=lastTrack;t++) @@ -35,21 +36,6 @@ FOR_EACH_TRACK(t) \ if (track[t]->getMode()==findmode) \ track[t]->function; -#ifndef DISABLE_PROG -const int16_t HASH_KEYWORD_PROG = -29718; -#endif -const int16_t HASH_KEYWORD_MAIN = 11339; -const int16_t HASH_KEYWORD_OFF = 22479; -const int16_t HASH_KEYWORD_NONE = -26550; -const int16_t HASH_KEYWORD_DC = 2183; -const int16_t HASH_KEYWORD_DCX = 6463; // DC reversed polarity -const int16_t HASH_KEYWORD_EXT = 8201; // External DCC signal -const int16_t HASH_KEYWORD_A = 65; // parser makes single chars the ascii. -const int16_t HASH_KEYWORD_AUTO = -5457; -#ifdef BOOSTER_INPUT -const int16_t HASH_KEYWORD_BOOST = 11269; -#endif -const int16_t HASH_KEYWORD_INV = 11857; MotorDriver * TrackManager::track[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS]; @@ -362,38 +348,38 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) } - p[0]-=HASH_KEYWORD_A; // convert A... to 0.... + p[0]-="A"_hk; // convert A... to 0.... if (params>1 && (p[0]<0 || p[0]>=MAX_TRACKS)) return false; - if (params==2 && p[1]==HASH_KEYWORD_MAIN) // <= id MAIN> + if (params==2 && p[1]=="MAIN"_hk) // <= id MAIN> return setTrackMode(p[0],TRACK_MODE_MAIN); #ifndef DISABLE_PROG - if (params==2 && p[1]==HASH_KEYWORD_PROG) // <= id PROG> + if (params==2 && p[1]=="PROG"_hk) // <= id PROG> return setTrackMode(p[0],TRACK_MODE_PROG); #endif - if (params==2 && (p[1]==HASH_KEYWORD_OFF || p[1]==HASH_KEYWORD_NONE)) // <= id OFF> <= id NONE> + if (params==2 && (p[1]=="OFF"_hk || p[1]=="NONE"_hk)) // <= id OFF> <= id NONE> return setTrackMode(p[0],TRACK_MODE_NONE); - if (params==2 && p[1]==HASH_KEYWORD_EXT) // <= id EXT> + if (params==2 && p[1]=="EXT"_hk) // <= id EXT> return setTrackMode(p[0],TRACK_MODE_EXT); #ifdef BOOSTER_INPUT - if (params==2 && p[1]==HASH_KEYWORD_BOOST) // <= id BOOST> + if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST> return setTrackMode(p[0],TRACK_MODE_BOOST); #endif - if (params==2 && p[1]==HASH_KEYWORD_AUTO) // <= id AUTO> + if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV); - if (params==2 && p[1]==HASH_KEYWORD_INV) // <= id AUTO> + if (params==2 && p[1]=="INV"_hk) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_INV); - if (params==3 && p[1]==HASH_KEYWORD_DC && p[2]>0) // <= id DC cab> + if (params==3 && p[1]=="DC"_hk && p[2]>0) // <= id DC cab> return setTrackMode(p[0],TRACK_MODE_DC,p[2]); - if (params==3 && p[1]==HASH_KEYWORD_DCX && p[2]>0) // <= id DCX cab> + if (params==3 && p[1]=="DCX"_hk && p[2]>0) // <= id DCX cab> return setTrackMode(p[0],TRACK_MODE_DC|TRACK_MODE_INV,p[2]); return false; From 43648fd9f4df5a1fdbc9053a95de1b803866792f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 12:01:40 +0000 Subject: [PATCH 199/310] 5.2.23 --- version.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 3c33933..d849eae 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.22" +#define VERSION "5.2.23" +// 5.2.23 - KeywordHasher _hk (no functional change) // 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() From d8c282434cea0f939b8768066948b7e55f570952 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 12:11:14 +0000 Subject: [PATCH 200/310] _hk in myAutomation --- DCCEX.h | 1 + 1 file changed, 1 insertion(+) diff --git a/DCCEX.h b/DCCEX.h index 2dc8eb7..3aa7b7a 100644 --- a/DCCEX.h +++ b/DCCEX.h @@ -49,6 +49,7 @@ #include "CommandDistributor.h" #include "TrackManager.h" #include "DCCTimer.h" +#include "KeywordHasher.h" #include "EXRAIL.h" #endif From 9ab6b3d4eae983f07ed4192c511960581fd03a84 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:09:22 +0100 Subject: [PATCH 201/310] Bugfix: Ethernet fixed IP start --- EthernetInterface.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/EthernetInterface.cpp b/EthernetInterface.cpp index 7d8d7b0..34e209a 100644 --- a/EthernetInterface.cpp +++ b/EthernetInterface.cpp @@ -47,6 +47,10 @@ void EthernetInterface::setup() }; +#ifdef IP_ADDRESS +static IPAddress myIP(IP_ADDRESS); +#endif + /** * @brief Aquire IP Address from DHCP and start server * @@ -60,14 +64,14 @@ EthernetInterface::EthernetInterface() connected=false; #ifdef IP_ADDRESS - if (Ethernet.begin(mac, IP_ADDRESS) == 0) + Ethernet.begin(mac, myIP); #else if (Ethernet.begin(mac) == 0) -#endif { DIAG(F("Ethernet.begin FAILED")); return; } +#endif if (Ethernet.hardwareStatus() == EthernetNoHardware) { DIAG(F("Ethernet shield not found or W5100")); } @@ -136,7 +140,7 @@ bool EthernetInterface::checkLink() { DIAG(F("Ethernet cable connected")); connected=true; #ifdef IP_ADDRESS - Ethernet.setLocalIP(IP_ADDRESS); // for static IP, set it again + Ethernet.setLocalIP(myIP); // for static IP, set it again #endif IPAddress ip = Ethernet.localIP(); // look what IP was obtained (dynamic or static) server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT From d24d09c37a3e2a457bd3f630f64d28827b8221ec Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:10:25 +0100 Subject: [PATCH 202/310] subversion --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index a53b57a..759a0cc 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401100719Z" +#define GITHUB_SHA "devel-202401101409Z" From 20ae915eaf82c85626bf52134c10310d7c3ecef7 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Wed, 10 Jan 2024 15:23:52 +0100 Subject: [PATCH 203/310] remove unused ccr_reg variable --- I2CManager_STM32.h | 1 - 1 file changed, 1 deletion(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 7e0f547..7e9e63e 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -110,7 +110,6 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Calculate a rise time appropriate to the requested bus speed // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; - uint32_t ccr_freq; while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // writes to CR1 while STOP is being executed! From a508ee7055edfbc72de4aa5559f31869f213006d Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 10 Jan 2024 16:08:11 +0000 Subject: [PATCH 204/310] Fix asserts for Teensy --- KeywordHasher.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/KeywordHasher.h b/KeywordHasher.h index d30f566..d232bd2 100644 --- a/KeywordHasher.h +++ b/KeywordHasher.h @@ -50,8 +50,8 @@ const int16_t HASH_KEYWORD_SPEED28 = -17064; const int16_t HASH_KEYWORD_SPEED128 = 25816; */ -static_assert("MAIN"_hk == 11339); -static_assert("SLOW"_hk == -17209); -static_assert("SPEED28"_hk == -17064); -static_assert("SPEED128"_hk == 25816); +static_assert("MAIN"_hk == 11339,"Keyword hasher error"); +static_assert("SLOW"_hk == -17209,"Keyword hasher error"); +static_assert("SPEED28"_hk == -17064,"Keyword hasher error"); +static_assert("SPEED128"_hk == 25816,"Keyword hasher error"); #endif \ No newline at end of file From a54a262f6841c7a1b150b171e1a69bebbf3ead96 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sun, 14 Jan 2024 02:03:42 +0000 Subject: [PATCH 205/310] 5.2.24 EXRAIL asserts --- EXRAILMacros.h | 64 ++++++++++++++++++++++++++++++++++++++++++++++++++ version.h | 6 ++++- 2 files changed, 69 insertions(+), 1 deletion(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index f79693d..2c18ae0 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -74,6 +74,70 @@ #define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; #include "myAutomation.h" +// Pass 1d Detect sequence duplicates. +// This pass generates no runtime data or code +#include "EXRAIL2MacroReset.h" +#undef AUTOMATION +#define AUTOMATION(id, description) id, +#undef ROUTE +#define ROUTE(id, description) id, +#undef SEQUENCE +#define SEQUENCE(id) id, +constexpr int16_t compileTimeSequenceList[]={ + #include "myAutomation.h" + 0 + }; +constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1; + + +// Compile time function to check for sequence nos. +constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) { + return pos>=stuffSize? false : + compileTimeSequenceList[pos]==value + || hasseq(value,pos+1); +} + +// Compile time function to check for duplicate sequence nos. +constexpr bool hasdup(const int16_t value, const uint16_t pos ) { + return pos>=stuffSize? false : + compileTimeSequenceList[pos]==value + || hasseq(value,pos+1) + || hasdup(compileTimeSequenceList[pos],pos+1); +} + + +static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AUTOMATION detected"); + +//pass 1s static asserts to +// - check call and follows etc for existing sequence numbers +// - check range on LATCH/UNLATCH +// This pass generates no runtime data or code +#include "EXRAIL2MacroReset.h" +#undef CALL +#define CALL(id) static_assert(hasseq(id),"Sequence not found"); +#undef FOLLOW +#define FOLLOW(id) static_assert(hasseq(id),"Sequence not found"); +#undef START +#define START(id) static_assert(hasseq(id),"Sequence not found"); +#undef SENDLOCO +#define SENDLOCO(cab,id) static_assert(hasseq(id),"Sequence not found"); +#undef LATCH +#define LATCH(id) static_assert(id>=0 && id=0 && id=0 && id=0 && id=0 && speed<128,"Speed out of valid range 0-127"); +#undef FWD +#define FWD(speed) static_assert(speed>=0 && speed<128,"Speed out of valid range 0-127"); +#undef REV +#define REV(speed) static_assert(speed>=0 && speed<128,"Speed out of valid range 0-127"); + +#include "myAutomation.h" + // Pass 1h Implements HAL macro by creating exrailHalSetup function // Also allows creating EXTurntable object #include "EXRAIL2MacroReset.h" diff --git a/version.h b/version.h index d849eae..15b7e5d 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.23" +#define VERSION "5.2.24" +// 5.2.24 - Exrail macro asserts to catch +// : duplicate/missing automation/route/sequence/call ids +// : latches and reserves out of range +// : speeds out of range // 5.2.23 - KeywordHasher _hk (no functional change) // 5.2.22 - Bugfixes: Empty turnout descriptions ok; negative route numbers valid. // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup From 8216579f62e166bcaf474fa182162233d1cbbec2 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sun, 14 Jan 2024 02:09:22 +0000 Subject: [PATCH 206/310] 5.2.25 returns bugs --- DCCEXParser.cpp | 8 ++++---- version.h | 3 ++- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 47665c5..16f4494 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1113,11 +1113,11 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) case "ANOUT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); - break; + return true; case "ANIN"_hk: // Display analogue input value DIAG(F("VPIN=%u value=%d"), p[1], IODevice::readAnalogue(p[1])); - break; + return true; #if !defined(IO_NO_HAL) case "HAL"_hk: @@ -1125,12 +1125,12 @@ bool DCCEXParser::parseD(Print *stream, int16_t params, int16_t p[]) IODevice::DumpAll(); else if (p[1] == "RESET"_hk) IODevice::reset(); - break; + return true; #endif case "TT"_hk: // IODevice::writeAnalogue(p[1], p[2], params>3 ? p[3] : 0); - break; + return true; default: // invalid/unknown return parseC(stream, params, p); diff --git a/version.h b/version.h index 15b7e5d..33c6164 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.24" +#define VERSION "5.2.25" +// 5.2.25 - Fix bug causing after working Date: Sun, 14 Jan 2024 20:20:22 +0000 Subject: [PATCH 207/310] HAL defaults control --- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 7 ++++++- IODevice.cpp | 44 ++++++++++++++++++++++---------------------- IODevice.h | 3 ++- version.h | 4 +++- 5 files changed, 35 insertions(+), 25 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 7811a0d..3554f6c 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -67,6 +67,7 @@ #undef FWD #undef GREEN #undef HAL +#undef HAL_IGNORE_DEFAULTS #undef IF #undef IFAMBER #undef IFCLOSED @@ -218,6 +219,7 @@ #define FWD(speed) #define GREEN(signal_id) #define HAL(haltype,params...) +#define HAL_IGNORE_DEFAULTS #define IF(sensor_id) #define IFAMBER(signal_id) #define IFCLOSED(turnout_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 2c18ae0..8ed2b82 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -143,8 +143,12 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #include "EXRAIL2MacroReset.h" #undef HAL #define HAL(haltype,params...) haltype::create(params); -void exrailHalSetup() { +#undef HAL_IGNORE_DEFAULTS +#define HAL_IGNORE_DEFAULTS ignore_defaults=true; +bool exrailHalSetup() { + bool ignore_defaults=false; #include "myAutomation.h" + return ignore_defaults; } // Pass 1c detect compile time featurtes @@ -460,6 +464,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define FWD(speed) OPCODE_FWD,V(speed), #define GREEN(signal_id) OPCODE_GREEN,V(signal_id), #define HAL(haltype,params...) +#define HAL_IGNORE_DEFAULTS #define IF(sensor_id) OPCODE_IF,V(sensor_id), #define IFAMBER(signal_id) OPCODE_IFAMBER,V(signal_id), #define IFCLOSED(turnout_id) OPCODE_IFCLOSED,V(turnout_id), diff --git a/IODevice.cpp b/IODevice.cpp index e811fff..99199aa 100644 --- a/IODevice.cpp +++ b/IODevice.cpp @@ -33,7 +33,7 @@ // Link to halSetup function. If not defined, the function reference will be NULL. extern __attribute__((weak)) void halSetup(); -extern __attribute__((weak)) void exrailHalSetup(); +extern __attribute__((weak)) bool exrailHalSetup(); //================================================================================================================== // Static methods @@ -60,34 +60,31 @@ void IODevice::begin() { halSetup(); // include any HAL devices defined in exrail. + bool ignoreDefaults=false; if (exrailHalSetup) - exrailHalSetup(); - + ignoreDefaults=exrailHalSetup(); + if (ignoreDefaults) return; + // Predefine two PCA9685 modules 0x40-0x41 if no conflicts // Allocates 32 pins 100-131 - if (checkNoOverlap(100, 16, 0x40)) { + const bool silent=true; // no message if these conflict + if (checkNoOverlap(100, 16, 0x40, silent)) { PCA9685::create(100, 16, 0x40); - } else { - DIAG(F("Default PCA9685 at I2C 0x40 disabled due to configured user device")); - } - if (checkNoOverlap(116, 16, 0x41)) { + } + + if (checkNoOverlap(116, 16, 0x41, silent)) { PCA9685::create(116, 16, 0x41); - } else { - DIAG(F("Default PCA9685 at I2C 0x41 disabled due to configured user device")); - } + } // Predefine two MCP23017 module 0x20/0x21 if no conflicts // Allocates 32 pins 164-195 - if (checkNoOverlap(164, 16, 0x20)) { + if (checkNoOverlap(164, 16, 0x20, silent)) { MCP23017::create(164, 16, 0x20); - } else { - DIAG(F("Default MCP23017 at I2C 0x20 disabled due to configured user device")); - } - if (checkNoOverlap(180, 16, 0x21)) { + } + + if (checkNoOverlap(180, 16, 0x21, silent)) { MCP23017::create(180, 16, 0x21); - } else { - DIAG(F("Default MCP23017 at I2C 0x21 disabled due to configured user device")); - } + } } // reset() function to reinitialise all devices @@ -339,7 +336,10 @@ IODevice *IODevice::findDeviceFollowing(VPIN vpin) { // returns true if pins DONT overlap with existing device // TODO: Move the I2C address reservation and checks into the I2CManager code. // That will enable non-HAL devices to reserve I2C addresses too. -bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddress) { +// Silent is used by the default setup so that there is no message if the default +// device has already been handled by the user setup. +bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, + I2CAddress i2cAddress, bool silent) { #ifdef DIAG_IO DIAG(F("Check no overlap %u %u %s"), firstPin,nPins,i2cAddress.toString()); #endif @@ -352,14 +352,14 @@ bool IODevice::checkNoOverlap(VPIN firstPin, uint8_t nPins, I2CAddress i2cAddres VPIN lastDevPin=firstDevPin+dev->_nPins-1; bool noOverlap= firstPin>lastDevPin || lastPin_I2CAddress==i2cAddress) { - DIAG(F("WARNING HAL Overlap. i2c Addr %s ignored."),i2cAddress.toString()); + if (!silent) DIAG(F("WARNING HAL Overlap. i2c Addr %s ignored."),i2cAddress.toString()); return false; } } diff --git a/IODevice.h b/IODevice.h index d12fafd..6c70f5f 100644 --- a/IODevice.h +++ b/IODevice.h @@ -166,7 +166,8 @@ public: void setGPIOInterruptPin(int16_t pinNumber); // Method to check if pins will overlap before creating new device. - static bool checkNoOverlap(VPIN firstPin, uint8_t nPins=1, I2CAddress i2cAddress=0); + static bool checkNoOverlap(VPIN firstPin, uint8_t nPins=1, + I2CAddress i2cAddress=0, bool silent=false); // Method used by IODevice filters to locate slave pins that may be overlayed by their own // pin range. diff --git a/version.h b/version.h index 33c6164..8c8ef68 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.25" +#define VERSION "5.2.26" +// 5.2.26 - Silently ignore overridden HAL defaults +// - include HAL_IGNORE_DEFAULTS macro in EXRAIL // 5.2.25 - Fix bug causing after working Date: Thu, 18 Jan 2024 08:20:33 +0100 Subject: [PATCH 208/310] Bugfix: allocate enough bytes for digital pins. Add more sanity checks when allocating memory --- IO_EXIOExpander.h | 33 ++++++++++++++++++++++++--------- 1 file changed, 24 insertions(+), 9 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index c8bcba0..b5c40c9 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -100,8 +100,14 @@ private: if (_digitalPinBytes < digitalBytesNeeded) { // Not enough space, free any existing buffer and allocate a new one if (_digitalPinBytes > 0) free(_digitalInputStates); - _digitalInputStates = (byte*) calloc(_digitalPinBytes, 1); - _digitalPinBytes = digitalBytesNeeded; + if ((_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) { + _digitalPinBytes = digitalBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); + _deviceState = DEVSTATE_FAILED; + _digitalPinBytes = 0; + return; + } } } @@ -117,7 +123,16 @@ private: _analogueInputStates = (uint8_t*) calloc(analogueBytesNeeded, 1); _analogueInputBuffer = (uint8_t*) calloc(analogueBytesNeeded, 1); _analoguePinMap = (uint8_t*) calloc(_numAnaloguePins, 1); - _analoguePinBytes = analogueBytesNeeded; + if (_analogueInputStates != NULL && + _analogueInputBuffer != NULL && + _analoguePinMap != NULL) { + _analoguePinBytes = analogueBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc analog pin bytes"), _I2CAddress.toString()); + _deviceState = DEVSTATE_FAILED; + _analoguePinBytes = 0; + return; + } } } } else { @@ -364,14 +379,14 @@ private: uint8_t _minorVer = 0; uint8_t _patchVer = 0; - uint8_t* _digitalInputStates; - uint8_t* _analogueInputStates; - uint8_t* _analogueInputBuffer; // buffer for I2C input transfers + uint8_t* _digitalInputStates = NULL; + uint8_t* _analogueInputStates = NULL; + uint8_t* _analogueInputBuffer = NULL; // buffer for I2C input transfers uint8_t _readCommandBuffer[1]; - uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed) - uint8_t _analoguePinBytes = 0; // Size of allocated memory buffers (may be longer than needed) - uint8_t* _analoguePinMap; + uint8_t _digitalPinBytes = 0; // Size of allocated memory buffer (may be longer than needed) + uint8_t _analoguePinBytes = 0; // Size of allocated memory buffer (may be longer than needed) + uint8_t* _analoguePinMap = NULL; I2CRB _i2crb; enum {RDS_IDLE, RDS_DIGITAL, RDS_ANALOGUE}; // Read operation states From bc37a2d2cf8d6eea6dd28fc97de7286a444604ce Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 18 Jan 2024 08:22:28 +0100 Subject: [PATCH 209/310] version 5.2.27 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 759a0cc..24f96c3 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401101409Z" +#define GITHUB_SHA "devel-202401180721Z" diff --git a/version.h b/version.h index 8c8ef68..3512451 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.26" +#define VERSION "5.2.27" +// 5.2.27 - Bugfix: IOExpander memory allocation // 5.2.26 - Silently ignore overridden HAL defaults // - include HAL_IGNORE_DEFAULTS macro in EXRAIL // 5.2.25 - Fix bug causing after working Date: Thu, 18 Jan 2024 18:56:15 +1000 Subject: [PATCH 210/310] Update EX-IOExpander copyright --- IO_EXIOExpander.h | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index b5c40c9..191bf3c 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -1,5 +1,6 @@ /* * © 2022, Peter Cole. All rights reserved. + * © 2022, Harald Barth. All rights reserved. * * This file is part of EX-CommandStation * @@ -101,13 +102,13 @@ private: // Not enough space, free any existing buffer and allocate a new one if (_digitalPinBytes > 0) free(_digitalInputStates); if ((_digitalInputStates = (byte*) calloc(digitalBytesNeeded, 1)) != NULL) { - _digitalPinBytes = digitalBytesNeeded; - } else { - DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); - _deviceState = DEVSTATE_FAILED; - _digitalPinBytes = 0; - return; - } + _digitalPinBytes = digitalBytesNeeded; + } else { + DIAG(F("EX-IOExpander I2C:%s ERROR alloc %d bytes"), _I2CAddress.toString(), digitalBytesNeeded); + _deviceState = DEVSTATE_FAILED; + _digitalPinBytes = 0; + return; + } } } From a5b73c823a0d79e786ebc530ebc7c238b5d60373 Mon Sep 17 00:00:00 2001 From: Colin Murdoch Date: Sat, 20 Jan 2024 18:09:03 +0000 Subject: [PATCH 211/310] Added SETFREQ command Added SETFREQ command to EXRAIL --- DCCTimerAVR.cpp | 2 +- EXRAIL2.cpp | 37 +++++++++++++++++++++++++++++++++++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 1 + 5 files changed, 42 insertions(+), 2 deletions(-) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index e0fe941..5c361a0 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -157,7 +157,7 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1 TCCR2B = (TCCR2B & B11110000) | bbits; // set WGM2 and 3 bits of prescaler - //DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B); + DIAG(F("Timer 2 A=%x B=%x"), TCCR2A, TCCR2B); } else { // not timer 9 or 10 abits = B01; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index cc3269b..de254a6 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -667,6 +667,43 @@ void RMFT2::loop2() { } break; + case OPCODE_SETFREQ: + // Frequency is default 0, or 1, 2,3 + //if (loco) DCC::setFn(loco,operand,true); + switch (operand) { + case 0: // default - all F-s off + if (loco) { + DCC::setFn(loco,29,false); + DCC::setFn(loco,30,false); + DCC::setFn(loco,31,false); + } + break; + case 1: + //if (loco) DCC::setFn(loco,29,true); + if (loco) { + DCC::setFn(loco,30,true); + DCC::setFn(loco,31,false); + } + break; + case 2: + //if (loco) DCC::setFn(loco,30,true); + if (loco) { + DCC::setFn(loco,30,false); + DCC::setFn(loco,31,true); + } + break; + case 3: + //if (loco) DCC::setFn(loco,31,true); + if (loco) { + DCC::setFn(loco,30,true); + DCC::setFn(loco,31,true); + } + break; + + } + + break; + case OPCODE_RESUME: pausingTask=NULL; driveLoco(speedo); diff --git a/EXRAIL2.h b/EXRAIL2.h index 30a2f45..63d20e7 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -51,7 +51,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_JOIN,OPCODE_UNJOIN,OPCODE_READ_LOCO1,OPCODE_READ_LOCO2, #endif OPCODE_POM, - OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET, + OPCODE_START,OPCODE_SETLOCO,OPCODE_SETFREQ,OPCODE_SENDLOCO,OPCODE_FORGET, OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON, OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT, OPCODE_PRINT,OPCODE_DCCACTIVATE, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 7811a0d..8ab854d 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -151,6 +151,7 @@ #undef SET_TRACK #undef SET_POWER #undef SETLOCO +#undef SETFREQ #undef SIGNAL #undef SIGNALH #undef SPEED @@ -302,6 +303,7 @@ #define SET_TRACK(track,mode) #define SET_POWER(track,onoff) #define SETLOCO(loco) +#define SETFREQ(loco,freq) #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index f79693d..93ea911 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -493,6 +493,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define SET_TRACK(track,mode) OPCODE_SET_TRACK,V(TRACK_MODE_##mode <<8 | TRACK_NUMBER_##track), #define SET_POWER(track,onoff) OPCODE_SET_POWER,V(TRACK_POWER_##onoff),OPCODE_PAD, V(TRACK_NUMBER_##track), #define SETLOCO(loco) OPCODE_SETLOCO,V(loco), +#define SETFREQ(loco,freq) OPCODE_SETLOCO,V(loco), OPCODE_SETFREQ,V(freq), #define SIGNAL(redpin,amberpin,greenpin) #define SIGNALH(redpin,amberpin,greenpin) #define SPEED(speed) OPCODE_SPEED,V(speed), From cf1e1c92b3b0f8d084def7f26f7aff5a3dcde3cd Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 22:15:47 +0100 Subject: [PATCH 212/310] Check "easy" check first --- IO_EXIOExpander.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/IO_EXIOExpander.h b/IO_EXIOExpander.h index 191bf3c..2e83eb7 100644 --- a/IO_EXIOExpander.h +++ b/IO_EXIOExpander.h @@ -1,6 +1,6 @@ /* * © 2022, Peter Cole. All rights reserved. - * © 2022, Harald Barth. All rights reserved. + * © 2024, Harald Barth. All rights reserved. * * This file is part of EX-CommandStation * @@ -257,7 +257,7 @@ private: // If we're not doing anything now, check to see if a new input transfer is due. if (_readState == RDS_IDLE) { - if (currentMicros - _lastDigitalRead > _digitalRefresh && _numDigitalPins>0) { // Delay for digital read refresh + if (_numDigitalPins>0 && currentMicros - _lastDigitalRead > _digitalRefresh) { // Delay for digital read refresh // Issue new read request for digital states. As the request is non-blocking, the buffer has to // be allocated from heap (object state). _readCommandBuffer[0] = EXIORDD; @@ -265,7 +265,7 @@ private: // non-blocking read _lastDigitalRead = currentMicros; _readState = RDS_DIGITAL; - } else if (currentMicros - _lastAnalogueRead > _analogueRefresh && _numAnaloguePins>0) { // Delay for analogue read refresh + } else if (_numAnaloguePins>0 && currentMicros - _lastAnalogueRead > _analogueRefresh) { // Delay for analogue read refresh // Issue new read for analogue input states _readCommandBuffer[0] = EXIORDAN; I2CManager.read(_I2CAddress, _analogueInputBuffer, From 811bce4b2a8fdd26315fc843183a5ad801981c6e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 22:16:26 +0100 Subject: [PATCH 213/310] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 24f96c3..d15db46 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401180721Z" +#define GITHUB_SHA "devel-202401202116Z" From 99a09c713fa702d1a73688f17e8340d9efc9f3e7 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 23:34:17 +0100 Subject: [PATCH 214/310] To make usage easier, use F29 to F31 for frequencies --- DCC.cpp | 13 ++++++++----- DCCTimerAVR.cpp | 17 +++++++++++------ DCCTimerESP.cpp | 8 ++++++-- DCCTimerSTM32.cpp | 8 ++++++-- EXRAIL2.cpp | 24 +++++++++++++----------- MotorDriver.cpp | 12 ++++++------ 6 files changed, 50 insertions(+), 32 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index dbc72e3..95464af 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -153,7 +153,7 @@ uint8_t DCC::getThrottleSpeedByte(int cab) { return speedTable[reg].speedCode; } -// returns 0 to 3 for frequency +// returns 0 to 7 for frequency uint8_t DCC::getThrottleFrequency(int cab) { #if defined(ARDUINO_AVR_UNO) (void)cab; @@ -161,10 +161,11 @@ uint8_t DCC::getThrottleFrequency(int cab) { #else int reg=lookupSpeedTable(cab); if (reg<0) - return 0; // use default frequency - uint8_t res = (uint8_t)(speedTable[reg].functions >>30); + return 0; // use default frequency + // shift out first 29 bits so we have the 3 "frequency bits" left + uint8_t res = (uint8_t)(speedTable[reg].functions >>29); //DIAG(F("Speed table %d functions %l shifted %d"), reg, speedTable[reg].functions, res); - return res; // shift out first 30 bits so we have the "frequency bits" left + return res; #endif } @@ -200,7 +201,9 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { DCCWaveform::mainTrack.schedulePacket(b, nB, 4); } // We use the reminder table up to 28 for normal functions. - // We use 29 to 31 for DC frequency as well. + // We use 29 to 31 for DC frequency as well so up to 28 + // are "real" functions and 29 to 31 are frequency bits + // controlled by function buttons if (functionNumber > 31) return true; diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 5c361a0..3bb2b9f 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -137,22 +137,27 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { // We are most likely not on pin 3 or 11 as no known motor shield has that as brake. #endif #if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) + // Speed mapping is done like this: + // No functions buttons: 000 0 -> low 131Hz + // Only F29 pressed 001 1 -> mid 490Hz + // F30 with or w/o F29 01x 2-3 -> high 3400Hz + // F31 with or w/o F29/30 1xx 4-7 -> supersonic 62500Hz uint8_t abits; uint8_t bbits; if (pin == 9 || pin == 10) { // timer 2 is different - if (fbits >= 3) + if (fbits >= 4) abits = B00000011; else abits = B00000001; - if (fbits >= 3) + if (fbits >= 4) bbits = B0001; - else if (fbits == 2) + else if (fbits >= 2) bbits = B0010; else if (fbits == 1) bbits = B0100; - else + else // fbits == 0 bbits = B0110; TCCR2A = (TCCR2A & B11111100) | abits; // set WGM0 and WGM1 @@ -162,9 +167,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t fbits) { } else { // not timer 9 or 10 abits = B01; - if (fbits >= 3) + if (fbits >= 4) bbits = B1001; - else if (fbits == 2) + else if (fbits >= 2) bbits = B0010; else if (fbits == 1) bbits = B0011; diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index dbd4e9d..ae81c74 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -154,9 +154,13 @@ void DCCTimer::reset() { void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { if (f >= 16) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); - else if (f >= 3) + else if (f == 7) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500); - else if (f == 2) + else if (f >= 4) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000); + else if (f >= 3) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000); + else if (f >= 2) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400); else if (f == 1) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480); diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index c220620..19f97b9 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -260,9 +260,13 @@ void DCCTimer::reset() { void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { if (f >= 16) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); - else if (f >= 3) + else if (f == 7) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500); - else if (f == 2) + else if (f >= 4) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000); + else if (f >= 3) + DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 16000); + else if (f >= 2) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 3400); else if (f == 1) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 480); diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index de254a6..d4537d2 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -679,27 +679,29 @@ void RMFT2::loop2() { } break; case 1: - //if (loco) DCC::setFn(loco,29,true); if (loco) { - DCC::setFn(loco,30,true); + DCC::setFn(loco,29,true); + DCC::setFn(loco,30,false); DCC::setFn(loco,31,false); } break; case 2: - //if (loco) DCC::setFn(loco,30,true); if (loco) { + DCC::setFn(loco,29,false); + DCC::setFn(loco,30,true); + DCC::setFn(loco,31,false); + } + break; + case 3: + if (loco) { + DCC::setFn(loco,29,false); DCC::setFn(loco,30,false); DCC::setFn(loco,31,true); } break; - case 3: - //if (loco) DCC::setFn(loco,31,true); - if (loco) { - DCC::setFn(loco,30,true); - DCC::setFn(loco,31,true); - } - break; - + default: + ; // do nothing + break; } break; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 3c207f2..09e2c58 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -350,10 +350,10 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) } #endif //DIAG(F("Brake pin %d freqency %d"), brakePin, f); - DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency to 100Hz XXX May move to setup + DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency DCCTimer::DCCEXanalogWrite(brakePin,brake); #else // all AVR here - DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps 0 to 3 + DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps analogWrite(brakePin,brake); #endif } @@ -406,26 +406,26 @@ void MotorDriver::throttleInrush(bool on) { return; if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT))) return; - byte duty = on ? 208 : 0; + byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec if (invertBrake) duty = 255-duty; #if defined(ARDUINO_ARCH_ESP32) if(on) { DCCTimer::DCCEXanalogWrite(brakePin,duty); - DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500); + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max } else { ledcDetachPin(brakePin); } #elif defined(ARDUINO_ARCH_STM32) if(on) { - DCCTimer::DCCEXanalogWriteFrequency(brakePin, 62500); + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max DCCTimer::DCCEXanalogWrite(brakePin,duty); } else { pinMode(brakePin, OUTPUT); } #else // all AVR here if(on){ - DCCTimer::DCCEXanalogWriteFrequency(brakePin, 3); + DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max } analogWrite(brakePin,duty); #endif From 9728d19b19dcdb4010818ad4e3f730ed89128af2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 23:35:30 +0100 Subject: [PATCH 215/310] eliminate warning --- I2CManager_STM32.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/I2CManager_STM32.h b/I2CManager_STM32.h index 7e0f547..821add6 100644 --- a/I2CManager_STM32.h +++ b/I2CManager_STM32.h @@ -110,7 +110,7 @@ void I2CManagerClass::I2C_setClock(uint32_t i2cClockSpeed) { // Calculate a rise time appropriate to the requested bus speed // Use 10x the rise time spec to enable integer divide of 50ns clock period uint16_t t_rise; - uint32_t ccr_freq; + //uint32_t ccr_freq; while (s->CR1 & I2C_CR1_STOP); // Prevents lockup by guarding further // writes to CR1 while STOP is being executed! From daa2ffc459337af98ce595f8319d7bc4e1071eb3 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 20 Jan 2024 23:36:11 +0100 Subject: [PATCH 216/310] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index affe86c..26195f4 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401030142Z" +#define GITHUB_SHA "devel-202401202235Z" From 0a52a26d50d26d2d87109a229ec32c659c8e48d6 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Jan 2024 21:09:55 +0100 Subject: [PATCH 217/310] ESP32: Can all Wifi channels. Only write Wifi password to display if it is a well known one --- WifiESP32.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/WifiESP32.cpp b/WifiESP32.cpp index 2aef5d1..e45d0e8 100644 --- a/WifiESP32.cpp +++ b/WifiESP32.cpp @@ -164,6 +164,8 @@ bool WifiESP::setup(const char *SSid, if (haveSSID && havePassword && !forceAP) { WiFi.setHostname(hostname); // Strangely does not work unless we do it HERE! WiFi.mode(WIFI_STA); + WiFi.setScanMethod(WIFI_ALL_CHANNEL_SCAN); // Scan all channels so we find strongest + // (default in Wifi library is first match) #ifdef SERIAL_BT_COMMANDS WiFi.setSleep(true); #else @@ -204,7 +206,7 @@ bool WifiESP::setup(const char *SSid, if (!haveSSID || forceAP) { // prepare all strings String strSSID(forceAP ? SSid : "DCCEX_"); - String strPass(forceAP ? password : "PASS_"); + String strPass( (forceAP && havePassword) ? password : "PASS_"); if (!forceAP) { String strMac = WiFi.macAddress(); strMac.remove(0,9); @@ -228,7 +230,8 @@ bool WifiESP::setup(const char *SSid, // DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str()); DIAG(F("Wifi in AP mode")); LCD(5, F("Wifi: %s"), strSSID.c_str()); - LCD(6, F("PASS: %s"),havePassword ? password : strPass.c_str()); + if (!havePassword) + LCD(6, F("PASS: %s"),strPass.c_str()); // DIAG(F("Wifi AP IP %s"),WiFi.softAPIP().toString().c_str()); LCD(7, F("IP: %s"),WiFi.softAPIP().toString().c_str()); wifiUp = true; From 6d0740eab4512a3b54acec0c6e34860f2e028f8a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Jan 2024 21:11:57 +0100 Subject: [PATCH 218/310] version 5.2.28 --- GITHUB_SHA.h | 2 +- version.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index d15db46..8aa2bd8 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401202116Z" +#define GITHUB_SHA "devel-202401212011Z" diff --git a/version.h b/version.h index 3512451..e94303f 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.27" +#define VERSION "5.2.28" +// 5.2.28 - ESP32: Can all Wifi channels. +// - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation // 5.2.26 - Silently ignore overridden HAL defaults // - include HAL_IGNORE_DEFAULTS macro in EXRAIL From 3c4e4bb14de63e85eac23b6e7d0d9843874979d7 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:05:56 +0000 Subject: [PATCH 219/310] Added support for DFPLayer over I2c - IO_I2CDFPlayerh Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h Added PLAYSOUND alias of ANOUT to EXRAILMacros.h EXRail additions as per advice from Chris --- EXRAIL2.h | 19 ++ EXRAILMacros.h | 4 + I2CManager.cpp | 4 +- IO_I2CDFPlayer.h | 803 +++++++++++++++++++++++++++++++++++++++++++++++ version.h | 6 +- 5 files changed, 834 insertions(+), 2 deletions(-) create mode 100644 IO_I2CDFPlayer.h diff --git a/EXRAIL2.h b/EXRAIL2.h index 30a2f45..6652526 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -258,4 +258,23 @@ private: #define GET_OPCODE GETHIGHFLASH(RMFT2::RouteCode,progCounter) #define SKIPOP progCounter+=3 +// IO_I2CDFPlayer commands and values +enum : uint8_t{ + PLAY = 0x0F, + VOL = 0x06, + FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + REPEATPLAY = 0x08, + STOPPLAY = 0x16, + EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + RESET = 0x0C, + DACON = 0x1A, + SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer (future use) + NORMAL = 0x00, // Equalizer parameters + POP = 0x01, + ROCK = 0x02, + JAZZ = 0x03, + CLASSIC = 0x04, + BASS = 0x05, + }; + #endif diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8ed2b82..98af846 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -59,6 +59,10 @@ // helper macro for turnout description as HIDDEN #define HIDDEN "\x01" +// PLAYSOUND is alias of ANOUT to make the user experience of a Conductor beter for +// playing sounds with IO_I2CDFPlayer +#define PLAYSOUND ANOUT + // helper macro to strip leading zeros off time inputs // (10#mins)%100) #define STRIP_ZERO(value) 10##value%100 diff --git a/I2CManager.cpp b/I2CManager.cpp index 1d1387e..2c115fa 100644 --- a/I2CManager.cpp +++ b/I2CManager.cpp @@ -54,6 +54,8 @@ static const FSH * guessI2CDeviceType(uint8_t address) { return F("Time-of-flight sensor"); else if (address >= 0x3c && address <= 0x3d) return F("OLED Display"); + else if (address >= 0x48 && address <= 0x57) // SC16IS752x UART detection + return F("SC16IS75x UART"); else if (address >= 0x48 && address <= 0x4f) return F("Analogue Inputs or PWM"); else if (address >= 0x40 && address <= 0x4f) @@ -363,4 +365,4 @@ void I2CAddress::toHex(const uint8_t value, char *buffer) { /* static */ bool I2CAddress::_addressWarningDone = false; -#endif \ No newline at end of file +#endif diff --git a/IO_I2CDFPlayer.h b/IO_I2CDFPlayer.h new file mode 100644 index 0000000..79fa16b --- /dev/null +++ b/IO_I2CDFPlayer.h @@ -0,0 +1,803 @@ + /* + * © 2023, Neil McKechnie. All rights reserved. + * + * This file is part of DCC++EX API + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +/* + * DFPlayer is an MP3 player module with an SD card holder. It also has an integrated + * amplifier, so it only needs a power supply and a speaker. + * This driver is a modified version of the IO_DFPlayer.h file + * ********************************************************************************************* + * + * Dec 2023, Added NXP SC16IS752 I2C Dual UART to enable the DFPlayer connection over the I2C bus + * The SC16IS752 has 64 bytes TX & RX FIFO buffer + * First version without interrupts from I2C UART and only RX/TX are used, interrupts may not be + * needed as the RX Fifo holds the reply + * + * Jan 2024, Issue with using both UARTs simultaniously, the secod uart seems to work but the first transmit + * corrupt data. This need more analysis and experimenatation. + * Will push this driver to the dev branch with the uart fixed to 0 + * Both SC16IS750 (single uart) and SC16IS752 (dual uart, but only uart 0 is enable) + * + * myHall.cpp configuration syntax: + * + * I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); + * + * Parameters: + * 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT) + * vPins : Total number of virtual pins allocated (2 vPins are supported, one for each UART) + * 1st vPin for UART 0, 2nd for UART 1 + * I2C Address : I2C address of the serial controller, in 0x format + * xtal : 0 for 1,8432Mhz, 1 for 14,7456Mhz + * + * The vPin is also a pin that can be read, it indicate if the DFPlayer has finished playing a track + * + */ + +#ifndef IO_I2CDFPlayer_h +#define IO_I2CDFPlayer_h + +#include "IODevice.h" +#include "I2CManager.h" +#include "DIAG.h" + +// Debug and diagnostic defines, enable too many will result in slowing the driver +//#define DIAG_I2CDFplayer +//#define DIAG_I2CDFplayer_data +//#define DIAG_I2CDFplayer_reg +//#define DIAG_I2CDFplayer_playing + +class I2CDFPlayer : public IODevice { +private: + const uint8_t MAXVOLUME=30; + uint8_t RETRYCOUNT = 0x03; + bool _playing = false; + uint8_t _inputIndex = 0; + unsigned long _commandSendTime; // Time (us) that last transmit took place. + unsigned long _timeoutTime; + uint8_t _recvCMD; // Last received command code byte + bool _awaitingResponse = false; + uint8_t _retryCounter = RETRYCOUNT; // Max retries before timing out + uint8_t _requestedVolumeLevel = MAXVOLUME; + uint8_t _currentVolume = MAXVOLUME; + int _requestedSong = -1; // -1=none, 0=stop, >0=file number + bool _repeat = false; // audio file is repeat playing + uint8_t _previousCmd = true; + // SC16IS752 defines + I2CAddress _I2CAddress; + I2CRB _rb; + uint8_t _UART_CH=0x00; // Fix uart ch to 0 for now + // Communication parameters for the DFPlayer are fixed at 8 bit, No parity, 1 stopbit + uint8_t WORD_LEN = 0x03; // Value LCR bit 0,1 + uint8_t STOP_BIT = 0x00; // Value LCR bit 2 + uint8_t PARITY_ENA = 0x00; // Value LCR bit 3 + uint8_t PARITY_TYPE = 0x00; // Value LCR bit 4 + uint32_t BAUD_RATE = 9600; + uint8_t PRESCALER = 0x01; // Value MCR bit 7 + uint8_t TEMP_REG_VAL = 0x00; + uint8_t FIFO_RX_LEVEL = 0x00; + uint8_t RX_BUFFER = 0x00; // nr of bytes copied into _inbuffer + uint8_t FIFO_TX_LEVEL = 0x00; + bool _playCmd = false; + bool _volCmd = false; + bool _folderCmd = false; + uint8_t _requestedFolder = 0x01; // default to folder 01 + uint8_t _currentFolder = 0x01; // default to folder 01 + bool _repeatCmd = false; + bool _stopplayCmd = false; + bool _resetCmd = false; + bool _eqCmd = false; + uint8_t _requestedEQValue = NORMAL; + uint8_t _currentEQvalue = NORMAL; // start equalizer value + bool _daconCmd = false; + uint8_t _audioMixer = 0x01; // Default to output amplifier 1 + bool _setamCmd = false; // Set the Audio mixer channel + uint8_t _outbuffer [11]; // DFPlayer command is 10 bytes + 1 byte register address & UART channel + uint8_t _inbuffer[10]; // expected DFPlayer return 10 bytes + + unsigned long _sc16is752_xtal_freq; + unsigned long SC16IS752_XTAL_FREQ_LOW = 1843200; // To support cheap eBay/AliExpress SC16IS752 boards + unsigned long SC16IS752_XTAL_FREQ_HIGH = 14745600; // Support for higher baud rates, standard for modular EX-IO system + +public: + // Constructor + I2CDFPlayer(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint8_t xtal){ + _firstVpin = firstVpin; + _nPins = nPins; + _I2CAddress = i2cAddress; + if (xtal == 0){ + _sc16is752_xtal_freq = SC16IS752_XTAL_FREQ_LOW; + } else { // should be 1 + _sc16is752_xtal_freq = SC16IS752_XTAL_FREQ_HIGH; + } + addDevice(this); + } + +public: + static void create(VPIN firstVpin, int nPins, I2CAddress i2cAddress, uint8_t xtal) { + if (checkNoOverlap(firstVpin, nPins, i2cAddress)) new I2CDFPlayer(firstVpin, nPins, i2cAddress, xtal); + } + + void _begin() override { + // check if SC16IS752 exist first, initialize and then resume DFPlayer init via SC16IS752 + I2CManager.begin(); + I2CManager.setClock(1000000); + if (I2CManager.exists(_I2CAddress)){ + DIAG(F("SC16IS752 I2C:%s UART detected"), _I2CAddress.toString()); + Init_SC16IS752(); // Initialize UART + if (_deviceState == DEVSTATE_FAILED){ + DIAG(F("SC16IS752 I2C:%s UART initialization failed"), _I2CAddress.toString()); + } + } else { + DIAG(F("SC16IS752 I2C:%s UART not detected"), _I2CAddress.toString()); + } + #if defined(DIAG_IO) + _display(); + #endif + // Now init DFPlayer + // Send a query to the device to see if it responds + _deviceState = DEVSTATE_INITIALISING; + sendPacket(0x42,0,0); + _timeoutTime = micros() + 5000000UL; // 5 second timeout + _awaitingResponse = true; + } + + + void _loop(unsigned long currentMicros) override { + // Read responses from device + uint8_t status = _rb.status; + if (status == I2C_STATUS_PENDING) return; // Busy, so don't do anything + if (status == I2C_STATUS_OK) { + processIncoming(currentMicros); + // Check if a command sent to device has timed out. Allow 0.5 second for response + // added retry counter, sometimes we do not sent keep alive due to other commands sent to DFPlayer + if (_awaitingResponse && (int32_t)(currentMicros - _timeoutTime) > 0) { // timeout triggered + if(_retryCounter == 0){ // retry counter out of luck, must take the device to failed state + DIAG(F("I2CDFPlayer:%s, DFPlayer not responding on UART channel: 0x%x"), _I2CAddress.toString(), _UART_CH); + _deviceState = DEVSTATE_FAILED; + _awaitingResponse = false; + _playing = false; + _retryCounter = RETRYCOUNT; + } else { // timeout and retry protection and recovery of corrupt data frames from DFPlayer + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: %s, DFPlayer timout, retry counter: %d on UART channel: 0x%x"), _I2CAddress.toString(), _retryCounter, _UART_CH); + #endif + _timeoutTime = currentMicros + 5000000UL; // Timeout if no response within 5 seconds// reset timeout + _awaitingResponse = false; // trigger sending a keep alive 0x42 in processOutgoing() + _retryCounter --; // decrement retry counter + resetRX_fifo(); // reset the RX fifo as it has corrupt data + } + } + } + + status = _rb.status; + if (status == I2C_STATUS_PENDING) return; // Busy, try next time + if (status == I2C_STATUS_OK) { + // Send any commands that need to go. + processOutgoing(currentMicros); + } + delayUntil(currentMicros + 10000); // Only enter every 10ms + } + + + // Check for incoming data, and update busy flag and other state accordingly + + void processIncoming(unsigned long currentMicros) { + // Expected message is in the form "7E FF 06 3D xx xx xx xx xx EF" + RX_fifo_lvl(); + if (FIFO_RX_LEVEL >= 10) { + #ifdef DIAG_I2CDFplayer + DIAG(F("I2CDFPlayer: %s Retrieving data from RX Fifo on UART_CH: 0x%x FIFO_RX_LEVEL: %d"),_I2CAddress.toString(), _UART_CH, FIFO_RX_LEVEL); + #endif + _outbuffer[0] = REG_RHR << 3 | _UART_CH << 1; + // Only copy 10 bytes from RX FIFO, there maybe additional partial return data after a track is finished playing in the RX FIFO + I2CManager.read(_I2CAddress, _inbuffer, 10, _outbuffer, 1); // inbuffer[] has the data now + //delayUntil(currentMicros + 10000); // Allow time to get the data + RX_BUFFER = 10; // We have copied 10 bytes from RX FIFO to _inbuffer + #ifdef DIAG_I2CDFplayer_data + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, RX FIFO Data"), _I2CAddress.toString(), _UART_CH); + for (int i = 0; i < sizeof _inbuffer; i++){ + DIAG(F("SC16IS752: Data _inbuffer[0x%x]: 0x%x"), i, _inbuffer[i]); + } + #endif + } else { + FIFO_RX_LEVEL = 0; //set to 0, we'll read a fresh FIFO_RX_LEVEL next time + return; // No data or not enough data in rx fifo, check again next time around + } + + + bool ok = false; + //DIAG(F("I2CDFPlayer: RX_BUFFER: %d"), RX_BUFFER); + while (RX_BUFFER != 0) { + int c = _inbuffer[_inputIndex]; // Start at 0, increment to FIFO_RX_LEVEL + switch (_inputIndex) { + case 0: + if (c == 0x7E) ok = true; + break; + case 1: + if (c == 0xFF) ok = true; + break; + case 2: + if (c== 0x06) ok = true; + break; + case 3: + _recvCMD = c; // CMD byte + ok = true; + break; + case 6: + switch (_recvCMD) { + //DIAG(F("I2CDFPlayer: %s, _recvCMD: 0x%x _awaitingResponse: 0x0%x"),_I2CAddress.toString(), _recvCMD, _awaitingResponse); + case 0x42: + // Response to status query + _playing = (c != 0); + // Mark the device online and cancel timeout + if (_deviceState==DEVSTATE_INITIALISING) { + _deviceState = DEVSTATE_NORMAL; + #ifdef DIAG_I2CDFplayer + DIAG(F("I2CDFPlayer: %s, UART_CH: 0x0%x, _deviceState: 0x0%x"),_I2CAddress.toString(), _UART_CH, _deviceState); + #endif + #ifdef DIAG_IO + _display(); + #endif + } + _awaitingResponse = false; + break; + case 0x3d: + // End of play + if (_playing) { + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: Finished")); + #endif + _playing = false; + } + break; + case 0x40: + // Error codes; 1: Module Busy + DIAG(F("I2CDFPlayer: Error %d returned from device"), c); + _playing = false; + break; + } + ok = true; + break; + case 4: case 5: case 7: case 8: + ok = true; // Skip over these bytes in message. + break; + case 9: + if (c==0xef) { + // Message finished + _retryCounter = RETRYCOUNT; // reset the retry counter as we have received a valid packet + } + break; + default: + break; + } + if (ok){ + _inputIndex++; // character as expected, so increment index + RX_BUFFER --; // Decrease FIFO_RX_LEVEL with each character read from _inbuffer[_inputIndex] + } else { + _inputIndex = 0; // otherwise reset. + RX_BUFFER = 0; + } + } + RX_BUFFER = 0; //Set to 0, we'll read a new RX FIFO level again + } + + + // Send any commands that need to be sent + void processOutgoing(unsigned long currentMicros) { + // When two commands are sent in quick succession, the device will often fail to + // execute one. Testing has indicated that a delay of 100ms or more is required + // between successive commands to get reliable operation. + // If 100ms has elapsed since the last thing sent, then check if there's some output to do. + if (((int32_t)currentMicros - _commandSendTime) > 100000) { + if ( _resetCmd == true){ + sendPacket(0x0C,0,0); + _resetCmd = false; + } else if(_volCmd == true) { // do the volme before palying a track + if(_requestedVolumeLevel >= 0 && _requestedVolumeLevel <= 30){ + _currentVolume = _requestedVolumeLevel; // If _requestedVolumeLevel is out of range, sent _currentV1olume + } + sendPacket(0x06, 0x00, _currentVolume); + _volCmd = false; + } else if (_playCmd == true) { + // Change song + if (_requestedSong != -1) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: _requestedVolumeLevel: %u, _requestedSong: %u, _currentFolder: %u _playCmd: 0x%x"), _requestedVolumeLevel, _requestedSong, _currentFolder, _playCmd); + #endif + sendPacket(0x0F, _currentFolder, _requestedSong); // audio file in folder + _requestedSong = -1; + _playCmd = false; + } + } //else if (_requestedSong == 0) { + else if (_stopplayCmd == true) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Stop playing: _stopplayCmd: 0x%x"), _stopplayCmd); + #endif + sendPacket(0x16, 0x00, 0x00); // Stop playing + _requestedSong = -1; + _repeat = false; // reset repeat + _stopplayCmd = false; + } else if (_folderCmd == true) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Folder: _folderCmd: 0x%x, _requestedFolder: %d"), _stopplayCmd, _requestedFolder); + #endif + if (_currentFolder != _requestedFolder){ + _currentFolder = _requestedFolder; + } + _folderCmd = false; + } else if (_repeatCmd == true) { + if(_repeat == false) { // No repeat play currently + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Repeat: _repeatCmd: 0x%x, _requestedSong: %d, _repeat: 0x0%x"), _repeatCmd, _requestedSong, _repeat); + #endif + sendPacket(0x08, 0x00, _requestedSong); // repeat playing audio file in root folder + _requestedSong = -1; + _repeat = true; + } + _repeatCmd= false; + } else if (_daconCmd == true) { // Always turn DAC on + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: DACON: _daconCmd: 0x%x"), _daconCmd); + #endif + sendPacket(0x1A,0,0x00); + _daconCmd = false; + } else if (_eqCmd == true){ // Set Equalizer, values 0x00 - 0x05 + if (_currentEQvalue != _requestedEQValue){ + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: EQ: _eqCmd: 0x%x, _currentEQvalue: 0x0%x, _requestedEQValue: 0x0%x"), _eqCmd, _currentEQvalue, _requestedEQValue); + #endif + _currentEQvalue = _requestedEQValue; + sendPacket(0x07,0x00,_currentEQvalue); + } + _eqCmd = false; + } else if (_setamCmd == true){ // Set Audio mixer channel + setGPIO(); // Set the audio mixer channel + /* + if (_audioMixer == 1){ // set to audio mixer 1 + if (_UART_CH == 0){ + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + //_setamCmd = false; + //UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + } else { // set to audio mixer 2 + if (_UART_CH == 0){ + TEMP_REG_VAL &= (0x00 << _UART_CH); //Set GPIO pin 0 to Low + } else { // must be UART 1 + TEMP_REG_VAL &= (0x00 << _UART_CH); //Set GPIO pin 1 to Low + } + //_setamCmd = false; + //UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + }*/ + _setamCmd = false; + } else if ((int32_t)currentMicros - _commandSendTime > 1000000) { + // Poll device every second that other commands aren't being sent, + // to check if it's still connected and responding. + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Send keepalive") ); + #endif + sendPacket(0x42,0,0); + if (!_awaitingResponse) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: Send keepalive, _awaitingResponse: 0x0%x"), _awaitingResponse ); + #endif + _timeoutTime = currentMicros + 5000000UL; // Timeout if no response within 5 seconds + _awaitingResponse = true; + } + } + } + } + + + // Write to a vPin will do nothing + void _write(VPIN vpin, int value) override { + if (_deviceState == DEVSTATE_FAILED) return; + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: Writing to any vPin not supported")); + #endif + } + + + // WriteAnalogue on first pin uses the nominated value as a file number to start playing, if file number > 0. + // Volume may be specified as second parameter to writeAnalogue. + // If value is zero, the player stops playing. + // WriteAnalogue on second pin sets the output volume. + // + // WriteAnalogue to be done on first vpin + // + //void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t=0) override { + void _writeAnalogue(VPIN vpin, int value, uint8_t volume=0, uint16_t cmd=0) override { + if (_deviceState == DEVSTATE_FAILED) return; + #ifdef DIAG_IO + DIAG(F("I2CDFPlayer: VPIN:%u FileNo:%d Volume:%d Command:0x%x"), vpin, value, volume, cmd); + #endif + uint8_t pin = vpin - _firstVpin; + if (pin == 0) { // Enhanced DFPlayer commands, do nothing if not vPin 0 + // Read command and value + switch (cmd){ + //case NONE: + // DFPlayerCmd = cmd; + // break; + case PLAY: + _playCmd = true; + _volCmd = true; + _requestedSong = value; + _requestedVolumeLevel = volume; + _playing = true; + break; + case VOL: + _volCmd = true; + _requestedVolumeLevel = volume; + break; + case FOLDER: + _folderCmd = true; + if (volume <= 0 || volume > 99){ // Range checking, valid values 1-99, else default to 1 + _requestedFolder = 0x01; // if outside range, default to folder 01 + } else { + _requestedFolder = volume; + } + break; + case REPEATPLAY: // Need to check if _repeat == true, if so do nothing + if (_repeat == false) { + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WriteAnalog Repeat: _repeat: 0x0%x, value: %d _repeatCmd: 0x%x"), _repeat, value, _repeatCmd); + #endif + _repeatCmd = true; + _requestedSong = value; + _requestedVolumeLevel = volume; + _playing = true; + } + break; + case STOPPLAY: + _stopplayCmd = true; + break; + case EQ: + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WriteAnalog EQ: cmd: 0x%x, EQ value: 0x%x"), cmd, volume); + #endif + _eqCmd = true; + if (volume <= 0 || volume > 5) { // If out of range, default to NORMAL + _requestedEQValue = NORMAL; + } else { // Valid EQ parameter range + _requestedEQValue = volume; + } + break; + case RESET: + _resetCmd = true; + break; + case DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WrtieAnalog DACON: cmd: 0x%x"), cmd); + #endif + _daconCmd = true; + break; + case SETAM: // Set the audio mixer channel to 1 or 2 + _setamCmd = true; + #ifdef DIAG_I2CDFplayer_playing + DIAG(F("I2CDFPlayer: WrtieAnalog SETAM: cmd: 0x%x"), cmd); + #endif + if (volume <= 0 || volume > 2) { // If out of range, default to 1 + _audioMixer = 1; + } else { // Valid SETAM parameter in range + _audioMixer = volume; // _audioMixer valid values 1 or 2 + } + break; + default: + break; + } + } + } + + // A read on any pin indicates if the player is still playing. + int _read(VPIN vpin) override { + if (_deviceState == DEVSTATE_FAILED) return false; + uint8_t pin = vpin - _firstVpin; + if (pin == 0) { // Do nothing if not vPin 0 + return _playing; + } + } + + void _display() override { + DIAG(F("I2CDFPlayer Configured on Vpins:%u-%u %S"), _firstVpin, _firstVpin+_nPins-1, + (_deviceState==DEVSTATE_FAILED) ? F("OFFLINE") : F("")); + } + +private: + // DFPlayer command frame + // 7E FF 06 0F 00 01 01 xx xx EF + // 0 -> 7E is start code + // 1 -> FF is version + // 2 -> 06 is length + // 3 -> 0F is command + // 4 -> 00 is no receive + // 5~6 -> 01 01 is argument + // 7~8 -> checksum = 0 - ( FF+06+0F+00+01+01 ) + // 9 -> EF is end code + + void sendPacket(uint8_t command, uint8_t arg1 = 0, uint8_t arg2 = 0) { + FIFO_TX_LEVEL = 0; // Reset FIFO_TX_LEVEL + uint8_t out[] = { + 0x7E, + 0xFF, + 06, + command, + 00, + //static_cast(arg >> 8), + //static_cast(arg & 0x00ff), + arg1, + arg2, + 00, + 00, + 0xEF }; + + setChecksum(out); + + // Prepend the DFPlayer command with REG address and UART Channel in _outbuffer + _outbuffer[0] = REG_THR << 3 | _UART_CH << 1; //TX FIFO and UART Channel + for ( int i = 1; i < sizeof(out)+1 ; i++){ + _outbuffer[i] = out[i-1]; + } + + #ifdef DIAG_I2CDFplayer_data + DIAG(F("SC16IS752: I2C: %s Sent packet function"), _I2CAddress.toString()); + for (int i = 0; i < sizeof _outbuffer; i++){ + DIAG(F("SC16IS752: Data _outbuffer[0x%x]: 0x%x"), i, _outbuffer[i]); + } + #endif + + TX_fifo_lvl(); + if(FIFO_TX_LEVEL > 0){ //FIFO is empty + I2CManager.write(_I2CAddress, _outbuffer, sizeof(_outbuffer), &_rb); + //I2CManager.write(_I2CAddress, _outbuffer, sizeof(_outbuffer)); + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: I2C: %s data transmit complete on UART: 0x%x"), _I2CAddress.toString(), _UART_CH); + #endif + } else { + DIAG(F("I2CDFPlayer at: %s, TX FIFO not empty on UART: 0x%x"), _I2CAddress.toString(), _UART_CH); + _deviceState = DEVSTATE_FAILED; // This should not happen + } + _commandSendTime = micros(); + } + + uint16_t calcChecksum(uint8_t* packet) + { + uint16_t sum = 0; + for (int i = 1; i < 7; i++) + { + sum += packet[i]; + } + return -sum; + } + + void setChecksum(uint8_t* out) + { + uint16_t sum = calcChecksum(out); + out[7] = (sum >> 8); + out[8] = (sum & 0xff); + } + + // SC16IS752 functions + // Initialise SC16IS752 only for this channel + // First a software reset + // Enable FIFO and clear TX & RX FIFO + // Need to set the following registers + // IOCONTROL set bit 1 and 2 to 0 indicating that they are GPIO + // IODIR set all bit to 1 indicating al are output + // IOSTATE set only bit 0 to 1 for UART 0, or only bit 1 for UART 1 // + // LCR bit 7=0 divisor latch (clock division registers DLH & DLL, they store 16 bit divisor), + // WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE + // MCR bit 7=0 clock divisor devide-by-1 clock input + // DLH most significant part of divisor + // DLL least significant part of divisor + // + // BAUD_RATE, WORD_LEN, STOP_BIT, PARITY_ENA and PARITY_TYPE have been defined and initialized + // + void Init_SC16IS752(){ // Return value is in _deviceState + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: Initialize I2C: %s , UART Ch: 0x%x"), _I2CAddress.toString(), _UART_CH); + #endif + //uint16_t _divisor = (SC16IS752_XTAL_FREQ / PRESCALER) / (BAUD_RATE * 16); + uint16_t _divisor = (_sc16is752_xtal_freq/PRESCALER)/(BAUD_RATE * 16); // Calculate _divisor for baudrate + TEMP_REG_VAL = 0x08; // UART Software reset + UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL); + TEMP_REG_VAL = 0x00; // Set pins to GPIO mode + UART_WriteRegister(REG_IOCONTROL, TEMP_REG_VAL); + TEMP_REG_VAL = 0xFF; //Set all pins as output + UART_WriteRegister(REG_IODIR, TEMP_REG_VAL); + UART_ReadRegister(REG_IOSTATE); // Read current state as not to overwrite the other GPIO pins + TEMP_REG_VAL = _inbuffer[0]; + setGPIO(); // Set the audio mixer channel + /* + if (_UART_CH == 0){ // Set Audio mixer channel + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + */ + TEMP_REG_VAL = 0x07; // Reset FIFO, clear RX & TX FIFO + UART_WriteRegister(REG_FCR, TEMP_REG_VAL); + TEMP_REG_VAL = 0x00; // Set MCR to all 0, includes Clock divisor + UART_WriteRegister(REG_MCR, TEMP_REG_VAL); + TEMP_REG_VAL = 0x80 | WORD_LEN | STOP_BIT | PARITY_ENA | PARITY_TYPE; + UART_WriteRegister(REG_LCR, TEMP_REG_VAL); // Divisor latch enabled + UART_WriteRegister(REG_DLL, (uint8_t)_divisor); // Write DLL + UART_WriteRegister(REG_DLH, (uint8_t)(_divisor >> 8)); // Write DLH + UART_ReadRegister(REG_LCR); + TEMP_REG_VAL = _inbuffer[0] & 0x7F; // Disable Divisor latch enabled bit + UART_WriteRegister(REG_LCR, TEMP_REG_VAL); // Divisor latch disabled + + uint8_t status = _rb.status; + if (status != I2C_STATUS_OK) { + DIAG(F("SC16IS752: I2C: %s failed %S"), _I2CAddress.toString(), I2CManager.getErrorMessage(status)); + _deviceState = DEVSTATE_FAILED; + } else { + #ifdef DIAG_IO + DIAG(F("SC16IS752: I2C: %s, _deviceState: %S"), _I2CAddress.toString(), I2CManager.getErrorMessage(status)); + #endif + _deviceState = DEVSTATE_NORMAL; // If I2C state is OK, then proceed to initialize DFPlayer + } + } + + + // Read the Receive FIFO Level register (RXLVL), return a single unsigned integer + // of nr of characters in the RX FIFO, bit 6:0, 7 not used, set to zero + // value from 0 (0x00) to 64 (0x40) Only display if RX FIFO has data + // The RX fifo level is used to check if there are enough bytes to process a frame + void RX_fifo_lvl(){ + UART_ReadRegister(REG_RXLV); + FIFO_RX_LEVEL = _inbuffer[0]; + #ifdef DIAG_I2CDFplayer + if (FIFO_RX_LEVEL > 0){ + //if (FIFO_RX_LEVEL > 0 && FIFO_RX_LEVEL < 10){ + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, FIFO_RX_LEVEL: 0d%d"), _I2CAddress.toString(), _UART_CH, _inbuffer[0]); + } + #endif + } + + // When a frame is transmitted from the DFPlayer to the serial port, and at the same time the CS is sending a 42 query + // the following two frames from the DFPlayer are corrupt. This result in the receive buffer being out of sync and the + // CS will complain and generate a timeout. + // The RX fifo has corrupt data and need to be flushed, this function does that + // + void resetRX_fifo(){ + #ifdef DIAG_I2CDFplayer + DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, RX fifo reset"), _I2CAddress.toString(), _UART_CH); + #endif + TEMP_REG_VAL = 0x03; // Reset RX fifo + UART_WriteRegister(REG_FCR, TEMP_REG_VAL); + } + + // Set or reset GPIO pin 0 and 1 depending on the UART ch + // This function may be modified in a future release to enable all 8 pins to be set or reset with EX-Rail + // for various auxilary functions + void setGPIO(){ + UART_ReadRegister(REG_IOSTATE); // Get the current GPIO pins state from the IOSTATE register + TEMP_REG_VAL = _inbuffer[0]; + if (_audioMixer == 1){ // set to audio mixer 1 + if (_UART_CH == 0){ + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 0 to high + } else { // must be UART 1 + TEMP_REG_VAL |= (0x01 << _UART_CH); //Set GPIO pin 1 to high + } + } else { // set to audio mixer 2 + if (_UART_CH == 0){ + TEMP_REG_VAL &= ~(0x01 << _UART_CH); //Set GPIO pin 0 to Low + } else { // must be UART 1 + TEMP_REG_VAL &= ~(0x01 << _UART_CH); //Set GPIO pin 1 to Low + } + } + UART_WriteRegister(REG_IOSTATE, TEMP_REG_VAL); + _setamCmd = false; + } + + + // Read the Tranmit FIFO Level register (TXLVL), return a single unsigned integer + // of nr characters free in the TX FIFO, bit 6:0, 7 not used, set to zero + // value from 0 (0x00) to 64 (0x40) + // + void TX_fifo_lvl(){ + UART_ReadRegister(REG_TXLV); + FIFO_TX_LEVEL = _inbuffer[0]; + #ifdef DIAG_I2CDFplayer + // DIAG(F("SC16IS752: At I2C: %s, UART channel: 0x%x, FIFO_TX_LEVEL: 0d%d"), _I2CAddress.toString(), _UART_CH, FIFO_TX_LEVEL); + #endif + } + + + //void UART_WriteRegister(I2CAddress _I2CAddress, uint8_t _UART_CH, uint8_t UART_REG, uint8_t Val, I2CRB &_rb){ + void UART_WriteRegister(uint8_t UART_REG, uint8_t Val){ + _outbuffer[0] = UART_REG << 3 | _UART_CH << 1; + _outbuffer[1] = Val; + #ifdef DIAG_I2CDFplayer_reg + DIAG(F("SC16IS752: Write register at I2C: %s, UART channel: 0x%x, Register: 0x%x, Data: 0b%b"), _I2CAddress.toString(), _UART_CH, UART_REG, _outbuffer[1]); + #endif + I2CManager.write(_I2CAddress, _outbuffer, 2); + } + + + void UART_ReadRegister(uint8_t UART_REG){ + _outbuffer[0] = UART_REG << 3 | _UART_CH << 1; // _outbuffer[0] has now UART_REG and UART_CH + I2CManager.read(_I2CAddress, _inbuffer, 1, _outbuffer, 1); + // _inbuffer has the REG data + #ifdef DIAG_I2CDFplayer_reg + DIAG(F("SC16IS752: Read register at I2C: %s, UART channel: 0x%x, Register: 0x%x, Data: 0b%b"), _I2CAddress.toString(), _UART_CH, UART_REG, _inbuffer[0]); + #endif + } + +// SC16IS752 General register set (from the datasheet) +enum : uint8_t{ + REG_RHR = 0x00, // FIFO Read + REG_THR = 0x00, // FIFO Write + REG_IER = 0x01, // Interrupt Enable Register R/W + REG_FCR = 0x02, // FIFO Control Register Write + REG_IIR = 0x02, // Interrupt Identification Register Read + REG_LCR = 0x03, // Line Control Register R/W + REG_MCR = 0x04, // Modem Control Register R/W + REG_LSR = 0x05, // Line Status Register Read + REG_MSR = 0x06, // Modem Status Register Read + REG_SPR = 0x07, // Scratchpad Register R/W + REG_TCR = 0x06, // Transmission Control Register R/W + REG_TLR = 0x07, // Trigger Level Register R/W + REG_TXLV = 0x08, // Transmitter FIFO Level register Read + REG_RXLV = 0x09, // Receiver FIFO Level register Read + REG_IODIR = 0x0A, // Programmable I/O pins Direction register R/W + REG_IOSTATE = 0x0B, // Programmable I/O pins State register R/W + REG_IOINTENA = 0x0C, // I/O Interrupt Enable register R/W + REG_IOCONTROL = 0x0E, // I/O Control register R/W + REG_EFCR = 0x0F, // Extra Features Control Register R/W + }; + +// SC16IS752 Special register set +enum : uint8_t{ + REG_DLL = 0x00, // Division registers R/W + REG_DLH = 0x01, // Division registers R/W + }; + +// SC16IS752 Enhanced regiter set +enum : uint8_t{ + REG_EFR = 0X02, // Enhanced Features Register R/W + REG_XON1 = 0x04, // R/W + REG_XON2 = 0x05, // R/W + REG_XOFF1 = 0x06, // R/W + REG_XOFF2 = 0x07, // R/W + }; + +// DFPlayer commands and values +enum : uint8_t{ + PLAY = 0x0F, + VOL = 0x06, + FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + REPEATPLAY = 0x08, + STOPPLAY = 0x16, + EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + RESET = 0x0C, + DACON = 0x1A, + SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + NORMAL = 0x00, // Equalizer parameters + POP = 0x01, + ROCK = 0x02, + JAZZ = 0x03, + CLASSIC = 0x04, + BASS = 0x05, + }; + +}; + +#endif // IO_I2CDFPlayer_h diff --git a/version.h b/version.h index e94303f..d44166a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.28" +#define VERSION "5.2.29" +// 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) +// - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h +// - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h +// - Added UART detection to I2CManager.cpp // 5.2.28 - ESP32: Can all Wifi channels. // - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation From 7cbf4de1b977c2e0aea65a32da3a53dc5a2c0781 Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:25:41 +0000 Subject: [PATCH 220/310] Update myHal.cpp_example.txt Update with instructions for IO_ I2CDFPlayer --- myHal.cpp_example.txt | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index 5533554..8f97290 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -25,6 +25,7 @@ //#include "IO_EXTurntable.h" // Turntable-EX turntable controller //#include "IO_EXFastClock.h" // FastClock driver //#include "IO_PCA9555.h" // 16-bit I/O expander (NXP & Texas Instruments). +//#include "IO_I2CDFPlayer.h" // DFPlayer over I2C //========================================================================== // The function halSetup() is invoked from CS if it exists within the build. @@ -234,6 +235,33 @@ void halSetup() { // DFPlayer::create(10000, 10, Serial1); + //======================================================================= + // Play mp3 files from a Micro-SD card, using a DFPlayer MP3 Module on a SC16IS750/SC16IS752 I2C UART + //======================================================================= + // DFPlayer via NXP SC16IS752 I2C Dual UART. Each device has 2 UARTs on a single I2C address + // Total nr of devices on an I2C bus is 16, with 2 UARTs on each address making a total of 32 UARTs per I2C bus + // I2C address range 0x48 - 0x57 + // + // audioMixer can be 1 when connected to audio mixer 1, 2 when connected to audio mixer 2, 0 will default to 1 + // Generic format: + // I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); + // Parameters: + // 1st vPin : First virtual pin that EX-Rail can control to play a sound, use PLAYSOUND command (alias of ANOUT) + // vPins : Total number of virtual pins allocated (1 vPin is supported currently) + // 1st vPin for UART 0 + // I2C Address : I2C address of the serial controller, in 0x format + // xtal : 0 for 1.8432Mhz, 1 for 14.7456Mhz + // + // The vPin is also a pin that can be read with the WAITFOR(vPin) command indicating if the DFPlayer has finished playing a track + // + + // I2CDFPlayer::create(10000, 1, 0x48, 1); + // + // Configuration example on a multiplexer + // I2CDFPlayer::create(10000, 1, {I2CMux_0, SubBus_0, 0x48}, 1); + + + //======================================================================= // 16-pad capacitative touch key pad based on TP229 IC. //======================================================================= From 63702ae64e1d1c9bb3ae0ccab3648edfc51c54ce Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sat, 3 Feb 2024 19:27:58 +0000 Subject: [PATCH 221/310] Update fro myHal.cpp_example.txt Noticed some ommissions, corrected now --- myHal.cpp_example.txt | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index 8f97290..9073430 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -238,11 +238,9 @@ void halSetup() { //======================================================================= // Play mp3 files from a Micro-SD card, using a DFPlayer MP3 Module on a SC16IS750/SC16IS752 I2C UART //======================================================================= - // DFPlayer via NXP SC16IS752 I2C Dual UART. Each device has 2 UARTs on a single I2C address - // Total nr of devices on an I2C bus is 16, with 2 UARTs on each address making a total of 32 UARTs per I2C bus + // DFPlayer via NXP SC16IS752 I2C Dual UART. // I2C address range 0x48 - 0x57 // - // audioMixer can be 1 when connected to audio mixer 1, 2 when connected to audio mixer 2, 0 will default to 1 // Generic format: // I2CDFPlayer::create(1st vPin, vPins, I2C address, xtal); // Parameters: From e7f82bdf9269245e80e31cdbb4342440a9c4bf7f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 12:44:16 +0100 Subject: [PATCH 222/310] WiThrottle sendIntro after initial N message as well --- WiThrottle.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/WiThrottle.cpp b/WiThrottle.cpp index 244dfd8..018ab2b 100644 --- a/WiThrottle.cpp +++ b/WiThrottle.cpp @@ -187,6 +187,7 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) { } break; case 'N': // Heartbeat (2), only send if connection completed by 'HU' message + sendIntro(stream); StringFormatter::send(stream, F("*%d\n"), heartrateSent ? HEARTBEAT_SECONDS : HEARTBEAT_PRELOAD); // return timeout value break; case 'M': // multithrottle @@ -194,7 +195,7 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) { break; case 'H': // send initial connection info after receiving "HU" message if (cmd[1] == 'U') { - sendIntro(stream); + sendIntro(stream); } break; case 'Q': // @@ -498,12 +499,14 @@ void WiThrottle::getLocoCallback(int16_t locoid) { } void WiThrottle::sendIntro(Print* stream) { + if (introSent) // sendIntro only once + return; introSent=true; StringFormatter::send(stream,F("VN2.0\nHTDCC-EX\nRL0\n")); - StringFormatter::send(stream,F("HtDCC-EX v%S, %S, %S, %S\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); - StringFormatter::send(stream,F("PTT]\\[Turnouts}|{Turnout]\\[THROW}|{2]\\[CLOSE}|{4\n")); - StringFormatter::send(stream,F("PPA%x\n"),TrackManager::getMainPower()==POWERMODE::ON); - // set heartbeat to 2 seconds because we need to sync the metadata (1 second is too short!) + StringFormatter::send(stream,F("HtDCC-EX v%S, %S, %S, %S\n"), F(VERSION), F(ARDUINO_TYPE), DCC::getMotorShieldName(), F(GITHUB_SHA)); + StringFormatter::send(stream,F("PTT]\\[Turnouts}|{Turnout]\\[THROW}|{2]\\[CLOSE}|{4\n")); + StringFormatter::send(stream,F("PPA%x\n"),TrackManager::getMainPower()==POWERMODE::ON); + // set heartbeat to 2 seconds because we need to sync the metadata (1 second is too short!) StringFormatter::send(stream,F("*%d\nHMConnecting..\n"), HEARTBEAT_PRELOAD); } From be40a7e274cd7eb907ca2fd75e26f2c707f885fd Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 12:51:41 +0100 Subject: [PATCH 223/310] version 5.2.30 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 8aa2bd8..56992fe 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202401212011Z" +#define GITHUB_SHA "devel-202402041151Z" diff --git a/version.h b/version.h index d44166a..c443179 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.29" +#define VERSION "5.2.30" +// 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h // - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h From 5f6e18e1e78620ea77a9b3bfe9e1d9dc740a5b8d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 4 Feb 2024 13:50:07 +0100 Subject: [PATCH 224/310] remove mega328 from default build env list --- platformio.ini | 1 - 1 file changed, 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 8767ef1..2630e6d 100644 --- a/platformio.ini +++ b/platformio.ini @@ -12,7 +12,6 @@ default_envs = mega2560 uno - mega328 unowifiR2 nano samd21-dev-usb From 4780ea63cf48ca544e3d9bfd3c285ee283aca5fc Mon Sep 17 00:00:00 2001 From: kempe63 <78020007+kempe63@users.noreply.github.com> Date: Sun, 4 Feb 2024 18:57:30 +0000 Subject: [PATCH 225/310] Prepend I2CDFPlayer with DF_ to solve Nucleo RESET directive Prepend all I2CDFPlayer EXRail commands with DF_ to solve a Nucleo defined RESET --- EXRAIL2.h | 30 +++++++++++++------------- IO_I2CDFPlayer.h | 56 +++++++++++++++++++++++++----------------------- 2 files changed, 44 insertions(+), 42 deletions(-) diff --git a/EXRAIL2.h b/EXRAIL2.h index 6652526..ccfbbe6 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -260,21 +260,21 @@ private: // IO_I2CDFPlayer commands and values enum : uint8_t{ - PLAY = 0x0F, - VOL = 0x06, - FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is - REPEATPLAY = 0x08, - STOPPLAY = 0x16, - EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS - RESET = 0x0C, - DACON = 0x1A, - SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer (future use) - NORMAL = 0x00, // Equalizer parameters - POP = 0x01, - ROCK = 0x02, - JAZZ = 0x03, - CLASSIC = 0x04, - BASS = 0x05, + DF_PLAY = 0x0F, + DF_VOL = 0x06, + DF_FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + DF_REPEATPLAY = 0x08, + DF_STOPPLAY = 0x16, + DF_EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + DF_RESET = 0x0C, + DF_DACON = 0x1A, + DF_SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + DF_NORMAL = 0x00, // Equalizer parameters + DF_POP = 0x01, + DF_ROCK = 0x02, + DF_JAZZ = 0x03, + DF_CLASSIC = 0x04, + DF_BASS = 0x05, }; #endif diff --git a/IO_I2CDFPlayer.h b/IO_I2CDFPlayer.h index 79fa16b..c291b56 100644 --- a/IO_I2CDFPlayer.h +++ b/IO_I2CDFPlayer.h @@ -101,8 +101,8 @@ private: bool _stopplayCmd = false; bool _resetCmd = false; bool _eqCmd = false; - uint8_t _requestedEQValue = NORMAL; - uint8_t _currentEQvalue = NORMAL; // start equalizer value + uint8_t _requestedEQValue = DF_NORMAL; + uint8_t _currentEQvalue = DF_NORMAL; // start equalizer value bool _daconCmd = false; uint8_t _audioMixer = 0x01; // Default to output amplifier 1 bool _setamCmd = false; // Set the Audio mixer channel @@ -434,18 +434,18 @@ public: //case NONE: // DFPlayerCmd = cmd; // break; - case PLAY: + case DF_PLAY: _playCmd = true; _volCmd = true; _requestedSong = value; _requestedVolumeLevel = volume; _playing = true; break; - case VOL: + case DF_VOL: _volCmd = true; _requestedVolumeLevel = volume; break; - case FOLDER: + case DF_FOLDER: _folderCmd = true; if (volume <= 0 || volume > 99){ // Range checking, valid values 1-99, else default to 1 _requestedFolder = 0x01; // if outside range, default to folder 01 @@ -453,7 +453,7 @@ public: _requestedFolder = volume; } break; - case REPEATPLAY: // Need to check if _repeat == true, if so do nothing + case DF_REPEATPLAY: // Need to check if _repeat == true, if so do nothing if (_repeat == false) { #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WriteAnalog Repeat: _repeat: 0x0%x, value: %d _repeatCmd: 0x%x"), _repeat, value, _repeatCmd); @@ -464,30 +464,30 @@ public: _playing = true; } break; - case STOPPLAY: + case DF_STOPPLAY: _stopplayCmd = true; break; - case EQ: + case DF_EQ: #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WriteAnalog EQ: cmd: 0x%x, EQ value: 0x%x"), cmd, volume); #endif _eqCmd = true; if (volume <= 0 || volume > 5) { // If out of range, default to NORMAL - _requestedEQValue = NORMAL; + _requestedEQValue = DF_NORMAL; } else { // Valid EQ parameter range _requestedEQValue = volume; } break; - case RESET: + case DF_RESET: _resetCmd = true; break; - case DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on + case DF_DACON: // Works, but without the DACOFF command limited value, except when not relying on DFPlayer default to turn the DAC on #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WrtieAnalog DACON: cmd: 0x%x"), cmd); #endif _daconCmd = true; break; - case SETAM: // Set the audio mixer channel to 1 or 2 + case DF_SETAM: // Set the audio mixer channel to 1 or 2 _setamCmd = true; #ifdef DIAG_I2CDFplayer_playing DIAG(F("I2CDFPlayer: WrtieAnalog SETAM: cmd: 0x%x"), cmd); @@ -779,23 +779,25 @@ enum : uint8_t{ REG_XOFF2 = 0x07, // R/W }; + // DFPlayer commands and values +// Declared in this scope enum : uint8_t{ - PLAY = 0x0F, - VOL = 0x06, - FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is - REPEATPLAY = 0x08, - STOPPLAY = 0x16, - EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS - RESET = 0x0C, - DACON = 0x1A, - SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer - NORMAL = 0x00, // Equalizer parameters - POP = 0x01, - ROCK = 0x02, - JAZZ = 0x03, - CLASSIC = 0x04, - BASS = 0x05, + DF_PLAY = 0x0F, + DF_VOL = 0x06, + DF_FOLDER = 0x2B, // Not a DFPlayer command, used to set folder nr where audio file is + DF_REPEATPLAY = 0x08, + DF_STOPPLAY = 0x16, + DF_EQ = 0x07, // Set equaliser, require parameter NORMAL, POP, ROCK, JAZZ, CLASSIC or BASS + DF_RESET = 0x0C, + DF_DACON = 0x1A, + DF_SETAM = 0x2A, // Set audio mixer 1 or 2 for this DFPLayer + DF_NORMAL = 0x00, // Equalizer parameters + DF_POP = 0x01, + DF_ROCK = 0x02, + DF_JAZZ = 0x03, + DF_CLASSIC = 0x04, + DF_BASS = 0x05, }; }; From 4931c5ed75af7466d205c3e8fe5e07cdadfa390f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 5 Feb 2024 09:28:07 +0100 Subject: [PATCH 226/310] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 56992fe..956a8d2 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402041151Z" +#define GITHUB_SHA "devel-202402050827Z" From cd47782052aaae9ae378aa3d9f32c86bc36c182f Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 6 Feb 2024 20:03:52 +0000 Subject: [PATCH 227/310] reasonable start --- DCCEXParser.cpp | 8 +++++++- DCCTimer.h | 2 ++ DCCTimerAVR.cpp | 50 ++++++++++++++++++++++++++++++++++++++++++++++++ DCCWaveform.cpp | 27 ++++++++++++++++++++++---- DCCWaveform.h | 13 ++++++++++++- MotorDriver.cpp | 2 +- TrackManager.cpp | 5 ++--- 7 files changed, 97 insertions(+), 10 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 16f4494..3f61f7b 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,7 +1035,13 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; - + case "RAILCOM"_hk: + { + bool onOff = (params > 1) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off + DIAG(F("Railcom %S") + ,DCCWaveform::setRailcom(onOff)?F("ON"):F("OFF")); + return true; + } #ifndef DISABLE_PROG case "ACK"_hk: // if (params >= 3) { diff --git a/DCCTimer.h b/DCCTimer.h index 3b14fd6..11e1c7f 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -62,6 +62,8 @@ class DCCTimer { static bool isPWMPin(byte pin); static void setPWM(byte pin, bool high); static void clearPWM(); + static void startRailcomTimer(byte brakePin); + static void ackRailcomTimer(); static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency); static void DCCEXanalogWrite(uint8_t pin, int value); diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 3e6c436..ea601df 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -39,6 +39,9 @@ INTERRUPT_CALLBACK interruptHandler=0; #define TIMER1_A_PIN 11 #define TIMER1_B_PIN 12 #define TIMER1_C_PIN 13 + #define TIMER2_A_PIN 10 + #define TIMER2_B_PIN 9 + #else #define TIMER1_A_PIN 9 #define TIMER1_B_PIN 10 @@ -55,6 +58,53 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } + +void DCCTimer::startRailcomTimer(byte brakePin) { + /* The Railcom timer is started in such a way that it + - First triggers 28uS after the last TIMER1 tick. + This provides an accurate offset (in High Accuracy mode) + for the start of the Railcom cutout. + - Sets the Railcom pin high at first tick, + because its been setup with 100% PWM duty cycle. + + - Cycles at 436uS so the second tick is the + correct distance from the cutout. + + - Waveform code is responsible for altering the PWM + duty cycle to 0% any time between the first and last tick. + (there will be 7 DCC timer1 ticks in which to do this.) + + */ + const int cutoutDuration = 436; // Desired interval in microseconds + + // Set up Timer2 for CTC mode (Clear Timer on Compare Match) + TCCR2A = 0; // Clear Timer2 control register A + TCCR2B = 0; // Clear Timer2 control register B + TCNT2 = 0; // Initialize Timer2 counter value to 0 + // Configure Phase and Frequency Correct PWM mode +//TCCR2A = (1 << COM2B1) | (1 << WGM20) | (1 << WGM21); + + // Set Fast PWM mode with non-inverted output on OC2B (pin 9) + TCCR2A = (1 << WGM21) | (1 << WGM20) | (1 << COM2B1); + // Set Timer 2 prescaler to 32 + TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler + + // Set the compare match value for desired interval + OCR2A = (F_CPU / 1000000) * cutoutDuration / 32 - 1; + + // Calculate the compare match value for desired duty cycle + OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A) + + // Enable Timer2 output on pin 9 (OC2B) + DDRB |= (1 << DDB1); + // TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS +} + +void DCCTimer::ackRailcomTimer() { + OCR2B= 0x00; // brfake pin pwm duty cycle 0 at next tick +} + + // ISR called by timer interrupt every 58uS ISR(TIMER1_OVF_vect){ interruptHandler(); } diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 93b21a2..707f8f4 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -115,8 +115,19 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { bytes_sent = 0; bits_sent = 0; } + +volatile bool DCCWaveform::railcomActive=false; // switched on by user - +bool DCCWaveform::setRailcom(bool on) { + if (on) { + // TODO check possible + railcomActive=true; + } + else { + railcomActive=false; + } + return railcomActive; +} #pragma GCC push_options #pragma GCC optimize ("-O3") @@ -124,16 +135,16 @@ void DCCWaveform::interrupt2() { // calculate the next bit to be sent: // set state WAVE_MID_1 for a 1=bit // or WAVE_HIGH_0 for a 0 bit. - if (remainingPreambles > 0 ) { state=WAVE_MID_1; // switch state to trigger LOW on next interrupt remainingPreambles--; - + // As we get to the end of the preambles, open the reminder window. // This delays any reminder insertion until the last moment so // that the reminder doesn't block a more urgent packet. reminderWindowOpen=transmitRepeats==0 && remainingPreambles<4 && remainingPreambles>1; if (remainingPreambles==1) promotePendingPacket(); + else if (remainingPreambles==10 && isMainTrack && railcomActive) DCCTimer::ackRailcomTimer(); // Update free memory diagnostic as we don't have anything else to do this time. // Allow for checkAck and its called functions using 22 bytes more. else DCCTimer::updateMinimumFreeMemoryISR(22); @@ -157,6 +168,12 @@ void DCCWaveform::interrupt2() { bytes_sent = 0; // preamble for next packet will start... remainingPreambles = requiredPreambles; + + // set the railcom coundown to trigger half way + // through the first preamble bit. + // Note.. we are still sending the last packet bit + // and we then have to allow for the packet end bit + if (isMainTrack && railcomActive) DCCTimer::startRailcomTimer(9); } } } @@ -208,7 +225,9 @@ void DCCWaveform::promotePendingPacket() { // nothing to do, just send idles or resets // Fortunately reset and idle packets are the same length - memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); + // TEMPORARY DEBUG FOR RAILCOM + // memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); + memcpy( transmitPacket, resetPacket, sizeof(idlePacket)); transmitLength = sizeof(idlePacket); transmitRepeats = 0; if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) diff --git a/DCCWaveform.h b/DCCWaveform.h index 1392288..3f6de18 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -40,7 +40,14 @@ const byte MAX_PACKET_SIZE = 5; // NMRA standard extended packets, payload s // The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic // to the transform array. -enum WAVE_STATE : byte {WAVE_START=0,WAVE_MID_1=1,WAVE_HIGH_0=2,WAVE_MID_0=3,WAVE_LOW_0=4,WAVE_PENDING=5}; +enum WAVE_STATE : byte { + WAVE_START=0, // wave going high at start of bit + WAVE_MID_1=1, // middle of 1 bit + WAVE_HIGH_0=2, // first part of 0 bit high + WAVE_MID_0=3, // middle of 0 bit + WAVE_LOW_0=4, // first part of 0 bit low + WAVE_PENDING=5 // next bit not yet known + }; // NOTE: static functions are used for the overall controller, then // one instance is created for each track. @@ -78,6 +85,8 @@ class DCCWaveform { void schedulePacket(const byte buffer[], byte byteCount, byte repeats); bool isReminderWindowOpen(); void promotePendingPacket(); + static bool setRailcom(bool on); + static bool isRailcom() {return railcomActive;} private: #ifndef ARDUINO_ARCH_ESP32 @@ -103,6 +112,8 @@ class DCCWaveform { byte pendingPacket[MAX_PACKET_SIZE+1]; // +1 for checksum byte pendingLength; byte pendingRepeats; + static volatile bool railcomActive; // switched on by user + #ifdef ARDUINO_ARCH_ESP32 static RMTChannel *rmtMainChannel; static RMTChannel *rmtProgChannel; diff --git a/MotorDriver.cpp b/MotorDriver.cpp index bd25be4..878beea 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -204,7 +204,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i } bool MotorDriver::isPWMCapable() { - return (!dualSignal) && DCCTimer::isPWMPin(signalPin); + return (!dualSignal) && DCCTimer::isPWMPin(signalPin); } diff --git a/TrackManager.cpp b/TrackManager.cpp index da96832..328f952 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -157,10 +157,9 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTF(PORTF=shadowPORTF); } +// Called by interrupt context void TrackManager::setCutout( bool on) { - (void) on; - // TODO Cutout needs fake ports as well - // TODO APPLY_BY_MODE(TRACK_MODE_MAIN,setCutout(on)); + APPLY_BY_MODE(TRACK_MODE_MAIN,setBrake(on,true)); } // setPROGSignal(), called from interrupt context From 1443ea8df95dcdead26dd9060424ce58ba7f6888 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 19:50:08 +0000 Subject: [PATCH 228/310] Its alive! --- DCCTimerAVR.cpp | 25 +++++++++++++++++++------ 1 file changed, 19 insertions(+), 6 deletions(-) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index ea601df..66b51ba 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -75,22 +75,22 @@ void DCCTimer::startRailcomTimer(byte brakePin) { (there will be 7 DCC timer1 ticks in which to do this.) */ - const int cutoutDuration = 436; // Desired interval in microseconds + const int cutoutDuration = 430; // Desired interval in microseconds // Set up Timer2 for CTC mode (Clear Timer on Compare Match) TCCR2A = 0; // Clear Timer2 control register A TCCR2B = 0; // Clear Timer2 control register B TCNT2 = 0; // Initialize Timer2 counter value to 0 // Configure Phase and Frequency Correct PWM mode -//TCCR2A = (1 << COM2B1) | (1 << WGM20) | (1 << WGM21); + TCCR2A = (1 << COM2B1); // enable pwm on pin 9 + TCCR2A |= (1 << WGM20); - // Set Fast PWM mode with non-inverted output on OC2B (pin 9) - TCCR2A = (1 << WGM21) | (1 << WGM20) | (1 << COM2B1); + // Set Timer 2 prescaler to 32 TCCR2B = (1 << CS21) | (1 << CS20); // 32 prescaler // Set the compare match value for desired interval - OCR2A = (F_CPU / 1000000) * cutoutDuration / 32 - 1; + OCR2A = (F_CPU / 1000000) * cutoutDuration / 64 - 1; // Calculate the compare match value for desired duty cycle OCR2B = OCR2A+1; // set duty cycle to 100%= OCR2A) @@ -98,10 +98,23 @@ void DCCTimer::startRailcomTimer(byte brakePin) { // Enable Timer2 output on pin 9 (OC2B) DDRB |= (1 << DDB1); // TODO Fudge TCNT2 to sync with last tcnt1 tick + 28uS + + // Previous TIMER1 Tick was at rising end-of-packet bit + // Cutout starts half way through first preamble + // that is 2.5 * 58uS later. + // TCNT1 ticks 8 times / microsecond + // auto microsendsToFirstRailcomTick=(58+58+29)-(TCNT1/8); + // set the railcom timer counter allowing for phase-correct + + // CHris's NOTE: + // I dont kniow quite how this calculation works out but + // it does seems to get a good answer. + + TCNT2=193 + (ICR1 - TCNT1)/8; } void DCCTimer::ackRailcomTimer() { - OCR2B= 0x00; // brfake pin pwm duty cycle 0 at next tick + OCR2B= 0x00; // brake pin pwm duty cycle 0 at next tick } From 7a9e225602247a5f6a433f8b1c88976bcca0d0e0 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 21:24:48 +0000 Subject: [PATCH 229/310] fill in debug and unsupported drivers --- DCCEXParser.cpp | 23 ++++++++++++++++++++--- DCCTimerMEGAAVR.cpp | 8 ++++++++ DCCTimerSAMD.cpp | 8 ++++++++ DCCTimerSTM32.cpp | 8 ++++++++ DCCTimerTEENSY.cpp | 8 ++++++++ DCCWaveform.cpp | 19 +++++++++++++++---- DCCWaveform.h | 3 ++- 7 files changed, 69 insertions(+), 8 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 3f61f7b..5b335d2 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1036,10 +1036,27 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DIAG(F("128 Speedsteps")); return true; case "RAILCOM"_hk: - { - bool onOff = (params > 1) && (p[1] == 1 || p[1] == "ON"_hk); // dont care if other stuff or missing... just means off + { // + if (params<2) return false; + bool on=false; + bool debug=false; + switch (p[1]) { + case "ON"_hk: + case 1: + on=true; + break; + case "DEBUG"_hk: + on=true; + debug=true; + break; + case "OFF"_hk: + case 0: + break; + default: + return false; + } DIAG(F("Railcom %S") - ,DCCWaveform::setRailcom(onOff)?F("ON"):F("OFF")); + ,DCCWaveform::setRailcom(on,debug)?F("ON"):F("OFF")); return true; } #ifndef DISABLE_PROG diff --git a/DCCTimerMEGAAVR.cpp b/DCCTimerMEGAAVR.cpp index 2b2bdab..19eb409 100644 --- a/DCCTimerMEGAAVR.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -80,6 +80,14 @@ extern char *__malloc_heap_start; interruptHandler(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { (void) pin; return false; // TODO what are the relevant pins? diff --git a/DCCTimerSAMD.cpp b/DCCTimerSAMD.cpp index f878ae5..a0b4da5 100644 --- a/DCCTimerSAMD.cpp +++ b/DCCTimerSAMD.cpp @@ -76,6 +76,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + // Timer IRQ handlers replace the dummy handlers (in cortex_handlers) // copied from rf24 branch void TCC0_Handler() { diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index f24adc2..eb7e1ca 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -201,6 +201,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { interrupts(); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { //TODO: STM32 whilst this call to digitalPinHasPWM will reveal which pins can do PWM, // there's no support yet for High Accuracy, so for now return false diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp index 0619e21..1230180 100644 --- a/DCCTimerTEENSY.cpp +++ b/DCCTimerTEENSY.cpp @@ -39,6 +39,14 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { myDCCTimer.begin(interruptHandler, DCC_SIGNAL_TIME); } +void DCCTimer::startRailcomTimer(byte brakePin) { + // TODO: for intended operation see DCCTimerAVR.cpp +} + +void DCCTimer::ackRailcomTimer() { + // TODO: for intended operation see DCCTimerAVR.cpp +} + bool DCCTimer::isPWMPin(byte pin) { //Teensy: digitalPinHasPWM, todo (void) pin; diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 707f8f4..2d50929 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -117,14 +117,17 @@ DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { } volatile bool DCCWaveform::railcomActive=false; // switched on by user +volatile bool DCCWaveform::railcomDebug=false; // switched on by user -bool DCCWaveform::setRailcom(bool on) { +bool DCCWaveform::setRailcom(bool on, bool debug) { if (on) { // TODO check possible railcomActive=true; + railcomDebug=debug; } else { railcomActive=false; + railcomDebug=false; } return railcomActive; } @@ -225,9 +228,11 @@ void DCCWaveform::promotePendingPacket() { // nothing to do, just send idles or resets // Fortunately reset and idle packets are the same length - // TEMPORARY DEBUG FOR RAILCOM - // memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket)); - memcpy( transmitPacket, resetPacket, sizeof(idlePacket)); + // Note: If railcomDebug is on, then we send resets to the main + // track instead of idles. This means that all data will be zeros + // and only the porersets will be ones, making it much + // easier to read on a logic analyser. + memcpy( transmitPacket, (isMainTrack && (!railcomDebug)) ? idlePacket : resetPacket, sizeof(idlePacket)); transmitLength = sizeof(idlePacket); transmitRepeats = 0; if (getResets() < 250) sentResetsSincePacket++; // only place to increment (private!) @@ -316,4 +321,10 @@ bool DCCWaveform::isReminderWindowOpen() { void IRAM_ATTR DCCWaveform::loop() { DCCACK::checkAck(progTrack.getResets()); } + +bool DCCWaveform::setRailcom(bool on, bool debug) { + // TODO... ESP32 railcom waveform + return false; +} + #endif diff --git a/DCCWaveform.h b/DCCWaveform.h index 3f6de18..a3e20da 100644 --- a/DCCWaveform.h +++ b/DCCWaveform.h @@ -85,7 +85,7 @@ class DCCWaveform { void schedulePacket(const byte buffer[], byte byteCount, byte repeats); bool isReminderWindowOpen(); void promotePendingPacket(); - static bool setRailcom(bool on); + static bool setRailcom(bool on, bool debug); static bool isRailcom() {return railcomActive;} private: @@ -113,6 +113,7 @@ class DCCWaveform { byte pendingLength; byte pendingRepeats; static volatile bool railcomActive; // switched on by user + static volatile bool railcomDebug; // switched on by user #ifdef ARDUINO_ARCH_ESP32 static RMTChannel *rmtMainChannel; From 25cb878060bd50f829a2788338355984e369ef54 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 21:33:06 +0000 Subject: [PATCH 230/310] remove dross --- TrackManager.cpp | 5 ----- TrackManager.h | 1 - version.h | 2 +- 3 files changed, 1 insertion(+), 7 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 328f952..ca309ed 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -157,11 +157,6 @@ void TrackManager::setDCCSignal( bool on) { HAVE_PORTF(PORTF=shadowPORTF); } -// Called by interrupt context -void TrackManager::setCutout( bool on) { - APPLY_BY_MODE(TRACK_MODE_MAIN,setBrake(on,true)); -} - // setPROGSignal(), called from interrupt context // does assume ports are shadowed if they can be void TrackManager::setPROGSignal( bool on) { diff --git a/TrackManager.h b/TrackManager.h index 6310030..c1f314a 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -57,7 +57,6 @@ class TrackManager { ); static void setDCCSignal( bool on); - static void setCutout( bool on); static void setPROGSignal( bool on); static void setDCSignal(int16_t cab, byte speedbyte); static MotorDriver * getProgDriver(); diff --git a/version.h b/version.h index e94303f..24bddc6 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,7 @@ #include "StringFormatter.h" -#define VERSION "5.2.28" +#define VERSION "5.2.28-Railcom" // 5.2.28 - ESP32: Can all Wifi channels. // - ESP32: Only write Wifi password to display if it is a well known one // 5.2.27 - Bugfix: IOExpander memory allocation From 8293749ac76199d9b0db6988872c49039f1a4ca8 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Wed, 7 Feb 2024 22:11:27 +0000 Subject: [PATCH 231/310] JMRI_SENSOR exrail --- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 3 +++ Sensors.cpp | 7 +++++++ Sensors.h | 1 + version.h | 3 ++- 5 files changed, 15 insertions(+), 1 deletion(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 3554f6c..f52b636 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -84,6 +84,7 @@ #undef IFTTPOSITION #undef IFRE #undef INVERT_DIRECTION +#undef JMRI_SENSOR #undef JOIN #undef KILLALL #undef LATCH @@ -236,6 +237,7 @@ #define IFTTPOSITION(turntable_id,position) #define IFRE(sensor_id,value) #define INVERT_DIRECTION +#define JMRI_SENSOR(vpin,count...) #define JOIN #define KILLALL #define LATCH(sensor_id) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 98af846..5873e38 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -149,6 +149,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #define HAL(haltype,params...) haltype::create(params); #undef HAL_IGNORE_DEFAULTS #define HAL_IGNORE_DEFAULTS ignore_defaults=true; +#undef JMRI_SENSOR +#define JMRI_SENSOR(vpin,count...) Sensor::createMultiple(vpin,##count); bool exrailHalSetup() { bool ignore_defaults=false; #include "myAutomation.h" @@ -487,6 +489,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #endif #define IFRE(sensor_id,value) OPCODE_IFRE,V(sensor_id),OPCODE_PAD,V(value), #define INVERT_DIRECTION OPCODE_INVERT_DIRECTION,0,0, +#define JMRI_SENSOR(vpin,count...) #define JOIN OPCODE_JOIN,0,0, #define KILLALL OPCODE_KILLALL,0,0, #define LATCH(sensor_id) OPCODE_LATCH,V(sensor_id), diff --git a/Sensors.cpp b/Sensors.cpp index d1c0fe5..efd969d 100644 --- a/Sensors.cpp +++ b/Sensors.cpp @@ -230,6 +230,13 @@ Sensor *Sensor::create(int snum, VPIN pin, int pullUp){ return tt; } +// Creet multiple eponymous sensors based on vpin alone. +void Sensor::createMultiple(VPIN firstPin, byte count) { + for (byte i=0;i types. // 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h From eacf48380b25a0c704bd05f6d2bf9b56ecd93c9e Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 10:15:23 +0000 Subject: [PATCH 232/310] typos in version comments --- version.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/version.h b/version.h index 0252f8a..3b02cf1 100644 --- a/version.h +++ b/version.h @@ -4,8 +4,8 @@ #include "StringFormatter.h" #define VERSION "5.2.31" -// 5.2.31 - Exrail JMRI_SENSORS(vpin [,count]) creates types. -// 5.2.40 - Bugfix: WiThrottle sendIntro after initial N message as well +// 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. +// 5.2.30 - Bugfix: WiThrottle sendIntro after initial N message as well // 5.2.29 - Added IO_I2CDFPlayer.h to support DFPLayer over I2C connected to NXP SC16IS750/SC16IS752 (currently only single UART for SC16IS752) // - Added enhanced IO_I2CDFPLayer enum commands to EXRAIL2.h // - Added PLAYSOUND alias of ANOUT to EXRAILMacros.h From 4b97d63cf3ae4320b73696eae0d11f4a41dc3454 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 10:37:51 +0000 Subject: [PATCH 233/310] Remove compiler warnings --- DCCTimerAVR.cpp | 1 + DCCTimerMEGAAVR.cpp | 1 + DCCTimerSAMD.cpp | 1 + DCCTimerSTM32.cpp | 1 + DCCTimerTEENSY.cpp | 1 + 5 files changed, 5 insertions(+) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 66b51ba..5310704 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -75,6 +75,7 @@ void DCCTimer::startRailcomTimer(byte brakePin) { (there will be 7 DCC timer1 ticks in which to do this.) */ + (void) brakePin; // Ignored... works on pin 9 only const int cutoutDuration = 430; // Desired interval in microseconds // Set up Timer2 for CTC mode (Clear Timer on Compare Match) diff --git a/DCCTimerMEGAAVR.cpp b/DCCTimerMEGAAVR.cpp index 19eb409..be9337b 100644 --- a/DCCTimerMEGAAVR.cpp +++ b/DCCTimerMEGAAVR.cpp @@ -82,6 +82,7 @@ extern char *__malloc_heap_start; void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerSAMD.cpp b/DCCTimerSAMD.cpp index a0b4da5..d281371 100644 --- a/DCCTimerSAMD.cpp +++ b/DCCTimerSAMD.cpp @@ -78,6 +78,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index eb7e1ca..e22758f 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -203,6 +203,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { diff --git a/DCCTimerTEENSY.cpp b/DCCTimerTEENSY.cpp index 1230180..d7bb29b 100644 --- a/DCCTimerTEENSY.cpp +++ b/DCCTimerTEENSY.cpp @@ -41,6 +41,7 @@ void DCCTimer::begin(INTERRUPT_CALLBACK callback) { void DCCTimer::startRailcomTimer(byte brakePin) { // TODO: for intended operation see DCCTimerAVR.cpp + (void) brakePin; } void DCCTimer::ackRailcomTimer() { From c780b968564eae454d2001d51b0988f2245b0e02 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 9 Feb 2024 11:54:53 +0000 Subject: [PATCH 234/310] Exrail CONFIGURE_SERVO --- EXRAIL2MacroReset.h | 4 +++- EXRAILMacros.h | 3 +++ version.h | 3 ++- 3 files changed, 8 insertions(+), 2 deletions(-) diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index f52b636..309c325 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -42,6 +42,7 @@ #undef CLEAR_STASH #undef CLEAR_ALL_STASH #undef CLOSE +#undef CONFIGURE_SERVO #undef DCC_SIGNAL #undef DCC_TURNTABLE #undef DEACTIVATE @@ -194,7 +195,8 @@ #define CALL(route) #define CLEAR_STASH(id) #define CLEAR_ALL_STASH(id) -#define CLOSE(id) +#define CLOSE(id) +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #define DCC_SIGNAL(id,add,subaddr) #define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 5873e38..3b579a3 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -151,6 +151,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #define HAL_IGNORE_DEFAULTS ignore_defaults=true; #undef JMRI_SENSOR #define JMRI_SENSOR(vpin,count...) Sensor::createMultiple(vpin,##count); +#undef CONFIGURE_SERVO +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) IODevice::configureServo(vpin,pos1,pos2,PCA9685::profile); bool exrailHalSetup() { bool ignore_defaults=false; #include "myAutomation.h" @@ -441,6 +443,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id), #define CLEAR_ALL_STASH OPCODE_CLEAR_ALL_STASH,V(0), #define CLOSE(id) OPCODE_CLOSE,V(id), +#define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #ifndef IO_NO_HAL #define DCC_TURNTABLE(id,home,description...) OPCODE_DCCTURNTABLE,V(id),OPCODE_PAD,V(home), #endif diff --git a/version.h b/version.h index c24efed..84eeedf 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.32" +#define VERSION "5.2.33" +// 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile) // 5.2.32 - Railcom Cutout (Initial trial Mega2560 only) // 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. // 5.2.30 - Bugfix: WiThrottle sendIntro after initial N message as well From 784088b0df9363a7f0c9a956f8f19c0963d0030b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 11 Feb 2024 23:19:51 +0100 Subject: [PATCH 235/310] get it into nano and uno again --- DCCEXParser.cpp | 2 ++ platformio.ini | 6 ++---- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 5b335d2..6deb34f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -1035,6 +1035,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { DCC::setGlobalSpeedsteps(128); DIAG(F("128 Speedsteps")); return true; +#if defined(HAS_ENOUGH_MEMORY) && !defined(ARDUINO_ARCH_UNO) case "RAILCOM"_hk: { // if (params<2) return false; @@ -1059,6 +1060,7 @@ bool DCCEXParser::parseC(Print *stream, int16_t params, int16_t p[]) { ,DCCWaveform::setRailcom(on,debug)?F("ON"):F("OFF")); return true; } +#endif #ifndef DISABLE_PROG case "ACK"_hk: // if (params >= 3) { diff --git a/platformio.ini b/platformio.ini index 2630e6d..a03ff61 100644 --- a/platformio.ini +++ b/platformio.ini @@ -148,10 +148,7 @@ build_flags = platform = atmelavr board = uno framework = arduino -lib_deps = - ${env.lib_deps} - arduino-libraries/Ethernet - SPI +lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes build_flags = -mcall-prologues @@ -164,6 +161,7 @@ framework = arduino lib_deps = ${env.lib_deps} monitor_speed = 115200 monitor_echo = yes +build_flags = -mcall-prologues [env:ESP32] platform = espressif32 From 59b0e8383d0509f784e9ba1108cd11142fa04b68 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 15 Feb 2024 19:51:52 +0000 Subject: [PATCH 236/310] --- DCC.cpp | 16 ++++++++++++++++ DCC.h | 1 + DCCEXParser.cpp | 9 +++++++++ 3 files changed, 26 insertions(+) diff --git a/DCC.cpp b/DCC.cpp index 0c5148a..ed2a803 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -278,6 +278,22 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) { } } +void DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { + + // format is 10AAAAAA, 0AAA0AA1, 000XXXXX + if (address != (address & 0x7F)) return; + if (value != (value & 0x1F)) return; + + byte b[3]; + b[0]= 0x80 | ((address & 0x7FF)>>5); + b[1]= 0x01 | ((address & 0x1c)<<2) | (address & 0x03)<<1; + b[2]=value & 0x1F; + DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times +#if defined(EXRAIL_ACTIVE) + // TODO RMFT2::activateExtendedEvent(address,value); +#endif +} + // // writeCVByteMain: Write a byte with PoM on main. This writes // the 5 byte sized packet to implement this DCC function diff --git a/DCC.h b/DCC.h index 3bf0cf5..e1aeae6 100644 --- a/DCC.h +++ b/DCC.h @@ -71,6 +71,7 @@ public: static uint32_t getFunctionMap(int cab); static void updateGroupflags(byte &flags, int16_t functionNumber); static void setAccessory(int address, byte port, bool gate, byte onoff = 2); + static void setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); static bool writeTextPacket(byte *b, int nBytes); // ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1 diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 6deb34f..a3aa1c4 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -384,6 +384,15 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) #endif } return; + + case 'A': // EXTENDED ACCESSORY + { + if (params!=2) break; + if (p[0] != (p[0] & 0x7F)) break; + if (p[1] != (p[1] & 0x1F)) break; + DCC::setExtendedAccessory(p[0],p[1],3); + } + return; case 'T': // TURNOUT if (parseT(stream, params, p)) From e4904e40802ca3f1a8e9a6b82d2f06cddd4f81e2 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 15 Feb 2024 20:05:27 +0000 Subject: [PATCH 237/310] Exrail ASPECT(addr,value) --- EXRAIL2.cpp | 5 +++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 4 ++++ 4 files changed, 12 insertions(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 8a2eadf..56aeeb2 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -800,6 +800,11 @@ void RMFT2::loop2() { DCC::setAccessory(addr,subaddr,active); break; } + case OPCODE_ASPECT: { + // operand is address<<5 | value + DCC::setExtendedAccessory(operand>>5, operand & 0x1F); + break; + } case OPCODE_FOLLOW: progCounter=routeLookup->find(operand); diff --git a/EXRAIL2.h b/EXRAIL2.h index ccfbbe6..e8235c6 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -54,7 +54,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_START,OPCODE_SETLOCO,OPCODE_SENDLOCO,OPCODE_FORGET, OPCODE_PAUSE, OPCODE_RESUME,OPCODE_POWEROFF,OPCODE_POWERON, OPCODE_ONCLOSE, OPCODE_ONTHROW, OPCODE_SERVOTURNOUT, OPCODE_PINTURNOUT, - OPCODE_PRINT,OPCODE_DCCACTIVATE, + OPCODE_PRINT,OPCODE_DCCACTIVATE,OPCODE_ASPECT, OPCODE_ONACTIVATE,OPCODE_ONDEACTIVATE, OPCODE_ROSTER,OPCODE_KILLALL, OPCODE_ROUTE,OPCODE_AUTOMATION,OPCODE_SEQUENCE, diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 309c325..633f4d5 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -31,6 +31,7 @@ #undef ALIAS #undef AMBER #undef ANOUT +#undef ASPECT #undef AT #undef ATGTE #undef ATLT @@ -186,6 +187,7 @@ #define AMBER(signal_id) #define ANOUT(vpin,value,param1,param2) #define AT(sensor_id) +#define ASPECT(address,value) #define ATGTE(sensor_id,value) #define ATLT(sensor_id,value) #define ATTIMEOUT(sensor_id,timeout_ms) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 3b579a3..8d870ef 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -117,6 +117,9 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU // - check range on LATCH/UNLATCH // This pass generates no runtime data or code #include "EXRAIL2MacroReset.h" +#undef ASPECT +#define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \ + static_assert((value & 0x1F)== value, "Invalid value"); #undef CALL #define CALL(id) static_assert(hasseq(id),"Sequence not found"); #undef FOLLOW @@ -432,6 +435,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ALIAS(name,value...) #define AMBER(signal_id) OPCODE_AMBER,V(signal_id), #define ANOUT(vpin,value,param1,param2) OPCODE_SERVO,V(vpin),OPCODE_PAD,V(value),OPCODE_PAD,V(param1),OPCODE_PAD,V(param2), +#define ASPECT(address,value) OPCODE_ASPECT,V((address<<5) | (value & 0x1F)), #define AT(sensor_id) OPCODE_AT,V(sensor_id), #define ATGTE(sensor_id,value) OPCODE_ATGTE,V(sensor_id),OPCODE_PAD,V(value), #define ATLT(sensor_id,value) OPCODE_ATLT,V(sensor_id),OPCODE_PAD,V(value), From 8705c8c33f0255b46a2925cbe9453d87a90c2c79 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 11:49:02 +0000 Subject: [PATCH 238/310] DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) --- EXRAIL2.cpp | 12 +++++++++++- EXRAIL2.h | 1 + EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 5 +++++ 4 files changed, 19 insertions(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 56aeeb2..6f0420c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1066,7 +1066,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { if (diag) DIAG(F(" doSignal %d %x"),id,rag); // Schedule any event handler for this signal change. - // Thjis will work even without a signal definition. + // This will work even without a signal definition. if (rag==SIGNAL_RED) onRedLookup->handleEvent(F("RED"),id); else if (rag==SIGNAL_GREEN) onGreenLookup->handleEvent(F("GREEN"),id); else onAmberLookup->handleEvent(F("AMBER"),id); @@ -1103,6 +1103,16 @@ int16_t RMFT2::getSignalSlot(int16_t id) { return; } + if (sigtype== DCCX_SIGNAL_FLAG) { + // redpin,amberpin,greenpin are the 3 aspects + byte value=redpin; + if (rag==SIGNAL_AMBER) value=amberpin; + if (rag==SIGNAL_GREEN) value=greenpin; + DCC::setExtendedAccessory(sigid & SIGNAL_ID_MASK,value); + return; + } + + // LED or similar 3 pin signal, (all pins zero would be a virtual signal) // If amberpin is zero, synthesise amber from red+green const byte SIMAMBER=0x00; diff --git a/EXRAIL2.h b/EXRAIL2.h index e8235c6..eec2a06 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -158,6 +158,7 @@ class LookList { static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; + static const int16_t DCCX_SIGNAL_FLAG=0x3000; static const int16_t SIGNAL_ID_MASK=0x0FFF; // Throttle Info Access functions built by exrail macros static const byte rosterNameCount; diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 633f4d5..723bef2 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -45,6 +45,7 @@ #undef CLOSE #undef CONFIGURE_SERVO #undef DCC_SIGNAL +#undef DCCX_SIGNAL #undef DCC_TURNTABLE #undef DEACTIVATE #undef DEACTIVATEL @@ -200,6 +201,7 @@ #define CLOSE(id) #define CONFIGURE_SERVO(vpin,pos1,pos2,profile) #define DCC_SIGNAL(id,add,subaddr) +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) #define DCC_TURNTABLE(id,home,description) #define DEACTIVATE(addr,subaddr) #define DEACTIVATEL(addr) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 8d870ef..698451e 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -172,6 +172,8 @@ bool exrailHalSetup() { #define SERVO_SIGNAL(vpin,redval,amberval,greenval) | FEATURE_SIGNAL #undef DCC_SIGNAL #define DCC_SIGNAL(id,addr,subaddr) | FEATURE_SIGNAL +#undef DCCX_SIGNAL +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) | FEATURE_SIGNAL #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) | FEATURE_SIGNAL @@ -401,6 +403,8 @@ const FSH * RMFT2::getRosterFunctions(int16_t id) { #define SERVO_SIGNAL(vpin,redval,amberval,greenval) vpin | RMFT2::SERVO_SIGNAL_FLAG,redval,amberval,greenval, #undef DCC_SIGNAL #define DCC_SIGNAL(id,addr,subaddr) id | RMFT2::DCC_SIGNAL_FLAG,addr,subaddr,0, +#undef DCCX_SIGNAL +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) id | RMFT2::DCCX_SIGNAL_FLAG,redAspect,amberAspect,greenAspect, #undef VIRTUAL_SIGNAL #define VIRTUAL_SIGNAL(id) id,0,0,0, @@ -457,6 +461,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define DELAYMINS(mindelay) OPCODE_DELAYMINS,V(mindelay), #define DELAYRANDOM(mindelay,maxdelay) DELAY(mindelay) OPCODE_RANDWAIT,V((maxdelay-mindelay)/100L), #define DCC_SIGNAL(id,add,subaddr) +#define DCCX_SIGNAL(id,redAspect,amberAspect,greenAspect) #define DONE OPCODE_ENDTASK,0,0, #define DRIVE(analogpin) OPCODE_DRIVE,V(analogpin), #define ELSE OPCODE_ELSE,0,0, From 5742b71ec608e79feaedba1b14322187d960474c Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:20:58 +0000 Subject: [PATCH 239/310] to EXRAIL DCCX_SIGNAL intercept --- DCCEXParser.cpp | 6 ++++++ EXRAIL2.cpp | 32 ++++++++++++++++++++++++++++++++ EXRAIL2.h | 3 ++- 3 files changed, 40 insertions(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a3aa1c4..bcd258a 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -390,6 +390,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) if (params!=2) break; if (p[0] != (p[0] & 0x7F)) break; if (p[1] != (p[1] & 0x1F)) break; +#ifdef EXRAIL_ACTIVE + // Ask exrail if this is just changing the aspect on a + // predefined DCCX_SIGNAL. Because this will handle all + // the IFRED and ONRED type issues at the same time. + if (RMFT2::signalAspectEvent(p[0],p[1])) return; +#endif DCC::setExtendedAccessory(p[0],p[1],3); } return; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6f0420c..928bc79 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1146,6 +1146,38 @@ int16_t RMFT2::getSignalSlot(int16_t id) { return (flags[sigslot] & SIGNAL_MASK) == rag; } + +// signalAspectEvent returns true if the aspect is destined +// for a defined DCCX_SIGNAL which will handle all the RAG flags +// and ON* handlers. +// Otherwise false so the parser should send the command directly +bool RMFT2::signalAspectEvent(int16_t address, byte aspect ) { + if (!(compileFeatures & FEATURE_SIGNAL)) return false; + int16_t sigslot=getSignalSlot(address); + if (sigslot<0) return false; // this is not a defined signal + int16_t sigpos=sigslot*8; + VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); + VPIN sigtype=sigid & ~SIGNAL_ID_MASK; + if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal + // Turn an aspect change into a RED/AMBER/GREEN setting + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) { + doSignal(sigid,SIGNAL_RED); + return true; + } + + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4)) { + doSignal(sigid,SIGNAL_AMBER); + return true; + } + + if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6)) { + doSignal(sigid,SIGNAL_GREEN); + return true; + } + + return false; // aspect is not a defined one +} + void RMFT2::turnoutEvent(int16_t turnoutId, bool closed) { // Hunt for an ONTHROW/ONCLOSE for this turnout if (closed) onCloseLookup->handleEvent(F("CLOSE"),turnoutId); diff --git a/EXRAIL2.h b/EXRAIL2.h index eec2a06..914c822 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -155,6 +155,7 @@ class LookList { static void clockEvent(int16_t clocktime, bool change); static void rotateEvent(int16_t id, bool change); static void powerEvent(int16_t track, bool overload); + static bool signalAspectEvent(int16_t address, byte aspect ); static const int16_t SERVO_SIGNAL_FLAG=0x4000; static const int16_t ACTIVE_HIGH_SIGNAL_FLAG=0x2000; static const int16_t DCC_SIGNAL_FLAG=0x1000; @@ -173,7 +174,7 @@ class LookList { static const FSH * getTurntableDescription(int16_t id); static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); - + private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); static bool parseSlash(Print * stream, byte & paramCount, int16_t p[]) ; From 7ee4188d88e899007658a197db6bea25ae47b492 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:36:33 +0000 Subject: [PATCH 240/310] Tidy and version --- DCCEXParser.cpp | 11 ++++------- EXRAIL2.cpp | 5 ++++- EXRAIL2Parser.cpp | 8 ++++++++ version.h | 6 +++++- 4 files changed, 21 insertions(+), 9 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index bcd258a..d66b51f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -387,16 +387,13 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) case 'A': // EXTENDED ACCESSORY { + // Note: if this happens to match a defined EXRAIL + // DCCX_SIGNAL, then EXRAIL will have intercepted + // this command alrerady. if (params!=2) break; if (p[0] != (p[0] & 0x7F)) break; if (p[1] != (p[1] & 0x1F)) break; -#ifdef EXRAIL_ACTIVE - // Ask exrail if this is just changing the aspect on a - // predefined DCCX_SIGNAL. Because this will handle all - // the IFRED and ONRED type issues at the same time. - if (RMFT2::signalAspectEvent(p[0],p[1])) return; -#endif - DCC::setExtendedAccessory(p[0],p[1],3); + DCC::setExtendedAccessory(p[0],p[1]); } return; diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 928bc79..014e42b 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -802,7 +802,10 @@ void RMFT2::loop2() { } case OPCODE_ASPECT: { // operand is address<<5 | value - DCC::setExtendedAccessory(operand>>5, operand & 0x1F); + int16_t address=operand>>5; + byte aspect=operand & 0x1f; + if (!signalAspectEvent(address,aspect)) + DCC::setExtendedAccessory(address,aspect); break; } diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index 99f0c37..7969750 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -51,6 +51,14 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 opcode=0; break; + case 'A': // + if (paramCount!=2) break; + // Ask exrail if this is just changing the aspect on a + // predefined DCCX_SIGNAL. Because this will handle all + // the IFRED and ONRED type issues at the same time. + if (signalAspectEvent(p[0],p[1])) opcode=0; // all done + break; + case 'L': // This entire code block is compiled out if LLC macros not used if (!(compileFeatures & FEATURE_LCC)) return; diff --git a/version.h b/version.h index 84eeedf..341c61e 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,11 @@ #include "StringFormatter.h" -#define VERSION "5.2.33" +#define VERSION "5.2.34" +// 5.2.34 - Command fopr DCC Extended Accessories +// - Exrail ASPECT(address,aspect) for above. +// - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect) +// - Exrail intercept for DCC Signals. // 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile) // 5.2.32 - Railcom Cutout (Initial trial Mega2560 only) // 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. From 7e4093f03fd96b76fb6cdbceb2c0b91918a86b8a Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 16 Feb 2024 12:45:33 +0000 Subject: [PATCH 241/310] comment only --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index d66b51f..af6c4ee 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -45,7 +45,7 @@ Once a new OPCODE is decided upon, update this list. 0, Track power off 1, Track power on a, DCC accessory control - A, + A, DCC extended accessory control b, Write CV bit on main B, Write CV bit c, Request current command From dcd332603c1cc97f0474f7e1266b76d1fa7af3ae Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 17 Feb 2024 11:09:03 +0000 Subject: [PATCH 242/310] accessory packet issues. --- DCC.cpp | 40 +++++++++++++++++++++++++++++----------- DCC.h | 2 +- DCCEXParser.cpp | 17 ++++++----------- 3 files changed, 36 insertions(+), 23 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index ed2a803..8a6e8e0 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -278,21 +278,39 @@ void DCC::setAccessory(int address, byte port, bool gate, byte onoff /*= 2*/) { } } -void DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { +bool DCC::setExtendedAccessory(int16_t address, int16_t value, byte repeats) { + +/* From https://www.nmra.org/sites/default/files/s-9.2.1_2012_07.pdf + +The Extended Accessory Decoder Control Packet is included for the purpose of transmitting aspect control to signal +decoders or data bytes to more complex accessory decoders. Each signal head can display one aspect at a time. +{preamble} 0 10AAAAAA 0 0AAA0AA1 0 000XXXXX 0 EEEEEEEE 1 + +XXXXX is for a single head. A value of 00000 for XXXXX indicates the absolute stop aspect. All other aspects +represented by the values for XXXXX are determined by the signaling system used and the prototype being +modeled. +*/ +/* CAH Notes: +Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX + +Note that the Basic accessory format mentions +"By convention these bits (bits 4-6 of the second data byte) are in ones complement" +but this note is absent from the advanced packet description. +The (~address) construct below applies this because this appears to be +required. + +*/ + if (address != (address & 0x7FF)) return false; // 11 bits + if (value != (value & 0x1F)) return false; // 5 bits - // format is 10AAAAAA, 0AAA0AA1, 000XXXXX - if (address != (address & 0x7F)) return; - if (value != (value & 0x1F)) return; byte b[3]; - b[0]= 0x80 | ((address & 0x7FF)>>5); - b[1]= 0x01 | ((address & 0x1c)<<2) | (address & 0x03)<<1; - b[2]=value & 0x1F; + b[0]= 0x80 | (address>>5); + b[1]= 0x01 | (((~address) & 0x1c)<<2) | ((address & 0x03)<<1); + b[2]=value; DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times -#if defined(EXRAIL_ACTIVE) - // TODO RMFT2::activateExtendedEvent(address,value); -#endif -} + return true; + } // // writeCVByteMain: Write a byte with PoM on main. This writes diff --git a/DCC.h b/DCC.h index e1aeae6..aa93520 100644 --- a/DCC.h +++ b/DCC.h @@ -71,7 +71,7 @@ public: static uint32_t getFunctionMap(int cab); static void updateGroupflags(byte &flags, int16_t functionNumber); static void setAccessory(int address, byte port, bool gate, byte onoff = 2); - static void setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); + static bool setExtendedAccessory(int16_t address, int16_t value, byte repeats=3); static bool writeTextPacket(byte *b, int nBytes); // ACKable progtrack calls bitresults callback 0,0 or -1, cv returns value or -1 diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index af6c4ee..db78d71 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -385,17 +385,12 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) } return; - case 'A': // EXTENDED ACCESSORY - { - // Note: if this happens to match a defined EXRAIL - // DCCX_SIGNAL, then EXRAIL will have intercepted - // this command alrerady. - if (params!=2) break; - if (p[0] != (p[0] & 0x7F)) break; - if (p[1] != (p[1] & 0x1F)) break; - DCC::setExtendedAccessory(p[0],p[1]); - } - return; + case 'A': // EXTENDED ACCESSORY + // Note: if this happens to match a defined EXRAIL + // DCCX_SIGNAL, then EXRAIL will have intercepted + // this command alrerady. + if (params==2 && DCC::setExtendedAccessory(p[0],p[1])) return; + break; case 'T': // TURNOUT if (parseT(stream, params, p)) From fbbedc7577ab390e22235ffab111384179ed53be Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 17 Feb 2024 18:51:13 +0100 Subject: [PATCH 243/310] make ext acc packet format follow RCN-213 --- DCC.cpp | 45 +++++++++++++++++++++++++++++++-------------- 1 file changed, 31 insertions(+), 14 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 8a6e8e0..a435eeb 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -289,28 +289,45 @@ decoders or data bytes to more complex accessory decoders. Each signal head can XXXXX is for a single head. A value of 00000 for XXXXX indicates the absolute stop aspect. All other aspects represented by the values for XXXXX are determined by the signaling system used and the prototype being modeled. -*/ -/* CAH Notes: + +From https://normen.railcommunity.de/RCN-213.pdf: + +More information is in RCN-213 about how the address bits are organized. +preamble -0- 1 0 A7 A6 A5 A4 A3 A2 -0- 0 ^A10 ^A9 ^A8 0 A1 A0 1 -0- .... + Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX -Note that the Basic accessory format mentions -"By convention these bits (bits 4-6 of the second data byte) are in ones complement" -but this note is absent from the advanced packet description. -The (~address) construct below applies this because this appears to be -required. +Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen +Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in +Anwenderdialogen als Adresse 1 dargestellt. +This means that the first address shown to the user as "1" is mapped +to internal address 4. + +Note that the Basic accessory format mentions "By convention these +bits (bits 4-6 of the second data byte) are in ones complement" but +this note is absent from the advanced packet description. The +english translation does not mention that the address format for +the advanced packet follows the one for the basic packet but +according to the RCN-213 this is the case. + +We allow for addresses from -3 to 2047-3 as that allows to address the +whole range of the 11 bits sent to track. */ - if (address != (address & 0x7FF)) return false; // 11 bits - if (value != (value & 0x1F)) return false; // 5 bits + if ((address > 2044) || (address < -3)) return false; // 2047-3, 11 bits but offset 3 + if (value != (value & 0x1F)) return false; // 5 bits - + address+=3; // +3 offset according to RCN-213 byte b[3]; - b[0]= 0x80 | (address>>5); - b[1]= 0x01 | (((~address) & 0x1c)<<2) | ((address & 0x03)<<1); + b[0]= 0x80 // bits always on + | ((address>>2) & 0x3F); // shift out 2, mask out used bits + b[1]= 0x01 // bits always on + | (((~(address>>8)) & 0x07)<<4) // shift out 8, invert, mask 3 bits, shift up 4 + | ((address & 0x03)<<1); // mask 2 bits, shift up 1 b[2]=value; - DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); // Repeat on packet three times + DCCWaveform::mainTrack.schedulePacket(b, sizeof(b), repeats); return true; - } +} // // writeCVByteMain: Write a byte with PoM on main. This writes From fe9b1da8a3bcdced2465074dd882689d93e29b31 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 17 Feb 2024 18:52:48 +0100 Subject: [PATCH 244/310] version 5.2.35 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 956a8d2..40e7ece 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402050827Z" +#define GITHUB_SHA "devel-202402171752Z" diff --git a/version.h b/version.h index 341c61e..d1d6416 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.34" +#define VERSION "5.2.35" +// 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213 // 5.2.34 - Command fopr DCC Extended Accessories // - Exrail ASPECT(address,aspect) for above. // - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect) From 821115caaddd513152d277a5e5e4426bad8f9b58 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Mon, 19 Feb 2024 20:02:01 +0000 Subject: [PATCH 245/310] Make ASSERT macro match 5.2.35 --- EXRAILMacros.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 698451e..f0cb150 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -118,8 +118,8 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU // This pass generates no runtime data or code #include "EXRAIL2MacroReset.h" #undef ASPECT -#define ASPECT(address,value) static_assert((address & 0x7ff)== address, "invalid Address"); \ - static_assert((value & 0x1F)== value, "Invalid value"); +#define ASPECT(address,value) static_assert(address <=2044, "invalid Address"); \ + static_assert(address>=-3, "Invalid value"); #undef CALL #define CALL(id) static_assert(hasseq(id),"Sequence not found"); #undef FOLLOW From 423d1932ae42035412c4b6c970f2d2d889a91991 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 20 Feb 2024 15:08:41 +0100 Subject: [PATCH 246/310] merge artifact --- version.h | 1 - 1 file changed, 1 deletion(-) diff --git a/version.h b/version.h index c3ea916..dcc7c6e 100644 --- a/version.h +++ b/version.h @@ -33,7 +33,6 @@ // 5.2.21 - Add STARTUP_DELAY config option to delay CS bootup // 5.2.20 - Check return of Ethernet.begin() // 5.2.19 - ESP32: Determine if the RMT hardware can handle DCC ->>>>>>> devel // 5.2.18 - Display network IP fix // 5.2.17 - ESP32 simplify network logic // 5.2.16 - Bugfix to allow for devices using the EX-IOExpander protocol to have no analogue or no digital pins From 3fa2edb0dac4cbae560af447cc0982e481f6d67c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 20 Feb 2024 15:13:22 +0100 Subject: [PATCH 247/310] fix warning and indent proper --- Turntables.cpp | 29 +++++++++++++++-------------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/Turntables.cpp b/Turntables.cpp index ba143cb..f75005c 100644 --- a/Turntables.cpp +++ b/Turntables.cpp @@ -247,22 +247,23 @@ DCCTurntable::DCCTurntable(uint16_t id) : Turntable(id, TURNTABLE_DCC) {} StringFormatter::send(stream, F("\n"), _turntableData.id); } - // EX-Turntable specific code for moving to the specified position - bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) { +// EX-Turntable specific code for moving to the specified position +bool DCCTurntable::setPositionInternal(uint8_t position, uint8_t activity) { + (void) activity; #ifndef IO_NO_HAL - int16_t value = getPositionValue(position); - if (position == 0 || !value) return false; // Return false if it's not a valid position - // Set position via device driver - int16_t addr=value>>3; - int16_t subaddr=(value>>1) & 0x03; - bool active=value & 0x01; - _previousPosition = _turntableData.position; - _turntableData.position = position; - DCC::setAccessory(addr, subaddr, active); + int16_t value = getPositionValue(position); + if (position == 0 || !value) return false; // Return false if it's not a valid position + // Set position via device driver + int16_t addr=value>>3; + int16_t subaddr=(value>>1) & 0x03; + bool active=value & 0x01; + _previousPosition = _turntableData.position; + _turntableData.position = position; + DCC::setAccessory(addr, subaddr, active); #else - (void)position; + (void)position; #endif - return true; - } + return true; +} #endif From 1101cfd6377702fe4e3f03fd361d63cf48ec9bef Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 24 Feb 2024 17:24:55 +0100 Subject: [PATCH 248/310] surpress warnings --- IO_EXTurntable.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/IO_EXTurntable.cpp b/IO_EXTurntable.cpp index aeb935b..0e134d4 100644 --- a/IO_EXTurntable.cpp +++ b/IO_EXTurntable.cpp @@ -83,6 +83,7 @@ void EXTurntable::_loop(unsigned long currentMicros) { // Read returns status as obtained in our loop. // Return false if our status value is invalid. int EXTurntable::_read(VPIN vpin) { + (void)vpin; // surpress warning if (_deviceState == DEVSTATE_FAILED) return 0; if (_stepperStatus > 1) { return false; @@ -127,6 +128,8 @@ void EXTurntable::_writeAnalogue(VPIN vpin, int value, uint8_t activity, uint16_ vpin, value, activity, duration); DIAG(F("I2CManager write I2C Address:%d stepsMSB:%d stepsLSB:%d activity:%d"), _I2CAddress.toString(), stepsMSB, stepsLSB, activity); +#else + (void)duration; #endif if (activity < 4) _stepperStatus = 1; // Tell the device driver Turntable-EX is busy _previousStatus = _stepperStatus; From b29a01f436daab54978cd00b0d9af1830672def1 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 24 Feb 2024 20:56:06 +0100 Subject: [PATCH 249/310] ESP32: Use the BOOSTER_INPUT define --- TrackManager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index a77108b..5aba978 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -219,7 +219,7 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr if (mode & TRACK_MODE_BOOST) { //DIAG(F("Track=%c mode boost pin %d"),trackToSet+'A', p.pin); pinMode(BOOSTER_INPUT, INPUT); - gpio_matrix_in(26, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback + gpio_matrix_in(BOOSTER_INPUT, SIG_IN_FUNC228_IDX, false); //pads 224 to 228 available as loopback gpio_matrix_out(p.pin, SIG_IN_FUNC228_IDX, false, false); if (p.invpin != UNUSED_PIN) { gpio_matrix_out(p.invpin, SIG_IN_FUNC228_IDX, true /*inverted*/, false); From 274affce45d1c0d5e5527fdd524f607ffa058af8 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 24 Feb 2024 20:57:38 +0100 Subject: [PATCH 250/310] version 5.2.37 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 9c706cf..699ead5 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402201404Z" +#define GITHUB_SHA "devel-202402241957Z" diff --git a/version.h b/version.h index dcc7c6e..ee8c827 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.36" +#define VERSION "5.2.37" +// 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define // 5.2.36 - Variable frequency for DC mode // 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213 // 5.2.34 - Command fopr DCC Extended Accessories From 7503421eb6bea5f7c3758cb0604c54829df826c3 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 26 Feb 2024 09:11:21 +0100 Subject: [PATCH 251/310] Compile time optimization for booster mode --- MotorDriver.h | 12 +++++++++--- TrackManager.cpp | 9 +++++---- 2 files changed, 14 insertions(+), 7 deletions(-) diff --git a/MotorDriver.h b/MotorDriver.h index b678a84..4491164 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -34,9 +34,15 @@ template inline T operator| (T a, T b) { return (T)((int)a | (int)b); } template inline T operator& (T a, T b) { return (T)((int)a & (int)b); } template inline T operator^ (T a, T b) { return (T)((int)a ^ (int)b); } enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4, - TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, TRACK_MODE_BOOST = 32, - TRACK_MODE_ALL = 62, // only to operate all tracks - TRACK_MODE_INV = 64, TRACK_MODE_DCX = 72 /*DC + INV*/, TRACK_MODE_AUTOINV = 128}; + TRACK_MODE_DC = 8, TRACK_MODE_EXT = 16, +#ifdef ARDUINO_ARCH_ESP32 + TRACK_MODE_BOOST = 32, +#else + TRACK_MODE_BOOST = 0, +#endif + TRACK_MODE_ALL = TRACK_MODE_MAIN|TRACK_MODE_PROG|TRACK_MODE_DC|TRACK_MODE_EXT|TRACK_MODE_BOOST, + TRACK_MODE_INV = 64, + TRACK_MODE_DCX = TRACK_MODE_DC|TRACK_MODE_INV, TRACK_MODE_AUTOINV = 128}; #define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH #define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW diff --git a/TrackManager.cpp b/TrackManager.cpp index 5aba978..e357e7f 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -362,7 +362,8 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) if (params==2 && p[1]=="EXT"_hk) // <= id EXT> return setTrackMode(p[0],TRACK_MODE_EXT); #ifdef BOOSTER_INPUT - if (params==2 && p[1]=="BOOST"_hk) // <= id BOOST> + if (TRACK_MODE_BOOST != 0 && // compile time optimization + params==2 && p[1]=="BOOST"_hk) // <= id BOOST> return setTrackMode(p[0],TRACK_MODE_BOOST); #endif if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO> @@ -401,11 +402,11 @@ const FSH* TrackManager::getModeName(TRACK_MODE tm) { modename=F("EXT"); else if(tm & TRACK_MODE_BOOST) { if(tm & TRACK_MODE_AUTOINV) - modename=F("B A"); + modename=F("BOOST A"); else if (tm & TRACK_MODE_INV) - modename=F("B I"); + modename=F("BOOST I"); else - modename=F("B"); + modename=F("BOOST"); } else if (tm & TRACK_MODE_DC) { if (tm & TRACK_MODE_INV) From 3d6f41398d5efac7fcd8e35a70510657649f4770 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 4 Mar 2024 15:07:03 +0100 Subject: [PATCH 252/310] compile time check WIFI_PASSWORD length for reasonable value --- CommandStation-EX.ino | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CommandStation-EX.ino b/CommandStation-EX.ino index 2cd9d33..3a0e5ca 100644 --- a/CommandStation-EX.ino +++ b/CommandStation-EX.ino @@ -65,6 +65,9 @@ #ifdef EXRAIL_WARNING #warning You have myAutomation.h but your hardware has not enough memory to do that, so EX-RAIL DISABLED #endif +// compile time check, passwords 1 to 7 chars do not work, so do not try to compile with them at all +// remember trailing '\0', sizeof("") == 1. +#define PASSWDCHECK(S) static_assert(sizeof(S) == 1 || sizeof(S) > 8, "Password shorter than 8 chars") void setup() { @@ -102,10 +105,12 @@ void setup() // Start Ethernet if it exists #ifndef ARDUINO_ARCH_ESP32 #if WIFI_ON + PASSWDCHECK(WIFI_PASSWORD); // compile time check WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); #endif // WIFI_ON #else // ESP32 needs wifi on always + PASSWDCHECK(WIFI_PASSWORD); // compile time check WifiESP::setup(WIFI_SSID, WIFI_PASSWORD, WIFI_HOSTNAME, IP_PORT, WIFI_CHANNEL, WIFI_FORCE_AP); #endif // ARDUINO_ARCH_ESP32 From b75266689928b1040a06c90240a34970379301c9 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 4 Mar 2024 15:20:48 +0100 Subject: [PATCH 253/310] remove warning --- EXRAILMacros.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 825ce02..876bc23 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -350,6 +350,8 @@ const FSH * RMFT2::getTurntableDescription(int16_t turntableId) { #define TT_ADDPOSITION(turntable_id,position,value,home,description...) T_DESC(turntable_id,position,description) const FSH * RMFT2::getTurntablePositionDescription(int16_t turntableId, uint8_t positionId) { + (void)turntableId; + (void)positionId; #include "myAutomation.h" return NULL; } From 4b04a80e6fa5b4d2505f31eb53c284944d3cfbd6 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 5 Mar 2024 19:59:29 +0000 Subject: [PATCH 254/310] Remove unnecessary warning --- EXRAILMacros.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 876bc23..ca12e23 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -95,14 +95,14 @@ constexpr int16_t stuffSize=sizeof(compileTimeSequenceList)/sizeof(int16_t) - 1; // Compile time function to check for sequence nos. -constexpr bool hasseq(const int16_t value, const uint16_t pos=0 ) { +constexpr bool hasseq(const int16_t value, const int16_t pos=0 ) { return pos>=stuffSize? false : compileTimeSequenceList[pos]==value || hasseq(value,pos+1); } // Compile time function to check for duplicate sequence nos. -constexpr bool hasdup(const int16_t value, const uint16_t pos ) { +constexpr bool hasdup(const int16_t value, const int16_t pos ) { return pos>=stuffSize? false : compileTimeSequenceList[pos]==value || hasseq(value,pos+1) From be218d3032967a64326a1daddf954cf0baa8b35c Mon Sep 17 00:00:00 2001 From: Asbelos Date: Fri, 8 Mar 2024 20:33:11 +0000 Subject: [PATCH 255/310] EXRAIL MESSAGE() --- CommandDistributor.cpp | 5 +++++ CommandDistributor.h | 1 + EXRAIL2.cpp | 4 ++++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 2 ++ EXRAILMacros.h | 4 ++++ version.h | 4 +++- 7 files changed, 20 insertions(+), 2 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index f838fd2..67bcc54 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -312,6 +312,11 @@ void CommandDistributor::broadcastRaw(clientType type, char * msg) { broadcastReply(type, F("%s"),msg); } +void CommandDistributor::broadcastMessage(char * message) { + broadcastReply(COMMAND_TYPE, F("\n"),message); + broadcastReply(WITHROTTLE_TYPE, F("Hm%s\n"),message); +} + void CommandDistributor::broadcastTrackState(const FSH* format, byte trackLetter, const FSH *modename, int16_t dcAddr) { broadcastReply(COMMAND_TYPE, format, trackLetter, modename, dcAddr); } diff --git a/CommandDistributor.h b/CommandDistributor.h index e4dff5d..f68a5e2 100644 --- a/CommandDistributor.h +++ b/CommandDistributor.h @@ -60,6 +60,7 @@ public : static void forget(byte clientId); static void broadcastRouteState(uint16_t routeId,byte state); static void broadcastRouteCaption(uint16_t routeId,const FSH * caption); + static void broadcastMessage(char * message); // Handling code for virtual LCD receiver. static Print * getVirtualLCDSerial(byte screen, byte row); diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 9f1075c..c9c6716 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1334,6 +1334,7 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) { break; case thrunge_parse: case thrunge_broadcast: + case thrunge_message: case thrunge_lcd: default: // thrunge_lcd+1, ... if (!buffer) buffer=new StringBuffer(); @@ -1371,6 +1372,9 @@ void RMFT2::thrungeString(uint32_t strfar, thrunger mode, byte id) { case thrunge_withrottle: CommandDistributor::broadcastRaw(CommandDistributor::WITHROTTLE_TYPE,buffer->getString()); break; + case thrunge_message: + CommandDistributor::broadcastMessage(buffer->getString()); + break; case thrunge_lcd: LCD(id,F("%s"),buffer->getString()); break; diff --git a/EXRAIL2.h b/EXRAIL2.h index b4a06da..f4cf320 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -94,7 +94,7 @@ enum thrunger: byte { thrunge_serial,thrunge_parse, thrunge_serial1, thrunge_serial2, thrunge_serial3, thrunge_serial4, thrunge_serial5, thrunge_serial6, - thrunge_lcn, + thrunge_lcn,thrunge_message, thrunge_lcd, // Must be last!! }; diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index 2428a09..e94c657 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -97,6 +97,7 @@ #undef LCCX #undef LCN #undef MOVETT +#undef MESSAGE #undef ONACTIVATE #undef ONACTIVATEL #undef ONAMBER @@ -253,6 +254,7 @@ #define LCD(row,msg) #define SCREEN(display,row,msg) #define LCN(msg) +#define MESSAGE(msg) #define MOVETT(id,steps,activity) #define ONACTIVATE(addr,subaddr) #define ONACTIVATEL(linear) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index ca12e23..5588811 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -253,6 +253,9 @@ const int StringMacroTracker1=__COUNTER__; #define PRINT(msg) THRUNGE(msg,thrunge_print) #undef LCN #define LCN(msg) THRUNGE(msg,thrunge_lcn) +#undef MESSAGE +#define MESSAGE(msg) THRUNGE(msg,thrunge_message) + #undef ROUTE_CAPTION #define ROUTE_CAPTION(id,caption) \ case (__COUNTER__ - StringMacroTracker1) : {\ @@ -516,6 +519,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define SCREEN(display,id,msg) PRINT(msg) #define STEALTH(code...) PRINT(dummy) #define LCN(msg) PRINT(msg) +#define MESSAGE(msg) PRINT(msg) #define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0), #define ONACTIVATE(addr,subaddr) OPCODE_ONACTIVATE,V(addr<<2|subaddr), #define ONACTIVATEL(linear) OPCODE_ONACTIVATE,V(linear+3), diff --git a/version.h b/version.h index ee8c827..97b0a70 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.37" +#define VERSION "5.2.38" +// 5.2.38 - Exrail MESSAGE("text") to send a user message to all +// connected throttles (uses and withrottle Hmtext. // 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define // 5.2.36 - Variable frequency for DC mode // 5.2.35 - Bugfix: Make DCC Extended Accessories follow RCN-213 From 9aac34b403b07f02ffdcad5747aa151f21bf7a86 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Mon, 11 Mar 2024 12:26:28 +0000 Subject: [PATCH 256/310] comments --- DCCEXParser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 2eeedc9..6f4bf52 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -68,7 +68,7 @@ Once a new OPCODE is decided upon, update this list. K, Reserved for future use - Potentially Railcom l, Loco speedbyte/function map broadcast L, Reserved for LCC interface (implemented in EXRAIL) - m, + m, message to throttles broadcast M, Write DCC packet n, N, From d753eb43e3d53a0c9d17ba98742b49cb27f3485a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 11 Mar 2024 14:52:55 +0100 Subject: [PATCH 257/310] Functions for DC frequency: Use func up to F31 --- CommandDistributor.cpp | 4 +--- DCC.cpp | 2 +- DCCEXParser.cpp | 25 +++++++++++-------------- 3 files changed, 13 insertions(+), 18 deletions(-) diff --git a/CommandDistributor.cpp b/CommandDistributor.cpp index 67bcc54..e7087ad 100644 --- a/CommandDistributor.cpp +++ b/CommandDistributor.cpp @@ -209,9 +209,7 @@ int16_t CommandDistributor::retClockTime() { void CommandDistributor::broadcastLoco(byte slot) { DCC::LOCO * sp=&DCC::speedTable[slot]; - uint32_t func = sp->functions; - func = func & 0x1fffffff; // mask out bits 0-28 - broadcastReply(COMMAND_TYPE, F("\n"), sp->loco,slot,sp->speedCode,func); + broadcastReply(COMMAND_TYPE, F("\n"), sp->loco,slot,sp->speedCode,sp->functions); #ifdef SABERTOOTH if (Serial2 && sp->loco == SABERTOOTH) { static uint8_t rampingmode = 0; diff --git a/DCC.cpp b/DCC.cpp index 5ab7eff..36d91fb 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -242,7 +242,7 @@ void DCC::changeFn( int cab, int16_t functionNumber) { // Report function state (used from withrottle protocol) // returns 0 false, 1 true or -1 for do not know int8_t DCC::getFn( int cab, int16_t functionNumber) { - if (cab<=0 || functionNumber>28) + if (cab<=0 || functionNumber>31) return -1; // unknown int reg = lookupSpeedTable(cab); if (reg<0) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 6f4bf52..fa4c9f8 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -283,25 +283,22 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) return; // filterCallback asked us to ignore case 't': // THROTTLE { - if (params==1) { // display state - - int16_t slot=DCC::lookupSpeedTable(p[0],false); - if (slot>=0) { - DCC::LOCO * sp=&DCC::speedTable[slot]; - StringFormatter::send(stream,F("\n"), - sp->loco,slot,sp->speedCode,sp->functions); - } - else // send dummy state speed 0 fwd no functions. - StringFormatter::send(stream,F("\n"),p[0]); - return; - } - int16_t cab; int16_t tspeed; int16_t direction; - + + if (params==1) { // display state + int16_t slot=DCC::lookupSpeedTable(p[0],false); + if (slot>=0) + CommandDistributor::broadcastLoco(slot); + else // send dummy state speed 0 fwd no functions. + StringFormatter::send(stream,F("\n"),p[0]); + return; + } + if (params == 4) { // + // ignore register p[0] cab = p[1]; tspeed = p[2]; direction = p[3]; From 8eec85edcf742b42bdd53517baa9b271463151ca Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 11 Mar 2024 14:54:18 +0100 Subject: [PATCH 258/310] version 5.2.39 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 699ead5..29d9a87 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202402241957Z" +#define GITHUB_SHA "devel-202403111353Z" diff --git a/version.h b/version.h index 97b0a70..23e7e02 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.38" +#define VERSION "5.2.39" +// 5.2.39 - Functions for DC frequency: Use func up to F31 // 5.2.38 - Exrail MESSAGE("text") to send a user message to all // connected throttles (uses and withrottle Hmtext. // 5.2.37 - Bugfix ESP32: Use BOOSTER_INPUT define From e3081a7e56a58d2af0858a8ba80ba6f3e66dede2 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 12 Mar 2024 11:45:28 +0100 Subject: [PATCH 259/310] Functions for DC frequency: Use func up to F31 part 2 --- DCC.cpp | 7 ++++--- WiThrottle.cpp | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 36d91fb..a8bc953 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -219,8 +219,9 @@ bool DCC::setFn( int cab, int16_t functionNumber, bool on) { } else { speedTable[reg].functions &= ~funcmask; } - if (speedTable[reg].functions != previous && functionNumber <= 28) { - updateGroupflags(speedTable[reg].groupFlags, functionNumber); + if (speedTable[reg].functions != previous) { + if (functionNumber <= 28) + updateGroupflags(speedTable[reg].groupFlags, functionNumber); CommandDistributor::broadcastLoco(reg); } return true; @@ -235,8 +236,8 @@ void DCC::changeFn( int cab, int16_t functionNumber) { speedTable[reg].functions ^= funcmask; if (functionNumber <= 28) { updateGroupflags(speedTable[reg].groupFlags, functionNumber); - CommandDistributor::broadcastLoco(reg); } + CommandDistributor::broadcastLoco(reg); } // Report function state (used from withrottle protocol) diff --git a/WiThrottle.cpp b/WiThrottle.cpp index 3e712b3..f3d9253 100644 --- a/WiThrottle.cpp +++ b/WiThrottle.cpp @@ -571,7 +571,7 @@ void WiThrottle::sendRoutes(Print* stream) { void WiThrottle::sendFunctions(Print* stream, byte loco) { int16_t locoid=myLocos[loco].cab; - int fkeys=29; + int fkeys=32; // upper limit (send functions 0 to 31) myLocos[loco].functionToggles=1<<2; // F2 (HORN) is a non-toggle #ifdef EXRAIL_ACTIVE From 59d855549e087cababbb3cab368208fd6bdfb629 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 12 Mar 2024 11:47:25 +0100 Subject: [PATCH 260/310] version tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 29d9a87..c5e1882 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202403111353Z" +#define GITHUB_SHA "devel-202403121045Z" From 3cda869c6e15de7c00e7817172f248e2e2be01ea Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 18 Mar 2024 21:17:51 +0100 Subject: [PATCH 261/310] Allow no shield --- MotorDrivers.h | 6 +++++- TrackManager.cpp | 10 +++++++--- TrackManager.h | 6 +++--- 3 files changed, 15 insertions(+), 7 deletions(-) diff --git a/MotorDrivers.h b/MotorDrivers.h index 907c11b..9e5f85b 100644 --- a/MotorDrivers.h +++ b/MotorDrivers.h @@ -1,7 +1,7 @@ /* * © 2022-2023 Paul M. Antoine * © 2021 Fred Decker - * © 2020-2023 Harald Barth + * © 2020-2024 Harald Barth * (c) 2020 Chris Harlow. All rights reserved. * (c) 2021 Fred Decker. All rights reserved. * (c) 2020 Harald Barth. All rights reserved. @@ -57,6 +57,10 @@ // of the brake pin on the motor bridge is inverted // (HIGH == release brake) +// You can have a CS wihout any possibility to do any track signal. +// That's strange but possible. +#define NO_SHIELD F("No shield at all") + // Arduino STANDARD Motor Shield, used on different architectures: #if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32) diff --git a/TrackManager.cpp b/TrackManager.cpp index e357e7f..338b11c 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -1,6 +1,6 @@ /* * © 2022 Chris Harlow - * © 2022,2023 Harald Barth + * © 2022-2024 Harald Barth * © 2023 Colin Murdoch * All rights reserved. * @@ -41,7 +41,7 @@ MotorDriver * TrackManager::track[MAX_TRACKS]; int16_t TrackManager::trackDCAddr[MAX_TRACKS]; -byte TrackManager::lastTrack=0; +int8_t TrackManager::lastTrack=-1; bool TrackManager::progTrackSyncMain=false; bool TrackManager::progTrackBoosted=false; int16_t TrackManager::joinRelay=UNUSED_PIN; @@ -498,7 +498,11 @@ void TrackManager::setTrackPower(TRACK_MODE trackmodeToMatch, POWERMODE powermod // Set track power for this track, inependent of mode void TrackManager::setTrackPower(POWERMODE powermode, byte t) { - MotorDriver *driver=track[t]; + MotorDriver *driver=track[t]; + if (driver == NULL) { // track is not defined at all + DIAG(F("Error: Track %c does not exist"), t+'A'); + return; + } TRACK_MODE trackmode = driver->getMode(); POWERMODE oldpower = driver->getPower(); if (trackmode & TRACK_MODE_NONE) { diff --git a/TrackManager.h b/TrackManager.h index c1f314a..7dce0ee 100644 --- a/TrackManager.h +++ b/TrackManager.h @@ -1,6 +1,6 @@ /* * © 2022 Chris Harlow - * © 2022 Harald Barth + * © 2022-2024 Harald Barth * © 2023 Colin Murdoch * * All rights reserved. @@ -46,7 +46,7 @@ const byte TRACK_POWER_1=1, TRACK_POWER_ON=1; class TrackManager { public: static void Setup(const FSH * shieldName, - MotorDriver * track0, + MotorDriver * track0=NULL, MotorDriver * track1=NULL, MotorDriver * track2=NULL, MotorDriver * track3=NULL, @@ -108,7 +108,7 @@ class TrackManager { private: static void addTrack(byte t, MotorDriver* driver); - static byte lastTrack; + static int8_t lastTrack; static byte nextCycleTrack; static void applyDCSpeed(byte t); From 0587e6fc097a708d76ce002d804df9c5d3865ff0 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 18 Mar 2024 21:18:57 +0100 Subject: [PATCH 262/310] version 5.2.40 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index c5e1882..e5f3571 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202403121045Z" +#define GITHUB_SHA "devel-202403182018Z" diff --git a/version.h b/version.h index 23e7e02..27a10f0 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.39" +#define VERSION "5.2.40" +// 5.2.40 - Allow no shield // 5.2.39 - Functions for DC frequency: Use func up to F31 // 5.2.38 - Exrail MESSAGE("text") to send a user message to all // connected throttles (uses and withrottle Hmtext. From 87073b0d36ad6c2b39d3c9cc45b7692f5d45fbe1 Mon Sep 17 00:00:00 2001 From: peteGSX Date: Sat, 23 Mar 2024 13:31:34 +1000 Subject: [PATCH 263/310] Rotary Encoder address 0x67 --- IO_RotaryEncoder.h | 6 +++--- myHal.cpp_example.txt | 9 +++++---- version.h | 3 ++- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/IO_RotaryEncoder.h b/IO_RotaryEncoder.h index 9d40b34..2e6cfe7 100644 --- a/IO_RotaryEncoder.h +++ b/IO_RotaryEncoder.h @@ -42,9 +42,9 @@ * Defining in myAutomation.h requires the device driver to be included in addition to the HAL() statement. Examples: * * #include "IO_RotaryEncoder.h" -* HAL(RotaryEncoder, 700, 1, 0x70) // Define single Vpin, no feedback or position sent to rotary encoder software -* HAL(RotaryEncoder, 700, 2, 0x70) // Define two Vpins, feedback only sent to rotary encoder software -* HAL(RotaryEncoder, 700, 3, 0x70) // Define three Vpins, can send feedback and position update to rotary encoder software +* HAL(RotaryEncoder, 700, 1, 0x67) // Define single Vpin, no feedback or position sent to rotary encoder software +* HAL(RotaryEncoder, 700, 2, 0x67) // Define two Vpins, feedback only sent to rotary encoder software +* HAL(RotaryEncoder, 700, 3, 0x67) // Define three Vpins, can send feedback and position update to rotary encoder software * * Refer to the documentation for further information including the valid activities and examples. */ diff --git a/myHal.cpp_example.txt b/myHal.cpp_example.txt index 9073430..f715c63 100644 --- a/myHal.cpp_example.txt +++ b/myHal.cpp_example.txt @@ -311,12 +311,13 @@ void halSetup() { //======================================================================= // The parameters are: // firstVpin = First available Vpin to allocate - // numPins= Number of Vpins to allocate, can be either 1 or 2 - // i2cAddress = Available I2C address (default 0x70) + // numPins= Number of Vpins to allocate, can be either 1 to 3 + // i2cAddress = Available I2C address (default 0x67) //RotaryEncoder::create(firstVpin, numPins, i2cAddress); - //RotaryEncoder::create(700, 1, 0x70); - //RotaryEncoder::create(701, 2, 0x71); + //RotaryEncoder::create(700, 1, 0x67); + //RotaryEncoder::create(700, 2, 0x67); + //RotaryEncoder::create(700, 3, 0x67); //======================================================================= // The following directive defines an EX-FastClock instance. diff --git a/version.h b/version.h index 27a10f0..f292b43 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.40" +#define VERSION "5.2.41" +// 5.2.41 - Update rotary encoder default address to 0x67 // 5.2.40 - Allow no shield // 5.2.39 - Functions for DC frequency: Use func up to F31 // 5.2.38 - Exrail MESSAGE("text") to send a user message to all From c8f18e4d67e4edd87037718b4c255bd555466015 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 2 Apr 2024 00:02:09 +0200 Subject: [PATCH 264/310] ESP32 Bugfix: Uninitialized stack variable. Will bite you with infinite loop if no tracks are defined --- DCCWaveform.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp index 2d50929..3d77e9e 100644 --- a/DCCWaveform.cpp +++ b/DCCWaveform.cpp @@ -294,7 +294,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea // The resets will be zero not only now but as well repeats packets into the future clearResets(repeats+1); { - int ret; + int ret = 0; do { if(isMainTrack) { if (rmtMainChannel != NULL) From 02bf50b909c03acf22a3396ca72ee14c98ee134d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Tue, 2 Apr 2024 00:05:30 +0200 Subject: [PATCH 265/310] version --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index e5f3571..5d6ee02 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202403182018Z" +#define GITHUB_SHA "devel-202404012205Z" diff --git a/version.h b/version.h index f292b43..1f11713 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.41" +#define VERSION "5.2.42" +// 5.2.42 - ESP32 Bugfix: Uninitialized stack variable // 5.2.41 - Update rotary encoder default address to 0x67 // 5.2.40 - Allow no shield // 5.2.39 - Functions for DC frequency: Use func up to F31 From fdc956576b3478291fe33ad0d072af77f3de5865 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 01:02:49 +0200 Subject: [PATCH 266/310] ESP32 rewrite PWM LEDC to use pin mux --- DCCTimer.h | 4 +++- DCCTimerESP.cpp | 54 ++++++++++++++++++++++++++++++++++++++++++++---- MotorDriver.cpp | 6 +++--- MotorDriver.h | 3 ++- TrackManager.cpp | 23 +++++++++++++++++++-- 5 files changed, 79 insertions(+), 11 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 5cf1026..984d6eb 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -66,7 +66,9 @@ class DCCTimer { static void ackRailcomTimer(); static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency); static void DCCEXanalogWrite(uint8_t pin, int value); - + static void DCCEXledcDetachPin(uint8_t pin); + static void DCCEXanalogCopyChannel(uint8_t frompin, uint8_t topin); + static void DCCEXInrushControlOn(uint8_t pin); // Update low ram level. Allow for extra bytes to be specified // by estimation or inspection, that may be used by other // called subroutines. Must be called with interrupts disabled. diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index ae81c74..3e8d49e 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -78,6 +78,7 @@ int DCCTimer::freeMemory() { //////////////////////////////////////////////////////////////////////// #ifdef ARDUINO_ARCH_ESP32 +#include "DIAG.h" #include #include #include @@ -154,8 +155,10 @@ void DCCTimer::reset() { void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t f) { if (f >= 16) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, f); - else if (f == 7) +/* + else if (f == 7) // not used on ESP32 DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 62500); +*/ else if (f >= 4) DCCTimer::DCCEXanalogWriteFrequencyInternal(pin, 32000); else if (f >= 3) @@ -188,22 +191,65 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency } } +void DCCTimer::DCCEXledcDetachPin(uint8_t pin) { + DIAG(F("Clear pin %d channel"), pin); + pin_to_channel[pin] = 0; + pinMatrixOutDetach(pin, false, false); +} + + +void DCCTimer::DCCEXanalogCopyChannel(uint8_t frompin, uint8_t topin) { + DIAG(F("Pin %d copied to %d channel %d"), frompin, topin, pin_to_channel[frompin]); + pin_to_channel[topin] = pin_to_channel[frompin]; + ledcAttachPin(topin, pin_to_channel[topin]); +} void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { + // This allocates channels 15, 13, 11, .... + // so each channel gets its own timer. if (pin < SOC_GPIO_PIN_COUNT) { if (pin_to_channel[pin] == 0) { + int search_channel; + int n; if (!cnt_channel) { log_e("No more PWM channels available! All %u already used", LEDC_CHANNELS); return; } - pin_to_channel[pin] = --cnt_channel; - ledcSetup(cnt_channel, 1000, 8); - ledcAttachPin(pin, cnt_channel); + // search for free channels top down + for (search_channel=LEDC_CHANNELS-1; search_channel >=cnt_channel; search_channel -= 2) { + bool chanused = false; + for (n=0; n < SOC_GPIO_PIN_COUNT; n++) { + if (pin_to_channel[n] == search_channel) { // current search_channel used + chanused = true; + break; + } + } + if (chanused) + continue; + if (n == SOC_GPIO_PIN_COUNT) // current search_channel unused + break; + } + if (search_channel >= cnt_channel) { + pin_to_channel[pin] = search_channel; + DIAG(F("Pin %d assigned to search channel %d"), pin, search_channel); + } else { + pin_to_channel[pin] = --cnt_channel; // This sets 15, 13, ... + DIAG(F("Pin %d assigned to new channel %d"), pin, cnt_channel); + --cnt_channel; // Now we are at 14, 12, ... + } + ledcSetup(pin_to_channel[pin], 1000, 8); + ledcAttachPin(pin, pin_to_channel[pin]); } else { + //DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]); ledcAttachPin(pin, pin_to_channel[pin]); } ledcWrite(pin_to_channel[pin], value); } } +void DCCTimer::DCCEXInrushControlOn(uint8_t pin) { + ledcSetup(0, 62500, 8); + ledcAttachPin(pin, 0); + ledcWrite(0, 207); +} int ADCee::init(uint8_t pin) { pinMode(pin, ANALOG); diff --git a/MotorDriver.cpp b/MotorDriver.cpp index c233c22..afd8e6e 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -411,10 +411,10 @@ void MotorDriver::throttleInrush(bool on) { duty = 255-duty; #if defined(ARDUINO_ARCH_ESP32) if(on) { - DCCTimer::DCCEXanalogWrite(brakePin,duty); - DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max + DCCTimer::DCCEXInrushControlOn(brakePin); } else { - ledcDetachPin(brakePin); + ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not + // registered the pin in the pin to channel array } #elif defined(ARDUINO_ARCH_STM32) if(on) { diff --git a/MotorDriver.h b/MotorDriver.h index 4491164..945e4ee 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -193,13 +193,14 @@ class MotorDriver { } }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; + inline byte getBrakePin() { return brakePin; }; void setDCSignal(byte speedByte, uint8_t frequency=0); void throttleInrush(bool on); inline void detachDCSignal() { #if defined(__arm__) pinMode(brakePin, OUTPUT); #elif defined(ARDUINO_ARCH_ESP32) - ledcDetachPin(brakePin); + DCCTimer::DCCEXledcDetachPin(brakePin); #else setDCSignal(128); #endif diff --git a/TrackManager.cpp b/TrackManager.cpp index 338b11c..21fe44a 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -252,13 +252,32 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type } track[trackToSet]->setMode(mode); - trackDCAddr[trackToSet]=dcAddr; // When a track is switched, we must clear any side effects of its previous // state, otherwise trains run away or just dont move. // This can be done BEFORE the PWM-Timer evaluation (methinks) - if (!(mode & TRACK_MODE_DC)) { + if (mode & TRACK_MODE_DC) { + if (trackDCAddr[trackToSet] != dcAddr) { + // if we change dcAddr, detach first old signal + track[trackToSet]->detachDCSignal(); +#ifdef ARDUINO_ARCH_ESP32 + int trackfound = -1; + FOR_EACH_TRACK(t) { + if ((track[t]->getMode() & TRACK_MODE_DC) && trackDCAddr[t] == dcAddr) { + trackfound = t; + break; + } + } + if (trackfound > -1) { + DCCTimer::DCCEXanalogCopyChannel(track[trackfound]->getBrakePin(), + track[trackToSet]->getBrakePin()); + } +#endif + } + // set future DC Addr; + trackDCAddr[trackToSet]=dcAddr; + } else { // DCC tracks need to have set the PWM to zero or they will not work. track[trackToSet]->detachDCSignal(); track[trackToSet]->setBrake(false); From 6d7d2325da786a53db11612508e31a7e4f0e9f33 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 01:10:10 +0200 Subject: [PATCH 267/310] ESP32 rewrite PWM LEDC inrush duty fix --- DCCTimer.h | 2 +- DCCTimerESP.cpp | 4 ++-- MotorDriver.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 984d6eb..4ce8590 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -68,7 +68,7 @@ class DCCTimer { static void DCCEXanalogWrite(uint8_t pin, int value); static void DCCEXledcDetachPin(uint8_t pin); static void DCCEXanalogCopyChannel(uint8_t frompin, uint8_t topin); - static void DCCEXInrushControlOn(uint8_t pin); + static void DCCEXInrushControlOn(uint8_t pin, int duty); // Update low ram level. Allow for extra bytes to be specified // by estimation or inspection, that may be used by other // called subroutines. Must be called with interrupts disabled. diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index 3e8d49e..b651a49 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -245,10 +245,10 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { ledcWrite(pin_to_channel[pin], value); } } -void DCCTimer::DCCEXInrushControlOn(uint8_t pin) { +void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty) { ledcSetup(0, 62500, 8); ledcAttachPin(pin, 0); - ledcWrite(0, 207); + ledcWrite(0, duty); } int ADCee::init(uint8_t pin) { diff --git a/MotorDriver.cpp b/MotorDriver.cpp index afd8e6e..235f557 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -411,7 +411,7 @@ void MotorDriver::throttleInrush(bool on) { duty = 255-duty; #if defined(ARDUINO_ARCH_ESP32) if(on) { - DCCTimer::DCCEXInrushControlOn(brakePin); + DCCTimer::DCCEXInrushControlOn(brakePin, duty); } else { ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not // registered the pin in the pin to channel array From 84b90ae75775f8ea22cc523bdbc663f1d508071e Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 01:11:12 +0200 Subject: [PATCH 268/310] Booster mode inrush throttle, too --- MotorDriver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 235f557..47c359e 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -404,7 +404,7 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) void MotorDriver::throttleInrush(bool on) { if (brakePin == UNUSED_PIN) return; - if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT))) + if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT | TRACK_MODE_BOOST))) return; byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec if (invertBrake) From cff407593713f09fdc6d701c3aba742dba49f786 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 01:12:08 +0200 Subject: [PATCH 269/310] version 5.2.43 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 5d6ee02..821e344 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404012205Z" +#define GITHUB_SHA "devel-202404042311Z" diff --git a/version.h b/version.h index 1f11713..58d0cb6 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.42" +#define VERSION "5.2.43" +// 5.2.43 - ESP32 rewrite PWM LEDC to use pin mux // 5.2.42 - ESP32 Bugfix: Uninitialized stack variable // 5.2.41 - Update rotary encoder default address to 0x67 // 5.2.40 - Allow no shield From dc5f5e05b9530a8b950c6382042fd19c2dbea76c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 14:05:12 +0200 Subject: [PATCH 270/310] ESP32 fix PWM LEDC inverted pin mode --- DCCTimer.h | 8 ++++--- DCCTimerESP.cpp | 58 +++++++++++++++++++++++++++++++++++++++-------- DCCTimerSTM32.cpp | 4 +++- MotorDriver.cpp | 14 ++++++------ MotorDriver.h | 2 +- TrackManager.cpp | 10 +++++--- 6 files changed, 71 insertions(+), 25 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 4ce8590..44c85f2 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -65,10 +65,12 @@ class DCCTimer { static void startRailcomTimer(byte brakePin); static void ackRailcomTimer(); static void DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency); - static void DCCEXanalogWrite(uint8_t pin, int value); + static void DCCEXanalogWrite(uint8_t pin, int value, bool invert); static void DCCEXledcDetachPin(uint8_t pin); - static void DCCEXanalogCopyChannel(uint8_t frompin, uint8_t topin); - static void DCCEXInrushControlOn(uint8_t pin, int duty); + static void DCCEXanalogCopyChannel(int8_t frompin, int8_t topin); + static void DCCEXInrushControlOn(uint8_t pin, int duty, bool invert); + static void DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted); + // Update low ram level. Allow for extra bytes to be specified // by estimation or inspection, that may be used by other // called subroutines. Must be called with interrupts disabled. diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index b651a49..93711aa 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -197,13 +197,48 @@ void DCCTimer::DCCEXledcDetachPin(uint8_t pin) { pinMatrixOutDetach(pin, false, false); } +static byte LEDCToMux[] = { + LEDC_HS_SIG_OUT0_IDX, + LEDC_HS_SIG_OUT1_IDX, + LEDC_HS_SIG_OUT2_IDX, + LEDC_HS_SIG_OUT3_IDX, + LEDC_HS_SIG_OUT4_IDX, + LEDC_HS_SIG_OUT5_IDX, + LEDC_HS_SIG_OUT6_IDX, + LEDC_HS_SIG_OUT7_IDX, + LEDC_LS_SIG_OUT0_IDX, + LEDC_LS_SIG_OUT1_IDX, + LEDC_LS_SIG_OUT2_IDX, + LEDC_LS_SIG_OUT3_IDX, + LEDC_LS_SIG_OUT4_IDX, + LEDC_LS_SIG_OUT5_IDX, + LEDC_LS_SIG_OUT6_IDX, + LEDC_LS_SIG_OUT7_IDX, +}; -void DCCTimer::DCCEXanalogCopyChannel(uint8_t frompin, uint8_t topin) { - DIAG(F("Pin %d copied to %d channel %d"), frompin, topin, pin_to_channel[frompin]); - pin_to_channel[topin] = pin_to_channel[frompin]; - ledcAttachPin(topin, pin_to_channel[topin]); +void DCCTimer::DCCEXledcAttachPin(uint8_t pin, int8_t channel, bool inverted) { + DIAG(F("Attaching pin %d to channel %d %c"), pin, channel, inverted ? 'I' : ' '); + ledcAttachPin(pin, channel); + if (inverted) // we attach again but with inversion + gpio_matrix_out(pin, LEDCToMux[channel], inverted, 0); } -void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { + +void DCCTimer::DCCEXanalogCopyChannel(int8_t frompin, int8_t topin) { + // arguments are signed depending on inversion of pins + DIAG(F("Pin %d copied to %d"), frompin, topin); + bool inverted = false; + if (frompin<0) + frompin = -frompin; + if (topin<0) { + inverted = true; + topin = -topin; + } + int channel = pin_to_channel[frompin]; // after abs(frompin) + pin_to_channel[topin] = channel; + DCCTimer::DCCEXledcAttachPin(topin, channel, inverted); +} + +void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) { // This allocates channels 15, 13, 11, .... // so each channel gets its own timer. if (pin < SOC_GPIO_PIN_COUNT) { @@ -237,17 +272,20 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { --cnt_channel; // Now we are at 14, 12, ... } ledcSetup(pin_to_channel[pin], 1000, 8); - ledcAttachPin(pin, pin_to_channel[pin]); + DCCEXledcAttachPin(pin, pin_to_channel[pin], invert); } else { - //DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]); - ledcAttachPin(pin, pin_to_channel[pin]); + // This else is only here so we can enable diag + // Pin should be already attached to channel + // DIAG(F("Pin %d assigned to old channel %d"), pin, pin_to_channel[pin]); } ledcWrite(pin_to_channel[pin], value); } } -void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty) { + +void DCCTimer::DCCEXInrushControlOn(uint8_t pin, int duty, bool inverted) { + // this uses hardcoded channel 0 ledcSetup(0, 62500, 8); - ledcAttachPin(pin, 0); + DCCEXledcAttachPin(pin, 0, inverted); ledcWrite(0, duty); } diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index 43c8ece..0c1d5d6 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -333,7 +333,9 @@ void DCCTimer::DCCEXanalogWriteFrequencyInternal(uint8_t pin, uint32_t frequency return; } -void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) { +void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) { + if (invert) + value = 255-value; // Calculate percentage duty cycle from value given uint32_t duty_cycle = (value * 100 / 256) + 1; if (pin_timer[pin] != NULL) { diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 47c359e..1ab52d8 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -336,8 +336,6 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) if (tSpeed <= 1) brake = 255; else if (tSpeed >= 127) brake = 0; else brake = 2 * (128-tSpeed); - if (invertBrake) - brake=255-brake; { // new block because of variable f #if defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_STM32) @@ -351,10 +349,10 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) #endif //DIAG(F("Brake pin %d freqency %d"), brakePin, f); DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency - DCCTimer::DCCEXanalogWrite(brakePin,brake); + DCCTimer::DCCEXanalogWrite(brakePin, brake, invertBrake); #else // all AVR here DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps - analogWrite(brakePin,brake); + analogWrite(brakePin, invertBrake ? 255-brake : brake); #endif } @@ -407,16 +405,16 @@ void MotorDriver::throttleInrush(bool on) { if ( !(trackMode & (TRACK_MODE_MAIN | TRACK_MODE_PROG | TRACK_MODE_EXT | TRACK_MODE_BOOST))) return; byte duty = on ? 207 : 0; // duty of 81% at 62500Hz this gives pauses of 3usec - if (invertBrake) - duty = 255-duty; #if defined(ARDUINO_ARCH_ESP32) if(on) { - DCCTimer::DCCEXInrushControlOn(brakePin, duty); + DCCTimer::DCCEXInrushControlOn(brakePin, duty, invertBrake); } else { ledcDetachPin(brakePin); // not DCCTimer::DCCEXledcDetachPin() as we have not // registered the pin in the pin to channel array } #elif defined(ARDUINO_ARCH_STM32) + if (invertBrake) + duty = 255-duty; if(on) { DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max DCCTimer::DCCEXanalogWrite(brakePin,duty); @@ -424,6 +422,8 @@ void MotorDriver::throttleInrush(bool on) { pinMode(brakePin, OUTPUT); } #else // all AVR here + if (invertBrake) + duty = 255-duty; if(on){ DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max } diff --git a/MotorDriver.h b/MotorDriver.h index 945e4ee..a6ed1f6 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -193,7 +193,7 @@ class MotorDriver { } }; inline pinpair getSignalPin() { return pinpair(signalPin,signalPin2); }; - inline byte getBrakePin() { return brakePin; }; + inline int8_t getBrakePinSigned() { return invertBrake ? -brakePin : brakePin; }; void setDCSignal(byte speedByte, uint8_t frequency=0); void throttleInrush(bool on); inline void detachDCSignal() { diff --git a/TrackManager.cpp b/TrackManager.cpp index 21fe44a..06b6a18 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -264,14 +264,18 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr #ifdef ARDUINO_ARCH_ESP32 int trackfound = -1; FOR_EACH_TRACK(t) { - if ((track[t]->getMode() & TRACK_MODE_DC) && trackDCAddr[t] == dcAddr) { + //DIAG(F("Checking track %c mode %x dcAddr %d"), 'A'+t, track[t]->getMode(), trackDCAddr[t]); + if (t != trackToSet // not our track + && (track[t]->getMode() & TRACK_MODE_DC) // right mode + && trackDCAddr[t] == dcAddr) { // right addr + //DIAG(F("Found track %c"), 'A'+t); trackfound = t; break; } } if (trackfound > -1) { - DCCTimer::DCCEXanalogCopyChannel(track[trackfound]->getBrakePin(), - track[trackToSet]->getBrakePin()); + DCCTimer::DCCEXanalogCopyChannel(track[trackfound]->getBrakePinSigned(), + track[trackToSet]->getBrakePinSigned()); } #endif } From d367f5dc8174230057e880f93016581e4ecdef7a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 14:06:36 +0200 Subject: [PATCH 271/310] version 5.2.44 --- GITHUB_SHA.h | 2 +- version.h | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 821e344..0bcb861 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404042311Z" +#define GITHUB_SHA "devel-202404051206Z" diff --git a/version.h b/version.h index 58d0cb6..6f25b47 100644 --- a/version.h +++ b/version.h @@ -3,8 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.43" -// 5.2.43 - ESP32 rewrite PWM LEDC to use pin mux +#define VERSION "5.2.44" +// 5.2.44 - ESP32 fix PWM LEDC inverted pin mode +// ESP32 rewrite PWM LEDC to use pin mux // 5.2.42 - ESP32 Bugfix: Uninitialized stack variable // 5.2.41 - Update rotary encoder default address to 0x67 // 5.2.40 - Allow no shield From 7b77d4ce1e9d679cf703da37ac91221a9f57e54b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 14:08:39 +0200 Subject: [PATCH 272/310] STM32 fix inverted pin mode --- MotorDriver.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 1ab52d8..8662ca1 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -413,11 +413,9 @@ void MotorDriver::throttleInrush(bool on) { // registered the pin in the pin to channel array } #elif defined(ARDUINO_ARCH_STM32) - if (invertBrake) - duty = 255-duty; if(on) { DCCTimer::DCCEXanalogWriteFrequency(brakePin, 7); // 7 means max - DCCTimer::DCCEXanalogWrite(brakePin,duty); + DCCTimer::DCCEXanalogWrite(brakePin,duty,invertBrake); } else { pinMode(brakePin, OUTPUT); } From f581d56bdce137c532607ee5d2368a24de88b4b9 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 20:30:26 +0200 Subject: [PATCH 273/310] ESP32 set frequency after DC speed --- MotorDriver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 8662ca1..66d1b71 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -347,9 +347,9 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) } } #endif - //DIAG(F("Brake pin %d freqency %d"), brakePin, f); - DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency + //DIAG(F("Brake pin %d value %d freqency %d"), brakePin, brake, f); DCCTimer::DCCEXanalogWrite(brakePin, brake, invertBrake); + DCCTimer::DCCEXanalogWriteFrequency(brakePin, f); // set DC PWM frequency #else // all AVR here DCCTimer::DCCEXanalogWriteFrequency(brakePin, frequency); // frequency steps analogWrite(brakePin, invertBrake ? 255-brake : brake); From e4a3aa9f1e42afc248e75c88aba428d2c599c065 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Fri, 5 Apr 2024 20:31:05 +0200 Subject: [PATCH 274/310] tag --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 0bcb861..5588243 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404051206Z" +#define GITHUB_SHA "devel-202404051830Z" From 1a307eea3debf251107a78dd5ec7e0847fe850fb Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 6 Apr 2024 13:19:56 +0100 Subject: [PATCH 275/310] Extended consist and --- DCC.cpp | 43 ++++++++++++++++++++++++++++++++++++++++--- DCCACK.cpp | 17 +++++++++++++++++ DCCACK.h | 2 ++ 3 files changed, 59 insertions(+), 3 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index a8bc953..f2ab8c3 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -325,8 +325,8 @@ preamble -0- 1 0 A7 A6 A5 A4 A3 A2 -0- 0 ^A10 ^A9 ^A8 0 A1 A0 1 -0- .... Thus in byte packet form the format is 10AAAAAA, 0AAA0AA1, 000XXXXX -Die Adresse für den ersten erweiterten Zubehördecoder ist wie bei den einfachen -Zubehördecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in +Die Adresse f�r den ersten erweiterten Zubeh�rdecoder ist wie bei den einfachen +Zubeh�rdecodern die Adresse 4 = 1000-0001 0111-0001 . Diese Adresse wird in Anwenderdialogen als Adresse 1 dargestellt. This means that the first address shown to the user as "1" is mapped @@ -500,6 +500,36 @@ const ackOp FLASH READ_CV_PROG[] = { const ackOp FLASH LOCO_ID_PROG[] = { BASELINE, + // first check cv20 for extended addressing + SETCV, (ackOp)20, // CV 19 is extended + SETBYTE, (ackOp)0, + VB, WACK, ITSKIP, // skip past extended section if cv20 is zero + // read cv20 and 19 and merge + STARTMERGE, // Setup to read cv 20 + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + VB, WACK, NAKSKIP, // bad read of cv20, assume its 0 + STASHLOCOID, // keep cv 20 until we have cv19 as well. + SETCV, (ackOp)19, + STARTMERGE, // Setup to read cv 19 + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + V0, WACK, MERGE, + VB, WACK, NAKFAIL, // cant recover if cv 19 unreadable + COMBINE1920, // Combile byte with stash and callback +// end of advanced 20,19 check + SKIPTARGET, SETCV, (ackOp)19, // CV 19 is consist setting SETBYTE, (ackOp)0, VB, WACK, ITSKIP, // ignore consist if cv19 is zero (no consist) @@ -566,6 +596,10 @@ const ackOp FLASH LOCO_ID_PROG[] = { const ackOp FLASH SHORT_LOCO_ID_PROG[] = { BASELINE, + // Clear consist CV 19,20 + SETCV,(ackOp)20, + SETBYTE, (ackOp)0, + WB,WACK, // ignore dedcoder without cv20 support SETCV,(ackOp)19, SETBYTE, (ackOp)0, WB,WACK, // ignore dedcoder without cv19 support @@ -583,7 +617,10 @@ const ackOp FLASH SHORT_LOCO_ID_PROG[] = { const ackOp FLASH LONG_LOCO_ID_PROG[] = { BASELINE, - // Clear consist CV 19 + // Clear consist CV 19,20 + SETCV,(ackOp)20, + SETBYTE, (ackOp)0, + WB,WACK, // ignore dedcoder without cv20 support SETCV,(ackOp)19, SETBYTE, (ackOp)0, WB,WACK, // ignore decoder without cv19 support diff --git a/DCCACK.cpp b/DCCACK.cpp index 8a074b4..517d513 100644 --- a/DCCACK.cpp +++ b/DCCACK.cpp @@ -314,6 +314,14 @@ void DCCACK::loop() { callback( LONG_ADDR_MARKER | ( ackManagerByte + ((ackManagerStash - 192) << 8))); return; + case COMBINE1920: + // ackManagerStash is cv20, ackManagerByte is CV 19 + // This will not be called if cv20==0 + ackManagerByte &= 0x7F; // ignore direction marker + ackManagerByte %=100; // take last 2 decimal digits + callback( ackManagerStash*100+ackManagerByte); + return; + case ITSKIP: if (!ackReceived) break; // SKIP opcodes until SKIPTARGET found @@ -322,6 +330,15 @@ void DCCACK::loop() { opcode=GETFLASH(ackManagerProg); } break; + + case NAKSKIP: + if (ackReceived) break; + // SKIP opcodes until SKIPTARGET found + while (opcode!=SKIPTARGET) { + ackManagerProg++; + opcode=GETFLASH(ackManagerProg); + } + break; case SKIPTARGET: break; default: diff --git a/DCCACK.h b/DCCACK.h index 7d39319..fa03387 100644 --- a/DCCACK.h +++ b/DCCACK.h @@ -56,6 +56,8 @@ enum ackOp : byte STASHLOCOID, // keeps current byte value for later COMBINELOCOID, // combines current value with stashed value and returns it ITSKIP, // skip to SKIPTARGET if ack true + NAKSKIP, // skip to SKIPTARGET if ack false + COMBINE1920, // combine cvs 19 and 20 and callback SKIPTARGET = 0xFF // jump to target }; From 38a9585a412a9ae1b492a031b2d785e3eab4e66f Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 6 Apr 2024 19:46:23 +0200 Subject: [PATCH 276/310] ESP32 Trackmanager reset cab number to 0 when track is not DC --- TrackManager.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index 06b6a18..d66b999 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -38,8 +38,8 @@ if (track[t]->getMode()==findmode) \ track[t]->function; -MotorDriver * TrackManager::track[MAX_TRACKS]; -int16_t TrackManager::trackDCAddr[MAX_TRACKS]; +MotorDriver * TrackManager::track[MAX_TRACKS] = { NULL }; +int16_t TrackManager::trackDCAddr[MAX_TRACKS] = { 0 }; int8_t TrackManager::lastTrack=-1; bool TrackManager::progTrackSyncMain=false; @@ -251,7 +251,6 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr } else { track[trackToSet]->makeProgTrack(false); // only the prog track knows it's type } - track[trackToSet]->setMode(mode); // When a track is switched, we must clear any side effects of its previous // state, otherwise trains run away or just dont move. @@ -259,8 +258,13 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr // This can be done BEFORE the PWM-Timer evaluation (methinks) if (mode & TRACK_MODE_DC) { if (trackDCAddr[trackToSet] != dcAddr) { - // if we change dcAddr, detach first old signal - track[trackToSet]->detachDCSignal(); + // new or changed DC Addr, run the new setup + if (trackDCAddr[trackToSet] != 0) { + // if we change dcAddr and not only + // change from another mode, + // first detach old DC signal + track[trackToSet]->detachDCSignal(); + } #ifdef ARDUINO_ARCH_ESP32 int trackfound = -1; FOR_EACH_TRACK(t) { @@ -285,7 +289,9 @@ bool TrackManager::setTrackMode(byte trackToSet, TRACK_MODE mode, int16_t dcAddr // DCC tracks need to have set the PWM to zero or they will not work. track[trackToSet]->detachDCSignal(); track[trackToSet]->setBrake(false); + trackDCAddr[trackToSet]=0; // clear that an addr is set for DC as this is not a DC track } + track[trackToSet]->setMode(mode); // BOOST: // Leave it as is From 6b713bf57c95565879fb5cbe2552ffa71d9b8d00 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 6 Apr 2024 19:48:02 +0200 Subject: [PATCH 277/310] version 5.2.45 --- GITHUB_SHA.h | 2 +- version.h | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 5588243..a9ab348 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404051830Z" +#define GITHUB_SHA "devel-202404061747Z" diff --git a/version.h b/version.h index 6f25b47..2af0a55 100644 --- a/version.h +++ b/version.h @@ -3,8 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.44" -// 5.2.44 - ESP32 fix PWM LEDC inverted pin mode +#define VERSION "5.2.45" +// 5.2.45 - ESP32 Trackmanager reset cab number to 0 when track is not DC +// ESP32 fix PWM LEDC inverted pin mode // ESP32 rewrite PWM LEDC to use pin mux // 5.2.42 - ESP32 Bugfix: Uninitialized stack variable // 5.2.41 - Update rotary encoder default address to 0x67 From f41f61dd5fc1adb8e0445f8fbfb4c3f8011d089a Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 6 Apr 2024 23:41:25 +0100 Subject: [PATCH 278/310] 10239) { //0x27FF according to standard + callback(-1); + return; + } + byte cv20; + byte cv19; + + if (id<=HIGHEST_SHORT_ADDR) { + cv19=id; + cv20=0; + } + else { + cv20=id/100; + cv19=id%100; + } + if (reverse) cv19|=0x80; + DCCACK::Setup((cv20<<8)|cv19, CONSIST_ID_PROG, callback); +} + void DCC::forgetLoco(int cab) { // removes any speed reminders for this loco setThrottle2(cab,1); // ESTOP this loco if still on track int reg=lookupSpeedTable(cab, false); diff --git a/DCC.h b/DCC.h index 4503227..4bc222c 100644 --- a/DCC.h +++ b/DCC.h @@ -85,7 +85,7 @@ public: static void getLocoId(ACK_CALLBACK callback); static void setLocoId(int id,ACK_CALLBACK callback); - + static void setConsistId(int id,bool reverse,ACK_CALLBACK callback); // Enhanced API functions static void forgetLoco(int cab); // removes any speed reminders for this loco static void forgetAllLocos(); // removes all speed reminders diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index fa4c9f8..6e41473 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -458,6 +458,9 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) DCC::setLocoId(p[0],callback_Wloco); else if (params == 4) // WRITE CV ON PROG DCC::writeCVByte(p[0], p[1], callback_W4); + else if ((params==2 | params==3 ) && p[0]=="CONSIST"_hk ) { + DCC::setConsistId(p[1],p[2]=="REVERSE"_hk,callback_Wconsist); + } else if (params == 2) // WRITE CV ON PROG DCC::writeCVByte(p[0], p[1], callback_W); else @@ -1347,3 +1350,11 @@ void DCCEXParser::callback_Wloco(int16_t result) StringFormatter::send(getAsyncReplyStream(), F("\n"), result); commitAsyncReplyStream(); } + +void DCCEXParser::callback_Wconsist(int16_t result) +{ + if (result==1) result=stashP[1]; // pick up original requested id from command + StringFormatter::send(getAsyncReplyStream(), F("\n"), + result, stashP[2]=="REVERSE"_hk ? F(" REVERSE") : F("")); + commitAsyncReplyStream(); +} diff --git a/DCCEXParser.h b/DCCEXParser.h index 3c3382c..d3b7851 100644 --- a/DCCEXParser.h +++ b/DCCEXParser.h @@ -71,6 +71,7 @@ struct DCCEXParser static void callback_R(int16_t result); static void callback_Rloco(int16_t result); static void callback_Wloco(int16_t result); + static void callback_Wconsist(int16_t result); static void callback_Vbit(int16_t result); static void callback_Vbyte(int16_t result); static FILTER_CALLBACK filterCallback; From 182479c07b4d0bc00ff4bbe2a1077284e3f32216 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 6 Apr 2024 23:49:26 +0100 Subject: [PATCH 279/310] Consist version. --- DCC.cpp | 2 +- DCCEXParser.cpp | 2 +- version.h | 4 +++- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/DCC.cpp b/DCC.cpp index 2ed75f1..0aa623f 100644 --- a/DCC.cpp +++ b/DCC.cpp @@ -703,7 +703,7 @@ void DCC::setLocoId(int id,ACK_CALLBACK callback) { } void DCC::setConsistId(int id,bool reverse,ACK_CALLBACK callback) { - if (id<1 || id>10239) { //0x27FF according to standard + if (id<0 || id>10239) { //0x27FF according to standard callback(-1); return; } diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index 6e41473..a8180ec 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -458,7 +458,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) DCC::setLocoId(p[0],callback_Wloco); else if (params == 4) // WRITE CV ON PROG DCC::writeCVByte(p[0], p[1], callback_W4); - else if ((params==2 | params==3 ) && p[0]=="CONSIST"_hk ) { + else if ((params==2 || params==3 ) && p[0]=="CONSIST"_hk ) { DCC::setConsistId(p[1],p[2]=="REVERSE"_hk,callback_Wconsist); } else if (params == 2) // WRITE CV ON PROG diff --git a/version.h b/version.h index 2af0a55..a772201 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.45" +#define VERSION "5.2.46" +// 5.2.46 - Support for extended consist CV20 in and +// - New cmd to handle long/short consist ids // 5.2.45 - ESP32 Trackmanager reset cab number to 0 when track is not DC // ESP32 fix PWM LEDC inverted pin mode // ESP32 rewrite PWM LEDC to use pin mux From 263c3d01e3fc841a0623a27c98d3b8615159c04d Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 7 Apr 2024 09:26:32 +0200 Subject: [PATCH 280/310] DISABLE_DIAG by default for Uno and Nano --- config.example.h | 13 +++++++++++++ defines.h | 6 ++++++ 2 files changed, 19 insertions(+) diff --git a/config.example.h b/config.example.h index a2e08b2..3fc86c3 100644 --- a/config.example.h +++ b/config.example.h @@ -211,6 +211,19 @@ The configuration file for DCC-EX Command Station // #define DISABLE_VDPY // #define ENABLE_VDPY +///////////////////////////////////////////////////////////////////////////////////// +// DISABLE / ENABLE DIAG +// +// To diagose different errors, you can turn on differnet messages. This costs +// program memory which we do not have enough on the Uno and Nano, so it is +// by default DISABLED on those. If you think you can fit it (for example +// having disabled some of the features above) you can enable it with +// ENABLE_DIAG. You can even disable it on all other CPUs with +// DISABLE_DIAG +// +// #define DISABLE_DIAG +// #define ENABLE_DIAG + ///////////////////////////////////////////////////////////////////////////////////// // REDEFINE WHERE SHORT/LONG ADDR break is. According to NMRA the last short address // is 127 and the first long address is 128. There are manufacturers which have diff --git a/defines.h b/defines.h index 14dd1c5..2c3ee55 100644 --- a/defines.h +++ b/defines.h @@ -220,9 +220,15 @@ // #if defined(ARDUINO_AVR_NANO) || defined(ARDUINO_AVR_UNO) #define IO_NO_HAL // HAL too big whatever you disable otherwise + #ifndef ENABLE_VDPY #define DISABLE_VDPY #endif + +#ifndef ENABLE_DIAG +#define DISABLE_DIAG +#endif + #endif #if __has_include ( "myAutomation.h") From 5ea6feb11aac6854a903d7fa8cd0ecc3e1ebb330 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 9 Apr 2024 20:45:28 +0100 Subject: [PATCH 281/310] Squashed commit of the following: commit 8987d622e60fb27174203ce47b49462a01ecb61c Author: Asbelos Date: Tue Apr 9 20:44:47 2024 +0100 doc note commit 8f0a5c1ec0fde18dbb262311a1ef5ef79d571807 Author: Asbelos Date: Thu Apr 4 09:45:58 2024 +0100 Exrail notes commit 94083b9ab8a2322c39b7087c522730569194b732 Merge: 72ef199 02bf50b Author: Asbelos Date: Thu Apr 4 09:08:26 2024 +0100 Merge branch 'devel' into devel_chris commit 72ef199315d1c7717331864abb11730890fd3162 Author: Asbelos Date: Thu Apr 4 09:06:50 2024 +0100 TOGGLE_TURNOUT commit e69b777a2f62104dd8b74ba688b950fa92919d54 Author: Asbelos Date: Wed Apr 3 15:17:40 2024 +0100 BLINK command commit c7ed47400d5d89c0b8425ec12b1828e710fb23ec Author: Asbelos Date: Tue Apr 2 10:12:45 2024 +0100 FTOGGLE,XFTOGGLE commit 7a93cf7be856afd30f6976a483b1db4bfc4073a1 Author: Asbelos Date: Fri Mar 29 13:21:35 2024 +0000 EXRAIL STEALTH_GLOBAL --- DCCEXParser.cpp | 1 + EXRAIL2.cpp | 79 ++++++++++++++++++++++--- EXRAIL2.h | 18 +++++- EXRAIL2MacroReset.h | 11 ++++ EXRAIL2Parser.cpp | 21 +++++-- EXRAILMacros.h | 13 ++++ Release_Notes/EXRAIL additions.md | 38 ++++++++++++ Release_Notes/Exrail mods.txt | 98 +++++++++++++++++++++++++++++++ 8 files changed, 262 insertions(+), 17 deletions(-) create mode 100644 Release_Notes/EXRAIL additions.md create mode 100644 Release_Notes/Exrail mods.txt diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index a8180ec..b9ac3a9 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -800,6 +800,7 @@ void DCCEXParser::parseOne(Print *stream, byte *com, RingStream * ringStream) break; #endif + case '/': // implemented in EXRAIL parser case 'L': // LCC interface implemented in EXRAIL parser break; // Will if not intercepted by EXRAIL diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index c9c6716..ef4387c 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -373,7 +373,7 @@ RMFT2::RMFT2(int progCtr) { speedo=0; forward=true; invert=false; - timeoutFlag=false; + blinkState=not_blink_task; stackDepth=0; onEventStartPosition=-1; // Not handling an ONxxx @@ -491,6 +491,23 @@ void RMFT2::loop() { void RMFT2::loop2() { if (delayTime!=0 && millis()-delayStart < delayTime) return; + // special stand alone blink task + if (compileFeatures & FEATURE_BLINK) { + if (blinkState==blink_low) { + IODevice::write(blinkPin,HIGH); + blinkState=blink_high; + delayMe(getOperand(1)); + return; + } + if (blinkState==blink_high) { + IODevice::write(blinkPin,LOW); + blinkState=blink_low; + delayMe(getOperand(2)); + return; + } + } + + // Normal progstep following tasks continue here. byte opcode = GET_OPCODE; int16_t operand = getOperand(0); @@ -511,6 +528,10 @@ void RMFT2::loop2() { Turnout::setClosed(operand, true); break; + case OPCODE_TOGGLE_TURNOUT: + Turnout::setClosed(operand, Turnout::isThrown(operand)); + break; + #ifndef IO_NO_HAL case OPCODE_ROTATE: uint8_t activity; @@ -560,39 +581,39 @@ void RMFT2::loop2() { break; case OPCODE_AT: - timeoutFlag=false; + blinkState=not_blink_task; if (readSensor(operand)) break; delayMe(50); return; case OPCODE_ATGTE: // wait for analog sensor>= value - timeoutFlag=false; + blinkState=not_blink_task; if (IODevice::readAnalogue(operand) >= (int)(getOperand(1))) break; delayMe(50); return; case OPCODE_ATLT: // wait for analog sensor < value - timeoutFlag=false; + blinkState=not_blink_task; if (IODevice::readAnalogue(operand) < (int)(getOperand(1))) break; delayMe(50); return; case OPCODE_ATTIMEOUT1: // ATTIMEOUT(vpin,timeout) part 1 timeoutStart=millis(); - timeoutFlag=false; + blinkState=not_blink_task; break; case OPCODE_ATTIMEOUT2: if (readSensor(operand)) break; // success without timeout if (millis()-timeoutStart > 100*getOperand(1)) { - timeoutFlag=true; + blinkState=at_timeout; break; // and drop through } delayMe(50); return; case OPCODE_IFTIMEOUT: // do next operand if timeout flag set - skipIf=!timeoutFlag; + skipIf=blinkState!=at_timeout; break; case OPCODE_AFTER: // waits for sensor to hit and then remain off for 0.5 seconds. (must come after an AT operation) @@ -624,13 +645,25 @@ void RMFT2::loop2() { break; case OPCODE_SET: + killBlinkOnVpin(operand); IODevice::write(operand,true); break; case OPCODE_RESET: + killBlinkOnVpin(operand); IODevice::write(operand,false); break; - + + case OPCODE_BLINK: + // Start a new task to blink this vpin + killBlinkOnVpin(operand); + { + auto newtask=new RMFT2(progCounter); + newtask->blinkPin=operand; + newtask->blinkState=blink_low; // will go high on first call + } + break; + case OPCODE_PAUSE: DCC::setThrottle(0,1,true); // pause all locos on the track pausingTask=this; @@ -815,6 +848,10 @@ void RMFT2::loop2() { case OPCODE_FOFF: if (loco) DCC::setFn(loco,operand,false); break; + + case OPCODE_FTOGGLE: + if (loco) DCC::changeFn(loco,operand); + break; case OPCODE_DRIVE: { @@ -830,6 +867,10 @@ void RMFT2::loop2() { case OPCODE_XFOFF: DCC::setFn(operand,getOperand(1),false); break; + + case OPCODE_XFTOGGLE: + DCC::changeFn(operand,getOperand(1)); + break; case OPCODE_DCCACTIVATE: { // operand is address<<3 | subaddr<<1 | active @@ -1167,16 +1208,19 @@ int16_t RMFT2::getSignalSlot(int16_t id) { if (redpin) { bool redval=(rag==SIGNAL_RED || rag==SIMAMBER); if (!aHigh) redval=!redval; + killBlinkOnVpin(redpin); IODevice::write(redpin,redval); } if (amberpin) { bool amberval=(rag==SIGNAL_AMBER); if (!aHigh) amberval=!amberval; + killBlinkOnVpin(amberpin); IODevice::write(amberpin,amberval); } if (greenpin) { bool greenval=(rag==SIGNAL_GREEN || rag==SIMAMBER); if (!aHigh) greenval=!greenval; + killBlinkOnVpin(greenpin); IODevice::write(greenpin,greenval); } } @@ -1264,6 +1308,25 @@ void RMFT2::powerEvent(int16_t track, bool overload) { } } +// This function is used when setting pins so that a SET or RESET +// will cause any blink task on that pin to terminate. +// It will be compiled out of existence if no BLINK feature is used. +void RMFT2::killBlinkOnVpin(VPIN pin) { + if (!(compileFeatures & FEATURE_BLINK)) return; + + RMFT2 * task=loopTask; + while(task) { + if ( + (task->blinkState==blink_high || task->blinkState==blink_low) + && task->blinkPin==pin) { + task->kill(); + return; + } + task=task->next; + if (task==loopTask) return; + } +} + void RMFT2::startNonRecursiveTask(const FSH* reason, int16_t id,int pc) { // Check we dont already have a task running this handler RMFT2 * task=loopTask; diff --git a/EXRAIL2.h b/EXRAIL2.h index f4cf320..7075f26 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -33,7 +33,7 @@ // or more OPCODE_PAD instructions with the subsequent parameters. This wastes a byte but makes // searching easier as a parameter can never be confused with an opcode. // -enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, +enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT, OPCODE_FWD,OPCODE_REV,OPCODE_SPEED,OPCODE_INVERT_DIRECTION, OPCODE_RESERVE,OPCODE_FREE, OPCODE_AT,OPCODE_AFTER, @@ -41,9 +41,11 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE, OPCODE_ATGTE,OPCODE_ATLT, OPCODE_ATTIMEOUT1,OPCODE_ATTIMEOUT2, OPCODE_LATCH,OPCODE_UNLATCH,OPCODE_SET,OPCODE_RESET, + OPCODE_BLINK, OPCODE_ENDIF,OPCODE_ELSE, OPCODE_DELAY,OPCODE_DELAYMINS,OPCODE_DELAYMS,OPCODE_RANDWAIT, OPCODE_FON,OPCODE_FOFF,OPCODE_XFON,OPCODE_XFOFF, + OPCODE_FTOGGLE,OPCODE_XFTOGGLE, OPCODE_RED,OPCODE_GREEN,OPCODE_AMBER,OPCODE_DRIVE, OPCODE_SERVO,OPCODE_SIGNAL,OPCODE_TURNOUT,OPCODE_WAITFOR, OPCODE_PAD,OPCODE_FOLLOW,OPCODE_CALL,OPCODE_RETURN, @@ -98,12 +100,21 @@ enum thrunger: byte { thrunge_lcd, // Must be last!! }; + +enum BlinkState: byte { + not_blink_task, + blink_low, // blink task running with pin LOW + blink_high, // blink task running with pin high + at_timeout // ATTIMEOUT timed out flag + }; + // Flag bits for compile time features. static const byte FEATURE_SIGNAL= 0x80; static const byte FEATURE_LCC = 0x40; static const byte FEATURE_ROSTER= 0x20; static const byte FEATURE_ROUTESTATE= 0x10; static const byte FEATURE_STASH = 0x08; + static const byte FEATURE_BLINK = 0x04; // Flag bits for status of hardware and TPL @@ -192,6 +203,7 @@ private: static LookList* LookListLoader(OPCODE op1, OPCODE op2=OPCODE_ENDEXRAIL,OPCODE op3=OPCODE_ENDEXRAIL); static uint16_t getOperand(int progCounter,byte n); + static void killBlinkOnVpin(VPIN pin); static RMFT2 * loopTask; static RMFT2 * pausingTask; void delayMe(long millisecs); @@ -244,10 +256,10 @@ private: union { unsigned long waitAfter; // Used by OPCODE_AFTER unsigned long timeoutStart; // Used by OPCODE_ATTIMEOUT + VPIN blinkPin; // Used by blink tasks }; - bool timeoutFlag; byte taskId; - + BlinkState blinkState; // includes AT_TIMEOUT flag. uint16_t loco; bool forward; bool invert; diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index e94c657..ce242ea 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -38,6 +38,7 @@ #undef ATTIMEOUT #undef AUTOMATION #undef AUTOSTART +#undef BLINK #undef BROADCAST #undef CALL #undef CLEAR_STASH @@ -66,6 +67,7 @@ #undef FOLLOW #undef FON #undef FORGET +#undef FTOGGLE #undef FREE #undef FWD #undef GREEN @@ -164,8 +166,10 @@ #undef START #undef STASH #undef STEALTH +#undef STEALTH_GLOBAL #undef STOP #undef THROW +#undef TOGGLE_TURNOUT #undef TT_ADDPOSITION #undef TURNOUT #undef TURNOUTL @@ -180,6 +184,7 @@ #undef WITHROTTLE #undef XFOFF #undef XFON +#undef XFTOGGLE #ifndef RMFT2_UNDEF_ONLY #define ACTIVATE(addr,subaddr) @@ -196,6 +201,7 @@ #define ATTIMEOUT(sensor_id,timeout_ms) #define AUTOMATION(id,description) #define AUTOSTART +#define BLINK(vpin,onDuty,offDuty) #define BROADCAST(msg) #define CALL(route) #define CLEAR_STASH(id) @@ -225,6 +231,7 @@ #define FON(func) #define FORGET #define FREE(blockid) +#define FTOGGLE(func) #define FWD(speed) #define GREEN(signal_id) #define HAL(haltype,params...) @@ -322,8 +329,10 @@ #define START(route) #define STASH(id) #define STEALTH(code...) +#define STEALTH_GLOBAL(code...) #define STOP #define THROW(id) +#define TOGGLE_TURNOUT(id) #define TT_ADDPOSITION(turntable_id,position,value,angle,description...) #define TURNOUT(id,addr,subaddr,description...) #define TURNOUTL(id,addr,description...) @@ -338,4 +347,6 @@ #define WITHROTTLE(msg) #define XFOFF(cab,func) #define XFON(cab,func) +#define XFTOGGLE(cab,func) + #endif diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index 7969750..95375bb 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -36,7 +36,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]) { (void)stream; // avoid compiler warning if we don't access this parameter - bool reject=false; + switch(opcode) { case 'D': @@ -47,8 +47,7 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 break; case '/': // New EXRAIL command - reject=!parseSlash(stream,paramCount,p); - opcode=0; + if (parseSlash(stream,paramCount,p)) opcode=0; break; case 'A': // @@ -106,9 +105,11 @@ void RMFT2::ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16 } if (paramCount==1) { // LCC event arrived from adapter int16_t eventid=p[0]; - reject=eventid<0 || eventid>=countLCCLookup; - if (!reject) startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]); - opcode=0; + bool reject = eventid<0 || eventid>=countLCCLookup; + if (!reject) { + startNonRecursiveTask(F("LCC"),eventid,onLCCLookup[eventid]); + opcode=0; + } } break; @@ -182,12 +183,20 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { StringFormatter::send(stream, F("<* EXRAIL STATUS")); RMFT2 * task=loopTask; while(task) { + if ((compileFeatures & FEATURE_BLINK) + && (task->blinkState==blink_high || task->blinkState==blink_low)) { + StringFormatter::send(stream,F("\nID=%d,PC=%d,BLINK=%d"), + (int)(task->taskId),task->progCounter,task->blinkPin + ); + } + else { StringFormatter::send(stream,F("\nID=%d,PC=%d,LOCO=%d%c,SPEED=%d%c"), (int)(task->taskId),task->progCounter,task->loco, task->invert?'I':' ', task->speedo, task->forward?'F':'R' ); + } task=task->next; if (task==loopTask) break; } diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 5588811..7db52dc 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -145,6 +145,12 @@ static_assert(!hasdup(compileTimeSequenceList[0],1),"Duplicate SEQUENCE/ROUTE/AU #include "myAutomation.h" +// Pass 1g Implants STEALTH_GLOBAL in correct place +#include "EXRAIL2MacroReset.h" +#undef STEALTH_GLOBAL +#define STEALTH_GLOBAL(code...) code +#include "myAutomation.h" + // Pass 1h Implements HAL macro by creating exrailHalSetup function // Also allows creating EXTurntable object #include "EXRAIL2MacroReset.h" @@ -202,6 +208,8 @@ bool exrailHalSetup() { #define PICKUP_STASH(id) | FEATURE_STASH #undef STASH #define STASH(id) | FEATURE_STASH +#undef BLINK +#define BLINK(vpin,onDuty,offDuty) | FEATURE_BLINK const byte RMFT2::compileFeatures = 0 #include "myAutomation.h" @@ -451,6 +459,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define ATTIMEOUT(sensor_id,timeout) OPCODE_ATTIMEOUT1,0,0,OPCODE_ATTIMEOUT2,V(sensor_id),OPCODE_PAD,V(timeout/100L), #define AUTOMATION(id, description) OPCODE_AUTOMATION, V(id), #define AUTOSTART OPCODE_AUTOSTART,0,0, +#define BLINK(vpin,onDuty,offDuty) OPCODE_BLINK,V(vpin),OPCODE_PAD,V(onDuty),OPCODE_PAD,V(offDuty), #define BROADCAST(msg) PRINT(msg) #define CALL(route) OPCODE_CALL,V(route), #define CLEAR_STASH(id) OPCODE_CLEAR_STASH,V(id), @@ -484,6 +493,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define FON(func) OPCODE_FON,V(func), #define FORGET OPCODE_FORGET,0,0, #define FREE(blockid) OPCODE_FREE,V(blockid), +#define FTOGGLE(func) OPCODE_FTOGGLE,V(func), #define FWD(speed) OPCODE_FWD,V(speed), #define GREEN(signal_id) OPCODE_GREEN,V(signal_id), #define HAL(haltype,params...) @@ -518,6 +528,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define LCD(id,msg) PRINT(msg) #define SCREEN(display,id,msg) PRINT(msg) #define STEALTH(code...) PRINT(dummy) +#define STEALTH_GLOBAL(code...) #define LCN(msg) PRINT(msg) #define MESSAGE(msg) PRINT(msg) #define MOVETT(id,steps,activity) OPCODE_SERVO,V(id),OPCODE_PAD,V(steps),OPCODE_PAD,V(EXTurntable::activity),OPCODE_PAD,V(0), @@ -595,6 +606,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #define STASH(id) OPCODE_STASH,V(id), #define STOP OPCODE_SPEED,V(0), #define THROW(id) OPCODE_THROW,V(id), +#define TOGGLE_TURNOUT(id) OPCODE_TOGGLE_TURNOUT,V(id), #ifndef IO_NO_HAL #define TT_ADDPOSITION(id,position,value,angle,description...) OPCODE_TTADDPOSITION,V(id),OPCODE_PAD,V(position),OPCODE_PAD,V(value),OPCODE_PAD,V(angle), #endif @@ -611,6 +623,7 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #endif #define XFOFF(cab,func) OPCODE_XFOFF,V(cab),OPCODE_PAD,V(func), #define XFON(cab,func) OPCODE_XFON,V(cab),OPCODE_PAD,V(func), +#define XFTOGGLE(cab,func) OPCODE_XFTOGGLE,V(cab),OPCODE_PAD,V(func), // Build RouteCode const int StringMacroTracker2=__COUNTER__; diff --git a/Release_Notes/EXRAIL additions.md b/Release_Notes/EXRAIL additions.md new file mode 100644 index 0000000..690ff0a --- /dev/null +++ b/Release_Notes/EXRAIL additions.md @@ -0,0 +1,38 @@ + +BLINK(vpin, onMs,offMs) + +which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN. + +BLINK returns immediately, the blinking is autonomous. + +This means a signal that always blinks amber could be done like this: +``` +SIGNAL(30,31,32) +ONAMBER(30) BLINK(31,500,500) DONE +``` +The RED or GREEN calls will turn off the amber blink automatically. + +Alternatively a signal that has normal AMBER and flashing AMBER could be like this: + +#define FLASHAMBER(signal) \ + AMBER(signal) \ + BLINK(signal+1,500,500) + + (Caution: this issumes that the amber pin is redpin+1) + + == + + FTOGGLE(function) + Toggles the current loco function (see FON and FOFF) + + XFTOGGLE(loco,function) + Toggles the function on given loco. (See XFON, XFOFF) + + TOGGLE_TURNOUT(id) + Toggles the turnout (see CLOSE, THROW) + + STEALTH_GLOBAL(code) + ADVANCED C++ users only. + Inserts code such as static variables and functions that + may be utilised by multiple STEALTH operations. + \ No newline at end of file diff --git a/Release_Notes/Exrail mods.txt b/Release_Notes/Exrail mods.txt new file mode 100644 index 0000000..68f57b7 --- /dev/null +++ b/Release_Notes/Exrail mods.txt @@ -0,0 +1,98 @@ + +BLINK(vpin, onMs,offMs) + +which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN. + +BLINK returns immediately, the blinking is autonomous. + +This means a signal that always blinks amber could be done like this: + +SIGNAL(30,31,32) +ONAMBER(30) BLINK(31,500,500) DONE + +The RED or GREEN calls will turn off the amber blink automatically. + +Alternatively a signal that has normal AMBER and flashing AMBER could be like this: + +#define FLASHAMBER(signal) \ + AMBER(signal) \ + BLINK(signal+1,500,500) + + (Caution: this assumes that the amber pin is redpin+1) + + == + + FTOGGLE(function) + Toggles the current loco function (see FON and FOFF) + + XFTOGGLE(loco,function) + Toggles the function on given loco. (See XFON, XFOFF) + + TOGGLE_TURNOUT(id) + Toggles the turnout (see CLOSE, THROW) + + STEALTH_GLOBAL(code) + ADVANCED C++ users only. + Inserts code such as static variables and functions that + may be utilised by multiple STEALTH operations. + + +// 5.2.34 - Command fopr DCC Extended Accessories. +This command sends an extended accessory packet to the track, Normally used to set +a signal aspect. Aspect numbers are undefined as sdtandards except for 0 which is +always considered a stop. + +// - Exrail ASPECT(address,aspect) for above. + The ASPECT command sents an aspect to a DCC accessory using the same logic as + . + +// - EXRAIL DCCX_SIGNAL(Address,redAspect,amberAspect,greenAspect) + This defines a signal (with id same as dcc address) that can be operated + by the RED/AMBER/GREEN commands. In each case the command uses the signal + address to refer to the signal and the aspect chosen depends on the use of the RED + AMBER or GREEN command sent. Other aspects may be sent but will require the + direct use of the ASPECT command. + The IFRED/IFAMBER/IFGREEN and ONRED/ONAMBER/ONGREEN commands contunue to operate + as for any other signal type. It is important to be aware that use of the ASPECT + or commands will correctly set the IF flags and call the ON handlers if ASPECT + is used to set one of the three aspects defined in the DCCX_SIGNAL command. + Direct use of other aspects does not affect the signal flags. + ASPECT and can be used withput defining any signal if tyhe flag management or + ON event handlers are not required. + +// 5.2.33 - Exrail CONFIGURE_SERVO(vpin,pos1,pos2,profile) + This macro offsers a more convenient way of performing the HAL call in halSetup.h + In halSetup.h --- IODevice::configureServo(101,300,400,PCA9685::slow); + In myAutomation.h --- CONFIGURE_SERVO(101,300,400,slow) + +// 5.2.32 - Railcom Cutout (Initial trial Mega2560 only) + This cutout will only work on a Mega2560 with a single EX8874 motor shield + configured in the normal way with the main track brake pin on pin 9. + Turns on the cutout mechanism. + Tirns off the cutout. (This is the default) + ONLY to be used by developers used for waveform diagnostics. + (In DEBUG mode the main track idle packets are replaced with reset packets, This + makes it far easier to see the preambles and cutouts on a logic analyser or scope.) + +// 5.2.31 - Exrail JMRI_SENSOR(vpin [,count]) creates types. + This Macro causes the creation of JMRI type sensors in a way that is + simpler than repeating lines of commands. + JMRI_SENSOR(100) is equenvelant to + JMRI_SENSOR(100,16) will create type sensors for vpins 100-115. + +// 5.2.26 - Silently ignore overridden HAL defaults +// - include HAL_IGNORE_DEFAULTS macro in EXRAIL + The HAL_IGNORE_DEFAULTS command, anywhere in myAutomation.h will + prevent the startup code from trying the default I2C sensors/servos. +// 5.2.24 - Exrail macro asserts to catch +// : duplicate/missing automation/route/sequence/call ids +// : latches and reserves out of range +// : speeds out of range + Causes compiler time messages for EXRAIL issues that would normally + only be discovered by things going wrong at run time. +// 5.2.13 - EXRAIL STEALTH + Permits a certain level of C++ code to be embedded as a single step in + an exrail sequence. Serious engineers only. + +// 5.2.9 - EXRAIL STASH feature +// - Added ROUTE_DISABLED macro in EXRAIL From 8a5a832b1d5e2301073b1170b977346de15ecc14 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 9 Apr 2024 20:59:57 +0100 Subject: [PATCH 282/310] Reduced EXRAIL diag noise --- EXRAIL2.cpp | 16 ++++++------- Release_Notes/EXRAIL additions.md | 38 ------------------------------- version.h | 8 ++++++- 3 files changed, 15 insertions(+), 47 deletions(-) delete mode 100644 Release_Notes/EXRAIL additions.md diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index ef4387c..9293c96 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -176,7 +176,7 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { /* static */ void RMFT2::begin() { - DIAG(F("EXRAIL RoutCode at =%P"),RouteCode); + //DIAG(F("EXRAIL RoutCode at =%P"),RouteCode); bool saved_diag=diag; diag=true; @@ -411,7 +411,7 @@ void RMFT2::createNewTask(int route, uint16_t cab) { void RMFT2::driveLoco(byte speed) { if (loco<=0) return; // Prevent broadcast! - if (diag) DIAG(F("EXRAIL drive %d %d %d"),loco,speed,forward^invert); + //if (diag) DIAG(F("EXRAIL drive %d %d %d"),loco,speed,forward^invert); /* TODO..... power on appropriate track if DC or main if dcc if (TrackManager::getMainPowerMode()==POWERMODE::OFF) { @@ -1066,7 +1066,7 @@ void RMFT2::loop2() { case OPCODE_ROUTE: case OPCODE_AUTOMATION: case OPCODE_SEQUENCE: - if (diag) DIAG(F("EXRAIL begin(%d)"),operand); + //if (diag) DIAG(F("EXRAIL begin(%d)"),operand); break; case OPCODE_AUTOSTART: // Handled only during begin process @@ -1146,7 +1146,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { /* static */ void RMFT2::doSignal(int16_t id,char rag) { if (!(compileFeatures & FEATURE_SIGNAL)) return; // dont compile code below - if (diag) DIAG(F(" doSignal %d %x"),id,rag); + //if (diag) DIAG(F(" doSignal %d %x"),id,rag); // Schedule any event handler for this signal change. // This will work even without a signal definition. @@ -1166,7 +1166,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2); VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4); VPIN greenpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6); - if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin); + //if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin); VPIN sigtype=sigid & ~SIGNAL_ID_MASK; @@ -1174,7 +1174,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { // A servo signal, the pin numbers are actually servo positions // Note, setting a signal to a zero position has no effect. int16_t servopos= rag==SIGNAL_RED? redpin: (rag==SIGNAL_GREEN? greenpin : amberpin); - if (diag) DIAG(F("sigA %d %d"),id,servopos); + //if (diag) DIAG(F("sigA %d %d"),id,servopos); if (servopos!=0) IODevice::writeAnalogue(id,servopos,PCA9685::Bounce); return; } @@ -1292,7 +1292,7 @@ void RMFT2::rotateEvent(int16_t turntableId, bool change) { void RMFT2::clockEvent(int16_t clocktime, bool change) { // Hunt for an ONTIME for this time if (Diag::CMD) - DIAG(F("Looking for clock event at : %d"), clocktime); + DIAG(F("clockEvent at : %d"), clocktime); if (change) { onClockLookup->handleEvent(F("CLOCK"),clocktime); onClockLookup->handleEvent(F("CLOCK"),25*60+clocktime%60); @@ -1302,7 +1302,7 @@ void RMFT2::clockEvent(int16_t clocktime, bool change) { void RMFT2::powerEvent(int16_t track, bool overload) { // Hunt for an ONOVERLOAD for this item if (Diag::CMD) - DIAG(F("Looking for Power event on track : %c"), track); + DIAG(F("powerEvent : %c"), track); if (overload) { onOverloadLookup->handleEvent(F("POWER"),track); } diff --git a/Release_Notes/EXRAIL additions.md b/Release_Notes/EXRAIL additions.md deleted file mode 100644 index 690ff0a..0000000 --- a/Release_Notes/EXRAIL additions.md +++ /dev/null @@ -1,38 +0,0 @@ - -BLINK(vpin, onMs,offMs) - -which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN. - -BLINK returns immediately, the blinking is autonomous. - -This means a signal that always blinks amber could be done like this: -``` -SIGNAL(30,31,32) -ONAMBER(30) BLINK(31,500,500) DONE -``` -The RED or GREEN calls will turn off the amber blink automatically. - -Alternatively a signal that has normal AMBER and flashing AMBER could be like this: - -#define FLASHAMBER(signal) \ - AMBER(signal) \ - BLINK(signal+1,500,500) - - (Caution: this issumes that the amber pin is redpin+1) - - == - - FTOGGLE(function) - Toggles the current loco function (see FON and FOFF) - - XFTOGGLE(loco,function) - Toggles the function on given loco. (See XFON, XFOFF) - - TOGGLE_TURNOUT(id) - Toggles the turnout (see CLOSE, THROW) - - STEALTH_GLOBAL(code) - ADVANCED C++ users only. - Inserts code such as static variables and functions that - may be utilised by multiple STEALTH operations. - \ No newline at end of file diff --git a/version.h b/version.h index a772201..3eaf199 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,13 @@ #include "StringFormatter.h" -#define VERSION "5.2.46" +#define VERSION "5.2.47" +// 5.2.47 - EXRAIL additions: +// STEALTH_GLOBAL +// BLINK +// TOGGLE_TURNOUT +// FTOGGLE, XFTOGGLE +// Reduced code-developmenmt DIAG noise // 5.2.46 - Support for extended consist CV20 in and // - New cmd to handle long/short consist ids // 5.2.45 - ESP32 Trackmanager reset cab number to 0 when track is not DC From 91e60b371667763135207e2ac5ea707f7558f8d7 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Fri, 12 Apr 2024 17:25:00 +0800 Subject: [PATCH 283/310] HALDisplay bug fix --- IO_HALDisplay.h | 11 +++++++---- version.h | 3 ++- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/IO_HALDisplay.h b/IO_HALDisplay.h index f2ca3af..24ffde7 100644 --- a/IO_HALDisplay.h +++ b/IO_HALDisplay.h @@ -1,7 +1,9 @@ /* - * © 2023, Neil McKechnie. All rights reserved. + * © 2024, Paul Antoine + * © 2023, Neil McKechnie + * All rights reserved. * - * This file is part of DCC++EX API + * This file is part of DCC-EX API * * This is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by @@ -112,13 +114,14 @@ protected: // Fill buffer with spaces memset(_buffer, ' ', _numCols*_numRows); - _displayDriver->clearNative(); - // Add device to list of HAL devices (not necessary but allows // status to be displayed using and device to be // reinitialised using ). IODevice::addDevice(this); + // Moved after addDevice() to ensure I2CManager.begin() has been called fisrt + _displayDriver->clearNative(); + // Also add this display to list of display handlers DisplayInterface::addDisplay(displayNo); diff --git a/version.h b/version.h index 3eaf199..e871738 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.47" +#define VERSION "5.2.48" +// 5.2.48 - Bugfix: HALDisplay was generating I2C traffic prior to I2C being initialised // 5.2.47 - EXRAIL additions: // STEALTH_GLOBAL // BLINK From 4aa97e1731e108651d372c947772485d3974cf10 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 13 Apr 2024 08:12:35 +0100 Subject: [PATCH 284/310] Squashed commit of the following: commit 3fc90c916c54ceae4364f79a4b9a2001bc75fcd5 Merge: 132e2d0 91e60b3 Author: Asbelos Date: Fri Apr 12 15:08:49 2024 +0100 Merge branch 'devel' into devel_chris commit 132e2d0de2c6e72b1a3d85520936fb7cddd8d739 Author: Asbelos Date: Fri Apr 12 15:07:31 2024 +0100 Revert "Merge branch 'master' into devel_chris" This reverts commit 23845f2df2035333c43b4aa05d76e9f7600efe29, reversing changes made to 76755993f146a1deaf46993d22e850b899dcf603. commit 23845f2df2035333c43b4aa05d76e9f7600efe29 Merge: 7675599 28d60d4 Author: Asbelos Date: Fri Apr 12 14:38:22 2024 +0100 Merge branch 'master' into devel_chris commit 76755993f146a1deaf46993d22e850b899dcf603 Author: Asbelos Date: Fri Apr 12 14:37:34 2024 +0100 ONSENSOR/ONBUTTON commit 8987d622e60fb27174203ce47b49462a01ecb61c Author: Asbelos Date: Tue Apr 9 20:44:47 2024 +0100 doc note commit 8f0a5c1ec0fde18dbb262311a1ef5ef79d571807 Author: Asbelos Date: Thu Apr 4 09:45:58 2024 +0100 Exrail notes commit 94083b9ab8a2322c39b7087c522730569194b732 Merge: 72ef199 02bf50b Author: Asbelos Date: Thu Apr 4 09:08:26 2024 +0100 Merge branch 'devel' into devel_chris commit 72ef199315d1c7717331864abb11730890fd3162 Author: Asbelos Date: Thu Apr 4 09:06:50 2024 +0100 TOGGLE_TURNOUT commit e69b777a2f62104dd8b74ba688b950fa92919d54 Author: Asbelos Date: Wed Apr 3 15:17:40 2024 +0100 BLINK command commit c7ed47400d5d89c0b8425ec12b1828e710fb23ec Author: Asbelos Date: Tue Apr 2 10:12:45 2024 +0100 FTOGGLE,XFTOGGLE commit 7a93cf7be856afd30f6976a483b1db4bfc4073a1 Author: Asbelos Date: Fri Mar 29 13:21:35 2024 +0000 EXRAIL STEALTH_GLOBAL commit 28d60d49849c8fc4b0ff0f933222c052ba7c90aa Author: Peter Akers Date: Fri Feb 16 18:02:40 2024 +1000 Update README.md commit 3b162996ad42546486b812e22d3ed6daee857d19 Author: peteGSX Date: Sun Jan 21 07:13:53 2024 +1000 EX-IO fixes in version commit fb414a7a506f078d2a075d65c7b171ae4399ef63 Author: Harald Barth Date: Thu Jan 18 08:20:33 2024 +0100 Bugfix: allocate enough bytes for digital pins. Add more sanity checks when allocating memory commit 818e05b4253a1a0980abb3a0bbef38a8c662bb1a Author: Harald Barth Date: Wed Jan 10 08:37:54 2024 +0100 version 5.0.8 commit c5168f030fa64330a1f0e09d6637a3817fe5e067 Author: Harald Barth Date: Wed Jan 10 08:15:30 2024 +0100 Do not crash on turnouts without description commit 387ea019bdc483667bcbcf45205a56330d615aee Author: Harald Barth Date: Mon Nov 6 22:11:56 2023 +0100 version 5.0.7 commit a981f83bb9c376d01245c328c5de7d7bf25ebfb2 Author: Harald Barth Date: Mon Nov 6 22:11:31 2023 +0100 Only flag 2.2.0.0-dev as broken, not 2.2.0.0 commit 749a859db551113567faae3248c575dbf6440ece Author: Asbelos Date: Wed Nov 1 20:13:05 2023 +0000 Bugfix TURNOUTL commit 659c58b30766a7b8dd2b4d2677d90663af8fefcf Author: Harald Barth Date: Sat Oct 28 19:20:33 2023 +0200 version 5.0.5 commit 0b9ec7460ba461d5602b6e06843d6be8468f385f Author: Harald Barth Date: Sat Oct 28 19:18:59 2023 +0200 Bugfix version detection logic and better message --- EXRAIL2.cpp | 10 +++ EXRAIL2.h | 2 +- EXRAIL2MacroReset.h | 4 ++ EXRAILMacros.h | 2 + EXRAILSensor.cpp | 104 ++++++++++++++++++++++++++++++ EXRAILSensor.h | 50 ++++++++++++++ Release_Notes/EXRAIL additions.md | 38 +++++++++++ 7 files changed, 209 insertions(+), 1 deletion(-) create mode 100644 EXRAILSensor.cpp create mode 100644 EXRAILSensor.h create mode 100644 Release_Notes/EXRAIL additions.md diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 9293c96..adea99e 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -54,6 +54,7 @@ #include "TrackManager.h" #include "Turntables.h" #include "IODevice.h" +#include "EXRAILSensor.h" // One instance of RMFT clas is used for each "thread" in the automation. @@ -251,6 +252,12 @@ if (compileFeatures & FEATURE_SIGNAL) { break; } + case OPCODE_ONSENSOR: + new EXRAILSensor(operand,progCounter+3,true ); + break; + case OPCODE_ONBUTTON: + new EXRAILSensor(operand,progCounter+3,false ); + break; case OPCODE_TURNOUT: { VPIN id=operand; int addr=getOperand(progCounter,1); @@ -480,6 +487,7 @@ bool RMFT2::skipIfBlock() { } void RMFT2::loop() { + EXRAILSensor::checkAll(); // Round Robin call to a RMFT task each time if (loopTask==NULL) return; @@ -1084,6 +1092,8 @@ void RMFT2::loop2() { case OPCODE_ONGREEN: case OPCODE_ONCHANGE: case OPCODE_ONTIME: + case OPCODE_ONBUTTON: + case OPCODE_ONSENSOR: #ifndef IO_NO_HAL case OPCODE_DCCTURNTABLE: // Turntable definition ignored at runtime case OPCODE_EXTTTURNTABLE: // Turntable definition ignored at runtime diff --git a/EXRAIL2.h b/EXRAIL2.h index 7075f26..1042d53 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -73,7 +73,7 @@ enum OPCODE : byte {OPCODE_THROW,OPCODE_CLOSE,OPCODE_TOGGLE_TURNOUT, OPCODE_ROUTE_ACTIVE,OPCODE_ROUTE_INACTIVE,OPCODE_ROUTE_HIDDEN, OPCODE_ROUTE_DISABLED, OPCODE_STASH,OPCODE_CLEAR_STASH,OPCODE_CLEAR_ALL_STASH,OPCODE_PICKUP_STASH, - + OPCODE_ONBUTTON,OPCODE_ONSENSOR, // OPcodes below this point are skip-nesting IF operations // placed here so that they may be skipped as a group // see skipIfBlock() diff --git a/EXRAIL2MacroReset.h b/EXRAIL2MacroReset.h index ce242ea..c799ddf 100644 --- a/EXRAIL2MacroReset.h +++ b/EXRAIL2MacroReset.h @@ -114,6 +114,8 @@ #undef ONGREEN #undef ONRED #undef ONROTATE +#undef ONBUTTON +#undef ONSENSOR #undef ONTHROW #undef ONCHANGE #undef PARSE @@ -279,6 +281,8 @@ #define ONROTATE(turntable_id) #define ONTHROW(turnout_id) #define ONCHANGE(sensor_id) +#define ONSENSOR(sensor_id) +#define ONBUTTON(sensor_id) #define PAUSE #define PIN_TURNOUT(id,pin,description...) #define PRINT(msg) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 7db52dc..508540a 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -553,6 +553,8 @@ int RMFT2::onLCCLookup[RMFT2::countLCCLookup]; #endif #define ONTHROW(turnout_id) OPCODE_ONTHROW,V(turnout_id), #define ONCHANGE(sensor_id) OPCODE_ONCHANGE,V(sensor_id), +#define ONSENSOR(sensor_id) OPCODE_ONSENSOR,V(sensor_id), +#define ONBUTTON(sensor_id) OPCODE_ONBUTTON,V(sensor_id), #define PAUSE OPCODE_PAUSE,0,0, #define PICKUP_STASH(id) OPCODE_PICKUP_STASH,V(id), #define PIN_TURNOUT(id,pin,description...) OPCODE_PINTURNOUT,V(id),OPCODE_PAD,V(pin), diff --git a/EXRAILSensor.cpp b/EXRAILSensor.cpp new file mode 100644 index 0000000..b0a5fa0 --- /dev/null +++ b/EXRAILSensor.cpp @@ -0,0 +1,104 @@ +/* + * © 2024 Chris Harlow + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +/********************************************************************** +EXRAILSensor represents a sensor that should be monitored in order +to call an exrail ONBUTTON or ONCHANGE handler. +These are created at EXRAIL startup and thus need no delete or listing +capability. +The basic logic is similar to that found in the Sensor class +except that on the relevant change an EXRAIL thread is started. +**********************************************************************/ + +#include "EXRAILSensor.h" +#include "EXRAIL2.h" + +void EXRAILSensor::checkAll() { + if (firstSensor == NULL) return; // No sensors to be scanned + if (readingSensor == NULL) { + // Not currently scanning sensor list + unsigned long thisTime = micros(); + if (thisTime - lastReadCycle < cycleInterval) return; + // Required time has elapsed since last read cycle started, + // so initiate new scan through the sensor list + readingSensor = firstSensor; + lastReadCycle = thisTime; + } + + // Loop until either end of list is encountered or we pause for some reason + byte sensorCount = 0; + + while (readingSensor != NULL) { + bool pause=readingSensor->check(); + // Move to next sensor in list. + readingSensor = readingSensor->nextSensor; + // Currently process max of 16 sensors per entry. + // Performance measurements taken during development indicate that, with 128 sensors configured + // on 8x 16-pin MCP23017 GPIO expanders with polling (no change notification), all inputs can be read from the devices + // within 1.4ms (400Mhz I2C bus speed), and a full cycle of checking 128 sensors for changes takes under a millisecond. + if (pause || (++sensorCount)>=16) return; + } +} + +bool EXRAILSensor::check() { + // check for debounced change in this sensor + inputState = IODevice::read(pin); + + // Check if changed since last time, and process changes. + if (inputState == active) {// no change + latchDelay = minReadCount; // Reset counter + return false; // no change + } + + // Change detected ... has it stayed changed for long enough + if (latchDelay > 0) { + latchDelay--; + return false; + } + + // change validated, act on it. + active = inputState; + latchDelay = minReadCount; // Reset debounce counter + if (onChange || active) { + new RMFT2(progCounter); + return true; // Don't check any more sensors on this entry + } + return false; +} + +EXRAILSensor::EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange) { + // Add to the start of the list + //DIAG(F("ONthing vpin=%d at %d"), _pin, _progCounter); + nextSensor = firstSensor; + firstSensor = this; + + pin=_pin; + progCounter=_progCounter; + onChange=_onChange; + + IODevice::configureInput(pin, true); + active = IODevice::read(pin); + inputState = active; + latchDelay = minReadCount; +} + +EXRAILSensor *EXRAILSensor::firstSensor=NULL; +EXRAILSensor *EXRAILSensor::readingSensor=NULL; +unsigned long EXRAILSensor::lastReadCycle=0; diff --git a/EXRAILSensor.h b/EXRAILSensor.h new file mode 100644 index 0000000..b5b00c6 --- /dev/null +++ b/EXRAILSensor.h @@ -0,0 +1,50 @@ +/* + * © 2024 Chris Harlow + * All rights reserved. + * + * This file is part of CommandStation-EX + * + * This 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. + * + * It is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with CommandStation. If not, see . + */ + +#ifndef EXRAILSensor_h +#define EXRAILSensor_h +#include "IODevice.h" +class EXRAILSensor { + static EXRAILSensor * firstSensor; + static EXRAILSensor * readingSensor; + static unsigned long lastReadCycle; + + public: + static void checkAll(); + + EXRAILSensor(VPIN _pin, int _progCounter, bool _onChange); + bool check(); + + private: + static const unsigned int cycleInterval = 10000; // min time between consecutive reads of each sensor in microsecs. + // should not be less than device scan cycle time. + static const byte minReadCount = 4; // number of additional scans before acting on change + // E.g. 1 means that a change is ignored for one scan and actioned on the next. + // Max value is 63 + + EXRAILSensor* nextSensor; + VPIN pin; + int progCounter; + bool active; + bool inputState; + bool onChange; + byte latchDelay; +}; +#endif \ No newline at end of file diff --git a/Release_Notes/EXRAIL additions.md b/Release_Notes/EXRAIL additions.md new file mode 100644 index 0000000..690ff0a --- /dev/null +++ b/Release_Notes/EXRAIL additions.md @@ -0,0 +1,38 @@ + +BLINK(vpin, onMs,offMs) + +which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN. + +BLINK returns immediately, the blinking is autonomous. + +This means a signal that always blinks amber could be done like this: +``` +SIGNAL(30,31,32) +ONAMBER(30) BLINK(31,500,500) DONE +``` +The RED or GREEN calls will turn off the amber blink automatically. + +Alternatively a signal that has normal AMBER and flashing AMBER could be like this: + +#define FLASHAMBER(signal) \ + AMBER(signal) \ + BLINK(signal+1,500,500) + + (Caution: this issumes that the amber pin is redpin+1) + + == + + FTOGGLE(function) + Toggles the current loco function (see FON and FOFF) + + XFTOGGLE(loco,function) + Toggles the function on given loco. (See XFON, XFOFF) + + TOGGLE_TURNOUT(id) + Toggles the turnout (see CLOSE, THROW) + + STEALTH_GLOBAL(code) + ADVANCED C++ users only. + Inserts code such as static variables and functions that + may be utilised by multiple STEALTH operations. + \ No newline at end of file From 7dafe0383d21491bbefb1a9ce3562396aefb421c Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 13 Apr 2024 09:14:55 +0100 Subject: [PATCH 285/310] EXRAIL ONBUTTON --- Release_Notes/EXRAIL additions.md | 38 ------------------------------- Release_Notes/Exrail mods.txt | 21 +++++++++++++++++ version.h | 4 +++- 3 files changed, 24 insertions(+), 39 deletions(-) delete mode 100644 Release_Notes/EXRAIL additions.md diff --git a/Release_Notes/EXRAIL additions.md b/Release_Notes/EXRAIL additions.md deleted file mode 100644 index 690ff0a..0000000 --- a/Release_Notes/EXRAIL additions.md +++ /dev/null @@ -1,38 +0,0 @@ - -BLINK(vpin, onMs,offMs) - -which will start a vpin blinking until such time as it is SET, RESET or set by a signal operation such as RED, AMBER, GREEN. - -BLINK returns immediately, the blinking is autonomous. - -This means a signal that always blinks amber could be done like this: -``` -SIGNAL(30,31,32) -ONAMBER(30) BLINK(31,500,500) DONE -``` -The RED or GREEN calls will turn off the amber blink automatically. - -Alternatively a signal that has normal AMBER and flashing AMBER could be like this: - -#define FLASHAMBER(signal) \ - AMBER(signal) \ - BLINK(signal+1,500,500) - - (Caution: this issumes that the amber pin is redpin+1) - - == - - FTOGGLE(function) - Toggles the current loco function (see FON and FOFF) - - XFTOGGLE(loco,function) - Toggles the function on given loco. (See XFON, XFOFF) - - TOGGLE_TURNOUT(id) - Toggles the turnout (see CLOSE, THROW) - - STEALTH_GLOBAL(code) - ADVANCED C++ users only. - Inserts code such as static variables and functions that - may be utilised by multiple STEALTH operations. - \ No newline at end of file diff --git a/Release_Notes/Exrail mods.txt b/Release_Notes/Exrail mods.txt index 68f57b7..6f8287f 100644 --- a/Release_Notes/Exrail mods.txt +++ b/Release_Notes/Exrail mods.txt @@ -1,3 +1,24 @@ +// 5.2.49 + +Which is a more efficient than the AT/AFTER/IF methods +of handling buttons and switches, especially on MIMIC panels. + +ONBUTTON(vpin) + handles debounce and starts a task if a button is used to + short a pin to ground. + + for example: + ONBUTTON(30) TOGGLE_TURNOUT(30) DONE + +ONSENSOR(vpin) + handles debounce and starts a task if the pin changes. + You may want to check the pin state with an IF ... + +Note the ONBUTTON and ONSENSOR are not generally useful +for track sensors and running trains, because you dont know which +train triggered the sensor. + +// 5.2.47 BLINK(vpin, onMs,offMs) diff --git a/version.h b/version.h index e871738..395630a 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.48" +#define VERSION "5.2.49" +// 5.2.49 - EXRAIL additions: +// ONBUTTON, ONSENSOR // 5.2.48 - Bugfix: HALDisplay was generating I2C traffic prior to I2C being initialised // 5.2.47 - EXRAIL additions: // STEALTH_GLOBAL From ebe8f62cf05d560a33553086a26f20af923acce1 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Sat, 13 Apr 2024 10:16:26 +0100 Subject: [PATCH 286/310] ONBUTTON/ONSENSOR use latch --- EXRAIL2.cpp | 9 ++++++--- EXRAIL2.h | 5 +++-- EXRAILMacros.h | 4 ++++ EXRAILSensor.cpp | 2 +- version.h | 3 ++- 5 files changed, 16 insertions(+), 7 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index adea99e..6b1b05e 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -253,11 +253,13 @@ if (compileFeatures & FEATURE_SIGNAL) { } case OPCODE_ONSENSOR: + if (compileFeatures & FEATURE_SENSOR) new EXRAILSensor(operand,progCounter+3,true ); - break; + break; case OPCODE_ONBUTTON: + if (compileFeatures & FEATURE_SENSOR) new EXRAILSensor(operand,progCounter+3,false ); - break; + break; case OPCODE_TURNOUT: { VPIN id=operand; int addr=getOperand(progCounter,1); @@ -487,7 +489,8 @@ bool RMFT2::skipIfBlock() { } void RMFT2::loop() { - EXRAILSensor::checkAll(); + if (compileFeatures & FEATURE_SENSOR) + EXRAILSensor::checkAll(); // Round Robin call to a RMFT task each time if (loopTask==NULL) return; diff --git a/EXRAIL2.h b/EXRAIL2.h index 1042d53..794eb86 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -115,6 +115,7 @@ enum BlinkState: byte { static const byte FEATURE_ROUTESTATE= 0x10; static const byte FEATURE_STASH = 0x08; static const byte FEATURE_BLINK = 0x04; + static const byte FEATURE_SENSOR = 0x02; // Flag bits for status of hardware and TPL @@ -185,7 +186,8 @@ class LookList { static const FSH * getTurntableDescription(int16_t id); static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); - + static bool readSensor(uint16_t sensorId); + private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); static bool parseSlash(Print * stream, byte & paramCount, int16_t p[]) ; @@ -208,7 +210,6 @@ private: static RMFT2 * pausingTask; void delayMe(long millisecs); void driveLoco(byte speedo); - bool readSensor(uint16_t sensorId); bool skipIfBlock(); bool readLoco(); void loop2(); diff --git a/EXRAILMacros.h b/EXRAILMacros.h index 508540a..e9e2f77 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -210,6 +210,10 @@ bool exrailHalSetup() { #define STASH(id) | FEATURE_STASH #undef BLINK #define BLINK(vpin,onDuty,offDuty) | FEATURE_BLINK +#undef ONBUTTON +#define ONBUTTON(vpin) | FEATURE_SENSOR +#undef ONSENSOR +#define ONSENSOR(vpin) | FEATURE_SENSOR const byte RMFT2::compileFeatures = 0 #include "myAutomation.h" diff --git a/EXRAILSensor.cpp b/EXRAILSensor.cpp index b0a5fa0..218b970 100644 --- a/EXRAILSensor.cpp +++ b/EXRAILSensor.cpp @@ -59,7 +59,7 @@ void EXRAILSensor::checkAll() { bool EXRAILSensor::check() { // check for debounced change in this sensor - inputState = IODevice::read(pin); + inputState = RMFT2::readSensor(pin); // Check if changed since last time, and process changes. if (inputState == active) {// no change diff --git a/version.h b/version.h index 395630a..0b8c1a6 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.49" +#define VERSION "5.2.50" +// 5.2.50 - EXRAIL ONBUTTON/ONSENSOR observe LATCH // 5.2.49 - EXRAIL additions: // ONBUTTON, ONSENSOR // 5.2.48 - Bugfix: HALDisplay was generating I2C traffic prior to I2C being initialised From c382bd33bc65dc8f8185abbf746bc1fe02f50b9b Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Apr 2024 19:03:24 +0200 Subject: [PATCH 287/310] Distinguish between sighandle and sigid --- EXRAIL2.cpp | 38 +++++++++++++++++++++----------------- EXRAIL2Parser.cpp | 11 ++++++----- 2 files changed, 27 insertions(+), 22 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6b1b05e..b811145 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -205,15 +205,16 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { // Second pass startup, define any turnouts or servos, set signals red // add sequences onRoutines to the lookups -if (compileFeatures & FEATURE_SIGNAL) { - onRedLookup=LookListLoader(OPCODE_ONRED); - onAmberLookup=LookListLoader(OPCODE_ONAMBER); - onGreenLookup=LookListLoader(OPCODE_ONGREEN); - for (int sigslot=0;;sigslot++) { - VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); - if (sigid==0) break; // end of signal list - doSignal(sigid & SIGNAL_ID_MASK, SIGNAL_RED); - } + if (compileFeatures & FEATURE_SIGNAL) { + onRedLookup=LookListLoader(OPCODE_ONRED); + onAmberLookup=LookListLoader(OPCODE_ONAMBER); + onGreenLookup=LookListLoader(OPCODE_ONGREEN); + for (int sigslot=0;;sigslot++) { + int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); + if (sighandle==0) break; // end of signal list + VPIN sigid = sighandle & SIGNAL_ID_MASK; + doSignal(sigid, SIGNAL_RED); + } } int progCounter; @@ -1143,16 +1144,17 @@ void RMFT2::kill(const FSH * reason, int operand) { int16_t RMFT2::getSignalSlot(int16_t id) { for (int sigslot=0;;sigslot++) { - int16_t sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); - if (sigid==0) { // end of signal list + int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); + if (sighandle==0) { // end of signal list DIAG(F("EXRAIL Signal %d not defined"), id); return -1; } + VPIN sigid = sighandle & SIGNAL_ID_MASK; // sigid is the signal id used in RED/AMBER/GREEN macro // for a LED signal it will be same as redpin // but for a servo signal it will also have SERVO_SIGNAL_FLAG set. - if ((sigid & SIGNAL_ID_MASK)!= id) continue; // keep looking + if (sigid != id) continue; // keep looking return sigslot; // relative slot in signals table } } @@ -1175,13 +1177,14 @@ int16_t RMFT2::getSignalSlot(int16_t id) { // Correct signal definition found, get the rag values int16_t sigpos=sigslot*8; - VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); + int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); VPIN redpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2); VPIN amberpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+4); VPIN greenpin=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+6); //if (diag) DIAG(F("signal %d %d %d %d %d"),sigid,id,redpin,amberpin,greenpin); - VPIN sigtype=sigid & ~SIGNAL_ID_MASK; + VPIN sigtype=sighandle & ~SIGNAL_ID_MASK; + VPIN sigid = sighandle & SIGNAL_ID_MASK; if (sigtype == SERVO_SIGNAL_FLAG) { // A servo signal, the pin numbers are actually servo positions @@ -1204,7 +1207,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { byte value=redpin; if (rag==SIGNAL_AMBER) value=amberpin; if (rag==SIGNAL_GREEN) value=greenpin; - DCC::setExtendedAccessory(sigid & SIGNAL_ID_MASK,value); + DCC::setExtendedAccessory(sigid, value); return; } @@ -1255,8 +1258,9 @@ bool RMFT2::signalAspectEvent(int16_t address, byte aspect ) { int16_t sigslot=getSignalSlot(address); if (sigslot<0) return false; // this is not a defined signal int16_t sigpos=sigslot*8; - VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); - VPIN sigtype=sigid & ~SIGNAL_ID_MASK; + int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos); + VPIN sigtype=sighandle & ~SIGNAL_ID_MASK; + VPIN sigid = sighandle & SIGNAL_ID_MASK; if (sigtype!=DCCX_SIGNAL_FLAG) return false; // not a DCCX signal // Turn an aspect change into a RED/AMBER/GREEN setting if (aspect==GETHIGHFLASHW(RMFT2::SignalDefinitions,sigpos+2)) { diff --git a/EXRAIL2Parser.cpp b/EXRAIL2Parser.cpp index 95375bb..4023633 100644 --- a/EXRAIL2Parser.cpp +++ b/EXRAIL2Parser.cpp @@ -214,12 +214,13 @@ bool RMFT2::parseSlash(Print * stream, byte & paramCount, int16_t p[]) { // do the signals // flags[n] represents the state of the nth signal in the table for (int sigslot=0;;sigslot++) { - VPIN sigid=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); - if (sigid==0) break; // end of signal list - byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id + int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); + if (sighandle==0) break; // end of signal list + VPIN sigid = sighandle & SIGNAL_ID_MASK; + byte flag=flags[sigslot] & SIGNAL_MASK; // obtain signal flags for this id StringFormatter::send(stream,F("\n%S[%d]"), - (flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"), - sigid & SIGNAL_ID_MASK); + (flag == SIGNAL_RED)? F("RED") : (flag==SIGNAL_GREEN) ? F("GREEN") : F("AMBER"), + sigid); } } From 3af2f6779221e9ab8008efe94b88acce22b811d9 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 21 Apr 2024 19:41:30 +0200 Subject: [PATCH 288/310] version 5.2.51 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index a9ab348..ab13219 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404061747Z" +#define GITHUB_SHA "devel-202404211704Z" diff --git a/version.h b/version.h index 0b8c1a6..19b046c 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.50" +#define VERSION "5.2.51" +// 5.2.51 - Bugfix for SIGNAL: Distinguish between sighandle and sigid // 5.2.50 - EXRAIL ONBUTTON/ONSENSOR observe LATCH // 5.2.49 - EXRAIL additions: // ONBUTTON, ONSENSOR From b4e7982099ee2a56f80a077a293425ef1f297112 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Mon, 22 Apr 2024 08:12:08 +0200 Subject: [PATCH 289/310] remove forgotten #define DIAG_IO --- Turnouts.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Turnouts.cpp b/Turnouts.cpp index 83603fc..ca5f890 100644 --- a/Turnouts.cpp +++ b/Turnouts.cpp @@ -123,7 +123,6 @@ return true; } -#define DIAG_IO // Static setClosed function is invoked from close(), throw() etc. to perform the // common parts of the turnout operation. Code which is specific to a turnout // type should be placed in the virtual function setClosedInternal(bool) which is From 83d4930124e9286577e380d71e9731f83d38d0e4 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Fri, 26 Apr 2024 19:04:20 +0800 Subject: [PATCH 290/310] Fix F446ZE ADCee support and add STM32 ports G and H --- DCCTimer.h | 4 +++- DCCTimerSTM32.cpp | 22 ++++++++++++++++++---- MotorDriver.cpp | 36 +++++++++++++++++++++++++++++++++++- MotorDriver.h | 19 ++++++++++++++++++- 4 files changed, 74 insertions(+), 7 deletions(-) diff --git a/DCCTimer.h b/DCCTimer.h index 44c85f2..c3fcaf1 100644 --- a/DCCTimer.h +++ b/DCCTimer.h @@ -1,5 +1,5 @@ /* - * © 2022-2023 Paul M. Antoine + * © 2022-2024 Paul M. Antoine * © 2021 Mike S * © 2021-2023 Harald Barth * © 2021 Fred Decker @@ -135,6 +135,8 @@ private: #if defined (ARDUINO_ARCH_STM32) // bit array of used pins (max 32) static uint32_t usedpins; + static uint32_t * analogchans; // Array of channel numbers to be scanned + static ADC_TypeDef * * adcchans; // Array to capture which ADC is each input channel on #else // bit array of used pins (max 16) static uint16_t usedpins; diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index 0c1d5d6..7a13919 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -1,6 +1,6 @@ /* * © 2023 Neil McKechnie - * © 2022-2023 Paul M. Antoine + * © 2022-2024 Paul M. Antoine * © 2021 Mike S * © 2021, 2023 Harald Barth * © 2021 Fred Decker @@ -34,6 +34,7 @@ #include "TrackManager.h" #endif #include "DIAG.h" +#include #if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) // Nucleo-64 boards don't have additional serial ports defined by default @@ -363,9 +364,9 @@ void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value, bool invert) { uint32_t ADCee::usedpins = 0; // Max of 32 ADC input channels! uint8_t ADCee::highestPin = 0; // Highest pin to scan int * ADCee::analogvals = NULL; // Array of analog values last captured -uint32_t * analogchans = NULL; // Array of channel numbers to be scanned +uint32_t * ADCee::analogchans = NULL; // Array of channel numbers to be scanned // bool adc1configured = false; -ADC_TypeDef * * adcchans = NULL; // Array to capture which ADC is each input channel on +ADC_TypeDef * * ADCee::adcchans = NULL; // Array to capture which ADC is each input channel on int16_t ADCee::ADCmax() { @@ -383,9 +384,10 @@ int ADCee::init(uint8_t pin) { uint32_t adcchan = STM_PIN_CHANNEL(pinmap_function(stmpin, PinMap_ADC)); // find ADC input channel ADC_TypeDef *adc = (ADC_TypeDef *)pinmap_find_peripheral(stmpin, PinMap_ADC); // find which ADC this pin is on ADC1/2/3 etc. int adcnum = 1; + // All variants have ADC1 if (adc == ADC1) DIAG(F("ADCee::init(): found pin %d on ADC1"), pin); -// Checking for ADC2 and ADC3 being defined helps cater for more variants later + // Checking for ADC2 and ADC3 being defined helps cater for more variants #if defined(ADC2) else if (adc == ADC2) { @@ -432,6 +434,18 @@ int ADCee::init(uint8_t pin) { RCC->AHB1ENR |= RCC_AHB1ENR_GPIOFEN; //Power up PORTF gpioBase = GPIOF; break; +#endif +#if defined(GPIOG) + case 0x06: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOGEN; //Power up PORTG + gpioBase = GPIOG; + break; +#endif +#if defined(GPIOH) + case 0x07: + RCC->AHB1ENR |= RCC_AHB1ENR_GPIOHEN; //Power up PORTH + gpioBase = GPIOH; + break; #endif default: return -1023; // some silly value as error diff --git a/MotorDriver.cpp b/MotorDriver.cpp index 66d1b71..da9d3ee 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -1,5 +1,5 @@ /* - * © 2022-2023 Paul M Antoine + * © 2022-2024 Paul M Antoine * © 2021 Mike S * © 2021 Fred Decker * © 2020-2023 Harald Barth @@ -38,6 +38,8 @@ volatile portreg_t shadowPORTC; volatile portreg_t shadowPORTD; volatile portreg_t shadowPORTE; volatile portreg_t shadowPORTF; +volatile portreg_t shadowPORTG; +volatile portreg_t shadowPORTH; #endif MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin, @@ -88,6 +90,16 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin.shadowinout = fastSignalPin.inout; fastSignalPin.inout = &shadowPORTF; } + if (HAVE_PORTG(fastSignalPin.inout == &PORTG)) { + DIAG(F("Found PORTG pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTG; + } + if (HAVE_PORTH(fastSignalPin.inout == &PORTH)) { + DIAG(F("Found PORTH pin %d"),signalPin); + fastSignalPin.shadowinout = fastSignalPin.inout; + fastSignalPin.inout = &shadowPORTF; + } signalPin2=signal_pin2; if (signalPin2!=UNUSED_PIN) { @@ -126,6 +138,16 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i fastSignalPin2.shadowinout = fastSignalPin2.inout; fastSignalPin2.inout = &shadowPORTF; } + if (HAVE_PORTG(fastSignalPin2.inout == &PORTG)) { + DIAG(F("Found PORTG pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTG; + } + if (HAVE_PORTH(fastSignalPin2.inout == &PORTH)) { + DIAG(F("Found PORTH pin %d"),signalPin2); + fastSignalPin2.shadowinout = fastSignalPin2.inout; + fastSignalPin2.inout = &shadowPORTH; + } } else dualSignal=false; @@ -393,6 +415,18 @@ void MotorDriver::setDCSignal(byte speedcode, uint8_t frequency /*default =0*/) setSignal(tDir); HAVE_PORTF(PORTF=shadowPORTF); interrupts(); + } else if (HAVE_PORTG(fastSignalPin.shadowinout == &PORTG)) { + noInterrupts(); + HAVE_PORTG(shadowPORTG=PORTG); + setSignal(tDir); + HAVE_PORTG(PORTG=shadowPORTG); + interrupts(); + } else if (HAVE_PORTH(fastSignalPin.shadowinout == &PORTH)) { + noInterrupts(); + HAVE_PORTH(shadowPORTH=PORTH); + setSignal(tDir); + HAVE_PORTH(PORTH=shadowPORTH); + interrupts(); } else { noInterrupts(); setSignal(tDir); diff --git a/MotorDriver.h b/MotorDriver.h index a6ed1f6..3438c05 100644 --- a/MotorDriver.h +++ b/MotorDriver.h @@ -1,5 +1,5 @@ /* - * © 2022-2023 Paul M. Antoine + * © 2022-2024 Paul M. Antoine * © 2021 Mike S * © 2021 Fred Decker * © 2020 Chris Harlow @@ -26,6 +26,7 @@ #include "FSH.h" #include "IODevice.h" #include "DCCTimer.h" +#include // use powers of two so we can do logical and/or on the track modes in if clauses. // RACK_MODE_DCX is (TRACK_MODE_DC|TRACK_MODE_INV) @@ -83,6 +84,14 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #define PORTF GPIOF->ODR #define HAVE_PORTF(X) X #endif +#if defined(GPIOG) +#define PORTG GPIOG->ODR +#define HAVE_PORTG(X) X +#endif +#if defined(GPIOH) +#define PORTH GPIOH->ODR +#define HAVE_PORTH(X) X +#endif #endif // if macros not defined as pass-through we define @@ -106,6 +115,12 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO #ifndef HAVE_PORTF #define HAVE_PORTF(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 #endif +#ifndef HAVE_PORTG +#define HAVE_PORTG(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif +#ifndef HAVE_PORTH +#define HAVE_PORTH(X) byte TOKENPASTE2(Unique_, __LINE__) __attribute__((unused)) =0 +#endif // Virtualised Motor shield 1-track hardware Interface @@ -145,6 +160,8 @@ extern volatile portreg_t shadowPORTC; extern volatile portreg_t shadowPORTD; extern volatile portreg_t shadowPORTE; extern volatile portreg_t shadowPORTF; +extern volatile portreg_t shadowPORTG; +extern volatile portreg_t shadowPORTH; enum class POWERMODE : byte { OFF, ON, OVERLOAD, ALERT }; From 742b100f65e3f7182e3e52917e84d4ef64e0cb22 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Thu, 2 May 2024 09:48:18 +0100 Subject: [PATCH 291/310] Comments only --- DCCEXParser.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/DCCEXParser.cpp b/DCCEXParser.cpp index b9ac3a9..431093f 100644 --- a/DCCEXParser.cpp +++ b/DCCEXParser.cpp @@ -70,8 +70,8 @@ Once a new OPCODE is decided upon, update this list. L, Reserved for LCC interface (implemented in EXRAIL) m, message to throttles broadcast M, Write DCC packet - n, - N, + n, Reserved for SensorCam + N, Reserved for Sensorcam o, O, Output broadcast p, Broadcast power state @@ -91,10 +91,10 @@ Once a new OPCODE is decided upon, update this list. w, Write CV on main W, Write CV x, - X, Invalid command - y, + X, Invalid command response + y, Y, Output broadcast - z, + z, Direct output Z, Output configuration/control */ From 76ad3ee48d769a653981fb2e8b46fa6b7f91887f Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 7 May 2024 11:10:39 +0800 Subject: [PATCH 292/310] STM32 bug fixes, port usage --- version.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/version.h b/version.h index 19b046c..0677dec 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.51" +#define VERSION "5.2.52" +// 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others +// - Add support for ports G and H on STM32 for ADCee() and MotorDriver pins/shadow regs // 5.2.51 - Bugfix for SIGNAL: Distinguish between sighandle and sigid // 5.2.50 - EXRAIL ONBUTTON/ONSENSOR observe LATCH // 5.2.49 - EXRAIL additions: From 16214fad66fbfa217356a510192d93c12b042c54 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 7 May 2024 11:13:19 +0800 Subject: [PATCH 293/310] EX-Fastclock bugfix for address check --- IO_EXFastclock.h | 1 + version.h | 3 ++- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/IO_EXFastclock.h b/IO_EXFastclock.h index 5ed237e..11aaea7 100644 --- a/IO_EXFastclock.h +++ b/IO_EXFastclock.h @@ -51,6 +51,7 @@ static void create(I2CAddress i2cAddress) { // Start by assuming we will find the clock // Check if specified I2C address is responding (blocking operation) // Returns I2C_STATUS_OK (0) if OK, or error code. + I2CManager.begin(); uint8_t _checkforclock = I2CManager.checkAddress(i2cAddress); DIAG(F("Clock check result - %d"), _checkforclock); // XXXX change thistosave2 bytes diff --git a/version.h b/version.h index 0677dec..443475b 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.52" +#define VERSION "5.2.53" +// 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address // 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others // - Add support for ports G and H on STM32 for ADCee() and MotorDriver pins/shadow regs // 5.2.51 - Bugfix for SIGNAL: Distinguish between sighandle and sigid From bd11cfbf8b8a8030d1eb58d462c5b639cde32d5f Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 7 May 2024 11:29:49 +0800 Subject: [PATCH 294/310] Bugfix EXRAIL active high signal handling --- EXRAIL2.cpp | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index b811145..96763d5 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1218,7 +1218,7 @@ int16_t RMFT2::getSignalSlot(int16_t id) { if (rag==SIGNAL_AMBER && (amberpin==0)) rag=SIMAMBER; // special case this func only // Manage invert (HIGH on) pins - bool aHigh=sigid & ACTIVE_HIGH_SIGNAL_FLAG; + bool aHigh=sighandle & ACTIVE_HIGH_SIGNAL_FLAG; // set the three pins if (redpin) { diff --git a/version.h b/version.h index 443475b..3260ebb 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.53" +#define VERSION "5.2.54" +// 5.2.54 - Bugfix for EXRAIL signal handling for active high // 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address // 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others // - Add support for ports G and H on STM32 for ADCee() and MotorDriver pins/shadow regs From 1449dc7bac4d375c630a5bd51515d0008b3913df Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 7 May 2024 15:12:37 +0800 Subject: [PATCH 295/310] EXRAIL move isSignal to public for STEALTH --- EXRAIL2.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/EXRAIL2.h b/EXRAIL2.h index 794eb86..8750e41 100644 --- a/EXRAIL2.h +++ b/EXRAIL2.h @@ -187,6 +187,7 @@ class LookList { static const FSH * getTurntablePositionDescription(int16_t turntableId, uint8_t positionId); static void startNonRecursiveTask(const FSH* reason, int16_t id,int pc); static bool readSensor(uint16_t sensorId); + static bool isSignal(int16_t id,char rag); private: static void ComandFilter(Print * stream, byte & opcode, byte & paramCount, int16_t p[]); @@ -196,7 +197,6 @@ private: static bool getFlag(VPIN id,byte mask); static int16_t progtrackLocoId; static void doSignal(int16_t id,char rag); - static bool isSignal(int16_t id,char rag); static int16_t getSignalSlot(int16_t id); static void setTurnoutHiddenState(Turnout * t); #ifndef IO_NO_HAL diff --git a/version.h b/version.h index 3260ebb..bcf6470 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.54" +#define VERSION "5.2.55" +// 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call // 5.2.54 - Bugfix for EXRAIL signal handling for active high // 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address // 5.2.52 - Bugfix for ADCee() to handle ADC2 and ADC3 channel inputs on F446ZE and others From a610e83f6ec4e1c943d06f63b913ec802f1723e2 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Tue, 7 May 2024 18:20:37 +0800 Subject: [PATCH 296/310] Bugfix and refactor for EXRAIL getSignalSlot --- EXRAIL2.cpp | 30 ++++++++++++++++++------------ version.h | 3 ++- 2 files changed, 20 insertions(+), 13 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 96763d5..38fd394 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1,4 +1,5 @@ /* + * © 2024 Paul M. Antoine * © 2021 Neil McKechnie * © 2021-2023 Harald Barth * © 2020-2023 Chris Harlow @@ -1143,20 +1144,25 @@ void RMFT2::kill(const FSH * reason, int operand) { } int16_t RMFT2::getSignalSlot(int16_t id) { - for (int sigslot=0;;sigslot++) { - int16_t sighandle=GETHIGHFLASHW(RMFT2::SignalDefinitions,sigslot*8); - if (sighandle==0) { // end of signal list - DIAG(F("EXRAIL Signal %d not defined"), id); - return -1; - } - VPIN sigid = sighandle & SIGNAL_ID_MASK; + + if (id > 0) { + int sigslot = 0; + int16_t sighandle = 0; + // Trundle down the signal list until we reach the end + while ((sighandle = GETHIGHFLASHW(RMFT2::SignalDefinitions, sigslot * 8)) != 0) + { // sigid is the signal id used in RED/AMBER/GREEN macro // for a LED signal it will be same as redpin - // but for a servo signal it will also have SERVO_SIGNAL_FLAG set. - - if (sigid != id) continue; // keep looking - return sigslot; // relative slot in signals table - } + // but for a servo signal it will also have SERVO_SIGNAL_FLAG set. + VPIN sigid = sighandle & SIGNAL_ID_MASK; + if (sigid == (VPIN)id) + return sigslot; // found it + sigslot++; // keep looking + }; + } + // We did not find the signal + DIAG(F("EXRAIL Signal %d not defined"), id); + return -1; } /* static */ void RMFT2::doSignal(int16_t id,char rag) { diff --git a/version.h b/version.h index bcf6470..eafba6c 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.55" +#define VERSION "5.2.56" +// 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot // 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call // 5.2.54 - Bugfix for EXRAIL signal handling for active high // 5.2.53 - Bugfix for EX-Fastclock, call I2CManager.begin() before checking I2C address From 86310aea4f331dd2cf3d4a727643e085f59e1800 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 9 May 2024 15:18:00 +0200 Subject: [PATCH 297/310] getSignalSlot minor typo (and indent/comments) fix --- EXRAIL2.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 38fd394..f401eba 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1145,7 +1145,7 @@ void RMFT2::kill(const FSH * reason, int operand) { int16_t RMFT2::getSignalSlot(int16_t id) { - if (id > 0) { + if (id >= 0) { int sigslot = 0; int16_t sighandle = 0; // Trundle down the signal list until we reach the end @@ -1155,14 +1155,14 @@ int16_t RMFT2::getSignalSlot(int16_t id) { // for a LED signal it will be same as redpin // but for a servo signal it will also have SERVO_SIGNAL_FLAG set. VPIN sigid = sighandle & SIGNAL_ID_MASK; - if (sigid == (VPIN)id) - return sigslot; // found it - sigslot++; // keep looking + if (sigid == (VPIN)id) // cast to keep compiler happy but id is positive + return sigslot; // found it + sigslot++; // keep looking }; } - // We did not find the signal + // If we got here, we did not find the signal DIAG(F("EXRAIL Signal %d not defined"), id); - return -1; + return -1; } /* static */ void RMFT2::doSignal(int16_t id,char rag) { From 91818ed80c2d01d70634bf3746fcbb887b126397 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 9 May 2024 17:06:33 +0200 Subject: [PATCH 298/310] apply mode by binart bit match and not by equality --- TrackManager.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/TrackManager.cpp b/TrackManager.cpp index d66b999..512452d 100644 --- a/TrackManager.cpp +++ b/TrackManager.cpp @@ -35,7 +35,7 @@ #define APPLY_BY_MODE(findmode,function) \ FOR_EACH_TRACK(t) \ - if (track[t]->getMode()==findmode) \ + if (track[t]->getMode() & findmode) \ track[t]->function; MotorDriver * TrackManager::track[MAX_TRACKS] = { NULL }; @@ -398,7 +398,7 @@ bool TrackManager::parseEqualSign(Print *stream, int16_t params, int16_t p[]) if (params==2 && p[1]=="AUTO"_hk) // <= id AUTO> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_AUTOINV); - if (params==2 && p[1]=="INV"_hk) // <= id AUTO> + if (params==2 && p[1]=="INV"_hk) // <= id INV> return setTrackMode(p[0], track[p[0]]->getMode() | TRACK_MODE_INV); if (params==3 && p[1]=="DC"_hk && p[2]>0) // <= id DC cab> From 6689a1d35fc2927f0e5aa1da99525cc8b2b0bf82 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 9 May 2024 17:11:09 +0200 Subject: [PATCH 299/310] version 5.2.57 --- GITHUB_SHA.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index ab13219..8fd0549 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404211704Z" +#define GITHUB_SHA "devel-202404091507Z" diff --git a/version.h b/version.h index eafba6c..dc6dfc3 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.56" +#define VERSION "5.2.57" +// 5.2.57 - Bugfix autoreverse: Apply mode by binart bit match and not by equality // 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot // 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call // 5.2.54 - Bugfix for EXRAIL signal handling for active high From 66791b19f53bf2470d22c36fd28768f41d71455c Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 May 2024 07:43:24 +0200 Subject: [PATCH 300/310] remove stupid comment --- DCCTimerAVR.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index cb9e685..2806b07 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -186,7 +186,7 @@ int DCCTimer::freeMemory() { void DCCTimer::reset() { wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms - delay(50); // wait for the prescaller time to expire + delay(50); // wait for it to happen } From 86291cbec41ca4b9f53a73a6212d21fa9198c239 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 May 2024 07:45:28 +0200 Subject: [PATCH 301/310] signal id of 0 does not work --- EXRAIL2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index f401eba..6980f03 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -1145,7 +1145,7 @@ void RMFT2::kill(const FSH * reason, int operand) { int16_t RMFT2::getSignalSlot(int16_t id) { - if (id >= 0) { + if (id > 0) { int sigslot = 0; int16_t sighandle = 0; // Trundle down the signal list until we reach the end From 2172d2e1754fd9dbe87cf2c8c80a3ddab0bf9185 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sat, 11 May 2024 08:46:25 +0200 Subject: [PATCH 302/310] make WDT time longer to work around bootloader bug --- DCCTimerAVR.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/DCCTimerAVR.cpp b/DCCTimerAVR.cpp index 2806b07..656ba7e 100644 --- a/DCCTimerAVR.cpp +++ b/DCCTimerAVR.cpp @@ -185,8 +185,10 @@ int DCCTimer::freeMemory() { } void DCCTimer::reset() { - wdt_enable( WDTO_15MS); // set Arduino watchdog timer for 15ms - delay(50); // wait for it to happen + // 250ms chosen to circumwent bootloader bug which + // hangs at too short timepout (like 15ms) + wdt_enable( WDTO_250MS); // set Arduino watchdog timer for 250ms + delay(500); // wait for it to happen } From 06b8995861f0dfac3300f9171dc6657cc0c754e1 Mon Sep 17 00:00:00 2001 From: Asbelos Date: Tue, 21 May 2024 20:04:11 +0100 Subject: [PATCH 303/310] ALIAS(named pins) --- EXRAILMacros.h | 2 +- version.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/EXRAILMacros.h b/EXRAILMacros.h index e9e2f77..827c1d2 100644 --- a/EXRAILMacros.h +++ b/EXRAILMacros.h @@ -75,7 +75,7 @@ // Pass 1 Implements aliases #include "EXRAIL2MacroReset.h" #undef ALIAS -#define ALIAS(name,value...) const int name= 1##value##0 ==10 ? -__COUNTER__ : value##0/10; +#define ALIAS(name,value...) const int name= #value[0] ? value+0: -__COUNTER__ ; #include "myAutomation.h" // Pass 1d Detect sequence duplicates. diff --git a/version.h b/version.h index dc6dfc3..e5e0241 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,8 @@ #include "StringFormatter.h" -#define VERSION "5.2.57" +#define VERSION "5.2.58" +// 5.2.58 - EXRAIL ALIAS allows named pins // 5.2.57 - Bugfix autoreverse: Apply mode by binart bit match and not by equality // 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot // 5.2.55 - Move EXRAIL isSignal() to public to allow use in STEALTH call From 449a5f1670ae12000020fcbf72e1a4ee6bac7511 Mon Sep 17 00:00:00 2001 From: pmantoine Date: Wed, 22 May 2024 07:16:25 +0800 Subject: [PATCH 304/310] STM32 updates for serial ports etc. --- DCCTimerSTM32.cpp | 17 +++++++++++++++-- WifiInterface.cpp | 3 ++- version.h | 4 +++- 3 files changed, 20 insertions(+), 4 deletions(-) diff --git a/DCCTimerSTM32.cpp b/DCCTimerSTM32.cpp index 7a13919..0917455 100644 --- a/DCCTimerSTM32.cpp +++ b/DCCTimerSTM32.cpp @@ -36,7 +36,20 @@ #include "DIAG.h" #include -#if defined(ARDUINO_NUCLEO_F401RE) || defined(ARDUINO_NUCLEO_F411RE) +#if defined(ARDUINO_NUCLEO_F401RE) +// Nucleo-64 boards don't have additional serial ports defined by default +// Serial1 is available on the F401RE, but not hugely convenient. +// Rx pin on PB7 is useful, but all the Tx pins map to Arduino digital pins, specifically: +// PA9 == D8 +// PB6 == D10 +// of which D8 is needed by the standard and EX8874 motor shields. D10 would be used if a second +// EX8874 is stacked. So only disable this if using a second motor shield. +HardwareSerial Serial1(PB7, PB6); // Rx=PB7, Tx=PB6 -- CN7 pin 17 and CN10 pin 17 +// Serial2 is defined to use USART2 by default, but is in fact used as the diag console +// via the debugger on the Nucleo-64. It is therefore unavailable for other DCC-EX uses like WiFi, DFPlayer, etc. +// Let's define Serial6 as an additional serial port (the only other option for the F401RE) +HardwareSerial Serial6(PA12, PA11); // Rx=PA12, Tx=PA11 -- CN10 pins 12 and 14 - F401RE +#elif defined(ARDUINO_NUCLEO_F411RE) // Nucleo-64 boards don't have additional serial ports defined by default HardwareSerial Serial1(PB7, PA15); // Rx=PB7, Tx=PA15 -- CN7 pins 17 and 21 - F411RE // Serial2 is defined to use USART2 by default, but is in fact used as the diag console @@ -54,7 +67,7 @@ HardwareSerial Serial3(PC11, PC10); // Rx=PC11, Tx=PC10 -- USART3 - F446RE HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5 - F446RE // On the F446RE, Serial4 and Serial6 also use pins we can't readily map while using the Arduino pins #elif defined(ARDUINO_NUCLEO_F412ZG) || defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F446ZE) || \ - defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI) + defined(ARDUINO_NUCLEO_F429ZI) || defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI) // Nucleo-144 boards don't have Serial1 defined by default HardwareSerial Serial6(PG9, PG14); // Rx=PG9, Tx=PG14 -- USART6 HardwareSerial Serial5(PD2, PC12); // Rx=PD2, Tx=PC12 -- UART5 diff --git a/WifiInterface.cpp b/WifiInterface.cpp index 87d5437..fcf9932 100644 --- a/WifiInterface.cpp +++ b/WifiInterface.cpp @@ -1,4 +1,5 @@ /* + * © 2022-2024 Paul M. Antoine * © 2021 Fred Decker * © 2020-2022 Harald Barth * © 2020-2022 Chris Harlow @@ -70,7 +71,7 @@ Stream * WifiInterface::wifiStream; #define SERIAL3 Serial5 #elif defined(ARDUINO_NUCLEO_F413ZH) || defined(ARDUINO_NUCLEO_F429ZI) \ || defined(ARDUINO_NUCLEO_F446ZE) || defined(ARDUINO_NUCLEO_F412ZG) \ - || defined(ARDUINO_NUCLEO_F439ZI) + || defined(ARDUINO_NUCLEO_F439ZI) || defined(ARDUINO_NUCLEO_F4X9ZI) #define NUM_SERIAL 2 #define SERIAL1 Serial6 #else diff --git a/version.h b/version.h index e5e0241..2079a1e 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.58" +#define VERSION "5.2.59" +// 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE +// - STM32 add support for ARDUINO_NUCLEO_F4X9ZI type to span F429/F439 in upcoming STM32duino release v2.8 as a result of our PR // 5.2.58 - EXRAIL ALIAS allows named pins // 5.2.57 - Bugfix autoreverse: Apply mode by binart bit match and not by equality // 5.2.56 - Bugfix and refactor for EXRAIL getSignalSlot From b17dc5a0dd4e28e87f1173233c7ef9f3b8a2340a Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 May 2024 22:39:43 +0200 Subject: [PATCH 305/310] Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized --- EXRAIL2.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/EXRAIL2.cpp b/EXRAIL2.cpp index 6980f03..088b79b 100644 --- a/EXRAIL2.cpp +++ b/EXRAIL2.cpp @@ -228,7 +228,6 @@ LookList* RMFT2::LookListLoader(OPCODE op1, OPCODE op2, OPCODE op3) { case OPCODE_AT: case OPCODE_ATTIMEOUT2: case OPCODE_AFTER: - case OPCODE_AFTEROVERLOAD: case OPCODE_IF: case OPCODE_IFNOT: { int16_t pin = (int16_t)operand; From 843fa42692b50570a28dc4eb06c4781379071750 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 May 2024 22:41:50 +0200 Subject: [PATCH 306/310] Remove inrush throttle after half good time so that we go to mode overload if problem persists --- MotorDriver.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/MotorDriver.cpp b/MotorDriver.cpp index da9d3ee..28fbfa3 100644 --- a/MotorDriver.cpp +++ b/MotorDriver.cpp @@ -638,6 +638,10 @@ void MotorDriver::checkPowerOverload(bool useProgLimit, byte trackno) { } throttleInrush(false); setPower(POWERMODE::ON); + break; + } + if (goodtime > POWER_SAMPLE_ALERT_GOOD/2) { + throttleInrush(false); } break; } From 0c96d4ffc2e1af26b97977b6f575fd4451b407e5 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Thu, 23 May 2024 22:46:47 +0200 Subject: [PATCH 307/310] version 5.2.60 --- GITHUB_SHA.h | 2 +- version.h | 4 +++- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 8fd0549..4807e45 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202404091507Z" +#define GITHUB_SHA "devel-202405232026Z" diff --git a/version.h b/version.h index 2079a1e..ddbcfac 100644 --- a/version.h +++ b/version.h @@ -3,7 +3,9 @@ #include "StringFormatter.h" -#define VERSION "5.2.59" +#define VERSION "5.2.60" +// 5.2.60 - Bugfix: Opcode AFTEROVERLOAD does not have an argument that is a pin and needs to be initialized +// - Remove inrush throttle after half good time so that we go to mode overload if problem persists // 5.2.59 - STM32 bugfix correct Serial1 definition for Nucleo-F401RE // - STM32 add support for ARDUINO_NUCLEO_F4X9ZI type to span F429/F439 in upcoming STM32duino release v2.8 as a result of our PR // 5.2.58 - EXRAIL ALIAS allows named pins From 264a53dacfaf502654f80206c972153db3378ac6 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 2 Jun 2024 21:10:57 +0200 Subject: [PATCH 308/310] ESP32: Refuse IDF5 --- DCCTimerESP.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index 93711aa..8927573 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -76,8 +76,13 @@ int DCCTimer::freeMemory() { #endif //////////////////////////////////////////////////////////////////////// - #ifdef ARDUINO_ARCH_ESP32 + +#include "esp_idf_version.h" +#if ESP_IDF_VERSION_MAJOR > 4 +#error "DCC-EX does not support compiling with IDF version 5.0 or later. Downgrade your ESP32 library to a version that contains version 4 Arduino ESP32 library 3.0.0 is too new. Use 2.0.9 to 2.0.17" +#endif + #include "DIAG.h" #include #include From a26610bc7fecee556e3b46f0bffeca878a15f100 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 2 Jun 2024 21:44:25 +0200 Subject: [PATCH 309/310] ESP32: More version locking --- DCCTimerESP.cpp | 2 +- platformio.ini | 6 +++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/DCCTimerESP.cpp b/DCCTimerESP.cpp index 8927573..e57f6af 100644 --- a/DCCTimerESP.cpp +++ b/DCCTimerESP.cpp @@ -80,7 +80,7 @@ int DCCTimer::freeMemory() { #include "esp_idf_version.h" #if ESP_IDF_VERSION_MAJOR > 4 -#error "DCC-EX does not support compiling with IDF version 5.0 or later. Downgrade your ESP32 library to a version that contains version 4 Arduino ESP32 library 3.0.0 is too new. Use 2.0.9 to 2.0.17" +#error "DCC-EX does not support compiling with IDF version 5.0 or later. Downgrade your ESP32 library to a version that contains IDE version 4. Arduino ESP32 library 3.0.0 is too new. Downgrade to one of 2.0.9 to 2.0.17" #endif #include "DIAG.h" diff --git a/platformio.ini b/platformio.ini index a03ff61..b39b136 100644 --- a/platformio.ini +++ b/platformio.ini @@ -164,7 +164,11 @@ monitor_echo = yes build_flags = -mcall-prologues [env:ESP32] -platform = espressif32 +; Lock version to 6.7.0 as that is +; Arduino v2.0.16 (based on IDF v4.4.7) +; which is the latest version based +; on IDF v4. We can not use IDF v5. +platform = espressif32 @ 6.7.0 board = esp32dev framework = arduino lib_deps = ${env.lib_deps} From 5f65fd5944d6def87673a3d21881b4d21bfcac68 Mon Sep 17 00:00:00 2001 From: Harald Barth Date: Sun, 2 Jun 2024 21:45:43 +0200 Subject: [PATCH 310/310] tag with date --- GITHUB_SHA.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/GITHUB_SHA.h b/GITHUB_SHA.h index 4807e45..6abb9b3 100644 --- a/GITHUB_SHA.h +++ b/GITHUB_SHA.h @@ -1 +1 @@ -#define GITHUB_SHA "devel-202405232026Z" +#define GITHUB_SHA "devel-202406021945Z"

6q;qa#QRt}IQ#_blCg>pkbXx0)5+Ht1b}0pqZ>S6Z6tL!f|E{51xgIAfs%y!p(o zr9|+dBZ|hgA7yGQ<-p^hZ!MY3ZVaVXb2*f)%w=i_S#lW}*X&iyUL1WsB!4X2DEfrKK1E8hN)z#$B zb9r#`+`kuMS-wK2fE)sf04M+ebpWhp1(jw)D?3Ki!6Xidsu?E^M~Tu_Bv>6vM~ zCm`^z&Yz!5SFA-Nl?qC1mL)?jvKVry#jFYD;@0~6-B(K^Eo=Px_Z%J_3>Y5#?X9;@ z4Gk{qe6~KGovEp*HysTwbHIvYF|t%uAg(V0MiMcCX|NMNEPdd;;N>{&tt|P% zOS>3t%u&UA9CwO|RVon7ttaV#5+GcN)3E?b4utl6<;<2yv8Li=j3$sIReB27;v-q7 z0ai2^7{^kxe<1s7Jw((mou|T6%N+5~Hrm6}VQXrll*S!Dh(a2wFBnS$6UJ=J2_W0q zk1&1Zz2@diAKkL^TG+v%)y2(>JbL*$KsO(oSdXb9{{TVmgZXvin%ALc z2i^Uzx2SPAtTytjp~qn9W1_`UjD8wrqo$`N>Eez_@$$;Xis%ERHVJ%Hm($&;Tp;SE8avaH@BawFJ`d{h( z-`fDNP-s5ht3XN5LMF=X4#Vr{@ihbq@J#-rfF+ytE!ssEY%ar&plMHYnzfy zy}i`JX(f@4OGzV=&c}^OJp`nAC7I=xMrqlJW@1^G`Icfy zB>IzHvARnc;NMWW(#L>DI=?&t{@dD7O;o0Ou0}q6NTjT*qN=5@p{c0H*U(EG^jQpj zM6`93buincACc zAc6r09bP#lhD4qj86`}sDJsDFh7=(D#X1{s-y!>F4+M1I-YN{DMzBW&+1wolQn^+r zd_@gxixl#?7Iun~DwYmk8D@fzBNkAmh zUjbFzcWEHLmQbOAr%5+1Xy3O{;a%|T4>E$(1J*y0+{J7Ei_ToV}%M< zML?@Ga5ZFb$EHP$G^mnOuiHtbq_Y5ZdVx0l!||e^P>2;rko5lmXZ$?}@CKC_6df9` zgBbX$erfz(ps5QCH65+CXO-HaVPKTf%~uSxQ;>WUtgxFBHCM@~Av-}XP%UboHLtu9C9zr;Ftk~u0S?|r+Fc+FH))ky{ubzw4@3FzjK80xB) zk~u$Vy-vI-)O~<9SlRBBFX3p;czk2_A5UI|7Y|5f)=ga{pyQtnsZsLtK0w#1*7>JX zQr{?kNzm2GWul<@E%Iujf`w|C=xAFr+`FQxz47ofG<1)VsDe4C)Bbi*bIA9F-1Q@l zb>`T$F^xBC!l2aY)jMjZrm6zerAX`PyV$5=9>@DRaRTYNmy)@8UCNDaBHC@$1c!@w zYFSdh3YrWaiq_5R?3ZnJ2Gi@TZWkY)+yHWf8T_n$qs_D0*m z=l4eC$YP_8Uo05-5#y#wWN8JJBoq68$h+S%%=@*b>ed#J1_ERb(zzcJMu^B*c|BMG ziUw?T4t?l8@?PKjCA8S`ru)g~nK!-AqYb@`32hP+r7kWexJhG)o47(142F!wk}$-h zw}#TI*i&Wt{{SVA+jt3a7#t>76DG~Ai!ax?or}M4k?wts*j;y+p~vDEE3x-}7O>9~ z8ag`KYPf2tDxiw4o@4=@apl|YS=?@R{levC)}A8H3l)(Xoz-f#p~2LW%5ZzC1hMQt zyS%UOXC-Xh@yga0HfsgbT3v0^qD67H-dnjzZ6rkkDh33?@qrYmM2T40S*)XH$e-}w zJCe2GOigxAbbRcg$u%r-R2sOTuIYEj<7NG}O2`^DEeT692f8xJ&#_g}U<5QhlD?!@);QT~#FTEa{N1mEy(VXuRcStdk)uOk6^YS4k{Y!M{E^DedFB zjsRQ4k~d|jVgju-F=|j!xTyq^0MA_M+@QId-b>ivRom@kjSWZvOoXgxE8OhFF~B-> z)r#V&59Q({Z}iMjscEu$ww*FTQIVe+8N|y+xlUS+S)+$L~-#2zS0*YyF;Rt+n5nrJKSsTriTx8GF+s+TQXc zk?r@kR}U4^$8`E*o^sLIq{w7a7{q|AMOjp#XMekYb$hOq+~Xavu$}6pc%1)K7I;e-!|&c+}I( z^%7c3Xz^a!TUkWR?czzPNtJX4U2(afRg+Z+6%_zbk{Ag1nrwXAUwq>yf`+oLTHUvd z#?nw#HYYcd`6tkM(RJ*t%! z$4-x@e3Jek=_$N&xXPJuanj*x1mD5&^!b@yx;m6hr5b&yw|nOw{0&GirUuRMQIuJ-NqPAcmPnSvmGU2T}c>IMqt<{-S4a} zCfXym+axza-4=SdWD_9MEy6M)l|s}Jz`=mhT*_;tJoMYhot=!Xc-kpx43%`)nQc@2 zPa8ETq^p)`(PfUB7}j*Cc+Qm6ss+7`Ica8l&CW>Rk*RGnxvq*TNex_|APG@gY2oTR z75io5CpTH#T&P>PMzw@@EYXx?a(K`HM2xt|0~zVF24asJ6FilsRqhy&A-w?9P;>ZYn&?_YIizq*w?~kB*~?F zWhA-}7h0JIYe?g^M|XLiFBU?9%Xlheaztd3p@IEI0)dTO4OJySn4Ua}K0=Vu3e<`3 zI#R4_xhYbaNNRO5yTK%8QrdLsh+X|rGX)QA*7Lht+=&!kNDWa(V@8YdP!py@l6YdI5v=bql4bi34Mv$(dT3szj7YJm z#L21ST1c{yI2z+GrUDV~1IFnva)r^jx3G-6NfNjbYRfK~;=VzD51^u{DgXiP<6ns& zWGkdlsrZ$NQl^6$TAY3waZ)e;$2W~K=`RelF(SD$wqx<`_+82sCsdDv5r~wg8 zO!$0)%X=~end2czAcB6Q@MX=dRd&tb8u((=)bY->!0Jibk~Ox!p(c=I{L2af^6O{s zU4;?|XesLNLtn_$etjQa^!{Yu7=Ad?Z?BL0^W?^R6&B9HRAc*J1=pP$ zy1ql@emd+e#a6J^V|R}6*?R+Yw@T4VmRKsW)U~z$0DX(Erh-~pNaIkCE%Nr|%qHGQ zwxqb5Y>HkdPlmD$f7!f*7AO_RVP!z1cG8_qe7-rl-o+!^XN1FF((%?eDy4>{jJ+A7 zELMoj$_|A9CWYwRd_ddZ81R1|a8mp?t=Ze#pf~zxGaTH&mUyzqbT+5%wh=`>6gqh)mr4LKznz@1YEz=EUw z=<)Thm*>&{0Jnf9#d|6Nr|Jei)u;2}^5fA0?W(=uUy8z1?p%4LmFsHd^BQb4(WX>MIs;>EPFKqWZI;T{LAcy#m>@l|RnRB`ze zpR?!D`j@Tu9s_M)={IKCqnfWXhQ#MK-`iDVvh=l>Jib1bOiosMiU*e!QA<@%A=fyX z>0`q(n=YA{5}a6m!JOyUrHYM`+$&Clc=v1U91z@FhYz`O`!^eqpC6X1p~Pe*%tM>I_LR(SoAL04>bY?rIhi&e^ zh}%o1vb_!5xt`xooe}POSu*=oHs4)P_2PUo$mLH??w#*XS5MhkPmsAx?}u zG1*)L!BHJk)kSlDTiJVHsxG|^mtK=C;pz?^aNsdA=(`~w_vT;~+-^3J17 z14Bxp_@&evr{r(R?y%^6fmyJy+uON!-4|c%2zSQkmtgh$o5wj!TW@V@jPudu=fc$P ze87(xji(g#6V&CZ>FKnVmf^@a)tFQ(8k%QKO+6}ULF!29w>TgSRCT=f{3WX~pX>Sm z0GZy=$;U_3{gJUYUrAE#>R#R3d5Q8}YrDGVGxA?*WN7;bY0+nP=2mJRx!e@>wD}w) zb(q?j9+}{Zwhu3sEzKljZ~CQi;nhfB3w&eHWr?8Dpn}J=Wb~pad`X~$#?HmSpkTH6 z24F&0_=sSmxPk>b*k7(YqvTe_?XH;Ve6L;nVHn!4k9~ntTerSG%R`FZI8Mi+-Fwe* zbp}&6)R~>mGhI#b^SL^QV^q|rr z@OX?y7Ca06oG=Q7ne2@VLYsV1BCV*m1k@13=t3A&lc(ZiQfsJS4wg!b^%rDHOx_~^ zwHy_*!;cUaof=Q9uX%&QI zF=ilJ`W#pTON?j2Vm)%eQ~bRnk*ZYrR3FRFt(B@^+BB;!La!*ac^oY@MmnV7YbC78 zP)@ZEBvhE{7%J-W30pa^hy^j}{ z{{V#xZ*94epKoMkqwODz11U*@hY^h0^zvbT74?o@zaIoR#;L{8<}jOvo}xU2F@K-Q ztlHIOb^}(tts2AEh$a_06fQ@M@>5d>cAQuKeUif+4gYb(Ycpy8tJIo zmcC&0)oBq?JuHb}38v{@=&n4bwSb(MHo=N|#S3RKqP@N;9U+YennXLHg+i_WDSX;n#)nu0j$)`GTb znPY;gIU{J|lpt?yj4ti1HUZxIMXXeT~rQ;d1g&~Z57 zjMr(-(W9r6e9cVq(ZMxcdZi3iGrD`l!gCSLsijBVJvXQIcN=kR0 zfh8uXwLX?+c+{6R1KEtxg5tj!3O{16N#T*>8j`io_)q$WSHJO#43T_&#V+U+)iXud zw2?zzl2<+}F}Tw|xe;n;{_)m1a}nZVlUym}H1TlWlB`&{E*Zaut51;9)&BrF;nm?) zXUH_teEkTZ{{U5bHyGICqNswFF+2UuY|+M#8wp-Ybzvci8Fdk$Eu-N;Hn_e0pd^*A z0tZS*acqiEQ`GwOy@+FHt<5C2VzeW~HLsV1-{qmN`Lk9Ls@?+i{R8r;)|4M_r$;a3O+*sq=zoY* zM>@lXsJt-3H5uyVQv_8s&?B_v>Mjsiu(i0k_KYzzFd1wC^EK(xDiBhKO@G*NxoW!?$DFomCn^voV{@RpFt^OOLA0(q}e31o&^` zQNvZUjMcOd4;4y?T#8u5ys^ZpRoIe8b#*qb-$GbWu*p%TpjN(hxz`ArUYNxIAgIUT zHKwXov_7@!&(@P*CJ4`$-WVE5aP77+8EpP*a$@il6#2SZ%u;7@+s&$<>~`K_xuub4 zDW@^Zd7_PZXv;cY!JabCpcck>k2=)ltB#v7-i<&-AsP*PNgpG_fX00~pGRA?>nd?H zIBb%f#T`aosjMvTp3u5me%6D@7(fV@TS1X*8B?3^b2y7m2(uv=l*K zAPKE%e9xT^_$k%ZWd)0qmcaEG7#@|!rGGwzTy-YQ$m4Jm&~Di)W2l2OkgA?6)*g~v zoSS}FS8>e@a4LAP+kT>_!&Gb@kQFnVva?=66KQA&FohDFg7sqzPhki~jZ;c+-xh~mySw6t5Ii^|8|! z&b=g<+Q9p;(ke>h?eprorUOoqt2xtJ4?O<>m!%ah*2Tjdh4&_M7{qbIIBmlUtAqQb zRk4T%n4kjW0u)>6&%LORNhFF___6cpw|Qu)61-{KoNy!kj;B^_)U2hiOeW{A#O10e zW~RhetyLaYlOI2Ug(X44xrUm$l9FPxNlwhGDuOi&h7JhCip5-pKho7h^B*rxnekaj zEgF&L3X%H{&)1J%IbZl#Uj5t|{{WOf4YmgE$5K)64zuX3_BSnMI#ra+RPL?ikCKBW zi?5QF3OuIQt)RgP=^a>A(^N}QPgx97#*aE10V&_NshqZv1++kUcA1=>Caio>Q$@y{ zW20-=jBFb`F{uFET}xW|I@_QWrYYf(N}pQLfHn2_P4dsbz9j7rl)IPXr)6fkt9x&) znbn&+CAqNl8+$57*G|WaFO{UIq1?D!-4&`OqJ#>F);XaXfNd_yPn~>NS_u^RFCvpd zLG4$k0yvY=Byu!UE2TB*AXEk!1o2ovjtexlb}d7`!<$ZeN>1vw3D%?pcEhv zE;&AY1!>Sttwqk~6V8F5h7eaEjcuqFZ^iJ`Eqi#MiifYA&+{$I=l3`Brv7R<{{Zp~ zoRoQPsN3eMNinpEjN7|QraHH3W0Hkx+|)}|_OuBTibXR@!K5}4{NIa-~AC)zAl-WxbuYsU~Qsjd4vZj2hp@aTbyZ8oV(XU=E<= zffdv`TmJwmMcr9n<{$Bjj|rThz-8m#)n^ZxIHt?TkE}aaaGKJD#ZxWGXsPLNru zAj(ITrHe{a>XE#1Be1pH?`4$POFG3$SHwt=kU;p20})xoaLsqRj(ljMH>_=kY&oypa|G4_@whkJHMLw5WdUW2yx zhgW9B9&Wd>HV=4F?w#ATyGIX-Y>L-QiN)>=veQ&OREnl(D-2e=+jo|VDK6v<7({1L zC}9~O4J|+hunMJBNFHXINhII)t-{jgGj$Y`2{MdYqqu65Nhe5Ps#(+$&QXGvDbcv- zU8}h^@6VmB26_sL9E^K2c)e~mdFgBFDY27m`DDaX=@wrfaH!a7v zxn>Un=Wr#mQNb0c2V7VO%!*Lc&b=LS%t9@~1!&z^J5rtaEef7PXHC$D4Z=btL_rX4Kz8RnD8M1>o4&uAiwY4+q|{=ho_Yb;*?x0;zE? z>v#H+NWPXW__y@t{{5fJt@@G2uRsCx7G+U(A$jBrsb=7+-}CtQKd)0CW;_AFQ=oOJkwVQxQCsL~crMSJ+{XNxAkO$+h`j1{b1$z1L zf5My{zuEHZbkV2B(bDODY~i=1do|Sk3b-Tb&)3*Z02iCt@;5*AjdT3^W12A+FN)NC zE7SgR8k%{3mYq}v)SbWCeA~3nbkkPnccV`t6XjpF%0}8zSNu=c`(ICR*D^*wue*fn zLn=dV0P>?n)DgLbJl(sqw+JoA?Te!KzHt-K9N z-}-wM^8Mo6+|3kdOT=`Ne9b(*T`${Mwb59Voj9*SbmBIm;Y!{`AdsMfpbK1BkU{+W z6vC`7i7j5=^?uHTcIf{AP*}A<$4s>e5XoX$Nelc(8LNPK`>0RT=s`bUX1hryLLZKL zH`<@|&b|T1@?q8F1(fxM5j09<8%qe}Mm0$y$x}x9l}a#hENnTj_lPr!^F7k(G#4}e z&i=loES;O#-I74VTWuR?&#s$#o~rxjl)hcl*S0Eeir(^iRS{Ilyea`zL{(K6OYkkv z9`Xa({Mz#q*9L2U`mjIG*D-$n#Qyd6iVZZ=x9+F*-+||!!{^oDd`}AxKy;X&P=&g8 zt(?g$DFA3r)rH-_C&lnzbgRn&gI|+ihk4f_AKHbbum3rj) zj-3okbH}inXB6*W6bef6(clJaOSp zku+CDNK3#N(uY7a&T1>4v##GO)6ub0)_tCi6c;16@GMZ38d*Q%7&^$La(~48ZTF5_ zD$1Obq}Lzg^Bhy>AFg_3?XS3Y^#dIKlM(eRFJ|N(P0Z>)zFnw14Fh%i8;H zB}p&pSma)^k)=SqhO&})x3qHZ8&if@`DjPx57kQ4ryLX#opn(hUUm=G{hRAc6a9)y<_yw>KvL0O9VDUhS$>$+0WvhtxDnPtmBR(JP{9b>{uFh+v zWhA#*_H-)6e2Y)p`+TAiU<@K&uV;VBI-303+tKeFvZ$f?8D2m>FWwg*lTIXfbRS^y z>&+eO02b*NyZ!fESBJ(tzrof-%XI2R3eTBxi-WAlskm?#sP$y-vPELOj3Sg~+EL_+Ov$^6Op|=6}Z$ zx&Ht|AD80t{(W}Y&XE5ApI_P<*f}KkMhqsS%0C@c80$Z*8v*^F>F(!xk1n;~UeSl|5yKy(xIVuZ zm+U@$V>zyrW6xQ3dW4S32Xo+tq6i8cw^cby@=dM*JX_ljxokBhIZ~Ma0F=p3mmlo> zj%mQt)25BK=bCQfo=3n_{{TPJsb9xBPsAK`muMY!jzm4vf<{AdBXs`&j7&qK+vs^D z^I>moE%wqGi*oQPYeDr=ih5M&&#wSHy4TX~T1Wf31meG-l;h+z`Hr(3w@U_P{{Tf@ zn;SbC108l-tZO>yq8D3MN1XuiWZsGFm?XRC2R~U)k~geRE9LN-`)NS=oS_>jS&7Jn6lp1ocRbTEpl;zqgln<%LMqxfNN! zHE*xE8i^)`fhY(R6c{wFI(Ngq(o|i>2_S+a;p!=`HTC1^)_6AuO4B;Bb#G@#$Mg^M z*N0JZ5AG|cRjbD!zu?>Yd)VGNUVt|uEod?~8RgGdbK9O;A^*;7DZdk5)30k02{n*_M=BMEE z#Rr$Jdh;#aF>x3q*WfrFgS#~KBdp^q(a}UEi>v!Z;c0vxSv!*x5`U6ZlRQej|Ff~3U_9lKOxlC%XG~s6CSYaMTA9o^mk@1qd_w?Zw$pc zycpzt0D!{k4emi6%f{ic=!hOz)XKCc>n0k{@e!l9AB1DiuYE4zithga^+7)@>goEE zJJi*$jK==}qpkM^Icb~AknXw)cxh&<2~Tl;vioF-V_?lAC~{P4ETh_VyW0ROCdL_u zpN}fk3SfXgnEbf)Z>PTC+nB9?-zksy)_O4C5NN4sK6?CghXaAiZQM>LxHgRpG+T!? z4(6-IO#pPLY=-2c#bF?dRy*tNC30P)CyoF1-2K^*b+ut>H=fv&&r|ak;ye_oGQ&T6ZGl%j zad{vVFPEm6z|yd^LZ%v4QU0pK@_om90+zf+FObN7(hYy&{Rcv;-q>Uy*ABlv)9tDOm@)NurfB;V3e$U-Z4CHYGv1{l9jt%|ce?8Rm*Eq(&YW?SO zesnUi&(F{Hb@b!x6l}i4`!HHYX8x&d1Nt-@eYoxQ7@$27UC!CsY_7uJSgrG0v9jH7 ziru?w36#fg-QCm~IB}cyrmC+hxc<=V{GKCp;OZ-CYwBQ{0`t>X(ACRM@#!Fe2PO0M z_bb}I)is-4SZimEQ0bO7YMCj6tscF~-w724nCcq)$9>f{&wcj|znQkKZB37w?P5qK zo_IygobV$nK(e89Fi!(1@MVdCZADlT0qOq$c(-e{RZBo zs>W>1q1L@~w%2ZT?#bGel@(R_Dy$|C6lR)A`njqra#gjJ6*9Hu2!ZZz=4-BKxqIm# zNNtudk;VyNio9yxta8*CBAGQNN%jlb4qo;Ll=kjU+VAc!_eZ{a%e&b|i7xK0O0&O) z4v`v)EHxyE=|UGut&{C3Qj6yv;)2d5qTZi4kYwu7;qlU$dTu9LIv7jAPc*JpOH4d$ zp+Y(a(g$C9*drfxec@$^$_{kf)|BqA>X5_?1LzG#omI^``B?k?Ok0{{oGK)w*{~#* z02E9o@fFA=g$bs56uZJm#@Wp2ReJbw6+Q-@dEum^#?%!1+O}s|V`|Ekjah*z%*q20 z;YsJeDkSS1LEec<&}UKdugGLj{Qlm#ow+<>OIm_uts~=8RvN2Xfv$qJ{tym8=_~LK zmV%}Z*)=tg(bL6Ovt*~Q$g8Y%HivL5k|T)8mMA1DU3d~k;@_nEl(xdA`th!J2;hX- zsBJ>D)b0UO_)763@dN!HnXrxtw_DV@nmCayQl#ZUF5~%NviXX7b$6d7pAOkRo55~9 z!J5TmX>fbGilUyTwr%G=8}0DhJ+Rm;Otj0UN~+mZy=_#I%p?;ek(kk3mwxpUO%~(J zw!3t0+qJB>pv5iAOKln#vj9Tu3WFMll0vT`m7Qs)I)>ix4YFJR0B?5v`**yx+5{Jo zyRmD=g;oo1r-Bf)CRyYI>Lg|$g0d|UUZ7fi)RYwG2o^Jtj8fDzm8g|DNwKiB$&Q6t z;-^=nglT|AUCVk9n2RvQ=^|IUf(ae&ZynI70O~@=Nzwk8pR-8(`icBW-)vE~#id5qsIz2is>sxt04@8nvR;X!a)Ts6*JPx zjZH@dU09i#c^;Z2oYqG(80DUVGpEj_d?l9bLjV}FmE?r;7Tr~JVD%(a)|C_^$l|_~ z&rMwTv5%#KSmYW4JE_c+0kuZhEUQo)QiXML-=)-T6Yb0rsl0$+GD!eh8mCia8`(q-( z&RZSTtc=IObu=BM_-|EuPbEWQ!qiP96!`pn)f3IQP*&B( zwDo>4k+nS=jV?b^T?snEk_+DDxQ5`&w-)|9o*thJF)|0hhEYJJlYv@Log%u`Pf`?C z;?mCEOMwoDAPA6>W}`6DN1896s4G)iRVSCmNkFEyNW2h7Q77>@kgHFHnA4f5B*!Jv zN`yrPxC2t5kw+3CB!N`3fokjwnp!o)fS7VTjV5R=2X`@Eq3+J1ZEr-txiAa^K|>z#?5#Zzz2`Q2IFhl0oNUg~|jO zmoHaMJnZ#wWd68T#?HdhC1N8AinL)IVA3^=wh(?NketUfwn2I6&b8$ zO&&iF@(&GFy0&)l#z^kFr|P_G>Wb_lMJ&WJB>ROzGikUMdSTs~_pw6Ocy_@K?);2ZvjE8aLEqElw&ZD_nh)6{+>5IFNcMSl^JH zx3zvd?cSll?oH=|+EpE~Ro@t_#U^s5lBaL)qu0yTb$MJhLgFbhFlTD^LQ6tsgD`2{ zgv5T%Dd9=WPZVxcIu8#+3R0kkBT)3s1w}LFda_99I~;>hLG&WDKPpwJ_SA6b0IH$N zVyB|ZWY;4l7ImYo$7U*;VAYkB#u+AmyLLZ47YT z%sfVU0%@%%zY#d54xZ&-GK3Ztr7t{@J+y)ZQ4ffeC*xuehGUXw4Gw~Do6+Qr9(tflveTHiV#SK#_c}C&s1)D4dW&wA+@qOipenZWScWIvp^a& zI8e6}-dt(a$g(KzJT$1F8BjY^V*-cHq?WF0!sy6@*3ujdUHLD+=Z;${Ie}TOx zy?T>+_Rr4jrZa7Cj-dESSDo2??Xz}|VBj+SqqlblX~m4{J)ybg+gYmmEb{eD9_HR( zb1w0EI;=;F310|Ro;3EZ+C_@k&KFX>P;nYbAcAo~7z3v{^5N4H0%d5VS`-1kRjn+LgyKL+lI_;^o_J-mke(kQm>>762xqS5mwG?n=G3H#|RV>vG<;!z#40jX5 zapK!}lLe<1@il2+ICy7JqgITRD#oCiGETDyq>sXtK-Ez|qydHkq&6}sP}LL%9T|?c z+!%hs-+e{ayLWZ2XLNS<`q=$@vUbE7ExS>euH4;$m7%5EbX6D}R^`ZMaS%`?SZeBp zS!2Z0Lp=2ku)!;>R^ln75dg*b3Sd+MYpBoxKzoe^GXVcT0Ki&jt1`BRkf-hc0E+%z zeKmhGkAz*v^2_Hh#R{IS{{TgmIgEEp{7d-VlEULVKdsQ?`?KS%4)~_-?xU-oEyqW* z$8zoc-L_@G(e3KIy)|`qYB$HnBF;R1=>*EVt?l?FqLy`>QzeySilRSJL~2vCX*m?@ z(s?J!!nMUkK+Oo~>E}P1r$z7j9EN&)20yLyGv&8rb=`B?J@eN)YrZy~ zUm3hJ8)qT0H^)^b3bQ%2I~r`R9gJ8bB=rEz3aBzLQjp$+xfa418bVjK6`rN4LZ$(4 zLTD&K6vcXUL={ny`$(W90ZL;zAZNW%ZcBgO1J z&Ahf1e(US%{{WD6op%nxuiv}l5t^#leLuCkYZ10HF;w9yGIeiNn8stOYUQO8QyCR9 ziEiPFIn!5)=;2RjV!D+}5!~8zu+d+O&Z4yu{*$+cNo7}BiWV6Sr!}BqN{|5{fslFy zHXeIw{B_zmu7mD5u$^_-zZ7=<)#}kUVeicN?NZD>s72%hcny6s>Da0qahy4ZF(-aC2IpmlmP) zp!~7NtC{L8!!Ix{LUqnQ3EM zm!_x3W$}+JL^VR9>U1k*HXhJ2)k}j=N7?rEeN}a39$E9J`#lWXq^>uvemco8ZzF#& z&y5t&C2cy(6>UROZ&-YEkVK5sIU2bg(V5&u3R#0G1p9U!J|&{}d{TX%*tZktJcp%l zde9n{`I)jH`zUp%=1*9EnU;SqgzAp`-5Y-^k=nV9sqw$J_f<804pzGjk-}BtHcsHK zk12!B;qP0H%P6I_6;(MBQdAKtvbu)$TXIz*oumY&H4icg0FU;?L}2nxN+K;S4V2RZ%4D0)S|tn0RDV zZ9Wiq@JyCpG9{>_42ncilNGM#=aK*?kA| zueRuS21_xq`sSLWv{$tEw#&n8%--kiTJ3|dvpC#-=*9NMKG55Bu)&eZVYAW5^A<&Y zF*s%tsU<`-k1F4$Yoiz*gI1C$lcxh6ZM2d8F(putdu0qY90nn4s|1fg2^Hvl=&zTZ zXW!o?Hpj(}i@WB7diRZfF0XmyI?HbFF2{U!%##g|nfK*qXYRboiwA(+n@CVcOJ0*K z^^sLi6(mu~Jf<+hs+W>67PSP?w2cG`93BJ`ah&iZQ>#cPw}hYR>$x*|PvfJq;OpU4+ZbEkVlYQeDj!{dL-4XN@6cpd)$+1rP8 z_D(N!()Iq>%;kFPzi``2aqj((U(^^KqaHa9aVqO3q0jB}4WAdLnq|7G{Wa3c5!GRD%BmMFjtU05`YNEKk(SOTC^O>!tnz4*iOXJz+B z!s;E{lG%O5gV~+KQw{^Adw;q5)2y~O)%iC;M~|$^(QeML*}EICGd+dX_@3LrVXHSL z(ua9tuyyrVWR6FTo<&BaX$OsO9E&KLbk>ozH4qb7Bq*R{PUi-NMQ}8*UEG=*uL?*^ za4`ju+LbS)X=gvGx~R2KL(~ z#Wq6$zcYFLzl7}!o+|?#Z1lZNwEqCR6^pueGN;<(Ye=G|jyCUqOmImYx&WRB2_S3n?b9fXNOTG< zTOMUc`A6*FdPt$A@RM02<33uAG1tzA{uTcKxuo1*G`=NORnnMpl6*&^$z-Ngk}7(M zbKB1`k%=kk%|!7-6&xT&G#fYpkJs9310mhFrXw0*{kmH}o;owThr`)+gQ%0@+zjv; zj8pl3Wd7P&{#{#R;dc4M{Gi&OH@o+C{B_tl9g)^`n;&=VeVbLgHy(F;W4jg*n`pcn zV|M=l2-}TCRMmM2%`{_8G6N|64sR^J6}reFX(SS@6-@yIHlp7p^7JPi6+;o4T^=$< zG_lm&1~?BYo&&2Ur|CcVPtMPuXz%U6{K|e|Z!XBdRMKvIHqWElQaycE{n{UIHqF2; zdV{2>Cxv$guj=WHygj)#eJ-JfSP=stDr@|>9=>p2%y$P3 zSM!_xXw?z;VEzrcI@2Jr#~QpfH8S-#TT?hm5Ro3S8a$K)nBxZST65= zeK7Zz3<3F$AGGxf?i*pZu-jo`pu=^1$4Kn}-OS>gF-HUvDszs7FXa-#FXnskB?{O@ z*|nf*TO)nO)7)^VXS$VSX@O7bz%S6BX4`6No+5EnVgCRbJrGLI``?pXGSF`J+M-CZLUx{~G?ZM(F)%&wA=2qvsyO35yOd^BS#fTXdtj2#q@ z^Uhq8Q>84B;&SOVJvdgUYE##kwM1EbXwnGk-oi^Rus(z7?2BXyE;jIcz#C}72s)~L0*sR6(q>PP?2o_00oJ-Ha7Zxe?HHL+g^q} zV*N!;>mU`m2J9D6QT?uYzt+RvzFl||`E~!$+$zLr(g=}NeM6NFPd6g>QT{jfo28VS-k;43f2Gu1)BFELH__!ZK!eh_v(359c%N? zT&<%?RRYny%Wz3UbM&~nfpdNjx}1C>zNf8muc_?WjNkQjxOGo^Jn87&q=Cs}o8E!q zzN5}g;lLmTjG+YE^X?$#QeT|6LKc*Y-iPdu{5*PsH#oy{e(fM&DHXVf2l>y zg+w2uAESSVvwg4oME?LvPxyKmR^^tncx_#v+kdBDc+w5c zk;qe2?;M^AuL89Fce9|zV{$T8Z_UXSbh6M=PSn)T4IM#wqtL4Ov2C`;dB5*cO}WDd zh4oUPZA8lINLW`$Z7#u!0@PY5&knwqcP?(d+C8uK{>sCZFSjPT8#R>A3aX`)Ge;Sd zaGj)NR$DN9!{{T#*nEj>!ss_=xoP75=f5T3%590nJs|E4frZMu0c9x^3_6};D z=~btQ!=Bmn*_f2WB+~1ug)7x%OR5<)SSa*~8u^FROzT<^PuY*>PPy@B4uupN!;$h7 zB!8-$c=fG6Wxt<$?g@~yM%88YxaUv-U3f$Ys>6X{U;y?pP6|A_AY!`SoGN-mqBNRf z16+(vf>@LFwZjkrzvBMYaHmc2>OQxI}S# zTi=1Ddf5aF_0%MWMjDA*>C^!L8;?*RsTThL3!i!)J{@}olni`S-eyHS_CUeRG%6fEiKANact`<>E$=0`a}T zG0uQ`lzkX`_60{;eW-C`m23^Hn=C< zNUaZ-TI-n92wn&-7+hGMdFPg2=sEYXU&_628R|(=UiV{O@jm=U zH6FAuenfSQmS9NILAsDgCqNd`Z}lJVKI~Y4pp12~z>4FnvFb;$EVn~(r&!hfmGP1e zlm4i354yD&SIe(t5IS1W#`P66a6*e+Q978H#7Xl!pp}bMglTlPo<*(4x(bT=AM$nX zJUH}gJ`h)~C*}`8JxjORN7;KlXQZ)`D$0e+MNf=^rY%8{}k!5i3xpK`4m$|2XLLrWBm zETj7nt1!RQ+<&n*_~aB?jYIkW0I|@X>=udYzyKflDZ%-%!1{ECX4ds2=dYoyM+x=P(KX0FtH175@O5jf{2l>+DOq zdk5^8bfb<@+DTK2R>l+M^60W{jq$d2uWjs@w;syu9oc}(^>=B|)YElt=ISkvyQ1wn zoWwN!f48vvx4mP??93L_%j0O{sm)YFOIMSPVvoj+N|jJgGkZHXFUPm;a@HfvUL_eF zv_FPHF}!RQn?NAz3xOt*;e{8jb^ic(wWmMJx$-14e(+yw8W77gQOP~9yVM21yNVK_ zuDmu+r848f60BNeZDL1x*7Y5KW^c;=jD5LR*HwE{t*Wzgb=@jc^&MAx%dz2`dS z8X=pjq~C0&o?11B5ZR{59CT|z;Jkb8wEJDpFwHfYjNU!E{Yi`{h|B=WfN7|Tm*5GZ zU(+epO#Q>{y~Kmqepa^U*sf!>i*S{8mAo<=)Y~<&iEfOwkmzhgSeDUIEiMGZqy4nz zs*~ok6q2gCwk`4VzOkxZ2AqU))%3zoEpd=QC?ZKTtBF!Yb+7?L1_yt78C|~Y8>E6j z9l6JEsbP`;oDzKtaQ(hj>*lZfz|=1|qQ?QEy|7rZKp=LUSMqa~V@Y?r=Tu$Hav8mS zKD5wnXT&`&=$jZY^>wcl^{Sg6PDdF>T~BO!W@KWpHl~_L>DibfEtx;wi^RR$xnfED zBWjJgjZpZCp-bA3JSOdp<^YnblBhM(iaHeg**4-o*89LVZD7La#F0CY(gm{pWLIC) zSxKa9Np}&kI#qI8CW@jbt}R5Aw9!v0R#Hlf;%ViPjPDIkVgh0C<(3(4o^rnc(0)-rZi_}CNu~8 zGe*_nsp3^~oY6nRpv^H_nkL~2Pw>-&a_HuZ3!rVTx zwUCuo1nA&oCB7Pgq_G5nPM}ReO1O$Dib_hFe3Tfb`@cPOc^~3bl4R<{6!^lTDCs1} z83Lj*dC}Y}>QfwmE6#0V_P#V*TOxQ0Bvq6bNzx+l>HtkT!66v3lyE#-R9ib) z5*AIuH~=KKiLEs?5jX|WUeQfJnl(n2=snM>3}j7JQVM;~+~VU#ma4j{xAn|&@(>Y8n7)It|~AbKOeOg_5dIuA{_(Y}!qR>Hx$_SF@6#MQw; zlgZ@QY_P?{JaWfUBZ4@RLo~?h>vRf@azNXZk|?ZqU{tXBl{6>KqZA{~f`=R{(eBDN z`+duDGI)iIG1LkG2B#rI9Oow-KbJ=Pka zEbF>nt^9LKxlbu+S=_V9CURJTq#*2$HC03yL{iL8&b#NnZzGo6`wi=H(PNE18zd=y z-gst)c;2^}5JnZDW26$KTc4@+CFMwh+ZI=@sG>jdlTL>`gA{49%wv5($_X^5;S}S? zs`+|~iCOhAeNT4PVoCisx#srvF{Lxqgjcm{KHu5acs1FJf;k#)M<7Pveo5eeynFTl z#~!NqRRDa!>GqngNcMi@q}IYJ%FHaRoakw(UT}_VG=^BEU_aMB*mJ7l*Ve864!sjr zLFrHOf1jh#)ipg|jrbiscWPrRGSoBtsoiv&N}mr|Sh)&)%NJ1WX=-H3(oy8`v&XmU zaFb0LnFT{NNJY?!3xzIGWRJ41-Jj^yYySWh($qp$Mj-fg0>3&nKR&Dv`A__h>Ccbf zFShT<{{W6XNllyXu7~Pw-rf6aZf-5={dchP!*uM-pHM}L-doFk?pbhKe-ntU>}c}U z_4O)1pr()-ktUFjGq6jbfCgmJ7|;dOKo3qGpAZ-X(0QJ$v7vPYmNW)}wKV)W_2FMC z*EAgv+5R`sZq0!~{>#o@zkY1}u@yep$o5Y5+j(8DL)m@NU4>1>yLOjbZ6QxtS4*~W zn|5?uE=M&_9!9=6B&e(y#HgpDfr7=@ev<)HrEpxR{A@9%ymX4`9kpT!>f{8Xi8Y!E znotA$BaL+Mt~GH03Un^yFkN+5&^7%jnA^3PUcsg84ZFQ|$6?{I^)(Ugjh|0}lM|on zto9nFnwFwE?4DktO6gvl+B(`uU+yQQaS|z=%RDkhD;O=P`H`lI1`h*6UrLXdX-Epd ziaDq3udmOp{v>>$`5XMdyK5=FJ}LZ@-CrN`S?VfEP31|BO{KW0cSaj+wS83;Cj0BH z=}DN{o5qU;9eq)uma3QTDTMNvq>o!Sw8ey~>PZ9|;=W(u`wlvGDOxRMQCV0}hEP=C zC>1nT#V+o?5v4$4|j{&>dpN)n83D zXlMPaGszkIbmO9ul{5Er8X(hOs zrMSBBFC1l=iQ&V$IRgqf0ZLE~g{p3j>#R2Im$I`teT7B1k_xP)X79{yz0i=+WTwYc z;;Skvrq5C(3REUKj73WIUv#nlv3B))R7?>EtP&!hFbA39Gvw5CPW!8?q%3`Ro(Bts=e1tU>axOxyi`rciXjHaIRv-c<0H&5_ts9Hc^pa~u z3IH5UqjXt(N#aQ(sU$HpIMOnV7yxsEH6Aqt4y_ZXKbU9pbn9=k-#Y_u{{SgYoZb1! zHswz3p`z$L(X(lCcnK-iy0>X|c0;UoZ6@S~s)r{WaLFDwFIb*mAcCQMX)`*@a1_R6 zbCOO0Q$dPnk8wF4;XPCceg5b=~*zmA=u z@Uw0A9baK~{_X6o@47mJdBug_opao~OB1xS-xTt3*5mgE-QIr=VyneIay_q-+jJGM zW}PePDru*U6Wt03QrZ|KpTbDWRf3jpf{gU9a_AazRBB>DuUZ}i`Q9!GLy@&0op`38=k?kZWT3_fXO zV(`3R2=JIGIHMdN;-xt7<6Qi@^IF>L@g5{+BNYdS5~7WOc%QIRoj7&|<=SGJ*y$%R;r;HRgF|v_TYWK zdEs8RLm61Asud$i^{VEd;QM+Vdd5A?+4WsZv@;buZzZ+5`@VMP$W7Yr#UT zNgP?W!DQcg9ZS z+gL5zPq{KvC0;{z?A)FMX=CefPl%4Sv$Yw#wJtR%sHKtWYAO}sxFteIjirL)iFPU! zQ;%@r=1KF$04IRyOcDsEw!x~JoZ|r0)KY+Ylg5LsYkmrRPu;&1{yTie{$IZ(x?gX>?pens&*zT3%+{yGqAV5(8up>lUvyRzqR`Yk0;R?OwAKdNj(ln8%>viC^7k5 zS*TZ-Mt5|f$APXQBA9Ao-~dzuKnVD#L7>miNv}nguEisgRFNZeYE?~Xl_UXzE040Z z&N?+U9e=kzA5i>0@6U#x46+?l+`In(cdy0P?Jten@2s&Mi`JNJ&5F+DcP`AW+ug6& zyPbYv{IK48a5}HY1Wrj1pW&;guE0Qa~ywx&n}C@i;oa zg^QZ?uu=@g5nF&sqbYD|2-HNNtrdn7K~tPi8n1f$<9|tQ&yid6vMYL9voOCT@f+4* z*!{PX>&@@5XB(Tj5w{-l-5uMXsohvCHaB-}jBe(eCp9i^32TITqJd0oh_y%ra7Sqx zMf6}YX)LS&P&+|2)JBjAso)7cII_DtT&%1oZt_57b}Va9paQB%;3x$+bb`zD9_{&m zn(ZC^-QN*+#`D^kt;4#y+v9yEGh@;Go4|KRLtuBl^4yc}%H7-6``2 zslmIMyw-x0Iz<+(=T^b$>3^1&#|^E~`wkw(=8*m<6`rlZSc zDQV`LHJZlmz0JMzskQKXp1f4gJk;>xjy-B5D>RL$ZdjbdeIW{$5T_iW-l#qht@Z%XPcWcIl=UwP++IhPD!9Bq$5WNo8*s$iYHZj?PtF!aL-O z!I5MVNM>1tdS6O-PPJ+KRuLFV_-ciiIaLa&t&-I@56aG<_{pC5^U_(oR_)F2?#Ie? z@5k=HpJVJCw)K{dyD5c*X!joZ%V6j=;5wq4Cqh4q=ZO?F6%(xUMzM*dh{)Sbb9Xn> z>LQGMfK)(DD#TEQ7*SR^(hWK)62!4;l~+*7sp3h^De6xXk5iG+r`&n!da5eO;iQU^ zuN}4bMpGcv)n9QAxi;3}gi^}JFER$211dU#SyzE$%1I*$1;#}LY&^wq4*nA801C}|Nxo(LPnwygXPe=c&X#wV$KsU#03XV#NseT(smEICCz8?` z(pan(B`n>t2=`6s0!SVW4ROJ^dJkXQ=h21ircI}6s?+tZf8)viqt?D16SXrtt7dma zHs9O(hjV0Nrt64bAGWsE;N4ZwW9oNJRJB!76{Gr>(iZ~C}&MoNZK#)60Q=w^Pb@0d59%-ywp1K-#krL{Br7z~DQp!c2%hY7cK z{a!gf=DR4HMw=f|GKHF1XQ^o>l?Re(9I3NgeWaGsjd749n6na1HM0ty>;N!yiYoaG z=W<;|FjesovLFB`0MHXm4kVw%YDwaH`z>r3aMNuxORV%~Z0yL|@;yA0Q5~mHmP6@;?HDqvf-&xYgOf&dps7PxgJ~xChl}L~lR@7sQ zBz4<&Lh>O4c)f1ZQKjyub^OAbGM|O2r-otO$_uD=+XPYx2JM`O4ODBXm=ZywHj<#y zq#BPdm;V6DLY|^8=7;ezSt9aM9?Gk_$k&X>c8=pzbs#Zjr;^ey7Sw|F`ujE7n5@Bw z6bRf;0Zu&3}Q7HfTC`opxl8+_vMdF)Ot z`aTV@i|u5j%dG?C_V(J|8^d($-L-^lr9Blq&Xw6Xsmze80p-zjR$shYNt0?>mRT7? zwy_*!si+b&Vv0#@E3)dsGG#-K~nTMVh)<0QVo6lA?$yK zv|k{5tFAV`O#FfP?eo8JZTx2R?TlZ}T20xwzF2m*R?$693j?3nz0;n(M z6dW-g4t&oN2bn!sFc*@Gb-05d-JY-k-CsVMUz_FA4;APHsiPBl2(l z$KR{g`s5SUaKly9a-~57>Pfl!e^K@K?!EG_Syh2j0$Kk6Qj@??0T&DTB>w=gx4&d{ zuq(uM|IyqbMuT$q3dY~;Y^0IRh5rE8yt|mKDtG}r?7-y?q>GBUsAu$CCAu2 zzFjfRAK3EoCylfJ0M*vd=l*`F_iDPu(YrXZwy)!R*<+9bbd|{!R$w^sg4Sd7{=EB% zd5|-6j_5@wBe$>5^!kA}HFxI?>D8!K8-Lhh=nCvQsB2@OMRYYd*q()=R0!of?>4<+ z-fvuol1Wj=)7Y1mVV2#e)U=9L)(_+d<-?Cl1+6^j8{*1wlbt^(xnA?WB9o|`#0LjGLU{O z^li4e@px3~82`e5OY}<8Ba5Rf^q@Pkp=6b9@pSarme*M^sT^-V= zXl^R{D)`GuLzlzC(9y-tIGKCMN>)8 zeGf}im5^1hLv>YTi<6`{vT3XO{{Rz`$4d{BSCWcceMC)7RJU2-(6j(6j@jG6__9QqCa35>sa2%l_cIdiDQ*qJibPC(pE`c?IQ;t=Nd*N^Jc%- z*u`)Z4jl*1Ni_B86o{89e=2PzvEx(q1?&$7*0&t{Q(E-c$DdK&+z{6{I=BMO{vTU_ zKc~L~#8Vx6J$62#%_H0#3#r>tfmT~$F{X2h^MexmKi zEo=Qf`kAMldiR%HNk!qV+DQrlvcDt}SaJ&9%ebD3(4tm#Ikg>AZ2P5(Q2>O4)z3iU1Ub6*eMRU!Cx&Fw%Jbzwq?_`0GBg3tF zbt;U^Dxg|L@=Wtb3=y)S)loZmVU5JUwRsuz`i`5PNcXTvHS2zTcHz~hhE(y?Lhg=? zY+{lYDJ(=S)tERU;Mv_pMdW0ln{;QT38orfXt z*Y{eIM_a~yI?o(3O)5s3OGp?;t%55s1n3OJC}IZ$kT3c7vz`rJyga({o;Vi;MeIM; zx%!XNN4qHDjwk*vtr~SMSfq)x%#M<14eB@49YZO%(MFU0KJSL%!^^D-kGH7_91Tk^ zmT2OZo>X{YT2?dFq_*=DRHwv(l&C7N^|{mURU}u>s}o;5_1!E9JE(bMjhH!7%oLv) z2FAnCAL)A^RlV$KrcOH6eR^9_#Tqif46Pc;8IVr!v6`Ye6bFHVvo4sO_#>A0O4A-y z$5sHIjCaEnO0_Bu#Y8@MOczZ z$(KY91cZ7R-;gcr0kHo7xt8IGs36nlLOK)fH5SjOj-&j@^ZtLARp0a0Y6*U2e7qDM zI8qOgTk@Ojp;<&TNZBbQ$mU`tQ7IaHxSBaBeP6n-Fl$L+hkoLVHs^k6lHI9t+k~N) zBvc%@CxIsgeQMr)eJcIiX57!Pp32+bz~4@sskfDpiq?i8V~U(zL`7Ijj8ZywRFw^_ zuyY-uy!Mw=ZORqgd#irqcSdUowP-djOSQLdcOA0mtMZxY_V-!hayT=%*Ab7z)l^i} zOOm95nm7U{nxa_Z_IJqM+gWd}v>V4XUdFOKcT+SLFu={CGc!jV(=?Jf>;f$jqP&tYQHD;;+PS@pkPs0x;8CFTBl?0Zo2GUt^MTd&GWL`J3)ue(PDD=vn@Q>`s#RU@tG1VQ%FBTWmr&={Dt$z!lI%EKmT!WekXYTLshSTrwC|Yy1 zj>&PgZnpc2*sxUlX!gS zt;}ktl1f)u*QR8Og8`eKNF$cE2%~9gL{Kq+ghp0UZaDkdCB%PrE!?~y59_Yoij7Ld zP2EaVrASb4Nv<(d@|*YakHO}6 z!zBa~zS^#Ms+-7S$zx4ExiJqM8cbQ}RZ65Ot)^<5N&YApZa@xaO7~<`n6=DH@Dz>Cv{8T{Rv` ziYYMLo;rA^dWg=d%$$nql9vJ{idAho)ccq@T_5-5_0Ra{fVNAh+sYz#a?@#AoM$8+ z3q}Nud3Tlj_g&E2HQAADL3Xxqj;pFrnIeF>EU49@kkunlJzM9>It&$N?dv?gCa!#z zRxP`^X(p*OS&V%q;Aw`=`-y(mpsqTN;DpB?+fl}oK_lv&wG~p6?>#-S=5AUEER>kv zi6(g2JYtV-d{@qZ;aOCoDuGPY^kwgros7G$Cf@DDHR@a3Bgv*z6NeUtimrS$(zFIR zR5WbWl+~0FDy)g1f}bV#H5A`zH4Qy{^#SSOdP`JCi+XsLBN|fzZ7936pSmnHMA)q+ znFYPgl8}MkztYI715Z2>JcT~aqPyT4-V1Bs%z`qZi*~3P38Yeie3)dO;X_p`otUsv zb;kBGXR-7$!<(R=_ySSn{4;|`RqSx+@GRN~>LiUwF=lBPc*YN(MNPLv}Xb7U7SW`4%HrEZ zhU!vnl}v%xRAMlpV~EJQmA;{atwNT0X2sUf(bpMXg0mHduA}}N@V(3e3%oS<}*&tm~*3er@!j8EW`rpiE@7^H7GXdWkW$ z6W3OM$}=V*${4>KSlpQpV2&uHnk|`0S$5J~y<1aOBP7np;EkA2FA&8*H0W!{ zH&&5vn<%%2a)JR1l7O6I2C`nyI0jAu<+?fB{KX^nthQ&A$HTdl}HAsNqZeC7(zNwK$=zbyAElSff-+ z)5jaNos+~P-D1L`vC!07i9tA4p#apCBx44F0lAwQ63CS`RWVB{6q*{eS!K-CCB;J0 z#soqq9y_@7$VdoDeG(FzJ4wamy_>}#lSmB{cLg=l&JHxW6smE+LP-kbo_4T}0lBzw zF%)e=rdIP%C^YcRXlq5OBr&Kzo^1r%7NWW}rIiL|8hFh$1oB5vxdY>Dbz1-`VXBzI z84Ss3j7P`fof}-|$|xX~B#KicAeGlbD@^1ZgZ9$Dh*WeE+@_9cC1{vpf~vF%tbP(t zcB4)#GxBaa`)`DTD(bihquR93Q6|kGzi9OS~~UC@e|s z^EstY%cUE85gdLRgGTs#*l;XQ%b+J26j7OpXiY#nU1^^f~* zXi*tZG~lR=o(_}Dskb#Yo#t>dAq4!tQ2_q{5BiT%Hq7oVujdplVjpPlTz*46Y-RkS zsdD(9iupGN*vLtV+%xVCzf+9M(!|o$V&sHRnondL=Luk<3` zO_eWp?f6eDk;CFs$=geGu@>2fDV3r8*Fo|+veaWkgPr&I=t{1@&yl(;X_(* z^6PHytIPZ^`0I!N0A#nPdZxAJ#O(y!)EzYsT}qp)x!Wm)OpfjBoZOvw2pEoTo7#i0}usTwJ!pFJY1Nd%X3t%znU zPF=@uV{Q`BVj95|QUP{t6dZERr9dojFd2qA(~tfW&6VuUk&^yq-xxA^Sa(NI^w)7m znb{T8*!*rIZ|$D%tE}v;qu98Or$LF9w;7JXZjGU}Xe7u}P*qi9VVem^^sg*Z38arV z;>TmPXGJ$5B<=*AN#M0#=c`H_ii*(n8}qETuyYlKiiJ(d)VW&xDz2#$Fr`U)$fVaI zAPx|9sfWzmvt>6X(qAE!DX}%0SpIy~Ma$auQs52;9@TQ9X|Yx#j8RkaUX6JUHcgd- z3Oh(KkKrDj5=}m{&8|hhzf<(R{{W}4ca=PcQUL@dJizKzIU!tL-k>=8-%EeD_g(_N zeKjcfJq9{^grDxtbOJ1A#u7Ov{OeeuwXc7z`M0(k`+H;OpYU}^sp5h1Jspj$wlcft z;11B+TTd1IXL3?}&Fq}^N}f3>X{spp;ppzIp<2(mt(F)Tj!MBIu`G1Ts4a3X>qPB! z8*onrvVBW|{!dEr=*bHBPgC9EFYKdd^Zx)RR;m903EB9wlB)h~odbaHeyZEq{*&x( zy6^mM=GlFL9>?FCA9(Hg`b)9180;qh0NS;68O$|pEO~9e4o;qrElC<0nhJV=s!|vB z^M{7U^faYq5HJiWf-_N80{~{E04hlUbyi;xkdc;FAOY$N0sjCL0IBNPdKYVdDcqk? z{1)Av-|`b?R4l&*y6Zo_bNid+?*747Y;M}_?cdosFQ2{1wf8x}Zd|Wq{H*KU?TzcW zztK)o2r)R!W?rVWWAgD{zL>?|ZjNh+RlGP-6w<*91KPwYjd(K7Tg8%vl|oTrQqeA< zNuDI3tgS4R6%{#;Nos*Wv4cty3kn@rZlQNSQhz7BCeX=lt(CtzJG3(Ux8z33>IzM_ zo%yBN-FLS3Uqa+JhI?*iK1J;OuJeF$lIfefKOs_um z+&k*G6-U0X!aofy9ZY!I${@9HQBeKUQz>HJH0>;l06@)EP=z#rNTm*PD07_TR~;zu z1S*ich1>3zMs`{TGa*4XNfmHs8%+u9m^yR+(QuvaSElpD^EDw&CAZKDr z#a9}JM$x&{4`p~~?BG2=)nAuYV1d_-0X6>sWBp!z2|Ewx4`05<$mX`b(X&9@Ed^W~`v6$>l5Q(9+~;aw(}L$_+Pl&o9A?{%$6*U zLVAo;TXAz4$fMgeIV^rw21!jVbdfr=Q^wB}s^0dJ>LAe2c~J2<&-r@w0-Y*xzzkNu z?D} zRk@v;yWyeJw&{w!TscWQLZyGP3E4cbXdpqsGiy zqX$pL>rq@(0gp=8s>+ffc*n(F2BRa_(>!_>F}T1la6!Fv2 zwDB~OROcXSdFFGdGq>q-tI1U@gdi|1bY_H~^7VQL(n}y=!;b;RwEcsp2sae9G%`<| z#^!POj5=f=Ba_^nQI*BhL5rlNdiu#SGtIdoqy8NYIWIDSsx(W0IX?FBs8Y<-N@Ub} z(wsQfoIYJOtm`U-5=h}%8sqW5aa${sZv#GLJ6)9=by8oORw-XS-s1T-PtXrnA~z~+L$u?W|qHe)e0@W zyFfJb8>XHZ@^ewvWN2~n%ppmmmEx$7OA{oqsTNRE0lSVXQA%)c+w19Go0Zo<)lC$s z6v?LmN2j0LjvXQU7p^)_a%cOuyf+@(P35)r-gmBQK4|szM%l<=dtF!e4ARu%>K2$(Q&Fgf;#5^_LV&RWfGTPzMtrCMW5$%O zI5cAMG$nA<0hFFKtvHG`Ps)U3dGvC2Cc@~f0Jx8;8uM@R56#H|qb_VO}ZMlcR z?fktyPYpv`wEH6)lfckot8!J@Ex#;3VVNZ4pB~8xltpCsr@FloQdt{Vs349X(V-Y0 zDpQAB@FHM}RI@Lu6G{{2N%OC$8Xdw{OFPl7g#g?wmw*bTzb<)YIasspiGi(CDhg zOO2?KCa0E0h3VMqMk9}S&)*?hjuiWR$l><&?+JA(ETW{7U+@5FTA!bvO?l3`>uj#u z%k8G>{QNkKh7!LAjh>Pmy0#W9?mD9jSzol8ddi>fhE|6aR>?(KMI2L80z^ep;Q6JT ztu&kpan5+=yncN=2p%0SMh$89WCAHh&k%9L&!v{u!am!@P;Iy>`x>Qa@%Syh{9>yC zw+%%2yk#tuxb( zzu=`ZNb45ks-mfbf5}I<>gTK3yIVf9?fix+j~^^KS$3UturuVT=_qRIC}qXgq@f1B zO1erFS$)ye7_MuqQZ^JIdT|uv_I&n-y`pZ()>${U8ba zKx@eS>M@Frm+lO$v~1xiMVjPe*0CJ?=s~BU2hXZ-{$F1+{zZH!+W!D3_t(d6!#!t| z-WzwRHg@sci?X(c_LZ>hyz-e$PBt2S+Y?8NO8nIvX;C~5vIh4!h-(*oG)U@gy`-6 z0P;_2!?X8X_>GCW=h6`0PD)7D~Z{iy)T8)E^aGN|jN0nn>heRC`Ai zoL7@X(#t7PFTz*~jbgk$$_(Iq$?0Ia5FruS+k(nFfMQ3?YGMNpCmelfI{JL=EUga6 z>wJz&IbVvw1`s3pR12jeU`wP65Yn#ftoa zGzaFt^Zx*PZQjKGav#hOci^fkqQhn?I@kNRRiDMnj;qecf$A=@#8lPeXs3BADDhc& zDWs^!JwnATO$Ux3kPLcrxbr4-b z@a(%3Wz~m+EQIMRQ7rRFq$%zd4_Y-Cejpm7qapmHDJO5{bMZP=c2b>zk*M^aSP8T@ z33$@uK{G~5fomK6eZ9A{EU%!GNS?Ig!^*g=Y4XQJ>XqF2Fe}uq?E(4IyC3B1=&84| z(9~mSDJY4Su9{^`l_ev`P-u0_E3#x~mArJ0Vs(_EK6X+xAp{>{9kJtk8)F&m2m$k< z10ekC$E=6j|oWaOSD|#~t%ibLFUZ z=GdghOPGt}{XbFe8m{~78r+3NBiCYf{?wBnw{g`sse+2E=N2gvYJo}Oaz}$);nfRYI5Z8klKcQ>%>)1HAsooT;JiM0Zo)+oiIGMV4ED#}KO!&*4PRB;FNS5{&eW zvFO!oER6+!&5W!_SIrE2!m^b-axa0OYEeLR#^4CNku%!AzhqeRVazl>XT( zPv`k?;nRBrqFc2fD5R1a3;~LM%9>NF5Dluv#SbKXN|XZnbc4YhoBI)gP6oN?ZZX%E z*LKnvIA9BabX?x!pRI+t_rFfP*G0e)lG?x6+Qaem`djJGzjePcj=91|Hvxk!zPy8S zMUA;PAJ^ZHTO2qT9)>`uY1}Z-wwZU@73caDQD;AV?E!O^Xdz~U0mV24g-hY8kgQ`=c;8XbF;6azt>9IVND0M7Jde+$bz8bqMzR~8 zE~MO&q}!jb=h>tRKB3()kNCcgtS}9@?vLXro?iEv0 zBZ5|)Men2+CcuARX4`7%mD|rh>ic>&+Y++2Y1}`<{(h|Ox7;0-y*h8={9Ee_(D`lb zaT{}a_GfB7TW{=biME9;H26K;xHIWND?_oe5;{$htffkaf{r;BFk~PYdzCpR&9}YV zn77NAPSUp$csUKGXJ-y1MLL6}K#dJGvnz1xw7&8E<2PGBY`Hhuzi)Oe!}{wc(`?tm zI9wOo;EEQCYdM*8OBDJUt|gCKTdXog+VwpaKb8LgAA53}u5$hBx4T1Ye5d%q*8QUo z$G`St`th=~8(Rn2nf!j>-t_%*PqerE8-KQ_HobK&BD*Pu%v9mi2a%?#Nh7IB%86+s zovgNN9k3v=jZt(hR1G`@1C_1`0A_$1P*+K(HMx)6&SB?>ojH>FN$wU&SzVaQ5J>u( zC6J1g@eNICOR;8d;nnBtsTsO6pk;cNsDb_>{C`NMs%Lb98eWy#)Y8*viM7W|PVtb4 zr%*ruH}+9@z+6h9s5N?epY>;;y}fASneiWorlZ!Y+u~^-ab%B-K@8@SPXe%b&+M;_ z$Le%1a=;U*Z)4A~#Rxh`p|20mpy}h~UXn5uy7=#N7!S#`k_(b_>Ga?54gUbw_MkOO zW2zCvb&L{NDYrK&2h_vG?2G%6s37_dpd~+5(Fm4>R0LS)hkovI`^ku z)OASz0MV=m;2-cJ+I0c-_pm{$9yROTM02QywVP2R@CuRmxc>kjbwAt25@vW6C4KvJ#Cb9<9(xDZMcCNswa5qQVf0>q zHutV4uX=UgAFPYm+?C*tI5+wWAFaLn=U%tehMrlKL!VBCOMg(8)6Xq?{(h(4`1y6Z z=d58!<-I9>LXJn|e~s<$M17rmBdq1of@uQ7hS%yO{{Y8MPa3%6@$TMTy=(I7SZxZj z#Ej@7Sfy%&Mn$M#!P*@bvVm;``oX>L?!X!f{{XAkuNn#g*G%q8YAh6JNXaMlAF8Rf zxqrvI9^~uZe{We0l~Y&+Lprfm3`i^qR$swO{{V&k>5hLP*S$y2rwV$>#XPjDAvCoW zFx5#Gh(@{KSt5#4D@J8jiaA(WSSbgPNCZ`@Ks@QyfE1uT2zwuDWp_nR;A~As--)(< z&B*VX+Fb5piw*o!8HcT*g0mfke1y=$oZLlgRpQ3N#-^?mlg6h>_vKoN32G3v`*TWt zzLoy~4_c`O6d^UQ4=?sQHNVT^uWbJSvvsu2yW3Gu%wGkJn#c;L4juGS#54gnpQGCV+TJ!v!|k=mIBAOSKGtO&yNcJ zeQyQPqW=IsJ{nZgsVfI?*OwB;w(!*8Gt|t|Lm^FKIOX(dB*!L~x1{?3a{92lgj3SL zu>Syup&j{eq3VBP5qo?oQ`z@0ZeTqSI|#>lq(dgoiAT_?j|+nlQtu1RN1V#wz>5eciba z-PYRq!+7U;`CFMRAutWWO|OAHyO37e<}1RnGe*i@-O+@IOARi+3fp*Z9LHh}&DdLq zaBc0;oZQ=g5sZf;v+=m>F3H91jfc0FX>6^Tu&{V~yoNs$vo=N_ANI8Iy-i(g^-WPx zSy4S)^GHa!x0p9BWWT-KHz))$1S+tAR79Wyr%M2J5kl1fv7sQ6Ns&E@_J5Ooj^yrL zm@zZ@Vt{CCf3j{=03Uy$e)Q zVro7nRU}rO!^^Le&%c`7Ma}lj3+TCxZGmESGVxm__- zwAA^GH7!m<3l(eB!39Jl{f}T_YHB2srUjC;85W)ve;OCnc!@>lmdCX`6Gq-E76rnP zC<>EZB#zdoB8Hg&95-C$-z0)59yl!)IBroj#u%`X^QPi0WU>O|P>ooDR^q0CE&RFR zpC+BhPft%CMy6V<5QcfT2*CdU6@jq(m9jMGgG7~Z%?wJ@>2KLYRwD9yls3yarQB}| z!xPAsQRojLk4tKpxD@!6fEtJ4?LKwsj#yTkdB1`fRql<7fTnK;w6xmNgDxFbum1a0 z1PT9Z6K~NzP3SkUo z+F2xy%D(im+&3_C?959>WWFm4D(gYwK}2R&V=1n!W{R=kRrLZ7ee!}?C*(N9>W~|2 zu^eorCxuj5YH1v?S9uta%7Fx8G%Q`@S{D%TQ^wU*6;jmH&E{IE3Yn-XmD5sHLp)|R z6RANdT{_IGbN*53IIVP&q6=u5Xc@I2s0om08_Y1{P9HPWH!Iu48_d%*k{aq`+^4q$ z9At5&E3f)|M4V(()%1N;O*JI6)l~hikWIQOjxs1|VO^#7RNHSIkV>fXl#}J-T8i3; zO+8Apq)iz{X%GqEw7Zv*x0%;whE13EwWMa|Rgc7m=fSy=Vv0iIQ42$`F* zNmnSDu~o6hO+7BRl1UoTK}Q>?q=rJ@wp>WD6m1AcC)z$-Ym_&x(yUDI5}~kKnAF%b zRRboXwbCn6LLH_nBWrMAxny$#3h^!9EA^K)0L>35;Bwq zpD#;H1x-1lSdiA!RMeeQW9ZttmJ|sdsda^2T1$J7`9|jTE^k%|WO&VtvD_?VD3T)Z zNu%VVRgJ|D6&ax;q5lB3ms7*c7VMV{g6aSzpbokMoqCvx#tW)|7rMGdbk?wQ4?|Im zrJk;yNUK^Zm@0J0s`*)>sh!pXNXqJzu*Tvy5MDBUQU2GFKueqUsHKt%h}jz8Mi3&L z$sBch=^%|jGbsyNp5+>KuTm}ZTgzn}_pzU;U_%uk85*Y=asq)xZ8#?@+o*Ji%id^A zRTU7&mVi@#3(8a?Mwl9iBe(GEh?iV?DiY8~E1%ia7Gl)QtfAeK@&M7aH>CuOzfUne z(KsY{Gls1dg%L^ZkBpk2V9B&?XTrOfEy{)P`hao~fL=l`0!df;k#@<*{`w%E54jX4kFP z@aq_;u4;UNKW?lZf}5t7l5l3ErGqjNmuisDocYrvgT(nBwea4L9a_&kUQu(RpG<+N zrjpEMs;Dw3A<{5>ZEIhfDsXZiV+{|6hmRKZ9)NtkdcNKIE{H}bNyb1t0P?4=L1$i8 z*3)(+6+I?WwuYX+Zf_h`LONKDM7gYGP7+CKur<+u!aP-EkjFHVvf48OwbzewwV~6o z@9nEgeK6o?KebF6dhqH_+1Ev$>NROEYC#@U)Tc@E$j9eTKDJZ-Pn6UW?B48(xsfU7 z$n5g!FRVA&noDk8}qR@{Cjh2 z(PVIaTef>cC)T?+bzrvNS#12ya=R^qz;5WNFzL9m)p@BPsi>`~o>_lt-ZzV+y|=X! z&jfO@k+f7Jks6Q~(KYE*2S_X^3CPAm^4{&w4QMXyq>f`Z!8GU#l#NPgjVh{R1QsJm z*6k~nVV4OQ-o2wq+8bwjQTDZWb7r@m7QM55y}0{d z9aoTtv3EA;sG&rtsYwMjDTnQ#r=^Y`0+sHQO7Pw*f!S{=g#+R2ZrX7K3RE2M7ywWg zI^Q<;EyndUvToB#4AM4}B|yNU0EiZ(tY{Tfvl?n=X8Do)oUD?kabQD)20U!nRr&(e zGI~Q^%%e{q(0dkg%8%XfHp8?1D^m{tv;cv{X$MLt~D8YPZsLNsTy9eYJ7d5${?e2-&xE{XW8`CYc zJ1=13d!IF(>`Yc4rMEVJWp12XU@=>=Y$UnLOrAZUQqL+=zjE48cLt4H|?I({S8dqr)1jH5r8h)}?D-%La$>aTUiz*ZG-sPT}jWv#_0S zvAa)YY)#40`%e+Qw!ZHJtDxE2b8BwB&qubgJDYIseTBAjos)&iQd6#RDSr04j=3ow zWT%v)EgqYhi;z{Eu%`_Mg*=4;Q&2e5BxkLO0Z%%N5he^c($?A}GDr#3OZL!av=kHtXbWYIeoA4tiQ$rI=XF&h0Yg_b zrFAbHntY8obaMXylh)1ZZoB?z{{Y_(rK0Y=^|NI7ecijOC7141>gac0S!FV7wz0WP z^$izSW@_+R>>hS1m&D^KafTd~6J(GW)+oH5(@izQY`f_(;Sohus>MsGD??109Y=ux zk1`9!7?$qQQbNegDX3|o;44B#ID`3gpXwdOlHA`HHpgw`dJi8<(HqMp@;`AV-QKZc zbG>QuP72-Kk=Z@7zxMRqi&IIydiQhZu(>!eRp)ACX>x1!D%3=nVbWN$-dWtm1=i$W z#Yl9*Kvs!LgaLH%Qp#A9#-O?QX!Nncb0ptPgy=8gKM>8Sn^33}#Q+D-g>p?r?ca}S zu)a_2KB39=q7`(dFo9<`oJm-$Z|E z8fbJl_8@7*ekhfxp$$y|%8f>XhXe|qCpgbVr&ns829(bql}GIRdb6LDT?^GU{{S3z z{{YFY*Vf~pyNeaGs%kq2sVFDgIUb|lyEA3hLAJWaE|$l`jK}6=%vNHulr`B&DyniB z3Q6FWlCg@UG9_N}izKxVA*OOF=7WYps)JGXob}|6x{4Fw3gh@duf%DRPYQW(80jhe zyEiV@?CB}?@5m2|9ZR_SSGMKe+e5GWs*h^Tp03z^x3Ts;Rc=46d#Y+$+PW&fpWoCE zPeWZ<{3KW6a#d8-R5dZwA!xMovd1h!=984x1_3o8XbBn3ML3i4>p^2OM9&>m5I*0X z1v5{Wr=4rj4cU4B0FeDp@;_r@ak>4&fbJiT`}b{bzM$Ip^oKbYSyT1Zek(P!_O*R9 za?{oC%3X@s3Vk^Ii`G)qM@J}`ThB7Hh1D5d*>xrfYEv}z#XUjwr&lG=GNB<2MKh3V z$J7vb@$;_^uUC0@KVWCR9Bm(v^!q;>9!{=@<|b>tdU}d&(LqJB`(vxS^A$UoOw{ZUe9e3V8xM?yoY+AVSGi|!6aZ7{yx>?zl<(yl^dmNE8Mj#XB%H|`i05hlx zQiS>rtgTXYr53y^!D&zcH8cPmlTnJAbi4jt+xxS29bFGm_D=Em%UehC*W?`d4$Rru ze2)3sKPG-2e5Bo7M)Y4EJ5PG`mg>oE82d-#5*evB&hp#tm6SVPu2-6ZrkfxZT#I3& zm-Hi@48X{1KtXC%iqnmBfl>HYl^tDTon#F?yNKwu%^6S{fNC&EsQ`+SLuWl#kAHlO zn|f}|jmg-wyGvp9uFTpSqLZs=emcOItUVWc;`<7MTs~fdw)S^oO)hq~ z0bPo(hc&j$Sm@@gsaKvjk_iLP1QZ?=h+WyMT_^iAPz@D^3;7(35mvjBsKiW5MA}qP zX9Vgdqk{|@8u?IgwGF@WBBKZVxN)85xw>y=Y)!+{r!&`WuzG7}&9ge&CH{-IP711A zoS4~r138t>?q1`g?7TKpa8^|2CCxrv^0kbD86djbsiu%cbx`GnX+flEtV*f}!m7hn z2`5Q8&KZRxMVCmR&VLat+{D+80RzZjd38{IA@T>lH(vSMemF6o}*T+Rh zrdkSX{sF?c!u0S8Tqm z$@f-2eD}UPdiETheOtUUJC_00eSg+{IfdTMRovaXmZuan+1!@jqphk;a#Z9LX~i`( zY6y=-%%y@lAXU<}cXBJFFOr`!Xa{o>PQ4_PpAHstB9m4O#30Z|a}i1&Gy|NkDb~~dxf{MN+?Al)1s;1i?b+P^-Z@=%h(y87xJCoza zYdw~#*cr&yiz7t^M6~p^v{cf|6MiBjOB>vwjOo-Jmr;*e_>HG0LJc~N4w6@hpy@N2!`eB_^?vHBz-2R?%eX4?xlP@^ za}AjLN3JqUL?KzK7MhME0VCDaA}dRWjZvENw`HEOtBk1AQq`- zX>@{D;Rc6Dr;!6EJu_}-md<4r`n76P;82H&{8b6m9m@nqFdbMn((Bkd-?pGGGYklhdwjjXMBw#{}w?&&4+#PxX@>g1McxND<~ z2$GqimN?R$O%qe9kU`a`CTQeRRjE@-3i11TQLQ9aBMc5rIDMXA!@C9OO zPp<&9896ne0IgULd-e>427hhMHco1YiR?UMMzT6nO^mDS)X12ErQ~{Ot0XTLu`#A{ zRTwLk_SBE96coV+>=b1m;6LH%$kK~3BY{fe`bYfTeENUkV6`PaP<#!wHhT@=E4K*{Z4K*`IiV{Z*Q74V0a9M_siLIm$y>7=MkU{21_@>Aog!vJ} z72;1zCj@L;XeOiUuKxhzmY!a|r-}36I;214)zUv4`^RhiqsDxk`FXZ}AZ$Da2dXP@ zn}a{L>UTYE{@#@vpF1ueZenO+j%ZRGZ6yswOeS`_UEj(6f~Riw7Tx}Pn`5yz z_7;6$m~SGALYB4@ zmlAf05n7Q!@O)V$l2j6S@jW~ASEs@-)(ZyLiP=ij)epZCLo7n3}n*5GX*Txp;eWxRg(TAP-C8iA+CY0WQ|l`*f#mY-EZ=%4IfhAajk2BeQGmbvbjAG?)Gxq zn+RFfg3>nPr%xS2j&r~a(=?zx8xQ4u4niO1H}Sr+8j97iZp!+cd@hCQny#O0X5@}K zifCRMiQzyCI;4@EDo8w7lfq?0xiOj%3)k!dzwuoL?>t1j<#LPqpS+PC#wATx7?i-obLX}J4;rYKg9vkhI@-Dyz}ILlnZ|*hd7C29r%nG=L}! zTBlVMC`0fHUpEQy~$=>|}W2P!cGEF=l-TvPn~<&sBfR-{uXC72XKwA$Mfj-l2WUkhGPhXaGui@vaZ^>fMn*C-o@OMz8fh(^dZfJbM@C zsW<#RV_hV3s=#_0_f{c@0>| z8FaE3n^Kdf)qQBf!N>H!`+hz9%Drxs$6x=`+z}C(h1Tu;qBsC8lr_IResAqIC_Oq` zii(R@zVckib}rTl#%H*Iin_E+6IVM6E!tUp`OxQ(4#Z->%zEk~%Oc z0Ni@FmPqN;58}q-f-meL8&>ms9+xBjt*=RWr0GqEww1MS`nuWbq3|j{*>1s-Y_ZgK zbbzq>N-H7p#TZ-ZYkGk{QhmeQ;c@Og*r$2=D*c`r>JGgX=Pl3xPi3$DTk`0kWhA?l zR0N}G)%hWjZjJaS^KtG(w@?5&xcPc?BZ?tYL&v0+Sm{tevV!8@>RQ$y{{TQQ$FqA- zYAf+jXXVkAuuxOG&!p-WIUG^|*A@8k0OZ_NLu(8AkN9)!-pYbN-lwBWLcyAtV#9~2 zBdfgJ9YKWceze-TT%|14`Ah~sXi#9z8zl7G`fR3hj=M+qLWvS;n#x*AOhk{Ckg3Pg zQs{cUF_6O-EGOm_<}P7vgsZ#Uzl#&ml0??SQ>#!Ahl2tgNg8r#*U^VJLG2B%v)p3m1!QM8vCi^WGl)`w`m78(j!TCBBIB=h;0Ix1w3 zB%RmyQ$@S&t7~$S&?=os!hyV0Ii{^t(^6D}Q<` z_2JLz(l2Bzc_e*(_>3qc9eSN)VPXCRi>V|AJPUm|{{US3@uwQ+{aNdNwCe$73IQ5` zxV6gtKdJZPMxcE9*IcQpJQGJKikg2DU%^=smYz|hjT1&1GVzdj0hEJd??Cy3j=k3% zS0o#Newx03kH9~WKA!jXb-MNCKd4w8RK@>)7j09)U>_gR$LFQ5Uc;E%zvvbD$rSbMM_1A*6w zuUNHQ`gIO2*CZR>!_&owy$aKZ%dOLguUP>kTxu*>azRxCn~VPdTmJyOd(|mV@b$e} zuTNB1TDr_;S1}fWMTV0d4O^Ka59i9wG*ocI31Kxvk_vek_|<|c652(H-2l^^^{yoK z1}BqGj_skO4W*Bx(hZ0l*xdbn+!}&B{{YR_iSzR5%8IUP8i^!}O1nWlGu%fqv^5c! zrcfnG5EhNNU;{7JNId)7>e2!8>tdC!mt8VOXP>~*Pfr*OCumwG5ZwWmXn~QV0ovbE zKim88H3Xgjb*cbxamT3;Bzj^h?(#dz8ZQ|LpfK?|$O-ZnTk0BAt-m+-Mkb=XI=b+! zdVQcuSt^j!$Y4mRC7KrdR;XDj5x-#C4@~aK7X(=8(Sd*$n8yCj?dQ6Q@j-cY#KN!k}8;(@RGwD@)y}&>NRcmeZ)~s zKWF)RQ3L3fGePP5an|+S2aA_2^M~SoNYsT*zuGBRBu=EYLCH~PXk$+&r@+dpU!6ir zX}2Kz0_-5I)JohWW4Nz>9ms4t7mE`Of-WGL6dM3{suhA37R<-hF*I`xhh0 z>>sgfrI4>E?AQfpz*$317zq4y{6KM`=$uw>-nr||_t3kedi2Kf?d_jKvU{To+W0&V zc1zF`SMI!q;-4een~!OBr4}D0{n4-6n@8-+QB)dZm93#=Nyxks%RbWX+^=J`O$F32 ze)|sQMVe0tTt>wBZjuTS;MGBoh$C4H4Mqoj{JA6Do@3@+pK#lxyqnupf+e>4OE$hX z7lJewDS2&22kZX;P(gAK(FcNsWY0>j>g+s6Z0|WHuV5P=jrIvi%448~&S2Y$h9ZkA(xQfiZJvu>E6UqtqV|1|HcbO!# znJ2qjT{jacC1jU~?qX`lv`1r-z_S)CPgBR-N0Yhdl6|1sHr{aC=i7GKH_2w&cKMZJ zlFMw6s92^QPQYyp+-E^cX8lf5mn4QTO)n zo0)d>0pPV`ZcJvO^yr65xnZo+fz_N5K~vDZ-4F^cvfWh87m^B3xLPXc;exGbsV+I&xt%(9i2aLF2;g7v7z15F6a>RBvg4@A; z#y6Ic)>QGJ(oT|O8b~UhH5rzsI;MIS`}Qn0>#kC^yXDzpmL$3CuwQ2>fiJ|`hD3vJStEQ!>sEA9KD!;<=l@U5Y=w=TsJv$9Zf-2TigO{5vknrV>4a4{UL4>&qLgxBHKWxczC<5w>Yo zL=h@RW0_x4%4BIP;l-gM8lF<@R5bxhjf$otTTwL~MiN+Z@-2Nh#)CY}Q8AMw0Kh~> zJIAP(d$JIQ!GA6%*2{ZwG(I2^X=gP62A~j%4mAK%&b0uqUbTiRBH&LW#%+qoOpD-> zSkplZ+1gYPNi5YWKr{>fp@u45Mxw54wA9fpH7iq2Mp3oIRqNzsP@t4q z6?B3RvDYX#j(f?)uY+oqE)KWSt68nrQ;LmMIG`LzAPQHhAKPeF*LNFxS%yY|HJxk} zXc~^XkWYw67{Fk(6g_uT-(rtX9*WxRV?9LG5F^1=kBMrkJasl^o|IQ0K0xr4SuNz! z2y`JnZjmkbIrjT_%Zp%+#Z;t<)x*?PbpzfsQ&8>zFlFjRboyZNtsd?ZQpzY)RM3%? zFPhbK)|H?jf*x*msc7Yrbv_BCy)GH*8q?VhL|VF(~T+fHCm3UU+1I8S=Mxw zHBiviR$}tcOt4iL<#++5G?f@hqGnktU?r3(kC>5FX4eme)@1Q?@djcU$tBTYC zPSSWC6r%Znbg3(*f!nzY+7T{hM+>T=s0S7GBg_$%00UL0TKR8C(JCsc5fY}A9LFSc z2S{;~JR?=()}CczbzJjs3v*y{Q)FgkiZ=u`JiiukUrv*5xMre`YT9kNL0wjpRmzCw7!lzotWrsT5Dvq%7K94FqK`Ad zMOf3N9J>-+a|E`nD2?W8c!RL2sd*SHH}pXxQ6_*?k|sim!zwapqG>DQ+~$;s612be2iXn{kd>PxR(jOmGq^M&wX1X752I_lDvIa(BYmh~W7QL_R$CiN`WvM(&G5-L^2SVOePY-EM zHK(7Y1v)QUZ*qS>@4wdeBJv#y4MGpgtk4tc{F|Sz09&3t_<=#yWy%Bd>Ha-m z-JHo#3jNMFN&2q0bEN+OsU@3_@b<$~$G0AR-{9$}jU-z9`aAty{*Ph!ZMLd=Dtwhb zDSl9PVZc=5MoU~d==z7N{D~;WEkw+XO(HNY2~}XWVhn&j-WuG*TQZw-OmG^=Blgt( z-%gBIS%H)_BMuMeL;g;eJsH~lG0^*>e%k5%$JkU`{{RDk>`lFtsKM?T@G}jIzxF3?q0v_O`W%UhLZ!ddZvIV>_X0401< zHRuMRYI8s-T#$O&Mx-=sD;u)vT+y`DjakiVYeEePp&UhQcUQ?S%kM0|T-Ek0+h$4n z$E-1ZO@pi3yK@n?>hilg8M}9W_@t9`{{RMx8d}Vpd2Q=g1SuSJ^t4#|dP-<1;)00QW+c<+pD!;U1ppph6}+}eY?X4$ERQrX z0<_T?WN4|9Ng0a3g|x;$;GhFx?tybv^QC&zaR#^_>OE{h{{RX90NwRFE4033cBUR& ziR`YV_&?Yc{XHf#B%j7{o6|42u!aikE)Jz$EY3om@zAm~tSPAgFEC_cJ*M6on zcgf+UX}~tBx5|Uh?8xa=iB`X}S%0$D39f1s6HNIY6yj?^(emrQ^R4-H@wed(X3pu} zt?Qn-_+{2RldC$<6}&1kTk|{F8`moa3;iwct;Mx4aBXh2+PEnDCX%+V1B#@Ewze3; zwM|okB18tu!QAHEC!bvMMH)r`BScY_3RtykAwAVVh`1UHRm!ia@h#1yP&xx6yOP5! z-byG)Kq`k@Ga3_7S_J1+^wgUJ=Z{l--;8mhCQvH!O}x7 zVZl|o>(}k`TZUYm=~;)!MOc8*x(Hh8qqoDnP{m}B5mVe3v?%QbaZ34$lV2{A$c-aL zuiF}d@bThJJu-Owy$*U*{Ke~y)AKTY!1!U-eN}c2W`;)h~&AJ5u9 zl^xfxHm`d1h@jsQ<+{tSdlqf4y7Kd9Hk9~E4AyTezBb}g)k6kKxoT=r-|i~X5Qr?r z*K#P9%I*l93x-+(!m6gCgwxWQ>A3?*AeE|-ob&s6RG+1>qFzPo$n?^*W#@a_$Vx$#@eXzs46qsTVd!(jTCKe=+7 zw>OU5dxIy`8-;4KO@NY~N=&6q9zHgyhe2edii(T3%Q(Z|RYOiKnT7nLiWnn=?>$`mhPxM6QCk#3F;_KA{xN4q^y;q# z$%G)7+nD1S91?=8L8VOwe5gP;0?ZmomLh&P)bBt5sjtGIV0i@x?DHen$}Nl9vGiYS z{8so6KW$(-zqj&x?|=3NJ2y+$I2vyG?e5dd?aX%bi+FDy!pX~%>)x^2T{*KTHvZn* zxOwq##>mwbm31;sM0K?#?Cm3(G(wcBhHW6%Q!)M~BrZUv0HsSYq=3L=Q6YCERO#~4 z6a~O#9~PobTD&_}hEJfn zd3-i2wf8>N$ZqY6HY2k3ED*yi)D^;NeDQ*+vW=pqk~tf?UlVuP?jeERD3QdZGAwGW zlBmHY*~6HefTaos?ovq)TPB-J=^fQslm!_q&8ba6r2q;W%y$qoT6J3+tK$>)56wS_ z`}evwhjQ$Gilp5boKIwS?#kMmt9W8MM{o7^@H^vdQS3dLfu_voYG}6IMENXzdQjt~ z$KN2i1xc!l#!W3+Cb=FYfT)Zd5vkiFg=z!Q6pYbpO!S`QNd2g~U5x=h3fCYO!1W~5 z0CXvTFB7$G*MIc4p|w$qgCX zGcNiW7M~$a4Lo)K0Ok0KS>9Hnq*alr?P5x5CJ!Hnb#39acJW@qs%u)YNl63ckwILO z>rf1&iHccGtUU6EB7;c41LOvpfLjC89bMnapO77AEWN$A>o)}Sz3IKW&H8JjJ~C|j zYOVX;QqXp8I}N?lwf;kG{fQ3XkK?WjF^Z0#CxuPlJ`S2pRRp@)T#SqDV_Qt#B25)8 z{7@Z6d?Z;iWIPpuw~9tIiYP5YdTC5?_%bAcY``Q)aI!f<0D(_*i&ZhzLl#4i68v_U8Nf6WEy^wd)LRPU*-{M}()`*jYE+)Z1fjPoJn0 z7$vBtjK>(P3j)$B#);;ZvJ<9^7XqjD0qC@+9vvt}T1!&Q6KM|mZvYyBU@1w~vjM3g=o#jKK{^6Uo! zx==2VNDRh+liE!U4Svk-ZLv`v-lX0&n4P8@7*m$Uzx_@aQOwz zWR{O5l*Z#{`+6$Z5>~R43zlV%+bGey5Ufj(N{%PAS3fc;Xgq~_^pVdPS9r>$b6-ve zhoSSw+0eHx@y4u17kZjXs_LlmanWStix;A#Q%Y)Jnn`L6K#C6sk6Mq~auu|wpD+XH{j<8Iw&{%a0Oq<@4)>F7}OTaTF~Cki(Rz$k5Ux)$j=xOgz%k*L}(b zdWweo$X+%DG^;84+uP;}Yd#>-1%6cY{{SyZd|*iIsXyxcy$4Aw%#^#cbnOV;){>ID zb?#bHkripRPuH~cE%tBYkqorXOsw_@4wWF2?#%-a440rfxO~cxe=2`7)r9nlK|)B= z$K=N!W`CDoJCFESG`qT&=WoW1rMa;9${cpk_^@eq#$JY?R8P6+D?2ZBNmZ7qRGH2` zBUc$zq?Hz;o>4F_JWT}h7g(VE>%Pim48TB|Km$k!TPB$#xoVPV2wn<0FuZj;F3S=| zN9x==G5k#a2p|t2p%hol)Z>R**>!y_EZrmCjO|L*?Yequ3U~t4)@5d*IbFu}=9?2q z6tYi209ARWx9zr-2JAha=yGk=G-hp2fC>Bz;}zD$c|X-!sQPUcclOJqW!g zjsE(4gy}2}ODB%l_zC+bW{1!2-MLk_wx-*~;pc+2Gg+LB_{wNuhbJWik36z?#I7Df z6fqvKf_RuSB$WiUO-%`@Bjrv5(!FXzj1(fKyb1~mpI=JXudhyjuEy-IsjH4EwtAdz zSIK|?4?yt0$P-KUWwASF6;D>Ra>^LgOtMrUPq&jxJeLgQY4&9u$d2M*6a*I!tMfGe zR5h;}bslpL$af2$5#&BEgBr)el?92_T$+*q3PmeZT2rkCf16Izhi`v8f1MbRZ!RG^ zKXpMf(nTn$eaZ3jtFkf39W;olURs$H$U?TXBE%3#HswpM@pC7}ZWz+MHBo^5gc^AR z(0iLU(_uc^4Lm;uRclV-fUSSkn)En-DJqA^e=`q?f_oU>u`Aj`IcUS^+542LuwDa) z)1)6sUg4YnkbS6L5dhbJFGGy6Sy2RSXga&uF+_qDwN&zZ>moqZFwrZSHUx9KsM z%9X5wm+rLA&a7pcda3GU^13hT^2|Xty}z%s-L5#I+w9|os}Mnv{P_Iq`Sp;tQN<0c zQ9}BoP(VMKC;5}r0{;Lvcp=VzFhAtOfa_efB?rjLZvO1O!;t<1w%;+iaQ^@u=r&~? zM`Y%=HsYYAlDlqo+}WB6N;RghXee_Pa=DLO)J&?dybbj*OhJS~%)sOTMHf&NrlJT3 z%&syp8utUnPFILSaFJcje+ogUsCRW>&*18#GexR5l*d*`$S+9P)a2}31}%PY!JnX` zrAZ*A>}+|SnnP6-F;wkLWRVDJ;&BUzOl3llbop3uZUX$cnp*785LQ4);r*)r0GJP- zOzbg0Zz7f`)ku~>gIaca{$KH3Sr{6Eu9gd{Pz8ncTTSouvHJTGbUN#kT@_dGu1Fq| zL2sc4>0xd?`nmb_zb}_uSY35LEbK{f{k8n7kH`o8kH2;AFP~X;fS{oPgA0$;1b?M$ zf3LrNy>H5(@azB7+!b6|TpNu#P0pWL;Mkr;!L`1Z_L%@`62_#)MuTH- z&=B6n;^j!>d(i-Zdi8T!b(>ZEA$&Xt8D)sZ?{{V$DJZ~Gjamuy zHIy?c{{U5QulNsgHIQ(gt(t#6gtozpF!QMY053@#vAk?`1L|v&bE}Il)9Og)k7o9V zPJn#ZqZ?}enw&RDg=QIyIUJFY#+!dqD&e{M*nhTz@{U zihK_1s>u9z-@9sKG<{=TjNG|w9F#O!l*>S=kE)_S-OR0CKOebh>1!wy)#BxzHLie^ zv!6-F9#7`ovz2+Dn?~oU7Vc+MlrFyvtG#s&Ay_sD_*hrx*L(i(p2l;(y`IJUB)o&* zTyDEHj8jWvEZzszEcSNjdR>3^7D6?N2vQgW(I)<2otIs@>@1xgBOAYaN}IF0PjmKCu44(e<&z7t_7=s-W~!*Rw%>%w{3eQNlsd;Ga6vqB zhVi!VvF?# zf7PraWSRUKot85zMp;%x5fxxqy>LJZ3tbk_R)gd3P5q>GXz+YZ>Nk#AkkV8#U4LmIjz2Hw)~}nC z591SnQJtWoKeUBai&Ms0>2@mI@(0lS7!0r#^Zx)ZL9FBK={i(`LamMYKhoU)0I;|F z?tQ7wGuDq-mE)0!5~Pj^W>t|{$iFuMi(lTULPc|4z5WiIVvVF$5$U)W1Ja}meFm;c zAbZ^jQ%*g5kJ;BHjY4T4*thP#j^;HVRzPf7lKg@1bgn6mz5X7!x-fedRv(5p0EPN; zFJjgle_wjhLrUYVdGPCqb(I(f1f!L81C(L)jF4_PV>#=p@f_T&Fx}Q+Bfc-~Tzi|60*ShB%Y)kU0Q4E)6PzYb_uCx1& z!1`2uefvIsU3-rXrNvP+5g36{9M2rm!oW0gn66?k8){NhQMVTapL-|Fj=TrYJ$CXi zb+Y)wD#(UEK+@oVN~>F&*#7{w_wF5R@%eQwgo9A7!jZ%%^(HFWOc2#9BU4hN4^gO? zaEL6-euR72;s>8z2ZvoGx}|OgmO7P9h(pN=4+N?MZ*EbjJo?b3cw?_S-SsNlP$9=Q zxg3=MivWI~f$w6brk;IzpcSW6seuS2Tag+I*y$RZ`Y^cq{XehM-5e5HhpnwCPM&Bo z6|v0}OFM;vGf@OqLmYBRBKgQd7-^U&*1x5|u^jto{6C#K-wIcwz5KYm*&m!89R!ex z;(h-Bj;^Suh{XZZM^P0_ZA=d<6(r#w#~BO}c;FvpTeFz9``52`hH`jThd=7`>G%{p z@CM)*9=FfNfI|> z8DPg;fTB>0DIL|RDxjXR@9#JFx4ZTicD3bRPut;>n~1k-neJnrOL$|s3Sf<6fTWYj zDzGKQfgn&z26`_^e#YCmJ)e=S#7&)}-V~Wmy4l^AviH6}4PUn@H;%#V%qB}CwQ}{l zVCDAT!TgtT|frSzFvZn|$`>SXsiXnonyi zff;aX}kr`@OC6-BGQUjVaLSiP5|Qd8 zSR8+Ny?CUKYd76rpqMD$3 znP0}dy^aO)gq63N&ek`U&6GN+8jNk+2(Olq4Nvf|mU`zkYkPs=zN&>UT`1J0Sk{#5T$^z>@2%!bTmJwB z1*Bp^(D<>`n}D&%YBbe}(L>zCc`54N{$2k78^!OAz0T9-;;*8I0hWp^J5o_JxEh8y zN*Hk2i81dq8L4r!khY4c^oC~%2oVi_(f#NA7UugK8Fw)&PA;56bn1mxbyY@@Gbe|p zt0bhzRj7etr%QhD6JFSFoTs|lUM!KVoQfkTpP*?9EOKZ%Wo1xlBZV9mF`#Pb2}-J` zm{mZOlp>amUKpjOTAI4~YAJ*PSP)XPDj1XF;zFOa+yN=XXSRXvO}Yssl38fgBVd%Ih>q9B`yTloiz@vj8YYbx1Qo#4l;>qx8MT$&;$-oMufZnk;4`u=B}X zo01GNrYAE#I*v(kIKd;sxqpIJ;pB=(r6@7YkX8#Po;@DqOREjpeZRfDhT7EZf4tHr zeOBL8mjd4fmcLkHmO3P7{l?UeRCubyp6zdYd+pVh=9VN_+HbdBEz<}2ErTI>1(o<-ZQ_q*TRJ8C;_w>lO$;~JUdp(D1SG@4YkFm#IG4v^Yyce{#+ zw(BV!E-M^RD(Y#Rv2Ah0y~c*4B7_Qx9CWejflT}IFT0Y9BRec{tyHTeNd7EDZ{wv$ zXxZZsEQBz!D!E_4_9Er)qmJ8hn&ROnLuBP-Ah#KyVnMGQ5Il&e^yq!Qldo%Oc)wQd^aohdRm#}uG|!ayh*DQXNPcLqn-qEu4D`&AQ3x6f@N zj}Z+JABmNkreH8*Y6BjsGd~a+a*W)cXHSKiwzSPzkD8$(%N-M~ZqUpEUYtNem?5B< z9i^w5JyA*PXu*(82ei9F#`d!+qpfue3mm>qb*dORPNNBRCmw1FSgqeNs+37s$RJk8i-VQa@c33mZFxb zjvyY1Wr*mLUa>53NLdW(ParJQ)B7oAH;i&N&f&K`#M#(Aiy=%jQ;?T50^n+$t?$GU?zoRsE(r_yQ%6l>p@198*;H4 zRJ2mvBDgj>0lkX@^^~mKor`}$0Hv~iW5th;Qa;q@=yx@0V%$*r{-WpY>t$c$`H!Kg z*!}ATZ9H>PRpoZQ9aJ?)l@L_JQI5+-VR#bp7#w=L#55E%Rz_|Vr;d=J^5PtU83-QUdDXLQEio8zAB`ES=74>7ko=O>!T zPeIe$*W^!V^>j<|d-0Ka2vuWmrnCJJNK8k{o9SvlYF%D*3pLOOK zkjHNv(nA935(v($Qi>#Q$EKwnsPB&ATBodn<;~ll<=Wtm*2W1fRvj_TG(@=qp<79o zG?z+&l80J~xppk)7f1A;Npvqoof*Tv@g)3I^Ancot2rWbf(I}W$Lw{K@{ysl?C z-PwN3!fL^9{GRC$qEl4T6`-f3rjC}HD3&6mpLv?<;v4py{-Cs-Mks0FxL|9YSfM91 z6u##{-X4uCbut^z|I0`?-}ttJPJHu>^(ml1i}P z6ZseR(I2k?`8Q3*tR)p5N276o!sK@k!o87<+qkTr=gQLjtn5s_PaTM+6)l9szf$$Z z3eS>>9L|fFmMc=!IF1P3nnVol`d0GAB$rT?82WYM{R_m|kJm>s#)o#9(WL)jY}55IcHJh@(`-uMir+uqxEc2Lyp zt=|O(6EikWYFfnbLi91zIf%y-`+1f~Y_ApNqnH>HriO=&Gv~woL>A=lb}bQ6Q@7Oy>v>rl+fSS?$<_lmQSVu?ohZ3aTI^cRLWQ z>~x9~R9baKNma>4B}m0tO$n$c08vy>g`s2pCdXBW@`i(Oi>Ih|jV|rUF7w>m z=BHxs{q4W;a%`>AHm+x`c@%6{Xl;ybPEvz$($c{~vDQMON=R(2BSh9XK?7ca zs+FdoO=(=xl>Y!HSEiO~HBz+(zFu57eVl!IC^4WuGja(aF$Tbk{{WBD-uw+4NXB}o z285I5df2D=C1q>&e@FiSHErWZim9uCel+d9p!qBfEcM&t?(>u#jax;u_PC~q)KSN~ z>TydQT=6)VEC>-;-pO}}o%VJJx|yy}P#OjyTLgKi)lxWl`3{!tqzmX-$O}Sqz*3*E z(xiVrk0-$Gv5MMX4Z0?ZphaC#S%=N;e2p=ZMKu2a$2UG=vX38AM35`d)WbqzGb8F? z!%-&o8orP`$=G!&DE!ZH{gwT->vo{3u~SvoO8Sl;;U0PO=+{zYG3I3-!YNWSHl!5{ zv&Exbo538BqQXG}--~j7w)T(`GfG#dY8k}|3t#YY>Dp*9(o|H(4mPP^oUmu6sAy^< zDhRr`K&=m`fTMwOLHBB85t{W<;Jf6A1W~N?kwH|*7N$6el36DT zUsH~FnT@paSXHzXM8Xs}q? zs54oUStKPqSZ#IDlFKx>99ShW;s3Otkm zat28!jXZFLdqbdpK;!zibk`l{*9UQJt*^MY{!?#HSGu-M9(yB>#~N&ZWhFH% z`KYK;tX1o)hNW1OPpoJS?SW>JzLzW+n@A&oCx$W#{gm~`N+X@plx&>mjcLcvkEfSc zgI(5mpSY;RoRl-o21HX+fsLv~Yf5!gGD^N;?5Y)`8W%^`*+!;Pr%B_Uj4_g=QkDC9 z5OMtvo}RLfrx{g^MW=_!D?TUDIffYtK@9Rgo(W?I@FHbVpLsuOPkW^u*QTU(T_npv|owD45b%+ur26F|~SNfdO_ zM;tMmDy)o-#EwbT!Vs(b$|cZ0v19YW1N~mTEKF^eBAF5|?KPpVm#%u#N_y5AOpK^> z32SQQK0iv6B+lnbi&;6~abfI66!>aD;5s8bPJH^@cm5KGNRn+Y=69K@#J*)Jy5p+0 z{L$5JWyI0dKyh84U;I7ehL)=NHI1S@Ev3Gs8q&0)HfiU^ zwDbMFKW9UC7P^$qKGK=br=35^(of?50C4>A#{7}~Xg#^{{))G=yE}LGj@Ik0#@pM+ zJ&DEjYf$0#S9Y38Ov1E`C#<$kuA3gkA!su3q={ypklm06cqF0>(!@s_QT9$f0kZ1EApSMHn!6F z9aX&de%jr?5%*r(&hLexq>p9q+<#H;JjL-D`Li9JQ<=(Rb6BZx(pBMNtjN+(QLI@S z8D~Zu&mGmg5iw~9KLDstAaw&qB=+gU5X|GX4Q&d=KaX`Qkpk%W+y-V0rN(GPdV8uy zmD57SnMYW9LwElGGR)t~j+oeAEVj4C3~$3KDvJHDy!&&dcHS2`-}@5@vikAHDtFse z`?DpwDL(6cM?pZ@sqlHI&aZQI^?ZnDW$S3;Re$ul&&ekus%ikg;HfFOY{nj~w~SWzN| zl;C8fhER!C0EN-w5YB&{!3cL|as_CrNzleHL?mb(V2xwaXEHf`bd7t!Ds+U_jw1mB zR=V7P3fXVQJOmj1pSW>v66GqkuV(LUwO^U7rb+5*vbYR{IINq~9C{d z?ikZh(f zB54*xg+oPfk|2UzW+>5Sc*&Bcl+J}FnFsideqV1ykr>t8o&}JUAZjE5T2%Iscvs8} z)bQ%d@t^RcPv#%oHFz$S-k1-DQtZw8_>QIAHM@V~x>sj#`x|i>w&i9oZO4}087vHS zIQ&*dVM830lSK_feu4mBY{dgy$cS$z((($>ASbvQd^ODguNrVQ>B9E#4&A!kl>mZT zV?r~lGLcc~@Yl<)rB>kIy>-ytZH21MR^zF%IT{U_w($7e^wjwJjFx8`w(-&7u~iVv z^z<0YxajB_VH+4CQjEow6`fSyO+2@A+S(wJ@t#*zB#MP#U5fxnQBXAyMOi=uuml6l zd(1mUoWpOD(oSHOH1MLHWr=WTton^rS1mzCax|`cht8k*i{!Un>HcsZIk(PwyRE;A zZ(J8qW$USScV}a_UNawuhp9UE5x2J3$kfA2QJ3DBY+f2Dvbd;Wji_ov2(L~fX9*h# zEG>6iGkj%|JK0^08!a=mr4TVJBaApjV@xO-P@M`6=16a6hi8)N<~Ni?)3qcInH|oG z&|xYPHU9v8s?wu97!Tzk15^J1Ge3%rI~Rgp!mNrm8eBAoYHkT4Ixlr8Duunc{{VR& z+QD0e3{IU7L+g)EpFxMO?_N-exDD3chx0r?ZhGG@yE_PVX3!E+;QQYh*+v5K@t2|L9&t!7jN?xhOSHn=07)_w`csN=aj8xjh&+W%; z#U5pr-Qj?-sU#g_00S2v9YzO`0H75FbQRq!F57#zzP`G+xhoSx3r(i6DXg+b5~3tA zhAzbDP|}PReKZCqV&k73^5zI}P@>QSzN5*2JRxbP+Eg_N-T*+7RINyrh~$?i@qcb? zEOp&*&^$r*ey5lExO8>P$ca26KZC_{{{R_3<>>sCI<5}{hPU=~us=_wfd2q*>_yPu z=hsD*Rg`*x(_o+gq#vg|jz6y+{nx)fxhV{7rF4OFeoel-HSK@!_wKAI!kFtSA5l{Y zXK`R`d181BoN78v@9#(L>sb7cU;owH{C>L?H`8q_EN;KqKh*w3{{SA-{{V-jgCq{5 z4I0bnC_;;^@ATn<{YyCq^Yk9-;M1>H%g?OQh?$})4YV*}^ct^aKhWORB#(L^l`GbX zr%X{5>Yt;tj62{%LVsBPpBY&s=ZS=AJ4CzxBMxC{@w+%P_^0~i=d31L+Uq% zYw`Fxc>e$s&-%e7KjS;V^A{iWjVaP@Xzhz(AM)tf{{WlKPO3W;@_(}FfK5x|MeH|N z%K}@^mMX?U^;D2X0RI3He{kmREAAc9(Z%g^{+2KDSNZh_-RGP4Rtu7CzhHrX&Uz?$ zV9fSq2vo6P!p!MqweQ1=ev|bAx;6L$M*jd3 zKAaDr)Bd-!i&Ywwk3pV{;rt%8=_<@dR}ggsBOyR_a8w1Vgx!ba59#dY%9_cipGLOy z0kcYxpCO(-UXIw`I}Zc7{yS{m&&uYuuEgxDmLG3!&Hn&{qs!I7*V}(yGLt2|w**^q zp09K^*4q$dO?FW+2r|;qQ?k-Y9HckAb>zNO*}0dQ`Ksf3?yVFUgmBSd- zS&>PvM8o-_b>7e0+tZ~x6Jl=zxOUHL^+w>IAB?HbZan`0*hAO-i@Y{PHuBjS4fnRT zk7#8&N44m2u;#XvcIn4bXD5zYxF(NHG7~-WzS*_x@ZZ>Nb}`#Pw!;| z7#81&X=(a1uOX_2ffk?Qw^u_QJq1iT3Q4i+(s)TIS{k&euB51_sH0_R2C%CsC{YTO z3hoK|(!|w-nW+AiKWC?}9vw%~81&G52Uq2j{$3qx1G&tTW?oVfGHEf^2m){@p$Vu4 zWfFx0RgJY?-o_vuL>@Ii;pi<|1;$9>>DCM_AgIsasm2~n)U`Q$LO$80p0<{waxA$D zXyn^))X*bjY3lP@{?#4;We+GRcDKFWHj69C1=zPM6OkzjL{w6ILL0P%_^8-4&N^+0 z3fZPQvTnrB)^@hm?~RAHs5XX9F00s^yK>|{J@$`AVR~b?el1Y#9>~VxGWg!U>`kLh zPd547U1N`ij~$bTaMaRNWN{Ky#%Mn760t&C1+9+7y7G?UaU{ySh0JKTw%4z7Z@Ijd zZtEq?Qfu&%Q_A$!Pk*+ShKm*so@mMtiB_QFCuAI$dgsw3*{@!6TG2 zNIW9JWkh2poHBo~emQi$Q@FcRp?bS)cHYk1Jy+X%H*c=_tH?##nC;89dlPx>J&88o z%wpD$Xv4O1`+qH;j;C$3QaqWJ6%>`)WiZVGos*q8n$woH9%y3ew$rGZLxv2dkqDcEgBinE0J;ZGLcKdmAZzZ+Gysl$3je|uTlIla>sA-Ie ze}fDv0aJi{dFZ~u-#bHN?3{*EZRK&BhjZY!e%{;ri$B>lo11Iwy_385mPbF6+!>9b zfX4NoXOHeo^m!b7aaT|Ttre7%f;tIdt27+Z%^N=1f4FWfYjFgTMA1nnhX9Ic?jg4e z;iQgcwjMgk6Bb9TeiV`uD0q~%`MFx!&3h!U$!jI5JY|X@M|X__0IbGHNR&8YS5A#A zYb8-5k?RkSwe{)PSUO$9n%cWZV(*Rdzj}+Ta@(hT;Og6C)a-m_+=7$3Hx3tWdz+g?x}NSBV7s_zqi`l!-cj_imsXlF z0b5N@iEz>_f3SZQLvCB7EcUX^5P2nm5#%VcFN@-a)e;sJ{UhM&AV^x72z4R8Rm-;J z#C%e(+1OXW;PQVM@ij0|)tpUcOU&K5+4Qv$<#z@X5rvC%R#7}(Z5?$*I@Oq9jye5N zpJra)i^l%EL%3ZDu9ui61(dd$eJ!4yD(?Omr*TDMwIzi$bf=b*VSUWeTwHjP{d&}j zf!%Lza0@V8Qlhl2Tk#Rmm+tR`y>ZsPQP`XB3$?yT(d0Ik+s5Xx^_#=9{vcva*A@Q`{b6-*>&9!tU>GYe}SV;yW$U z7a?Pjm&1FAmNYt$RLi6ls2#;YLt(#eH#?2JtoIOjCPoI9w@6I`5Eb0$2Okq)(10pO zK{vyGyTeVM+5Lw#M^Nt#)tleh4!zqQU%xj7%${r(8cnZRF6iyN#?ahZSem}Rh6>Y3 zw5jBytyyx=&sfnf+0(Sgp5pFTX4i7td>zUSrrymiWVyCU2a7L^qANv}04lX#67NeP zF)~F`vdN`KGhN6n?`<9%l(Sn?D@z)jwy+W)!-YsDYJvJx0QVMBCsmKA#8y>et7M{< zuNhN44OH0No;x>>lA@MYiblugaP@WgoV^^3w~nTgdFkdt8aHGijHVb!1b{FMD?$p9 zQCc#v45WFh0Lp3z1XH14I)b)x2O5LwQR%(hCB*fE*F^4aL-3n|rXPb5HX1uChxhk~k2>PJ#qv@jkT>0$o!?Zs31QornVuBFElD=}p{!Bh0~ z>1E&*wXDbfDer8j2EAw;=hv*}no__X7?Mib#`pYxt^F_W#D(+pr(2=)>E50c3M15{ zu9aqErF~?QTGt1k&*R>h*N+PS056wYtub76K7kQy)G<_y#EQ~1Z6JY6w(Z>MCQ7CRHFZ zIR$_x**5k603_SrFVa8YH2mw*n`)bzapqhP+t&BL706GSKOEzc5?Q~}4Rn$Dn1zl} zvG=1$5fBuWg^h>y4<^>XuvWqT<_c6%GtuSx>bI#h0FU_a>Y;vVMW^ML%L~mL5%N2^ z)>z1R$aB~^_GMV-26sq})V~0calsz&yPi~kUb);3AHD9Y`N&V(LBhR#J$n}Ay@&QJ z=%W7sQ+A3{hlPwHwHT@6Pc9rsL?^Jivme@%?20Pdt<5%P0sZ2~Z2T71#b&o=Q#Fm; zQ^Ankm>PYPw&?3O7U0L%O8}awXq8M$B)&uAnn1^Vnamu~w!7_H1(CkBk+qw0tifFN z>r$k6W=iRCT{0R}6P}{~0K8|lp3C!%jgL3`r_Ljluk6?9;@!Tc3t-CBacwHx10BwS zf#IO>U^Qi6gsD;G^L0Ci7n9HBcUSkird_`V+ZmZ6pvKVRu)7l$`(p#LaJzR4M~=em zjkmC9X-x$-3YwakG0Y_rA*gws!@SYCZ(F7P^t;r49r7tp2SZ2U04f*5Y>I*nPsAuj zG>)X-W;q9ty|(2(TIK%$Y~)*xSb2ov@9Gxu@1>FHEzGxSSWP21D~2K>3{(Y3>eO~^ zU1|BzlNIz))m1k8`O8xx%OV-#361F5X<>>=C-BQhN?mF+DvfM{#NOV=zj-*Ko9?f> ziKj6I=RLiiS`t-5JxBx4VADCr9==U}{{YiN2RB0%q#{Mv07Kjf?SzVgYo$S{2PEU< zM&FQ-P{Xr#eJmK7YOH=oY*bTG?fkmZW^miys+%Q_$}U$aNl?(NG*ne|%TWp_4;+xj z@mbZafSj{8(#t)imD{BQD@=r`k~XOY2(2BL28SS@I)l$E>7uiq;K3P+2`$_)4XDWY zEhQ=nA>pKXP_9D`vHt)pdWxDzyL&N7Q@lhp*@*G;Wp>^^pD?t!O6`@pLSt(&l|^Hg zi$i|JO9E-tq?$W4clR*zY`;ssZjRqs5gTk{Rj!ig9NdW6mB>;Vg&6!w7OS3|A-jqcwD821=p_Kj9oQZ;N8>Il;jtBrhLK2RsJI`NvgPu-hpg$Ssqj$K;&2QWt&xWlUsb%oeqMC>XKK+}^`;JG3(QQ^cYkR*D5@7R7JgsORdE@ZV zqR~Ia!SNKRlSxIYbX)P1P>O2WmaS@Rj2VGN7A+$QSTYY!u9A9sSC`JhrF}BgXwejZ zwAYD~-YC1=$8gcZ0>y7lO*u3X(2!K0;v<0b94H4+wY|G|7dK6NqV79^5Qqvma+O9^ zCsPN=cczpbrmD-*vbLV3y5nZiM@dyKP4^b!g07BLpg8QlGCY*4L}Lu^Q(2V6W!_OK ztXf#3TSS`OV{)WE-TS6iiP&zEUPj@Y3Q;Z3XkWw@qC+7)q4ep&1YVmkm{uprNeH;_|hWH5kgcKF=#lOEg&; zEQJ}7D`2F73RFUzn3?q}vwq_ZdX$X0NIkU4xNWx+M|B*?>mpZQiKUp7A%!SS0n{kJ zv!q)@+k%VT!pCry8@MFxm?>6?(2&7b2Lrc=HLDu1Bc-oXR!vFRu(dr2p^q?QqN+%# zA*zm+3W$XB*ZJm&{@ybzM9KpomB~apm=9t-o>egJP+i3wA5m?iv;wi87A830Y6sbx z(*lwwwwDq^%&9oGG5F|;;Z;~rikSf;v=S=9pgUDTt5c@9rmLH7ZHlSIG&5IXC4z@P zM-UXdn-5P}TNM`HsD=ini8Gjy8&e90RH%;W4M1sDDOfenmiwg7u-)!P3yDlRBc44W zCbv;Y?d}NDrsB|p5Rj_M0Z3=m$rQZ{luq`WY_pVBmLemaM{Mz{I9M180VHG;4rt&7 zNdavvQq}QP{1nTeysXCf0@~;DPxr@aHgW6 z%`9@5sp5^k;*1uSrWoa(Ub#z|Z7%Ip{R^>GQ$o@AS3#wNB`H?W>cfL$ zZ|sfyNIz1{tK9%AR=fj}4VbwK1W8*(_LeyY4g*vLj9yyG- z8N$TG^9;@qe(3rUZ=t!At<5$a_KQ+rP=3QISMusZ+L>e9_f0+l|dMd8-Nf6Dte zm)pGq^1pCx(M=}h!cx*?uq{KqGzDI5D*3RWR!)r~C%4cy{tWFw>Y(^?EQB@gnc`6xNbXuy)mS7(=6m6FB>CkxQ z8M5&8lS()7QIxu?AB)4mBsW?T_613* z$~=PPtI4a2Th`}+__y@-DcTdm+w9Vq@KgReIvs3aCfjVM%@_VUG0=QP>_-QW_}{Zi zijPi?ejl@}k+%)cB=i2YkK_7#^(jI|I-x*KM^5qT8-FGRw3@mS$Mb(!7W{C1vPk-f z3FAiUh)I+ZaseG1J)gNZ2FUoYvg>wC$%EaStK=VJQPyNzACIj$-MNSBp1yp26sEEY zuPj*HwOv_?EdZ>umR?)i(>&4522a!Y4Al9DAfJ{fIxvX=h?P;|7X$L4G^g4+8$KqU z%K258?hlT8$F}etdx_jVRh`YryLXlcEe_Dx**%k)#BPeZoyeVeg|6PKLzu*3DltW9 z=__?q*1#sGk_C`^wzPX$E<2bF2NWcX@C1SLC(sfzPO4O^vXPJo^c6VI6aK1j$3=gv zI_I-US-LVgsA&vXyk-w@SLQZ$FEu7dE^+wjaHn`s)Z&`1H+W*m zQ%egGBy6JcLnB1QEemM^xUEhpUNr#l^gVebQy^9DBBb#&01A`oN{%$*Ixji;9F8v` zRY8)Zl7_01cY=CZ6UQVK2&mFUD*ph-Raq3D>KGq>6atmbf6diPiV@}hewk3Vr58V_ zet*Z_i1}3YpeiVMb+xDbC-V!A{{Usf=Dy^UKapIOS8n`m+VkyK#nZ=vs>i+qwQ^Ls z`mM?5`>5(@YU6m#8^z-)>mt6bL)%xbK9CmVAsd|HEcDKsi-Lw0Sk}cl$#g27DSnzIVJEZj&mx4$ixxsgZK5}c?XY{UeIWCpELFWQauk# zj@KDQsc}ZBU`|1;Y5uJAk*fY)-w~T{zT)2TJ0CFNjfJUR{-)@oNjL#c8Pz))l^Tt2aahi2i+W~&pkpgEY%ZCyV zp{JF42lM{`$Upf`?`-4bGk+a-<{q{zxX59$TYtYhf`cJ0J49tP6yK~+$3wB$=$VwD_8 zDKY@w?EJ}pJE<_jR+y;usbfmeV9*~RNEj!p{Q*eYAFC@-{40pYV?7y%{#<)jTx z>p~$Rgk^?JYpCe1O%;@9ELE#bKxJw{DhOFjEUM#(G_3}q#-s}4hx4aN?W6pz`$kH9 z23nu_hjydQjijn84QEGnu2&Znm4+!9tEr{T3M%HN4PeZgl#NPIExo@U;U1z|DFOg! zb(WwbjR_Sb(xRe+fjl~_pIIeC3wnc0AqJceu1yUIsTKVCFu6a2JFYAcrpWg`K8m;O zpBqEAy^$^4dUlWCcnMBH4M;aIMiq<^U{Bx zAD3DY7H-8_3VGxMT6Ub8U>w)2WIvqu#EsqA*{AsJ{*yNL+{X2s7+v>>?3xXyUp*G@ z!S0Q*62cN67-|`}o<@fr(p6DZxu^pTQCfVXU8E745q<@`b;|A@7y*(aC`y_iFe`(=SNU{N zG*1%+Vx-WVdT06LucF_;ujO6Rzsn=9K1J+Koa}zh?%l=Qn@)#*n_!UtX-pwrdDjBbdEOtB?+nTmS_;fF{0u zUeY;J!`M-*}z-hI79wcYjcJ&MLoZ_4e!9yTbuh{m{z9VWy_0X{w~Cjw+cU_GL>}c{E7A z3O+t1(m)MXpf%JDNEx9jN1sgzCWyw=c6QaM;Deed1fD80tJah}M@OT7{5tv7zqI`e`&e!e=*Lc$b5|5-6is?ujZlJ-!XOe!EqonvEDBU<0ojRKv10!K2AxbOGpB}=fe$(HOXN;Busc(} z@Exz(`}?+jL14DtFT8gC$n2h&!E|0?Y%VJeirbkS7ft-C#&#D~KsxT9YGdgzIjl7< z+s_E+tdgoKmX+113ARL%9Z2Y0zNRuMCZLR?RB#E34GIMX1vev2E5sXGL=-P-qiLYc z6zQlWlE9Oxjas~VwC3OY@-IExlVf(&82!SVn{V~@+oOv#WX5IEvjMmI z?;p0d&24=<3aoV52BVP6sU)Qctz+XQwPlhqNsR*0oQ@px z$KF_+TXptBc61NS45s?q(seIg_WuA^8U#Ygc_8TO7HjX zlic#~%0T|g`?PW?n%smmDIg}J902{e`SCq5EOH1Y)x#v{P|VVUlK9f zR-dVNB@XlNO1woL19;X=p3l-g(89@{-CH_>Ov=Efr^G7^vPOg|Tm$U(SrRy5l2F7f zgaD$XhDNXCx}ofF#t=0p@?$^ZtEUWFN{$<9}CF?2gdef6e#d zCj712c}gw&L9q7ScEqO7Ze7o|vK0CH9>2j*;(M!g<|N4G(uhM1P^6H@JF2V_vwLD4 z#@ZR-G22`-hZLY4)F2%BaTMcR@aaL@Z;F<5MTVxNoB>bfNU0RXDU-vmpjUJC{x7t5 z_EUdu?C$2qt}|+N)<+Mv^H})uIBmI%&TXm+nJ|>J!fIOTUDLTYGqhPMr%4Cez=-68 zM2z;%mbZ6e2o%ou8W@Z-P>KM2kyfpwP--X4<{9RllEUwJZNlPrj$vmWrYasi2xZbZ zh7vrDqPbll8dkk%mHf%DbaWriPv*8a(Mui=HLxEY1ay$BVgu8iboBIU5U8XHNl+~Q zsVoKgKEd~`uH%@b)t{-7gO3K`^QX%l5$_S`8+2m}^pKtu{6CkM4?c}I@`{F0{Kx(( zGLbf($Es4ys$4@Z-p|NG5*Uvf-F5v~SaE-7w!#|b8q%d2zmW3(09VV;qE>VJ*Oa?z zPU!&q2BLiUaHsO~>*%L~#ZuyFCXSV)VOL#OUpqU@L8z&d)Um@fk_uR&L{wOlN-mxS z$t3Q=G>*;%jjFV*X-bl6NghU|^^jJ`sR}9_3i(sa`FVYvSGV&U+k0y*i}=@ZTK~47?mZKk#q^_*&3|#<(iq*o@;INTZR%s$3Q$t3~M2iXctMa}I#>&h~ zgFp#5HL0b0Yd~w-2^GycE9Qi?Zdu+M@#z>5i0Vkya9nsuq;YfJ%D!P3@KQsT$f-#_ zUT!3JD>PGX*N9C6K;@3u#05yBDmYjhhifZ^CghQFeT8HO@XDlA%a68N^n+y~uH1$V z`p@M`cJLoD!1Q?KV8kdXp!0CHH?Y0`03-ZIv;Kx2ePPmA`bZ_NSTNxJ3FGib^!My_ z@0XG5rPZtG57kP70B@&1;7`AG;abwYN)4js+ME&V1e;&_53RuWu031IglDh+*4zb} zSg0xIFS)AE)?xP5E@ShDA+JT(qC_Y)Uqz)yE20i<|RyzaITwJ$Z>a>Q;q# z!T?aA4mAB<&1a0<{cbPEy>M++>YjM(%mC5=0zm!0z}Pj(Z}2=WlX2_f$K41O0D5)o zpFDN*+W!EBFgt(4fNZh$WQaJ0et18+(MVgBEK88wYsRy_2oJaH&KVE4OfvHqV=aK`r_ zUVOU*pY1LG0GuPw{2f9UZljxbFitB6{a9b{bW<}j+{qgtXN>6#P1r^iY?k~0P3`VT zvPyVuUOA_gdJ#l~5g}?XNL;8PUz?~cWB#k?0RY(F@&3cv-Lb#~W|-*O+Ku6YD0)o@ z#F=bL7ZHq{&2%}bcTR@?z{{ZF@ws$7b?{&xS z%r5rB=CVC`wK8+o@662mpC!5}UGlV4JC_Z*j&E_}w=UDDr=t6M3aou(v`8tQ6j<6P zjdDYgZ26AUYnnc3x>>g`s&cNZtcEhFqe)dzcvFQ(0!=#PkKPBE{g388WZCY$g4qt) z$v?R*mTPy0NGD6tCCRum$1BMoa#>iC)MjRIqgHO?ZM<|nAJ&o06+HzN2gZ)IhFx*I za79fAPvMcOYN4VsOB&9hrf`>&N%{sleV$w$cZG=r_<(x;AUel13>B2q#H(V1_>ZSr z%kE7d#8^ZIgrUZ$U>d}VIPOb0R=GTji~AXVCO^_Y;pjGaDf8(&Cx`&jOQJgh>Ko}6LarmZWl=pfv?$e%Fv~>-HBsRc8qzl^N$j?5hQn|>g|(asd0G|(R0B$Znk_~R zDS}4=dQp6i`AMJduF2n7&A*e}+heY`4*ZvV?aj4Q4i=kq3-L1n-yfG1AaX7u9Oa1hwLmXTCF+;Sl*jg>gzg`w-<<8`iuPad$j*`yl zBZf7!_SW9eUiciBb6bdfDGS4KDQFET3bcXDcH)Cf5tWEgX;Ds=+wI#`vAOVV;sL`c zs|M_EiZB?Ev46srk%54qW2qS*lHJvq+*@09RrU@>43@;G%~kCDb{B4K?Ypuz)9!gh zyS;IpX@J}K&bz0k-!gy4!4bw7bHj@Cs2qFLUfEk)S>IYm$+vzD%El&lisj~)!Uw@J zTt2CZhQH$E$yhPr6rk#{ZJSImOKz~lW06%_tQnn9)-cY@S-dm-ok{TMG*W_zzSHi` z#_r7KA9D7V>8ag$oCey*?A#4Oz~XRp*lnwdny#ZCfXCvt&KnPiq{q?ETQj1h3V(3& zN40w&x6*RGl$&P3$~Shla!&Iyh-W3{lAa`t&aBMMq*aL~fLDi3*xGHobaF>y9C53; zcB2mFZY)hnEPYN-L3-0ugB-BO6Mj}iP!y0z4359!{_-vFeWr{kYyPkJzKjQ#N-ep$ zGg~)5h}~OqzxY1kz}1Y7Co>EbvQ*>h<3>fDe(njNe;jUfi4~Q8pkJS9?=0IGtQ2tHtip&vdSFx!QKGoxQZ9Zd)>psD$a z)P8+WOg=})Q?CuUe33>T9~KV0roSKzm4wp=Nc3MxTad$^J-nM1`sDmg)I(0D^W~kXrro+5tK1h zfLW46W~2pHMfCuAAoK3ymN}~>d0%s&75@Nnrs3=GdiC!f4n8_@r^Gn=apTruimRF` zFSW()32LQjqpOVIvOW}XFiKHNBy{g2#za1_%B5UbTyyTr%AD5W3UaRIYIM|E&T4qj zQ8?4fk5o6dTA4nwEnrlQYfu3Io;(2{6TlJ&9-txyU1-WcW*iVmb>YyD^-6xA@(x-o4ILtpl+e)8 zl}I!=G&nfxM1Tp_ppG>lQ>O{0hL`rIj##P`w!KkFp^PzJ-TbBdSO8pjkC7oty2dwIpFzQ7B=yn>ghCJ^1Xq=@{5= z{Xg7kj%ivR&rJQ9>Y`Zx0N;t9=`C^j`E@KwY9;)5c1FreE8~hgl$&8jPIc z2XEPmIHZl-w2;pXfn|baDkOqY{-KmI-pAQwu*(b04DdX62-IYCWMw{Km4IbGB06zM zDx?raaBEOUt$g}FpUSdW*XP$ueaMnXUm>{Fm(3(nB!>-E7Cs>H6?rLIwn+T3Tr7wP zV8hZ#H{u4*eggjhp`V}nsnVDU6Wfu;TK@oqf2-{4dk>3B=jMmU3kPqu-r1R2VzWsa ztM&f$5^)v$PHm*Mw42eh+7T<>u~d+WFg)Y%lkIR9iUXNNpiYskYhD zIF@hmW>zZ|`3~Pz60hsyAEjRvGkz9kDDWm!c*5(Qc~1ZJSYwKE10bLn|8F8(UM6m z?A8e<1hlIQw3d80@5mn+%MM0?Oa_!h5+`Dgf)z#@rF^J02RY3(oS#b1E zPc=q9pBhpqqncEdsbWHhD%$ihH^7cphRqgVry;bXJE5+mVn5?RpM?70jCIb2*SX)B zWl(VI64(1QD$J zmRMk|rj-~;F_!WmQR3yS(!V4s%fDU09kNSvC7fi2eH2vsmS(BJP-qIA)|xU;O>#eq z+{1kkvhh^ds}>SyWneB%6cQECkBe8qKvyh5w!f5Esu8_*UgE-T9FAuxRkZUG)vaVz zbd=f0qRLT6k*~x{QAbK=ILbniPGEUOfRVWpC$M+kX>F`I%a_HpS5Iwnm$jBfby*~i z>raasxC^BhOk|}-rKviJ9TXuzrt%Q)9b~qqr>&@YVt0Z>@vG=^dwTL7UbVM- z=q0lkO{yg$#!nVXJTo)J{n4y}-l~SB@=?teUmXoqLkb}hDaFe~WsaGC(3X-}7&MJC z=`6>eW*bXe$FggcrHKQ9E`wGmY6ww)kEa7sApZcSI8k{mth*ibC1r|skT8-k#hG+~ zAuFgY0o3foYAr!i<|1@l)Jxd-+40+tBNc3PRe;Y;jDtm0X@JxC(vGfEPV`2OcXu<8 zt2j+Qq8UbeBJI)JFYfl9RuTSGSd`et%wR};YoJT z%VQ~)-L=eMU>F?S1430zY8(oHNd%Fn4MJ*P=c20h{S8bKQ_TfdZfbZHW0i7LzjaM3 zONz@#sPUw48nKO}{jyQopG2Z?W&Tk*&86L|lVn)w2MmN9g1^OH2ZK(sEU)YsnzLLs-{d1@1>`vontRg zT`nYuDyZdkF~dZv>5)2aPdgc*7!88 zODzZ6Uba#GO_VKLusgP{wuvB-cOKG*N>@`ns~gZ{qzn9)E8P)2kWmkLDlM{{R%%ZhUTE z=4aMF2dlAlt3vxbKh_v-^338Bb4v5#Qx!qDG1)wSQR85#X;~V-?zZhB#>$j*!YL8u zEu(ncqqa*scx9H-G%Ad-k`O7NQ6&gqfPgUiG==zAM^le4?)={TyJ=&y*v0gaL?eo3 zR&$|Ap+zpDK!E5|Q5vX3TrQr6KCkKin&|%kkDHGf@%8Z8KDF$9zuSH9Tif{Vz}wxG zmhau`*;_+3nBIN$xVuYk)BgZ>`wKt5swvjhSjeHqQd2=49R)o#JS!5E?>7^+-GAfM zM;)BVswxNz8z!2ZmNcUl$zVnR02W={Ute$co0as=+m!RxMl@P7k~E?!s>d8{s4PgJ zDK5>bSCU8hKyC`5QCl>MSffiWooY~pGBFBNl2m|gVoklt_HmT8wo~y4)O@}X=hV|< z6)f$+_`EgyI1V4``#Me=j#TmWk)7w4P7&A3&C(8^gppSRSS0-P;+~l3Rq6fL(cM9f?*0ANo3C>3oyU*r z>2dYg?8LW%w{7kn!-U(lO(fMA3@j`tYjY4yFp@(w@xrjgt0b!DY}L1sRRWS0+C?GB8aVq!UM`7z|C5TD3n>sZw%4P*q6s1Oq^PxMX$U zTS$+@It6J=R1;DUoe9YvM}gzfP~18Ep5@9{X0sE=QQ+KcM1R$@*nYk=jpZrtbF=qirUxxasIdaAJ4sxJbL%p>(}Bv650&lvrI! z_Lp#FSS-eZU8R@(s8x^owy*fke7aL?tYw(11?{KLC;S-CR-N3xBl@r7rqImxzjN+t zt*No`)pU4VeJwUG`0nuCn}Z<~(oo=bo&}x(mE0K$T6v{No?2=+Acf_gXrn^j%L}@d zRgIcvGzveReE{<(>=_^x!B$X4rC8KenX9A&{{S!_<`IJUF*j7E#f1J;Vf(W;s5B$yUzC|Xc}6qY53;ZPI+YC)+T5?X)wP`xE>UKa^V@kYFD`13T` zI?8|a&sw=0O*ST*RxW%5IPI|oD`n|xiD2~%BQYHZl2}|>N?qPh2A~i-GoP8^>F3s# z`UFyt%XBJfT}mps)lpMg{{Rhq>!|shPmG_=M-TF=|DpmsfQ|*qinTsH08yzM>OLO$|&`o3n7zHB6YwNhoP0 zR;I2%<_Z~}G_e6AVhJPKZ=$m_4QUl~PR0COe7yYnx7FQn`i2em{P=&xbn%4UyTU5@ znwxlUDpmV<;jFETb>~dxpG?b7O&sFA4~-T^{hRo~c57Vw+gVwaEA(*$AJASuv(q1E zR5v$7(Wi36QzsZd%h#bYi@7)H$l+?+es8*bwk;&1pju4*O;s4AY6YR5igl{<)BT-H z5v$Ay7nwufSO?u7Zrh1!*~VFhO(;fd#Abl-1E$U8&;<8c}VwTZ0-0MtcRrNd+Y0K$!aBxXGLybsAttTiys|3Ote46{tn_#>;tE@rm`C9(2p+W_2PR#V`>EQk4A5IOq@jsops^&HRI#HPljIts(w#Z3=q&H5-PHiDns$M}0zl85 zPjSvoa=GlTm)M=pxVHx6?55pS+lzJ6<7qN-P-YG-Vi>GkIC>g!8eIAl(9=Yr|47@U=25aZ|k{@$6)hv zRbELMCNOjW6IRtgOHW4fOi**}w$0DZ{5&hcBfu zs8+vc_t7- zfI#&hs_C`;*kEPNYv?-L3h4qBr9X)0{a#%ut8;svI<#4`yLHx~zhh22DNY(nYN!&k z9%m zA8(xx9-3i~5XD3XhO8g3VEpUDpx19_=r?}x>x`G!8@ z9~?3G+Bzhg7nYix=^CW?Y9zG`@YI8*P=WCf200amkfdN!j*?Hxl%e_8s)>k(<^rUb zC~N7azsT45b@QhG0EKR3RepSYaoFmsEPZ?M&uQY*C|aCUWX@NzyBjjkQ%Ms^E!b}7IcOiQ+3Aj<$2|&1 zNk>7sF~b#6U0E|!M^l%|gjpP~0;z}!fPgEuiKCJQk=dVGnv>>ER8R^9@*bY2Jzif8 z$tV;kz#lJCeSLqIUuGCl%Hns&mFUP#WhAJawvbmPZ9G!vWKYmciE)gHw)`{W>jGe7&?swSoaSi zM+L|uI6Zv(f17U96u-|S=fxfZy9XXC6GPE^mZ>Upbn#VGHf!V0R!f-2W9ghs)ww!6 zyE%GADh23&McYp|7Wy7d zt#HQHTwTXQT890FNYD6s1d>MU%C!{#0Ctx3^QU(Y&b@EF*}dg}>T^qmmk+;p=Jd%? ze;J_b&ZXGde#73gVrI-^a7Q&+NsmbIyJrPUTa-p>%)M;|G|LR)CwGcPS0TB$fugmx zN1cp{jo~O|h`O_>mEDp!fmN*;^){eYO+o5+wKK##IS3LkXVdX91%irs015Lsqfp?` zpmjgUKaQQr@=t$ZaZv7UoAR?};pv9->R#%^?oFlI*d2o^M?ntj**$x>bD5pB9?QzK z3FXc0GvLZDnJOlj6?1u7=v>IsBS!26E2NTy)Kg1105CNb3{Ij)8U{Iqr=Ir7Cn~}q z%^HzPY7}==B==D%tap?Q0ni$YY*f-O&05roH8IUTbt^nB7)L;Q-x)GIjrC+|$k9j~ z2S4HO+g71*f27nIX0M?ALrQ-xjke=m(o%{78A&;<2ZTRuPxya6j>$z={UXHN5N-jr z$s>*r=h@)$=u~?1S)33wkT|!~f%F7eHz(h^-gpija%YX1*5nAlW<2UFSCAOkAFt4R z_gk%a^~oE@rpHhq+>2iCb@gic9Y53Q@7;J2j=%rc+w~Er5c z$Mp8u^vwb4x$7>H-<@Qu*)9VyusTJ>f#dy;zfb~AdhxGcJ&*WO^Ev)uJ4?t#lc8|R zi}_pb-1(3&7X_G(f5zk3LOOj`?f}Qs*Y?Jr;Qn1C=C0J(d#XN-zc1B(s^@CK3HZ-| znWSi?MC@r&T>vX7+)WrBRzK&Ep$lPcKH#onm4~^PXrj8LwFG*9i-Y?OYI=e1oxiTz z#Ao6H+Mo7Lr}^|rv!XPbc@`sOawK&eO5UGPH|0W`U;I7F_BCWhX3Gp8LFv$@AY6r3 z`#MBqh>|vL0~aLQf&F~|@)q9C;OuQ69UuyHaR*~Yw8eT#%cSJ-mlp!EhUz&iKI#!= z{AwP~EDo0c0B_RxXkwRDO-Ub@SHH6Hd8%ypOm-F*F}txDF15u)p2JdY&9$)iwmT=g zqW&LSwFdmyotGp#FL-Rq9ELgCqaRlymXyaNcak*+9eFpK?72&sxvE>}+*@4C;7F8b ziILzWmll?(G=4fV zwY=!DRv8AQC7E0bhFb0ZU>o@5GMzEhuC;&4kgo;oV6jBC} zTYkhQLZ6|rG!?PRwXuA4!_q8u9w5>o>WV+L5`DRNz%a1TMaWwlUgO%rbzQv){@?r$ z!}IDU1=L7%mQt*LJn{bkKU&ys{{SN7-}NiCCM~3n_hEVnY#56xf(^kRk7IHPdWwIj z^cX)1kF%?3{#Cyi_6K7B0DC+0e_?T3^1EX1EPlr89fg^shby-!cYpATO~I4i`@3#d z(a%A;MFlQKmY)reo6kojTTd-a58;JhBfW>^4YPB)zvi9BAv@UIM-&keRT8?F@t9DC zCnf)X-5Vji00Z7zcqS?{M8c+@ zi$897`t^lTZ&T0XEw1d(nzbaUsU+31eCtZ_HR=f58MJ7_!rt_##OcY@Jx)BwpRbo%ZN~J9i|Iuv_>Fx30M%bkr$xB)-U(7X zty_uGB}a}y9FV5HC(8hf$0EvY$rf7!?WR&>i&TsPR--3Z*_?I1uD(@bw^9}~q1Ht` zYCQVsw@%~|vmEwCr;IdhItZ@%EQoaoR9-Yvt;LvoekjEN0*Z14PCb15`24!lZkw0k z+-IQvk>m0l1v;Z2=F9P)t+uA#+FvL7{{Rb$*ty-`*im)AYV7U1i=@PC?a80Y?fk~$ z+dYrA@R+!1@cUmmRY|vNX>-(+aZ}J$IHjwG6{(iB3tn`wj77OkaIst{ z!ps?4M4EUB6GoRH4-_zV{Xp*~V}0ED?|t83-8ol#oZPL1D9}#qT2hq?(a6MA%95oW znVf>bz7;06`YUJcd2qY8wf8+8HsO>Dd4AuHPIYsfGCZwIh&ZL zp62F$VZIVgBQ%<4lxk;f## zm*0DlTwMCJukkQ$%r0$jcmA{UT52oJd!W^WOS_KmBVW|cJ$l-5&n#5|<&C zAMu=5si(8MQnja^Zp`dCW~tRZL0#>ig|4foUWlvWMq3N%PyqVc{`S1t&5Ep_*8SVV zr788dARO0#l7~Hba>p*5uP#{XbCcjkYf93jt$fI@9@OL67wG2yxZ?LvPrw`wy?=>Aw^>>3h4xp zPaq-L&^&TMD~D|;Z>Bc{Hxf5&U3(cc@<+xT2pK`gDIju!>#Xg3dPX$=%j!iDI z!T|zCSrDi$I#B-rE)R?QALO@o?gZ^J`5wFKO_IHlxi(cLWp*~de^gDlv0Gzq?V5`E z6pDHcu=$*#O_^wFDXX4_GZizWlKG*ReWB%DvzxihSnmKn+ih(3FBz>RDCmh9r{LD= z&MGx1Dh_(Z4|=)hapWFIZPRFs9op*ZJ6K$RRwj`okjhlxm5wO{VAXt5g_V#povc!i zbKvn5{tQia(A#u0)ReevW(#Og?OmIO$B-qU#^Lc;++I5ghQ}3<_#mZ;A~)0lB$J$C z-dLjoJ5^W`gW)SdfG8G#R}|sKo_%w?a~;+F%*NxHE-o*hQ8lh8O;mMghV5BhWb zv)4L($GFQ%pT#R&MI4UhSQl9Sq1b7$WIR}MTj(r3(qgJ3V#G0}4No2i^8QrEUKiVo z>n8eRO8z$C`+CFu;@lMSstnaln%bT@Sxk#y+Q=xYDMI8h`h9;s{0Vev2s*rhCm+wx zi0X#&^<4nIl+({!e=nb}SsO37o++94AOX#}AYa`< zc?bv?)6lndsR&smSICdM_qco2r!(2|KI3yO#?5*d zL>!hj@**?#F*R7(RD&3*>e9*(>+ve{`BO$}K6~`7p{NZ@nXIlyqy$sU)TSnu8uH5E z@LGuHQ7e2-4g}bJ@6z zH3Be+G+PIERkX4qc+0^IgNV(phTN0v8L;X4%y9~7>zaS4{JK2cw1`Nr;s+ctTvy1S z@byZ+Gxseucg)Y2Sjj3eb#X!Rqq?w^`CJT@Pm89{LA~;=S+lc=kWo{I-Bj|DVJG~P zB^kXj1O#kI_X}y39&qN{yLg;8*GnU>^ck@-{{R$BYpj2vJweA0qc6J;IKjC4CG6(U zcX<@3oV{UhZ!H3`mMdfrV{m|wmoY624NxxNDCz{5ki6_{E=zrPF2U)_IxX22=M#x+B$lPj2kW4WUy_RP(I0*-Y(SJ~El%oD`Tx z?dP}l9Lr~Sy>D*9$V$<|rTi$E#=50)IJ(AtuUrlarn${_1SZ%HC?1P|bC0$d?GoR9pP)3Yo?il`2bZ*t_9v^>Pt)5Zw&8iaU2b(+sX~K#4|)5L?Sq+QjIi_LT@mM zANxKzNZL`1$~R?v;?Y}OE;hFpT|{=LLd_&ClBZeYhIMGto&W>J1eOgO`x5=;;D%4S z?=mB)Xp@}w?MeY8En1I*#fw&>017rb`KZ;=19pW0fa;0R;EK&Cyp?B=Kai)+cHU|aHo?V9C3rwxAMBCppzrn z^pz_?=KHB~aU8Zns)t+A?A_7#br@*lf}qU|Ars9J0M3mX4Fl99&On7OIg06?dwAm( zNl_?j0IPJtm6Q{xF`-X|>Y$J^74i~8FE?F5c3?9L8lYz=#46nqV;~Snuj-G)gb$dt zkC|BvwQphVI$X|P94t|7?7PbIQr5>-w4cN%YjF6fsivNIgfwoV?+tl%FEeuNcbDD*C5*+@ z!`Duznk6X2sFq5*FMt&|YtsD(89_giS0`V*d5!nkif`pa;gG`QasM6kJVKr47C#^aut;$f}q8aOpG8! zBo4{ojYf~sBqDv5(#Bn=6}U!~r)FSD)m=JH2@1qwpx{>mx$AckgxFpy%SggIs8$Y9 zf$kyELsCs@G`wtRiQy3&Zx!EV;;o!oXjEFA-KDO*5Of_ZKH89 zv;Ob8(4Hdg`=SFfNeWyfW=|EgTm3=-?Sdul-Lu?W?h6*yml7;fs?tkoik3F+LgEX6 zM7p#+3u^6)SWuHSBvDdjG0l#AZ82n;+>Sf_XJsi+gJRq#~MZoPfHb0hk42+d#}HLWZY?;EmcPiuTFvd?;CgmL(>r-~m+0 zG$w|X(CdyGNUDFI@lXw`9Z{>yMVYS2Q>A5eaZ$D-apLM}SthS%Nf6Uz;jE|epha_8 z9-~koo)Tu7d2Mc9=F;Zk8r`_oUcIv}0?DR>OOM1xPx>I&l815@%_}~+8u_&5iX)W( zqdQRH)u;g#ED7;6u&LMce$z=jvdbHV@WCjif?W~#;UovBF#^c*IrR$N_6#QAVQ*8hQ^EEBVtsNE>i3x9$WE-3n+w4J2Hi zwo(31HP1=bo!dtqT6{HCX7NE#_I(NGeF=HSO$Y z?c74+Yu@41R6gSp>IQ^rg+Vp)BDDv~pDv8~Ryb$o3)^dnbVVy$sXk(?;Lsj44O9LO zuWP^dZ$)&MS@m}I>2A8m?ahz;usic{bmxC{mRo6VZ0`Qe{AT$rM~>Rv(_I!qOqFKf z-Si!Uw|icjv1)SJ3Fe~A*U-IvWU62sU)3LARS#%ck*lN4(<5M2lI{i54|e)7I&$> z7+>b1@aQ^^%_HS_0Waq&r+*iShrR+_Iws!vMmVyE!f~K{lc%zo4V$sh# zt*F>9??pbK#X2<&Dis(LN(0!#NNQvek~)w1t}Ausm?Mr)@s_n&83+JVTP$vA_?>kx z5=z9Np3zUA^?P1vZ)Uu*0#EfUNap7L#?b!&We>?0`~#^T+gH*;2N0s4v!>f=Hu{2i z{{VXb0DAWD8nfrq^b7$wJ#qs`Bp>y~{{X=7J@`=8r>*f6Jw8HpZOo~?iq+%2CjOvH zf&K$WwwP(ShwMExtEN%unsjZV!Pn~ zW1BmwsMDmzKm=(8`=w_3PYibpc{uPDlNI#fdRrR=iM4zNMJMtEe}nyA zuOAyQ`TdrkAgZ&ye_Q?C&h*~k+aJUC<|(K#wFbW@L6gTxRB{m0$31Q`s}&VeNlsPa zmL+v5=|1*V($Fll3`*pDgH*5jzTULOOs)_eKAv>1sQ!Mr=rg3i^j=1f6&+T3J+#k@ z+LV!2(C0EaI*g7&d1)ryJA-&o)YDeQh>B>MdqqKMh5Ae5sGl zx%A=y9eHS1xcPDa09Thq=X61crpwpCgK;i83i`-sivV<+Y5H(XmL3BX3W8r$86fXG$xj!d0>L6GgEF_T4MvSSe;Ts#r>k(WeF9L z0GSMu1Rg}Ugg(z9pFnz3W;M$)G@(;TB;@=erj+vlA4>F4f0*a<5Za$Ua2++%Ju9#? zJ11=H&BK@9x%}T{X7;Wkw=cXaF^`CVQ{_%lJVrBX;jo5Rl6uL}o@ox0MM15*dufH! zT+Klm##8}Pdy1AVk1Z>vl{Bx}*5;A}AB7QTnVm^uG>Rx8R4q@N5>6?@JbJP}<#D+7 z_rQ;gJLfOoS-rhcvwJ_WXt(YQd+mM2jcuxFhTEar@!^ej>`k)y+`UCehN39&;=N{q zM35H(!`BxzXdsCg%Tqz~VxxvmG}nja)$J`>Lm+8FkO4m+aZ}~T%g>-Q{uC>mT!(dh zL%?c_?eTvecOK!7$BTy<7QNZnxj707y)ny~lf#NlbI3IZB?k&U+Sv;38=A49RgFJk zbAk4g_Vrna`gj=+X_iC8{{ReNSIA&+AK^VwUfQKuw;mdv5gSQTwV|{+4N)a5kET{u z4dC?i{e74*rmaKE{wt(|h(29g7xIqVhyEO+(%~{{Z11{{Ww>6YnqQqn+w5^6svr+TRs+ zrvAirCui>7tA@I6-ppY4-fDfPlAjNd%s$ws+nHEWm8)nf6bKA}3kPDr`zN(ao7f?p zT~(b)14%ScO)6?LOrI+GbY*bXme(dZmSPoDvjU)0sA2+@I0VpDsz9&Hqc`6l%#Wynbq?9Fmi*b9OBGRsrN$2AqRVx3czkt6^{389 zQ;Dj@)YU+I6%@0qbyU;Fs%|Z(hUD3c$XelIM`1&N_0#x?t_ajXRx0{61ShIRHJe6c zcy3io6%DByQ3kC})zd&hBCSnJQZ)h4+d=%zI@1x={dK;3^B>nA9P?YhZshkKTducH zbZw2@y774GY3Hn?Y$g}4sk6JUaZqHj3k0xDHaj0D-ArMUHF%^0&kIECjWWBcg4$H^ zrAV&+DRz`+Gj*9CWH59p3psfKU(zN106{nX~;r{>%Kiyk9c=b>6>)ce>nW^_4 z@22ft;f=4z)YVf|%h!3$zpyJX)Y9SFWsaU@sj3pmBgC_6V4ApL?UYHQ-ln&8p<7T$ z#}gv~k@g=xo6>)FJF8YNs-XLH8vaC3k3fEXP^ZRSxl5Ma+o~wxh5rDBZJbt8o=>ul zx~dAoJ6QYgTF&};q!pQUI#gqr884h8L0d;`6_6nLL*TVqPWskNM_DvNhAt$ z;K)bXBWh>J`Hr8S-Ha_Eu9c_ks0aOzQ;xS1@4o5Uod@y198uL% zVPT1BO37AK8FecAI~G!;H`2>E)RFcAp%n;qFQk7PEo)Lwm;F5|(S(-Og522(yU6^{r9?lmB=n@uUfLWTqKW+ZXro&%<9D2mZmix~|60BdT}NUnGQF+s-_sp#PCcqnOL z#|)fRRn^BWSWO)}lT{WrOjSUWA4emgr8LJbVJ=u|wSi)U+tG-^sA_nIzilax*m`bP zkUbR9Xg#1BzB|R+S6C0Hph+n9~-MGVl2b;Do09Gq=vRBK`|q&aXE?E{IvM_B$LMwOI-`4*f_DjB%f@M zHMIxn*UzU=(HFP4f&uAGM@VUSIwD2oxVo<1A7XJWI%l<*+`=O=} zoqE4g_} zoKXJ&gYDz_bO!CU#zEXN$0RiAEd7tzb?{aFnDMqz@SA>#simGpWL%7x^d%$>qNJ#v;W^hbHx9}nSs44z#zI8wFthy-aeq8)4F+w3peh*>V5#^3q zB&AN{?D0=5%#kFGBZeaKypoG)X0m_^wuvN{cIGiD;LrhpKhQ_WS2(GupaQf218vvC z{oA(armv~GuO2_5eNT}G01WW0NvdzO8voI(J86XZo*Y;x>lP3r)PTxGL%`y^+jS(a$T-wsy58 zMNLVdW@p@a+xU_i2xAG{$|u}e70vN zxH1rI44&Z1Wvk=K)7^1f6qOZIBq>WmAeJSjrGhx4qos~2cvWJJN3iVnc2>W> ztt{eHw2J0JfK>MuEbPq0v%9-9$m~gHVt!pmJFI2l*_J?c3uSEN>SE0Li6oY0V$8&r zW;G<7^lm?tq?&)3PsFup8diSEofN71vh6L##^toOg^vFK4%GOxvqn1XI-IT>c zO$=&+$clg{1KG~ph?a2#3Ih_yO#m*&tj3;X{{SEd0078)aH|>6z}1N~;acbH`Hx5gR%9TilPxz|)a(i> z`pm^EKiMp_)bq0WCq=PM{aft%bDsXiK8%)uD?*s z5;YnDB)+B^PiX+NQ%0q8*%8Ah%-q{Y_e4_A?kc5fmena!webK5K=;2?;#RRE?W9=& zjB&wU0pr+nVXmvuLr`3td6yNh_y2>;KT)1#AbX4gmc;gQ(qfu>23t_@8Nx zICQrpP!72l^_91vu<_iBi(bk&TdNcK_o|vy4E3rHT=mT?w+t0oeMZVZBoZz?T7M*P zZ_m2wsju_@054kmI_6kNzL3{eX#p3x9D;tHtA9^*sntWrs+P{4zIq?0yA!{!@&HFKnvddi~fCtqb064b@CTK^^FPXFErGy#aw@iAJ6q)sy83I70H3)_&j@Ky$=sTSw} z{(sA;7jR}?b>C)Dlv{I8U-5MR06#?^af417?g)?2(kZgY+Cqj1N7h9jPjW`sL$Fiv z9Q}ij^62))Ul@%?xaaKXJgtiG2D2)WV{`ql)nRY!l{|Y8!zl5Nd$|5z=ji$gL2!f1 zKbQIXOvwRkwmD-c0#?wo8Cy(CYN&luwY@R_0AI)+&bIc|LVV9gwyy02>;SEJ9v`2e z{{Saf+12~EW#PAHPVK(P+8Le6*4w`ijmLHd_{6VcWN>{Gw4}~$Oh)AI9r=aoh`-V% z;M%=^g3Hv^e+{CNlvh-Eqj{7Nl0ck+%Uf3a&3x5$yCO)ob33GLHK{D}RlF`T6d`E2 z0GgF-4!f84r}u-OJ+<}|*!`1`_Zc?Zj$pHj-s1i;Bc3IK$_I|t3yA@a)ZROhB<#K? zgA=SwgtK%*znT94Rqef}xw>Dqc8pYeb8dH6T<(c*{d*>3d)DW$c#gB)nLU|=-!&LM z$bud7v-Xd1;}#tL2OE)TC#IyRWhF>xqnx$~EG(OF+iYy3g<-f|UK)js`$ zibw_n)|jVUw&sp-=T35KP0yV9n)7+OOBT0=>gAQ?Humg%D2s$b%NLAMO8~_JlDVr| zr<5L?#LDwjH7q>^x8pL@8bef+l)YDvhR-BXK}RHz#+D7F7ElZNu6^84UUn`_{{Zv; ze{VqmTty=aWH;qb^++Kv~ClEm_kEN}F;v9cO!3&%A5 zy$0C)KD6rOJ`TxIN&L4yW!KTvRb%TZHxFe^Ly)0rh$~>Li>LOeiD>I!v(r?(j;N0r z@<#3&-~fH(*R1{R$| z1{Ff4;c~#>r~sA+jXFL(G1XLCM|$kszg+YmV|-!2rUpqn-VWL9rtCQTqiy9jhBy0_ zh1wF=Z~n}s+WEbq*pp4T>ZdJ$SH{UCFF6P7q?CC-mn7P5HvP+OoAJI336WxjKLuQ6Y|>MRYVuhV@Di8G6dB~cs= zIJvh1*<+;TB>}L!xzVD|a;eqQCyXnJHVG{#RI3srBx4d=49x0zi%bnwp%9Mxm=`(s$Jg272=9^(cveKNkjda zVksV+l?+ql4{heYNB;nzO}d{LI`bz}mdD3S*ZuvB`6EHx*z7cv6xG>CGTY0q>GEG1 z>NhUq#hG%OYwYuq(A3k^(NnumTPdezcOCDV?f0`|A++1<8fei?#hu)d1!7HGa*5W^ zwBUY%5D1Z$1_af~L_zr1%Dw(X|oU8ctFYiVuL#_nn6mf4C*A-jkh zRn|(f23B~+p(>8T=KFuMW_^m!>n`VynXawYXlEBYdhKf*(RlE^#Bwm)RTV!4KvXu@Z9spAvJbog4apWoeiM5E z$CXxJ^?khzzUxdR-}#zAr#3^65m_TVKHu_=sl%mE{{Wz_$B|1|cYju+Dyd^{^ncm5 zcKRs*n{m%P@o#uZ%w-QN-;sm$w*LU}*(ujgy@?<4DCR;BaN5?tVYpxN{{WYx!|`W* zVm1aJvGQ20`L=pbw(D!Q-3HF@&d1o5y@l4eU6(FDJ^lUas=Pqj-Ghjt-y7+^&n1nT zrvXtZgAY1GTSm>Mpwrq-^52(-FyBeOTx@%b7-EZfOKEOnv<{P*ZDdH1m^I?B>6%we zG7(W)3q9iH``%=`<;xkiS+~wrSfzRPt9!JxxqFq8AE&+!UI`xF0j}OamkJfG6`mPK zbYjj+sjIuEYSHniyQaV4Al$w{igGp`R2=X<}_{BX}Pi&FMn+{zS`GONY0R4 z-$`_2ipGB!7$#eVMt4sRJw>B-3GDpZoR{r3`ka})q+7*?>@4E4-IiO?wm6Q^&9$N1 zL(hF22{5>daV5h9p0Z8g#uhN!ar{uE*&Em8PQuUbTKt}Cp}JE8+*>XkuK4VPxr4eY z_6|!Kw>PykxbZD!O9QjFqYT4g1JXs2rIMnWrfg~nr7XDi%Es52x%-#ozM5OR4V+$C z#*Gn{StRftIGI3ka26R$F@T|U0%g)WIvVXB?c8rW547CHZ?{KpW4&)P*=WmU}jKlu`dJgfTZj#7n_8dKFm&MdaMNE|ytCvirG^OJES?T2|eZ%Bklb1HV zyL{NMLPIUVx02cS3q8tD6GKX8j(a6Y{2dx2XyjFuB?Wu|R=w)ZyHtrNe4^zR+zC;FstWM)+`yiS2gksNeUtJ+C=6Xj(@x>?_3bpE!| zs73qVV+}~L1&vb7(kn6`^#s4E#V zll`R{NtcXQ%NFq7e(r)UUXs_E?ym17gL?55ltmrnhG@h^{{U9yppD^@4JKHilw4^r z5d8r?%iNaNapv>9@7sOvA;CIZe&>SKBEEv;+Cel3_X`waHMX8byAqp_lAvf2UP@ay zufP8Qm}cC;cGl~qz{A%M)jKbFXLf$!>ngpC@*6$!%ORfHyNZ3GxG|l3p4(WOpNyF| z$Yxb*Fs+cu#10)~jkXgQhlopBOeJW^hsB_R{>Cz#XL^$yHHM&$#Moa|3cM8%q(z$vo&qyK`pq7U{Tc+bxsM+kb#3bhDoBISlZ{aE}|n z>Jb_;;bU!1MI{VW1a*9|?TkCV&$I5kn7i<|P|s~FH(PWt!4Q$4KUo#qi>H+)Q1A4p z(U=P&pQsDeUyvEj{oJ`fhnu6UXnH4Y^~Yg+kNC~GI;(GXwO4WDd#aCoZykxe_ckkL ze2k;nb2iMa>Q$t9#+q0+kavok1F=}#kC@=cE2?xx?r{_?op>~H)*pGfYAw1e#I;L_!mY?fxDow4!34^HD3}lJ0)VBkpbiw>{Gno+Pv!yDQ2C+s zP;TkiNpjL4#4(gCPU#$ukQXiWkqwH1K~vAZVW;kE+-E@a{$J$lq87CJt8#d296fxx z-k;)RkRO^|4H>#W@eR*XDkE7U5lQ}!cXCq&aHJ(fuG&yA@t3fFP5pxTd=Yxp;s@vD z!{`1^jrSo)*MO_72j+imeEwZ)Yy8HsIc~Z6!}DLTwtLiPHm+mjXKvGWM%c?^sxh>1 zK1YA$B?lpn`-!WL%FE=Wd9c}d&zBik?g?1gR!A3_C4+S4o?x_9=!kRvs zoVt7$5gG>zt!q$Mw0_yx?;M-$Pq!S!w%fG34E(jVt?j(T6CaBLv|c$uPXqox18=ir{i}J4(N>Dlpk?>(~3o4V%Yh zuyv2PGdKz?lrql@l=(`S5~3!Ksiid`%T8nFK1_z;Hc3?=2gG}321t^)GeJ@qM8s6k z);27xpnNjNG5b~R58f($y64P6+e~clrSQ}Q+waN=5w7D(B8OH>sFpb) zkhumy8$S+BaG4pi8O_nTYLjnHl-VuWnmLN$Lk>T|M@f#Ngi+x3<{pxso;c#iV(BO- zp^i1QI)P#X<}KTG<_Ye19pd0U+eeB~RaEd*0<;4>Nk2LO219#E?dKx&wnd0 z(9r?kf)xnuQ~Pw+G~jWbxPL8b?5!m)Z7n88A}X>uZNE-m3AWQQT9iqQ&!o*X?6dy> z3&-N4s{a5gF`z7ud;Z=1%KVaM8>QK@iu6sU)k@pOB>gsN#Ij3YhBOpnY6u#N<$B*L zU0hr4`^~kauMm>TEkZa1(l8HkSJXooqe_C*6<~cAt9bcTV4&=r7B(%Pq}0*o=9+rt zkmK^z^qHD!d9wH^D{5;iDe0)^XjUUm(8V$-T@5YB1O4T#W*p_WN^B#s@mBaFtAb~X z>ZtR`H9nSXBuiCYBDytH^l|UH!EMajRlDpZV3lRm?NXCX6p8wfYiD&xi$)ZoK;uxM zdXNEq-cnjQ)^>Ig$oTw(Z5WOejRvGyVWdcN zbE>1usUzD6?5{UVD-_$nmVXRKBRL)yhL0m12ew^cC{jo%LrRv!?Xi+ITYnKII~fj7 za#Zciie#y3)>NV1TP-VUXQ+aXsTv^`;n_8mvQ$&ekN*HEB0YY!il&*)uI_J|_R{Na z*mus3ZkEvqb_Q1vFNMynK-Lc|nBAU>N)W=#(u}^H$R^NCow*9o**rc10wqYiq zX>)I>n2lASn%#kD+8`W-2e>SeuyvV=j#iPWt6)l+s%o~zXX~f`03*oJ2o*noov1P~aGkY630Ek)oMJ z#ESkL?rNn#{>DH%0As|{6$dFmDs$&HHV5mvd^J8X>E@)|%UMge<&qXkbu_cXTxrcj ztCo(j>XB9{V`rwQMe){!kWxx!9$dS;Nyv2(TPu+yWRlQIX-y*_#8#l1lknty#u>4p0X~>r+|6s z-L|gtlA<^&1W-vsJ{r<3NN|4UhHI;|V$94Hg|w0GS+I0{hkbQDf+XX|5-0puQdY|0 z_TA)`q-F{q_q93sd3CZ+@^{8i)OD|S(bPPVK_>9o0(ltfhOD+5E3O|9ywXV!K*f}c zD}Z?;*uUHF)Yk+dcG*IYd3q~MN5~Z9}Y9xvr zf!KHMdbzZBg2vwTND7JOj4Pgn6swDhf;ga| zjv9E80T(h{$#J!A%;Ji+(yE2cJ4gT%$I8DUiU0s3f;;%{?pt%YmQBM8E6YH{#tMKH zKtx3)iXsg)W@1_0-M&uMLtK)QEp~Uc{)ba>fAx>KUN8i4f&3%<1F6P6QNwNl#RvEY zP=_nYzt{co_TdFiKQ5gh>jZG?wYQA_0I}ozY=7Q4_v&VyY>--q)O7O!18!x39;U0u zX+PjKlYebCE+GexcV4gRDES_a7S`YS{;l}m)ERA$l%>aJw@+sGB_83ABZ#NS(ALpn zFgqb|kup>(%Ofn=I)c6}Dr6`c`bcG0G*q=Aj*}Y`_J^RSHh$b_#Nq&!o?ob*}HRa;qkKV>RL#SQF{k%Q{>t#g)>K0NtTxzsUSxZ z!sHbT870jP8U~wF5FG&g>+VJrw*-*4$O;E74)AYXoaVCp60( zhM)MQM09xbQWi_VwUu%#YFq)SfHt`IcL3?98vg*Z)`I{E9C}S;s4Fp*l@xW*JuOu{ z(nCEwnoGqrO{Q3+(#)br+k!8__iPGK;B``RX~V84v6oY<5^et2{{XM~{{VRRN_S}< zW37OD2U`>W054n)M;-jDzE#!d_RS`LW%hS_ZEP(S9FogX7D4b3ZCX0&jl+tO+K#6g zO<$9OIw;TykJwXoBx#B=i%(@)!={J3%r;ur#;XQV;r%M+>Gt zB6JpCZoPis`0LTtGfRYe$YRWFO}{+V6;MMgjZBY5BASumjYpMT(qjJrkWaK%S29M9 z!ec-Qr~}hHN9^+S=~Nc*IU1qVq>oYZ9%GN6Mh~+-7W`%1-3QhA**a&ea$Ay*qjp|i zr+nnG`?kAt)>X+zPV}`X>!15^9Tv2vg+wV#w6LfMZE{;C;dc(;d>PuMl7fJYfNE+h zUpCE2;nLXb;COUAYD$*#JOMcL;f@&SSNR3ey;<8m@w6*@E3JC#wKDk5m)iKL>o>;Q zq~4I?>0c$5mKscTJ#d~` zl1wkeFOIu=9WLL?Q`1)BwjEaAqmG=SD>axDdY~2Ddy(>)80)iVq%iI z_i&=%dHH$_o|9X$v4py6EAu%%m91z`r%gW~zCHAhXi)T~Be*(Wt-G$DVD;)Q+C7c7 zY4;5lBA+0*%u~>9`AtPNd^BHSho;u7%@Huh)(kK09n8|3i-{wBF3Pn&d`TxD;=Df7 z(S$L^(P@-mNNBmB$DVS3o;qHCFaH4L>F}F7-JdEx}F?)ipJasg=41{YPMQm_E7%GV%a{2FWXZ=Qke zj2_h4{ps92m6NQ`H%9b^>g-r^omI3p9v*eseYd~%ChFh2GYJRrMHKk#bz~G2lc|~n zh_M7&W@8Wt!DXnDPSd2Fa*`Q}(TO#{CV*m|gx8HGn3a@j5yGT5dMyU3DzPXsD#uQu za7_sY{6Cgw#CpEQ{$2fb+xxp0gzhfG?tR@^y?3sAzWWoldomhI8X_v`D6{>0ZM)Wz zZh@8Z%_G52S54xcH9%QdLTS0icF(4c2$nLitJgp+RsxzyIKkotNzO1zOI9~?-AKjE zh4hUt;ekqqZonHk(kcK3o}i6=JJZ{fXH$Hq-aC-NmEBY{m^@uK_jZzlY;2u_*0`;Q zy5y$AZHyy|Yz`YQo2_#BY0N@dl9~eY5*p$AcM;gha?DGaU&MC!pGv5WLH>xY0Lu_s zrzGnBuXDEBM5?yh2~}E}J2=+tPjRINfLPFL(f~9CW2ZlvPfGSy_w0V@?B2rK-xE6b zt+yvx{9)M@oAY^L_8xO^Y)!4Sv7(oDcP$-!*~+TT_a9(aW@%T&JYt^+D3PPHOEaC_ zPMS;1x?Xu*f{L{O9knVct4Qu9v?7(D9Tdd`(gau(NT`4oBxIAC7a##rCE$k*cb#y2m6-o2Z@x0EyD#^m^4P_R$fJ+IOmgFA`GS5S6t9}QJa zTY^zZS&y&BrC}8dT$IsBnH4-l`hlVfuDrECBmqDHCar=oisWR4aU`yEqN~hx00>%Z zP)~8F8dPM8k(}3W@-F3@N{v&34S*pCEtPn(m&c=zhG~`7N$`Un`&A`&(vXpQd*% zM{v+}{(E)P&5nzF*L;H9wfO0&_l+EN6}xIN1tgecrGxKfm6p-quCMKknrYlkC<*`o zr72R)QY+>c0pt=DjKyv|FolUFK`clNNn=eQkf?z{8Tgp>WFH?sLT+98y7BvdwmGXY zd%ppV&um@TH!THz$=(}aVgCS(!MdQzoE;WIhHb@3P=gs2Ajo5KG=fRvsY0o$@u+_k zGp?lso;aliK4gLz@W&1{Ey(on^r59lJT((i4Jm*YgnHN0$k|fX?wr11#W=-dDdfp# zF(l;ixr|0vJx7BSkC3R@*t+b~R_Ab{L19%LG(vc7BuvW6%;mUn%0zXIg+@R)Y6^IP%@^89kZUv_O8R2C*MP=u zgveFJPno30P-3gGxtd8~rIxWV8QgAMM^#GlJ0$RsBw#)2DFU=ol^RQ60mhD2ynN|V z)n$yS@RiAW3jB%UzmXKE^7ZLG9`&QyyXUZSd%q{Jc9zM;ZvEAg&+iPiSND3KX5jY5 z)5c4l-MK9GR-!yb9Y$J}(QB$?nkZ>ug;=(|Uf*lDk~+u$jRTT?!q~v6;pLJ|0O_%B zD;h_aaFhegnoxhM?dw7R0QgjYOLiw^e3$B9l^aWJ=C`j?*ZeHlJA$`2voZM{&5qf) zO0C(sa(L{<=E*>bK}&?M#b#o!H8fP~3>5OmB;xGy`$xC9n)82=P|(jFqD44Di>H7m zNFOmn#5CpIV$u zo*ldr%p53k1r(BXB|+jbLB!B~wF9E)^-CkAxJHvt0>E$}dGW~r(;}mz(0`Fu`{>=} zv%3Q&^H1Vtc3qXb=reHa9hs_@Ti*e?*uFg3wv3xE=b(};?FoJ247(}Zj zM~)Itw(aDCIU$lL?j?*m(3DU(iqx0DT7zFdD)sLU) zYCtChkUG%!`L*o0_LuXl`JuPya@5kpMUD9X0Gi1>@~t&xT4z2w^~Gec!%A2z^)byG z6^$6_g+tqdpci_zZR&E}tur^ytQDw#-oMpeig}}Kmd9>>P)i3;IY@1Cpf9;e!wXmR;E_%VH1yC{ShdQI6JbhUN)Y*ba1RZw_gs;F3FiU{r` z-H^`mDUK;~rNI>n0n!T85t3*a*DP>)3vZEK&$wF8b#Ah%EP@bf0x1e*WKsz6BpO4w zCSMIHRfrH>_7+ESSA5NCikx;5T57|)Mqep`$k#0`B_ul!w#=83`X-t*&2-b8D48_tx>(dOnU=y6HR~ z6o@xPg7O>s zkL&p!^u$vmt@_ih!78ATSJFti)n`1bDI5`QJ<*2)=jYW(Bvf_t#s2_>Fi1b)#xUw` z6m$;Kb-jUBlXC7->VG%Z3BS|&dkI1apLIUBC;m9SB<7lvv1<5!jL=ty>Nog$s{OcD zPKN8)V|0|O?-rJknOD~)>#1ZmHr3<|MZUJN2l4J1<^fK3-(;m4unLcrx__(f>IJAr-»{au01sm> zSCVU{xObp}IW#3W&UufZqc<`}1fm;g`>Ey5<;D6Zr z6F?X01Aj(`qsSp)C}G1Oo|5%-4<2V1BqdeSvV{m_SB(Dvl*M(HHU(Zb91uac_H(r; zP?X`QpWD&BhNXerE_D(sn&-@YzFvJ_p2Egvw=NTG;jolb*Hut$2=Y@^&~66VG<$b# z$M!L94E|?!jE*XN9swt;r%Hny(o{_Hq;OMC$H(s&Hl4SacYbT#zj0n0S*@p*MxRkp z5|?HCAhR=Y2%wWfZ~;AiA9MczJo`iKpRpX7x%<7dN4o5Lrrlv{9@-&Wi8l$B*(6ks zCuK!gRdu}1$gv6%b55!k=awrwi0_KQoWkWXgEiOtJ2{EU_i0bb1 zl}x=Q_p*6mjlMtPD=E!mElW#8dd`t)>a~L6Ws)m0+?%f-QSEj`?w?zLNBiAr{z`QO zhy5aS&;)9JK;V77YjL~SjHyOOLLi`BCrXPgBp}<=!=J71&Hn%%#|uFEytDougGQWu z=sLbH<$1Jld;8&^d+hDVl2mQ2-QAmmYwk)K3i#-NUy z(FK*^kRfv%fpXW_8*5$9l)2k$y8-PcyF`{S%&cRQ0=>leQPZkCz_!y4p${wj!qxa243R zy#+2u9hJaIj{Xru*&h>34B24#T{Q(u<@{=M^>XNDFsLcNFY!u!}Jcu!tc$$ z*wj1Ezv{EQOCOWKZ9TcTJGVET>rJ)S*>_3uJxhS=y1a45V|slI6viFCCTeKpqoy}L z6}WmnQP?5fEqBhPbRw6Wce|aM_m}0g z+Sh8ibe2+ zeV!8H<{O0+ajp0YSC|@%}T-%Bw9x*ylSW&{<`y2wwHFRcNz<;Iqhy9IF>nY zVVW?E_p&L~b#oeqFkH#{u$d)fHI_p8sQM#lre-XjV}1OD?1~tw>nlfJ_V0Y|9?9wH z9;T*zg);vDqa5BgJRqgpIce6j4w}#K`l@)PypD?g)j`XfL=0xra%(e6W0L0LTXQp( zCC#j|yc(*+r|JHgp^r&bqA9u0dY0CEOMSa$vmY(helG7DGoI(v{oN;h z{`t0V+;;l6b8z z$}OIh@EIYFY0WQI_G{HW6+6hY)KgHcTwieUqbw$(AtNc314Ms#0+I4%f|@HyeH91s zX%ZIuN`eWe3X0(Mkl%He@i~i{NK(OV6c(lwms$dU4xkAG%qc!cs(R?;lB46#Y8c}) z{hxVtEk$XkkUQfksjQLDYk~|+dHD3oi`U;_NLLtc0X3;vUD2G2Xo~5`#$ft>i2%y^2#xJ zIU;JR1gM!}V6wO%&Rpj0{{WQcx|?Oa(36GnBXtr)<~I);G*47AM!*z$YCu^*((DZB z&R*a0=RCo;F7UT7UfQ`aT-r?bw{eE2i4xq!NkkISOt6Ls?5M;RMIm)b@~5_9-&sxJ zQo9o|g3aS7uyx%Vxi&U8Kk=7j$)T|pLLq?9j1swBo7)jt3-mS8MY(B(2x4aDce8m3P?%lqF-luCSF{y z<=E}6Ae!0BrTjBATc?Qr7mp#oKqqM~QW)a6V#Lc7aid~5^!t8%sO}B_0NGmyxF)OF zdmFO);};eaZ|^Rq**Lzo%T?m(pg6ire(9e8W0P~x(d~2m3Mgtxh+qq2ikf4i-S_T) z=AL8R_Pyr%@;LWvDD*`v5l0Jz6bgjKtEmx2ltbDSu%~-f&R_P2lKFR+x9(Aj+Uoa~ z_c?r7V7-~HQDnmxfJspcnSaI$pbhmPP6&`{={pa6_GKq#P1WyVzWEOY=+rq_|4g((pbdX-!wo1A%$UHV>R{o>2HIUt2qSbR1l zwYY!*2(@aE*1KcoS!X`dk~=b#E+}`keWsR0MrEy_4TZV=u!2P z_(@)xJ43ST`)hGycScWQ^$x?W#%(7+x65mwY7DyR^~9fczv!Nu`L_zn93YH$)i)whsb*2Ls z*l~7F+}xeFv+E(KugFK%J1?~N2GjWXGP#Oc=rh^sj+MbJ9^I_m8>YJ@Hb*Novb1>& zi<+sTGPI2MlVjVYyBmwgD&F{_LQ+|yNhAWEB#=iU+sPpWhIfgX{wFNsS4_V%U)}95 zvESKk_g1WmrfKbCmh>tzv}m`FS%O3n5;d=6Y9mq*01~+_joR6q{eFKp*#7_|vXr@; z-ClDo)m7d5x~e)8El*!t6uEt+lj(VA-)U8K-ex$AHJBMSQdCnrM90Hu#V$E(W4n^> zON#=}EQ=(E#hXNonsjP_OW-;#kPK}Rjq)8BGgQJZaNaHK;k1g&YDQQDNpQ9>t@0|V zRdv3nj<*U4D=<3Loj~jE>DNEhn^!ZP$L<_v=XzrznC9jH*ODHb_I~S3}WPY=>-`X=4 zTyEX5hu_%RoPOp>1IbqgcNMuX^Clm6Y~9mGB#%SAHU{I4DyrR~z40kL@zdm~Lexi1 zQ#>~?&niCet*!ScE-f!2@h#=3WioU7gZL}*+KUT{+gn?1QFL6mtX3-(O^?9gXe6lY zJ(n#GFB6VKO-D^rkgk=?bnvN`re|kGXD#d%?nl$wdwtE2lBo!?kSgI+7At@N3*5)^ zVtmbdl)a8?yU%ucTH-@A^9Gd3BWjVU^wSMeK3bHZEY#o^&~-_l$>7x1{{S#vr~7ni zp%fduRe2}zg@SBUi&0eXaLyx(Rgh{j8!fJGIql2@9isPD2WRuB1N~p0T^_Wcy0+9m z(FgPEdVh%wN6t={fWVQ%PeHt@R;Noz1I{)s;z;30Z6}tkqJ3z`NQjMB2HwGY0V{gs z9?-v^5&oijINS$pO4QU}&*U3DQdiE3SnGaVe6o>df(rV7k^Sin9aT!ELY?ES-+Ab3 z@tKNpvO}8NnPmOC>Q=hQgp{*@ec{hFUNx_{JnCxR0o~^`28^X#fh1?}%BL!S+PBN; zciIh-4d?Fj>`g>#dc2XfMy}`@HjV6J)o*bb2gJ6QgP|2#>rU#1s?*oIr)lpTj$f=W z^bLuY8X6wO*je26Gat8h{yQ~1pJz*#&S$cC`f0WaS66q{_U^4t=j z$>FNR9!G&iTElSyurbjgVp%3Oy@S_1!PeV$mmk|5UA#6tTZ^wSyXR@<_ca|3LJY>u z-xSr$v+D9&vutEDyFWJ`UFhb5gC$2>Bz3+Y6+nitgqSVOe5br@meO6^?ZP{CiCv6j zJbGk0QbcfZ8GgczrQvd_z$+o@efC4%&PVq;eXd?!=BC^=-n=n9sLwibCl6>_=|NSs(Ko&SPpat3&(?bo{~1J#A5(ByP_%Y^ptszVr|T`>OL9ks4N$oc86@P@vEf2sG7IB$X7%01rOC zT|WNqw;aJ0(70Q8ZN-$jv}p{W{!y}Js)=lLXvB0K_-yoo5D$6eC#oVjS;dDX_JR-dA)pkJPF^=F5sO%ME2h%#B->3s>hVPl#EmqzFzSk52q1YU%!Z&aQK->| zojUb#9Wl!S@p*%EOK++$$!%>I@Ec2bjV$46)f53tgoD~tomlGGK2hT2m$osrFy<oue{GRH2NmL@J_kQ7-&4_NCX{6PI_tJ#$l?X zFv~|#1XTqp%|$t-ru(T8C6TITA7w063P02lAT7cp0q#)QE-fCy!s7l3qgdcC8B?W! zccCxlaZ(dW;&l)J>G)=YZnWIIZAbz>rwl1a05J}GPOp%w3Xaflv+2yzCi$VLsw|i1-^t3ceBK^Ty7IzO!F|eEJ_d^=nu(-zIGgZ&;+t#GfW+SuZ$RhGgU zs=U8bZ*0|FM7W*X3XzlmSlC>;s8j|Riv=FnaGCX zpNiVxp-E%xF2lr)#lmQnCzO&YS0M&zR}U<7rl%oKOHBqsI_i{w)-GEX@R3bOv%wC zzKlU2LS$6|!(&&7gkeb(B!EJEV^vv2UwrAS$DM(Spvh5FPnpqO{c1f08@P} zac4S$lRt9UDFIRlkJHXS_76?%#OQTX`gEtwPm%i%K(57&Uwu_a#F4?VH|ptM3!OH?xXcnDL{qaMN{c z)HOA+_IBUJJR9N+ofcY;c;F$1v^Vird1`WRRNE|;o+L!=OrgrD8d?SvCLl;bMHCg_ zQ%UX}W)K$F5lHq(jwrF|0-8b!g`gd$;UHiYAk>D`YLEFJPu-nS(qGMU;x}Stu-n6_ zJ~372GhH#9*}K~x+5KBXQ`=or+Ig+bFH&!eH2(m=vmJHVTWb%5-Lx>#ifCezvPzbw zf~vNu9x>;r?cZd-y0!(PbeTk)H3bA`%Blj5K$?OmNT)zO(*bDNIm-`!UoTSx?vK ze-<2ny!&%JdV4zlRO`$782Cc~ALjM3S-NCez`AB89^tpwPHC6Kp zxA=}af}1L^>nxK(2P(_aSHcxs>9jOX`7Y|yu^T?;l zy(qJ)wZ&Wx-`Soc*XQ!+-+XfF?#J7(Z!P)#;KX9O!n>+68-H+hzI;{gUEP`O!@O!U zuiW?m1wi`0Jh_U88MaM+%7&i-HaN{xhMX5#c7GK_DX;uEEokJDM`)m+?V$wMI+~>8 z%w$jwm0N3h=nVh{r`4;2!+=@hCO73*#}CwY{v8O(clzBglbO zaYm?TVtCgS9#rzLOHr-@+bmji9Yu-br#e)50p?E8$RJ~5fZOZu8uiH>|b7G)uvr(;OLJHVCk!X!WlwepD@)0yw&c#HsTmTq? zLV#30k&#^?se%L2pnyk6p=kiLDyLV5O%63=&=Xv(X;LU@z=NKR&rV_YQ+9VswRUR@ zHt)xE6sNMA4*6OgtCH*qy5j|o>}fWpI;~cxHP`9CC&*8SgDO7en;ew0F*T8oWwMyj zZ%w|x4MEadjSGqv0N|0DW}dw)9xZLmfNLx@1>g-B(0!N{`B#TZeZiCL2{%qTJ5z4# z%tn6)+#8Nvp_=QAu2(UH+&fbrimNz1z_acuYFfGpGMK85@|ddOf=FgwBTElyHspnF zcG=;Xn&etZuBsDDoH!Xhzrboq2gs5FyVCO7-ACZ~aqB?6+N(o@fIiw&96F+Izu0*! zuYGK~Y?fEFGTmL8?7x(oo4xUPs+NksY1T=L$xqPv9;V1=YU*%%iy4&PRdma{lC2VX zv4To^Ker_&K@GGlwlO$5WLsfM){OZAg9eqQbHi0?Kphp{$^J6xL?KIoU&lZzRwAHk z$O4$4;n9Sr+BoIRbdD!;#X=2dbaf6Yz4BPevT;=T_vRPwDCx1wGX2t3R6?-4epG0Y zgNG$gyV>{O*&5gNRF9b%1O1-8B_p@GDllSykrh*s^8-C?Q62|8yHh`u!EMY|OFK!0 z%T?oX`HYEV$e7Hs)l#)Y;nCoDS&oozAr|8P?$XDhyhZ^D163+Q`I>x(MF9pX4LrvW z+2z%9ZcKF58Cp1ME2yiej@qWmVx*>(YT(AhU0pP9gQLkp8LA$VYI5!#_l?4iM+G+k zmyy>rU@K29HK#{*_3-0I6l#!sj}AYd4vshS@y1IpYkbhIsGlP8oxSmk86&=xqiEsA z_C-=H0gj=hsGbQY(&9)^!x>T}lgLss+m$O|%z)J09Q?#;5A6Q{R(e?z6LD?{?C_eO z?_5vp=w$hkura&lm#wHb6ghf)Mi;vJ<9Sf$@ENg&%;WR>QhNNBEkuPRk0V8pVD$AA zu8tl#H36*^l#gq-AHR0#?h>XkBMvz_2nuwNN}WWoI3Q5q)1zCvhmULAqqlk&i$h=$ zp@6q94Ro7Jx1k|Gx9b`arE#QX`sa9;p@?~Q&t9fTU>XYA0;fc2_+G20T`}#YFPbS0IgKU=+6}*^f9I zh-0{s6f;Jtiqp4B=Ayp{HK)thr28C^z4Srk3X(Gl(zGO>EP3P0qFa*O-GRCG56N6s z=-ZQZ^jottzi`wWFLTpTWOI;hc{-yfLb(jOV&?H>C#kEMnmCXv{?TOw6(lWT5Phv- z`hhI1B+N8$6)F%4;-fV^2(P41-j=SAm54)(UjF_e?H zdaL<@d}!=iEbe=ELAtur6RKHGdYmccnVlseWX9yQbguSpJpVnNGp$tmQ{%^&i4&JS`qKvUmL0 zx$xa0=Uk)`=wZUAcIB)aneZjZr2L-gY76WNk?cI;JFd2;2-P=2>wD%M#j7n<8js$vYMv8o`O!K@VN;C+MJhDTk zM^H^oLw6`uMGQhH6*Q~*yEy+Q`3~N?NSMakTS+3|=~^9_XNz2T~aeDR}fZ zh}hr&@mLCcfF7r!ScG(o!);69CQS(^MN1RwpU;m^J3t5SD%i}G4NN;PvkD5iJldw4 z8I4++DBxJYf{BQCjhUD?={C6cXxVMtg)H{1%?rzfDeLd9w0KoPh&D%K4&tmSaqt_cF1^4x}(CvyW#zS({QDE_VS*j^z zT3D7vrk+T?(llw_IN1{1p}AsiDLcruClzf0i9VzNNk6yCrPA0mz$A9;(J7FC2BJ_g zr~}jG*FK*9U?0k#y0Ud0Z`U6odS|^dI~oc-&620tJ4Z9Rdc$T-g0IS^4A4~I_O@57 zHl;>4Cr@2I3XSVqBt(xjT#A)NNOPU<_GXYatPznWB@cv;x7NG0?^UUqs{`}12n-`g>UFU`Bz3DDD zFP*H~Kf&Hw44yk|!6Xsws41v1=Bp(gG_FF&1eGfbnC|n&=^Q}|mO5!rDj1J8B7&xd zwDki$Ry%J7SfzJLAqA;c6%9=_0I6e2;FSQ4L~sUsDcHMXqP9F0c?@{VZw1=eEKWCO z;OpX_E4i~cU9$w#SPi)yNQ$3BP{A~_R7ml`8m6XhN4GBS96MTDsx{G(^s5q!hVE$` zE0jbTCqoc0s?0)=R_(Y&wKUf@u!;A(n1F@?;S7Z;KvP3N0~U~g#)Gw3kf-Mx{KfZv zpU({1QJ|SvOD-Vjt^j}_4ZLBpMwXSMwe}wJv3^f%xVp^KP zG^rG5>Yy-f9?mV&(o5I4l`dswk%cugv27}~C1Q+HD3q3A8YZGmdW`qWo2&SC%Ztgw zT?jR`29>L`F$yw5AR!jIn1uzIn37D-@``BT{$-yOb;uSr?5deh7Sl8BEyYb4X)UhK z@(Ar~9enZ6z3pG_WK|}#YJS7f5oK-5l!M?d=Wc8EF+P8=pPyexI#i7LY6LJxJn}G_ zNL6)8u)CxNSptTTtXBH{E^X{XZrb5S(iXWOdhkEs{#|5RkVRIMua{IC{NOhB-Nbye z{#4zU)pO!;{{SzmzEIV5-90WESZMd=^!TJY{{VaLPT`L$4K(zXx$Tp%H$cL?PgnOe z*ovLQQXoj*B~s4po)g17Gk{T}Vgd6YsO|ocByi0tX+U}j^Z9#zQn=hy$R>{N-5@Bs ziMWx7MFxbeQC*7-BeWwwdZdR-uhuC3TjfMhB@A*@?!vUxt!O=4PK=WG)#OP6>T7*m z1NgVF-o#BV1D^d-41Axa`FYi@HAaf4(>(z63VnS3eIG4G@uIH^7;C-BVn&b`l0o); zT#@O}->jhN1co3l0e+w2-%s)Ud*566`Sp!XunwyNO~YI%U~T~e>3jbGt?%4A_Zn2= ztbme71;5oJ1FGsR!2bYJN9W(V_A%H0(%bSj(C&C{11N3}(!^^VAFs6jfONBls^_e- z-$DWvk=7|Ssj&gQBmh58)8427rF!uct$e!Z8zzNfEabX=2)=>O(A)ezzUtnz$?L-( zZ&DT$qGjVuS18TNACd>s!~NslnBt`I>ZX((eC@yCORTN@$MM8-ujB5=GJnCpynCq` zLHcPLcmwh5B>+Ay=xc*?-<1(7`FeDhnZOUT1CVV00B7nof7$AFQ!Fe`7vQdc%4O zQZaJjY32x1k^H|Q(f-EKv`yg(cel!%Kf};LP{31#{>w29X0f_}e!t+~?fr^jAE{7# zwDf-wN|y8KB`9;Ap#T>D0CJQTQ)Oa4;sT=Wz&7@Mw@`>_>0k5oXKus5Qkepuw!A-Y zSDCW1U5~Lh7eRNgO7E=4TK7jvRO9z|TyE@iTYo1{M^{rsw6))Vw|9;Ya_t=K>q@`m z$&#R{ro4`>6cFC=!cIptsPm_vUH$i`?&rFF z;ytVOUJZ|!?QAc$eVrtUE|yk;X1TVusFT6(M*SrS!{DoA0(!3B<{#Vp(|-1D+t}Ik znu~6AuGz_C_SPz5|dk!Ha zQb`ny8PaAXqBo%ZJ*WVi=!oEFU-)z#f0gtZV-Ofl1c~+(#?_06ZeReLk!HFRpNZIBtwa zmfsz_qxU1yLv~+YNUHw;kJ^2lgGG(LpsnxkP4|zL<681E_=Eml=s$0RU$?8r_f>Hw zrS}MxHU9vJBahkjRO>o_ISz@B&^|hMLprM<2eZ2LE`kUHN!hM0r2R)f;yt$i0C?G) z5BUTrY7h9A=UnH&;pzPP*!!%=gp~Ibt_c4Ca0d!g{!;N@KiStAKb(g_s*e}PPUvkj zB#uAQUciPqY?fkE`=3)JY_7x*8J181^!+{C{s{SksT_`_sB2rk9+dqI=hRo{(`W9Y zJHmU2z)&Ce1W=zk{{W3+94Y7W>o5E~zeLC(if@j+;MC9;@gVJ;g5D(3?h-iPV;Imh z)+|Thk_Eu`wEM;dXLHDlR^mm-smBxgInVOykM~rWkyQJT)LtLrI3BqAuRr#BsUMc# zFuNP&&i??#ZjH}LNwc@n2UQRXc}xZhDM-66G@W z5v=uo2w+u;lA4y92uGax+kNMq%x+t}iV`uVC}XIGCE|1fNi4@M?N)3G=~V+IxgU{v zcia7+_dhRNxQ*XjvPeTsGw=-~g;7Nvv7k_>DrjBgcL+MCw{zW7pULFuC~>==Zf>kh z+jFq?7U4Bt-L3n!sw$zcIP9m{O;1^m$>Q>~@Z>Q$I#-Uf6_lrnrWVwNSQ#v8@yQ#; ztd50QSXEdbCLUt6Wg>-G2U4u6z;|PPeYRfOZhKwimivqj86-nOC_ySm21f%+qg7o= z1axX)?k|UPs? z06JsSu4lJ?9fC>4e7Eti(uCxCA>|epCP@DPhAx{u^xyRl&*$4Cl(|UB9;Dq2LHoa2 z07_KQDey>Er2##{wQ3KCr^mk@<&-M>X2MN>-*-6w0IL3+KW|+xZu~m6&NJn~xUzv) z(Lh++hP??kYh3>TPi`kE@^Os#kZ$Gbv?Ai%0xEUj+mf{u(~<^B2Zvg3etpWUdN#d? z=en`n@E)J7pP4;LgSWmLiGXZp%gEz)jUCpnp=WeL>*Zk#lu)F_Marpo!yXF{ueaNj z`3TE!Qp0=tdj6RD+igI4JAD-!%OO|n>i+=i^X@%Sj?c02?(Mqa@;*2CM@9btxcja? z!-E~PHfGza>%ODGRpav%8!o4CO}O&=qj=I{CB;Ua&Bt0XO81UMCZLDXxWq>;MRRLdG(6dUv$`v)1{BNbEe+k z3dv@YNC2jg?z6_SA2Px?!6cB1J9?l001rjbl@eCV2gY9VS~w23N9~@lGDi%gMNaZD z*%5iAxwEWbDf-xZb$;<7Q7Or6TzQ+JpUc9>ubntl@#!J^sNCr!dxpBP{{RpuKkX{D z{#|mR{&PJSTU82Ed|&Tss*0K7q>7pj)$4iQqI!oAQBuPg*&;=%s+pBkjYm<^6|Ozq z{_#b{7n0Zy`RZJM)f|u6)1&UEDw$9E;DbSm*zx}WP5w2H%DMS<-GB3u>3TZanrx57 z&icny(9cs#TR~UZ{dOv-t0`o7XQQl+qh!HR4MjBQV|0;LNLUmqNIuwKyi~zJ{-pz2 zXX?DX&-OSp;q&R?_f#%epKzL$JS>36l}FWA?WbHv^OorMD97VZdInl|^$yhQ5XIzS zsA>M_sAch+So*jeSo_iY#K0GI~v`Av(V*t=V6Pt@HJh^wd14UHz^r`&t1u(vc)&X`Tr+PjAzM~tGZn{CrI zu{cUvbjM=nl1i)3Qy`Th&V2VDeCK&#f>aipEM%3pMl1_p>XrLMj6V-(Rlx&QNt%7I z_KTPOwOiY}NuKk6x`|R-sT3=CYE`@_W2*>bF1{lG%+A!-?5i5a@%)+DWd2~iT@=wr zIXE5fSrW;p{{WQG;mvo7IabD!aTGEYb_EFq4a<*k=P}f6H`MeW%=Ix@f4P>Tf~Efe z$;a*V>w5nHhyqzYarHGlJz`SH{nG3iVlrxBP+w!^;i;rP635njG^FUNcyD0c zga*8ja5_JhrN_vhFY|PDe?qX6#JR`&R;M3B$K_u-bx0pIV1}FJx61l@bw!3Bl0DTF zOHT^Zz+#KAv%nZ2QKA_Br%3u9J>iEty?O7P)O-uNTz|*OKhLkHUt%@Cus+5IZ`E#1 z*^5-v*XUv5e9zCKM@gIQ?x^jpv)-LQnK*sZw=sDNY$kN6(xJj=;;cDtOg?dHz&Z=T@V$Pycab#HNNG186ty|UZt z48=r>PXK6lA8YoW5Tr-!R;=Y=?OL_@922x^RaGT&d6hXFSz%P*X_E_>YEjx z$nDH+UR$>|44GUu4uXRpkEf-s62mq{q5Gvj=Y9U)nYj~o`U0bCiW4MX5MUncM&;Ci zJK8;ANLqtZ7>e`?`>T5~yZbTj{@Z2F7b_<{?pNAxLKSOR%547tTWbZQit1>s?!Ei@7oj#QD~yu5}Fx{mpEZxTy%yzjRo%;#emtm1! z*~aztp~Skuh(OVRAywiV#;m48T8bcUBd&LEGjgTg%M|-X#r=;mETGG2a6D^iA`3}m zwz-W~hg(Ksigi~gBq;2d36JHiNfk~LuxiaLSy-g(ZoQ$T)mF5g3W}<1kg1|dNg5Mh zS5p8*rw<}S8!1;hB;rfuHGyv@j$3%l=Kla~Ro5U;b;~dz6yceO8DbS^15`Ib?pJ_K zyKeJ~Ep#?1Qu;w@C7e-Kqf@w2sZs*4qZ&6>>GG{I^c~4VH9UKB10_M+74$7=3P+Bi z+?9~|cYZ3GMy5G>in!bCBXi{uLQpY?1|ZM8t+a=pHQz;Q>o~YzVhFP6HzJsSJ>9sC^mwzN^&Tf|b~&{HZSoBK=1)almGi)A@c8z^l8y#o}pVrZyk zSdynLGt|`0n53+a?kREc)QE#m9VeEa3YzMrxiZ99t0D@9N`DrtWu694X3$5Dz5A+Ql_A&@k+&_vFq9@+)6eo zu3W|{7$u}><$;o`GKQp@Nh;x-B-Az1(|{Rd3W9W34X7%zvi=mw1c-j2yOlvSQWO?r zLqZhfe7Y@=t;M{pw_O{JxkDzZP|P)UmsbI!a=1Ex0f05FD-NFu`T9D1Vqu#+^I+?t zlNT*ac$$$qnOn*#T>ZS26borW1l2PiPz8trJC&MAHb|0CBS^!ufn9YcP$s_z4g$ZP zI%{m(WZo7l2sZDlne8PD8@Pn4W{g;nrIX^*#m^j)Iu*JmuNj5jFFdr>vE!niIO*R) zOAxD*9Z^m8d4D0NsHLKLl%+{-X^Sq z0A>Q9*GVRo24wc8Sa$8^KNd2u29AsX)8cq+g=7SRvAWe6K&d)wM5*aDwDK96eZSWb z(XKsv139$vbo)CiGs9oA`>(8*Av78Oz272PqNc0e+dn5u3p9o(GFe@-_p+&{$i)@rV;~FnQPe=eD_yH%xv{e5 z&9GkD@@iZqvm>)ldCM1au`xw_+E#gX=a7>H>c)>T4-iG%BbEs~VSw%T+ntP)F2`1hY{!rG*OVn+IHFc;u;&IV0@JOEhGFblLv^vfkwF zjbtks*QQPt{x!i1_Wb%Ju~yb}wG@I6p%mah&(Jlu3>4ez&S)m9s*7lELncm$@9lnrg78ULi=wc^ft&*en%dM1Y7bC zwxp=JgwwW%s;DM!_Prcht-VW~_^I*cI*;O%NkzDRL**t~0QqV66oS8C)6qjmNdz*c zJ+Yz*%hSrqEmi!Ht17c1n~iN9xQ%MUGf&P#$JV$5)AQ;0nw3^!BQ6QYqVXTM=lr^8 z>P@AOtLi@H#YML3Uw34&blC-~%2efOjW*rK z>Zlr~fRFg2{>R(U8NBxOHs8+VsIj#MyBQ8kDNjRGCWfirl8+@-M@(mym)KA9Iq5M>mzhD}a(}1$Z}t7@YFN`9RYguXb+r%j-q_R`59NP~ zYC4*%&3@(iVYo6?+isg~VXEsJCxFM{vD7%I>#^}oo5^6_gvDIYS1sYHI-&ixBi$~h zb$zZSZ-hDd)RrHY`#n8x9R=L4K!qt&=a5LR4OsNyj;z0J&n-_;ZfBnjk*F~3J?Az* z?`r3cT1=)t6J0e!*FxnY!I|D49AZTC%6%#qk7f6ew5c3rhMZ^RT>Yoz()(G0xg;MD zupc8_bTnm;kE(Y2WAOPAB__t{ia2q&siti;(c(72rlX`8KI%z5`# zib$^{2AV#ljebC!^rysGA_BQcyz`TapYrr0(d|hf?Owp#G2uK|?ZaDxt)C#18d_TX zoHP`avk9K8G%Ya^n69S9tXAg!-YQzwBsC}?5|2vN_{((qUs>y`UaoRjXF|yZd)lyxi+Fv!X%ozGrFlKrmK>e z(z3~jQ%@{}>e7)+Yy{{Rp2>HCI9v~pUskumw2{{SwE zH)hjSY{{@&c2uaMsVkhTS+G!KYoLOvsu3)!ElX381vJxYD;oe?n^=21k(J27Z7WZg z9DkRhpg?sv1)9ED{{U4*dIk3O+BrS<@!Z#8a#@^Yz3Vck^q?^!6Bv>qh&?73yt6C`}`x)Sjf{zN$Y|)WpZ|Utm1^?G-7bNz=L@&K!7Td^uM|~ zsY4ZZ_m9KwqkVJd>eo`zwn1o|W1*tEkJGp9q?Icai>6 z!=WGLPI^p6Hx*k3Ei;u=`_B^i`guYKAjn5aT-0;TGKMs(O+To)yNmio`1Tyz8c8>3 z0va}nGJn$ge7uK8m!Vf}y(a*wjCtpW=j-`-^{0>X%cG&lZT|q}{g|w-%}KnsZs_?V zi`Oc!jj?++oV4xpAKDXfbfsJf0!_SQvzr3Z$wHL?Erib{A3QV;58*D5a z41y&@am=q=50%3zknVUNPiuLqNklu95tdC_Y3V`*KFSJoOK1m+2sEal{LfXh+*SA= z^u68G43bBeil&S~Nm4@7Jv^O3Q$9+nh6Z?Lqk3hSJ4hbVNPRXW`v>x!PR|(8-}M&) zzac09AI`MsWy}ccb7=a(9s(bct74>J;~hBSuvF)_wr);(nzr08@tdX1Hs(mEXtx!9 zJpTZAO%#+_m8DABTqZeC#I$TwikFf?8sveQmQ(x0l~PU5ai%ge(^KLqV1**xm9+0QM3afC9=1;dOHm5X5w@!U ztN^gF_S;WJuZEcv9fPO5AwpJ1s5CjJPdj^J{{RJxHB}Dn?0TAvg0$7ACBL${e<-Pz zSEa{MA<;<=8xkrc`&x8}G$D=Td;4jnYH2XXN{$LVyvgHVF16t4V0=fQ`Qz-RI$B{i zWg^naG+W2AmZq5?ppE6m3s(xK^$VO~H;V4_ywT!HS!W*IOay*ut`}=5XQ58yfVv7D$yon zJQ=k+mM7f=tU`(azI4TCYyNt5?*&wmsG1)?Q_)fEZ{_#UoyGD8V0?z`UXQp+uM70?P#)exGwKbyPBX?Z9JxCqAHEKT?5Zdu+~c@ zT3)}yt`DPVI#q=L#opwy*Jax>Sv$B2#M_!1B$i5#LzqfJBUG$DwoMpgp2 z9$gvjx3{+r*x4KN9lJAC`<0^0ZfdQ+n8;+CBVSdv+`9>lOM{N>fpPu6sHUT2bE9dTn~^PCw8L5z0WV1)9(|qJ1i>0 zUY5|4%R8vo{A&;lWnk1<*Mv>D@ z@+OvN)}XU#MSK1Bt%&a8(mg9_3m>!NAbRoW^LQp5w`T1huN}i5v2IyM%DD2#r&KS~ zyOVEFe=o0=_}F(6;dk_ZBR(nQa9Heia<>hfn{LTP*m&%QN}7_2N@**xIQb%I>l7P{EQKa0nrLW#KJFhcPw;f6 z{#{aT+=tDNjnHLs`sHLZE^HG?JvXgA={mUjzvbZM9&pU`38^X0I0d^YG z$r`t}t&$ouX;SK%xKqqi%a8eoOvyClGJQmv8;^0JuNvnd`SI)OTiQEEJGwi&dqqRo zF=00KUc}qDlzQx~RJ1sXPwuuZI_#oUe-Ej~ZM-f@o`3ftkfo7imKOCE7Ep6)uvYG4 zY{j1C%V`;47yzdrkP6fxz%?|fJwyD=m#x3g9j@&Z5Xoa25bS$TdDbedu#GLHrV{LFUUB`5QB`E^H%-8(wAhLVG%=U2n$C6O{I4@7nK1lVPUvWk{*xv3?kGE`7$ z1~`hy9hBeLBIvKwa|7nTQuG8+jvPnJfg>K3=&yf;VS`X%3@iM5$h8FC};qt193N>ES+*HU6ATiZC&Evhj0lb8bH};!rE%i_p zH6%Cep|A4(Rp>CnMcny8fixSfxb>hdPuOdxb#y_>t}@wk1! zpC2|3X9I)7;JV*()9qSRuCKwiR(zXL>#fMt5prH{ZWuIDLo8*obz-^rK?JUz+RzeC zom@JOcl&Frox<7oIYiG8>>5OIp&G`h;}~bq%(~dgDGJT3E&{)2$M%0O9vWz5FttwT z*3~sWX$(^AnCcd(7!TY@7%qhR1Z!UEeY3LEJ>t`}NiW(v{{YMW1JTDVs-)3IqqoI= zIX?w!`Qn4qqu@bKd0~uG5q`YTRn4xHnzT?thO#m`jSeh`dEHF`>zVr(Dnb*+v`X! zbek@cZViF_HLuCI{C!Wf$A`@Hu=f()ePz&5PPHK}H2`^Q*lADg4nCImy63HVb=cM8 zH&NnOKe>KS7AQ^lAe;XHQ|_dimGkoJ-nr^p77nW3q+()E$EAllzaOU7{-fOr`H}u# zv~^lkP>lZotNHcwvHt*tETa$ROG=}iJp-`OLtHYCI^x;4FvyeY&iS5;}Z->q@fTI!IG}OEifJxe-Ua9w`AWV{hCi z(WsUHdxUq=8=m=&5I19?$l$ zbVg5;bZuj(+ejL;ulaw~POnQ3SeV_7g2JhYhzWYJy{qK8lW_lM_!AxU6h$?>%h} zE!4m&q_fpJG`0%Bd&)m-Ez;YQHptQth-Q_CcD5m$uy-^7GuKg3gaj{_Tx9#^ZxY@Wh#-;XjP?8swJ^Lx!bE}Ypj?{{e?G+#A#KTYntzNa{EPL8j-pv*Dr1_IGM!@#iCo*%;iTRYQlQq{Bs7L07r=hUA`#Xz`esCyD9=GS4iK($mz` zLnC{A$QzeG?sD1M&ERdY0B4wh+5=ZgqH0}oJq-q+s-Uwlz%lo@zT#}2-0XvO-9t-t zGZeSCTs-n91(i(*R6s*ZBVj=bHAwNJ+nD}O9~~8A3*P+MxaS^&`Qtd&e)T)qG)_vktub4M{e*a9 z%dX=7PX7QM-sWES@5q^Mn*RW~y>T+hAo{8ilwANRxg`BK_Vaz-IXpN)yY89}Y2(9D z^RLooxEw#&r~DN=^BSik+X$*@TZXUlj+Gp1!kEG8VE#>C9Lu%)+rL-kW|}_?($&O?;+q zADa1jpFd8!Pvq6{#zFgi?cZ__T7WjUTE=AY{{Wn~`E;5>u+mArk35feA9tQj6i3~6 zYSd@PgbeT>?jiel{JNt3>UZ(0UnSZfKqhg+jcT4>mt5ERGkj`iHt$c6Palzxvh9Ag zQlX=?ZK11lHi?bTs0UGDq?`M3KJL7jboiT|>%%m-hbPp3iQs&*_R#du`_^+3sIMkj zmamkrPoEXzPd=(A=3m1e!1!^#aM(@3l%?N2b-pRGIS#As%sx6yP9uBL;aZA4!-&Y? zC9KF)?LG0d=g7dBOhog_@TEi*F-bigRV_@|{{Ze6x0{b4Uqc+1A5*i>{gnDbFmM5Q zra;UQ#cGbM(aj%nHnf^3vTxh3arQ59_PI9=sI+%boijlH032l3OK=*|z^b^#K}Msi zC`9~O_`TUbEqhjztUBg8Dix*1$+`F5_sxmdYjw87qOPLHWVd$Wk_3{bp;o&iPf0~Z z0BW3$LZ%vMRJ?=PCn$1`J1*K)NgAY)z8Ine26|K%Y|$fJvEo%jGMV$oJM5m{ z^8Eb6zsi1{SVtUcDw?r6V~x5ntHsUgUGf$!?-_-UYv zCy>YNe!0d_*H^_7rB!x66Iq(b)?%nDYA*28&r?w>5uGnAj0+r;U%RI&2;vg&dy`G1 z24O5JtklU=`ghVj7h9j{9O_CZPvaD?3V)~1kqEQcMDp!!tw@(ss(~zxTooe( z^5@bA_qq<9a}lVI zl5HtN#&$kkwW1F`Kg-vut@+dN2YGxm%HVe%H*vpe^e+3!ONQBftsV`w_Cpc7BBq|c zezfeZxRtp$HrDrx8BX>JqOTi6M*h!{kr3p6l%1=WX*ntR~xefDanoj-m$-5n6*%6M^PD z#R`@!{{SC)Be1?mcOK8_&aJ_n!?^bp)74c@a!_sjHrm@bYG%l8ed)P(Ep$`SZQZ@K zaj`W`MMQ}syDGy3a@0!LL6i8H(GWATf;8rS zXxTYGV%)iln6G>drrL$r0_;mLR763ScVZC~WU&JStLKCHD13K{3RrUAB>U@fX5odu zjqWTa!Pr=gE^fW2l)g&~h0o7esR*AV;g8~h|NgnFIckWb-ux-zBb_(C<@zTCVg4fHIi)>c;JYkecq<*I)_4wd}6 z=U@DpzAnR0NYp&1dJ6m9B?@FslN2vy1> z5-4zMfnMJ^{{WZf@A$QZqU{Zdx^msQ@%E~t9kr@AK3fY#h2H%~o~@RuOa{{I%uX(8 z@pU-e$4?uKM&h8+Lt9#sQcD#rK!qlX{mJ&4DnbG|lZdyxUK?4Ry53Z}eQz1VToDwNhB|Ss-JQ6^@rf+^5tKOONtm zgs<}k>WLwLA(L-OPgk!1F z$T!v7k^EHu09VV`t?IrU$EW9CRaLUmpB~KYNGGPM@EF#V?9807*3vYp?-oXqRnr(t zAKY)vhzV>Y8?!?}r-#m}4nLR6qpiSJC@3o4Cm;5&{JNv>o3TotFaBDq#<3#&lJ50D zjC~B9kDqT_I~fbQb8-d$0M_?~{P2u9>z&F9{{XvNgIw^}=lS`ZeqDV#dlJ$A0IVOe zAE{7zFJ`T12`0iG9!KmS=jgKawpXjMowu~A`@em`*Ij){xN+$==*jGT@7g;{YROBt z^Ej#H_c9z_qb>Zl??Ii-2z*1FI)J>9xp#8UkQ1*+KHXX*-aNc(W5?`gy zhLwy?AW(tCpH6-@cEEP{6;6;zJz&@0-`;O@`A2r;KW+INben3~ZuXOTJh4nIE;lI} z>8+mHJLaK+8#n=;cw-^wk>b@N0IK63%Z-iE_x}FF6xFap36kubKk&9^YOEdUuKnjWiGQ;n<2RU=Exf?e$Z(RQXeKzlD zv~O_R?OUYD7x=_-tciOPOB84>Uf1dEk?szsD=Msv#bXhfouw^qJNb-ml>6G4>Fc-u z0LnC@X{1_+WRjm@_2ouPSHx-Q;*`&-D4H@rk%(yY$)vHj-b2Ly0D&`@W3~bAzpnNp zBT%6cV2oC@B&9&70tl)3>-+fLH}$6V87Uin@6rbVLN2xg(u4q|j{#2Zj6cXKcFOD> z)10R@6nLmHfvaiXA1zGSljc=5w6!f5M#Y+#)zQz5wcpgUDUG@BvcYPW%`K2^Wpy%B z3Z#`Foc7n@JVC*ujPr+a2KCzZBr5`;sue#lXw>)#0E6qqhR0mLmfJ)853qjVVp6C5 zBy5_X`8X=7sp}wIRZ~<{(zP^g1vE7(tM@MI$54!o9->E_tr}czs~nQV9d0ZnQ1P?1 z5_vVys30h+h6EDCr3lh`Ny^?B+&5&Lzykdf9~3hh7rCmgnuP|RsO$(Ira@X7+h5BX ztVVCPo5N8F%u`Zs13%s6>S}4XTEm@|d8DbQt)-_;wOfIQ#R5=^kO*_=kP;R9!{5ty z?li@=!54+~aWj)C6Uw)9G?KDPtKi6iqldzb6&eFpk4}w!{kXKh=TM0tTe#wvRIMp> zyZt~!Y^78{&>&S2iq}wYg~8|>#MVYA>FMOFjueuTu+rrQGAi}jwX=^SP-Q76H0F95 z(BG-#M-m9+ZBPY4ja!wdo}MM# zmE`vF#)`{sq0!c>40=c;0&4H7jG*=_4ArsGjsEDCmR7+w_WIc^Sqris0iv;_J!eH+v@G^!-%w$X;3l} z@w{v#S5`_DVi3OqH6=)>kG3}M9;c_Ww6X2Hy$&KO93E%7dgci0rQRD7r6P_Uukt6R zX34abb-QadkEu#*&wD&#o=fkHQXXXMIS}c`Wfx6ZG`)7&ue$ddxffPQ`_64O z84!fJ3tbVP3RRNH(nOt=*#HGV`oEix3y|6yivzf}mV0(?>NWo7(^b>Pdi%a`H1Df5 zv-0@rxz%yG+|?=th*m6BAH<_H%GBA)c;#UK058YPn}0GvBsD#?em`Kt-IP)W`k(wtDd*F{t9@#@b?ea@&j#4L=Y&CLyt@sTLq_y`i-$>4G zEdwwQCf~TRe-1}duE?6iH<7S?bGO_tj}@oNkCbAu)Xc3DWA`#kD|%?7Z%C1Be291# z9!oBZj5Zk!!$x${+zRRQihyVAK3=^AtV_uxVTb6ham6X-Pp9~LEqL6Q@a@@8t1fYH zj3($0j&RWZ%1@0`E&^8sndGUMETJ0O!~*<<_cZL$yY2g^K~{LsY9EXB7e8SbJxUzE z8%YM@W1_P}1%HTZTvP1pWiRCD__;cpvGN%@{H7}vQ`!A}Nu18$C~7kshYhytG0?}H z%3*N$>Rg3(LoGu^Jk!%sK?Ov!O&Tgj?!gG_kdY&?+@YCIfZM8vrlP?-IMnIV3s!{F zNG7=eoD*JCh6BHDP~LxHZY@!b2_hyhsDJ?^kz560Xgf*4HhszPyW`$ZwflRox)Q5z z?0(ZV6nGAUq1(7BPRi?g&XL|2D%?GHZ0+8+$)-~+-X9}+{{VBoUbB7nPiAB$TyEgV zQe*05$Rt>lizs4w6K}WMVzv=kM3O56>^gV=oFcc6O9fvIHMtJsEX;D<;f@uzw}p@* zX;_e+z!w1iDJ3A+SS%4nlqUcRy8i%#`R`8Mq4T9*Xt{ z>>%Ute{Fdm>)(%KOJD4x{{Tuq!PJ4bHmf*?kw4(+7zd`;-~4~xkNi)+9y~GCtD09oL!_!5TrliB;BprGb!7OyZsUKpgRj+JUHKO;&&%KDBh&_ZEEXrNx(lr-@cVyrL7K^6@HzeIz3@}lZdNqe zEKE3k_Pct8=%T7*`?iLmqPRqJ?YR|R!tUTO4kwLx42sEL$Q2(W)sw{WB844_WvN^i zryd71I3xVsZ5`Ra%Uc(^@|9Z?ISqc;+Ix=!O^Tnf`rj}2*~Q9MBs8_Jn}>PhvXr}5 zHCU1nOEX7Zh^kAkk}9GUp^w9nS=+tH zJ7|9>{+p$qCG4%i+kKy!$JEebsOs|DlPj`uu;6Hx7;*FE_Qt|YW+t;EO&uCUDx-8( zU}OpllnzDU2L8&jRMfE~h^Cl|RZ5KK z2D}DGr=<;lF1>{QUpTGxHX}Q^tM_tds48QxCo?SsczV_HL~HSt8(utOPV^bW8VZ@3 zt|>eg(PMC2j?yTc5;IRc{goUrb51>Z?&g(rk^=pdq4^ruhYumquFw1~+8e5g@%x3S zaukwBPaL@Tsb3X?kz-N>V;7E=Ddd6#w0=2faOw5_p58IW#~{+5xANdC{JLcvpu1e#%N7SG4%o^J)dnwaZ_Fy?bK7pM ztKyA=)KJ#M2-9$+GVUm%ie;WQD&rhA0ytEPieUK@!^*u_&djc_lw~6rBZtU?{Jgq3 z*uRW@!Ba_Fh0Sk_2081%!(?kPn=>PpNTR5OB-L1$^0^Fh%>^KGzDX@0;h9DFM%E$4 z8fMc|jul^8*A?`qP6@)0-U`$x98Vv}bq{BMFG^f~%B$M>?aviG5-Jwl3JRISt3;?cwR;iHlVH+&Fw?m$3zj6LF?!Ff2)Vjrru^|)W)A@NIt0e zUayA!_gr(@u^#?}m%`bv#5G?^2$t2X% z{1qqc%G0{OD14vpUAa9L2Y2-+T~8Hd4nq>T2)AC~tgb(8S3{7GIVBw~KARU(X)D@D zCZ!cDlf;I?EIdY7d7T8rZM$Ya^~3@s;1=Wv_ypQ`%qhZ(0bi#Y-L{jnYrKNFIt^T4R)zaIEj~ZhMrowYpohY+d!qIaa2!tw`24s2>O}$&hFb z2B+-d+hY;SbAKdaiA9bFk(8f@R-+mL=5)KTQVCI97a6+;A=v$g@-KaFF0!xd`Wh{< z+VJ6pX8zk7_s^W^zObi#*|cb&+t55(Nj%Q%`Gibz{wndfT0e>w9jQ?VR=xy zNhF=MAcl}=$)N-eHBd>VMruqqZNe+dn;{dk2;)RGjHkrRYI~SePyi}vQ=cGV>7jgA zZ)|#s<55Wy{7C5vvr&_$F_}ZuZu)5FpYEk+frJX_I>_3@{{YzpG4^iplx@ivP@9wI z{RPk1Nd2JnPFut_WldNkQ^=^*QV-8L`BT@UHH2EalZc?D5=&D>0#nHhu!w6UsLD)Q zm1zW|t$Wmz(h*B(Rk^UYw#06GlgqdB;(wP<7FGE0+)tm%y(*FE(t@&QX`^`Qpe-Pb zB(#q#>j;ieBY7;umS9%o4o|w2WnhG4k>~6FZmf9oqz^3; zNh}43maQ}>s9JJcOc6#yf;lAf{e9JgsiO|+^|YfUSA{e7`gEtFSm#i>e3MI)GARuS zrfA}0rS%)ML;`LFiEmfek8}X}Q>`~>I6OaRO3Zqe@)Z{+B`i})5hIZlU0Q24xaHBt zol0&8*PnasAqyV7#L@JVU!P37f|^UA2Fh-%#yLjRkEjM%ega);MIYlA;WT8$C-GWcJk5x&5t_j-pz* z@R>-b@-;nFa8E~B=7icIc z5Lnh3&P6!f$@yT^W5@z&T6J8%2)Cb0^`FK+lAH6tda1j&V$t_cK;mfn?w-D$idv1s zRf^x!Qs=U3R_jGujKxC{g&>?fQoU1x6#BvJ#iC0WSc4XpRjH*Ch=#Nv@!?;Wm3j}w z9CEGSi77->Q-Dcs@B)f5@Fu6bhX8uAZ;Br(KbOCC_in`Mj-vP#Mbur%zH@olwnt}U zA=tQjt(}me+L>&PTXnwr=yODG>A!a2ndQro7&X4(rzl%{{R_k9MdnxzNWbOo;^mq!?&f* z>bX^apgNQ?f^@0VT9JWDu{jDT2cKFCe={f(GyLCvTi4RS5(->LNmWxMW+i2U504#N zL}Zi=4J_quTHdmGJbMODn~q~*PN8!qK1Hkik3il2jd5h*Yof;A^P&-7o;>*UWB&k@ zbrh0+F~5rS20-8Ok!l==Dph=2S8%YoZZG0nC>)6j`)6t&<1l81hyFTi{$7fZYTUVG zvCr>2Zxe23a_#>BnAmNVx8=oD%DI}3z24n_y)s>qKymb_^;rxXjh&5p z#}`U;TQ{a=1*@fbA_>MNI+z-13&63j!%SpQ){Ey(g52-nFDh;mOCU*OmM;YPn}&KK zA>*lrvQ>MT5y|aVpy#veXe&NoRMb&8G_%!i2&jW6jiqRI94hMe7G5hxmB^0I|~>4}fo2z}1V!aJBT%Y0>NeJ7^bDqTxQI0#5}00Ezm3eTV?_ z^XO^z^^`7>#zt-d1YeP3rvCubkLmB-Y4$8+u4C)su&w^M>_AO?gP)5-BO)AUd?fP z{(1b|g%F<;bJfS{U+ke&r}_Fp%{{NQgHQJnPp{%^{(hcR>adEi_}A57nNlN@I+%0@-?k_U10KboFGw5v;8hUjDwOgIJq<#|i+<)hlMmi_? zx0+Qje&WV-%5F#QJ^s1}q}u#@k?gc1_=1|oK2-a96I(_jb0PTu0LjuXDBdXJKy@;W zEN#KCH?{t@_Hk%6yT9Q*8`-9&EJ&jo^pKgu<}s}$l?`nOa7k71nwUXnVd`E!zR$Md zqy=9l=-SajqXr{EHP5Ag)Ox=yk+!Qh{y(pJ*KJi`sdskz$KtT~72Mf{!r>;Yo}(WP z1t_Y5lPi|5%w;R;VWP+5XlUzl8C-=#H1yEBI~B!^kCt~HXXg#x*KVS%ywg06^`Hc@ zs8BM_$MB8-7C0IDHuoFeo=f&q?)%7_*Efran{wOs`+GZUWe+^gu|p)S+{%%|3`1MX zBP!QQR;*cSKj$XN&TMay8@`(>`~s$zB}I?OU~{`iFD7ekXK{*>QBPAtT|5+d3S5m2 zQktTVCy%Uxp0^v4r=Fg8k&@o>W0bb3wrz^bZk}|KSlNMP1PbHHfFmBGJbL5zy&mCh z9_M?H%sk<;*j?LL+(j5j?sRy-E~8g5Ge%B-12CW&JzSJ-X}&JAW3(*s^c*c0+&q2- zsa=pwNG$2%L}n}kmC~nx4<6OWt+z)H20d2|_jmWd6W^mz6yF*L!qC z(dLMe5l@DVkycMK>1ZP=6~M7$en<9A$FZv9$VVFV9X>p1^bI6fA1=Egmd3*V z@)1ciMq&^7LG-5%v31T2ilhA1=)HW2?)~-9*o?mF+Wi`PKW6P-zJ2??w}xA>se0JggG7qhXIReMKs((XOum8#uz`4L2qPdD)BXPFj341qx$=geF0EZR2Xwd_{+ zyL@)9H0>m>7*<&o79=Q-soh(|1@uN08FlMqQz3FMDePR~e`mICT-NqGrOn@gZwz+d zQ6!4CvfVt+1hM!~sD+`{LjyA+k~I#6%r@-a6dh&T{f*mQOSwA6UXaT6gk6iacIHTS zeKFa+VM$F{H)d?@(72tYN4mCt@}zm>!_=6mA*%aV(IG;vR@!gdg|5rGZk*d=6`jSG z)JRr0)U(?`ABZQn@l0;sB8Srys~oCSEQ*Xs0eLoi4a1oB9gCHB=%>fE06=J%_Z9yFgv16*~sqocxRC#Q2XE0c8&5460kEx)mmkGErboq>J zMD+Ctj||gMR>sVR_AEiU2iT6@<_pLz?rr5pf>_bT8Csqqhg#_*0u+EnYODx75IIpK z>aH2#k>hG`4;vJ9`$Gd?QA5-O}}(XMZ6P8dsS5G5v z;(}D5%4&h7G9-wJ`D=dM_g%Gj4q)3Y>{eLq<+mv*WSS{s@d^D^jzxG|^xQIOatx5O z!cs>=&6{??vED-l$;_ty(3_a$XNT#ef_Nu;cZNuek`dx)GRE45xX5iFP?4)Cwewhc zsn;`x%VJulEmXgIM^j2&VRb@PY9l~VNwbCaDOqBAEH?tg<}3*{qP-Qnl#=W3p_0~G&Lp)f!NSSDk){20{F_oO*F9?;xWq5$nh2_BdbMT z_Ax%%Z@xybnsEOBiB{sjJ~;bpj!hE%$u@bFS}!U)^m_ zQTp)k_4Lj>_|vJ!?^eWneX*c&18;ED0zhH(w`aHl0RVt|yz|5kuII7$ruo`iucA8p ztoo-B++By?`?Iq4#@NDVJ16}W;V}?(H(E>D8;>tlxklFAsXNbtrI{(|%n>Y;M`I<( z9`a+Ew~O7bep|BJVYhp&#__HH09eQo0>bk%)+J_Q0uT~|Q6Oppq+#DG?0aVGw{w2^ zzHYNw?K>^Kq_P-b7ZOSJcLvrqR5C;WSD|*)Xbp7ZuCRTvO9cJHw>zU1iRj(`0P)%_ zg;(+y5tiL_+oP>^4lB3z^xMa(vpC+=j*|^bx^er1X$b0Tm-u}%;w$A^MiRM69lJha zMos;9qYP7RL0WksS^k{F-XRh~WI-z!mL~d|Aqd|CNQ54rzU6zRy5*zG&ijVjy@^iT z+EzP>&ATjD5zTH{giMl>BdmMNf4B&5J*&jq=mEdHp6eTFEQO-h1eMs_@P;W zSqNCj6a)uisx@f=mnu7_jlJ60T*fzBc9+D6YawD;86uE7A|rUn71dOh z1&WoxBwf#b-|qZ}zRR{>+sykzO$>I|Osf)INhC1H$r^`ptrW5}1ThTl8D&rokST2a z``2Bsh05*@rQf?pvv$tj$xz|*IgN+7X!j;N3z5px)>cqsGPTr$!%JO~rJ$&mogU39 z!sRZi);8ttX63$QTZwiJ?mMuA2^m&I(#$Y4%#po79n=Ib1|alB%sU?W%U2e*8~)QR zmDH&6MHIS2IwJ*uv9g?{0{{Wwp{5>6R zB9U8wD&8-xF{ShV$5gHJa|>6H`DODKvK)O?b}tw5hqfN0C#F}Y!`4^!Hg+s`@k*$Z z!$~z=L1^F-6<2Rc>O6bHzH*B2bI-VQK&QeRl*r|4r9_WFtbH7c0C!(kIML^zWY_c0Zsl1QQGmmGfHs@%I#cLwI9>)NNtON_^M zL+?zdUDoW#GE%KQLw|gB?Oi72T0FgdDnK!~@mEoil0Qu|_=~FEM%y{I=JIQfUfg7} zfPS2^sWdn}z8DSTGUpmeMI_V%nCI_7&;G-5=PFuQd&9`~+}Ci&>TGt$wn?Nd+OII3 z+972VE*?geR%S&)j#Oyxuyz)2u3LF*-PMSP3%FMa9_Yx_$GE6B)fVx`Z)^wmi);2i zBe8J#T-#w;ktYcJUX6%2Ol2s)fO)S$kJFU7NYC$~OL@bmECy-od zjoVo_WFkrX#g}iocRIu+Ww;#aw+_=n31kI@JkJB=Ojfk(4@SaC{O}5%T~b@wUE$J(S5WqMN+jCT50Pd5lau<#Z6YTM+IEcNLoo} zj!g`z#`=OTGO}B}U+r{;Q$siFbinL=ylm$ZtU`L2s zEL~Vs0%{vb?!Pnl*xY3$Rb$lFVm9tG5rvy0M-DY1!q9!nQR8JuBSDa)ppvBMsgb3b zr_u`&+Lf8@4!gNyY9W=`z%`|5`igjheq0AhCf+VLJAJAP+mkiborG5Q?D3>pZJ{!F za4?Nm#EvrNl1Z*Y{8-kbHd=;!!{l&q*2R#LlLtkRn+sI!3*_=~K^jF&G8Gjet0W66 z7(65{w`9`HrTxh_q?%a#A0iprYtAR)YH&m@X%3Va!j$* zqY2{3O14%AT-?vQE!>L}6^uA6q9kD?dQ^d0flde*A?{LhVB6xe zmEh&hXDA|lhja=WepcorVCef*(2{X8-Q5t7DPAypRhqT4yVKJ}%}Y+v9Qj15I4f5^U# z+O^Zt?jE<@NNFi(d-JKFTKd}IMh!(gb=dq^Sl*oyn;`N=lvx5>Z3U$ET=Qvv$@1;n zOgDZ%G;-30S@~-EvA{W>mm@m7ZMf?b&u<)pIN@lmr;<&$*IK@~=90FOW|XyMB%)yr+f8x4#dUSKjn?){ zbZ_2q3PZfufTA72!K)_VgG6_*F=?ZcvD}{)HIbuEX^MAaxLw|hnI)ug-bUZ2xWKeA z$s!Kqnj`^b@kwTuHdzmg7Pr?=uxeOMH8gbM8rVdwSw{1RU6)xY*4ap$t0a-l44RrU zbPI<%fl#wIF2=qZ$Vo5~G#Y35e7G01T%Tryf7%$3=p^ zk{XP@G`We=I&9<8*H0viE_S{;JFP?!xg}(UT#&!&Z>W+$6E`nN79Ga8V2M>66S#K% zeM$VcO?TcS0LvI9e3K%G52^nECtE5103+O1QMv=T{PpwG&U?Z&R$TT=nEGT2S;y|$}Kv-S=fH?*+y5XphuLV}u`U-1Tq{Gp7}6^AwRBiqIj z(rc?akgkxiOgj_apd*!k6TL$e(#cVzsF*gcW9Iw4a@%c|jXaS9;=C?paw`_N)5Jt* zsGYzfp=!3XS^>9YbQfFvWcZP}_9w>ur9)fQ`QD@MUeToAIGx+I`y}^eZ(()b;K^<- z>dkfr362M_>i0H21!(H1bYtM8q>7q~C}D*o0WM;>yS>}@TbZN`dTBE7rK}3vLFoWLLH___`S!M*8MpR>J#$_Y z`u$HIgQWieU-0*%f%GR$mCBL0~!hbW2>MdWi;)f9SqdFTMtdwc)svE#+PDk&g$KLflIYE zu74Djv^gsNvV(5_0DAIOTaoJBsj{^>9onWmc!WdYnF`2T_SIC8G;!LygGmDw`xUg2 z`F#HXFFu`CW)f)?3RDyGAfNCLUa^c;!QQyoG5Fo)cWoOoWwV$y+jN+5gQrv!v;B>1 zl~U9tW;vV~t6+Z|jM@qXC);3=!n%D=oqyTt?6d}kt>ylI_BtK9`>s1H8fX?>=d@~I zp^fP9m07K!Jf^v&o~8-TPO6r=41f`1giQ?QMlC+Hai9igDx_4B3HvGb^-)b&T-P7u z9VKg@?Iz7^UD-?Nl0`HAUby2n>@s{+`JtMh9}Aow{`i%RTIU8DoO);JJALZu=<6OSBBP5W znB__4kci?$S0TR&6^h+$;GB5OY3o3Qe$VptunAUb-~s*`e=a?4zyAOU+}kmy^Hu(G zHCZeUPJya6f5kR@KH#L8E3s6$>@MNS!$G*HDy5uLavloC5Vu;8T&x|{EZ3n>vHsl6_Qm6732xzT?!A4P$WuL)@1+@ z{Rh+9V5$p@WbpjDp(KU*b&Krajozp29NAOU*-J^O`zeQ!~wpDwXeWa+Bwayab6s50))md4gc?52yA4>u~`{&oFKnKY5;qTpRt|b+Uu@@*wQ**%}sXy(H zy-;BFut)?B2d-c7KKItT_rG=Sz3<(7s@48zG?Z1H8Ml(UK(H@k_2jcelSY*_G|+ZF z#;KkvQ8F}8$q<2NH3a_9io`NI4{d=>k_f zDo)PZben^7ZY)OT&tWqdt&Oy5@HBgl2&BcjX637fx+=PfsOmMqJ#nsCw@Fe!(LKpz z3ZM?vRb#BN)^$~ApepI5OKRz+NW2}ss=|K^lc}*razF|fQq@3exv8y3Zk~*spD`Z| zN4Ij5?A%$z<-dhsv6+*-Biq}%A-sOls<|*5Bd2R{Tcdk+^>VWaiQ1J_H8j!rrJj{( z>6%ukj#$=BE!|Q=(yVAQc#k7eP5=a+s>TT!Ni;=KsGosBG@~{&&~P~fx; zCYcw>Drh8*%F-0oT2i8?>=no#Z`tY9h=~!BDFHlBp!4{L4?$2Uc=T;{_j&ZTN)6FL zxBGi$?%(cC>7v`a!!fkys@&K-c79_dM{h;AuryVBa;GVdiZn`$buCP_xZpxoM+>k8 zxkQW>Mp9LY0D)aZQnd8~xg!FEaRhbZf;I@lOK1(GkPefPQN?O9wWgs)6$BoJZMnO4 z-g6aKCr z>ZeyMwV+^WO4B}mzdF*(W=T5`1UPfBF2R#J~qPCSO~6t^C~NN-8E zx@(LAH4Q`gb+%W>VW+9<4P|-_wO+yEo+_MHQc56cl0gh**O>ea==710ZpuyA{W!O` z6_n{DiV`#B@eKZ4I;$frj15C-72-U4^gPmg}nqH8uI^7#}gh zzn@<*Pxw^*Lc{#sH?9VnyKq(GcGp03W*Z*{;>^vOII2(K8BDTc@P?rT*o-KAn@Y5- z^AR+XNvw$isbs zYFGGmFvL{UQ%dPOD>_VCJw*s2CP^+5!Zl@8Nn~awzltEEfHo+-ur!BQ8GT+?vr&=Arm6Y&R%a)?VirA;f{{RWAR5+tbT-67Z2-#w9 z*1#x0wVO_}`mMlJVc6G?1JrrGfhO*tUfLx8089lXVugc%J}m~E3DgOoI!K{CXes>B zurNs_mX2ka zUDnqH$O)I21DZe8%6?=P$F4`8pUcoQ%<;zeJ8*(X)y0$~(9kedBT9-6>|lN+8mrLV z{HiHm75v419?r8ZRC#{N5>uKtEKE}Eox>dHA!`+CNfo^8MZ{6bZY+Jbwh%8NMPsPf z{yIPai-JUqjsXRd9H^yra@(azARC)`JO+sLN!k z%KE%Cv=rdUG|mD1sQ#pT5Zp-cL}WkbAA9un#oeh6Qm;9&y2E(maFfrA-s)-2Lv`cU zx$pR0TpcOB}Sq`fFpipTidO|)(h9H zDs{sc6i~%z&MTL2s&yKj16Gity*zDHY7du~+B#Zz41dIT6+5tK;wz7nu3DvKg#s<+ z5+eFQ2T5y_VoKecQp<52apFr{`B%5|s1+VVqfT2v9MK>H6F=qpXFqA^{25yOs)w<& zUy-Z&f37{BbUdzW*AN>{tCqPI7QUi>qwDqm03UwqUzR%N!$zG-x&vR54Xtrte+&rv zd-26d;nv3t^^zbAjiG?O$OrpDO~}%D79RcAfT^H8fB)6n*qg}AKh)d?7P$HmamxKT zKiArRmExkg6ze=!Lb|PDgfKp3OE%_f`@%N*{t%{%7*Kq0dCpWnlKSU#yP`PqNMkyy9$ zGswnBV+Ta_m?wc@EpFzMNmVusr2hc1_6(YlHs)F&~+8U-64y z$o(SMs2I2WjX9-j!dq;7&9W2wdL{X1VJ4Qks5gvU+=3S6e*^t*r@1!J0*gRD)m}Xd zA_~Csv&$e21vn0ktbsZzFh9Z4NlKj7ARFKKg$cER zAMh$0194&xv&#{I{5rZcw*$gre9!F9pXJr&?W_)PZZ3)J?Vn$s#_#^7NcS$ouiAT? zIk7iJKRr=FO!T?ktGl-K4sNq;?py^;3eQ74xXh(0kn1He3>`6>mN~*+Qs$0jQMOBU zZ+UR)%M%rtXlJ8FMJm)|s8m#BWOeiv?(g05+uzS*J)i#ok)5{3zHEC`6TxwF7?#RK zxVE-gp}b#-B5w*a9Fg}%<4NseMQQxz?49koyC#FL_XT9DwR+mOr?k-4rnNpma)aJKX!oyUIp=fs@0oYIJ;!>pvbL4(ErW<%ZlYP#j~0?E zXk`qoT{>{hl5R6EPc;|Es{Cd}A;r&0(t{T>5DZQNIkzK_DBCV<#X@BB8Au=hr+(%kAhoNU92P9c(T9pOBA= zy^74T20tPb-f_cCfeumNqvZpXu)~KJH)gt8*GC?l;;%C-4^ePKV| zt5N1YP7Dn{cF9lsD3Y}MNTK^Ww8e%sDHfS!Qi^3yA!St6aBt}V6+E#7gY@^1V78ZM zASvK!ocjL&ldM@PI{+0vWBp&xpjYJn#oc|Y@wdDB_hjQ_&hLHcgWB{vXAx1E#$oZ* z)wq7i*!!BkERIt(Bs5g?(O_^@aw%t0@}fpLa0qjowu{~CmA8Ie+58l{xqu>ggsK80 zN2zcdMil2s%`xT${@rg|cQ5;a%KXQ@O7ZPh(#_(!sdiP8(&7~%2Xhf5iNd-?TY%~J zfd210eMJmHAh#l>oL}Xc`sZt$StDP=|$|x;PlY4#6 z+wZpV zvJz2cw-qKMGrKa>x&7t*2N#9TZdRLlXZJ0BI$ZPO#EnZ&G&GQl1c@5tyR+;&X2WG2 zj@xMrF|LxrG+4t(s-dJPfG91bW}1itQ!%R&{$%FPVdmY$Zd}Ej9d?;M9mRd$hPc+d3IEJx$(?gRV73UZ#?sEtQ) zhyFQnf<LSN+v{w~lCKuZAs@W}a-6ui2V;XXVgI{Ey%=Y+sg4vIvj&yQ9-apaY=7 zc5^?F*by3nIlZ+J`Su(8w^QnQ+^`f2Xh*GoUq9;peII@7^_{QV(3PRMz55Ssu0PAw z<1HytRGBqN3OFT*Qh@&eXVyf5%VIyn>+dIiAzV-s{Qm&K_VtF69XO%Xz<)3B`ctG= zZS73X^yzNy*!yk;tld3<(tX3RcD)4kl$iQT{mHy~=W^}6yGJd4LRx%&ItskTQWScc zhe%*nF6^oc1bdtlU2R*{qzb+~_E!-mqd~4%9yHcy)KJVd9W6zv(rH3*%6pxj)6IOT zyY2fqVs#u< z8+N;NZwy^76R@^tS>g76VyX<5z})+4w4ak|tz@G%K)oU(${`hF}}Iq)<|W9SiACAEX^o5($mb zB=QifG)JJRU3!Qik0pM-*O1kzB#Qi~K7Zt=mqcWNPz4+Fsq|WK9<}owSNHQ)jT8BK zcdG*ICEnc*gt=v4M`FaxNWGd{sq~OR1hD#hioNVs{{UNU{;f?b2{^$9?$~}=rhZiO z>mYvYnp@n-STzUk`M)|c4F1x8E~|(67sKT350yb(OMjq!m_iY9%zKM#pHkZ6K>(W` z2R~16*WK)?=S}U8{TiHn^KlOk+0@zhtPXv>fZiL{CUUx zkKBJ6w$|~$$+&uNX70}U&UX95xMSO!gKZ}4==zPT)qAID$w!gLA zLNQyAxz1invghlay70lw7m#hMXj(BUFoO8ac9IGd@ZQ+6GPa))SgJC}6!n`M)?2rx zx`wNz{y*%f@VjHJYcP=Q4Z%mecI6*q_l^TRgEPHzTMIY8s&_8k>hF;Wx|-R{mj3{u zso8ZeHbL;%_^6v39XV_58_v_pw>u9nAh(XzCKkREDm;PXlk}Clex7BULyOX1#gKzC z3d<_JxNloN`^@jmT*kt)h)p1LlV3lE zm@eV#XnQgq@9MnfA0w0bH@|!DY;Jw|+C3lKna;|>_8oQ)Ax*b81|O?vr`g+Ecx>1< z+-Y2Car9e$u3GSMbWkiahi}`xyP3Iq4c_0FAfTS@u98oxX{OaM3oLU?rD)OkYo+7C z3`k}oqkia5%e=vPv|aL^`xC~SCAEZ++uK~)t-IOAV+|LI!bxGANM0h+Jm{&Sc?%Vw zQ;7Jz+wy!~-2VU+A9Ho~*r34UtKr!Fuea!Ga9xML_cWg)s{Th!xUe})WqYQ>+EZ=( zk=amUw;U4WX?HCM$;mvJ31g@Bn&XrAE52Oa`8rMFMA+I%d^rR|Q8yP$edC}@k>JY{ z>a;AN2SRRyZ0f5hhV$GFjC+M;?j&1mw->htw-(Yit9WBOaN9fvM?htgH(#rFjf`?Z zC)0uT3eo{Dtad+P<~tW9-Cf5+@(*rrOdi$E^>)s{cTaHqSM90_y_vlC4F>kyxvXs8 z7y9F1;_+GP9m#>GfWAds$qb+5$dG{?7UZ3Sn3C-89O^EP^$aFB47ba8iwwaUQ~^{7 z-%=vEW@6eGNL5f+i<`HtqCKA1l{sa$X?AD1Te+mNw7#@qa~y91pN?W|ajoN8h^zRU~EtV^ce^NbGFP)<03~$J}j0ka@XF z06%xjL7MR3Jg7gP+0oCjI)B$^l+6k6pNSMd;?sF?t$jEO`SnGg$zEt*=ibOZ7F>wg zd;COo0FhAt0C(!X;d~7X`6`xGj?Jn&$EbdN^NX0n4W{CUySAUSe~_QEu9w<>xmM%) zU-5s-t>%6TPGtG}v*AaU7{^X_G^VLz@)@R=4^JCnOkf`ZRK^-_FDMN-7YtX}PnQ7t ziB75=BzogggC=L^XX%kP(P#Zeg=$9fq;+W* zVP@I^T>_MfsbX=h3#$PBp<~ayE$68VbLTu2Bp=?hf(8MjnpZidDc94du<@h)-@S$L zBLSC_c7mjUN|R#^bRH{FP-t>7!=k-}?C$>SJ@?bymGS=oe${o}_v#7_{{V)-Zafy- z>)p$_G5GGpsI95Y*W)oAr?+=5#K_kV;#E*9Rzn3_FmE`n^;Emk`l*Ih+{>Aj1$YI793hc|`T z+d`*!?r*x?+pTd}NOvCk-h1nQXLH#};iQIwj%ZZs$ z2$~j*vmHo6qlp0T?-Ow(KXqs8U=|5yU8^Nje<=R|okrB&VThoPfnyn99-@Fat$g!kl1G5U8%O zJpmc1#{-HGvHn^+i*OFQ-+Mn1OOiPj?YeEy*?b*Dv^i?=o!PkksY`=`zBfoehR;on zn9mfYLGqiOB17(8upFr;!J(#qYm1d~ei?0CYTLNNcmHgnY(JAAA;M1JV`nO zfM5J>aV&(ZHm}!Lh9}@eRTR|SHSgWb>CTW_?fXK-V5&gzR4Y8fXIp@>oqE>Lm5hXQ z8;w#frfQI8Tzz`sVS0&Dq6eB}f*gKW)Mhrdd&tWL4qh}#WJ&Aeh|L-^N+N_KFYY^m zj)rSUu30SA#EKP*Fzs|aSx!w9;EWwdhXd4ab!EAW3r4uOgu^2c5-GLKYbHc#IskOE z%DT{1!pET0I}kWmeZ@vLpYHFIs)rVssx1^S7^xwP_NwcvU`Y#8OC&DK7*lj+AdLjF zx)C9D(JdqKgon>rJR{9;e8KX^MJD3zXuNsTUE14tF^vnQ0^#IfGN(x)KsYBWry^ET zvXYl0m8Y*Yba;v_xko`+Pl?CUQ`f={J~gYcV=LtAUY*evc4(rJ0wQTqt%qB`(?z>( zR}FG)l_6D@fC(8H6!>wIRn%|;8UtV973ox$k)`F;uHujM5bf%QIHN^z`gM_uWXk0T zRgjfJG^hXq#6s$GR}Sc%sp3k*L4?Ot(#KCpPc2nu4qPonait72uF}1Hk&z^=8XAb_ zTQ~sR$$L~n`0tUiMwuYDC?cU}2S8tjgfIiVfl&Vd7Btpb_TyUK#L+|=B(s5$RaaX= zVl)T`adI-`4-s5Wk6m#y{XXw zk9ygRY**={TcRzV>fPj#Z!OG^$_;S4V_Lr7ZF9^MSpNWzZRsN|w)eMD*(b7PTBhY; z#E62q&}D(vUlK5e$Y*9rw#9xgf7h-{Z)2K^#e)Hq^c~VIflyg?Y zK~ibs)bqy*RB4h~G1EdL3|VsocEgk|?K$3QXSKHwa=$Sc)D%Hoe6h?>(c@thZt$kB z7AX8|H2ZY=AT3MzW4YO$$A6GdX0+M&2hbftpf9v;%cn~|gGDu9HCI=J%BH41eNso8 z>&*5;Y2u^AWH9;YX?v5Tvo(~J2d=k8NP1|uZpH#=G9TQGgs`M^wF+mFD(w(eX?Up~ zL3Y`1v{usVXS4m+Vwa!edr@PrZrqB}SF!}TJ5|!tN|$E0I$>v)BW~cEc3XMuw{5~J zcC@&H>NLLF%LZ#przJ$T;82?>XcxrE3`BBJ1U+k|y}TtBut?J4;gzXl$g({?LpxZE zWlVNO0~0J%j1Gg#X(g?#v^iwkC_zMXuhbFS@e1yiRi=F_Mm|T39JlDqxBvhi|cPRi%ik1&v}#8kJg5oOaNpKuBuE zg;~1Fc1xeCWwy1f7V;{D4XNmi7l5EesAAgWs-7bNbyQ!-e{^=l9|Av_M@Mc-8oKVd z`0tY6@$D?d7Jah2e{c34?CK7}kG8gs!>Nt5uFa{c+7wx@6ea1_dg&%qQ&l6&3Ujrh zrpbSF(gQ1_k3z`0RFm@pi(FI@_Vfhi2<3;FC$y%bZB|z!1PyN-WtbCIbVg7?$cxO> z^`!RYnWmDB+Qk0=52pse+Tt|TVf`=cdv3Hv1JHl5)Q@6-TSNiCKjrBr7t%-i_WuBg z{{Ug_N#jA$lVU*LN3KcwPx~MDfPdaS`20t$J#j;xm66muTO%h*jUud>$|>8_d~8K4 z#62L}$e@vb$Uf7yZeST3_sj~Y>FJ}Y zu1s2{_3J!&sjH`gHdrcJdQ!+aEQJXcAbT>97Vrgs&@g=~ESUYYC+!_Q89l(7F0bdL zAM?}fJs6+l{nt1h+w#+X?S8`QJb!R)X+9wQtIxyMd&?h_O}V=A+drzao0AnaZ`!Rb zbZ@qDxX5yG)Y8ce^tBXG$gYKT3NU!K?cKu#lv~s>0DyI%G*g0TO+3dDk<+pGa!m@p zW7aqlJoAyBtcq@_`0=wkUYj-7KPM?WS3QZr^pE;0r^jQk&$xa=$G>*fK2yK*d&8}0 zs44ds#wfl&=4O_jjvVb?MqSA1_SS~2wX4@=*<{gcQZ=%UCWscHoE4yEH335swH4F> zVB7+5#bu6^QpAx#sI>q?Q>=x{VQI(uJrUjCv@!IQJCchF3>ec}gs+~es)m_r0m@Y@ zh%*(HwVq0f?3@)XW_HyeL1kbq?7bNHWM@kB^JVoB+<5dJ?D#U(Ukv_cVi7*?A(HNo zhoYfYj#|f@ZTv@S)C$UVa?G^;dc`jkj0U$=0nel>i#Pj28u(&aEBUN+{QiH;SFZvD z7a7S5PsxpcV9#6H{{SHz;^se?fAf>ZCJK`u{nFh30373!Ia2Vx=-dgsDSKN#Nd{ZO zKW`DX(w0h0WDN3(YI~}9fie4T%?R6On_C@oii4UEWu|ykgOkMZJzC|%1Wh1lrbnGs zaqB@$1H&}q*3O&Xa#d`sU0&*Xe4c9+K#&UEzk|cincP)=NrWofdWwmKMRjJmRJ;XP z7?qqd=^?0U2%sdAG5)VkC*%)F)GJ_+C<&?I`SiAqM3oX)*feq?x-j}OI)+vs;8gp! z4yo5ae(T+P-@5lz!}9a_g+b9BkG4KA{B`LK?)$X{~^dMtHrLK@trdoe5&IJ|XR$t%Eu3%Pe2-NSF%<5p`i7u3%o z(QRyHDpn~Z0GGOGJWG_cgYSQ=#JQ7G?_GxKpYk#>)V~XHNV2wa|=J3H?X&GhH zZYR+L+&NTMXYj<$1n7j?51k(`_TJ3y+y`@f$NojVUGj@|1sXgxi-GW z><*6aP0+Pj2zKV$-S~*9cU+hX<-_G`Dq50`b#a*uM1WLzjt3{pK2-DLUn*4{!rO-; z-^2pH3(}&1d5Qu{Y80R#0mPhJFSmM4*S-6%b?<)b-Fx4<_f_Nk&LpBA8!^=NHD;D- z&hF?sYI2bz?>fobn?WkzG|q%oz-gSckn4-e7TSl<>NchR)G1orQ|$dYGy7@z)2HI6 zfqYMtCZBCb51$|B)m8MRIE&@x%!%%)PxD{-h$NMNb4+5ak}az}7m}5t5>wDa0fWUn zG97W$fe}&uaQVYHhBi{K^sPXA={89x=Sm+skF%%7rG>x*0&UL^BN(UW=lg#!cBeT> zlfrzaqckwXMUkWaYm`t^WTKEY6&*K0%<@&|D@BbpSCE6?QRfuWv)b|UjF&q+y46Yg z79fu*N=P7i)6eY38g#xgBEGbyS#E8CJS)buKWXFEsQ&=VgS7r_>~D+PmvDSL=-#~U z$ae1Sq^ikLc0OLLPmkZ(&9jWG%T?_Cty{S^{{Zny-Or2rNvd&lbHz(hJVthnsw86T z?h;C`hcJx`uoV>`4j>K`sTIZvr_Z9uS|EGvo!*(DDhc(*Yfm6LydRiQ)$VVGzZ!cI zzK?ipUzM9XYEgGLWof7*2iPxt>|sT*Smr*w8G*tnH-fhIH}5IC6g0Z zPA0u^sHLYw49Re*s<;XpwCiUnr~stZXhj{EIY-F=ZsgUj!{UfhGU_q8tGqdS%yL{u?lE9uUZc1V5d7-hP* zMroprGiHo!CwS7 z4&LodXT*Ki*c&Ujs(wtjUhgc|$ZnY4xT+Yoj>g|pZ8J%l-5qaFo85J|nDIEA&12*C zwMHu^S6^ASYP^{-222S3+{GkJLPD<}f!!d}m+j$0TAmCj02*jb4O2TKM$FR%CD%#~ zRRXnYk}#`HRV3;sw@}DCIDePDcb54H-aQqwx_39Zw=c#Wi;3(nll7a%ZI9M;olk_{ z^f}z##@ibQ6`F)6Yh-sG-r9AUM##Ze4%wxqk`$ji_fpA6PKljkGnwt!M+$<>NTXGC zkr)-!5cam9nIJB)S}aR1sgBp_?tzwhglLMa#1d#4X23$^_Nwb*0~SO9ONyTyvLD|( zPWH}2AMjYWMSU(`7mfZAQG}$Sr`;WQu`-ZEyLu_6qs3O&rA#x`qH48EO6nI^FFbw` zP~g-Ss5qx}bdisThX6-R&8=saHEODn_<R=p@h4Wvhe~^?Pcrj%UYF&q+xrd1)%cEK*WQd0e`dWf3SS#Rw&snjB!% z>SYiK$zkuR!_u9bRhRe z$k?p`&hwj2S7POf+j4xdb#ee09}0l2=)s4VRVUM(oxOVVn2ek17;2IH%SE~m2gSfYKAM*DDqh0H(Jk8?F47sTVTv z0De5+P=B7auRy+HRu|iNVs)jZzny;psQst%82NNN{{Si|QGb}%#N(u}{{Tu*okLBL z#sfUxwng+QHoxVC*YoW@)>vL!f<1rZt;eEOX8q^OL70L2(%gU5KtRutKAG$2!oZba zr%Mn(YhJ{T4X!V5V&P6bWKUZ6e>ytc4#V$1 z_4x6g*}K+$^~UGue2`b?ddq9p3{7czl$x6zldOs)@wP@&BXh|S{{RWW6L0k%S8|Pv4{H42Ynh1M#i^7l~W?7zC{4_?PWbq1xVuf`85s3^Hj;=E? zNdEvmV8w@7WUQjgXZ> zxAt_CXJtE~AcCe=r8r_Le#6oIu+$EaY(Fe{(_$}fe!uO#i7U|4u7jxh{RldZ{-*c; z09-G<_3!ZY+q7>YmEaHw2KE2}V0h<&_5T2G?_F-SJ!X&8R>Z4+UI#03FMr2A{nonw z*4xJFNe1n8wyObdK_LBXrry)wW2J=tB72WggDU7MrSvFZY=753U!x93`rhhCr&|2H zy2+`8g_h}XSx4Y;b+F`Eem&^%3tuk1>rSO>CJ@EHbAjX1pgsQpwZ;8H-|=5{BfL;x z^{Nq20QvRvrvCtiArb!o4t=-+>9_g{>QiO>vp(h2?a2Yp_J;rw{@fwOw-QZ%#$@|{ z5Bi5iyw_EqY^5kIBjNs;&+Y2CYl z9a&K6#sc(_Q>QnLdy%5Pg@FR?>8ghMN7DRoJ)YWpEB5qbZa|2z#Xry0?RC#*)pc)e z{8q|TZ9T`icD`qF?aCeFU$Y?F84kqTJ784e>9?JCRbY43RWDuV`+l!s*5x7E^!d{+ zHaw$=3^Gcwl!869wA!wDubW==&(_5&ctJ=KFlirOhFc2QK*x@gOag1!{{X(G?amu- z-SgP19jbXCXS9PFdM62L$UV$!Kub=O|g)o#q}2N-+N_b9Eavn5sgY;6grWL$aiPf-YW!k~0HPkya$7a21fE()Joj;ZT+_6H)Ny8Vt5V7} zIc6hEc7kXSC{Pe6>f8GWMN#qhb~Zh{wDlcJTJ&Z&^37+!pA-!wX3rwA3T;07yA1b zu_8v#na}6YaQRcytB(FuA1gY~VPUtY#-7vM7%sevdGAR(AFO)^aaB{|Hl1GVtHEQi zJCk8=eal-@PerzqFF}B!p9@`7W1vc?r-Gtb%}h>{=dxbm?L4P@xa@qxI>EGF$g(BF zVIi0OMK* zc6!C}O&d}=%Nj*B{{SY|%qejsFe65Zf%RI>Fq;l2x1RQu0gN``U#CeY_*QXkNua}sYT6EH- z8aT~G!>gsjq&p{{XUxXiv+( zk5vAv^HPQp^48!_{LqvU>0aOU9-P0q`B4lNCWuq0)f>ig*!j)l^-m#>??a8h2;Y)b+E{dXI8pyA*6a{@tV7U5B=^ zc>Te#;oj6cYQJo4ZG+d_rxjCIjom{Fi`-cm^SK&lmmMWkl+^UHxu%`v#b0_o!rM8W z?Rj@(c;~RUm1UA}DjCACRE(b?;u7QlYelI7oo0vK+uN=Cl(xOke&#!NwY|RzBeq~f zu|^JBbw3P}5T#?|8Ud__W=O&B9ytsk+k7=GsV~CIi#8V=y@hdYb zEY*r9gtZjW(TLU=c9^5uS(=)9dfFq5$z!XbrK+OKVzYQWt}i8xt%f=2GI-36J0Vd+ zlEzj;B1sKQ61*}-%IeIdA9<3z!^_h}9MN+Y-q5m!Q}r;?hJODrby8nZMkQHXzGPZ!U=%zSQyQxGZgB z&(_1<&iAqs^yVuSk*XB^L^vcGSHC1uwD}&Wyr<1B6<3va0s~O~gq0+D3}dOIX=a() zNZ^HIk)~)+Wbv=24NA|Yg?_2lB_T_je_yHhq~5kY2wQ%zE*6Encz`G7Lr_%aoow>A zG#8ZzEp7oxG+zQ!fyc_Go_$QF*_rk!YCT0+nZjhTz{n7;qvJKqSU^q9xfi!S?03zQ zrkm}SlU)5oWCQ74SSS3QQF&9E0Rg#Y{{Yu8NGdqjBOna_0D`?|gJW(wiN!rWHJ+xX zMS==M$WlE^$teL=2vVubR7eVhux4UxIrrngYz1SlF<6!L7clYRPm9*I{(U;Ur_Bdj zFDzgB)4-76WSj$uQ9viiFT zu&b-`SdP1<+}LWl@wrah$nG?!n<|u()Y4$_@jVSeIT>nV$K#*9KI83srG&hjv9iw@ zbTiBdWTH5K4l)nL;v(uKU@4_T1J+r6+`X&c`FisAoq3wpOG&4L!ne16*$O_FX=O@P zD?q5MLmuMDpd&qb{{So>njL@fJGJ*78@4etbUj(!7>XUEyZcWQg{jJKp0%l>%h6>v z)@GtQXQ-;pb(JPwm_C0QMNIi8fUQ+1o_bj5>LQPAxyn99=F5HJ@)nb4niFqw6awiJ zvbT(jjZGV>mR&S6bn+w0G9xgu?sY@H+C?d}rl+gS>d%Nnv6UCtvCMDi** zqO65HMo7!B+d7*IE@Kys&F#$2+uj>%IYsO$t_4OYrT+lSao~{Zq(oHK5Z;y2 z7}x{(9@RGc%j6Qg!(pgbjl?_$6Y=7lPp9YA7nJ$EKvT-wj+0D_d2&twuAJ9^{heX{ z?d8owtvnxWt*1efzYz?{C4(-c{vfP~><6fGYZ3Jx{rl%*Fou_Z+nEJHrOZTA&b|C- zcya2#)oyBzM|I_G%~F;B0CD65Q{|_HMo(Q0tC%tcG15sR(-AwIrX))dc4m2yHbUMq zSM}WLU~GNw_twT^S6%wVMhPqaGYt(fPmiaEDsxCybIW(-cvjD>Iv{>^i({OOXWza2Io100QAkEAkWG6_!{lnGY{d%^A| z)orp}@~+i!70&T?g=Z+i#ccL=R>8%r zE~RCeq(Z(kDfnX0?W0$7lB}ahC#u!{Nvt9H^R%7XD0TIxU{r>cV=U38CSfcwOy*w* zk=P-P*Y_>@k%H>N-ems(l4RrT{{SUFZ&|ZrR=l^)YJScK{Db|Tw~F`~CZFaHf|in+ zX$&79x9Zfi8cYjGG}w61%F^muMKZWPRVw37kaW2OEz4;lPbojcPv*TEZWJQfU1)Wa z_KgqzT7KTCFXtAA`G4}z#~G(9@;|wJyt|pDUct{Svk1!QrV?0QH6=y3`k#1H&a`fP z=ba*iZnqzuBqF~qzMj2_3_XGNCsewW@@~&hkop*CE5)hmXiuL-UY4_~@mt5Gsrwqg zaOL*C_NVMR-pRvl-kqTDT*k+x*_F8%Hq3i>sB+o71`o3LPhrlu%6O&8O*IzYr>|PRVoRt3jO{)#`iN} z-1crs*|$k{j!n3;N$uy3dF<10x~yX1E-x*}oGHd-b5mu5$y`y|cJ*xqP1S>&>5&sN6fEv-k}j0O2xqIEuW5OuJ__ zmafCAB|Q`nL<#p+!)V+2fdR&sq>}=S)`mx0I2JJhFPmrJaNx8MJ)_PP&$9X_iQqDtCa8lC{(q2_@qy%g=68xqGo@Y;gU7cw<$KY~BE{L;GMVXGqN0*2 zS=n_*Q!J?>#`x(5tzzpjja(xE$(H$QH*bB zRm+h&Z&&v|8IeG-8bdOQnXW0Qf)orN>1nQ(89iFZchFCV?CLr3`-YD-L4~Kt(^TLo z-M+^Ik;rbG;$o8vRVzjxZvCx5otVgcUQy%>`n|<|`!>@TI9+WvS4`=maOt3hiG|(4 z@S);75VUy3NmA^jY6SGJ-Bh@-=g4KT-38c&CK5!%_*TW|ltz(M1<+BvM>@MnU3DbT zE~`-#Rc(^3rF@PyAL2BQvQ;fzU!9mwi>Z>EL=k1{=8P&Lsr|TsgrP3R3zkM}n^bt2M^2K(Ur)KJvb3^AMN@{U zik^(kQ4J+UMWc!3St;tEsgANOAV`TcW}G3n38&b)*Tj#SP1lO6;mXdHsAbTnxC%B$ z6Q~uXcr7|N@Gjxru6GEo*4)~#P|QGfGz5(WSUS>-11XN5E`)BaS>WFFzIZE}B|aVU z^iVAHw255}1ubG%)+K!e(V7Z)ctFTfNi_jrIWo4%W#Fdjmk@-wn#4>AaYBHA&c%2x zqN7bgAk>Ob^)GvRtefC6G@n%^vdI}GS6+ZaNv#ObpkPp|HlR3hZrIi7H&kQ(;d59W zr?&EVDvU1bq^4EuAB>&fl&6ZP2c4dxf}#w*OR9To?8FrkJZ1-}jT{IvaFIGKstXG~ zMckv7TiXs$vc7^tFlIZyD03W;!}QnaW7Bc_i+BjJF(XUM7 zY#cOkQ{Z>QV`@I>chq|nfYc2cYCPf zedBAlR9kED8LIBq04R>$bQGRw<0~6Us#N_snl-cBU2bu2a$ed+;?Hgd>1!As4f&1r z{avEan55KNNnJ<uVx`U1<}2x_vNZHPZ`hPE$M^fEA4^Or>NXzy zpsBTG6@JvEks}o`Ni@n?VwGwU;HZvUs0PzVJG zLTFhHRD$ibES@dfO6sx4XLU?V0*bY*(lrXrZiI!CQ%J;7wZ?VzM7@CXPg7Kj;it<* z1d>-qgG~-HiAsp8DM9qEQb4v)pvkKDK3;v#9KA@92?X1cH2(k-G5jt454WprN|7p+ zL-ggwpWM#^+`FUj;V5t^0NK4WN_2G zVo`DWSUCc1=5g;STGctvz%OAI`pTCn; z3{`zC+ACKsmj3`rIEkQW$yOil+CW@9T4#!)H$*7Nz^ed31bY|qN+<4p%7UQZkx%)w zpUnRNgQq!i7~cDs0*Xi{fPgvo)5 zP&|G$K+~znTGW^INO6fskwZlsRItYqg*mF~ORbx8X9!@9Dk7;Q02pCO zCZoubNk5PPx)|mc_w(OM@^12wZXLAicSI4?g$jTL9jb~H1FN~2nZ8wda$Hf82tQ#? z2tQx*3H2Y>+^(PvUX|)(whAIp4h#PPgQV~r5r41epZOpBZ`;0L`Sh`f1bU9URV%?G z^Ypp;kM)PW*H;0ayh5-vr%(4k-Fm_JIVwYAZ>WvG9@ua9A}?Jh{GCx2lM_!akM8N+ zRsCh~%i%6xZLyB8c-H)-mp=JXHBK>(53#n54lH6}hM^vxBNS3UnYaaILu-qbQqZ(O zQxJoWH8M%ZNugBiy z?mQJf;K=4MQ08hn>jb->E3~7^Qd4GRTFmAaj&z}lSQZJZ9a4FtiOZ$D5cc5O{UtTvx1~_tv@#d&{)3 z{TtGq!`*p&WHe+k9@5F-u`pIuWpeobzuI|y*;|apQsd~dRrNUv`fNi*3~*Ca zO!7Dh8?g#g-aX8Amr_|l;@&K5V^8C7r%Lf36Hsv+c#f1>M3dcHK`go=c@;}zv=RYq zkT5fn2h4S?hsE8q+PL40{Q=imEd74Y`L+DyXWbt(es%X8(oKlp+e2b+tVSjFw^d_~ zaOSrkRPC&G$lRE{k+vvepUbu2#^uu!1tv;!JtgAW7HbP`U5a|`woo+J0O^hAns+ix z?;J@KZ6(D1A-HIfH6%)o3bjhvcLt8;>wjn$>t~T+x6)ab6oo*HBe^cZ)*lTb@pX4d zWCSwlA_r}M!g%^tEvmTgyrtNAYsPBX zlHNZhm=8%?HRQdG9TcSi^a?NqDNfPA3Jw^@MKGq8c4j5q)cwAHZE;%U^;y3QriZS( zLv{ZEC;tGHxO~TGe=q+4m*3xykNMuZ-t*(L5PV?o%#}4(cdKf8&Z41nxt*6u*mYZZ z<)@^A8hmEn-%;W7*k+)tmnS7*Wxk8EDT;tNEr32XsbT>HYF#CXp~yO`PK~b`PYxk7 z>UB{~M3bcP8mp+SNC8PY1r=yI+0Xe?cAsbVAH)16&hLHe{*n9t0OKEM_h-Zo?BB;5 zxiQl3z3K6zv^O_b<9hK#FT8T^+vrQ03 zkt?R5sYYZqBOekm$Cr@c3uW-c(%Cf z{{YO@>L2623WXt!=_|X_pq9FJsE#=xh92J8(jbZ!jpUQfC4)NLMPOJJCd`%#f3wt# z-4FQV`F)i?v!yWwHrt6}N9Z3ajw8>@(0{SjS#&l!uP5^hu3+&|8hAcn{{S^?tT_dw zul_NW!3;hrsajaxPqfK-s*(uf*BaC&g_U1eD#}YUL1tNd1&;y1)=`|~lgIfUpQL^R zQE1@X(~eJt{JiVs$IGOq%*N+8=I`yjjewSiGrl`pvOk&EU2F(H%)13;wb&+Q}Ejz>gC7x15^ek%2T}xj_H}s{oK!j!G*QA&UT!k*sVG#p8w$slxfyTkcjZQk(N zoh41%U5nYZd*iD2o?E^4;lfeUb{<99~l$k+Uu?Q^xUbz6Taw<#m)9gj%cw=E4MHMuIy`hS6}_$|3MZDvTZ z*y`!3swf>6T7+~e+KsJNHB)LUkfX$7Km{t^TB(stSJ#hLV{+N?6x14>7&SkK)6+jQ z^67)6f0cJmbjIZET;E#uPsrK|KJD(T_j`5*6LEE(%G`Kd*J^Gm>g9Tt>4+*osZeOiwlohaV;(v_%k#0Hqi2AZ{M&kyx|y?GUc$o17jKq){mPe1VabWFEe z_ZA1{PszT+hvT1Me3t88`|2K^_~X{Qx1lLMKJ35tUb1~XkKeUjhllx#nC@QP*ju)z zBSX6P!{;&inpzyi677n}Xz6jaRV1ZaC)(}zNUlDvbTJ78gINfXI(G0{GgC+|Np>_L zC^R52hj5z3?cM04le$^ z4axEcqxQ$de}&uUu6wI5p4?UYYq7fnBfIE^8*YDfGbvh_ib|f{-&k$KxO4aqJan&B zM6^)OU6x%%PrD@7^UVloBZ?tSbPG}oEix2oT!L5{(wHEgw9(q4F&8FQsMCS~rVUBS zKar{8MmqXKZ!}7M$y-Mj=D^TRHWjERPvO}mt*@Sq*B4+)4_F_n8yO$qpo<5ZH%{X)r-_bs{%|z*oICv6kM92hzQhp(d>G|WKXZc+2 z?Z}@#{xntMHswBJGey|ZRO9fEmWLS@PO=;>WK-kbx#?$t#GKow>U@YL|H3iZ3Td$T@LZ%wzk zDYjPDZI`(zcJ*?MuHMK{W^!~hQB_2yqLU4f+gsBORk%NKqNa*^DOPlin5%k1BDcHd z21yrhogAtzszy(pDm4e3y_Wrc1>!=Qy=lxz`DRB8-DlGGqIX+Rt1 zCFU#F+M9h~uv@Y4mWrw3I05G>f{fvKF{zD72oz(Z57PUlzi@o_*;#lfMMVZ@Zf@KZ zRdQ8U!yQHnhht>tP1}xwzZs3LY<5yyWG0m=AV+9wH4}Rfzn7ts8@tqXq=jEqK@=52 zFmftD@&`OP^mWSq7`>0fo5cM>Dk>EAQmTB`g0(aUhy$yEyDp;5q#J?twfP#q!`P?K z9Z3|(J!3)1c9mEKP$K}1E%nq%<+XlCzh(~F++szeP7phQfZ#Epe(wySStcRKA;G)k@N=V@%=r}*M)fX;ge1S zu1bq{msz?1RFFY(Pb{v-1`WMi7(AXKB`afC;V4Mywc6%?Ye28S|vxH#Qj%RNn$@3`mMt-ake+r z?Fep9V%6BQpHjnf$LCicOM8N6C;f9dh+|LHLFec6Y5e+vD9g^g(!l4(fqvRrN6{|L zM9Dkq)ItR@om#bADLjE?{{RqvhwJW9vu#l*QNJGH8c4^P{VE|R(onS5fX)XiH&s<$IiHBkiwjz!7;0AcLz#-~nm ztM+uh06Yf+C#&@9eY-aNo2`1vh+yjXA7E4Aw%!8^naAX}6q}DRSoE}5y|;qdJ9{0N z-5dV^bm#K55mRHa7`jPnDrREr(8n9fF;{2hEADLOz49wdhK49EBzJTK$UEACFbemO z38`fYpz$;Z=*Qe|yeBRF-#v=<%XHp0Cf+w)+ibMAwXh~NhH)LVPdt}$N*NZ~6)RDp z-dANv)~2GKzFuv(ah>P6XTj8MEUwed97)=_orjFgVRprIR5+R%9F+jU?krvxJ+}8Q z8!H@?xr|kHJau^Nf=LtW0VI5zS#Fi6i_ ze)p5ymG^_(erD&Wd0x|HhV;M|%Gs5nfJ1JOkc^6o+L|)tg#xYW2p4y`rlhU-_nfGT zIM$K6vUpW#;u0vfAz_k~M9iUO3(`F3Z!L|x&klwH7-_$uN2FglTC`kKh z*17wyP|VD(PN5wz9-!7w3TPUD0D!0I^%l3WGa5XU{v-Y#gQm1m^68+{v8PF#eXihq}2BsbvEieY6g{2q(-1B zfDal_an1ST-otRm5Ab#EJ+$-x054e-At%xp*n%7eQip=9gcT#7&*R>K!JyAtC<&?c z>jB5(U5AbXa-hrQZ7b#^>+p!21*iW2Q-4tW``JjysEmEM>&k17PCa|qJ$qf!4;M=hrx>G48=ynN>obZ0y>Ax`Ss1#GZZBEJT1%40Y-pXNO$QDui%p;sW-$ zce(!n0cW`9=tsMV(X|5@ui4g(MJRmwmaP;hsT!zA#(@-Ss0GdMWl^h9H#g*;&%L3c zWdLdUb)vaL>DDKhGZSV28*rqOEJ6I(aqq=|W;LZcwJXGR*V$vWf53WIwyjMVa-O9Y zbwWahAn{-eK)n1J^dA#xl4x5dCebL#?iEz91Qxe~2Zo_2b@z zaq1+-K3L<|i9Tnni$jm7;8MYOBLSDjKzPF_0a$8nWS&^t{5{nYD*pgvzq9;3ShJc{ z$)NM}>myK57c6LLL%p>piF8I3f`TBn0_*j^yNIDQ{V|@ZNhX!+f@AS|!Zj=h{Zo}| z3!Nucf*3|G{wLqOIBG|RG1jwM>OD@5G^LI>sbW|aS&L}&>MiIDK^N9Sk5RqHz4nCd z00Y;lQ}gQGzmjARAJ5&ss#pZ;F39_VF@;)9I46KaxlZ1})=|?3v20sCfs;^3D-buW182qN(o61}7 zFi!W|RqNQot>O5}Bxh!(qa1O?-z5O6{uIV_5IT*%@qYXJYwa%4w(Oko%0Jef();zJ z+SP3|q-xJCg)=4jJeBXwdr>25jy*WKY&@N=G z6p}|ou~Ms@4+}Bzp)MF|9_1gr^eZpjAD^7u7+c8Dq-HY743~E$jNTPhr?`|n#iTwr zhS8&d5Hm6Fw6{@nwTIML$7yRNgpx#{BAE-_%(G87h622o6QdTWP_aiEX{>tO9+Iw} zXO2iIvbhQc4<=TYL-w_BO(aOwGh_bUiKnKLNPLkP*$qr_g>{17taNm_J|s)w#=(Y@ z#1#jFaLHUSzz2mu>LzQgx=AB3+gx1Rgg!KEbT+L$<~;`ymKug*^=SV2V_VO9GEv799(=3R1c9zsU zhY&CYczNTc5PcMqTEr{h291eu0bpp!6;_}&njiGQ6X;@YN~&6K<8ntukW^W#{{VS(h4fgZ-G!R`6;(SN^dzxItp5*_i-J(AfeXeXfFJ9ao?soS+Oyl*75>m0Iu%F7cTe}Ytw7}A(&(crO+hSpT zVYWdH%y%5Xwgwmspm;m946XHBJ@Jq!N#RhfX(JE|Miy46j#6HCE7DNIkE+AvbCTjH z*B?I3&DXH?$bk_Ttno8qChrAy+DxXnVwVUj6)iljYEDUR^LWp8mDn`hO*W{#%T zX|Z=_ILg{ie-ubV1#JKd7wOC{h~M?V7rtJc9IO zWqPilWkFb;K?ysi=--aD3dDaD??2TW34rRC)C?s zO!A0brj6&dQsE_-DgU zbYpyRyoq0drLB^x2?DW(RT2(UfzKmB9M%$9+_6hJw>=UOOd~96$11}LbB67%Iy&Uo z;g@*bZEh|+6q4@STapUKtgO27tUE_@DN-7l2EALK%+HSfC$@0k6gyXEZC#(%9dW-p z*Lwc|CXbSRYuVf3W9wXJL~cF1+4+8!gSL0}Ga;1C;c2!f$W5b+lkcgXEaq+<=FnDE zQl(u)%aU!P-e_Qr6>Z2>M2$|BRbI%^X+Vg8#-fx^p;sB}FcA?g)lwrGAkYI4q%CxV zsBqQVN0}7BY7VF``4{$oVCTP=&+{|s%D3Gu)g2GH`%WH+rru3a2-!3po7J7QlI*Uv zrKMJxF)>ru;OH{5V<`vQQ{^&sl^Rw`$z+l<=lg4GeWK>=8kZ6WQaF}WC>77C3qViI zRKu>rz@)b~uH$k8|Sc(B{1QjHx zlsQvh30Lj?Ne}Gqr%Dwo4{4(ZE&EkR56E;re=pkYgVFn&?DjaYkUXx4T1D|lx&BquFfipOn?zJ3~(nx392s-GExo@iuoEKi%06}I4(;*TtT z7(Pl^j_P@lObYejwVDTf6kyomNXY*HSNXcJTA!3(B|CGfHpbiTp7`G#iH@(^nt2O!;_J?tr}zQ4djxFlnf{(~+q)5h z#&$*@dS`YT=C+PHrim-|u<2dVCQh@zch(EdUk2vgIDg?-Ts%tz>r*q+Jp}466i07r z6%ZE{u96tkl0I4#0J@J8z#VEs2+VHoVg=b%atTtZap&P){9F&9yhm(o)SuG;Iw{Jw-#bHhaY)oh%r8Y5*F2u`5CKC;mE> z{QUm_E}v2QcLx*-Kbun>ZSDM!K0|bOO@B3i=5^KGkDjO5JNM+rXY~fu>J0W?wrH@u znYnt~ZtrZJPQu7l*Gcvm4feQw;{$EV2#hi2Ad0#uL)25l9EfZtrqgPypm>rqSI-RN zKbbi=B-4q@*AdAilQJj50X{~7K&?GI@#WpZr>)Ha2a(Sw{kS$i?TGgFIz!if_t(1U zkO3rs03?!Z034D@`T_6Vd!TpZ9?IQ)pV3{-*1dVZa@}FryX&iW-qhGVkGFEQIDG#A zU+;axwlcWQpS`g;3NZB))!S!q&re$)qEvGRmySd%jFS2$n$qGp>*AFqm3t0I>S z!C6>Fv4(djh1`V<`n)8eFHViFt*&mbZ0&8MCg$hDR9g2PL};yOJF2QHKx$YVSF1k$ zR{fFN{p;~F8S+!Ovzy|!qvZbpX?I7+4yM{$@|$Q=}EO& z+#2*nE(0+f)$LW3Gv(%5iI}RQ8zr^PrL~kBg`tCV@KvWnA&{ifR#%MIDA8*Wv{gPE z#>t9M7hTJ5EzI9XIF`vc-hXTOc`+0sN{D5QxPy${Xo?OIpzP6%n2oG(JRn z@aT=;@&5qK-F_5&%j>=4@vo@pJJy@Jde^_YhFql&x(?xYgW|_Rdr1)u8`_j1Og;gLQb~eHAz6mfbjqd z1J#~LKv}|fg;}dE{VkNeaA!4Yq_W?@mMJ7GL(H) zPl=>mba85`6$OAQS!qgeV?$7AY699Yn&vW8#~h3S zUKAK=R04aoaRB4eog4`2B8qCXS$sx1x_Ig-=88cOeF>r5DYx#pD6GelFYc89(!PCI z)kqAuKkBDK1{Ef$r&-{Ui&W(0f3#-PDoCihsq{MsNWuL!;G3Rr?#)9=AN6_lpvJsD zT|dWOka(fVQ_WWM&0L6}X@)pfouQB!Da$H_)omiuHSSHo_gZRN3R0ip>%eL?B#IhS z=f|iy4TskG{pGheo_}dzW!~6Lsh+^nWLeoiifwG=CN7gPfX`7yQ5`<>qmn#LCyJXX z6>L=P5RxAolEp!uZ7d7aQ_y2L^7ZPfg+lmxfG!&Zim(J$zE~$BhxT->qr>9y*_rY% z)2ua_^^&(W_cUx{&Pp+~7{rxfK5A-edVGE|mI%-VjS>I|y~{LOMkKK$oCgZtTEhh-0D3L|02sb5Z=aDr3j58vk7(t4 zH?X1kE7W-0#>T?uFdKTO7uVRWg}yVj`>MYqxvKHl(H&Mz(u$He<&twYw(%80eVt0N z$pwPz3qOx3s}K|e8YuG_)ImAO6zHxuEA^ql@QiCp3Y|g0q4TDlS>O#ldb0@nXZe}t zerJ!JUoU<=?y7CYN7E^_HzrGKZa$sD=QAmZ`0-WKeG8Y_+h1jFd9nC?(ABhCd+!#4 zf|C+!eAO~i(!nIrD{;Xp{X)IU&$&${4|0O?vmmWhX#i50;1{@)+*BEo;q0UERx3!5 zBKDH1fU}a-C5dXeIi*b$1p!CV6KW@5uF}{L_jWgK*LRjbrnYTQX4P!zOc*V>+i~nn zRW|X(VKCUUHa4?v)8`u)4?2$h=NF?3mw!=be59VAtME2Ug4`OH2^@b07j#L zb6%sZ;?fy6MwV+mOkxBTb6DsIRR}Anve1&R{M^1^RAp+T%w;5} z>P)pxR~vPpsjjW*KD&3VE#Z&uVrbZnT2Q;2kPZEUr&JU335{x^>Owxk)jzc7pa(HD zjd``at{z{bg^3&i3P?&Q9^9u4umPxfa9Nn5Vk}EX<&a%P z&Va|;duZ2l9Sth1KjSC;ROpPj8<#3d?VC`t$Id>He1xJ+NswrzL=~@Wp$qJP>%<hNK~P# z0C?(EBoy>)QlgkNH5euQ)ozkP}`Z8!({zZG_k8KBc%`KIq0mMU<8V8wKZ*dH(A~mUzr)tL|IpjSF+vXj8>>C+3j=Zu{{REpa6zw1>4JL99^=%mSbbPnDIevRHKh>VS)>yP1TA4r~03A=& z{{TlIeGfd3&$`run&*!0b%J;z$9Ik z-oeLEJAnK@RV6>;Jr;9Xfi~K{UqpxYv;P3A?Z;LB0Fi`A@pG!RH0!5pZ!ZxZh{$fo zt!5-Q5(2|bf%Or7IJ^flmG?uK$N;Ijhv&l1G5LD+0i%THZf7BQ&ky~g$I%|n$ura# znTcT`XHo*FYYU&H+fer{St_g=fbz#fI0C45tt!9qT?e^k;FD!-YZ#U|6;{YeEDe`)U8UBRB&b(?o5P}sLz-V=Q7yuKH5 z>@C4TRgQ*CerkrJ&qFv2BbXAN@qc6IJMK>AZeljppHT(X(Go^0tmtuIy@2 zDzD_0^37*^YNuq>WbwHzm#}vgc-i+UTnT4#p;7BCw#Ql^7JodgJf9{@+FI zPq^IM?d&|sZM=Txl_Oi*f9$3*!yL}Ybv;6}==g~2^(Q z#~+aRXI`>#%e+=m`jv4e2<{FsH)Y9976!8LvNQnB2uloM|!iTR{H0y<|SlDvJgtrTR zMw@<>vEt{C@%OWX^XuGeULAOX0VC)*zXXH$zx4;*di6T@8dZgfus>g|{=d_k`>-_! z0=zobYm<*orL@9IT6Gk(@QPt9a#X-%T8hSzjG)$oDWqqmNC4dP??=|T>toZX z`mUs}3M^Oga(~2Jk#F_5_wTolUh5`?a&-`)Zom(xKTs{mzqd49=;TKflFw1L4P zh`041kMXeP*Y`~=Ubj)gx$8UJLXzu=RpgRAD#PwIMgwYikM1OF4VBG<8;^IWpeK!g z*z4X^>NH6tzGg;`_8@uKyvT>fg;l(I$TLfK7Dc-eb8Zj4YR4Zh&#!go6L?~fq42Xx zkhud(ymm6EVavL+az6n3s036TP<8K}I^u^*07-2&)&~yCYXNWQedtsQ^{%CO zgHgRzX-Q`*uKN03B{%)%)=H?TqFU6H{mJqtv8%S-elHtIhuV1T z99xpIY_4B%tjcLKISs{`H86PS*cwPuDHRcmhQxk4&i6GYN2)h>Rd(icsk7ZHO~2`IIjyahZK;-}#C9y=UBe|l z>4P7UhJz`prg~^<>nW zsZdpbAku&XzVd%`%P)TK?Rke~->tUZVT}?irM-$viwoFOK!uqQ)*F}#0IU?G%Eetn z0LM1-&S!Jj*)ki7JOw>wC#<&TUtw|kZj&N0bo*0e(B`Ga*5vZJdFnG8%YJU`-r>n- zw^retQ=ImHDN|DwEi6qO2pQ)dXgt$=FH+55vW6cHBm^Qe7?DL@C88AdyE7=2)Y4H_r=enVUA>&5DRLFg$!hHVtmz? zg=hi5I;sbM%YlmQzR+1{Wt$;cyXkQ;RZzc>!g3fjk{Xy`kHRNe9dD~!Mi}~l;?n;B zEXG%OO(Rfa5-mO;bjT~GfgAQd2R@q-mBpSIJ0YHI;NCEM`W6iY+v+Bxye&%1;SE@!t23p}`H zeSN8^D3T&A5VC;UwTA+Opk@@7cqNXDK&f?>L>J{xcQ zP>D=-(a4HV;?f4DBsZBE$DqY}Qxim!ZSl)&s~o8uiYi;Y8lk>O6mMcNea3~B?&H-amxTG<(Mp7ZgSmS>UW-H zg%URL9nNA}42am02O2lUUW^5tS1EOKa!tLfq>QK;i_LU?7X!#hO$bnE)C5wrTlG>c zPWjw4xhjK8Q9ctTUTY0H);So=O?uS8k6Hv`b!mL5sxn-oEx`ivcGzERJjRz45=&(D zC2*}(K+4Q8s#u;B$5L+~G*WNZ_V;?@V{fjssRB5gQq{i@)v0QyQ4GGFJniglMB8nt zcQ(=*F}n)|lHZt2Rb2H|7;F>APMc@s-(6Q#tdi8!?fL52GV_BiQLfY0cX!xGW{K@e(`Z8J-glj}5{_6oyD74Z7at ztv;W3+0jHhbWe2*Oh`ybUju!!b_I*TSw+Tz@v4`OWD&G%pr-B_3c8uAtLDaJ>znOq z>Z_ysnI1J(K{RjT2X_eWZY6oH86{#79LE_|-1NCVJBsQO zIquXzY5=rZ6@yd{&o+TDG_>=>4Nf|2nXkjv2ABAzI=(MBpBGe9$4v0hK_iG&V-)5l zE|30lG@7|B5f8ir9s+t#WnYU*aKX2Gqj)DYO;MNBt_3H2ezQf|i_4-LW(S-t+6diLiUGbM>`G zB z?75!!m|>m6Sj9jlA+bZ-SyWP$1zJO@hgPPjBdK!3nt7?MqT8+Z@2a)%!U<%B+1N-< zmyy;;mQa8&*32D>3dqbd=OXRI1AAS$7$(FK%R#{zF-1bsE`%>7^7=RYn#tD59l{$j>AE z#d3`4JWC{gCR%urkQF)zjeQ`3!Giw)U(dOcFf`*oKVGKWbPaA5UaNu+uS~2iZl=U@ z{=XmZ9^C0bYE&?w;n%Fz`u_lj^tT*)_f`Q^W2FM0_v+VzMgIVbQ5$}L%}73{`k!o{ z_bLxfE!6=YC?NTCa61u%uqli8cIZ9!d0kId6-D&4Wa_VRC~f^Buv>`Hyr9C(bLRv4;i zHuXhaB=zQ+8N~kE1V<&SX(Y!py*|)@AI_a<5F(ofg+TuRjaT-OS`U{-x4kiV%;#n9 z&yqVUC6?~rjXyAViR?bH>}(|!Zr|TsdD;6D54Lf=htS=}x2keb?w+^#0n__}2%es$ z=cH_vEOeR7GfhQP9MC3$4G<-gmGIG927?U5oO!NjeJf8spYd5|@yTFK2q2U2fl4+# zIB`-aKqIY+J{W((lBVlUncMwo^5dg^MfZ-jO=sX-i3QsgRe@l<1Tk}Fr~aTbi(CAEHDSDrd$pmGso@yx#IdkV?3Is zyYMT=^x1`RkQabC$CfAvI5~^|019dNsSD7>l=!jpFB2w08mTFTW)tJxIG$Qq%e5Ub zt@#N?($%>~;Hn~|W!Zw*mW;O`(XEs<38#oWyoNe=_kP?%Xx*wo0-h7(dj4LWO{M<; zg)4kb$l#YNH^z^alVj?rW|~Q8F`pl^c+nfVf;xJN+;@J=ie(M^he1Rav2ZW$rdx(w z+NnY_-als!A3nA8J9uChbv$ucoN)Bd?EZA=CAWX!ML!8~5-(nCkB472>T77W?khI< zcs3tTM6_7!eB;R-TC$pX zD<35eLXaf#ELSZ9K(8i~sDr>%ohnTMHKC?>@u=%k2yKhoc(L5a;p(Ui3gnK~AW(rq zz=A45_W@IDJB#_YQD!=$vT@V6^l*jPMv#oYa4vbwkA_TJn*P2GmOuqgH}_>TkK z7~k&p8?3UOPX%OIiShY*Xe#pfcUqiERoY<%n8?9oSfQ3c-~vqr2x`7njua3m7_${q zq%k6@u_H*P>R6-DY61epifBRHwbW=>lA#na8reb;5x4$S_K(c%+l1LaGk!Wj@&5q% zc5Mug_m66PD)_^=@Z0xxe3a~bZg(G-#nb%H>^;)^D-*ip^+GUpA?qcv|yLK;g;Av>)js{=%9d3|_q${pF zf!g3u41OGWV~1S#H}iG)*|j#lV{>G7XLnBc+)`KLw%$8!Y+Bvbx~uAHY3T90Z)@U{ zvK1?Hxmuc)5Q(LyrBqjvS>lR09clGTsZd14i%<^V+wo8e0&`4!=sLW6X_7#nRS;h` zJ|Izy*Rr_bfOEs8Cc^$|UmH6%w>^c~cuv>OZjGalj;nfYS{<>st1}xrB_2kH37Xp( z+30tTRta|=)!Z3MOny!pddi5Ys;b~oE3DDGZEm7q%qyo=0XPks0=1<X;D#cd?UWr`tPQZ+k3{t=x{cp}i`f>p4L{iTvL z@vDBbk=q&vtDi!2iYWXDG4-F$Qw}+$s*AF7&h=wXeB7I$UtO_Q9vEE7I%KZ%XL;$ zWp7Qbn1-|DR>$lv&+R;3>D`#>x_zyZeuG7F&?M>0w zU8PgEpZm9$Fk)L3iO5mqcJ5}6a&7ATV z?hQh`apX>V^*~S~cL9{CqMU=}>z)+;eF-$XQY31DO^x}3Nl;S}8GLs8r-3Ud-&C@S zdXbS>aurK62a!KQ$fQ^RN4DNJEVZLDeVC^Y z@K>d#J7(0N$fxj6n2<*{M;SD=YuGz(rzJ-fE0z?L30EZ4`7B*i#2R;y%J7q=3J@<* z;*Bb7ZLw28_yhKF9-L2JV;_49xwrr;9%?urm)pbh=u_LfdXlybWi=&F%Nj$M+_jY$ z`Lg@VZ{soJ+$fdm3OZEHEez=T z;CIxq%N>M;{Q!nj?b8?~<46{vX@=pB1IT`PBRw=-zqD(Sk~pdSvrqO1nXP)Ch}tzz zLHANre5jJWU|Oi+sLkP5?Ov9cukhLmnu>U95}v7!nG##bSX-L_d}Gvri+=IOjr%=K z2lDhic+W;Zthx?zxykdzHF|pdhg_ng%F1i1RenWBO^e#Xy&omJsp#tRH4|3H9d;gq zj-wYfU1ely+Tt*P&EwF>gs3V_q5(kaL1iBvbo!j&e7|YwfjL^Gf2Ht@H;}F~oZay3W!^xVT+G|mTsjt43-ul8WYU(kuNgBu*3&+5{!8o{zCxXb#DmBaxm*I`L{Is9- zQ1nf0EYZt(;k5^XzJ|Z3qLd*202M(L=;M4&`5W?wef<9F?~lEc^9Qy*NA*0|+=Wd% zyN5fu_RiVe)!6Q;mvZB2DKVLtpE*e;#@&%E6l6K_)#8qZ5J*t9VH7eEa~w2rB~+Fz zfhYn>R-MWVP~}1O=~VMv&_K>8K-EN0cw|%nO$G@k?d$2i*%MY_w=`K=V^>>6Tle$H z6d0O{pR$!Gs0~&Z6_KXBGUMTiMEcoY7mRk?_@0_WGz`hSO@?D53+T&*E+pzfB&zGL+TY3M-Udin=vFq_tS zvo+f%c3135oUKzatA}k-Z(L-R5u(!l?Pk}gG|tt5BU{N!Qv*thf=?hpYuHJ33$ojW zF}vzu7gaq^l`H3*;~45}w3_*ECTM{+tspcjsc0~1LZx`;NvX#gbzhx(@%yTK3*^>s zx%;!dGruirJvt?~O2K&Qf`p0PeTfuKf8C;!LS^R6KrK3zHbFeYrWGgq8S@W43 z%?%Y4aMvw0G*K$4uH#2|THV(1^R7)n^iUEZQ`)FN8k#zmr+ZZNS-a1>PV!i8SFH9T zRF*gq78paQV3If*rnz*h74fE$6fdbEMhH|+!Lmj3XBLzSUK#1LbomvIXnE7tYb2G8 zcKyYAsFbv6c>}f2=|1VSXg61yXcJS=56IW;Kgzu**h-720%!FY9QlaOe?LwmqwVBt zt12Bt*Z|ypcn1Ffq@U^ieV=qT`Sr_6f$M7$c^|1u0zpzq{YpREpMLAZu43wh0!h|I zfcmKyvA?F_f8IUs&xc;eTyCXeJy@X zz_|nK!MEbx)712=V!7+Jx|>@`{VuFW3;j*LfxqHC`>z~u;q&V$47@F!2rM}l0QyK} zCjLbq(%$P(K(Aim$E?8!g?JhQ2PA@jv<1LC=^%bR(T<|Vy~F)f>r@o4Upe3SQPhh6 z0L?pkSTNDieJBZIs2x-}*Zo!iDu%FLNFQHe1sZ<5(+1*C@F=g_UOg1^QU3rMvCV(Q zBmV%8Ha^aXhCxy6;k~8V&^@|^P{XVAmN0}l+ z+%A&?IJAA{;me&!p62kLG3_H$vGV;|D5Mi!&QiGWf~e{D|=uES;aPE)Km zzsD`X{okzIdlsYaaQoJ;0ZFnlo3m`z6v_zlAO6XE;n_?77?C7ocB z8KqeSDebClmb~H47dx8>w+D6><(tE5863!BbMTWyt1e1Z3{)P{{qkFzci+2*vD;58 zrQO#iLv0K15!$Si_a&ve*)8laRoVoRrzISCX(&S=;ni?_t_tBEJbB5l$59 z=KCH=8=jYKhp8*Tutq*bJg)Yk-Nmvz}_h%krm-kj}pldF}Q`4 zs34!Gv-Urz%y?>VR?TiYq}}b-!M*uRH(>n_Y+F{6XX2grkK|Uh6Dj;*}W<+BR2KvanW-gDVjCjfSE0 zJRivSvcOZ&^|Ok4bs##)B$CehNpmT@V^pmqmykxWs>2)Dk^!>uVQ+g`LYjF4`+C+o z&XK&!QzbNY64TS@dFM)LUOIT>a+K{=BtfI4Gs$F97@lQZD| z0EALW9Qk3NH8lxa1kqC*Omrf`mP&bp3a6`M`jm|${4LMCRmKfK<6gBxljYMm(!}yb zhy|=q1YePG#`fpkOn`!Gf&Q%ZzPnNY{{T|I+aNBX{Q%X+C;hj*YXHzzzv25j_gv9Q z7aZ7+sj#^=u>SxN`MGpdk(KtNo9^ z7E@aFp}?O`rL~QtSpDN5&N!Z{2-|PtTWQxySnz+3Tmn2=|WFi zqx=PAi|6NQ*EKYLY;VLYoq5PSKY3S0H5Nl0)S{NT9weowYK(=!((;LZjpNjyHMg2= z7pfRjzxL37DskvbV;W1${H%_ek?znDOl6O0A7}08gnZQ46Rzv*ob)v8m9)8^?@B@u zXIzFKD_IpLQW31#3E=(;UCn{_(?~d4KA8eof}tNx8F@t~lz7Rtn$m4W+^K z4PH3!&#-*?96Q#{%6F2Fp}(^5;wKs|Es(rR^YIWoT71b*N)kb{v)v=Ka{YV#`KsSF zo0oQG_Z&Nn?B1l>UDdn#_hD^}epBadKS=PA?z}4MXkL&HX z22-N?(>dAu7pbXngQ_~~=U^F_e+yxF+S}Hw`#}t~9@bBV+{}Gaem_O#**087k;#Dx|~K zcK6Cm6nOluRT?Prv>gl9`3ec6iy;Q7TqR_a>D01Fi4q_Z1ee&a?=L9j{4;KHJ(n)|G!t_q`-VHph7%hsWj<~V65iN+XLryu3J zSsL}O`bLK{9Wd!B zZ@JfeiY?E?a9*uRD*}B?thQ)m3#=$6O2!&B@u(fBX-{`ZM7R%j)9`by&{c-%x4 zO1UZqm5{k)D-nEBvN#W?NU0-8(~4)*0bl3TQGYD9n?#8k1*v8*gbW^~NMQA-0YxZD z000i6MFi~RF+*2Njb^5(uEst(Nh&FF6xlV%ii~Y8Mu+%)Ol>I1(&M0)#i9p4ZziY} ze1hS1lwLP5S_he)Zt4(f2-0#-sU!AK4AY?<>@8_LdtC5awd4jmv@#^AF1V6ZSfpC4 zsTg3NroM?*`LMgB2aM^`O0y+@~P-6cXu_ltQYaJ%Xtii)`aSf(|{lfYCnRR z6wYhV+1C|Q*KQn!G($^Gkj?EwlAbD<>S$)BG`Osc^wJi8p^>Qg`mH%@Kic>1TYcRn2@qQdTTPBJS`(Ot1c zR@75hs=gg$b~5NxtBxa$x(N2mE>vhawCxaWx20|ODauN`ue)5p86&zhas6E0$?zqW zLEFo_Ea;4vF|47>?Hz{IvCi9*Sle378pSM!{lvSTG2tw_HTZj7;<1UR0NbfQsiY*T zfgbwXRr_{r$%)*!C)%}GI-!rv;VHwU-Di}LUkeTzc_)##4&KSe6w*kJ=`|^dOy*%t zJlNO1a>nh-d*?E2Jj2TEwOm?V((26trr$Kb*j-q&F>8wnfYlob8B8W9nokf#BbDx3 zY?cyVSzpsM=cJ zw^@GpWMGndSOG^B5W$n0H*#GP3F;M^UmZkm8_ho7i>Hn$E=YT#6o#!;lz@Cdcw|zi z2DJAaRha zBngQhdb#GRP{;h5=&H1pEc7~<3+cWSH_WBK2ugvu(Y(yU! zwR`~%pD;CIzi(Sge=kox|a1=dYm1)l=3% zjLXK7uiDEbQY3X69IGg|vF9xKTZB=IlUQ2pgOascAk$DPHGCqRYxC&yU@N$9yOeSt z(30-iX~dquCJJdNOzxXp@V3=x`hInRO%c7{Y9%&)wNZP;<5g=MK>IiV}Ei&uAF)G zC&Zd!jYWHD(@+{o{Dbrty}3T^iVt3t)npXwu)zNSy#D}S=zrdM_wK9V;)L{~I)A#A zY;UQu^ol1+FFkMW4HjVJt_c~?w>HOEKhrg|=&_|fpgb0Maupze%kdS`cJ zl(adT%E;x}eZiI5G#NRmX04>5$yUuzkAj{wq>?p;8gR}GtjFEmo5f(Fq(r27R;=Qc z`&OpDpmd>Wr{-Ay0Dym=_Sd5!{JZwgb$rL0<;PuYS$5tlaqLfr{lDB3oThszwqxA; zcVad#HM{l|R(=Xv_~~hPR^E!CKHjPkkF1&qp{kM?U8jvfSle#gZYP`wAVrYWR25bg z`)TFniurZ5EVD$BDKax@6!jqI{GXq%Lw+N3)Jw5&TZrvU^5Sz_8yy}By*7s8qob>V z@X_Y!A;ZZoG}D>o!c_guJZ1j?%IQ>17m^TU_T|dW1I)4`DN+M@Ff<2A^kN92@u96L z)uLo@nC+n;`haMD&>MO83=n&&BqqWcL36VeNg}j-}q6X#fI1{l8mRQ-sA(nyPvltb|yaV+zgA zYFb>{i|FK4ln|f*6-;Wa95DlxBvI#ZS(Qr)ap^s_fq1ShR==y**4*l1fMtMK6>FG6p^QHRJh=arEg~T?{CI>he4YuLJV)ua^)(1FOKU z_#^zab9p`0yLvPEhW7_bZO!+$dZW8HZ%OUXi@VRZu^nT$dn2uITe}a{8Lq%QL;brv_i#$`q*0ad)kRHe&fY*#eh^oND%2zuYE_|IJ#MqD9-_5giZ%)8nleVfiMjs#Wq{K$meOjBMCchui5k=~Dh&%%5=H?4(uSH?5<)+jfAZ?xV__Kxh_45A! zxBKp&^{HSd2f_^H|0j^lB7jZ*Sq7VwkGlE`tHi7>&ar;*@~{;&E?fx^+@fRKVaGhlO~0)|7XZVwdV4OQW)Yj!4$0B$6sZ z)K}+TIOt~i9nt%@;ttW@RQ*Zv2PfaVGXcH+N%Wc6+oxydde^%?K5xFg*f?(3kE-{N zZqV;d`?R~JfpD9y3T4S*DX65Ss5GLUSB>SOpk_g4V}eUpVoY+97y_ijJ4D(5qcVmX zPM{8@ZajK*TI5K=<{+R5$UdReGSqMZhj6LFk>yIQznP~(bT`E=iQ0XI(BI4gY7OJq zeLt7p)%E$^=ZoB3jl8gZceS>j;NBf=)m^W#F*(h-wmw64~7Lr0nlAw+ZKz1a&5Syu}6gOddtwO7k zQlgKhfCUD+opV}sM4u$^dq<*|q&_2c-(d9D$&Rw$e;4|1<~G&u+=lJV*JUo9Kc5KvyT#6Pi)b|iS*MnfeMEPR@Gk5F`iazvG=#{+lJy8E^wyCDazm--FW)_t{i0g!-ZbR+Q0ia=2>5RaRxks2 zVEB${tm<-9R=2DCsD3-g+xSGCOSCpN=-xYeEL@ah^({er;u z7h-k>Smbs$aP57gK{D0sym#EL*`UTR+s7E$93Hd3uBWoJ`O8>Dxs@Y)w8 zsPFh#0uGYiNTVV&9mgc7KRpt?2V-5^+Ln{h|G&E`DB}JY&0$0Ky!Kld3%b0LG{>#Qt3^G8?Z2 zT?IprmbCFhQ@ClS$iYvrcC9@0lS z8BHZ!UDSd>^Gs?Wf4qu}4yr$T24%OABao0wEQ*XN!h|rO$*->fLFngohBlcpw z3lx2w;K$Q7e|!9WlB4)uLZ-G@W6r}(_E2hJQ98EyxXEf4V9yD-Vv6?T%PqMfMAIA! zRwm==@PVA?fb!$hZnrAWAh(ZDfA{K<<@TCW?eiF>1Wkk3*$T|HPS)OZl(@auOSR}X zB_#N4wSGfwZ!Mo)JQPuH4W&_84K8EFOO%;uvKac*j=LE=kp_B*Y9XE7E1_HV}?_d}(Mj12vs=IW26Jv(wSUtdAj%Y*(Ep*WxU$#0!LVj=kV(J`#D+{aQM z4V0Z{rSvNOx$|i@)I5Q?`~-ZwOG(USzv$%D^{0akEA#&VB|2BTpYcvv9+nJ0?DFXJ zQT`jx@k)#NZ}%N<%qq^utk`k<*4dxjeWBHvD%@^sH`s%vb7DH(&r^?%X{omMD+4V= zl(M?N`Ch2dD@a?}<-@Xm@6ia7Leuf`6o*mbwe%vjr>L()_UIm4opTuB2(=(olTuZ1 z3E~Mg8hB?=P*3l~NpG-STU$jSNdn-G#m~wk2aPD(jvPnrdo>bgGpY#Vty^p$Jra2+ZjB z8}lG-B6mC}Fh>vQ`g-x`1I%mwHDwzRK(>ydbC6#Z;7_R-t$H8-0F`Acf5VLYPnJzK zi?%3aky+_RiTsa|0X-llxSU_`jD$C{`=ZTxq|v{o`+6 zJ~9jen&Zo_qb@zEo|PJrypY||Ufi*YMv1O$3u$B^9&QKJ{e6h+yg#LdqWB1{NTEM7 z)v4N|@!3l6wy33>N>v zXY)ZERZfb!kEug`53)Ust4nfg-};1C=HO%Y{?3bb1dVS9jMaQ*BmLm;{{U7xKk97g zR9tEoA5f&*Nx$In>_g?y+pkGxZ6NxY?4fxd>WeoP9R5wO@7;Un*IK0d9uBZS;KJlv z^Krqyz4h+7fJ5j68(F~?14$o%KsWxL_16CY!`J`P+tI*B`dqLCk-;bOK9=I#`%jP0 zrALom16d3YCg^X?fEPEv``72+xL4Dy;M3QxY8b7E1IAGq)L5wJNwaaKiT2-d2DPtR zuMBmaT(|A&3^Y46>>U(~5EJU)o_*-4s9psB06+Mysag;#j=pif@S{02{{S^^#*Cdp z9+K$YKBCGM@R?^&pn<3LexIoP^Xw*zPpl;8>SZ6Wull~;i}|bpabV3#8$=)B{h#VR z5m}}4{BY_T7kYVVrQ6wERBpbvjPE?$(zqtpWt;*E^1yv=J-`>hMea8=TqdQFXI}3r z_z?mB02%8aZv?5#yw5CaM-!z!f1wcmV~0fNb$EkG5;^iLfkbx#Cr4}*V7YDlJM4$##9S1A#NJh;5GjM*!w-Tlz6VE82drTxY-cuxH)U<;jyG#=jGj9WQMk8O3XYb!b~e+^)Io}>$k%P>l9G>h=5yGo zC2U4MqOzUZcv?+s5gy`BUgQY*!+YNEu3675#dPYr>se${PLzBVNZbz)fJF|0LsC0O z?r+|2bM_zF{{U^a9fmt$?-l;V3%H1`iyL-{7sa`Tj3k!s2P+1)Qmn0T$jjlY*GFk& zw!MFARbsY#WGeQ)6LG#T1)j=My*5v9V5#y^eU@Uk5NRpp##Gf=r8I?FNJEI&vjR-Z zwQZ8^P>AJ}7bFu-3V0fNttn2h8=5)NE_}X*akmJhMKz%{b!t6YqM?JA2PV90nss@d z{ZB1F!tTp?q>>Wcxtk^xV(WPRfd)qSwK<44MA;xZCQnF!q~QdSI^~N z+Iov7#iXT;2}AxLFPE=c;4?4^s7Q+HY&m7pw)HU=01i3!F~)ii)DXaqx%i<7vn=4q zU6tvIxoG1Gx@HoeL0JnG0CFwQ9{hL?yh$sO^65jgag>{jcI{2OSN97=xOX<*!Bopj zD2le447O&1f}(mUUO8e~w5OefWzo)KX}pNsCM2KXm;Lfa^^A+*KVx#Mz=83QRFLYCVGhx=9|jW z8zNyPP_m6|%c$fE3}g%p=73U^$5tvkvp^^Z6T{Th{Juvu=^2sQdrB_3p?vn#=?uR7 z#eB+thh6QoaJ>bzw$20Wb4`{zZ+Z16WbNw_c;mvg{hzn0l9yC-PZ~(>kWW(tQayyMu+&Ks zG{Jo#+B5{)>QA)`LKL^3RbfI$q3C1kf8khMPigiZM{RBG<&f*Gv9_{1cLBU;>N5LH zvb%?UZT-1EPcMUtvW^_z*y8J_SSjjD(s`v1ByLehy0KwO4?oJ3KkEMgXCqX|sK@90 z{$HQ%73$j$#*M4C^BW&!_XQ6|Z7uP+Hulla_H5fjH8jTJ*-57*-K&^+OK4R=vtvY0F$e?yapRH*amdy|*NLS+B6iCnBlIMAxBQsZss2Fe`r>1TwuWCx0hG!ZSh;S>FV+| z*t`~hHAPcPn#W-3^A)))%(y8s7{;llTB?cWfoJg<93Wz`Sk=L$cw_uO>ioKF<4F}2 z{{T7v05?d^z1!5g!?1e$Xk@A@>9Kpad~IE`mZ-&;MoyO(o6gYVvNc%ts*ZYOt*4}@ zc8#P)jaUM}f$zkS2^>dS0Fz9Q^?HAkqZy8&>g<8u8^?3?pI7ytSYY?=Yi3}hg1@+X z3wP(UG&HqY7`FBg7awKfzq}J+v4WmVu3oNOT?Bu50Ynl_9Y40!rClm!)IqH%px1>? z3DO4uL8ap-n|)h{McU30#$L+q- z**lN5v3sv&<+j{8Nopg^ZB5s`a%`ClO!Q}Z6J+gu!MFQ2d~Pk5KWOAOgdY42qFJZRcDKqNx>^&Z{D@-ZL!tcqX)42M=RU=3w2X(9gVp+(&p*+UTZg= zjy%rVIC^?Lc*>dawei$DE{1?S@1bB-O9tcJk;0xw?fHF~>Yy6cfvz~y&bX-br~5q< zk*JnX!tA<7;D1|dCdycje!kwVa!*#RNX9yrQ8l7K#qAn{aN(qvNqHB<*J0!OaCEkt z{{V--6Ow$-TcPULKa#YSzwqEY3J<%fG>z7M)mKqWwJrA2h&tmr_L5B!xJUbHnM22M zbdUl+HzMXbe(IX1gD?DeWA=2a$%wqSt`@)KI6p65w`TYQj;F}{*7*ZfB$3n2jre1e zF9XdhH1(AgIIwEsG0UPUsbgqu42r73i(DQUJ7Yt%?p?Ss$@YwND%+TjYUKcr-SzNs z_3NtwQ;CJpx`Ihs9W<#lb+x)na`xU*hhgKfIUK51(H@`mH|6W+&n zX*?omXIhUIGup+`iFn;yGCIE&8i636*Xeaan0OcE9Az{MNqXl8rj#N z`mkq^(bH4AtQ2n*Ev0t?K|4kQfX(hs`^?8IzjJ-P0>R0M>RC^Q`N34 zJNXzrL@Q03g0?ViQATW&Mxezo8YBxMq=%kdnIrz~Xvqrhbvl89aYkQ2K&NTW0|Ed& zb1!s|2YAuOnwCLYnjBQ0Rp3-$@HqhVwEkOEl!vJIRP|{L)d#q;G|e?^^HXA~sj0Sx z9)Gs3Q9P9O@%anuRE=4qB?&tH%sj3M-Y4+w%!((n{CYzF0BTyOKePsdvC^&qTG8p! zZd{HNF7)#v{{U+W(aj?x!;sO%Xv$9!O46daJy_StO0NfRQ_y2^IeJ%{Zh2y<&Eu-E z^m&|aOL69l=W)?iHBD766CFA}KOWI}BZ?Yl&|gtii+%C2+($Z@cb%QAonw+n+^I<> zfZW^^m9-P7YS#>5XpyX8P;uy&-xdJmdKWW_XL}a_^izp zok@_I6G~=;x7agZD(5{$ajbS~vES}(q$L)IR-FWz3S^c%2f_t(ljO6jhPf)>^GS=V zWTKbs;-Yq~qNb^#j3ud|4kmA0taS!kl2BXqgI&H$M!&wECwRO&SsW-`TG%ZD42lX@ zJZq0SgNQBe7WEyjVj*K9FguY-VRV3hq)9aytudaH;%s#_HEYz*TSE-k_R39FF_x;i z(d7GDn&9-(B$(NfLb0lW<|s6up=L>C4z0bKNsrWqrj-=Zx@)90MGxmvcyw9%Fxy_6 zhL8t@%t0F7K~k?FBPl~gABuxDp(IJ`8Yye{mgUCMK{n>6qu7;oIdpnur=*Ej3p|l# z1$0$HNNHh)NZwxyN&D?$gncp&2@+K1S#G9T;Z3wFHjom!1saNcxaw2dz|>G;WcKpf zOYP$J$_U=#D7L*)jUXTbDv3+hp%qBf6HzW{PeWVe-jcWtJxqA3+6DfIzP{o7Ph;&%Qfx~^QFGXwYgf26n0emVaD zi){RkE$QUkKO6o+V`Yw7Jatyxnf!S7sB=$410%rgi=IWGj<;@J+2-1IU5ftZd%jt* znp;hac)Uh8n=J84zf;Ma$p{)&I7wx;lH##Mg=e-uyCs<{N%w8G*)8_lS>-cYz#c8W zc>&jLB5CpVt<^h#@Q-W&lCh;4CN}LPaO>gx!!bELTu(_|hn9nK4aJlLZdG~e>M+$4 z2&!^&Pf=FidMN3g;|Lk*Jj5$j+Gy#dofgMqce7tfw{Es3%1B&>fPxH7f>A?$0tnJW zF)K>50v)1l-U(s4+=bP#g^a|q)RK&9#Q`}eD@CbdMK!Y;J5YA?iV8=lS!8+3R5#vL zw~=Pa%-3Jo+-{5ax%eLJ@_l7%{W3IY5ed7qi| z=oO%0Q@-$u`U5-}#57T<5o4*Mpb{b~scuz8*n?nyQ7linGRCm&H}nLk5uILaOH=$k zNIOyR?JjhtD4pJHOHiM(zqjn`YA@vljG?Uf>Dg3uOB9syc2|O~o}o3;)Fo!vq8cX+ za=MTa>HHpkzQ$abt1mCy_=~Ap?mM|XlHfn~^XS{Y$N{QJCCe>jENVKR zHg0d{58YBMdrDonO+GWMg}@amSSpbr3aGk)S7i=a+1xsYxqpk@OYnpFe|&`K&Y0SJ zpAUfB-6`GspLS zj27^sj8r6GvCA{N%JNA6058cGTEZ{-X`$r*0KpgB#=?x_=6apAcxp{N`iXEjKkIY< z02TUs*IobsSx!$}!l)cu>VANm9Y5ps_wScgEW}WH^q^o@Y1JR>wpyCpa2a4X0P*#> zC)*_d0F1@z5dQ#&uPOajukennSA1h}Tj$}|!TrCP-2VWDHkMfR;ck;vB+ehQwXU#3^k%o_ZHv9M`@(ZHz5ms)m?glRfxjUBxn+~5jxpzuQ zlA4nV1{*b5Cypo@ddjGxr;X$CG>Wa}@b>-2C{P!b5k){cdxI0EhgZWuoEo$^>(S~H z!y#fkHxgixT@@f#?Wd@vY7Y*qKja6_-;f_BJ~UKy_U_qV9=4rFW9{CG-u>Iz9aGjD zgJE`$erLKXY*JJ8Kliq2cg|02ZHk?(6)bf0(CzF_Dw>xXi;SmOaR5<^UOcz5m%Eo- zf2e#-y5@kSkp(18}0-q6kZl-6Oq-RjqWYoB@h`g!!>O7$1!t8Mh0FK++d;DJc9kjPrZ)W_D_`$!jn~UMCS9or%u}`r#F4FkT zx~X$pk7nnx`HIX|O=Pa4+Z75b&Nd27Y?kSHEwjpDP|=UmP^<`0U5>3ur%?#BCBd$h zTDMKZb>dA7QnImDH3CYN10ZRjB)4c|_;93}by@!aF!!GJ>W-?x_U~I((PB3TTW{{X z%fL~-e4m1vnrs&O^@czuMNjs$V&N%*(&H??}>Uz{)`#SX|!b-M_-=m-vk3=BuQprj5%-5+d5}B$<((B`T|- zbDC0=6s0RtPo+&dq%EZitt!k(IzjWTDn||&82NNCe2ncq&o{u{=z zJ-l{t+sGp^%t#`jf#I-S2gs`pTKI#)oO-;HES^7$-KrueX-|m(!1AG>0)xwjI%w%n zkUhnQ>fM98F#Ef4QPkyj&eYyJ>pvc5zOy;Lw^m;TjH1o&p2p1A?R~=E1pzJNa zx%`gXWJ*2PM@I_|RYlTWh9dP$Q5fLT28OE%9bMQVFRn>G z9}of&Sgsm6(iO8%i4j(~@g!nbP$5c+DD40NLS><)N|RpZ1cTrZAmFbb@GiMvhHR)>i2y38_;VXHvdJw5ZP%C3rC%D7>QxkewXK%EtAULW8Dpd4B2K z`>SX6xAO$uyYI65mvK;TT(xI@Y;TIa8Is!j+pqTyJ8wrO(dxd@&*o&^d1JYkAwDNP zT~|*}SZUe;5<7YAH#pwz2tJnCAiRxIGQ`GWyF_Mh5DMhGYQstKNHuCDT(+{?$f-Qb zE6mo?SGVDGZo(JwDuqQ~!l6LN07LnSY#)YMsc>C=@oV{T_O{;nLD#(lx2h{U3Jtfi zy3b_i`_4L@tG;?mYHpe?;5qK5`C+pt^7ZxmqjTl<)Y)p9$`qrgr_0q*)mB9nZ=Y~` z`>_SAcKdRb2<+N5lEr0Y3Izl)C!n%o7*GqaQ#~k0yoxh#=x^yC)QY2Yzq#*EOWrYIhB-E8(gw~|~ZAK&$L4sJC zH4GTek0X*?Dv+sM6v$lhBrc@@tr+Ajnf!tIOW7Uwm%wfw&+CfmDt4wDEsNWD-GjA* zQjC`8sGzOg`==`TUBO?Ish4urV<2^gClna?;|l~zOw!7dAtIS&bYfTmk|>}Oe7K(D zRwk?|>i)mKOnnLbM|K6?WpRrUk*M*Y>uqjyH83vbnrlU7)7IgN-b;&hxRqAdSS&~D zs^{7{iRrQ%qN{G#!%dQsglVHIA)f6a3k967Zcde9N7bcA7ITILh@doGK=#yuzoSW< zfqfh`t#z?gp;z=24l&vIf+_Rah7UT+pLhOt~zIAAI(h9B=Fj_YsI-16-rHQc8PE|!P zw9Xio$smnH5uAA`lRKxeTB43Ay02mX02IjOF?94*(s#WXD_JaJQBO}y+ZLiaxtfhg z5}A=9({)w{Pqwt(X~o)8QT#G+Jaem$siCh5b+-C+lCj#h0P{?rmMdQ>et#~OIK9W( z*!o|!hp2WoDq0-;Rerwp#K{8{vxw1GWyD&oixQKi{{Snb5$=XYP^0VOV_H*7j8dLw zr*yPHAQiXk)iILy-_VwLe*7oRZ8=1m5wE+ zS$RebRcbY?wSc#ME{@#=&ML~ob)t1tG$svSw5*6)c8kJNq zP++^);bu>`eol0!$sAXI_m5oF^loPdxuDpcW!f9FWo>=*_-9En8y~VZeloV7Yj57O z-SPO|x*FaJU*oKj0W+N<200>gkJoNML80msjzlFN4RC92D&*CdQ& zoQjY20YGU`Df7$!0EJ&otNF?HTsq_?o1(fN5|S>H36pHp)|gg3Od*X8Rn-9@K?9$! zvff%sv8S*8?=IGtm@gjdiGYGNlOPP)Q(uS^oehp|SW$(fqSH3y{NBS4-3iH60&NR{sDA$m26uER)Mq(R%?U+Z41FbjC`W`f%c-%FP`eMKcK_Vd+2< zxFN3jfUzP$Jb(&TxfG^&0YUywf&2BeV(V`a-7cS^ixgmWQK~b$tLVp&mWRT%zs z*6~pfuxcw z=0dk07!LAcahUCOuq`xisz(M`)p=zWzqEE6zUOanmhr{)5!c{QSm_)}k?@R+ny9G9 zQhv|BUzZlkx3sygka8E)Q-{vA1C2T@JI%3sv%Y`QFJe`0E$!GnVM|diz}Wdn>GriB zPhfW_jyKKX_B*;&&A78dB}sQ3VVSDqjbMkv3W$d0-uDKQSZB9rq;X0zm2EXRT91U& zxUEYOQp5!ckDGUW##t?GFCdl;rZ@2xC8!cf!CqFV60!kUmAfJ(-Zcf>lrLNF9Dd~a z^|2O<6DpVnny6X{3Hf{= z1M@W>VLd42tC%ObvoRx7$k;R#>@_De8UFweR?rTB+7|2@;ER#@7XsYrKkR*qhYlS` z-=A3vkk&dt(m}PZNgVzx#2?SSUxr;NPqdb5Fg61Yc`{Q)9LzK`g_&~Y2Y*0htICwJB1+YWmGK5 zeOe1xeK;Tw_WtWa%5$94sx<{k6+L|6KjB6aYyNA!qN;r{bmv6JU_%8bZRBNPetAuQ z>P^zW1zC6T9s~X`;06}u^Oy7`mq4}6hdn$I%|xd%lsW4M7`rkt$It;?(RUK!HD>65vjYH^v*!w!$;}IA#bktY#=*Hj0h6<^p@&124jn;E*Z!G@! zqQq==+hb)i|jSEZW)#Nh%UGtZ1>bEf=**Hdk)nxi=0fimH5_HZOjrGF+BL;1Wu- zxfp5ZS=${N)1Z!2bz>4JvhXj*vCiFbJ>8X!)y=!XJH{Nw;*NypO9PO@%pM0FW9I#_ z?cBA@JlC^rd%PQkjjhCxt>gt-8P!ERNL@)*jg53NnlgaHk5|3lvFCRm!(PY3;PLrP zzEdZ%F?6(>e+iGRugK(QJA(*9QsQW!lCG`N7)+%R2}sb$KmhwmwjFm7NX<IN|p7ucVzN-7%ID^w(_0%A-(|t~ZQ&Jt4IaaMu=7bAQ41F!5p^ z=!^S$4rwX?0N3n1Kg>F9ZlvvHBp$EqWn=(Y>`l}(+>cXV5)Y`JFa3SFs1raz`v^U1 zja;eq^XXHu_BUhg?ens?6@OKBeMUcT?;Wq4uBOK9J;fz_^q73*4Si%3F;q~~LnU;S z^z0*7k~J@2SPp%(%#4PTFYW7E7~@H=*~YzF&r#&@U1>L9O;x)#hU3IZwn4zFP zpR`x2mQ`6<{Kar-`+i?9+tN>ZO|~jF#5np1wss1pv*un`<|k`zi2Fvbu=6{I?K1n6 zY;A+qTL%fTaW!-9B*1S8sjGv`vDRcDiPlKrC&fj>u99@B6&mBqDiswi3DunO95;9 zR56NY)27*heO{)&k?3vd{hwQy+g;DFvo$ew?r(hTt+Y07cd%f~?QNS~l-hgO5xZ)( z?Plnk9WFZsn9gHya{mAfmb}wYPg56xsv?$1R!W z`E_epz4_Os}$#Ad})?DZ|Up z{hwYP67?03B~3a(T8mJN4NPrAGP5jli6Tc25oIXi;ENw>yg6z{hR+;y&Y?nTI=JtI zo%N6Dj=sm|@cUm0+BJE;yrbB8jk!nNTQ{cn-&*fohrhFXqMB{RjqGeWgE_Rfrr6$* zPl?FlC#h7ZrIs0da>Xo4Uvn9#5844dRGQ<4Du0&`%C1ILw5>@Qr9DsV{{U4wGime7 zd+qJVy7y+t_(#*2oyopups(F~lB?xML{Vn9?pqm4RG56G{-0`M_P$ee%}Y~RB+?mb z)@q4fNo1GJBg^f-0$HO?S0FG3oveJYM+}cGSsXAraQJBD!ZRSCJO)KEii&#ECyCB_ zqtB65*jP8N*xQsj+)jS0V|7^jj*%TlnZaTEbEz}A z?9C<<1B2}CiFnOrtfR_S(${XD$J!Ya z*w{?ABQd)r+nCxIv9(lH7`gD(GspxLNe7LlX%ei=JP>J62{ottHLv?q)w@}wDy>|f zPCj-203|(o7dqyj8P_yD8&SHt*Jbr(FH_O(-QC%{`hM5zy4)2eeuHJ@uobi5w$1~6 zZr#Pd_jhP*yf!X50fHIh&sDS(6sZbE;gjOGh}=|)00FP2cv6J?>MBX=(HO%l$a5#^ud^8WxQR+UfLon=Lg=v;O;s5j=s zq1ZXC*HPaa9|zE%9JiHUZeX&RN3Fo(w)Xk0?ejyAs6jN7)lOrkD>Y-Nl0!!lR41gh zo%JYiJ5H(qX+cs2Y4Z7e>KxK(K-G}7b6V-mepMo$AZeaG5r5_bytXFqrQLgzZ*5F} zPUCl%XY@mCPOr&g`tNJ+di|x={Uf{fX7TJi?#Al6?5@(@8{pZMwPbkF7KKacr@{H>spsyOw3FUnZrrk-f&8R~LdlMwPe zNZ?Ce-Z~JvQ2hZv*#rkH2wj(V)k=k!de^i3KAj3|!5r7g%s7kq4mke+YNDg|b(g#H z`1%PO2-K3rS^fV2+nIXYy3UPFHrvMI>$PGg#k2&qXYqQKt4hU{Ss+KJD$6CnH;kUO$&z9p1Ki@BWryF1423p-8F1X(o&Z*ILk^F_fVMkoBnR zU+%@-yRMfxwYSFK?ycq1gRQcA^BuP{n>)3)A4^r!ZSKp;)mH9ICL^&noplCdXwz;& z@Aq&*v%!*zQyoMyc;RHn?n3tp^Oi-;iQ10iw@)j`u&X$5%m{Lt0b-7ay=g(lqNl9o z`^Wv&Idk4-+4+=nTztFDdwr}n^4?DjGuldss3BXVo=A{Q3!xVB_?4k#Ab=>rzBBnv z(SW6|$W-HH#_jH?+x>6Xm@TyR$7XEqt=V|Ym-k0%Z91&BQ#F~&Q#Ed1A(zQz>nf@% zv)RnGZbG5_l^Rs1n>n8An(o&2`Y{lOKME+uL{X+R|Vrd zRy?D!Zc|^+cexw;+v$}SOUuiKP}69Pn8ac=NaE3t2@r4!7R2#;wp<_cDcPHr2`j|k z>7(XtC5g&>y|hhi>u;%*k7BR^l~m%i zG(0FMPCDg&>C78wy=g7v1H{!>%9SYX+({e}7#`3LPmmPoL;hP(QVyogR8LI|O11<8W(vqM3g$I@4bY(hda-8f6Og+y1u4u zVT!|UC1C_mNKFe!1GI@Al!{Vx1}?;bH5K&HM?7(0WXWZt!%vT`qpOg?49!%MihBHA zej`-Xxk`A@eX{UmI7zrYHiD#7n{V>2G)YPpB>19(s4x$=W!$FgR00lt$zZz|^1iOw* zoS6RryPI;yODp785u!;x-)+&-n5p4u*=CwVkV-UJiN>o5?O>zTxz7PcIwT?dx5uAs15*JXk zVuCW!;bj7zAT(fd0RSF`j;ExGt8w-$ z6|h#;y*9(It)NOr#?i$)V{jP+ucCz`F;lupEWR`mNV3S0^AqZAITfUH+)2i$pyZWZMNZPbNyAYmK~B~=&)R;?f@3_!{? zO$1GW+IvUrcJ(&q-CIusm#5oXLv7|NHw={xv%7Px6Bx1NcBb>j#?<*(H{Q&qp=zDE zpG`G0R#U@6EQO6UswU;Hak)zOb79Q<(`Ny-5ZXy`Cy6Dt@3#wbC9&M1QnDM1MOAIP za4aNigoe^bG>OEC%iQ0vn6}lu-t4Wn52dw%{C6vFxLFhm_V)-#k#6l38e2=XqqK;Y z&cqnVTK1=Fbv;(!-5YkZvNqONJ(-(oV>d47+j+BFlkM$>Dlw1O8_q1#&iEq^v{{S(K(Y1FkS$_|quFP&c-oVRYvH1Mf2CU8eJFB(iAjHvbhL(+~ zV#T4I60xbO#!~~5k~(E7?~> ztzP@ChN~krtvswuew>Ugp5=3q+s=O+K z2PdC$R7hglZ`qcvd^~wqUzhoMA6T!4V|34%e@}-2N8mrp*3n{FeerwpiOv z=q;OYVId@dBV!(;P-+b;QV1Y<^mWNr@Z4`#P+bby$$0>ixTs|-Mg@fm&~acvP-+cx z(&zbse=5$Y`4XMg@|&P~lVj$(FLPAxczfS$;C5~cuRH$$;@50#r=i5|EQajq>?H;_ zWpCZNx3Cy!YxCJ(<1l9HsZ`}@C90{KOs+>HwZUU=ai-?UrvPlIl{1eVD&P*RNTA_{>_IF6#Y zBr)?nX%!q3f1 z&-%Rj>N0F@4eoFLBH!)3?9;8Xh7=tsCF5w%{SIOa3lV!je>dcNU=Q(_&-4%YdS(zc zwRqF^=c9|?s{r`9{Jq`ApZcU^kNG5FnZO2{#5G4KajS=!*4Cs{LN2{j<6z6s$(6uux-6E|&BsMq3(`|$a2tw_8R=_MT3Wg)#f{*Z7_s(j2#aLj<6*Hogv3AuY*=$@8(o*Iyc`0V8ubUt%F~%A?Cl!>r zdtoxeYvK?PYIYP1{{V=n@>5zUs}csLDo8=K5*W+L5JjhGs4YNf385pnWKaM;9^wh; zW%!x$>vCrL0|~Is*z5hLvAz=aB~I$^OkYytJDYZPhBM<<@#&r4vD@cgVsw>%ZDp`O zA~79T+*_I$djma&!`0-v%K;TFRtpV{r>~WnyW5Fw5*Vgx#F086RaK|Mr??8SJ=%-v zV^cx{5NmE0DJPPLT#OlwOK>#{Ls}^E3qUbY#+?u^=99E{S6y_zZ>~3*U?kkQ`re!0 zv^m|exoEd{UG`5_?<`e(+Y7roH+kb(v0aPPeWgn@Rd`I@APDg!^tB01UrSX-0(n1B z!6-CMX9tZ+oFAC~00u@6N*%)^5Oe3BFhxN1^&c$t6XR|=lP~f2rt*jUs-qLLqo*FW zl1h0JuDYEAQpGDQkwKu^NA)FuP(Gg4$jAydGO9n2AGaMf7(74K{{R=#=j8PrZd2f{ zQ+Pp1imIU5pCCH7Y-i!At&SPZ3gTOkzr!9}=+wIUR#H zX-2gt1)77;IvoB&fYkcaIRLn&nJ#EBBLw}PA`jbAC^BhN<+Ea9FflT zM#jaKnv3>vk4?8}rf8ZdVVNX2^Dd7wfb}Xh8+&@-26rgkpbDQn0oRbAjjC$Z>e6~o zJGNirzr@b2>>3Wtpgq0(+<%t`Uu_P{>k);~x4R<&+I#mmgP%8Fxu`O@Djc$4Ws+Jr zWudK(q9`OM)c}p^$jf!I${__3>EzT{E}b^6067dnVxfX}6*Ls4p`>B{Hj+vPsA)pA ztzB3FiVUyBPYRDZbTIahWVS1^f0<@aue$rR*+eW54QqMu+4M(y6NIotM0G zyTfB;HjPKeZG%IQ?A^yjx_dWxNwjx92Xsds6?3%mW)hz%5>VAbf(=(zQSKJEu!NFg z!ien7vLFfJifN5QHl$+Zs0cuHYggkd5Nl~tQz=4}1yClI)aCUWwH0*fRjDVqfSMRo z!Tf~H_D0U@yq^8WbdSVcySVnZM|@t`-BZ`!B>J1TX6|nO>R*_h0=o}&?GCoVZC$Or z^PQu*_P%2+jiklMwK8ptT@1g+O&RbQAGi=%EydN&;S02@ZJ|?9WD!X*mPRE&Mqy7L zrGV0)I~HZ>h{0hT7V$~0KM~!S00?vdC^g8f0KjKw?NU$@Lw*5QZ(XPI7vW!E;&%2w zH@9~$P<)x%(``+yiNNkY-HQvj{{WqrXVdRvf!KS7DfX^%wA#4-AigwpF7nA^c0Wz-pO8NxK3wiudeh{$c6P^Mcb~(W zEw}QKdj4*v-kJWx?ftc!d{*V$)s;KfA&bb-?W);wQ`Q=~ynvpjv>;AklWcvG)>{Z) z#qf;A5T-axj1e`>pfsxzmeBJA3>28rYE&HB?2o*D_qw;cnQg80EG5E&APCIlMjD9D zQEHKRjT*WsccPMNK3w$=$33b1w6M7jq^0Z()>9Mm+rN5CFY-4R+B^D_Y40PB>kZG+ z9p~IVJ1*qk{n3=({TaIHc4am$muJ>zGBlXn?moJfjjB?fTB@UYq>AR>Yelq$ZRLV; zfl9aOiJFb2dr6(N&XvfCqdx%yqLz+mZm#5>cKVc9swg>YgjW>4=4jMc)`(MC18LkI5*_uTgBp^|(*KzJ1+uol)x_UnE=zW{g z8_#Tf3EBHH9InOKxhOanC;XbGi0ED9Qu&>^g1FlZ~Q`bWFCcC7)g4&#D#W`Ibk zoKvP+iRu7Y*we`~8sQ}EB<`1mMxs3NI8A&q3mqeq?H6-K;Cw_8PgByx0Z3z99Q~gz zjSs*Y-SM{jbG>Ui^JQ%9<(Qw~Psu!Pb9rx}pQVSQHeG#Q$E4jIt&80Ia+0Gbwkt3g z`9v~QMrq}iDOn?)F|3yEW0Fmmc7{uqj@|9F%Im}-J=#TAQ39-@paw;92to_6_(J;4 zT;mqeL9*uVdrOq-T1wz$>6&C>vvfTv~ zCrcsK5CDFdRAa)0f|3blAoyaGZnkpFkxOqU)OdgvjhDQZI*HU2Dd4L?MHxD&LQZ}! z`VP(#=B0_=w8^fJqfSIV-ujB!VRXaG(NHYE#j;*E>K0_}MtD&xg8-#)DYnmF#77y}TU?Ppa+9^Xmms6xMAl}~U9hhk! z7^ps65|Kg2`SAY$FGD2d>POliB{`?b)6@wXNx+_X!)c`}GAyvH&;SL$Y&ian zaEL0g1g%X8$N73!QZ-QI^s2-RjWkUq8=f|$J;46ak6%8EzsHP!!cXNT(|x(sy-&2hKyDniH>R_nE;}xd ze8<={`AyePv8y&;Qr6|R{ReU8arE0dJMHh!H)-#$kpvW#>C?{T^2@@cw#B4 zXgo2oqN9!Bt#p>7!|g@X2_$pQh(t-@#z|mJbdsdfqK%=BDgml$B~MKkVfv>|iJh1# z)alcj6F>%#`f@`aIzS-w`Pv`M2jizs_YTzf`Pnn?{7-0a&eFtnUf66_#oW7}Wd8tp zHxAXuZfpfc_1{>U8mtz^!R6x1Q&Y!Ll&GRm^M^%fAgY?2n%X;?sg?*V=69=iC|wE^ zfmS7f?lquL%|J;Mr%L7##SpoBn3W2OD-*5iO+o+&qJ^s#AaE6_0Q}%No4v4b%VW)!J|V$eNY5z8O%P?~zF-5#EA-ANUQ^fG&EVT4;Y_z&XT zWjqfPr`PQAz~SZ7`^=_TIdqfo?Z`Za46`?v`ftyTGtpJ}{oj4v@vHe^_6GInjqRD) z81j%=>SA zI`1Eo`$Ocu#-yi)w|iweYag>>>&?ZSi>PUL^#oWQ?YDM@*~}s9UBi|b{G`;vDE|8! zRT)`OE1K=E1@arHnqwNfs+TM(Qe7JK)`ePyk&SAlPAk**fuIW$MI3T8YEFG@hA&s|Ct88U5fL@GgZX=9Q$R8Jr zUM+!4cM;ZtU(E&@N`L1k^HCDEyCyNYUcXvex|yY#p=F1t`u;Vfo}yN1DycD`eXh1Q zWsOfiQWcbeKKwwa@#X!x`2Ku;b?6VwbWO_53sfz%Uua;sA7CB7l{z2)0F`b{^FPdk z;&n97A&ySajt|=gKSJ%i`#C^v5lB*`kZz=o2?Qmui^rTq!l>xr*XE25@;w#1i8nr2 zjO9+}Z}}a5Upjv-zK5F=XwdB~ze$XSI&)P7)zVbe!%rL%%`HV^%Id`nw~xk=rHgX0 zt-!T_i*1NoSV3-|2o*R2tay?J39c)~fDbOG-L}+N*+puil&L>9CnWlw0=|HCUw_Px zF}HRszZJU!9a)d1?kRprY>vCx7+AzI?hee_o7$f(N7$Wp1~p|$%)S`mP-W-Pl6{o8 z*yaX3Oj+xQ?QSA_Yk)jfM={_M7ywBaBnknjtv?QLU9Oe5|iv9wMdt`C{02n{&{QWw!Fw1goZ*>>3 zUVf(Fn+|`&pJH-yy$|~2&KU3q7W#5Rl189Ev>5*Yw)gJ6)S zAMJ;|{{Vxp53{ZY{zkQ~TH^koKnCS4_!s*7)q34C*Z$IS6Y1};W@ zDGYz-=&^RxaDN!b8ftiFMAgHdY4$P}m+SOP`WYCI0xi=m1bGfjU z9g9jOkkI}R#|l0}Bv&;j<a<$ zzaN;}`%)^L`=nXQnWVV= zW2!4DcSSm5j&mP?&0`~~ftndwS}KWSl|uwEkZ#$#BfG_Pw6iijO6AtI(}PtawAGJV zREiMw)DNVX>eFc*rwUF78iP(W&V2qw(0qITXq=bZ9|oE-uF(Gg##ZiHa~c?g$uet& z8d%mwG4Kd4_4N9^n|)r)1AmU(P=Wr2Kgg$#+tOJD^QZ#aC2Hc2k@Cr=e$&=v=)dNe zB8uA=;Zo}g$``zQ5;lk_<~I^l6e6IVAwevpT#zh%wl20xg1e-|6aM-FJX7JZdFTZt`KMsStC^%Sdaz_WYFXG^?ClT+$^)&r4;Gy zeN0cM*-{VqI#}%-$IgwzxN#e9hideK=64?MgRk+p={rMw*HX>8t0Ra}?fCMPuT4QN zPPV)~AKSE%q!O|dBY;7*gxhxKYxPjxO0ep6I?yW(287chgNUifHNfh(M)n6b_ZDgx z=`;;mmppO%1u_mZ(x+tZPW6cHxjVv_W9>HE%}1qr=XdA#RTNZ7S5=P7&$uVdl{B+b zu`-()zhG}%PV3&;n!FeAyu{d!$LpQJ z7AWm}ep3rq{7Gsl>mF)YB1BlHGbHH8?^|n)%KKxpVs}`oB@V2M7$8uqej`Q{9;Z0# zUrjq&+uk}Tu$4O)m15ba!ZMm9MYH+EyAIwpEOg|wh1XeqFpey&+7sxU5+ zr3gxjiDM#oi$qGQY40w$6-gD-mc=L*nyckZ^<1a9i@?#5-C|^@Cc^s z=^8VnA16GwAP=Xp3vDt7)BDkupV1?S`+qMki_OZmr%Ns(oJaiw<@t5WALhNdvN9jy zpAmZYvKZT2P5u5Al`*l6ikL=2uB9wksOOC!8~#1(_iUe&!^zBLf*|Nr*MxPP3PNHdoMxBp}fu2Qu6Dla`hFD_p8%L`aJ4w6ryo*$x|YAq!l*oy^87y8?@tT0V=Hzx z4eA|KDkOSasAi{Jh_L5Qk^uycJ=ga|*bG;78f)nP0QIw~HN~rT$!OXS9@VaWJv~3c z)(UUtqqAX(dYaFI9br-Tv&Kv@=X%PfvaYVI=vI=FUXXdFmE3Sac@@p9#NXY9)wmJ_ zd$;OoARpAn{Z!9aYr9GUZHPXlQ^*hU4j-RRzwqi?B8qpJ{s(M2O4w@BSXRF;*A%(f zAgn-?nVOMN(McsO4O0&kb%IipI0~%XT8*=AIzV09wLm}Untc!B{#d747nTfEt-Bn5 z3V(yrzFjEW`M33)a?p&=!M&|b0H#cVt)$BJEYiy);Qfs4E?=l=Vv-47o!S{ht>%ap zOMpkczSX?4$Uk~0$OAI~F~HG|X`d=ruPyH0lyPcHP#i3D6!RQ0`Dd(IFXq+KRWV0` z+;|O#x~RU}6-YL%uD`(@DO#U8)bXeIdTOQqXkQd+ApP&QHV`c%p|sDIK-rjsTP8pFW#w-J}9iDSR?T zdt1!xgxEXt!PkGMGIU; z;n}aG9(}U=X7t3fZjpdZemRAFfCLT$$P5mx^}BOu0@h6meAY65B z-J-22@y-7LK%DxVW2VjC(Lfs3LFHXBiXZp9{JzeeANh`aQN|@0%YQA&A#CWKspur@ zkBoBUS)r<2d(dR4>M$_mFqv9>gmOaEa>TU*Qr!U{8!evy0Ixf=Mx1-)AM@ouKVGWW z8%fknqtG!m(zT}!8vOjn0rTi|>pz|yH&s!)GyQq|x;Jjw&2`@2$ye@8!Lqhr$1SC} zHtqz=PfwPipE1S{#lv;%U{N{{SXV@}&6-^P}X)W8wDJXJTP@ z55rIH*4x^9k1vbe8-%9YtlQtj_YPvW8%-7}izPl*tL?@%np&8s>GW%wM{+|cX8V5E zxLZpyz0rziB>~d4!s#tS*riJ<)bJe{ZPy8R%v`H*BP(qkcT(+KuK7frqpF0>grS7`S+e;^B%_EUA6ptKLp@0*_7Pj@Z*V^_Zw<0?p7C(9 z5p_I&O&1F5m=$Ip^G-c&QNV%fI_&=dw0x$V-OgN%0YKI^@-6i3T?B9?5r_vj@by4>tZTz-tIf&o;i=;69YnAOyyR_)(YY+Els;WD3hO=UA zz0bWXDyUx}lB*EawmObTX(mY&doA{Tc5`96+Pj3@b=Fbhm?f4Fq(q4-_pB=Um`B{i zscO+k4S#r!-_M)9?#$p>kk*T zw|>s-I*ji7*qHe7v>U6cwk}hCL5jiBZQKP%dQ@ODvi78#V;PEqiw!bTQ$7}tGmyr^ z4lgmfX)=}c-bJW-iGv>LUv2w`Fu^^sjkh6g7U`2tmyu`@iCQUOovy?NdIx%zshqyx z`&T~f{?jBJ?6;BZ4a`!u#+QC4)TY*4d}%RhV}?of%WV^}5WwpQ3!tK%ozbFi<}HP; zFw?yzC%isV)MZ{dhBh{nDe?EED=?LGfnlPpmh$5yGH8q#sw|ABUD{6fv8De2ffwAX znKVidHrSA-fztM&$)!A;E-B|xO!f11{ouYD!_3h-GdxFaW(>xo^p}^%fw&iNwpN(W%4%Pv>5_BN5uAo?EGQ!o`@ClU&Tq)ZzhsE;UeUp#b#v z{I=t)#q|d3jU=mwBAwWx3Y=+{uQFz++M9lqQsC(3Sz@fLtCR(T5v66QR1K%n##!Yn ziGICig_KNh?GXx!To-axQWm94zNHAH>DQ*DVuQX?o^kv7Yk3)5Tv~-?T~iO!VMx%| zQxk+-26_T`b!HzSaxy1)Whm1G)O1ke@*XvsiRkOHG;!_?!xc7Kwz3&&DCfym<>RP| zNh5VhQj`UbITV(F{p+y59PPQb;b#@S$}Fi7LXF~E3)`JCNXX0{W^WWbk|e^ZRniG} z-fQ-cpYHAD+Duz&M&1S)w zec{O$g<*Cc;aSO@6s(`90C5_eFd5K7)v2m5m0(02!%VYPZU`i%pvRnjB^@)-Lo3qD z6wO0PEIA6rX=)i7vNu|W@-d3d>jo?PI2)VGF6Sh0B3lbm07aq>;JU~jcr`V^@~21l z&_LH0(HkVT@Zwc51|flTRuVQ?_ktwJD?^Z0y(6h=#WPZzyG#AqmnV=-dkAR}h5wzraL0FvbphYMXytShBR`vDcf#b`PywVf@R z-aFJMZu*F)kpQN+;ixJAJ-Vtx1v-sE2AX;mb_ryoN*QQsa+uob;Hi?1Y&B&R)8qc)2&w9ftRXSSB7q)eNx9wLOBC2hWu3qglDCYYjw@>jHsrP1{9KM*1NmLe0& zDKR!1K^`F?$EFZ`Nns=wK8>;o+u*S%MA zWEIh&ilF#L*udCS#PfZ+#@8wrO9xOv2kGojv4S?*Tc^W2k4l;;6#FZmI`p@0iDSIo zo(AtSML;o1M^Jv!Yx_Doot54Fxz*i^jqAR!{$*Vc@hg1qI;>tMlONf=Y0`Vcxv|s~ zI3t3`ZAt5Qe`0MsA7$g?$7ULAJvRQKn!b){DVZv(V}=C-OHOW@D-jjcle|{!sAW{t zi>a7tX?!+N?9sZA&fg1~0<;p|%g&t1XST)u=%BnPj0BQ+h~-5BF%bY|SjigL5MK+e zNhhSPbkjQUnDY9Gt0DW#<+p#N#=Ijmkk!mVB z8jQ|&9~27^q=Fg>DjIkak~BmN!H#Udx!rd8=95aq%M$4X=n3MX$E``JU&Q=rX~#V%Wxw}IV{kysLKs_>J_B$01pffN`%nJ>5@Y`WNPolCAvKVaai^o}+Pl&n zoAH!I()#@r z_JxX`xr{ONrcORt^XS0Fo(;R#xr=`yDbcF_TRVS$e4byNdrx8HF*{!~w7wPZUgh0} zw>Ku(+j*|4>Rrcx+})$J@_9NcW|}JP!G#e#H1g@kRv2W0vPj^OoGv!z<8IupWntjk zgq5q2K)?)Uxgh@lKB$DGutth}Ssy}y#;gyYkf1g5^ytjTg3Z$HOg>J(YHr*{-mJi2 ze%CRR+8du6wkL}@MNg2y(tmmCu~hg*p1T&|>FI>xY3WKzic-#9p3?3G@osJ2F|S2f z5Cf?0LJmVHBB1c|>d>?@1tMi24giCXE*@Ap;f{hTyjJ+?9>d%H<y2)|u!x zKVR>iwD7)TX=G~XrlH8iRZWwntitYHt+}xkvtsj@9E=rMjNTrqdMfI9>E@9cgWfiqW%liqG%GK8P_sZYpyH7svqRwwG<+bt)H1K45AFJx?l8>l+1*mEfXz^8xnVptG z8A&V@25JfoWGeu*JP9Obn5X1)7!W}LNuU)bi;>6WQ;hkV`5v-tuY}*s52d!3SZty2 zljJXD?F_G0b-!hG=W={;>CVvaKCbMIhuE7o4ez$|v+qrTgUDdE{^p~j%L*)(9;l^6 zHBkc@o*5yYTikfDyD*Xy6#%J`R8#;lsHxA{lTs==axw;_0M@6-)bY*-59T@+{!sK* z`|9tFdl%zJ%=&uoiJRl(&gB09XTPlf0KRx!Hcox5(O(rlI`@9`-&=3E;L7freZ{vv zL+@P9c8dkH_8ujmQ(Ym4D&r+BB`|(}2Hhlz;_w@|L3dcF>UGjMV@760c^Xz=?g@<} zT}oJ2Raab!@&pPPXi~wdNM(5q6;6dj0FpsxGy;P?NZ7qA^IM^I=U#Q^Z~p){J}Oy$-Evr7@Ird{>$i&mhHGU&e82Y!0nuu_baacXyvHPt&5A7}*}C?ins7xRFZ& z4wVH%$koP~buf;!V5-MO8od`^iyfWa-G$Mg8}s{jW_(jjr%C*t&V0MsovGN^e*4`0 zn!WX$-1{RpyyNXm%?|Gy2XyU@(|)|7rfhXC771|_^+Kket_+AuwK%$F(3b5pEJEGm z8fZ?LmW@i0Qfrb=001~0A%tsVI}J~)H7W&2B+!i~0=V-Wb6$r1sl2{N?Krm{FKgBO zI-|@>)7_Kt=U{d;`A?QRbG|xjXKx<&sQF8_vmIU8n=^7^BdG13r0>jjFDJIQK2H%P zY*Nz^TD1_%QnIBB3Rq8QNR}xQ1$}6vQrn{>V1Rxcv1K}k4j=*2myy}$a#?876`|qc z{8gyQBNZRFJsEF@zYKmH_caa*hq-=h^&Kj97skG>`BC#@v9h%}yrx^Qcb9f#cOKX5 zFOQp>ac1{^E3URLX#7N}tf0?9Rg_GvY}GXnkjUcZr>MzPz^Nv(wznaj;(XshyUGZC? zsCu)aJ}La8+@C4BSEart(e>VIzdyYDljOG8$KrPG{p?!D#_kmADY3l~R~Jfceb~g) zY-~LqaA4MIEbG;km{l`KC005`6w`2PUb2V?K9(fRe9`3u%K&V}AN zN&YY9J3kwS#Z`Q2+dC^@OT9YFq`RYK)voT#?%v$p*^RT6$6~hzLZY{E;4!jE{7+6T zCX}+~<7xfvx(ho=F0WL^WGrU2eJRhl|3 zl6y|MR8R*6Q^PEB#LzJTfTFLFy>FcBf1LjS9%iojDUtatgzO*X!GrAnw5-W*Htb3c ziRfL$-#wo})BgY(FdN#lHJ8d}BkH}Khofq`nz>}FY_(-tmYy<`Im~9xMmO+Z~_on6#ELsL?{LTD-Gs*}l8 z;|>wlVHrsnto~2(jS|R2D!?6TqQvrT$F#K?Whin7^Xc6rv|~*V_(8zVBBX0iyFW-|pi?UY}zA>9Ob9OGogZrc>+52)F)(1V0+|pN8Iy8vi!wogj z(;-VFh*^utAd6|-CY!n>iF+zWwk|t00<_md7y#AT)hR|jD7IOR?YdhnXV!lXtt+JJ zdJsip9r}nNDXSFgU{B>uuyFExb*RPl*Yh*4z&3Yhb%x|ln2&t*{`=ou57ij{t*4(4 z()*8nb_Uyr&@b`FGeKXM`2~^2VJWaQ zhrGL2Axn;>+*$q8ON^z+<*}00)uvlBMMaX9uCA&^nyOWfG3AoU1ZWjXYJZE{k_cTO z0ZITW)LIfq1JLK!Jzhw_l*SmeiUnI8%mo;VU;~l|km%;)YicTLGL1Ymm9V$)rD*Bi zZAO|%lzC}ncJobCBvqPO06-Iq0toipiVY}DYo4nSRUj}RQ~bVvmqL{orIX3xX(_xl zbka=nP2_?@8v_x7%c@B^(7S<+s$-6(onvqJ zFR5XytE?51l%^nxd1^^nR7I&wQ#aPyNH+G!0YYMg1H=7av!_iQ)K;_xzvk&-Lp@bw zlyz9jQBhI;TNE`B)Jqf5RLp=zo@rr7>RynYZ>@Pgo@@`lQ0mku2A}nQ&a|wm7&pSC zAGe_Q<~HcrSTBO#C#knq8)4)zuzYFn2)7L{X<~O~Z>}?y(rj#-ZTyd7(CpkkV|Y!r zD7O%bT8S|*Ep;?yOf3_ro--SJhdNRSPly(Ri>REB!}yw+3TO$zU@{u;qx!pJaw`i= zl?8$d15!2q4^3Iq!~${EUG3iN>8ZXJeC*oWFEvf_zL#u&F3Ox}?Kjwcv$eZEk8tC5 z#z&|(p2y5>?$x8hZc(+UH-uDsrj4jY71<=H)hx+NB`Kt_T*8;XPYcIvZs8+R=x@~~ zk};rGXpu{z@ZvS7V%;Q(klooe+^FB$u?rw|0Sd82%M=byijvJikVv5)ehqe?Uw3}+ z!b8cIQA4?qTZ+!0*@!I`PpsyQ7uF^(yKX#JM8Z7||$`pXFP{1>wz_yXd=<~Y0 zG{}-@8j!U@l2Ear0f;mlI9BGy(At$dul*!TvmpNfNI05Q#Y?)pH5Afku~$fGg;hSk zu&#O-jiEJA%G6q$!pM>^C{}rpC|07^%jfgspFdwdooHfWLvg3&ivHd|Z(lEO_*DEc z!~E%fLNrN_j!M3~=(>uQ$I>M!lBfL|;UOm==@eqOBOGxoa!z#?2%`2-0begMknf<& zsYc~62Ot4NGyv0q!SXB^)bS>p;6=CPoiUYTwy8BWB>3~>`T{6ac_xw27x4NIkDI&s zZSGBl@{_RlcTjcKALrrUdp~>aS_*?zlAOiYxP==!!7TZed9kdsV7vC`PJMzLhwpc=>dB z{tb1n^3&^&lYK3@z9{^T><-TFzvEk<3y;}bg0jCOi^=UB)wJ?d8`mLUBpqM0>1k^A z-X?kL5Q_MOtg;u5WKBx0IpMf31U5!7K~vqNC}i_ue!)!juLf0Dl3SF1-z_yH{wfTU zUOt_D4KlFPy+%T$Wh$PcpRy{aT&`blPq?x3P}PcRYP>}wVrnVbs(**;s#z@Yyh-C# z^0K(CsRa_6gj8`sKuIi3Xnck~b5RZ}Wrsi488|rpM#y{{Ye5eiD+pmp0WoC~JC?V+uXLNNVAhqLQU(-_EA4 zO)@VWlRTUrZc5J{%+w~ld(izJV+DTMEUx@&f1aK?>sp@fAE}`+B z+1Dyq>#l&sfCQDurD$nd)Dj0Ch;G5n^xw;_#o0aE4{!9Z%FWmDsrR&Mf zT(rOO;79qtK8-neA07cxPm11k{{TZj>iasdvKSUN)Jd`A5pT-^e<$(%J%~R%bUEwJ z65_zG00VAUPzTa(MZd@C?|C0@Ui*6B9fG=`wvu%oEW?Za5A^>4U!Q)-1Fs6#9D2#Y z5tU!1i+YQFc~Q-|{-WOWdf&^=y?_7J+q8s^&viPHm>V5N!~%`|9D~XBobWW`(yDs( z-Or@Dn=R}|;cRX`zko>kbML?r$E{+6*Q|u;1QjRK7p*KfCx%oOI&5s-^lA-2$6n!+ z)>ib8NI*kasIV*mKA^us0Q&ttzT0D3=A){UTGE|-;=kcT;6L+W?jXO}>Q07I5B?dF zz3eZ>mIv#9VL1t<#XRn0{{WwQDdwjC02;6!e@>sCKh^p4Odm}*M0Dj(-9}}PWcebX zaLW|3HuueWgT1ugXxO+S_OMGQ$xhQ#2|n2sPAwI;(EFizBf6#~Gd67`lAL zJpH96@7rsYQyvp1yD2mCWvH-q^D{4t@8^msBL$Gk(Uk;~?<;nF+S75^;@j<~3viZc z8!r|M;i_t<0z8izR0G6y#cyQclC zVNVV`Y6de>A~~%dGv}OYbK{QC#cxjY@BZ8Bvz>y6E!Q1azB|`=Z9ehrjjtwBd_G%zZ2qgS*@tmqHg4Xi zg^gBIcCG>%v^Jtz*#KW=vU2Av!Qv(Dm8=siZ6gXE)sCRFgQ^9<@bjpMMle^+fRUOzpw zt1(%6eYx2gsa25 zAarJRz#u(Bf;iwB5$j%ncUu*-ui%O0O1(%Z6oFn8B=F;!kF<0yV}5i|?GDA;`=4s{ zog6h7&f>-QmfB3tNwQe<-_%v7B~t{n)Kbyp>NZr2`d1h$Ro)8*kVpiI#>c#&+Ge+o zB&kUW(B!Bx<%lF#G#+A^`+8?|*~{KTC)B=%(~_Vb(~5ai{hyaj`OlP?4eyfQG?DcV zM<2AetTnjJ-%&2(GTHLkiL>=oJ8}sr;FB05$WB%u)lVRUN=U@=X|UWKlG<6Jg$&c& zc!6~sw{=ZTXe!5m;ZIC^a`l=cPnM_K*`tugS49rT#`WV&HjPAb!G)!5xrL`ii|?ihKB*A>07o9>1%>t2?#&m} z&NMR@DwPB^0LVEMG|!((j>#;rT5a*Xo(w3ZMvA_W4o-bfr=Luj&z-UE{0~-Qsyb@3 z3olJ<-MQDh6DME1Dd5J*vv!7aGr6$;0N#o!xH46F4aC`9!&4lu9PvXfIEic-S)R8% z%V&4JSZ{YzA!}&-IMEF#m39D{Wa@T0h(1Gr9eUfA=8DSZ%G@`HJdGn3P)@c2tOal= zpat^D>kj7m>9@BRQ{j5&CD+s-?4H!zy{&+%+xfiRM&YQd)=;aXCH-bUqxi|a0LzkubAUr85E_hIZpIh z-iEl<<1#6#0iFsMK4Xum&NI{I^7;Eq*cj~A7eCW|k&B0Vb%i%oXR%u*Dhj++HrAut zgKITDAn(Shs)=jxtZSt%?>tq~I@3!PIaETszi@1?E}Bb;Ad7AjD@dYRnn$Fd6{$L; zT}@U|sOB0i)hLUuzX}|#ICbxGc+Ug9v@K?WCZ`>VB zYLu*)!9cWf(o-VAMJ%*cV3Ai%1S*#fH3G%Vjb`>{-sEkUlCW7{Q*omy9=NLy*gU#X zA1B?bcxUPSOmPejq6eVOc-N1wOo_Mpu+u(`v%C#b#2LQh4MpImohDx+z|_^n>tbqO z)FlYY{{W`o`%ZbsY(`Z#7dnZ}SulU2-TQ0#bbNVQ)gw8so5F-$np?Q5QMbTb5LrlGUCooXeI_!jhzo$er*z+#q21;D6vX<2o~EL;u< z`g84P_4jXNVdG6eY4|V?`){!HUmqph%*9qH3k>mK2lDgs>1EehEFV(#M$hccpf^n} zUu#rk{?+O*P}V^7xqJpkZRBw|T1vHanvS;%m6jPqOeF!qS5wco2R-d`K`atnO{s^L zkxClpyXE9gDmtalAm6@^3OGRxsG5*T`F7%-RrBaqKO?fVJ#V|ZhakCq=dpJl#o0Z1 z9Txup+IbDlNr}U3x{2##gkx%Q%Pw_ub#+2nA*`t>L0wBtJs5>y2+qUKJ2aEUa}~s~ z(nc&7Kqjj|c$E~UaZ)`_LO0}l=1@E+4<0N?Ah9GISC7I5JiU5YReZ_a)q1F)+W0NU zi>u0YUf>Ja9ecPpwJFZ^3YNfRYjEQwL;O!6PGF{o8#kIi;P6vMB8iESpJ~n85;m!~ zIiu1YNJdc9V}=BiLU^&_Poe1yyp_BKNEX%^B?(ol9XeFjgivq-fL4N)$j4peK4MQ- zLsPeM`(uCYynS}l-Vx6>6*mgiQ9k6{(r$X;9$H1m5~Ln_;+VWliA88c3v&s%Su6G3`g;C9+S?~??gZRZ)?@Ki zIX%gf$ziFhV`I+#Q`0an)zJOycRaJ6k+!nkodY zl+L?~zs-8`=xhb4r za#@)qgx13qGEd{RO+2d|LYu+O+kBBjw(QF7Iz|N<2_+Cv;ZCM%0Z<2UuN1FE*Ph?= z7<0L95Jr%*24W?QQ&R<8mY}O?6*(0Kgy7r-4njaBdCx@{iwzO zpMOh*%k15sQP@;_lYQcFdlxl|ilVZ&e$~)L04YC^)+{Y{NQ$}CTd}$jBv$I)BP$SJ zNm^w91QD8y5~EM8dM0g-<7~XSp61{zu_K|UdexMNHB&=_TF{z`d72l0<)PS=-^;`1 zEjHKfeW%#@9oyPbzsCB_uMXTwoZi&jJ(;_9wPrhZRBilKHcxbJdW?O33Mg|seu@;R z6m>p&chyfKJ>|8%xSBwgnuM|VK~<{Sst+H8(udFZsz9OWNwsp@O|`!8cSxYNwGDP2 zPSj*YH3k0w(An!mVkxKvBCI-<{K9)Kn|J)7?j5m;#bvPA?z`Vxn{4E$vdc*wdEeAo zDJb`)Oi|HRR#Th}EQk+_^uFq z1ELizK(p(yM@3nqc-BzEi-t!J8=KgRkN2N(@lfSMC4D|etdx#v;i!sIwK>fyD~kH` z%em)iw)S=2cMiBrjB%Am770Nz#;O6nwY9xA1Ly$vup=1L+x`>hU-F+mmF@QuO}lN+ zaN60fBdKFrfWUswA=Rtx-o28i=AX#FlJ$F@yZf)zJ-e0b&bHb3oHjC8Cf{3|raF$h zdv+G#t(rNg>FH>3xi~23>8OiUHbP0Nm_%vfNlyOsKIxOmR{p@nWCe!dc@FP+at@Yg zm1$>d8l^PWXxeM0YKBFIB?L5uel7n1ygQnw+I`rw*qr%5h^?C~_0N~Ktd8hMk!0Xu*y zi&vLShC;>FS4%Kwgr2&SJ04Pp5r%4-31yOr^8Q(=9tzhAe$D`i;>t}OHiQ>eq0J^2cwq4GyP|>NOP7*g6yd zM8yeJZ6$n8@}o|ZKRYEHnGM*~aa2=c78oPO8A3;0SfY632_-@@LXr9Pe&a3CEbSeM zi`mq7F-vECbrQPArZ~uYF;Fpr0^*}k#{-dGt9tg0xbp+;@kln&9+-Y^E4CJ{j~V`GB8V$#a78vj-%I1BwBjN=b=Zfijx;nFlLgRx-+hy zQn*!N9#EbfNCeH;t|)YaLQ7Vl5(g464@K4xSf$(-Tds%N+EwwPW|B2+AcbXUzf>el z!P%oEFZL#`4nf~^ErYNIG5w9akQgShDP?JvKhOEuD|SPfjtE^)+~? zarlZxjtW+SF)W06WHLz_laE#t@7A+i%d_((#gWk(#^}KKQH26UMKwh;XI%!K6rs;R zox7Z7w6xkU8o=C740HI!ODat)^#K|+caOt~G{+Mn>m$BG?y7nZcNR-}ZYYgz<13e- zdIZK|Dc&C~Y?WGKg|^i+nCg0Wubw!>Z8UN;t>cg|8jCNtt#=D6dzoXixsi8S8GKn8 z+P)HvA;~OzXu3i3(?i3iB)R5&;yCVarV?5BeiTbVt62aWbttM`z|vhs2%`stE0++@m&$ zuiKlc_Zf@5>}K4kF|!ud%HND72A6WA0>D&PfdZ%2cK25I7j`#JV!K%DJVY*)VW&dJ zGBd1?pz38>0mD(qU3@zdS}H1v+BT#6Y38VDBy>pr&YkK`r&tyXgf}*v34BsfR+;#XI99z6wkYS6M?a2Afxz*{44#4Ay&BhV%v~WSSU$rtfm{Mu!H;6D z?z%};Va2|m(*ER#n8UPQ$Z-0Q{e-_#9hvZ~ZY3l2iC^a3Z6W-uVawwFB6g%WEy0KD z?AAxODX_GigPEjS>{nk$pT+I0Hbb#%={&HC$aXF+vRtm0VHtWw59!r$A1avl9h>Q{ zCy{L?z9{k|1!Ro)VnU>X6on*KhMYjC9UF2%hWB~Bj`f%6n)=;IV}PYib!2u{x~OZW zxd$U)?~s4XgR1v0#9X(+{h`4O_ zsV!Ctfys7vYP`~yXJeI?7DCoLltptR0TTH(lG4_f!3{`%EP|%9o77= z{{WcJT-F`&xq5TsZC`k7pNsiz`C6F`(YE?ic6FBY+ZR6{?^$9j%0CGus@|+?@iC|idbYE-=RXP|ReNzO zfN4U;R1PUXHTZQPd`uY9q}NM&tR&J$MI0)4elS)bsyB<-p2!)=lOJ{4I+O$^@xjKkD)*9!W)nEf%kAb zdc0&&y*gM^Vlo*mrBc*1%{ffGAcZQd!C)-L%)mCCW7`6z>LKT#{{V-ozzKhyIy&3G zZf(xN=|6_}`aSuzDKlGdtvBA)-I)E~m8GYPVOPoByZ-MnGvz{1y8OmMnmtpTahfMd$F{k<-!@M8cILVqlZ{{XA(=np`Ir2l`33R&G15KMI*Nm8Zam*wc6Vi0_5Q-G+WV)ld+)DT6)sPI;7%8aZj~_=wttgebbb}f6Wm=SR}W_tMW=|55b#tix`Nd4VhANxqyibJ ztc9rZEOB_!wH1XFR9Ef$JgfH7v@|FEXY!YG?e5gsUAxk|zPqgZN38R;+n;LI;;HYv zvBsv3Ty}Dn9A;uXuFmY9zuh}(vZoihwzf$pqudxds;O%!XQYx;E-ckh(i8TNBl++@ zl{3?7@yMm)H3U;M{K5SH0A>yiIyabI(U9CQ$=k!Tn_=u8$?R>Zn&p_& zElLtk8r1RWU)0^msI4pLUeE(I6mcO%O#vr|OAX8M3o}}X_^yp`;!R{U7 z@dL5?&u&Z89nG;jB8zWsnti#ss=iiNj^o=u9JgIYFLh?K6&*Fwof}8Fsj!&dwx+1X zW+>_7dQ5`nqo$12pd)aK(V%9Du3E(uRhTb~09oz{3U!$%N{SQ*3nB*8ACYaARAmmf zzB3$9p9Y|!uBuU~O-yLUzX_*7hr~@dpNzdyVyvo;pEr!i&ya&zS_$f*+*vwmd1@iM ztcy&ssuut^A3_v+Q+Hn-2A;( zV*5=M_&Q-SRzj&B{bajwV6!=rAE!j_Wrsl2ST|s2YRU#lpwLtk*O6`6qY>N~)T`^0 zK?F9URy{z~g=iW3K>3kEb3RI*sqK%EdA-B&gQYu1;D1~0FXhwNSu7V?ZeEkebZvZl zpKK=Zs_OpIs_R(ms`ggdpw3p&Q`1-G>eC-4FByeXk(2HkI#i_XdvPx7Hty01i~y>$ zhmtk{G?{2vDyr%v20BSW#E`dyTEMnZ+G&!LcbzO1>c>z}%C2isk^yHewlJy!tTo0KRCA^$G*hM?CtHezBy2BUE{dB19srHEVYZDkF~KidjooPPFH9_ zolWn%XqvvU=;oBsPg1q>)ca#`ed-&n!GCw9j@EQ2cktqKs%o=#v8t5O;j0ySByQ?x z9aa%$5lh}I_XvIi;y7I*h=Qs+gZ7fOMOCIjprNhspA#YZhu3TI5`%Ea34? zb>8B|!-rm%`B^`CZ>W3Ir}nN28Eav}>`k4VhMr7a7|CVQIBG9Xk*cM5*ezL>+Ofdb#$6qg9Beqe653ud}5dA!Deh45N=n6X8S~5?Q+9?oclSjlZq|K_o4;=^KPMzuynaHeoWWGGP|<$u zty5i0ih@mCywUBOoOWaUZKFXM3>QNepd_(X01~B`p4h{Y+*hl_kxMnWyqrY_y0a3% zX#kR=NF=iXMF1T{fN`F$%lUtH2lD&foo|T4_dmhz+ot&i*PA~JlI&?W=f%UnA+PNW zq!jXREtR)&ol}9_TU9anE%#ATOSe;WH6}}NVvRi0%TXFUk*tZX9yv|6-6YXM7(~h= zlU)TsjhUz%kbi_N6`Z9-G-6=z58iRYCXi~Yx&)~-cA(T%S0#WXZ~(SCEuB}{m_3V$ z`2m-o7r!F@1KoZ1SG_jw=G;3&C%fo(r9S5VGq|>`cIw;o*jp5w3~p16uoV^yE|;X4KVvzDYJW@Bb~-)4G4j7LqxxQ6!GyPYn5lMF&s@svI*=a0QNQk$^*OED^gaT8(0=Lo*U7 z=i5aL50I#*&nDWxmnZX(>OY-Z_iS`0Xl*T>)*bD;ma?y?x1U$%Gd0~u-&HuuDQYYB zeLf#OQ(vCzPV0{yj;O4I4_8rJj?2YQD$&%(R)&qWEE9^fee32aM+eZ1jAtT%s`lLChMY5f#%CoZMLgA23p|zVsIpIyj;*Bo z8KOu5kO)DW>tyI+i0DUt= z)iNtIwF6L*h?-MoZcdwOUv&f;g4hH6xa)4T1RpX#)%kQG;4^aKtLSn`EGbz@PcPfa zP_0u8HM7F;&MBt~QfMWkmDB)0Yv~`?+N6}m#gx+&;rXAIdTvO>>O-leYBT<$(0Sgw zhr717$6fnD@tbXI>H9AOvZ=A1X#h+XHcT!)f}$U|+gPY~9xA(SEEM=rEI7If*j|Dg zB03ntueB0gUC-ge^?^~OQpAF2E1%7%0~!;iw9N=gw${<>mP>L-R>zSv!8{EYHW8=O|c1Ml@8i>F& zEY%|#s^pUG_^Cw);Zf2<<df*@@&~HB3X3ySKWtG} zZY_EGr=iDfeB4{d84k(~Lq|g;W-%eCl*~_-DBsy+7O+WwZ+UaM&m0ly9u#2Fsi?VX zuvTXURZ9b)EqXRvs9~|awSB5NZeF@2CYn1yP_)X?hN5U|zzm+W2LAwsIPD$Ti~eo@ z03f%fLk*Ow*;|upblpzg-qibFHI2YzXlc6hZ(-J!qPC(LG3O(Ptfg#wnB=sc1ZEoC zlJ3Tmn0JXp4WQpjN%9pUnF4~mMS7<6)m@2NMP^F`Tx5z#E*SdIgZ2;z2BV_6(cOCo zW`8V73`=8sXK`)lKbmgUuI)-blGxJrM`7(wrf-gOWA_IC0NT4uWHDI$wr3Mhkf;>U z*4JZbs%u3(JhimKUn&{R9I_jBf&%W5+?rN`zvB7~37xB;L-H7hZtI*qzs5*;3xwq!g+E^Wh(0jY1wp0~0y>|NxU{PZB zT}^K5#&wSB?n>$ya#;*KS(@q!9Ijfnnv$YOBUuHut1a0!=w#hvZ?2dYZA=&kc@{>E zUWut81fnrj)fxg+8i4)l*&C@=#mCbiP%=&xLbK5KcMw}i$R?aeUr9>1>ndV`l~Ji= ztL++Q`!~qY)6?W>a=IueX(*(Z!+h3Gz2b^D4j~N~)=F7T?aqY~EeIO(pE{l%fMoR> zZ?@@kx`wrXZEaxvY&vjgYxZe8K7ZuslOuNJKq;&Dov=SX{{ZzKzKt7q8@H=6c@4^mi^y)6 z8f~|c%ETh5uEo>P&hw_;Nr-8vAcRz`vO=XquON}NT}VCKSw*1HBD1mYBaWd#rM&wn z08@d)3b7|5U{RnoL3(K?>^wgs{(h-P`KRn!u88?N@H^)ZL~Lp-S95MZk~<^f{{VaM zItR|C3Y_-Q3SGJVxW-gDdI$Wdu6+5k)aIq zAU1U<%V3TJjcZT=Yz;*8NzHLv$FOc2p+)-JP>zghJ9VnE5*Sy+)DS5RQp5lWsWiKF z)O^*NngH=FE>Cg9P{bXCKj_#8^4YY+C2cLNamcW-_8!{7jKe=fL3Vwzc1ELF$!BL4u?a-@6rTBnzvSrlCA1dCqQ8iD?|{{R~wd+XUe zdjHnjy+{F(i#C;GdkYJIwmg4B_5T15Y*VE?Jo@CIs-e_%DzM>!4hbsC!|D#7ZHkU3 z?CaIx*J{e7f#|qX{ZYpasedX!_iSN^{{UCdt<(;(5P`!ux`M6A<-u!TP$a1b{qNg) zg$SpYR3v7CoqXfJ;X!C+{%l?Ar~<#}iUU) zF5%G!Hb_O~mVg2JWc;y{{;oX}&B*A#9eP$Yj)plP>pA}b$~;bM=X#FB%Ty=aO6+5k z!ly)K6ckGWPuJc*)SqyD8?UcdcXkB|91Iw<+t zb0f0LX8HsXh6K0tC+Y~*{@>h(VJ!f3GzPV=r&fS0O5!t06Zv!)XJaIyT&V|>$hZR5 zA3=MMVtu^R#5Ad=`j71BUAD1B4N8(f)%kRhXo<*Eqk6Se(T*C!{QO^5{ik z!&3x=JZ_{qIJmL)XKT!N))z3{+04l_c~j|(gXC3)2sk4Lq8;zs9fO&6jniS@w#crw zo7B@ZY%pqdE2}LTWR2+Y$fPnb45Sg!%lPHu9%u_NfCZ<|p6i~_ge>~W3RC}om7lxHzz<3VE z$xkv=>KrIQ$5prs_;;xk~2Vc)AO$%mq1;k?*9PqKI=3#OUlu#40N;0C|H6v33Vyr6{ZOA z&3JInO*DO#@mD3g@_oy{cYkwl-s9fXQb)e%`>W!IUwoy&GtRK2b#rbm;O@uG?j6aE zpn)lWh}7$j3P50`jyT7uT6?|8tGB(iqweJtAnE96 z-*pdsr7+mv?fkX-qS3*#Xg7=78DY{WpbJY-s5077DWs4~6P}y5$71|K&Qa)Xxv+|r zbsi7pS@D{J@-S;My%%VQg;h<|sn>s~KHN`sIZfz^KIGAGI;?C}xMr*+^K9eG)1;Tb zbkB8FStN?uf`n@3ed2t1;zY?lWaHDSNcruF>6~>Y%-$VY3~KkY{9hSQQoVln@043a~ZD&!c15 ze4*Nw$dCTI&(qOBtfxGPAie+=>|uK_`d~8>rgD zm!-1WHd{q|tC=L79x&=!MGakX;c68a8dru!0O+4%@|k_*x$5BFx!iRI*UfH>{(7qs zfR87Xsm@11Uo0DQ9UDd}DQG0hRIEcyNsJnFGL`_Zvy1Cpn{C?B?e3ZH;k1f6vkt<@ z49(;isMVCOcW;sC_m{Z?+}-B>+(pT^YiDtA!-~}Kb#Gks z9y4oG&%Qf5y*B4!W-BsN?y4=7(whgc_Ps=2a@%+&<=mZzwlY;x&``ID>7t{Kk_S_z zrM{vXk8$?vakqo_&7SfC7FgEZt<_dAXb2J->Xw?^kx_-g73(E7kGh|{X>TFEPG47_ zOR$#WAql_)aw%F6N$6Ij**_Yz%^P>e$mm|MMGah|;wMj3xRN3zLrqgt z+-%fWvY8vy(l<5&z$J9{X0biRmov7FT0%`~2XNrSQrC~BK7Ag+_eu9dL=qVJYKc=% zs=du{a0l$-Dbmjsw|WmBJ4sFQL*&IRL^Tz2#$xzy(uSQyaE~XZC|Bd{1w|!9eT;ggSu4O>P;qkje>JzzwU5Ql)AQdNXgi$Gws>>0VHyC>8q4 z@lXv#NEtQr!Om;cY`!z&K1wvDm*i*5DQU|1stWu*=t^nT-L<^QP@Ue+%N&}I15;cD zwXf~_ZNKjMX)lcpk2M2=D3FfPC}v>au;!{qmumqvYQl8vg*fyN*WyKeMHO zDththKmE%1ujE+Qe@`IKRELzQtV~7nVHAPzuo+1vT;& z@n}ALM^3lh2j7PS#a>ME;di(SdhkvJeE!~~%dq|?NM{)jk-sn*YXC{xAMqcd9&r)~ zrKS`UN!<$_Bu!u>1Jv>cxC5VV!rsBcBV)GnLp*gV1eWwQ7}Z%tNU0wxW7nqQ`=R^b zKv*K=;iD_6?{EWEO?7^mEkVPGr3m3pu+;27h|)TlenouNZyK>xr}&le&Xhcp)JIh| zfhTsdqAanEI=@QY7t&9=CFigaB%wAwYCjDtEwI2+xgIufc+^(}ijKD*-2>l&#y&|b za4UPcfj|gakqM!p;sL42$m<;4XYk^oSii{6oH7)71vozyJ~_duCD!uIBM#?~7ZSP9 zTFk06f%GBN+`Wlf73KbC1&FWfTM%hX{{U(zDa26J=cZrodGFeSRz648X`igzs0hFx z*q^r;^(310o|~;c8Pgy{`62VAlgkv&k^ENpNgkX5^Xq5sf$!mwB=9*Im;x*HyO_Zp!h#dW%hI^v z(EHY#v*CwY(`P9r-`^oSP4^38pCM1({{YLw;rDJ}sA0j+S5c2mvxwdO($v_7X{#Dq zpz9*dEKoQK@hf{@u=8KEys9q8EZXn((Oi`AHN|H;zlWF0bqMrj)gco%i$DNOHwd(K`GK$&=2Ja z{Jw;e8HsT$rMqm29wsNlz|hw=KEwmveoR&W0CP9OMStQgkOsUcJZur>eEwZreb7Dm z@W14d%DyWTU-=euD8TX*v%o)y8q{zjpl9S2N5W3{$85+W%l3B6tl72sTDofPz5ZI? z3Oc7LlBLS66tiP9IlYD46!~h%Ql^0lF`+P0;GXX zi`73~d}g5AdCj*+**_s=pw3BD^%7NlX6i^Qs10+Y$h0+7UE5&P@rK*#5`!Ty3+)RhhRP(%wXq{SHMC+c=O$YD{u4M>NWn3{Yn#_8XGF1zQhHq|vQ+UvdPk@#QLdo!?b+e(UxI$UPmsm^uxeAZ!i%?>3Z z5M!sVq@u}EQ!2wGjTBKT$?Wb7Pqhx?VBCF8vWc!8v3-X&?>k{u8U(S5d3-~wsN0koO!oHq zM?Nx|hOO#;VD9Ls@>LR5B=yyCbXPz}`xHR~~r7mXezj!9bVLw>(tU%aiDo8232 z=1cGKLCf2607q?9&!`UElZt|CP)`bV@g4o-_Os3RkK62`w~xgfv16*W88m=~B za7P(ukzfVHRkvC|w^4z018WFXkdgr>3e^L-TeJaC4nZTXe#^3NW_a!6Nv?c2nny^( zN@G$+vQYy#p#IUcl|&kugkw;b@IxrIopVv<#nR*#BixvZSt{~%5>f4AP9xhvu^W#k zO(M?*IEkKlDp8e^nTjJT>GvS)mr+_=!M00kq+D*6UGCqat>Q!pxC6VuMHBHUgCQyd15T|Uz2dH-?5ddt4+oB;r!}uv zH2{LM8RMfkUgv622))tjQMv>sVlEz30kf6|fS4K(+z1tU1b8W)5-E6T!@)D>JtH{$xUg?T{pj(9S z)nSzDjbmDxIOrOps#>InBm6?GsTQ?Xrx^>$O*6o@N#2{wX@)-22<*3D&1n=!t9YqW zC~j65?Ezu|smkL$-mP4ac!8XC5zf-d0KS&=v|;LDQbW4%V3p5=H3g#ZC%d=;Ryj)a zt{Li&Iy4eViKVZdDPQhktA*G|tw`~sMO=s#9pP4QPOuD@9?kA3H15& zTo^}d42>SBkg|ypYE@nGv>Zf*s5pfu9&{BpcIle8u=fQ{=&7rcx-2bZxTgLeS55pT zqK|FONMfp~rAab4$_hFHR#1`YnTrN+Th%sfJC)AkW4Z1dt<1CCDm4inBCK(CwH0dM zqR@(BfwNwwZdl#g=b1MNcd4W|OKia@8wH8d0=itKUMSH43>9e2P|OLV7O&u&pK9T@ z&K|pJ%b%&rM;&I`$WX;yNmnH;1!vgRV(@jeA>qr*9N`4AM5N>VtsA2=0hB;Fy}Sg+N6B-@B0 z28pR}aOBWN#A!z=&M6MZ3bv1mD&p(h&H8n?uL}d=1(I|{ zkceXl9*)|0W~0pX6Kw>hZor&i@(6i2Y7ZLM z{GA?-%IrSHi*9wl#=J+)9=Q1b0J+z0c9%fn_eXy3_1}5At%KV*syd8CHreYf``9~2 zY*qZD>e%O=4UxR(uZCJ}uU#f8uMv|*YQJ(dpESb)TSYXI>4Cg6B6yCZ002o@gT|(z zgUSec_L3-TJZyaJ%x7s4F3%mzu#&5A=1_n-l}3|DVRn50=xb4$RISXcs2vrqj(6b`}Uozy1xyxW-LV!zV`=#dXc{SYH z_X(d{u~4c41Nvx{?2a%Bq7qnDnc3uLcKPMyHs(FH!`9YSNsbWXsTz@Eppv-HJBu1g zj8et+wn1?r)VCJ5xj;x7OOeI3as2btqhW9*EDKQo0IHoAD!8Lb6bVT;Vg787&-(m( zRsaYzjC6e-Vl-@2SLf7CE1>CX`r7`IE$BAA@AW?RDiq@f{GB+4izRwdVz&im-lwIj zrwdUDuf0tatilR~jy@Ii@{T^L!{~nmaqg?}sr*119-X(P8G+%^rtL{~7ggfAH#tqS zHs0{9?VhE?cLjS?t!*mp>dcny-#a>^X~|7j1w=KqSlW%7_iJ31hG^=-7_}j9Z^*L8 zBIs}qka&L(2EXK|PmGOZni~1~dUSL;nxAC$7RtqTX3*RFY8r}Yar7Iv3q^f1j7z)xZZ$38(t2 z{v7mYHWZi~{{U+B1`Bh7yKi>(pIu^ekk!bLw0O+M=)>ctOoyH^{7tYoKf?a4o289!w|VCm~6F~ms(RM-7qZ&v;BQ)_M9 z=Ur|peaLGXeZSc`$J*a-6)>GJ*~|?jJI4cDC#0yQ$?aXq;Ixn>rbbfXk*rF}E{F*L zu?_n$NA2_cx-mc**jAYor>=j&j*U$Q_pPq%O{3RTSotxL*TL1jX+yYXH90N0urXVY z?K<;fW-}P5W~9nX)Y}IekEMqr_C89SeGCM~rD7_{!V>ZqJ*>v2pNg7^^!a9=Z%#ag z6mdF5c={2KUsGO{^pxGiwE4Mea=QvF?JhD*Ej-(1Jg#1rs-haRPgPiQ^V7g)r^eU9 z(@@P%5sIpkMe;|k{_0e+G1gbi3R4Hn*UzVwnOT=jPwmL#Ps^(c{$E{h@~;uU`qHoA zO)pb-&(6NL`6t+4Bf8qBx_4yM`&$LDyG!F<()h{pODpm#WIteRo$*=IJ7*VFw&vOU zqij7^QiE}1sxYZRRZUkhg~)B9`i(I3Z#}*IzrIc2I_qfQ_BI2u zD7QcI@ZLC1z|VH~&01>dw+mHaC8pdtd8zR`w{TYCx5nY})78m{u4Y;!^$6EiF_ZO@jWi@Y?_}n84M)Y!_1-({dG8upyuD|C;3>0}Ir`1FS5Yl(B&}4q zYFd<|k~J_vBi?UHo6D`!OKfff$ym^=f29&cm8ez2(Mu?OB&}46__2u9r?;$NNT3SU znTf2Y$dstk0afh`Nys8U&h5|hqKD>&aXxbP4@-3Sd+#5D&rP*zz9!)JR`BYKPTS1( z4O7zfzVX@JlNS7>-FeKme*rZnQnxz_TPUz)ywHmGe8kkAy8;rQ?k?NpUKaj-!HnG zdu_evxqd0^PP5y872x}$IHoK;RmGICUX%{>0o&1SdPSJU2ZlRShftU(5sVK$?vv3+6IhF2vIVuVmU zLfco0+ADaitrj(}bdLW32q;vr2nLXu@YDukTRNzqP|tsF&ff2jnKV27df(!IQSUCh z_}#KPDkmsv^mDr(fewTtu6j zZsVGUw3#GmrIw!`S5&Z?N@-?P<~DbkBf5{U4M3|@0%)MtfHB1Z$OIFfoGnO)iEko; z#ZEvq01_!$;Bg>RAXdFxSHeGppE3Hjx4(CPXzfpf+e0nh-xG3OA<`Mm{{Y*2`zw*^ zJTG=_9lgGApCS6kBiB7!xv`mDsZoKen-e7^C4MVC9^k~lu+`Gzno6pxUt2{LuIXaC z(lpNN9KIY)B7{S!ih{_+-59iL)LlY1U_ymwZRd(RxF)!;ovoBJD%Di84NDj-z>OX# z0zv^HLnr~VE_31k0L{OXI}@We#uEqA9~JjTF26IE+W!D!wFhJTV%S(rT?HJKRDUKh zTT69yp7HEG^ z!z>A2Gyz2b--QHoR^k~z(b*VoyT)xDhrbsgyE7Oui`x%Th{_D!<-kWt{8mMys*@P> z&`lFg8hHxmSf`t2u@TDlt0#LoB)5c&P&Fu{Qvo4R2-GM$MGMI!k;i*-bVqO_B~?EL zw+c$smZ*%F^;V{(xSEfjW1xwGMGHo$V4yh#Tk(JE{eQ>Ufk8UY%c6zClUj6fJ|boN z2W9qF7j|tgxuUDUXE0mSY*suqUJQQt+PQ3QXK(Hdbd=N6R8r(9ax{=Ubx}InMNms} zJ-Z4~m8n)F06j%O{{RW=VaTCUK?G8t=IiSdx^uL-x>|kJxbhVERHUH(^KOmFmCC_Q zQB9Mhrh=m>DUTCDM@{8g$yx{_r-M~aq=G2f%Bcz5Qrdfk34qKMMOdEV0Iq6J`zC{< z$dROm+zOXu1Ivy-A)hmfWb|A+leVSWQFYZVbvJ#|?k&-}@K_DE)ZZTH`nNmZ8&0>g zCYu|zx3_Fk_KxVXOWR;ZV+i|OW`DR1&Wp+ z>yymW;Xnu(?yJhN#U$~`AAoC@Mt>FR0r1pdM!yJhMz<$TK)`L4>^|M=F1_A;quZO) z=6y!O*!z{R8=EP!_D4bQ9G2b_XDIf~H89w;8^T=1>ZYvR70^TX*l6-m>M}~H;EHJx zShKN{=@u1cGJsSG-mJ})6hDNX1d0Kg3=XI+uSD`h>24V-P-9Vq6=SObNE~WtX{Nm= zvEMACsNIlk+?MP9VmmK!ts`Vi`}1J@U#Z*J41V0GNh5rm`&WPNdi}zcv(>>G)MBXe zv87yzMOWjSRA}6GQTG{RJ_-Wbh0_{?isS=>ii}{9fnKWDk~%EKpaJLr@N|}_twu;u z>a9cPo*f7{-qv2Ik#SY?wEW%`tE>9U zc;<{#)~?FO?ua(UWnK$-%SS~tl=PF*!wyE4IYlSjR@2qeMQ@_Bj!4wQF$B{y$x4cl z2(3Y=q4V+{bfR5cxSB&8R8dmC66y*_?f?it_rLU^sHHe@z#x#bvpzm{*3<7zfd^-N zr`~%ndiIXtN?xPwn#_MvKUMCX=|M}8%40faT0GxcV+iLMp>c3YyRnKw~6|Q~*VKtIsXXshN@&2q?-U0hAxd zKtLCQcIu#MJZCD zR2@EG0YOfZp;-#}5vH|fAT|Kj0+LB;aIX_Ud#g}79XdDS?@xB;X7BCyyy~#k**>w& z^^Fb>thOG3aG z?xUJXF4@{*?4_B5zA@pc$V6I^!%;P>RGO7;n}l#A)^JF$v|%d3HZ<`*7ku}VN&qOL zp!yDtj`3ZyBv~4b-MOl8k$_6nw~d` zd3_3=V5B<GRxG1yY#sYchz;?pNWdUIgMkJ|Lqi6uyhjwq!|WGZA- zp6tzOn6I#Wx>`-`r6fpakW&XC^GaX=N&&LfBLWY&DYU|yo z)Kuiwl^6d2l%+TQjGy8YdG1@aqIEVxy7=x^1SHaW?@& zU$TUMhKHc()cc<)6%;?cExy`o@;_%Em3sOry*)PDtjq42R-~dCx2LS!k6bF&31i1X zxY`QHVu56u3d2mP8=n&^qAsfy2imyjp3guF`fXQmLmE_t1ww*qzzX1uR=rR5ree(N zm64gV+5iVgprvZSRM+k3n$HHgnhP3$vivT&W=h^tJGtk$r0O)p>-jxFANj#oSwEYkI z#>d~WLteMnFzWX(4*e-@e{G zd&-@E|JU2Koo|0nBU+GoxVp8+(2@@~;@;TL8u@glzI}CYsmZy~>Iy~0jfK9yKx}XB zmD0LSTA$(T*vadV0rU&<;ZcQ%VWbrbcmt3{kGk+;DnHfyy3zTO)TmW|OF1D1g$L*b zt@R(`2PfT64K)1vtpV*kKh^#ozH*<>^?aYrkK_v$E(XKswKq*Hmg{_d(!+*O%vd)U z3_XFbjST2`ndJWfj}C)e*(Em!Q}F#PRQoiK^?qFwjne^NkG(u!?gLHMw6a6wfSP%c zcdlkPl9GD`AvEccMeQIXf<3?`tL_Iekf1NuNt*uv!eXcTzI{O@nR$blivTrVOG0=M z6$U=eA8$otD@?*w^6OD9m;E}I#%-inUscoV&Bw9Dq_m7QbjCkEoQ`cl^Z{S>XP~b= zO{PedwH;clEx=H2tOp=D{{VXSFS3@X*0;zcx zwf^B0FfD6={-Dv4`dVtDsf7SBz>S9i* zB07tdAc6q=n>V7sSSdVx82qZdhFg$E(86v)b{{WYdT+*{pD0BfK20-O~ zFa4>I+%BL8)9OXR_h{uNozx<=Kj!JFtph8&0!ZLKUZ3ju9)iBy+L(>wLrDYBMKVWS z=OiOrP=%0zW2eLky77CT>FiCh^8}lG(=s+`O7Q;xSNZyheZuzM-xqBve$2(<5CdYN;v}GzjV`{{W4&3kI8A)?)V@FSVCm)o=H3qc<>Hc-p8zR@0}|PaRdQK~O$@ zMmrbxhWkykTuT@F(Q_MF_#h;!b!4&`Yn5o~2ZSgBks)eVv(usT&tgSWFc=(xq}0m< z@ZvHFTO?Y*h}4N|#4yUS^4bHf_!s*7*!E&W5(CU{;$ppvKz#Jj)cR+p*Za(NK`~eM zMU9|yk$c`p*i%4iWbpvtdi0@(=if`cWhEl*zSKx+XND;u~Ao09Kkh1OX6olW+iR@0GlvU1;9T~r?@Fy`oF=|szFsC z{{XA}9c5X-jh94DT&sy1{zM6@h}z^Lz5PIrc=u8?)dONjw zaq{Xacv5b+Bj`Sdl0Y~A0B!Ht)T8kc<-@B20i`~Dc9M{#WMyj-pp-vR`BVLMf4qBg zfDh>&KjiDhwGpQSsVh*0t~8?Q{Q-$6*0DT`v2XAkU)ya%ryuJ70B5aLh7D>w`slP% zSzSYwZGTk&Y5iYc&(h!1-Bjq+U-+@r##iD!Wl0%4g?w(ZYh6qOlY3mCJfxt3Vm^fX zb11bWf3g0q9cr39pHTGv4W9m@yZ~DEEIy;@?xvL^Rz^B_mdFC5?D_uyldQUc ziLW8Lg29pW02MA-Nen}$_IUdHX^N_~2>=8B4z87FL7-Bj2j+bK-#)EJvHm(>qWBfE z`@195`wwkz{k77)Bf4>$ldZ6whqG()n=7$<4KN?+8@wT}&ty8+vUi^5im*rgVuG%= zsimup8iN}g2@O6#^B*kj$J&jjd$`&yS9*hOv?(+QVj5(S3OU!Jc~}#z+f=ODfmA3$ z;5Q(9!MnHK=bJsVwdcLk>y+;Kk9me$TlrwSRl2gWGK*ce^cL@Lv$tr-j@{N6L~$__ zT)eF;)re{#zJ-k=)=sHe$&OH@nC~A2bzA6pQ|}+N)o2Yr%12r1LxZTbX~0t=zdt^) zBk5Tg?P-@qxVkVpu5J#N1CMtal>9n}S7I5^kHTyIuU@3bTGZ)i3&u$|eM|vUZBeiQ zDbxNR*WDRa^#?$5f5DEmRt1QVg(HB+&bamJJIHm}it86QCsK`LP%PXB)IS&c`||;% zRPo3BS6f;>l6ZB@NVg?KdTq*?Zr?yiBmh;vp(5V(lmH$F{a>@KliWsYk1Btw^6F9} zOLo-~Ds%gi0#{YavY@<<2o|^&1laqb6;?h}{k>Df(!oNKO%DuX=jHZ!^v{sUV5G-o z>GB!;Rwjm@8(i63oqa?UbU3OTtf;G!3TRRYn47$c4S@QeZ>^ox(?f4-ZzPuz zFjPcR?96xot5Qimoium7yJl&(ty%E)bME%{x6!flO>4&B%tX||->+lrq9SworMyT!JI z`BwTKe+Av`gJojiMX#+%Lk43x+ z%8urbB(0`1rZ(&3JMW?FJbw6noOR)>9YG* z0o+@AF%HbjzF!HKdU@z8XT-}_M=_1*tJ;daX_hBZ@7VWazjL%`JM?pq9 z+R=y9AOK~e6NEV|272e8GJV{=?Dpevmw2Z1Tdov%C%S$CyMKm=VHBR1?;xTxw6B_Kyj?XP8 zh8B)uJW`zidyiu9r=2$oJ6PowdyTVPeyB-hg;@!#FDy(iiQ$kj-y?o7^Ax1 z@2%~`i38er#5R7JTXn<2z?QjJFw662Y?FzokrpD~N)@rY9Rc#!7bp;JY zT2xYCX(rsenx>m>z2ERe=OvxYQT5PdWS;EGQZOR-}?H@lY`B>dW9<^96o?J`=dgIs}?6x>e9 zX&h*Zkt}Fc%pkExk;^?8CDmEDcp8;$PUX7JfP%J^30gOm!DZ`7a!gHwU$q*SRS_i!6^?Dz6*W?Oxo?xXPh zZ4W5z0+Td!LhkyBD}V@4ODSTN#~O%hDkz}Efk!CR@X(xb) zDwHsbTfAT~HbrP4X)NcOL@td|{z|mM{{W^H$Q*xfMK)qcW!!A-Y;|jdp%N;)1+Hg+ zF##V^4-R2cm1bHo!pCCQJiVK_DDn9WsHMm3?A0XI*xYk{#I)3VTkhn^K~XhBEoELl zzGX_GB!}*c7F9MDn7KphqucjMEM;gUk_(9_DOMgJ(m}$dD6gavTTxnZq{GTn#V0gf z$8B?PE$!@C8byriDz@R8P|QxIjo2gWKd5_vI3TA`c4qLTI85CR;oMZUlgCj{N&Gs# zzDe+T7^7_~hOR8oQpU~a{08zc*WnV!C#cRdyO# z=3z5PQ-JYgq?J$sBoHZ1s8@H<))`r*g>}gi%?;&Qhugi(I@q_O%582eO^3Xt*`yACt9c^d)tCMtPel+jAUfA5&&6&D)Cv4O0Y!_he z8UvEUb?tU{AGdI0ePr>?QBE>68zz>$vXVkxHIUNjcL}J2&P%q2eX1)m?;JB`?_f%57Tac{byxneg`2}H`_7px`S0EoCYmwnya8#!1bnmRg{rWq4*krvt@wpd`>VgXVVQ5;bqSrt+=h$M0MQQnBEo7AqjMacQT9nkb^KblTwC z_W8}6XqM9G{W<`lmRP;=)w?~P`QN2x7Y;-`yPE~)&>7bUbs%Y9vDzK%2%9C%Wny=>$=Tf!Qi+6 z3g`a-WBWY+0D-ahp-puM$o~L`r(xj#0B=U)nzFto7D-+4)pilQmiW`ado7*8BUo5k%8 z)FI>HBG(mj3`GC^}!}H6AB>cf}U}0P6n$lh9G^ zJQjcCk5ytDvwFX}cGfzLw&ez6wRV<9y9=0?vGLJT<7jC!7|fJV*1@hixL!r35ilf8 zU_}}{U>3)11uKjZP9*-`tuVHkL6;LP0L4KZIFnF7pr@V(MSBbJi*NNMN@R8x;LdOT z^py2!2Ii9zaB*$=8mJ`4*3@CPtr^T@DYAYU=1R_v_K{pn8N+S%Mr?ZMIK_AXkZ54bk% zQ)G75gB?TXT`7;S@%0%sA37d^ z4aZB;`OGaYa+-eV+q;poJ1JK%O)Q;)flR}{H9WZ zo}4Pt<+l}k&T1o>5n3_8<~W|(4+sF-Ra64XRh76@lnAP|J)sow1eX#*9T_fPT7m^h ztq!VzoN6pfde(=e*3js`hB!P9I~z^c{pQIPO;imwKfd=~+Nnxflo7*{r;8a|HU@^O zS1PihrDz-dQN5Mtdv`tib+MF>iM9S!@ALUn?59iwG03#OkV9XDQ`3(M;Qabm*Yvl; zoc%q1**k0GHXjL`+jZEf^P}X}_1qiB2a{mb)ex@T$y39!D{y&KSEZUd)RmeyeKEDx z-qmL4PwuNVb*FF=3V>>BSsH}=y(`s#DnUDp%~OzR$A(A)?X4@HPA0o$?@hPXTkjE` z>n`Z|X|QRr+asyAjcs%HF5u1fD(z00OhmnR*YoZ?p7MNab*9V9(m`8*+p*)nhT;+9 zU$!zRk(+%InWd7}AtTAJw3XD$PYv9H3rK({S0P`&Y7eMmm=hCt~(idmFts%sYP-UTc#PklY!q z&nu@ky}q6RUIBH1G?%mnOx2$iV11yuoUyj zTRbt;K&eqnxZ0*_x#J=H7uOa`{7~}5@YZcC{$nGF%Td(FtIG_~7^FZ)uI=x^ zq+blHDuL%(cODrW4Ltbu;v+1@<`o0}FUyDceL6s3ai0*VYcN?=_?=6N+^d|<=WrX> zYhbh6BYSMTl~n`d+N-U1cE{`;xw-oGnMw$g8MSLMn7CpEnvjN-Bz3MXh}YH9U6ZwV4`4T5(QQK^Y@L@~=)KTcZYRsLN^c z)k;v%4%*ktAPV{7y$oAZxPCf(qU)Z^_+#=nu6tK^{CfEhgrM0wvPHqw(PMBGbon|A zw%*?qo0^`sQM79|Hgc8>wKh(oHbj=5KO#t|sMHcm6Znm63?P;yvi9i)tZHgB@a?H2 z&`LC=3^sVtNdpX3~@jWRI{Wi2IQsX zeYz)}FR2H0Fb<{WPIbWl!H4-|!UH#lY zA!++2n+uQXI+|LnP8)A-Zo0(wW+N-O9+P%%tl&&GQ?Yhd(X4}TPVjxbPDg($v5<*Y_BdofMrMFLaZ=C1IKCXWG-}{ex9Q$G_Bo2`TL_F6NP)#^ zsOSaFNvl!lT!3nII~ul5I%bP-BzL@O1j$ja2|^WU02Ijrs*Avo4SEsi`oH6oY!0#8 zxn7maZ5rO#-@S)PimcjQ&z{L_ABJ6lu+giron!I_SKfO^wWxBvlRn+5!0r6**u!Kh zYirPwxcYjflA}iQ>8@cOG;G*sW0upX9Vr=K)mGI)PMm!^lXvmaU*G>o^ zn%1;w55WpxuL{wEzR6L`_vmZFI`Sm*s8rMk#uK-Iu zKq80$9WW9osF2J^284|?7^z@O2Fb4#T30R6g~fG$R`wMh)x+$WbK4ts;m+ZU8AlfD>go($FK^V(MMs;as>g0>HOmT@ zd73?O=^;VXx`RJ?V$8?5u_V+raoR9Cc*7D~xD!=?pjJ^uPzhi_B7& z`N8jx^f&y!KbfZP=$y&g+tRPDBFuLFC$H-2Xz*Kiyl8t9t2XstcII$jHpF2fQT{=mSj#{dMi^kUy#6YXh5GJ$-Oruo+%Lc-*#XusYbgIfD;%ktS z$!{wtBE6;;U@`EO0J4)&!?(+=0ruzfVg6`+-Mr{JtFS(D_a^Jvzae*zP3#TPxA*pA z6}&cv0vu0dZ5*!6+}ke&xTq>|yJ`?YN2b%i~=@}7C^Kgr5Iz!CBlbe+)Y`Ibe<}tUteH< z!i#qPLu_})MQ%;c^ESV2S8hzk*sHFCcJ2JG<;q93cQr&AS$5w3rOe{DR?Nq48p=sb ziACauIwFunkfHIS9XC^@w8q+z(OFlV}`7ot8@jYxW{F%G*ACO-genj{EC4TDP6usx!TRy9+sCU*s1+jOkY`v?rHr~;t z*-}NZj5r#3HkDo;szCfCJ zQ=nHe%VgJ=QAKPenAu06d(_FISv58?r2d`(tCbkiIzi<3F4K0L?0Fd!+dMV{FWw0AC2u z)!kRIgW0c>j2+L3p*1d3YwbIq?!+q7y~rxB4I4iA#OD4i+`Jb z^so5o@^|@UckfZ{DtJ4evp!4B@o#@_tYpniQ@{Q^Zry>sH&$<{H|`FaDq4N}fP;17 zX|mWEGF4Cg*UF^w&_uFis^wR%VEV*JnlQ|Yc|j2%-3>K?gV7{Rb{y zZb(<^pprif8g~|IG++`n7fnDd4nS&xp!8$5wO60#6-1CUGDalL!ii5Bgk-1dXsG`H zaH6ucQh0rG3u-@~udw$o$j-Ar5=?~ryT8@;{(UFeq(iv3h42R>9)c3)quNQ zfGWg>9-=ghf%Lfglm6IyKjB*Ep@;Z7>Du>I1OnE&{WTv|xcx*A>F;BQTLZ3YTR|)7 z7aEH&EJ(G;;9vc>z1Oc(u4J=4fh1dt0KAW=z3y%P^Y7lhYQ2B|(A%xmsmb zbW!x;`o5@1Dj0okzk~H7+a%{tp#K0+>9Pe_e6iMe!jt+KY1BoSDHj};AA+QPKO^4Q z@dx6sT4FsZ*Ur27_tKh==D+d__O$BQ-4+18lXdGXTCpeeo9Vc>7WW-)lZfP)*SJk5 z^J@P9fb?Z&BXB<-H=g|Xx7E3~$JNnox?hVs=d||5dnJ~K5w`1b zy?4KNTzif2_4O2$*!7jO_)3gfp_J20U6+zL5=EA1*yHWo64~?C<9&H7cJN-^+`K+3 z5^e-hEM;R<)XL%2lxqs0E~cb;Fl^R$ueIn&&F$+%Zp^39MjTi>t5&;~K$o3?%+~79l-M~^RY30!>Ucez{ zSt_LFo<#Xmthg?RtKM16Ha%j^)&0@ROOS&NLlpH;Q{zfB<`Yoy!6fE60aOOyeMPzU zX>ZLY5p|+8qLd4%s2fnh`Ebp6^ex-B9V&%IRFhG_(w|wZ zWoAWHV`~PtBz*_7>pk%U+sM*(F;Wk%f63DOTjES$9^&dT^I^pK5z+C*Z(Xa6!{TVF zYwKZ~8;qr)sZZd!Mo8tPjbV`tkWF3{W2zz95U-!`jyQ}1vY7Fc+#C*ec-*FVh8os+!8<)R~7TeZhy(t_&Wz{RC7vqJzuN~ z(CmHTUYf`rmU>J)zz{#JuYYdC$UNh5R=4Hp-$*|Q2Og(AH7DL9*^5>mQ|<+-*MTAU zW~brdDTX9_4>%xl5R~&GUMF;=)TyV`QOBm<-y* z00OzvO$nt%X;2L?H~YYS&GzTqA8!4%+Bqwk?Kd6j9rkG-!plc))^4PhZ6`xGT|jn% z7gZRbViVgx%ZKIXNm5c*_77a(>1gsTBviFHE&H|i8tadiSyLBTG?3gLH35Hfgw_iW zhQCsctJ1hXKTq~YT(Xa7zL`mh1qT|CIR1J3xOwNI?*9NE`*1HCI%}5FEm=zUH#Qdz zZ}jKeV%dXfGJ<@%^KCnV7#eZ?zb>wNue3I7^%F}KUUA`f zX%<1WbL4u+EF@t>Zqc#QZg?Wz@TxvS=H*3K*(RvR4^Qy={(XHg-TmVImASvUxrd&u z%FMxr8-oDUrf5ZI!_*!lJz*W0v##vb8RgSvxY`?n!ALhI^dQ`ubM(Kve^Gg|hyBw_ z=l-M8Q}>1TYycOXpkR36{d}rCy6yWrXMkENjPU;eH)egGxI|YX;4w5r2VwO7zW4n^ z=H{a|%OyB{r>4i=E7^h=e_kLi2k@}}046;;<~uWIIb;=i_arlryGL*{+CEK!(UQN_ zzo+`%^qh;$%RsvvmHo8p$L|;Hub(_yh5H-w#XS1TdoyMF58Y>#KSH~0O~4he!6_l4 z(s}xul0DS&H#RedZJuCTjenLsI#^&oae%JMoTZf;K* zT~7|s+>+YhS=0&w?-?!iu=j83A2yvuc3Fzk%dHQ*PqRcIes_UECx~ie%AkL-*Cp(| zm83`|+#!EDwvOUdk%y;3I??iZ{=6S{9F5JUh4x8Je>&&=R6mzZzuq(1kV^jmUu}hW z;EH_n*Gt*kJ;M}}as>)y(l(ZP%0^ArO-n{axxM~`1MZUY7dI16+>;d?G5b2QedE2A z5viA-EkuVL8z<%V{@$~%XKcTytIh>P4Dx?;^TiPUZ711iALID{03UV!qVsievCLY6 zxc!tJI6m<{%xYo%dABQ1M&s%B`48t#yn9Dw0M@L}+^8$3Y3BTf_Rvb2QFUYV{{Rnl zJcrHoEW0G6Q$1{bDpP+p@_bwZ?ymg zAD?ypp!0DQ{mmdGdHueJ%d7tY!6odCHGf|%=y*|EjRB|g0G(j`NeH*#3r!^xcH@WpTY zs$*`AsZzb6vMQs1G$xc4$>|vTzPS|FVwUAo$9R^2 z1ZfHi00jW189RexG=<)~I3zlZjN3Ojs?T5m*eL$IzG4th>Z#jVN@hG;ONnAZsDHM%KI<7UE~EJ5E5!IK@Aor(HjC^_)!6 z%bm!i%c@6>@HMeC01L_Fjmr4i+}MF($>PV|(~&vAkpBR=pH6sYzhwtj{{VtN*;P6} zuJGyuBT1;Itw^N@=j+#pb@gL${pOul>RjR^Rt1!>@*g;2E%-lz2p0C)F20f)f;wHd9|%LSg{hhX@cEii^nO{<#{0T zN8{apsXWuG{z;;wd9eQgFQ-&LcyDLoq5id!x~ORrwGApkp*hC^_KbC1-QC_>XDyK4 znqN__NSXUd!D_#Ym1G?YPz>a!ZdnrRz;cyjmbHM)k)$G zP_B9;_}Yw~>(92{#^cQfZB{B;OjLPU-kNNL^Tx5vn&W1gs*WihMiN~ki6mmyUUC^! zDapa}^!5C@M?Mx^wwf4mWW2G_|s)uuDr9OQA>#2rdKy2SnC#n64cGGek+F|=5!t-Vo`%vIsn6G>a9rm8Qqk!mEaYdn)X7FP;SzF~Wn zcpscDCAUbEY??n7*<(W*Iy{oHG;3Oz*+_j%6qyU-8Nz>aW{UTiE^Z;T5n8PbOrVHX z*`$%B&(o3(70suS6j;tKAuLP7?NuvuDILTGS60&-1tn6Wx;e}%~ zsYyvyJCEF0)ByI=9GnJa?-L!i*pyX~ryu~OKmkU3vMM;&B>Htrm$Yk3)~<_DJ17jx zD-x_i_b60${6k36cq0%47&z*xn5rmpiB}d*JXRj2dP*9)Wy>1+s)~e3sHzoAGt*(J zL$sbrbt=f30t*xGdwR!jG`BF>cPsF0pe0BS)f6OTQ2nEaRkXTgcrX6|c>*nMB#{)T zkjUkN_;PS$h3Z(jCrc654LTO1QVc9h60ORKcVx7AvIdsq!!~)d_<%23MO)G+s#2jrq*GmEDEO7W?Fuw(WNWREh~y zs+=<_QL%;lUCXsZC|V z616}aW^uH;a;BE7Q_$xnp|0{KJ>fKX-P4c9kcM0&Zxv-VF66}4JZ)czKDAeAU}>Xw zPi9<=%&_v#_iM}-u*Y?|+ejpi1{xy0jCQQiVb&|SA4|_`L4vbew6U2LX=IjrJ>8Yv z(k0Yz%T-!YWe7!d0vk-Ru^uEQylSk7C|Kfb*3^$_K_=7&P4k7i)y*J)61yG1PxCo~-J*`-`%6rsKd=b|+!& zjj!G~p2FMISdFtwLAdH`I|l(%^EYqq4!6QXg{ay4yZBVHB_=XgtF1JsT1~g+a}Bf+ z?lH{qMgZ}QZevzb8Chl^Dmglpncc=nqMY?T?0o6W(`{45ceAy`ngB`HR8^~Fxe+qD zss>u1EYfK%O6#kBU*Y#u{1W&d-`^iPdWSVjwzj8BcZN@KR_@vqPQl;1<2kXikGQwS z^f;;-N;*8wL+#;6C?beaV`ypNrAx;fNaTFic>9Hw#L`p43lK%AAxDao?(;P|i~0P8 z01jFU`M0g#a@;2pZZj6~Xu1b#6$u&&_;DZ_Q3+-TQ#-q}vuPJsw>HK{t+LCyGr6t1 z3gU4x<0ZrGw%m_jT(Y?PD#~x-*oDW_Y101ya%7M%AR#0IKC>gnyBc*hN0=C?sXu2L zaXksPN#inHc#Ko9P=Q?67$4!UL^FHs+y*X^hNl~ztI9OhRWQhA!cB|uc-365j!N3F z)?>j2#2;q5kTWimr%ywR8I{sySE*HB=jYI8<3SzKi{0h9Dp&o|O|5cm?LyI`rf3Co z`E+R+8eG)Z{w}>{siTry9SbYQBAY2RB1vQsLj-~gm6}(wAS>#*KI)Y$4KbwjrrY5; z&3ZRKChG9rf!9A1^Ekf6>+G#=!T8^`I+rE1FA4GNhX$otJ*T83aToa6UT*WDh_jwmT3JrjX*R$V!shN^yB=xF#iC{%jah9 z__>mNeP-sX+mxaN#$q?M7&R4JYZE1Ds~CKWAr+?&{6bcilD>pVU5ql#84XE1ix5wl zd2z4fd#eTi02w2_0n%gxg%9yiQI`S00<|5(K2_#RTO%IbysdWqM?=$BhQ|k5@iF;= zDr0K32spX!_o(>e^Iu`@x}C?cw$>XvLX;J_-q!1V&0B=5$kmKl2W=m<0$m*>|0@eX*AA z$X3;4C^Z5yxM5E!R8!D#p(J%5?z=wYv)-kx{{V%krlm2yu**_1C<>6uMGk5WF_Mhm z{{R|ymPVRvh8wW=j$V%^PXuygx1Dm=SEW5GMKrQw<)Xw;RhTLzjo(TYjH3iB)?&v7 zD3ujM5Nawo@Zr)5wrT;#mroczw}`=2M>og}Z3a&01unrg`BR;N`f6f6n0)+LCs6O}co?XUUx;ClU?1NVLZ0Ge#|y|1^ed1i;> zivAsE%U6QRvK>5107HKm$45)Af0q9MdwhMt?f&K6{hhcly;wpCRw-)u!SCPyo=FxA*;vEb*im9Im&GI(^VdRS>HAz7nS^tQq|QvNjID z>8y^;#^*LZ=YwctJ9iOXwRWEW0N!-9H8h!A6(%;KTKfH9P&HFRv606t0!EGtmZP-{ znntG7qymPZ8%%hJ3Bg(Q`wad3GC{ORBO6r)AaRCS*oh>PCu%SUn1`Wu^^1 z^BehDe=z(GA7gL6<=NYBr~2lnXYDSC+LXJ$cI5GtJFWU!hcAtt>NYZM^~~XB&A_r` zY5wY-oA|vvFIy0GS7dbB!xhA0Sz}qIEXo1aR8V%YTCON)0XjtmdSA?(<8R7)YTDx^@LmB zeB-guZcVdax2vCgV_&Z_DA_mLd6)Z0S~)7mI*%{D`ma0F`=jIqCUa%&iT6g*sDi)y`GxGtcFEGzA%>=E3V0-0 zYG{>VP4tTMM+|LQt6eG_YC3#6QB)Q+ASfBBG^J{354?PjBsU?A^2-sUqgywL6A3iw zk#%ZUE!(DrtJzImJ?*dMW%FBZZ@#Om@4t`Zt-7y0ldq2p6<1|v`ip^v?`qbZ1`$irGIF_^llN{HrZspOH#ZDX>KL3^MQ3bh8JC~Cmz2Q|*0 zuu`=h8p-Y!$hU$k%RSQAy)?Ymb4MH1K`OG8Dql$@mZRZs;XNDful`;bzwW;2rlRSr zXUK}Zp}977A7OUJ%kDkfu(6o!kGXqGxHe~V?S1{VHorvg>Yba_J;~79BWv%P1jy#2 z&vkcUX7QEyO1zdfuQi3DO#|FrTgcY7!@!M|NYF_P(A0ox1GcRLO4N-+j@*;0E@Ihl zBcATo@u#+gfaWDK1=dE5K{YxW2f-Ss5wz%Za!9uy#m}1AKCZ%2_Fl{Q{j#=>#D{g( zR&6{dboK95R_P-GrF z>@#e6G5H_5QLhJ($YZJmVxY(GM$o{~$rOnjD=7g$r)egHQj|46?Wkx-1S7fk$B=BC zrS--7F;~^D-Nv0YQmk0jNb>{&1#8fa-`^7cTzrDwdH&4njTFd6bs4HLSzR=AQr3OU^l>m* zBvp=`LkY55+&t_o<8p|h*r6d4g5<3hxx$|#Pd=0Fe)jTC=`@!6MEjK2HPp(Mlb5H% zRsy69QEF(^rn^ME0?U`(l-;rM{{ZA}%HPG4px@b*qikaN7I6HOJ*DP$|cXTxrG)x6hSxGuonN10+QL<~rHHW)Afjm-L z#k)%+j9reKXJ^oJ+7)#l43Hg4tqJV}0057i@1FLPDZH?K)$!YO_2$^@Ez1Vr#chq@ z)pRsnxz&3=c=zT%yZZ+Vw>R}ZJFn_D_QRo;14oXYd~4J$95e_dX;ebg7MHth_R~zr z&l@d!gD40Zpm!3avu9Hr3Q!7B`>%3&I@y{T_ZcmvnL7l~NfQv@CyU&m6h*5kS{?@^ zX)3*k@>{?APd(eXd_P5Zm&skBC2r5lW4h<#-(6sK7fSVZD$%2n{w>> z&Fi$}l6tksRn1%d;E9zadU~3e#cgdb#i*T;wd%x@xD`^Oqe<;yipBvXIJ+-&2d!~xEziV~&=fh$*26q{f+%uH)$(P>9yo;LwZb%{~+4Jr?65-7)oFae@~VR6r#v$FUX z`>yZw&|E_*2bCsKGdyJlSgF+DH9+FUK_pb3wfp$B{HMQ|?q{&NKea#E5BW!x>TCyc zb%tYb?(82{)n;L++Zb*4hRJRWrrpQtntjtvkH_Qc721*-s&71P42&EygB07Y%yP(9 z1wf{ur-dG+O*;#QIUwMEM~6yw-QR8AY$M!utFIq#W}>)O0jSzos9+d?z=A;2gPb0O zeDCs=`MtY4H@0##y>*A#TaLH1`znVK*PVmg9e>sRub!jc+s`Rghrq|xTb81abXCur zp~%xXf;dF1B~*?kVyo=BJ6TLtQOg-JluBt3rHT_PF^;KKR>`gfww7CRVppo= zKyVZxWn8gcNXJncO$7}>p*HGmIe|ATZNBnf6%`|M9B-)^9hs7)R*y#-kPyTX_pDDMnG+Tpe}3H@9NqSZxr-z=$Pdp(w0D1Rm9^yLkXr zy?W3?`KnUw$UmHC%xP%%ZB1S_rmJArQ6*LbIf<%S@_k9N+LLQ|Dwdu^r@_!PMJ8z0 zoscX_w^DtCoFIMcP$ET|K~6cT<@U8^PSC}W01MiSG5x3ivUB3S^5%2Nko30sfr^et`BwAU*d)OI~c z!5ya~pv3CN`<0S8bjaJCvZNGUrjx^!(2d|*VXZ95rPT`Yrz%z$;+nrB z*~>{j*U43sNGX2PBHOEO&5p`eNI%U&)1g-)kB8?WxfiCQP{SRE=Aq-LcxI;vHG z$kjkmE2xkvdY=;E?P&-`r4PkZQV0dA4FyTa$f@!tHPf=TZr}Ms-FsiBqMZ2_+-9Zhr8@5I9OC2v9bf`$-CsbleldX=ql!09epac1a=XKmKY^--RmMyLx z@1=y2l1S1Pj%&6WOwABQ5nIVfqLM!vH4;koR_!dLE%S>PPmkN%wt^b`mg9|ED~mYg z$I_0ksjFwmgFLd+1vKO=WO{_LuLZ0V>|u-ClMaaW%xO`9sOba)$0GomA6g!b_C!do zt^6cy24(`FgG~mdfy(F0KeMYK^)h4mFVpC5OAlw@Q=z|E5EH|-^pZt|fIm`r z`blrE`2PTpzYJiWwdFzAg8*7ZX7mrzYzI6Gsrm;00B(Kn=hph>CH}!eq*Ip`(2OwA9Z52?H}xQQfL7K zAL_?hNm2svq^m|*2|Alrudmf#pT`9Ip{9Cl{J3@V$^Ls3&oA>}`4Slrk+S+hK`eB# zr&eJ~xKqL~JQd(^e{p9qFphafuk>d7MO%UY09OuyoZ95>(PJXk5&W3v{a#%PeIbv_ zN%3o~{?2O19#4q-qaO7ePQHoj7YCT%JDUZa$96^^BT*eCRSruZnVy=Ko;32j5>wS_ zc8|!IY0cY=mR$RM_U~?_?)N7M+S$AyM~J{0I4B5jD1b`VfaC1@jnsRuHT^rususQ~ z(bKd%x)@w55DJjx6+k2n5`{F>E8}$Ri0OAFRRnUpa4t?b772`PB@8Pd2}w|aiHcbC z+QhZV{=UaMcIxl9B<`KUDw=R7%#V@i85REkX$Um3oR6Oh{#_kTmFkm~UcPD#yDsj^ zrU!nk7`DyJv@164RQs&Z;%f1^#cCik83i&$B+m6q4GiQus6Z4O{bagL*O*~Tm>`X( zwhCN=B_0a2fK>MBJOb$?sUwYg7;TqNa<)lsRqk12?XI0PeISRxB>9t2p!~Wcsn)f* z*)#Rj(MRBua92~o1Nf-xE2l$ZDQQZ_3kcClzo|yCqzjSmK|9}p1+;A~9bz4%*UG26 z<^1^c^_}aOs;)IJ9Py~)KF&Q9KH$QC3toi{)>6TdHF{#xg zi*|b(adTjJF1F-fjy>s|1_Gl`6QAe)Zmv8cRD=a7UKzpuU0CnLE~A@fQRPhx^^^iu zkIfw<(!w1;TeHZm8C$mjSX=TB*W0nnDkA|a4McgLpO-~fHrBIBlS^$G#X%|w72)NM zkHkB7IU$Zn@_8a7MQD%T)UA;$G;=1H$|$|ZHsjrVdAN&)sQI7uaO$Sc#m=*57O(V+ z<>$kw)tgGYFBp!tuC}pZk=-GwsGg!TE8G@>IbHNj5smHj_vV<$DDoB_RV4oatL4*? zL2Uy&!)}OMj+FwxX#%IE}mK)ekn`n2&6L}HAox{EZTSj>VMYuobhz^FH$2bHa0OET0{#H03DCjNKj6La7VY0khP{k`+9WE zr~|-OnDpz4{9VT}a&f?<|u+Gy8MXFD8P@xoXzGVBJV)%OQrF`35{B{7xnP=0a*PXbqgAfTKTsSG^}YDB6U6ZSy=VwY)#0wM zI`I6yd^*n;#q4|Pd1%0mF0CcKcN~c{fu)}R0FFoJ--ECKvl37Ff5F!23e~(7G$YFc z9$jZY7qQYPD?rjIZX4>285%$%PtyF31;Mqw=}QCg9Dl`*s_7Me1fk$Sr&&+Mta~8~ zjk&mDZw!hE;2ux=AAa#415uzRnc@Ec7uJ;_Vt+|;2srZje}ktK_^FAK zMMI4u%C`NG8J|%xh8le&HNO@&zrC|bLQ5TV{{U4wp^7G5LN%cto?e}1Uy8WcBbnvJ zMX0xs2;l@qE*V6Crj2q~@<94u--9v3e=jdiyvZFw@Q_#JI1iUxW%#d%&~#&I&(W4v ziF8JzltMz2XJSXwi*v`ilJzuv`Tqd1)jTM*>Jf^OoDcPXvCu2re+e+VuLCT9!C`UY zks>}M5;GOlZpx&ESN$JP^}YFkDghrc{;%cM)gT4f#JJDMpR?uF8+TvAT=vPX$WMr+ z^HZ^$Eh{J|)9d}VU_Wh#(2-+naqTm}S5b_Twe|l1CmyKwmQD!}BSva+qPgG>KHiF+ z3wh=`zcMIyrqPFV;NvL_u+>8hdFm=%L0xET>LZq)BLYQmuvGs5f~2vJYHe?>tcu30 zULZyZ;ZvF%`FRjW$aK@#+v!FTs<0TK^7NcZK|E)K~A-B?5*dvs&cec^i}fB zkB>Ig)5jEYOHk5dpWZi@F79?NTjv;M)Vn?WI-ztDBS&*_Zy1?W)TGf$BCCK?!7t*g z1wxp?_lmHv-u5l0nD*(d?zc^f@ip4LNtP>#;DN$`8I{q>HlP9()#B=;dUpHm?9~%@ z6?CYMOd}e)zl(bQm+vU>6(hV zvNVc1nM_kPFqCPUF)fntewebBmUGD~N^Wg~CZ%F%>?p-Y21R34I!HW9klE-BeA=dt z8%2gIWRy3F7%Qq3J<+oYYC1`eSHu;LpVJf$S$g!z&{owxHYyqGGWj}%qJgA&FqE{l z;VJRLx=4~rxfYdt5=}fxvgzO`(#3Y;Bgod*{uo4>X`~T`E`T|xK+W7zEGp`&Q9)zs zuKxNh%G!I0HlYmjO(F1<)WET@R8JCvQxzH>Mnw!wLa5SuV>ubphZ~2c@X%A&60=Vd zGd)ZmX=SH1uG(jsD4tttR#LV;L@WoiaKjoc<;~^fqBT4PKnwt-e3^Xy-jTs_>9I7D! zk5X?b{Unp~J++mq5fy*HZ~3+hs(J5Xfm1bH_T#Cs{3w+dj!Hl-Ch# z>kJFy%R@D#%SNo$()f7#CXlhVl@uZd3r@)gPFsS4mvQ6jG1U}JPrdNN?l%V0p_T}R zbsan&N?qTxs%h859_q%U`BiBH!BYc%*=U)HsoUTB<8O0qHN24ffoUK!TgOEgu&Ate zdwZ=EPYnxxfbgCY9xZUWR6mv&?~$!1w$Z*rLnXK)xfM$Z;WVezC^e#LSrCx5Qfo-x z%mSj7@ar9}${d4%%c zDM<3YtKTEXy9YX*2AHKF1rjt>tP?N{mk^Cncz{VBg^;3yuZ&(avaP@}yDmT~Cket$ z6rxBfJZQ-Z4{}zl&#&h4`k8+7%OeLA*%2cbT6olyq;>ren_j?J5&C%4J>;Iq#-Iqa zpyHVLyw68Fb8Bz}dQfp30VmJ$=rGwqzrXlp)As&4EyXFLAgPY{z#6vK(P>8mgXuha zeUGH>*>?h`RZLm?AL0DE8lcs;UCFOK1$L#Em59yNZKRkUCk&mUb7r&Msd9rz@k8ZNK+V=a?F4ki0jiW0XxTziuNo^`g ztGHT)49log<&<$vqAgG*yfF|LNdzoo6>umPzDk;a)j>*{R{sF{rvn-19P-L;Hdu2VZxk4f?W0K_P9GBzU>1x{-_GUReI zK}Sm@SX^~M1%ti7(Hp*$VSd#tV)Es#7%U5xB+~%Yiu#@d=6Xr6B=>X61-J%Q3IHT} z)Y86#By>zZSasIa*;!eeVbyKy?!e0AcHZyn{lT|)#Cy_=?0(7FlzYbyw{rO(wZ=~_ z^x2cu$%fBD^svcAmd8yC0t&mDs}CAN8ER@k0MHB&Gn@lV65sep~v_-TWUd9 z6!Qo94uO1~DpO_Z!^QT?3&O%FDcX>L@I@p}uuB|FsVF*?w2fef92@(7JSx}X{{UB? zPml}Xud&%8;>8kAF;cbRpM~b z%0L6Kp{S?@NUu*BU!2{i)%6%Q%SrL$y686^4=0qQrP#GOn!V|^s`mC?Tsq@BD=oIh z(}QkR?nq#Is3eAtukI)5#6v&TEw<@iIMQTnWsrH~(4I8&$)^g}te53)c)7Z3 zJ+^J)8#{u?M{H&X8Y-cfMA|`MDp;??a4FDl7h+?(>K);}_r~I?+nt%dcU^9G`<;-^ zRb*$|dq)niV)ka&qp#eG)tTyS2Hv2BBSPyV(sQJK;R6kmYqZ$*`)#t>KTbAhEu;-j z?WxW%YIB;?g=ji1<~{D`n74b4-e|lq%7~~5V5qA=0pe@Ljw-~OXQN%$naa=a6?XHk z-1NJKrnakWJpsw!CYX;`6&1-Z5EeY_QtrzCmQ)RK6Tetdr3t0tXHRdnY7c@OqJeF3=b zvrn`WEtuL>(ru}7bz;7vEEQC^$}FZ%6p##+eGD#?HCZTFi&{-I4Oowss%K z>T0~P#`T8An{RAK+q9dASN{NcF!=7w+n5SY%gA6emARU_%A9phURqzesd-~Xax7hU zwcG9zO4p)UQP8PFB!V_lDMK2tRusmT1xUjw9X(}myIfHw+ieB7jDo%#Xr%~Z)k-Z9 zixS$@2Mv(GfkVadOXa^(^%r^U?)C2ufvfKdJ&m+*nXQe1+1;;~i!HXkP<6ZQXX_5^ z%C73%dqn4OwQ_BilRbv0$W^5*^>S9zP-NAky-95w#^9KWk(3|MheH`3RDU< zQl^9e%m$EBwdk@fqilX)x8H8Wy22H32x3VTc^04nB#1mQTBy`ns%qU2-68zUK3Mlp zRs8$t-{yPrBWUkjA8~aZ2Ko4nxas;*hAH-M$W6CgY4QDSwD8*tuGSrywKqlvDn+Tu zW@=2B<&Enpt4(cIMoCl2WhIT0i0>{gF8o-4W2ajcAT*L`5yu*xAj+|-$3prOS);kk zHe;B!ZS!nvD|n)~vbl^R)GF&o(4ff9@;b=M(KL+A8CIksu8Ronz0Lf?cQ5k0_!ETw zLz|y$WvVck8Vong91lKSCuX#7S9cN zTG#rm%DWYWTS_d896-FWnSZm0iBWYijhb1XRMHe@QyTbh9=R2UU5ktO(NX;DwjBHR ztE~4QZgtO3>^dIs-YZju&g{I;^8l*ZRQrD;*jSo5V#8r@ImJ;!ik1vUKNB4m=Z=w@ zmXjw^?d-b*?`>xIRKxVA8K{Y@dzWgR1s6$s6aX={Mw9s;#@YXNt2gO(ktT7vE$u zR5{6FCi*Ehou6-xd*J)E^~y&Q%Wy6vmgLpskSQtQs;q5rZIT$_ND@;J5X9}&pUll; zdtuC)t&i?Vt)*trhCLSLkA{WRvoyXVMI17-c&#~z9`=bw9n-phnjL?_4~Ufi0Lk}n zb-cL*pL%bPoE@#!tI)X3(Uk416%7qdZ%$G5mws%@waI38l~!Vu(Px%W-@|BWqMD|L zf>$qCm$-Kp4XF;SqqO1}pmoz}J ztF$H5xf&TXrh-fU%lU=#E9GY2{%ZRt`ILM_-5(ZyFLYl?W?{h8_O{)|<0PW*i2ED0 zDLR1sc;9%sLAQH!Wp)lbYE?~Jjm>T(i+#ron7YA@&ts@yAhnX_-ok&W-27eUkfDuA zvkQrgn5}MLMcBTcj_8cXa;6+MUo|_ z1sR?Hh3}?xj ztaz!}`#*D4$5$>pch%st&6^OYGQL?bxQS}S^wLwTiY>2YvfVc^4C^P;6o^WM=v#sb z{WDy*f>qZQh)E29tFjOs=3R@Hw{LX08f)-}c3r;eWrctqD#Fo=c_gSBj7RD`D%F_A zM+-ll0EnG|y>ea0*n4XSn%ETGwb#3rzAd-e z-x~Y#Z%;#q-5YOs^?htRnx6@j#*Nvuvlyuos;-%wW65-le_>&`ZrArwENi7>Rgnub zwRGu@izqJij4AOIo5EFc?!&2ncd^*_YZK`9k&2$iIV~RkglB{DJHZ_qVfOA~VtTS7>(LPL~OhgLCEb27QCm zlb+1U(CqpsaJzpU6)`k8ntYq)YGLuUT#_!{A9lWLUB70PkVi2NfQeJn^+)~Vt= zz8bWQT9)HN3ixh-4`nv3k80#SuHtA`d9Lim!E}?s6HL-jyo^#uA~?*898^XOsJ*MG zH15O1b?HbsW6oE2Id*GZl>0oN4ikexfX8yW<~WW_~b#DJqYfpAxoC z)cFDO6MDzGcL#HJ4)ED~({V@D8111J=&i`@P0QB3YV&tCQ)z6f&9y^%N33?@@a`G^kP^vU+mu3%a)v{ zZMa*_&6MW2(Iy|MDset#!g{{WC%8#~au zkL9+}IlkxUjn9&*r`>xhmaAgyzQ~WL_bq&M`*U++W~%HAo9!7Sl9v@n2O^#&LQT|omWs+I9I41$lPmaM%Z=lzFh-}lZ#u-#P+oYz-NM#qei zz$R$*14dHu!mfg$l0v5rDsMVB<$raz&fU@Q`h()VM$GuxwKn% zb$r_!4YOsNFPNsN>mJ?Nz2*Jjt*P6!`&sd@W1+@NLnJjdR5>Q5X;*fcu5YiV4{R$| zIH4`rx|&93Z2*=!RAT``_sdejx5H~`Yhw$ph~reFDMB>&Dk7?gl^BIY?k6PDpec9i zp4sVti=P;KgZYDH@RRnAYbDLBxF^KXykd_`G^tQ>^xj5=CDu1@CB!ecJ^W@1 z_k?Rz?+9E*?Mj6PgauY$ymBgO)7raOF_8kl5qp zg30hl`Ivl@$bU4h`2JM8v)}~1SJ6Eo7VML)`-@^`I|Dt9+FM6$P)C%-Z+_0)8`o)V z+z##A{{SE}IVYb7S&2+-Mmr%<_A*ms)n>{@^igjTneOkTfuJOj;l%MOg2W_Ynnv+m zR8iO}Yayfxpb$h~L$uggTUu?F(nl0%043Ftj~Xf}j}Cx}sggn&TDfW{%kvNCKgC~% zUmgBNe=_ay*H}LJ?GB^tEH7GY9k#W&Dh!I8DwffT=wD-M!3oVb?J99CN$;p$c z-3>z1raGRk6ojVQ=@tDFXlx506RVubO*|fzq5C@ zM#b`ft9J!N9e100e3s_e`gA9rJ^F|p=0@XTUfd>&Rk_imBnps%~?O2+WbbSm_wfr(V{kYo?y05lryt zcG?;2+x%v(gLqTc%bwfaWtXAJNtlAVjO3FWkICccYHRD~uFKWc)EYV{zll~BCRvP= zh}9%m!fmGNDHK6(+OX+SKqvF#H?77G_A^=KzsJrPpY>*p}xV| z-|8PcbRBl4=gG!}iQTQ~PcjKUc;Q;tucTcT+Q8>4@7 z6TC3C7AmS@*gZ0)jq|_bt}2JD`-`={Oza}U{uo4b`~0z2=Q5-#OrFT6J)SC>0$mPkjC`0Pc1xjvB3V|W!$X3d#EpD09`77a@SU*@cDga#s8kem_1JKDBsU;{6zL>_ZO7OBZ+`1|2DIzU$4;de z8mtYkscsE{KcfEt?Y;PVf!6*41H!(YWm6|D$YuvnDme@+E`q=~`{+Z|1r3G22vw z`>oQ+t(2{nKBwF41-ZD4lE2ga=iEKbGO}IDigV(h`1X1L^K^xGlT(kTfPA<$NBR0P ze;e_*TEC7P4;hog$DGS%{wbz6Wl4vpj~AK1@42h8&9y$}rm9gvxv-U5WQ!)ce7|c@ z;sX@XD|^CDaNO*yxyP8UH+ze}p!)mess%)jQlVpZVysMRYDip`(^G;v#+&mCZyfh* z*5+%OCb|&m?R1#A3B>7;HbjAiLLR~x0!jYk+F07G@rEp9!!J>or)FZyP4+d=%Fxuu z;IyecW?mau*JZHao0)Cfo!lF763n6%gz(O#BB0mo;pNnDx8Wm|N|tXk=f@(SZ%4zb zHmlFG`l^o`Pq24hOMGpf>Drl$HsYesVyP%#r_W_1L7L6SN{~TV@Z;j}RO6k%qGpNN zXDw*j`*d49&ztUUM9Cec?Szq?Dg z6D*4$(@9vL5$U8o6lrMd`hBL1dLeY3f0E5(@)E2PnI+8DRi8XiM6k;;L}f8k)JX}a zne+f!*IN#MKIEOpdy3NH)-x#ZRyA5wkZ5Vg<eZNp7aWmz#*lg9-0WlD8`*gFkD7PnxD_B=>9~TA@g|;lGT&INu{pp z%4K~j+EPj#|U?|Ycs!b?A!hhBKdLHttD~r;t{1vaSck=6Hd>>Ze z+cSp8=jmn`YU%tn)d+xi>82n_DVzpq-D4!H>1{1;KOWA`pjM)zKbPgu)xHywMSQsa zT~tTJdA?=#2Y&Ys()m-=Refi$wwC9mPKwLR*LgjcP1raYcP4&~@-&&Mx#}plj1<@k zIvJ*Th-f6J8o(@3Z6%w)AbFQK zasL3^)T^b*WEj@h$1M~w(KN2nggTvDJBz>UpGqQiSxEBZ31P)fs|DRhdXj7$za5YRobAoDb)p@b$3qo6xc~BGdyO6!q%6{{WST zYJ9T!C9(1w*XB=0)qHyGIt}-^_T?v5*7g4YV0DE=yE2OjwyUrkvQ44cmH7?R1i2iZ zO1hZTG{0?9w0fdd^$%_}q_%8{Jf+;JB#@(lr3Rc*ppoZ8#EKHpy7ASXID)FMz$D_8 z;(Yj5=fD7H08gGhzw%#Y{{S(LpZLYII#Q=K@ppgiZKay*4*aO=uFbBe*jtA=kKA+R zuv8tDjLb#W)H2dkVyN{)T}dpkwQz-*S(U?YZE(g*kjLp%U;r{e$tQ>vH1e%6UX{ai zk-=>mC^JY-qHEeUQE(_LO#JFPR(!^jdGt5Kt>@g`SJzM3y_2%w+OM|u8sYagb@x>H z-Oq}`o zsA_3TJ4fnIHLcuH{an$v(Ma?|pr{`$WRS#+juae6s*e^lo#9-vpv^(4AQC=Qtvt;~ z>=QqlcXw{zf?Z3~osrhPL5=OI&cWZ=-G`gNODGSfuoKn?qaMVM;1_QDaR zmYL7(9$&Ys>#f8Q>g;kjc?LNn*9RR|fAZYHhD-Z5nU$FZ#*)jcPK&A=B0k#B-X#`uO6sp z5(&ggXr_ZT!6!TirFeP#x>@}A`Bj+so${ySFUHNe*7)7neoJ96IXB%|Jj+L9@nl0v_xtK4*x`GZkFFb)n#$Q^84 zBym90tfaS?9)NjN8k3$B#WRDa-HhEK@dLU(Le%2lbl3F9R_FUA@Kre}F#iDFLx7%= z6vDnrDol%GBd#@o8Bz)SKwKjM?#islMMkU<$Jg@UDsX(iKDVq1SUCMGwFL*lq|?rX z(v_j(!1P~#mhX2~eCO(%4|!JYShiL#JCfa)VX~;RwR?sfO-|Rz9BC8g>Tx(JE99y| zlajRS8Z3b>#arD1xP3Bl8TlHTU{s&yj+%Rwk|6P+Ug~7j@bfhP03hfb+89FMRrP!NEZI!7TZXp>xG8DQ791qAJTg;-nJ&Iah1_~!DTKAU zshkS;R+Oe|r#xr{JkQt*ak`T{k{;Cn{iKjQ@#kO5p-hbYiZ;PV+Iwqk z?hHmD@^tycz|(Gl8`0BCmZGMorp%gn033ObKA(1sG|_^5 zMGeQ)W6Oc9O+7w+2_MX3=048;UwIyg#_r97x_9KiAu4ySGi}9z-CI*@Lx8NL+p3oK$U5?uG`pruFx zr12i0f5miisc==eUYg&1pO=QRvGyj!-ra>;LqP>P)y>QAr~sBDDKQnDRXo51Kuv*WF+8M{j&*%kBKGQ?WO+`yAj}iMH5= ziVnb|$W>u;75Mtv+FZojewr!?V4kL$DbL&iACL3x$tEc@Q7Y8EGn!}92COSxB#dUf z0oZ8Fej|Cfr3cytbHbqKIp~i3yZFhqc2`wZc6RHcNbxi?;{O1PR~Tt&Dd-z;W@xY! z^_4YJ2;!l|(^cdnXXGlWNk^R2+8d zqNJ|H)(Q%xs6I;iM>TN)tHm+n*bm$fb?$wt<<{nly|uR+D6XN6;qgQ=5h-D*C1rKg zwCz^_F*GhXi1VKL(YYIJhj{(iF5(vv#?g495=5G+%OP16O6jc%ka$!cgfEjn%BQ?= z{{VfscZbKA`!58vRoPmu!T9l7`@*7vl97a!vgbD46(%Ep<0~n=%I_SQs>sA{vI!bH zuxFFL^PbFe)DVgJfNa~5I!qg~i$Y$as};y+wU>w>iIA{0)8t9^Pk1>4dJv_?^Cs1N z(dzK;R78f2M+rJKmhGaUiFb*#kV5G->V#WnRb%%Se;WiFf(l)?mso45_XRk^=I~g# zvT@@nhE^(}OK1ByyvD8Beh9F>YIi*A=zJp4sBt6W;Y;2lPPz=9xTcQBj_ye`&b~ zmO1|CceUSnsrLJ|0bo=_W@jTZI=d)j$W=vUEJM)to|CjYr?L8qwgFXLor@T=#?(8X zX=UY1sRGVMkw%zk=-r^|8j!F>lOsc@E4J@Tt zGCB}QI3k=!mr?%!x*vCK=alZA=JvrPvSvCi;7<|<;sBKyYa0>8Bws$=V?AD9#$V@e z^DAjl;&J)y^R>QLZR|xJE}Dx4+to7SyL$&ohHz+3Kd~^;N4TpNgda=gDKnmDCsdbm z-tq6;FS-8!vfTdwI__I)Uvl3ul<>s1FXCGj0EI@exML7SsnRXvw+UK>JPsW5hqBh! z(;Jp+i(AAf5_lWL(jr2X{wzX8g7IquTV?{C`+{p6K1(RSU~kPemVO;jnr7jc*)u(LN)1 zNrlZ+WGb`+_H#sZO4?->wV)nt_Ltr6SFp0T=09w=+e=7Hg_u~pk)=*QS^+F{(koqB zMomZqsK0sSj&;~A*3$Qt?-mHdKD`X#(;7~t*2UZkg@43*x*4%JyyLpm;-Y-b84HnE zXp)wqcLt#ZvC=g{)X`VeQIq60lftQWkg-*~a;Q@4UkKz@m z=ml*Y$t0#pv@V@`7zpMyVc4l4?qwBh(R2b0Xez-$x+ATw?0THVeA(K?#%>g+pw9V3 z`8ukNsA!h8a&$4o)Y+OS0Ez-z#HzYDC0S%^M;AMN<>Rl5c2(7N67^CkR%+CojKL`U)Y0|*cOSmg4c6P?i<9^nB z`t|PD+qqn3VJQ{j+4Fx-G?ZHD!PK}b@TVd(+(AT_C4PaJerh&F!kmS8fQXDrvP z7%jlw7G}iKM2^T23_*W!0i`oSBaO0Fd2A$0*MjQZ*Xb?|M7wLQruuu56tgKhgj^H` zX;2u9(1Onz7PhjUEAnHF!Gd-*k{MgO!I+Vl)B->Ns2KpnSvsnZ<}+DCo9p;;Z3Gy- z@rvBEYrHngBvH_A+M1P_SAF2#Inn9qgE#p?)2Vd(m1Xi#A1qlX%eV1vaqRaOmIl+9 zR6KW-ppJF{SuUedRZ}U~;w3`rAjDcdAyZ#8S1?}QPe`{^k$$CdrdM{SjR51GE&!zs zMN_-2cK1$0$t`l#KpmVsOH2wy5U7oX>X1dLWK;|5QDS&texaxRsv@Zfj!FvDo+N|i z^66EY5K}?G&)HrT=pevWLq)vkt14x76!@*g=<$thC~6f?4xr!_3dMq(-rQJm?n#E- zt~Se?tD`ZAtt>S(vM9JVbz%tymKNWt|Bse2QY6GDSi3`SoCbB>q76Z(!44I!X_fe+&APcH}AXn9Y-% z`3@Z5_eEV!DoXf#JEsL(BGpw%t0PrZi6Y6C{O^5f z2Ala^VVP>Ik%BbUl#wG**u9gv_FY{re}C`l z*bZhQhi6c`h`Dd6h%sbSZtSH}37T-z;(G68br6ILqx~K_o1!$lE zp+Epy?i;@4xn19G8;U;Tah6~-qNoHcP@p776hO9=sXCe6+2nV2)a!L&b|jryxZv!( zhW5q5K09rVy!$h5ZLQr+K4Ki4wKY`R%7bxcw*1lJCZvkg)ig56JXM8SNZLDtAngDG zK>fdxL?pRgEg?Ecp#qsYi&u?tKtDfFHrZAblJi{brB!s5749b?vIrFOA3S+=S$&xv z%tWM%Z00u}PMhxQCV6waeuoWEuO^LJVWZ1r<9n4CI)<;W^!9cb2@44GN`1W#_QZ)q z&lxo;qd(7}lT3aFD9qO~T)Kq+0CgK$#NXSaiCSP+{D-53Vyv`2pXKWXe3Kjv4Kq6$ zf8x{1kzDCVcoAO8cm;q2`?>`)0tR&Sy4-?{N3TXlc<=1K)Y~0ngNqBcvI$YwxLwO8 zLbD%7Uz~Qz)Z{6D%j;`tYG$4ELHhxoMuIj9ffOo--HxSQbWBswVyFBaKL7;^kxZZP z^bgkMX6$UX-^DcsA8*4gW5ZWhLktwr!9k=+U6HS2_H^Yjv@pD!lut?IU)|9a=1&>B zIFrL3e0=G{=hdWbD8wa5{io&m^=x~eF^1cnX|`y#-r>RIaWuOFZR6#t-2yCBwKy}k zG4XBOnpeRrt3FdZMNTC&l=CztuBvPU5^I?$H0qTRiE;R=L!V9@E9b_8tbV_QN6ed- zf<(73JDC!Mcx*{D2h3EF@}_gsU&KF)J;UlN<9n-4G5 zyT-Q{nUHM^*4MyORc(0k8`_>^OipG$IEpzVLX^dy*&W=5+Fj1p*f@y*8REc?BjrFz zdU5@up*#RLgCn4)5G&+ApZbqaU5W8m;}62FnA`30C;gnPm&>l*>&~6|37Vzo3caV+ zeFyP7r#nYCl&HooS+Y@PYx{?E*X$n^LPd?DT1rfu6-dEp=|f~UGRU$EYdyR*ybJ}! z%ehir;|?RXj-BePbjZv_Fh*O$M0OCW$K%{i$kOU4f{aF!@kndisAN*6f|^Y=vS)XE zbNOGiK2PtihNJJ^fZu(2vHDkI{ENf)pKnCnWw5tjL~raS-rO5wCsmWc;VN@jz1gd9 z9A$Mmj-oj0XewG6=7>cki!E&CYrC6CJXN@kREWkD$n7JlylSc|#Ti?O(x^)kc(36^SH)Ku80LENPxSLz`^jt1=sh1(EGPjkWM?tZq)Zx4z8pTvVG+ zeaRFU^GQL~RC}u%xAz|8e1WW;DgN%4A5h=Jt30uxjxjO3ys^zOP|eF%xqToAWMXnM z`auz{MH$G!AH*wI_kFHL@T0w5Kn+2eS3xzXYOu&S#cD_cHKckDf}Wpi*7lq|iPX6c zwZ>)fdwy-v2Jy-+Dvxt!vP(&X+jHln+XH7NcP&8UCrL{AB&n;#{_;l6XpP&KH>hQb z8Md3K?wpW_@v@iBbOYSQF{*R@ncY57#pXQMN; z`g;LULlf5gmH1n>B{+&qq_~~s@(!N~m&ealJ4Y58zK$KOky;JI0;132W_Y|(DQ8=d zu0JmCO2mHWykS~ZV333BLO=uqitw#ydMf_3Yzrc%?+C#@uNbKQA>YEBD^J;;hT2}Z z*cl;3RaNq%;NOy)7XX?ZSIH_!E7G*y2&m?!$zUL-daXbiWT%m$7rOgTCe6FVS!LPp zg9GPpAReZe$OF%(fl=%zr-x5z8=kT{M#BXfTp`tqMK4KG^!pZG^d zgr0)7Y-{enlY4vqJ}Ub3Ki%37?%v+dRt&anr)i-wLh2<~^D!dl$7tPI3^MHZp#p)W zEu|nLj?h6+s-OU)$P58ai7yk9cPX0g{yQme3$qCwqSRZ7ZEEF<>Lk?nS0MD=*&Vg= z-)ZiCw%mKGxG4LVJ@NB&ZH~w2Lmzx&`^Rt5ZjGX9DXDf``Ca9bsmI~=mg2=^D=|4n z$J5f*tu13pjMGO7g8L3tSlUP0_DwSoLDLt9K=ckO;Rr_pj1;P{9o;Cr+%_p%-dXo% z7bv4aGPI!zQ^SzP9!T0nAQW~C>S%Cl(Yn}wGIq}2-xKGymvDA}$6PMssS?MC+8g&j zu|+zZb5BjzSq#rwZ+HgbsoM3DHa{Oda>~t39Aub;jEhM*XL&jtY_m%&VTka90vCW` zm7*UpQa;{22lm+Zy9T&jo0?&Q&Sn)uE*z~WSzHtiKnWmf08@Y+Pw(HC9ap`-(Z(xc zZp=>D?D}4XsoLGkzh$Jx;$q$1kGl6hN~?QhDk~)3WoFIpJ-0=R87zdb#WdT7ntG@R zskF@ca`!M#5C>qm{oIj78i5cRiqy81MI%EubqEZ~S)33_Dff-1X1cju$NI+%d#fy> zS;XwFd_n^kkdfX%S{n8+QiKo(NX_TpJ+ZrXzB6rhugN_2;M<#O2F-1qzuMh}yYt&e z7EL^8_34PrZrsfi zo~`+R7gc04wMLt8Ct7YQ`aQ9^{=#`6#AntSb1%2|By!OfT1wgR-*}KXRb>X=?RT@@ z-L196yt{f{nIR;N!kQf}Vr6W931Sr1lqA(RF6=4F-&1Y2bF>Ju5vnz~iKFo;O==}p zj57`{BUWlCV?Y3D+#SBV)3o-c>BIK6-mTuB#ut9%du2CXdokIc#)Rt{Zj8=$uPyg-qqFC=jv7EMu-K9l70n=R3vfL5;)XGh_QgZ9bVx1%NKS0UYn)+ zTjYLEw6nO4$4i>4!tYJTy%!Iamm6Bs$d0Dph0|Kv*eSknq7g+MT&ugtY;C3Scb%&Ft}v=0Hwc-o zWH42ZkSH|(GD&ewB)^h5H-FfcYdyQ2VS{DVSi`2(+r*^_R=HPHRvK`FQDq)O14FJL@^TvwJ&v?eCVjPTgPbW71b;rN-@j$G$sRbGhd0Ezj4>w?6Wt z83szWTrM&yS@F#zQqw29?b~g-**S*MlW2B*M?*MraVaOc<&X*oW+p;F1dLKT=T1rI zE3S9j3vO~;Ze^pEE5gPD3Zqs!l+w21Hmjn-79tqQ8isilZCkQ-*J|#rgvo7Ohx3l< zFPiU#!qfi%5$HOc-%Rz*7V|VP3c0ZuZo%8T!l!U|4oZ@EM0Aw9np&znr0X1&FHcdW zf)`zlZbDl_cnop^hT)`TBojweWdZ0wb*oNMfN0-RhBEf=%Ut!ia{bkc^Q?C>Gy!Bq zg4zKxkw-};gY_U11EG|Kj#Vub>QUH$r}=qx_kDHN;_R&6H|6hF{1e$(%IaydxDD~U zI-h^#yC*dTB^a#Tdw;6;2Ir~T_^KRL1o6@~;CZ91s-6X;@X1e37%RG$WsI%W)y#(A zPz8#hvX9~=TDc?uvAcm%N(yQV`*X@1_p`^mK_%zz?Y-sI;j%??8d?C(w3AE%ilLbv zvS|U9hz~)p&;GUCyQjWq$n@U&tod3pR9jPU(D&?Jxv*NIk8vhWy~fz1-LyNW6N%bU z_5Mx|;xI>qii(pBPg0UViBOWCX{}(}}xN`>Ed$x<6!saNVXy-CT57RoxNJ!BPX#(p4;*drfu4G{H9dBZNr-S)5 zxc)5GV6y)J%^Rur_GfEsQacx}`rkd*R8>329ZM5TakPEQM;OcZm;)X+#j~HXoasFAmhvnyA&DeOUJGZ0yXXA}Fe=h}2_W1#s z#>csFo5sEr&gXIcQMIab7@94`i=s)FBa&>rO${9#O;(yIrq^E#Hn{!K;;f&(mK*kq zLPVuYN~px^A@BlfDoTbYP^y8F751ZL_X@yn+hz5cJhYQ*jJ!am-18Qy(uyKuEr(d+q)76V1f(I@=|&ap zRZtgGFimniy$<)Cj{bSAP0ifDP_b4qAZX)(JV4JhD;lk4E{F_{<(*McpTdb_2N$oq z)4ef26!UnmlslVhcjn}mdTrgSir;@8dv9dy4gUbT`d@bT4nJw_j`8n3xeha~XudpC z?g_GxL!QKKT8-BD3P}q6{IV@v)XZ9)y&_u~cW5RG7sc_Up^sXEBbkx9%5jDI-I~wWN7l_3b)ku`Fap9e6QF&rMi1QEKbMy8P(aLyLX-w9fs|$yw1hj8+wN`n}-pS#pbbi z>b!L|Z}H8$oQk4(60v=xs-RujMs26ix=7Z9jXA1@sx=&`QKf1rK~qw#w{M$nxOpw_ zovddp?uBLk6aN4=-fC>^E6Ps?X!#VB7G!5TR~930;&R>fI!85e!VWgl!R!X%>Mx4t)E`L-=z+v0F89u zvyve$TH%DKx*%A|*=^0$@Kp8& z7k733+}k?qD>sf0wleg)Yibt|84i0JzFw{t+Zi{CjYQB*61B3 zFZP9-!!*=r3o%3SGaM42Fcf2gKd|QW#THRZklD zpKVlpuI^sE`3JgtV`q03#Og}s9VxK-qa}dK^nY1)y>=fVh}}E)b7pZF?aN!*U7#=- zgG-92%1Mo*z)(ufMT?52s;080i@m+l&uwl@axv26)nr5}8$phNlU)O9dX`h!rAt`1B7V||mnG~5CbrJ-3X6*_VM+%6mS_01Eqp90R8%IO)s+y{2mo=E9 zugznsvJ?TLq>3z$S4imfRPq8QN&tLvFtZ2d{_U|76gLpXQjILxAPx*oc;h4U{Q4Gb zQcV;V_KhZ}nszw#0Q%$#@%u5=kG0DJ;PMIOZS^FLEJ-bUe?k5p&H$ku#GZwNg+a$$ z+Tz0O%>MwVP4yKvHn1EO9CPl+IP2YWCd>d9Q*uxCtzb)YYmh%bkAC@{9eeZ7Tr8lN z*HE>K5^QaIkO>@v{XqBcPPf9olQV_d;DV%IlWuM8APNI2kMs1T z{{TL-Mm5IdD}I}(2Fx$ZS$>29KA!86YRCRBtsWWbN*xOtg2qNus5jEY+yKJ*fd`v= zZMva6DU5ZQLn}wgVoj~atMCfy{?I><>F$hcN^t75&U*R(0RI3xR960KA0}C@pkex@ zEghLqw^VJ0C@wAuXEz_z@$L@i88q(KAxN&V$L;g#G3PnL@9v|4wu2s3(nWeU{{S7= z8@IkabwruDHw_{Vh1%$}^fOSU4Q|fPn)z~{!)sBbtD3H-AtFE9YeWgbE0Qg*1^)Ac3p5(!4!7i)6l6Y5X#LB2Fn@+Td5#o_!u}nmCQmvijDeb!W3U zoq@7u-`iG9t~wlkH$Q>RX6dT;wRRet_+Uh@sh(=cXQZzuOH$9`)|Ca6N8G^`*57~3 zmpg5wQf_zG7ShWZCAF#qfo9U@wlIiQlu&q!PzdT$*e{^nHl31N>**obY?|iZ#!U+G zNg|u05Ch|JsY*HH8)?)Yy$b&T3I08GS77w(ZcXjiSnTFvyEmGnsgpHVkgJ}I;&O7+ zMNds6HBeKmW}4U1puVe{*jq6DiQD#F?&F_7dTjQWvB7g}kvy?0g;$5fV1cVmMXFC9 zL)5wLF3Ym+T)c004XP=xC3jXYRtgeLASfgOQO21)Ykl*NX=1S7Ci~NG;ppPV?d`e0 z^7y_yIXctB7!c=P)&PS4_CPZmq_|~i8!dI z=32Grd&=vk8_IC1e}TH$k{yYV%H=S4tW`7B*Vk0f6&(-h`?`Y-;iUxd8d*rt3k4?E zKF>%5qLKpo`F?#2<9bI@F;EBQdM14n@|WXZ%DwfR+T8)!8-KL2om-#B(e@kRaGTc> z`zs?~QI?{ipsQ`=wYKDS&629Y*2f(9_N%3HO5{mxC6n9Syyfd{A}Y5RT{WkgA1OK$;(p}V`$N6EM{0G(ce!PH4yVHIIQJ{m_C7#l zDDbmkux*6E<|q=XES^f5o<^;fl9?K&JyHPo_iKraEfNS_%baOa)cLU(QS&tEl#Dtw z<&+|jwImGS(0*CRMy{75MYB3{J-u@A)9t;zv$5H&(YqwA@>5gojk$%Vp1U<)SRjg7 zBBsF6(@8YmHDZy()&|!1W+h^gi{VD1N9{a6)Oyk;tAQHkMqmf${;%`&6Z~uW6VhKS zXM?diAF%evaBNx{+|Jei07!d6Ox(Cxv-o&uC(3Q5mvG`Rd0|_Kiz!Vkh}7aHil#Xt zXO2a7V%~44U1ldyUJivCzv)N^^Xu0L5Rt7&)kCF&589-Tf^U$2CAuqa_Z&YJ_eW@K z%y-B=#Y0b$!}MK7OE5RS>cQkOljrC&Sp0Hg+X+)aCK`%r#Mf4`_^G62L!ggtJgm1q z7lg#0Jts&MsjJgS`w6XRDbuQh!&wWilfV)xXlY$F)x=V?rFeBWv$u}J=sv2)_Md3) zO~2M%cY~7^Lz&;Zt1{RfzqhhExxUX3xg4r1y))!$Pl6+Byo4y^k8emqF19_m91C&b zg#@43)gccfv~eEbrK?aVqlu{?3VPS5ogbOn9mz#k**$TW#%~R=ys?z|J-@uLwU3d+ zZ%Q|5;HJ)EvT`cELXLSLXx3r@EQB6Z+rj)=Qy-BPA7KEGm>?0;GZ3LWs-x0}K6D`G zpy+ppO?D>u$@E?av-V!{?4G^LJe#kpu-n#)IlH>rrh>j4ZB9pWZ73?Gt=j1oWolCy zCWNCu*#%#MXl z=xJa!{cjq zW_L4!qge4TB}Q059*E2|A8ggNb+3M6rZj5PU4oAoEx`8bJ3gl#c|YMl?Dbi3AXhqx z00KW?=r`ECkJLTqx-pp!v+O;E+UEmV{5H38b@uz)J&TRR$YW^^6D672*=)Tf1%8P2 z3Q43{R04DX?U*m(zFknut~5Mziuq&%o;b%&O&pOUD+(G9N`YE`s2-MGpSya;XlDNa zxm)vgY+N3DaZ<-F8)oiJ<+L#yt9E1OndqXIYwbM7Qk!w^DtRjdLJbW(>E{|RtXtcU zcp#8lnFx`_7N;QN?BkBT401ePGOu82RMU?U`#AKiiyMa9J!M6n%1e&IZG3!dQIyN) zvRKS64-JnqqD5Jp%jYMh!{aC-c@bWExnqGCjZ8h+rtqRS1@x+llfy{$`E^7L^RlXH zbHnHBkGG`%09wbe_lEDR&Fp&JxtxsA%THaJ+8I0!Yj5NvjZsii<+jaDUJAaV5TRY6 zmO?G1jm5p`E>`hlnl{xL7;2n~`kuWkZxs;G5=lHUj+wW7-EUW0U$*m7?E|}D%6Nt! z@3w<)+G^OsNgY#Sps0Q4OG)9iQ}@)Z;w}q z5M(^)=Kk((ji#B+&w>fluU?FwEma(8!nx^)VtK}djIkLY3XnZ<<(gNd_gC%hulAdg zyJgW*$A#35OHY7;k}P^kr1@73O^jIa(a|dsVp?FZFZ--o-s~i4o!jCqn(?VVb@Q)Y zm$kx3a0NXn_VkpSY4udwixDmd1F^B&sq!~^&8vXfn7qwwzG&vG8;-YZ(NkoyQoOI^ zkmMdoJj_^~Y{ckp0^of*+=&7ZDXcc0Gz3(Y^8jFCo?SX)mKAp^Ku4u2epUYf51&i! z%j^EQ&Pn#2iL$mf>!+ZmcAHAKlbo-*#g1GGZpEcvMR*ABsX_Tea0~ zVYnL;i?0Ycq3#Q-#w_!s--gV_uDYyUO|kf!|$oF(r2+$_~~m~?c$E5VvNkiR2MgSFIp(t+_2C=?Z#`z z?fZEA`tn4_Lun`cg0=qu4@JMZJ~wP$#p>F9nZ5STKXh#z)f_^*1DM0dnZ@Pf$5us@ zqW&dEGPH6vB~=`CC`hu&7-9NHx&{%2bu?f;NBJ6q)sB`WDO~#bdG$~o;qbq&w(iW` zyE|ZQnmxCOp@uS>V-<`{Z3Zf)dZ(zJDQFG8)XeT>WVNnIum{^0FXIB@hC(>-1pZjh zSBz=asyj$DALXw_6Zv0t279aibkSr*b}w#HQ1wr51kLBqgA<67Om;OOtDadY>taWc zT~G*SWiN20Lwm-Lyv%OC+exP3A%EUh#5BD z+^vqeC?il7YO@j>1BU}cnsu{{uf8QF*s_snhnGERNHSGm8Or$fX&L- zsaqg+o8)V0{_b3PlB$L}pCoHF8?ld^aP9Wj1~{+co9N;2jpQJsNVcVdy~V!1$s%Ck zh!rtAtLE9AlM^GglJ8&DLm{+`fp&vPF~z8Ac!8?2_W@8FLo%M|OBL7S`Oy3f?!M-) zrulQ%J6ZQe^T+iD+1p*`*SHF5oWAg;%=NIE8eQMC>FHo3p}+jZ@a$q(MhP(C`A zRTI)qB!@Hp>i+KXk16bO`$^4vukPrRa=4Rcxw>GmO%%)v*u0f1Z#vCcp;jvlqIU}5 zh1WUzJMLD+%GUF87dBpf1PJdY-*GKO1|nBgq^`P_8I{R+^->b8q)0$oYwgpYB8+sf z>>c-$!c}b={B1TioBP&=w{Nq-aTNw$Nh7Lkasa@^J1V3sqf^EPp`Ph+EviWjv6hd` zO6mtWs3L@VjP;bN?;Nq*M$WS#ss}sOW6Z^@iB3rBC2l3f;F&lgGtd zL5ZHC4bQc*R1<({vRijLlT}olMNl`6Q9V=#`y>HiL3zsCP5YbcH841G8IbBtd8)9l zV|t3Kzse&5ffbzf+2Tpm7_hj4Wr2i#I5FiDffOSv&|SHlzvsWnD2rlUEC zin?c3l1XWno;SY{Ev`!}pxrEFAZ`~g1xX1gSJPerWC34D9|&zn)sIo#&$W9c!#~h- zA)4K)bjjh!RIw(CKu6M|iUXE!GTESOZqMtCuZ}Ijw)X}Sp{`~#q?lo3wjIlWx^h zRdv65=k}#i5#U^I>)jhRq7xVvM242X2N$N?3lU-Y_LBZhuXu>Vzw+gs^lkA8?ctiW z-R#IvTIO3LBDBa}|s~b9o_ZV+qbB|^> zS!ADR-?#myca+IRxJ#&(QUaM$JGh*rlvDxMK-5GPI#!A9wjILOHMcu-s|eD-k>Zf* zx;#K@5!O@%V$9V56ISl%-EE)eleBZqB|m9=e%;t=EX&PNyKudA*;Ez#b8}R)Leb=9 z#qPW=2P;FELkJ?FD&%yi0%a?zL};IK`-blkZnN)vvF_EKhw6r+%=0y@ zvL}khj3r3X(m-Th=aa-Cn&R>aB#vf~ZL>KyF%ZZnCr^0@tQJnt+QWh!LxW!4iwDWS zoSk{zm`E^N53TzH8AXYzc`(_$_ETe>#}*={QzYAdrjr?wXfjk48ib@tDQa4jCX~kn z^TNhkPu+jq-d$UDySv-3A&kFbQ#G8FrQD*C9TN@%EZ)bi=0$N@Cfv_3j!RBAD8b8#iV zNaO?0u_Q+3*45DM_cbLCz;G3+e_;OrH$ymn=6>WuZ%wnFxhCXi1G)DL3!s3isoFsf!1X!5-Rs_~NMp5bK^_cb z9Z7j)BOSp`g^uE(Xb<2O8bX3PfBs(o053OYAK>S0d~NwRy({9}-FuDPyJzDqM&qH~ z8;@~rF16g-QzI2WUt@C^oHkwxycW*giKhrM6-e~dnMR~WN;+Cdp$GE?ly_6b`-^Y7 zl_zYXTe_$r#aL!rt0mEyWRB}C?(t3J(Zd1s{B^S-CJir6;EjG+}7#L(RLL!*~vi! zbdXkT97aBpuC|^@QhbFrMPjEuKuD1GU7vK0MwWfHWe&ockf?1Sno#!)g&ZkUk~$4o z@~-V^aeW5q0EOuuoYW9pYwjJrtDH4|l}RUKe=e_>d%tyVO5VKq&$*XuW%ngs;oE65 z;WqSGj81MQuN!ChUT;2`984Q_s$)kK6+q0368RaqVk(1|HzrXe^4rAcQ7U9zL-G~- z2khuoYZ#BkA_nlt-~s%p=aHY5Ytt16@|FHzIR%@?(34R`Hh#r>E*}Ihue;p6o1KI`GaP$ z)RbqeHnuWFtCFExCBOFkYVpX3s@kEJrZ5$+e^4WiKc?508CbF2Y_LCyPx3~8!B3w` zW1GX)zfUf&JP+B%pUy^gRJ;iS%VCGvGubN8BrHt~I8DLg0>WpiV+G<5dpGAM= zZ_2Lb+?yvWkLmrpLDKt%yD>wyHt`s|c1opo+|fVr4E-$G8n(pkx~OAjrl+TtIcn9_ zWg0JZMY*Q>pnXG;3wJZC0>MX>aB9Z{3eX>mq7GO4!uvq3*KJH1%ZmQ(Wp?w% zS2vJsB{CS=jvARvvKblEOp~ZxVYE|r6wrKCB$j7jD?)Nja(uDW=*+>o403Y z@rm+FtFX1ybj>E%6qzTbk_fT&1=a{@(84=y!opp@cDJ~;j8{}?I)~I%fD)>Bib{qR z1%U;D(8h!a&uQPem-l_;wEF|zEJ^^DIl?m`)%tlx@f}nulCFdT3k^e2sc!u34&3gp z+VAf5?v2w=4*2X$NWt%|ym4~u$_x%WVSfqRdt<8bTO%b-D{vStsK)IYOmgEU@z>M+ ziI%QOYMP=+4*4F__h$FCtalPicO}b6^0BMSEQOj$7=cQiLgNjq92ZtolOEOD?b}%muTz&@ zvz4w)aNN6opCr}TT!<@GipxO-WDF*O54NtkcGmXZYe&1dg&e3Y422{BI<}ouZr0PK z#WIY_2(3b!ZhGIg+l9M@Ep7^i9u)B_#!Dk8W(%Q-LPU#416r=2R-lZZ4!TZ<8MXd# z?aCgs+nM}k?f5&`(AHMxC@FV-;lS5oGdpW1wlZ6LE50-I)9u`~Op(;dHEuRXu9(9a zP+Bz}!W{aLSj)*|ZYC(C<_k#9hmk~x!a(UDMPgM&2nK?*B-f#@w>$Rry?=VdrHX>P=J~S0eC2=3My(yzCirJ*gI2i&4}oqh+S#%qp~)J#_CP6kL_)N zy|?c4-P@BlhS|AYpWN9AHrD?D#N~S43SW?Tyu}tp3!9km(|bxgdEyKKAG)5_PwV-fBx zVuDE>i4N(hWRt@LuW$;gv?MKRM-Gi2&Tia?p!Vj}_@C1q<<~vW(Ea(q`Bj{l@JnD)PB4tF^Nk-S3#*JHv8rZI??(DiW@jC5^__y=<}MaJ2Ks8!$iH)RT1Q zIPQ(z*lQJ?6U8hPv&Z4eRZ6PRiY}lS0692QYYj**<@3~?$@1U5cgDx*pPHLr;q09|(|eobWhVUJSj;|J`-@=xzDE^; zrKqlv^7uLOEl*L9t;yq-zC1oNA3V)NRNfkSo%aIf(jVTF?yq(9@&24~#LTM2(<;